From 99ec28bcf3aece7daa82a940f62ac66c724320d3 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 23 Jun 2023 15:27:42 +0900 Subject: [PATCH 001/118] feat(dynamic_avoidance): apply LPF to shift length, and positive relative velocity (#4047) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 50 +++++++++++++++++-- planning/behavior_path_planner/package.xml | 1 + .../dynamic_avoidance_module.cpp | 35 +++++++++++-- 3 files changed, 76 insertions(+), 10 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 1dadf8c02ad5e..217104eb7c938 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 @@ -67,9 +67,10 @@ class DynamicAvoidanceModule : public SceneModuleInterface public: struct DynamicAvoidanceObject { - explicit DynamicAvoidanceObject( + DynamicAvoidanceObject( const PredictedObject & predicted_object, const double arg_path_projected_vel) - : pose(predicted_object.kinematics.initial_pose_with_covariance.pose), + : uuid(tier4_autoware_utils::toHexString(predicted_object.object_id)), + pose(predicted_object.kinematics.initial_pose_with_covariance.pose), path_projected_vel(arg_path_projected_vel), shape(predicted_object.shape) { @@ -78,9 +79,10 @@ class DynamicAvoidanceModule : public SceneModuleInterface } } - const geometry_msgs::msg::Pose pose; - const double path_projected_vel; - const autoware_auto_perception_msgs::msg::Shape shape; + std::string uuid; + geometry_msgs::msg::Pose pose; + double path_projected_vel; + autoware_auto_perception_msgs::msg::Shape shape; std::vector predicted_paths{}; bool is_left; @@ -124,7 +126,45 @@ class DynamicAvoidanceModule : public SceneModuleInterface const DynamicAvoidanceObject & object) const; std::vector target_objects_; + // std::vector prev_target_objects_; std::shared_ptr parameters_; + + struct ObjectsVariable + { + void resetCurrentUuids() { current_uuids_.clear(); } + void addCurrentUuid(const std::string & uuid) { current_uuids_.push_back(uuid); } + void removeCounterUnlessUpdated() + { + std::vector obsolete_uuids; + for (const auto & key_and_value : variable_) { + if ( + std::find(current_uuids_.begin(), current_uuids_.end(), key_and_value.first) == + current_uuids_.end()) { + obsolete_uuids.push_back(key_and_value.first); + } + } + + for (const auto & obsolete_uuid : obsolete_uuids) { + variable_.erase(obsolete_uuid); + } + } + + std::optional get(const std::string & uuid) const + { + if (variable_.count(uuid) != 0) { + return variable_.at(uuid); + } + return std::nullopt; + } + void update(const std::string & uuid, const double new_variable) + { + variable_.emplace(uuid, new_variable); + } + + std::unordered_map variable_; + std::vector current_uuids_; + }; + mutable ObjectsVariable prev_objects_min_bound_lat_offset_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index cd7311f3308bb..97453b0325cef 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -62,6 +62,7 @@ route_handler rtc_interface sensor_msgs + signal_processing tf2 tf2_eigen tf2_geometry_msgs 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 47e8c73c394ae..d8860c86ae112 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 @@ -16,6 +16,7 @@ #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" +#include "signal_processing/lowpass_filter_1d.hpp" #include #include @@ -128,6 +129,19 @@ void appendExtractedPolygonMarker( marker_array.markers.push_back(marker); } + +template +std::optional getObjectFromUuid(const std::vector & objects, const std::string & target_uuid) +{ + const auto itr = std::find_if(objects.begin(), objects.end(), [&](const auto & object) { + return object.uuid == target_uuid; + }); + + if (itr == objects.end()) { + return std::nullopt; + } + return *itr; +} } // namespace #ifdef USE_OLD_ARCHITECTURE @@ -211,6 +225,7 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() // 3. create obstacles to avoid (= extract from the drivable area) std::vector obstacles_for_drivable_area; + prev_objects_min_bound_lat_offset_.resetCurrentUuids(); for (const auto & object : target_objects_) { const auto obstacle_poly = calcDynamicObstaclePolygon(object); if (obstacle_poly) { @@ -218,8 +233,11 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() appendObjectMarker(info_marker_, object.pose); appendExtractedPolygonMarker(debug_marker_, obstacle_poly.value()); + + prev_objects_min_bound_lat_offset_.addCurrentUuid(object.uuid); } } + prev_objects_min_bound_lat_offset_.removeCounterUnlessUpdated(); BehaviorModuleOutput output; output.path = prev_module_path; @@ -389,6 +407,7 @@ std::pair DynamicAvoidanceModule return std::make_pair(right_lanes, left_lanes); } +// NOTE: object does not have const only to update min_bound_lat_offset. std::optional DynamicAvoidanceModule::calcDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const { @@ -455,10 +474,8 @@ std::optional DynamicAvoidanceModule::calcDynam motion_utils::findNearestSegmentIndex(prev_module_path->points, object.pose.position); const double signed_lon_length = motion_utils::calcSignedArcLength( prev_module_path->points, getEgoPosition(), ego_seg_idx, object.pose.position, obj_seg_idx); - if (relative_velocity == 0.0) { - return std::numeric_limits::max(); - } - return signed_lon_length / relative_velocity; + const double positive_relative_velocity = std::max(relative_velocity, 1.0); + return signed_lon_length / positive_relative_velocity; }(); if (time_to_collision < -parameters_->duration_to_hold_avoidance_overtaking_object) { @@ -535,13 +552,21 @@ std::optional DynamicAvoidanceModule::calcDynam const double max_bound_lat_offset = max_obj_lat_offset + parameters_->lat_offset_from_obstacle * (object.is_left ? 1.0 : -1.0); + // filter min_bound_lat_offset + const auto prev_min_bound_lat_offset = prev_objects_min_bound_lat_offset_.get(object.uuid); + const double filtered_min_bound_lat_offset = + prev_min_bound_lat_offset + ? signal_processing::lowpassFilter(min_bound_lat_offset, *prev_min_bound_lat_offset, 0.3) + : min_bound_lat_offset; + prev_objects_min_bound_lat_offset_.update(object.uuid, filtered_min_bound_lat_offset); + // create inner/outer bound points std::vector obj_inner_bound_points; std::vector obj_outer_bound_points; for (size_t i = lon_bound_start_idx; i <= lon_bound_end_idx; ++i) { obj_inner_bound_points.push_back( tier4_autoware_utils::calcOffsetPose( - path_with_backward_margin.points.at(i).point.pose, 0.0, min_bound_lat_offset, 0.0) + path_with_backward_margin.points.at(i).point.pose, 0.0, filtered_min_bound_lat_offset, 0.0) .position); obj_outer_bound_points.push_back( tier4_autoware_utils::calcOffsetPose( From deffac2a874de02a7cbe1d02133a48cc8cd754bf Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 23 Jun 2023 15:28:30 +0900 Subject: [PATCH 002/118] refactor(crosswalk): minor refactoring (#4046) * refactor(crosswalk): minor refactoring Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/scene_crosswalk.cpp | 78 +++++++++---------- .../src/scene_crosswalk.hpp | 8 +- 2 files changed, 43 insertions(+), 43 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 7047fc7b56f2e..ca39796c616ba 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -194,52 +194,52 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto logger_, planner_param_.show_processing_time, "- step2: %f ms", stop_watch_.toc("total_processing_time", false)); - StopFactor stop_factor{}; - StopFactor stop_factor_rtc{}; - - const auto nearest_stop_point = findNearestStopPoint(ego_path, stop_factor); - const auto rtc_stop_point = findRTCStopPoint(ego_path, stop_factor_rtc); + const auto nearest_stop_point_with_factor = findNearestStopPointWithFactor(ego_path); + const auto rtc_stop_point_with_factor = findRTCStopPointWithFactor(ego_path); RCLCPP_INFO_EXPRESSION( logger_, planner_param_.show_processing_time, "- step3: %f ms", stop_watch_.toc("total_processing_time", false)); - setSafe(!nearest_stop_point); + setSafe(!nearest_stop_point_with_factor); if (isActivated()) { - if (!nearest_stop_point) { - if (!rtc_stop_point) { + if (!nearest_stop_point_with_factor) { + if (!rtc_stop_point_with_factor) { setDistance(std::numeric_limits::lowest()); return true; } const auto crosswalk_distance = - calcSignedArcLength(ego_path.points, ego_pos, getPoint(rtc_stop_point.get())); + calcSignedArcLength(ego_path.points, ego_pos, getPoint(rtc_stop_point_with_factor->first)); setDistance(crosswalk_distance); return true; } - const auto target_velocity = calcTargetVelocity(nearest_stop_point.get(), ego_path); + const auto target_velocity = + calcTargetVelocity(nearest_stop_point_with_factor->first, ego_path); insertDecelPointWithDebugInfo( - nearest_stop_point.get(), std::max(planner_param_.min_slow_down_velocity, target_velocity), - *path); + nearest_stop_point_with_factor->first, + std::max(planner_param_.min_slow_down_velocity, target_velocity), *path); return true; } - if (nearest_stop_point) { - insertDecelPointWithDebugInfo(nearest_stop_point.get(), 0.0, *path); - planning_utils::appendStopReason(stop_factor, stop_reason); - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_factor.stop_pose, - VelocityFactor::UNKNOWN); - } else if (rtc_stop_point) { - insertDecelPointWithDebugInfo(rtc_stop_point.get(), 0.0, *path); - planning_utils::appendStopReason(stop_factor_rtc, stop_reason); - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_factor_rtc.stop_pose, - VelocityFactor::UNKNOWN); - } + const auto & stop_point_with_factor = + [&]() -> boost::optional> { + if (nearest_stop_point_with_factor) + return nearest_stop_point_with_factor.get(); + else if (rtc_stop_point_with_factor) + return rtc_stop_point_with_factor.get(); + return {}; + }(); + + const auto & stop_factor = stop_point_with_factor->second; + insertDecelPointWithDebugInfo(stop_point_with_factor->first, 0.0, *path); + planning_utils::appendStopReason(stop_factor, stop_reason); + velocity_factor_.set( + path->points, planner_data_->current_odometry->pose, stop_factor.stop_pose, + VelocityFactor::UNKNOWN); RCLCPP_INFO_EXPRESSION( logger_, planner_param_.show_processing_time, "- step4: %f ms", @@ -291,8 +291,8 @@ boost::optional> CrosswalkModule::g return {}; } -boost::optional CrosswalkModule::findRTCStopPoint( - const PathWithLaneId & ego_path, StopFactor & stop_factor) +boost::optional> +CrosswalkModule::findRTCStopPointWithFactor(const PathWithLaneId & ego_path) { const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; @@ -311,14 +311,17 @@ boost::optional CrosswalkModule::findRTCStopPoint( return {}; } + StopFactor stop_factor; stop_factor.stop_pose = stop_pose.get(); - return stop_pose.get().position; + return std::make_pair(stop_pose.get().position, stop_factor); } -boost::optional CrosswalkModule::findNearestStopPoint( - const PathWithLaneId & ego_path, StopFactor & stop_factor) +boost::optional> +CrosswalkModule::findNearestStopPointWithFactor(const PathWithLaneId & ego_path) { + StopFactor stop_factor; + bool found_pedestrians = false; bool found_stuck_vehicle = false; @@ -485,7 +488,7 @@ boost::optional CrosswalkModule::findNearestStopPoint stop_factor.stop_pose = stop_pose.get(); - return stop_pose.get().position; + return std::make_pair(stop_pose.get().position, stop_factor); } std::pair CrosswalkModule::getAttentionRange(const PathWithLaneId & ego_path) @@ -844,18 +847,15 @@ bool CrosswalkModule::isStuckVehicle( return false; } - const auto & ego_pos = planner_data_->current_odometry->pose.position; - - double near_attention_range = 0.0; - double far_attention_range = 0.0; if (path_intersects_.size() < 2) { return false; } - near_attention_range = calcSignedArcLength(ego_path.points, ego_pos, path_intersects_.front()); - far_attention_range = calcSignedArcLength(ego_path.points, ego_pos, path_intersects_.back()); - near_attention_range = far_attention_range; - far_attention_range += planner_param_.stuck_vehicle_attention_range; + const auto & ego_pos = planner_data_->current_odometry->pose.position; + const double near_attention_range = + calcSignedArcLength(ego_path.points, ego_pos, path_intersects_.back()); + const double far_attention_range = + near_attention_range + planner_param_.stuck_vehicle_attention_range; const auto dist_ego2obj = calcSignedArcLength(ego_path.points, ego_pos, obj_pos); diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index c382d09e9ec6e..d53bc30471426 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -107,11 +107,11 @@ class CrosswalkModule : public SceneModuleInterface private: int64_t module_id_; - boost::optional findRTCStopPoint( - const PathWithLaneId & ego_path, StopFactor & stop_factor); + boost::optional> findRTCStopPointWithFactor( + const PathWithLaneId & ego_path); - boost::optional findNearestStopPoint( - const PathWithLaneId & ego_path, StopFactor & stop_factor); + boost::optional> findNearestStopPointWithFactor( + const PathWithLaneId & ego_path); boost::optional> getStopLine( const PathWithLaneId & ego_path, bool & exist_stopline_in_map) const; From 385ef5bf7a22b932a06a713c19b6d0e1fcd3510a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 23 Jun 2023 15:28:55 +0900 Subject: [PATCH 003/118] feat(behavior_velocity_traffic_light_module): print not found traffic ids for warning (#4045) Signed-off-by: Takayuki Murooka --- .../src/scene.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp index 925dfb0470b98..679a2f0cb9320 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp @@ -442,9 +442,15 @@ bool TrafficLightModule::getHighestConfidenceTrafficSignal( } } if (!found) { + std::string not_found_traffic_ids{""}; + for (size_t i = 0; i < traffic_lights.size(); ++i) { + const int id = static_cast(traffic_lights.at(i)).id(); + not_found_traffic_ids += (i != 0 ? "," : "") + std::to_string(id); + } + RCLCPP_WARN_THROTTLE( - logger_, *clock_, 5000 /* ms */, "cannot find traffic light lamp state (%s).", - reason.c_str()); + logger_, *clock_, 5000 /* ms */, "cannot find traffic light lamp state (%s) due to %s.", + not_found_traffic_ids.c_str(), reason.c_str()); return false; } return true; From 7c77bbdefc5f2aa2bbec05fe1a8d5ac4c8374b94 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 23 Jun 2023 16:37:15 +0900 Subject: [PATCH 004/118] =?UTF-8?q?fix(behavior=5Fpath=5Fplanner):=20print?= =?UTF-8?q?=20avoidance=20and=20lane=20change=20debug=20mes=E2=80=A6=20(#4?= =?UTF-8?q?058)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit fix(behavior_path_planner): print avoidance and lane change debug message Signed-off-by: Zulfaqar Azmi --- .../behavior_path_planner_node.hpp | 2 -- .../behavior_path_planner/planner_manager.hpp | 8 ++++++++ .../src/behavior_path_planner_node.cpp | 3 +-- .../behavior_path_planner/src/planner_manager.cpp | 13 +++++++++++++ 4 files changed, 22 insertions(+), 4 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 60152bdf42bb1..ea0e990a8b259 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 @@ -234,10 +234,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node /** * @brief publish debug messages */ -#ifdef USE_OLD_ARCHITECTURE void publishSceneModuleDebugMsg( const std::shared_ptr & debug_messages_data_ptr); -#endif /** * @brief publish path candidate 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 c91065d4a0a5d..108ca29f161b1 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 @@ -17,6 +17,7 @@ #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 @@ -225,6 +226,11 @@ class PlannerManager */ void print() const; + /** + * @brief visit each module and get debug information. + */ + std::shared_ptr getDebugMsg(); + private: /** * @brief run the module and publish RTC status. @@ -461,6 +467,8 @@ class PlannerManager mutable std::vector debug_info_; + mutable std::shared_ptr debug_msg_ptr_; + 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 a853661891e75..bc3711b72e648 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -1295,6 +1295,7 @@ void BehaviorPathPlannerNode::run() publishPathCandidate(bt_manager_->getSceneModules(), planner_data_); publishSceneModuleDebugMsg(bt_manager_->getAllSceneModuleDebugMsgData()); #else + publishSceneModuleDebugMsg(planner_manager_->getDebugMsg()); publishPathCandidate(planner_manager_->getSceneModuleManagers(), planner_data_); publishPathReference(planner_manager_->getSceneModuleManagers(), planner_data_); stop_reason_publisher_->publish(planner_manager_->getStopReasons()); @@ -1416,7 +1417,6 @@ void BehaviorPathPlannerNode::publish_bounds(const PathWithLaneId & path) bound_publisher_->publish(msg); } -#ifdef USE_OLD_ARCHITECTURE void BehaviorPathPlannerNode::publishSceneModuleDebugMsg( const std::shared_ptr & debug_messages_data_ptr) { @@ -1430,7 +1430,6 @@ void BehaviorPathPlannerNode::publishSceneModuleDebugMsg( debug_lane_change_msg_array_publisher_->publish(*lane_change_debug_message); } } -#endif #ifdef USE_OLD_ARCHITECTURE void BehaviorPathPlannerNode::publishPathCandidate( diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index a84f13fd5a9d0..c9d4d2c191a4c 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -718,4 +718,17 @@ void PlannerManager::print() const RCLCPP_INFO_STREAM(logger_, string_stream.str()); } +std::shared_ptr PlannerManager::getDebugMsg() +{ + debug_msg_ptr_ = std::make_shared(); + for (const auto & approved_module : approved_module_ptrs_) { + approved_module->acceptVisitor(debug_msg_ptr_); + } + + for (const auto & candidate_module : candidate_module_ptrs_) { + candidate_module->acceptVisitor(debug_msg_ptr_); + } + return debug_msg_ptr_; +} + } // namespace behavior_path_planner From a0a0b1a91200f0f12077a52917129efd3b1ea605 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 23 Jun 2023 16:48:43 +0900 Subject: [PATCH 005/118] feat(dynamic_avoidance): suppress flickering of dynamic avoidance launching (#4048) * feat(dynamic_avoidance): suppress flickering of dynamic avoidance launching Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance.param.yaml | 10 +++--- .../dynamic_avoidance_module.hpp | 23 +++++++++++- .../src/behavior_path_planner_node.cpp | 2 ++ .../dynamic_avoidance_module.cpp | 35 +++++++++++++++---- .../dynamic_avoidance/manager.cpp | 4 +++ 5 files changed, 63 insertions(+), 11 deletions(-) diff --git a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml index a4ff684839321..0b8f35bac3131 100644 --- a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml +++ b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml @@ -12,21 +12,23 @@ motorcycle: true pedestrian: false - min_obstacle_vel: 1.0 # [m/s] + min_obstacle_vel: 0.0 # [m/s] + + successive_num_to_entry_dynamic_avoidance_condition: 5 drivable_area_generation: - lat_offset_from_obstacle: 1.3 # [m] + lat_offset_from_obstacle: 0.8 # [m] max_lat_offset_to_avoid: 0.5 # [m] # for same directional object overtaking_object: max_time_to_collision: 3.0 # [s] start_duration_to_avoid: 4.0 # [s] - end_duration_to_avoid: 5.0 # [s] + end_duration_to_avoid: 8.0 # [s] duration_to_hold_avoidance: 3.0 # [s] # for opposite directional object oncoming_object: max_time_to_collision: 3.0 # [s] - start_duration_to_avoid: 9.0 # [s] + start_duration_to_avoid: 12.0 # [s] end_duration_to_avoid: 0.0 # [s] 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 217104eb7c938..799c0aad6e307 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 @@ -47,6 +47,7 @@ struct DynamicAvoidanceParameters bool avoid_motorcycle{false}; bool avoid_pedestrian{false}; double min_obstacle_vel{0.0}; + int successive_num_to_entry_dynamic_avoidance_condition{0}; // drivable area generation double lat_offset_from_obstacle{0.0}; @@ -87,6 +88,24 @@ class DynamicAvoidanceModule : public SceneModuleInterface bool is_left; }; + struct DynamicAvoidanceObjectCandidate + { + DynamicAvoidanceObject object; + int alive_counter; + + static std::optional getObjectFromUuid( + const std::vector & objects, const std::string & target_uuid) + { + const auto itr = std::find_if(objects.begin(), objects.end(), [&](const auto & object) { + return object.object.uuid == target_uuid; + }); + + if (itr == objects.end()) { + return std::nullopt; + } + return *itr; + } + }; #ifdef USE_OLD_ARCHITECTURE DynamicAvoidanceModule( @@ -119,12 +138,14 @@ class DynamicAvoidanceModule : public SceneModuleInterface private: bool isLabelTargetObstacle(const uint8_t label) const; - std::vector calcTargetObjects() const; + std::vector calcTargetObjectsCandidate() const; std::pair getAdjacentLanes( const double forward_distance, const double backward_distance) const; std::optional calcDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const; + std::vector + prev_target_objects_candidate_; std::vector target_objects_; // std::vector prev_target_objects_; std::shared_ptr parameters_; 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 bc3711b72e648..1359b1afc86fc 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -743,6 +743,8 @@ DynamicAvoidanceParameters BehaviorPathPlannerNode::getDynamicAvoidanceParam() p.avoid_motorcycle = declare_parameter(ns + "motorcycle"); p.avoid_pedestrian = declare_parameter(ns + "pedestrian"); p.min_obstacle_vel = declare_parameter(ns + "min_obstacle_vel"); + p.successive_num_to_entry_dynamic_avoidance_condition = + declare_parameter(ns + "successive_num_to_entry_dynamic_avoidance_condition"); } { // drivable_area_generation 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 d8860c86ae112..c75ed08b7a5ce 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 @@ -192,7 +192,19 @@ bool DynamicAvoidanceModule::isExecutionReady() const void DynamicAvoidanceModule::updateData() { - target_objects_ = calcTargetObjects(); + // calculate target objects candidate + const auto target_objects_candidate = calcTargetObjectsCandidate(); + prev_target_objects_candidate_ = target_objects_candidate; + + // calculate target objects considering flickering suppress + target_objects_.clear(); + for (const auto & target_object_candidate : target_objects_candidate) { + if ( + parameters_->successive_num_to_entry_dynamic_avoidance_condition <= + target_object_candidate.alive_counter) { + target_objects_.push_back(target_object_candidate.object); + } + } } ModuleStatus DynamicAvoidanceModule::updateState() @@ -293,8 +305,8 @@ bool DynamicAvoidanceModule::isLabelTargetObstacle(const uint8_t label) const return false; } -std::vector -DynamicAvoidanceModule::calcTargetObjects() const +std::vector +DynamicAvoidanceModule::calcTargetObjectsCandidate() const { const auto prev_module_path = getPreviousModuleOutput().path; const auto & predicted_objects = planner_data_->dynamic_object->objects; @@ -329,7 +341,7 @@ DynamicAvoidanceModule::calcTargetObjects() const // 4. check if object will cut into the ego lane. // NOTE: The oncoming object will be ignored. constexpr double epsilon_path_lat_diff = 0.3; - std::vector output_objects; + std::vector output_objects_candidate; for (const bool is_left : {true, false}) { for (const auto & object : (is_left ? objects_in_left_lanes : objects_in_right_lanes)) { const auto reliable_predicted_path = std::max_element( @@ -358,13 +370,24 @@ DynamicAvoidanceModule::calcTargetObjects() const continue; } + // get previous object if it exists + const auto prev_target_object_candidate = DynamicAvoidanceObjectCandidate::getObjectFromUuid( + prev_target_objects_candidate_, object.uuid); + const int alive_counter = + prev_target_object_candidate + ? std::min( + parameters_->successive_num_to_entry_dynamic_avoidance_condition, + prev_target_object_candidate->alive_counter + 1) + : 0; + auto target_object = object; target_object.is_left = is_left; - output_objects.push_back(target_object); + output_objects_candidate.push_back( + DynamicAvoidanceObjectCandidate{target_object, alive_counter}); } } - return output_objects; + return output_objects_candidate; } std::pair DynamicAvoidanceModule::getAdjacentLanes( diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index d3212a7c0b1d4..b9ca4ffa964f7 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -49,6 +49,10 @@ void DynamicAvoidanceModuleManager::updateModuleParams( updateParam(parameters, ns + "pedestrian", p->avoid_pedestrian); updateParam(parameters, ns + "min_obstacle_vel", p->min_obstacle_vel); + + updateParam( + parameters, ns + "successive_num_to_entry_dynamic_avoidance_condition", + p->successive_num_to_entry_dynamic_avoidance_condition); } { // drivable_area_generation From 702947346bb48f89a93aab1a88cc7d60a2a9ea4d Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 23 Jun 2023 17:33:38 +0900 Subject: [PATCH 006/118] fix(avoidance): update logic to keep waiting approval (#4059) * revert "fix(avoidance): don't clear waiting approval if raw shift line exists (#4012)" This reverts commit 8577563ca1dca2994f099c7c47307ad57cbce875. * fix(avoidance): update logic to keep waiting approval Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 4 +++- 1 file changed, 3 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 51312dbf6d333..1d5142c81c0f9 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 @@ -2695,9 +2695,11 @@ BehaviorModuleOutput AvoidanceModule::planWaitingApproval() [](const auto & o) { return !o.is_avoidable; }); const auto candidate = planCandidate(); - if (!avoidance_data_.unapproved_raw_sl.empty()) { + if (!data.safe_new_sl.empty()) { updateCandidateRTCStatus(candidate); waitApproval(); + } else if (path_shifter_.getShiftLines().empty()) { + waitApproval(); } else if (all_unavoidable) { waitApproval(); } else { From 25f9d6a03adf91ed2312741b9acdf937560245a9 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 23 Jun 2023 17:41:10 +0900 Subject: [PATCH 007/118] fix(lane_change): fix debug visualization now showing (#4061) * fix(lane_change): fix debug visualization now showing Signed-off-by: Zulfaqar Azmi * renaming the markers Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../src/scene_module/lane_change/interface.cpp | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 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 c23bf807f121c..81df39cb8f789 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 @@ -116,6 +116,7 @@ ModuleStatus LaneChangeInterface::updateState() const auto [is_safe, is_object_coming_from_rear] = module_type_->isApprovedPathSafe(); + setObjectDebugVisualization(); if (is_safe) { module_type_->toNormalState(); return ModuleStatus::RUNNING; @@ -270,6 +271,8 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change); is_abort_path_approved_ = false; + setObjectDebugVisualization(); + return out; } @@ -300,6 +303,10 @@ void LaneChangeInterface::setData(const std::shared_ptr & dat void LaneChangeInterface::setObjectDebugVisualization() const { + debug_marker_.markers.clear(); + if (!parameters_->publish_debug_marker) { + return; + } using marker_utils::lane_change_markers::showAllValidLaneChangePath; using marker_utils::lane_change_markers::showLerpedPose; using marker_utils::lane_change_markers::showObjectInfo; @@ -315,9 +322,8 @@ void LaneChangeInterface::setObjectDebugVisualization() const }; add(showObjectInfo(debug_data, "object_debug_info")); - add(showLerpedPose(debug_data, "lerp_pose_before_true")); - add(showPolygonPose(debug_data, "expected_pose")); - add(showPolygon(debug_data, "lerped_polygon")); + add(showLerpedPose(debug_data, "ego_predicted_path")); + add(showPolygon(debug_data, "ego_and_target_polygon_relation")); add(showAllValidLaneChangePath(debug_valid_path, "lane_change_valid_paths")); } From e70df1239c67d8ae86a7a8bf8d6c83bc20e7ece7 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 23 Jun 2023 18:02:39 +0900 Subject: [PATCH 008/118] feat(dynamic_avoidance): ignore cut-out vehicle (#4049) * feat(dynamic_avoidance): ignore cut-out vehicle Signed-off-by: Takayuki Murooka * update cut out decision policy Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 8 +- .../dynamic_avoidance_module.cpp | 89 ++++++++++++------- 2 files changed, 61 insertions(+), 36 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 799c0aad6e307..4898188c71319 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 @@ -69,10 +69,11 @@ class DynamicAvoidanceModule : public SceneModuleInterface struct DynamicAvoidanceObject { DynamicAvoidanceObject( - const PredictedObject & predicted_object, const double arg_path_projected_vel) + const PredictedObject & predicted_object, const double arg_vel, const double arg_lat_vel) : uuid(tier4_autoware_utils::toHexString(predicted_object.object_id)), pose(predicted_object.kinematics.initial_pose_with_covariance.pose), - path_projected_vel(arg_path_projected_vel), + vel(arg_vel), + lat_vel(arg_lat_vel), shape(predicted_object.shape) { for (const auto & path : predicted_object.kinematics.predicted_paths) { @@ -82,7 +83,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::string uuid; geometry_msgs::msg::Pose pose; - double path_projected_vel; + double vel; + double lat_vel; autoware_auto_perception_msgs::msg::Shape shape; std::vector predicted_paths{}; 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 c75ed08b7a5ce..a8a7f89c54021 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 @@ -73,20 +73,6 @@ geometry_msgs::msg::Point toGeometryPoint(const tier4_autoware_utils::Point2d & return geom_obj_point; } -double calcObstacleProjectedVelocity( - const std::vector & path_points, const PredictedObject & object) -{ - const auto & obj_pose = object.kinematics.initial_pose_with_covariance.pose; - const double obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear.x; - - const size_t obj_idx = motion_utils::findNearestIndex(path_points, obj_pose.position); - - const double obj_yaw = tf2::getYaw(obj_pose.orientation); - const double path_yaw = tf2::getYaw(path_points.at(obj_idx).point.pose.orientation); - - return obj_vel * std::cos(obj_yaw - path_yaw); -} - std::pair getMinMaxValues(const std::vector & vec) { const size_t min_idx = std::distance(vec.begin(), std::min_element(vec.begin(), vec.end())); @@ -142,6 +128,21 @@ std::optional getObjectFromUuid(const std::vector & objects, const std::st } return *itr; } + +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 = object.kinematics.initial_twist_with_covariance.twist.linear.x; + + const size_t obj_idx = motion_utils::findNearestIndex(path_points, obj_pose.position); + + const double obj_yaw = tf2::getYaw(obj_pose.orientation); + const double path_yaw = tf2::getYaw(path_points.at(obj_idx).point.pose.orientation); + + return std::make_pair( + obj_vel * std::cos(obj_yaw - path_yaw), obj_vel * std::sin(obj_yaw - path_yaw)); +} } // namespace #ifdef USE_OLD_ARCHITECTURE @@ -321,14 +322,14 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() const continue; } - const double path_projected_vel = - calcObstacleProjectedVelocity(prev_module_path->points, predicted_object); + const auto [tangent_vel, normal_vel] = + projectObstacleVelocityToTrajectory(prev_module_path->points, predicted_object); // check if velocity is high enough - if (std::abs(path_projected_vel) < parameters_->min_obstacle_vel) { + if (std::abs(tangent_vel) < parameters_->min_obstacle_vel) { continue; } - input_objects.push_back(DynamicAvoidanceObject(predicted_object, path_projected_vel)); + input_objects.push_back(DynamicAvoidanceObject(predicted_object, tangent_vel, normal_vel)); } // 2. calculate target lanes to filter obstacles @@ -338,7 +339,7 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() const const auto objects_in_right_lanes = getObjectsInLanes(input_objects, right_lanes); const auto objects_in_left_lanes = getObjectsInLanes(input_objects, left_lanes); - // 4. check if object will cut into the ego lane. + // 4. check if object will cut into the ego lane or cut out to the next lane. // NOTE: The oncoming object will be ignored. constexpr double epsilon_path_lat_diff = 0.3; std::vector output_objects_candidate; @@ -352,7 +353,7 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() const // Ignore object that will cut into the ego lane const bool will_object_cut_in = [&]() { - if (object.path_projected_vel < 0) { + if (object.vel < 0) { // Ignore oncoming object return false; } @@ -370,6 +371,29 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() const continue; } + // Ignore object that will cut out to the next lane + const bool will_object_cut_out = [&]() { + if (object.vel < 0) { + // Ignore oncoming object + return false; + } + + constexpr double object_lat_vel_thresh = 0.3; + if (is_left) { + if (object_lat_vel_thresh < object.lat_vel) { + return true; + } + } else { + if (object.lat_vel < -object_lat_vel_thresh) { + return true; + } + } + return false; + }(); + if (will_object_cut_out) { + continue; + } + // get previous object if it exists const auto prev_target_object_candidate = DynamicAvoidanceObjectCandidate::getObjectFromUuid( prev_target_objects_candidate_, object.uuid); @@ -489,7 +513,7 @@ std::optional DynamicAvoidanceModule::calcDynam getMinMaxValues(obj_lon_offset_vec); // calculate time to collision and apply it to drivable area extraction - const double relative_velocity = getEgoSpeed() - object.path_projected_vel; + const double relative_velocity = getEgoSpeed() - object.vel; const double time_to_collision = [&]() { const auto prev_module_path = getPreviousModuleOutput().path; const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(prev_module_path->points); @@ -505,19 +529,18 @@ std::optional DynamicAvoidanceModule::calcDynam return std::nullopt; } - if (0 <= object.path_projected_vel) { + if (0 <= object.vel) { const double limited_time_to_collision = std::min(parameters_->max_time_to_collision_overtaking_object, time_to_collision); return std::make_pair( - raw_min_obj_lon_offset + object.path_projected_vel * limited_time_to_collision, - raw_max_obj_lon_offset + object.path_projected_vel * limited_time_to_collision); + raw_min_obj_lon_offset + object.vel * limited_time_to_collision, + raw_max_obj_lon_offset + object.vel * limited_time_to_collision); } const double limited_time_to_collision = std::min(parameters_->max_time_to_collision_oncoming_object, time_to_collision); return std::make_pair( - raw_min_obj_lon_offset + object.path_projected_vel * limited_time_to_collision, - raw_max_obj_lon_offset); + raw_min_obj_lon_offset + object.vel * limited_time_to_collision, raw_max_obj_lon_offset); }(); if (!obj_lon_offset) { @@ -527,15 +550,15 @@ std::optional DynamicAvoidanceModule::calcDynam const double max_obj_lon_offset = obj_lon_offset->second; // calculate bound start and end index - const bool is_object_overtaking = (0.0 <= object.path_projected_vel); + const bool is_object_overtaking = (0.0 <= object.vel); const double start_length_to_avoid = - std::abs(object.path_projected_vel) * - (is_object_overtaking ? parameters_->start_duration_to_avoid_overtaking_object - : parameters_->start_duration_to_avoid_oncoming_object); + std::abs(object.vel) * (is_object_overtaking + ? parameters_->start_duration_to_avoid_overtaking_object + : parameters_->start_duration_to_avoid_oncoming_object); const double end_length_to_avoid = - std::abs(object.path_projected_vel) * (is_object_overtaking - ? parameters_->end_duration_to_avoid_overtaking_object - : parameters_->end_duration_to_avoid_oncoming_object); + std::abs(object.vel) * (is_object_overtaking + ? parameters_->end_duration_to_avoid_overtaking_object + : parameters_->end_duration_to_avoid_oncoming_object); const auto lon_bound_start_idx_opt = motion_utils::insertTargetPoint( obj_seg_idx, min_obj_lon_offset - start_length_to_avoid, path_with_backward_margin.points); const size_t updated_obj_seg_idx = From 4ee69759ecfc00efc31aa710b4a62953f48cd518 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 23 Jun 2023 18:51:28 +0900 Subject: [PATCH 009/118] feat(mission_planner): add mrm route planner (#4027) * feat(mission_planner): add mrm route planner Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka --------- Signed-off-by: yutaka --- .../src/mission_planner/mission_planner.cpp | 165 +++++++++++++++++- .../src/mission_planner/mission_planner.hpp | 3 + 2 files changed, 160 insertions(+), 8 deletions(-) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 098f5e07ac071..7de19df1b3b4e 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -75,7 +75,8 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) plugin_loader_("mission_planner", "mission_planner::PlannerPlugin"), tf_buffer_(get_clock()), tf_listener_(tf_buffer_), - normal_route_(nullptr) + normal_route_(nullptr), + mrm_route_(nullptr) { map_frame_ = declare_parameter("map_frame"); reroute_time_threshold_ = declare_parameter("reroute_time_threshold"); @@ -155,6 +156,11 @@ void MissionPlanner::clear_route() // TODO(Takagi, Isamu): publish an empty route here } +void MissionPlanner::clear_mrm_route() +{ + mrm_route_ = nullptr; +} + void MissionPlanner::change_route(const LaneletRoute & route) { PoseWithUuidStamped goal; @@ -172,6 +178,23 @@ void MissionPlanner::change_route(const LaneletRoute & route) normal_route_ = std::make_shared(route); } +void MissionPlanner::change_mrm_route(const LaneletRoute & route) +{ + PoseWithUuidStamped goal; + goal.header = route.header; + goal.pose = route.goal_pose; + goal.uuid = route.uuid; + + arrival_checker_.set_goal(goal); + pub_route_->publish(route); + pub_mrm_route_->publish(route); + pub_marker_->publish(planner_->visualize(route)); + planner_->updateRoute(route); + + // update emergency route + mrm_route_ = std::make_shared(route); +} + LaneletRoute MissionPlanner::create_route( const std_msgs::msg::Header & header, const std::vector & route_segments, @@ -278,6 +301,10 @@ void MissionPlanner::on_set_route( throw component_interface_utils::ServiceException( ResponseCode::ERROR_PLANNER_UNREADY, "The vehicle pose is not received."); } + if (mrm_route_) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_INVALID_STATE, "Cannot reroute in the emergency state."); + } // Convert request to a new route. const auto route = create_route(req); @@ -313,6 +340,10 @@ void MissionPlanner::on_set_route_points( throw component_interface_utils::ServiceException( ResponseCode::ERROR_PLANNER_UNREADY, "The vehicle pose is not received."); } + if (mrm_route_) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_INVALID_STATE, "Cannot reroute in the emergency state."); + } // Plan route. const auto route = create_route(req); @@ -334,19 +365,124 @@ void MissionPlanner::on_set_mrm_route( const SetMrmRoute::Service::Request::SharedPtr req, const SetMrmRoute::Service::Response::SharedPtr res) { - // TODO(Yutaka Shimizu): reroute for MRM - (void)req; - (void)res; + using ResponseCode = autoware_adapi_v1_msgs::srv::SetRoutePoints::Response; + + if (!planner_->ready()) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_PLANNER_UNREADY, "The planner is not ready."); + } + if (!odometry_) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_PLANNER_UNREADY, "The vehicle pose is not received."); + } + + const auto prev_state = state_.state; + change_state(RouteState::Message::CHANGING); + + // Plan route. + const auto new_route = create_route(req); + + if (new_route.segments.empty()) { + change_state(prev_state); + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_PLANNER_FAILED, "Failed to plan a new route."); + } + + // check route safety + // step1. if in mrm state, check with mrm route + if (mrm_route_) { + if (checkRerouteSafety(*mrm_route_, new_route)) { + // success to reroute + change_mrm_route(new_route); + res->status.success = true; + } else { + // failed to reroute + change_mrm_route(*mrm_route_); + res->status.success = false; + } + change_state(RouteState::Message::SET); + return; + } + + if (!normal_route_) { + // if it does not set normal route, just use the new planned route + change_mrm_route(new_route); + change_state(RouteState::Message::SET); + res->status.success = true; + return; + } + + // step2. if not in mrm state, check with normal route + if (checkRerouteSafety(*normal_route_, new_route)) { + // success to reroute + change_mrm_route(new_route); + res->status.success = true; + } else { + // Failed to reroute + change_route(*normal_route_); + res->status.success = false; + } + change_state(RouteState::Message::SET); } // NOTE: The route interface should be mutually exclusive by callback group. void MissionPlanner::on_clear_mrm_route( - const ClearMrmRoute::Service::Request::SharedPtr req, + const ClearMrmRoute::Service::Request::SharedPtr, const ClearMrmRoute::Service::Response::SharedPtr res) { - // TODO(Yutaka Shimizu): reroute for MRM - (void)req; - (void)res; + using ResponseCode = autoware_adapi_v1_msgs::srv::SetRoutePoints::Response; + + if (!planner_->ready()) { + change_state(RouteState::Message::SET); + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_PLANNER_UNREADY, "The planner is not ready."); + } + if (!odometry_) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_PLANNER_UNREADY, "The vehicle pose is not received."); + } + if (!mrm_route_) { + throw component_interface_utils::NoEffectWarning("MRM route is not set"); + } + + change_state(RouteState::Message::CHANGING); + + if (!normal_route_) { + clear_mrm_route(); + change_state(RouteState::Message::UNSET); + res->success = true; + return; + } + + // check route safety + if (checkRerouteSafety(*mrm_route_, *normal_route_)) { + clear_mrm_route(); + change_route(*normal_route_); + change_state(RouteState::Message::SET); + res->success = true; + return; + } + + // reroute with normal goal + const std::vector empty_waypoints; + const auto new_route = create_route( + odometry_->header, empty_waypoints, normal_route_->goal_pose, + normal_route_->allow_modification); + + // check new route safety + if (new_route.segments.empty() || !checkRerouteSafety(*mrm_route_, new_route)) { + // failed to create a new route + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 5000, "Reroute with normal goal failed."); + change_mrm_route(*mrm_route_); + change_route(*normal_route_); + change_state(RouteState::Message::SET); + res->success = false; + } else { + clear_mrm_route(); + change_route(new_route); + change_state(RouteState::Message::SET); + res->success = true; + } } void MissionPlanner::on_modified_goal(const ModifiedGoal::Message::ConstSharedPtr msg) @@ -367,6 +503,11 @@ void MissionPlanner::on_modified_goal(const ModifiedGoal::Message::ConstSharedPt RCLCPP_ERROR(get_logger(), "Normal route has not set yet."); return; } + if (mrm_route_) { + RCLCPP_ERROR_THROTTLE( + get_logger(), *get_clock(), 5000, "Cannot modify goal in the emergency state"); + return; + } if (normal_route_->uuid == msg->uuid) { // set to changing state @@ -413,6 +554,10 @@ void MissionPlanner::on_change_route( throw component_interface_utils::ServiceException( ResponseCode::ERROR_PLANNER_UNREADY, "Normal route is not set."); } + if (mrm_route_) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_INVALID_STATE, "Cannot reroute in the emergency state."); + } // set to changing state change_state(RouteState::Message::CHANGING); @@ -468,6 +613,10 @@ void MissionPlanner::on_change_route_points( throw component_interface_utils::ServiceException( ResponseCode::ERROR_PLANNER_UNREADY, "Normal route is not set."); } + if (mrm_route_) { + throw component_interface_utils::ServiceException( + ResponseCode::ERROR_INVALID_STATE, "Cannot reroute in the emergency state."); + } change_state(RouteState::Message::CHANGING); diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index bd3655bc55b0d..d3ca6be7eb63f 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -77,7 +77,9 @@ class MissionPlanner : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_marker_; void clear_route(); + void clear_mrm_route(); void change_route(const LaneletRoute & route); + void change_mrm_route(const LaneletRoute & route); LaneletRoute create_route(const SetRoute::Service::Request::SharedPtr req); LaneletRoute create_route(const SetRoutePoints::Service::Request::SharedPtr req); LaneletRoute create_route( @@ -136,6 +138,7 @@ class MissionPlanner : public rclcpp::Node bool checkRerouteSafety(const LaneletRoute & original_route, const LaneletRoute & target_route); std::shared_ptr normal_route_{nullptr}; + std::shared_ptr mrm_route_{nullptr}; }; } // namespace mission_planner From 4bc5ccce99efb3742421fb8b939737e8bbeda69d Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Fri, 23 Jun 2023 18:58:31 +0900 Subject: [PATCH 010/118] revert: "feat(behavior_path_planner): relax longitudinal_velocity_delta_time" (#4064) Revert "feat(behavior_path_planner): relax longitudinal_velocity_delta_time (#4039)" This reverts commit f6f3babcf2bcc0f9638dee055cb05c3590131feb. --- .../config/behavior_path_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 bfadf9497c0fd..a35f920dfb482 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -31,7 +31,7 @@ lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 - longitudinal_velocity_delta_time: 0.3 # [s] + longitudinal_velocity_delta_time: 0.8 # [s] expected_front_deceleration: -1.0 expected_rear_deceleration: -1.0 From 87f9b86fa1023468fe09e2a0e67ed4dce6db52db Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 23 Jun 2023 19:01:14 +0900 Subject: [PATCH 011/118] fix(start_planner): not run other modules when back pull out (#4043) * fix(start_planner): not run other modules when back pull out Signed-off-by: kosuke55 * fix reorder and value name Signed-off-by: kosuke55 * Update planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --------- Signed-off-by: kosuke55 Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- .../scene_module_manager_interface.hpp | 16 ++++++++-------- .../start_planner/start_planner_module.hpp | 13 +++++++++++++ .../scene_module/avoidance/avoidance_module.cpp | 8 -------- .../src/scene_module/start_planner/manager.cpp | 6 +++++- .../start_planner/start_planner_module.cpp | 12 ++++++++++++ 5 files changed, 38 insertions(+), 17 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp index 46a8d09c77ef2..596be548508fc 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp @@ -49,13 +49,13 @@ class SceneModuleManagerInterface clock_(*node->get_clock()), logger_(node->get_logger().get_child(name)), name_(name), - enable_rtc_(config.enable_rtc), - max_module_num_(config.max_module_size), - priority_(config.priority), enable_simultaneous_execution_as_approved_module_( config.enable_simultaneous_execution_as_approved_module), enable_simultaneous_execution_as_candidate_module_( - config.enable_simultaneous_execution_as_candidate_module) + config.enable_simultaneous_execution_as_candidate_module), + enable_rtc_(config.enable_rtc), + max_module_num_(config.max_module_size), + priority_(config.priority) { for (const auto & rtc_type : rtc_types) { const auto snake_case_name = utils::convertToSnakeCase(name); @@ -281,16 +281,16 @@ class SceneModuleManagerInterface std::unordered_map> rtc_interface_ptr_map_; + bool enable_simultaneous_execution_as_approved_module_{false}; + + bool enable_simultaneous_execution_as_candidate_module_{false}; + private: bool enable_rtc_; size_t max_module_num_; size_t priority_; - - bool enable_simultaneous_execution_as_approved_module_{false}; - - bool enable_simultaneous_execution_as_candidate_module_{false}; }; } // namespace behavior_path_planner 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 3f6ea8f5b3799..a48c24b183111 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 @@ -104,6 +104,19 @@ class StartPlannerModule : public SceneModuleInterface { } + // set is_simultaneously_executable_ as false when backward driving. + // keep initial value to return it after finishing backward driving. + bool initial_value_simultaneously_executable_as_approved_module_; + bool initial_value_simultaneously_executable_as_candidate_module_; + void setInitialIsSimultaneousExecutableAsApprovedModule(const bool is_simultaneously_executable) + { + initial_value_simultaneously_executable_as_approved_module_ = is_simultaneously_executable; + }; + void setInitialIsSimultaneousExecutableAsCandidateModule(const bool is_simultaneously_executable) + { + initial_value_simultaneously_executable_as_candidate_module_ = is_simultaneously_executable; + }; + private: std::shared_ptr parameters_; vehicle_info_util::VehicleInfo vehicle_info_; 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 1d5142c81c0f9..ac98eb5a2b59b 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 @@ -117,14 +117,6 @@ bool AvoidanceModule::isExecutionRequested() const { DEBUG_PRINT("AVOIDANCE isExecutionRequested"); -#ifndef USE_OLD_ARCHITECTURE - const auto is_driving_forward = - motion_utils::isDrivingForward(getPreviousModuleOutput().path->points); - if (!is_driving_forward || !(*is_driving_forward)) { - return false; - } -#endif - if (current_state_ == ModuleStatus::RUNNING) { return true; } 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 ab33c78c945ab..3b2917c94c8e1 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 @@ -39,8 +39,12 @@ void StartPlannerModuleManager::updateModuleParams( [[maybe_unused]] std::string ns = name_ + "."; - std::for_each(registered_modules_.begin(), registered_modules_.end(), [&p](const auto & m) { + std::for_each(registered_modules_.begin(), registered_modules_.end(), [&](const auto & m) { m->updateModuleParams(p); + m->setInitialIsSimultaneousExecutableAsApprovedModule( + enable_simultaneous_execution_as_approved_module_); + m->setInitialIsSimultaneousExecutableAsCandidateModule( + enable_simultaneous_execution_as_candidate_module_); }); } } // namespace behavior_path_planner 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 263c8b2ea197a..67ad82a489ade 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 @@ -270,6 +270,10 @@ BehaviorModuleOutput StartPlannerModule::plan() }); if (status_.back_finished) { + setIsSimultaneousExecutableAsApprovedModule( + initial_value_simultaneously_executable_as_approved_module_); + setIsSimultaneousExecutableAsCandidateModule( + initial_value_simultaneously_executable_as_candidate_module_); const double start_distance = motion_utils::calcSignedArcLength( path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); @@ -283,6 +287,8 @@ BehaviorModuleOutput StartPlannerModule::plan() {start_distance, finish_distance}, SteeringFactor::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, ""); } else { + setIsSimultaneousExecutableAsApprovedModule(false); + setIsSimultaneousExecutableAsCandidateModule(false); const double distance = motion_utils::calcSignedArcLength( path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); @@ -394,6 +400,10 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() }); if (status_.back_finished) { + setIsSimultaneousExecutableAsApprovedModule( + initial_value_simultaneously_executable_as_approved_module_); + setIsSimultaneousExecutableAsCandidateModule( + initial_value_simultaneously_executable_as_candidate_module_); const double start_distance = motion_utils::calcSignedArcLength( stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); @@ -406,6 +416,8 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() {start_distance, finish_distance}, SteeringFactor::START_PLANNER, steering_factor_direction, SteeringFactor::APPROACHING, ""); } else { + setIsSimultaneousExecutableAsApprovedModule(false); + setIsSimultaneousExecutableAsCandidateModule(false); const double distance = motion_utils::calcSignedArcLength( stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); From 79024d349cc3430695097360f0c68863d95345b5 Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Fri, 23 Jun 2023 21:27:21 +0900 Subject: [PATCH 012/118] docs(default_ad_api): fix link in default_ad_api (#4067) Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> --- system/default_ad_api/document/fail-safe.md | 2 +- system/default_ad_api/document/interface.md | 2 +- system/default_ad_api/document/localization.md | 2 +- system/default_ad_api/document/motion.md | 2 +- system/default_ad_api/document/operation-mode.md | 2 +- system/default_ad_api/document/routing.md | 2 +- 6 files changed, 6 insertions(+), 6 deletions(-) diff --git a/system/default_ad_api/document/fail-safe.md b/system/default_ad_api/document/fail-safe.md index b9967089c5e3a..a5a8ecad3542e 100644 --- a/system/default_ad_api/document/fail-safe.md +++ b/system/default_ad_api/document/fail-safe.md @@ -2,4 +2,4 @@ ## Overview -The fail-safe API simply relays the MRM state. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/list/api/fail_safe/) for AD API specifications. +The fail-safe API simply relays the MRM state. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/features/fail-safe/) for AD API specifications. diff --git a/system/default_ad_api/document/interface.md b/system/default_ad_api/document/interface.md index f3fc6a389c294..ed5a69219471d 100644 --- a/system/default_ad_api/document/interface.md +++ b/system/default_ad_api/document/interface.md @@ -2,4 +2,4 @@ ## Overview -The interface API simply returns a version number. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/list/api/interface/) for AD API specifications. +The interface API simply returns a version number. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/features/interface/) for AD API specifications. diff --git a/system/default_ad_api/document/localization.md b/system/default_ad_api/document/localization.md index 866322ed807cf..6f27ae3079f0d 100644 --- a/system/default_ad_api/document/localization.md +++ b/system/default_ad_api/document/localization.md @@ -2,6 +2,6 @@ ## Overview -Unify the location initialization method to the service. The topic `/initialpose` from rviz is now only subscribed to by adapter node and converted to API call. This API call is forwarded to the pose initializer node so it can centralize the state of pose initialization. For other nodes that require initialpose, pose initializer node publishes as `/initialpose3d`. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/list/api/localization/) for AD API specifications. +Unify the location initialization method to the service. The topic `/initialpose` from rviz is now only subscribed to by adapter node and converted to API call. This API call is forwarded to the pose initializer node so it can centralize the state of pose initialization. For other nodes that require initialpose, pose initializer node publishes as `/initialpose3d`. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/features/localization/) for AD API specifications. ![localization-architecture](images/localization.drawio.svg) diff --git a/system/default_ad_api/document/motion.md b/system/default_ad_api/document/motion.md index fd01a8f56ed7f..f13ee2a687808 100644 --- a/system/default_ad_api/document/motion.md +++ b/system/default_ad_api/document/motion.md @@ -2,7 +2,7 @@ ## Overview -Provides a hook for when the vehicle starts. It is typically used for announcements that call attention to the surroundings. Add a pause function to the vehicle_cmd_gate, and API will control it based on vehicle stopped and start requested. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/list/api/motion/) for AD API specifications. +Provides a hook for when the vehicle starts. It is typically used for announcements that call attention to the surroundings. Add a pause function to the vehicle_cmd_gate, and API will control it based on vehicle stopped and start requested. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/features/motion/) for AD API specifications. ![motion-architecture](images/motion-architecture.drawio.svg) diff --git a/system/default_ad_api/document/operation-mode.md b/system/default_ad_api/document/operation-mode.md index 703f6aa47b50d..69b79ed9b1fd7 100644 --- a/system/default_ad_api/document/operation-mode.md +++ b/system/default_ad_api/document/operation-mode.md @@ -2,7 +2,7 @@ ## Overview -Introduce operation mode. It handles autoware engage, gate_mode, external_cmd_selector and control_mode abstractly. When the mode is changed, it will be in-transition state, and if the transition completion condition to that mode is not satisfied, it will be returned to the previous mode. Also, currently, the condition for mode change is only `WaitingForEngage` in `/autoware/state`, and the engage state is shared between modes. After introducing the operation mode, each mode will have a transition available flag. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/list/api/operation_mode/) for AD API specifications. +Introduce operation mode. It handles autoware engage, gate_mode, external_cmd_selector and control_mode abstractly. When the mode is changed, it will be in-transition state, and if the transition completion condition to that mode is not satisfied, it will be returned to the previous mode. Also, currently, the condition for mode change is only `WaitingForEngage` in `/autoware/state`, and the engage state is shared between modes. After introducing the operation mode, each mode will have a transition available flag. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/features/operation_mode/) for AD API specifications. ![operation-mode-architecture](images/operation-mode-architecture.drawio.svg) diff --git a/system/default_ad_api/document/routing.md b/system/default_ad_api/document/routing.md index 899136f2d9e50..88969277e9263 100644 --- a/system/default_ad_api/document/routing.md +++ b/system/default_ad_api/document/routing.md @@ -2,6 +2,6 @@ ## Overview -Unify the route setting method to the service. This API supports two waypoint formats, poses and lanelet segments. The goal and checkpoint topics from rviz is only subscribed to by adapter node and converted to API call. This API call is forwarded to the mission planner node so it can centralize the state of routing. For other nodes that require route, mission planner node publishes as `/planning/mission_planning/route`. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/list/api/routing/) for AD API specifications. +Unify the route setting method to the service. This API supports two waypoint formats, poses and lanelet segments. The goal and checkpoint topics from rviz is only subscribed to by adapter node and converted to API call. This API call is forwarded to the mission planner node so it can centralize the state of routing. For other nodes that require route, mission planner node publishes as `/planning/mission_planning/route`. See the [autoware-documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/features/routing/) for AD API specifications. ![routing-architecture](images/routing.drawio.svg) From 1b9232f5a9aedeae3946a13d5ceaae16b8c88508 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 23 Jun 2023 23:50:29 +0900 Subject: [PATCH 013/118] feat(behavior_path_planner): add turn signal debug marker (#4066) --- .../behavior_path_planner_node.hpp | 6 ++ .../behavior_path_planner/data_manager.hpp | 5 +- .../turn_signal_decider.hpp | 8 +- .../src/behavior_path_planner_node.cpp | 77 ++++++++++++++++++- .../src/turn_signal_decider.cpp | 8 +- 5 files changed, 99 insertions(+), 5 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 ea0e990a8b259..d06a3aae68e4f 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 @@ -219,6 +219,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_maximum_drivable_area_publisher_; rclcpp::Publisher::SharedPtr debug_avoidance_msg_array_publisher_; rclcpp::Publisher::SharedPtr debug_lane_change_msg_array_publisher_; + rclcpp::Publisher::SharedPtr debug_turn_signal_info_publisher_; /** * @brief publish steering factor from intersection @@ -226,6 +227,11 @@ class BehaviorPathPlannerNode : public rclcpp::Node void publish_steering_factor( const std::shared_ptr & planner_data, const TurnIndicatorsCommand & turn_signal); + /** + * @brief publish turn signal debug info + */ + void publish_turn_signal_debug_data(const TurnSignalDebugData & debug_data); + /** * @brief publish left and right bound */ 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 b682d28efeaa5..639f495a74598 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 @@ -150,12 +150,13 @@ struct PlannerData mutable TurnSignalDecider turn_signal_decider; TurnIndicatorsCommand getTurnSignal( - const PathWithLaneId & path, const TurnSignalInfo & turn_signal_info) + const PathWithLaneId & path, const TurnSignalInfo & turn_signal_info, + TurnSignalDebugData & debug_data) { const auto & current_pose = self_odometry->pose.pose; const auto & current_vel = self_odometry->twist.twist.linear.x; return turn_signal_decider.getTurnSignal( - route_handler, path, turn_signal_info, current_pose, current_vel, parameters); + route_handler, path, turn_signal_info, current_pose, current_vel, parameters, debug_data); } template diff --git a/planning/behavior_path_planner/include/behavior_path_planner/turn_signal_decider.hpp b/planning/behavior_path_planner/include/behavior_path_planner/turn_signal_decider.hpp index 5691c03d31f6c..b550f132c27da 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/turn_signal_decider.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/turn_signal_decider.hpp @@ -63,13 +63,19 @@ struct TurnSignalInfo geometry_msgs::msg::Pose required_end_point; }; +struct TurnSignalDebugData +{ + TurnSignalInfo intersection_turn_signal_info; + TurnSignalInfo behavior_turn_signal_info; +}; + class TurnSignalDecider { public: TurnIndicatorsCommand getTurnSignal( const std::shared_ptr & route_handler, const PathWithLaneId & path, const TurnSignalInfo & turn_signal_info, const Pose & current_pose, const double current_vel, - const BehaviorPathPlannerParameters & parameters); + const BehaviorPathPlannerParameters & parameters, TurnSignalDebugData & debug_data); TurnIndicatorsCommand resolve_turn_signal( const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx, 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 1359b1afc86fc..229ae0eb679ea 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -78,6 +78,8 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod create_publisher("~/maximum_drivable_area", 1); } + debug_turn_signal_info_publisher_ = create_publisher("~/debug/turn_signal_info", 1); + bound_publisher_ = create_publisher("~/debug/bound", 1); // subscriber @@ -1339,12 +1341,13 @@ void BehaviorPathPlannerNode::computeTurnSignal( const BehaviorModuleOutput & output) { TurnIndicatorsCommand turn_signal; + TurnSignalDebugData debug_data; HazardLightsCommand hazard_signal; if (output.turn_signal_info.hazard_signal.command == HazardLightsCommand::ENABLE) { turn_signal.command = TurnIndicatorsCommand::DISABLE; hazard_signal.command = output.turn_signal_info.hazard_signal.command; } else { - turn_signal = planner_data->getTurnSignal(path, output.turn_signal_info); + turn_signal = planner_data->getTurnSignal(path, output.turn_signal_info, debug_data); hazard_signal.command = HazardLightsCommand::DISABLE; } turn_signal.stamp = get_clock()->now(); @@ -1352,6 +1355,7 @@ void BehaviorPathPlannerNode::computeTurnSignal( turn_signal_publisher_->publish(turn_signal); hazard_signal_publisher_->publish(hazard_signal); + publish_turn_signal_debug_data(debug_data); publish_steering_factor(planner_data, turn_signal); } @@ -1386,6 +1390,77 @@ void BehaviorPathPlannerNode::publish_steering_factor( steering_factor_interface_ptr_->publishSteeringFactor(get_clock()->now()); } +void BehaviorPathPlannerNode::publish_turn_signal_debug_data(const TurnSignalDebugData & debug_data) +{ + MarkerArray marker_array; + + const auto current_time = rclcpp::Time(); + constexpr double scale_x = 1.0; + constexpr double scale_y = 1.0; + constexpr double scale_z = 1.0; + const auto scale = tier4_autoware_utils::createMarkerScale(scale_x, scale_y, scale_z); + const auto desired_section_color = tier4_autoware_utils::createMarkerColor(0.0, 1.0, 0.0, 0.999); + const auto required_section_color = tier4_autoware_utils::createMarkerColor(1.0, 0.0, 1.0, 0.999); + + // intersection turn signal info + { + const auto & turn_signal_info = debug_data.intersection_turn_signal_info; + + auto desired_start_marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, "intersection_turn_signal_desired_start", 0L, Marker::SPHERE, scale, + desired_section_color); + auto desired_end_marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, "intersection_turn_signal_desired_end", 0L, Marker::SPHERE, scale, + desired_section_color); + desired_start_marker.pose = turn_signal_info.desired_start_point; + desired_end_marker.pose = turn_signal_info.desired_end_point; + + auto required_start_marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, "intersection_turn_signal_required_start", 0L, Marker::SPHERE, scale, + required_section_color); + auto required_end_marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, "intersection_turn_signal_required_end", 0L, Marker::SPHERE, scale, + required_section_color); + required_start_marker.pose = turn_signal_info.required_start_point; + required_end_marker.pose = turn_signal_info.required_end_point; + + marker_array.markers.push_back(desired_start_marker); + marker_array.markers.push_back(desired_end_marker); + marker_array.markers.push_back(required_start_marker); + marker_array.markers.push_back(required_end_marker); + } + + // behavior turn signal info + { + const auto & turn_signal_info = debug_data.behavior_turn_signal_info; + + auto desired_start_marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, "behavior_turn_signal_desired_start", 0L, Marker::CUBE, scale, + desired_section_color); + auto desired_end_marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, "behavior_turn_signal_desired_end", 0L, Marker::CUBE, scale, + desired_section_color); + desired_start_marker.pose = turn_signal_info.desired_start_point; + desired_end_marker.pose = turn_signal_info.desired_end_point; + + auto required_start_marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, "behavior_turn_signal_required_start", 0L, Marker::CUBE, scale, + required_section_color); + auto required_end_marker = tier4_autoware_utils::createDefaultMarker( + "map", current_time, "behavior_turn_signal_required_end", 0L, Marker::CUBE, scale, + required_section_color); + required_start_marker.pose = turn_signal_info.required_start_point; + required_end_marker.pose = turn_signal_info.required_end_point; + + marker_array.markers.push_back(desired_start_marker); + marker_array.markers.push_back(desired_end_marker); + marker_array.markers.push_back(required_start_marker); + marker_array.markers.push_back(required_end_marker); + } + + debug_turn_signal_info_publisher_->publish(marker_array); +} + void BehaviorPathPlannerNode::publish_bounds(const PathWithLaneId & path) { constexpr double scale_x = 0.2; diff --git a/planning/behavior_path_planner/src/turn_signal_decider.cpp b/planning/behavior_path_planner/src/turn_signal_decider.cpp index 57c5f149969ae..ac11941ec1eb6 100644 --- a/planning/behavior_path_planner/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/src/turn_signal_decider.cpp @@ -41,8 +41,10 @@ double calc_distance( TurnIndicatorsCommand TurnSignalDecider::getTurnSignal( const std::shared_ptr & route_handler, const PathWithLaneId & path, const TurnSignalInfo & turn_signal_info, const Pose & current_pose, const double current_vel, - const BehaviorPathPlannerParameters & parameters) + const BehaviorPathPlannerParameters & parameters, TurnSignalDebugData & debug_data) { + debug_data.behavior_turn_signal_info = turn_signal_info; + // Guard if (path.points.empty()) { return turn_signal_info.turn_signal; @@ -76,6 +78,10 @@ TurnIndicatorsCommand TurnSignalDecider::getTurnSignal( extended_path, current_pose, current_vel, ego_seg_idx, *route_handler, nearest_dist_threshold, nearest_yaw_threshold); + if (intersection_turn_signal_info) { + debug_data.intersection_turn_signal_info = *intersection_turn_signal_info; + } + if (!intersection_turn_signal_info) { initialize_intersection_info(); const auto & desired_end_point = turn_signal_info.desired_end_point; From 6c6973b79de2682b7a01c580cbdf9888b502b64d Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Fri, 23 Jun 2023 20:25:23 +0200 Subject: [PATCH 014/118] build: fix opencv dependency (#3987) Signed-off-by: Esteve Fernandez --- planning/behavior_path_planner/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 97453b0325cef..48c0762461d16 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -53,6 +53,7 @@ lane_departure_checker lanelet2_extension libboost-dev + libopencv-dev magic_enum motion_utils perception_utils From edcad42338a56cd2c7eaf0803f0861c56493608c Mon Sep 17 00:00:00 2001 From: atsushi yano <55824710+atsushi421@users.noreply.github.com> Date: Sat, 24 Jun 2023 08:24:56 +0900 Subject: [PATCH 015/118] perf(voxel_grid_downsample_filter): performance tuning (#3679) * perf(voxel_grid_downsample_filter): change to use faster_filter Signed-off-by: atsushi421 * perf(voxel_grid_downsample_filter): changed to not use pcl library Signed-off-by: atsushi421 * refactor: split faster_filter() into a separate class Signed-off-by: atsushi421 * style(pre-commit): autofix * chore: restore old filter function Signed-off-by: atsushi421 * chore: rename Signed-off-by: atsushi421 * refactor: split filter into multiple functions Signed-off-by: atsushi421 * refactor: improve readability Signed-off-by: atsushi421 * style(pre-commit): autofix * fix: pre-commit error Signed-off-by: atsushi421 * fix: copyright Signed-off-by: atsushi421 * fix: add const to calc_centroid() Signed-off-by: atsushi421 * refactor: define TransformInfo in separate file Signed-off-by: atsushi421 * style(pre-commit): autofix * refactor: improve readability Signed-off-by: atsushi421 * chore: fix copyright Signed-off-by: atsushi421 * chore: fix copyright Signed-off-by: atsushi421 * fix: typo Signed-off-by: atsushi421 --------- Signed-off-by: atsushi421 Co-authored-by: atsushi421 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../pointcloud_preprocessor/CMakeLists.txt | 23 +++ .../crop_box_filter_nodelet.hpp | 1 + .../faster_voxel_grid_downsample_filter.hpp | 93 +++++++++ .../voxel_grid_downsample_filter_nodelet.hpp | 15 +- .../pointcloud_preprocessor/filter.hpp | 14 +- .../ring_outlier_filter_nodelet.hpp | 1 + .../transform_info.hpp | 43 +++++ .../faster_voxel_grid_downsample_filter.cpp | 178 ++++++++++++++++++ .../voxel_grid_downsample_filter_nodelet.cpp | 25 ++- .../pointcloud_preprocessor/src/filter.cpp | 3 +- 10 files changed, 375 insertions(+), 21 deletions(-) create mode 100644 sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp create mode 100644 sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/transform_info.hpp create mode 100644 sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp diff --git a/sensing/pointcloud_preprocessor/CMakeLists.txt b/sensing/pointcloud_preprocessor/CMakeLists.txt index d8d561a9c5098..47d05b8c6ce47 100644 --- a/sensing/pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/pointcloud_preprocessor/CMakeLists.txt @@ -41,6 +41,21 @@ ament_target_dependencies(pointcloud_preprocessor_filter_base pcl_ros ) +add_library(faster_voxel_grid_downsample_filter SHARED + src/downsample_filter/faster_voxel_grid_downsample_filter.cpp +) + +target_include_directories(faster_voxel_grid_downsample_filter PUBLIC + "$" + "$" +) + +ament_target_dependencies(faster_voxel_grid_downsample_filter + pcl_conversions + rclcpp + sensor_msgs +) + ament_auto_add_library(pointcloud_preprocessor_filter SHARED src/utility/utilities.cpp src/concatenate_data/concatenate_data_nodelet.cpp @@ -65,6 +80,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED target_link_libraries(pointcloud_preprocessor_filter pointcloud_preprocessor_filter_base + faster_voxel_grid_downsample_filter ${Boost_LIBRARIES} ${OpenCV_LIBRARIES} ${PCL_LIBRARIES} @@ -167,6 +183,13 @@ install( RUNTIME DESTINATION bin ) +install( + TARGETS faster_voxel_grid_downsample_filter EXPORT export_${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + install( DIRECTORY include/ DESTINATION include/${PROJECT_NAME} diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp index 3b392401de49b..1406679ce0dba 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp @@ -54,6 +54,7 @@ #define POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_ #include "pointcloud_preprocessor/filter.hpp" +#include "pointcloud_preprocessor/transform_info.hpp" #include diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp new file mode 100644 index 0000000000000..d92b511d40c69 --- /dev/null +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp @@ -0,0 +1,93 @@ +// 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. + +#pragma once + +#include "pointcloud_preprocessor/transform_info.hpp" + +#include +#include +#include + +#include +#include + +namespace pointcloud_preprocessor +{ + +class FasterVoxelGridDownsampleFilter +{ + using PointCloud2 = sensor_msgs::msg::PointCloud2; + using PointCloud2ConstPtr = sensor_msgs::msg::PointCloud2::ConstSharedPtr; + +public: + FasterVoxelGridDownsampleFilter(); + void set_voxel_size(float voxel_size_x, float voxel_size_y, float voxel_size_z); + void set_field_offsets(const PointCloud2ConstPtr & input); + void filter( + const PointCloud2ConstPtr & input, PointCloud2 & output, const TransformInfo & transform_info, + const rclcpp::Logger & logger); + +private: + struct Centroid + { + float x; + float y; + float z; + uint32_t point_count_; + + Centroid() : x(0), y(0), z(0) {} + Centroid(float _x, float _y, float _z) : x(_x), y(_y), z(_z) { this->point_count_ = 1; } + + void add_point(float _x, float _y, float _z) + { + this->x += _x; + this->y += _y; + this->z += _z; + this->point_count_++; + } + + Eigen::Vector4f calc_centroid() const + { + Eigen::Vector4f centroid( + (this->x / this->point_count_), (this->y / this->point_count_), + (this->z / this->point_count_), 1.0f); + return centroid; + } + }; + + Eigen::Vector3f inverse_voxel_size_; + std::vector xyz_fields_; + int x_offset_; + int y_offset_; + int z_offset_; + int intensity_offset_; + bool offset_initialized_; + + Eigen::Vector3f get_point_from_global_offset( + const PointCloud2ConstPtr & input, size_t global_offset); + + bool get_min_max_voxel( + const PointCloud2ConstPtr & input, Eigen::Vector3i & min_voxel, Eigen::Vector3i & max_voxel); + + std::unordered_map calc_centroids_each_voxel( + const PointCloud2ConstPtr & input, const Eigen::Vector3i & max_voxel, + const Eigen::Vector3i & min_voxel); + + void copy_centroids_to_output( + std::unordered_map & voxel_centroid_map, PointCloud2 & output, + const TransformInfo & transform_info); +}; + +} // namespace pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp index 7ebf80c2da958..ae285b4fa9239 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// 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. @@ -52,6 +52,7 @@ #define POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_ #include "pointcloud_preprocessor/filter.hpp" +#include "pointcloud_preprocessor/transform_info.hpp" #include #include @@ -66,10 +67,16 @@ class VoxelGridDownsampleFilterComponent : public pointcloud_preprocessor::Filte void filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override; + // TODO(atsushi421): Temporary Implementation: Remove this interface when all the filter nodes + // conform to new API + virtual void faster_filter( + const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, + const TransformInfo & transform_info); + private: - double voxel_size_x_; - double voxel_size_y_; - double voxel_size_z_; + float voxel_size_x_; + float voxel_size_y_; + float voxel_size_z_; /** \brief Parameter service callback result : needed to be hold */ OnSetParametersCallbackHandle::SharedPtr set_param_res_; diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp index f995be741272c..47c0f2b403faa 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp @@ -52,6 +52,8 @@ #ifndef POINTCLOUD_PREPROCESSOR__FILTER_HPP_ #define POINTCLOUD_PREPROCESSOR__FILTER_HPP_ +#include "pointcloud_preprocessor/transform_info.hpp" + #include #include #include @@ -134,18 +136,6 @@ class Filter : public rclcpp::Node const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); protected: - struct TransformInfo - { - TransformInfo() - { - eigen_transform = Eigen::Matrix4f::Identity(4, 4); - need_transform = false; - } - - Eigen::Matrix4f eigen_transform; - bool need_transform; - }; - /** \brief The input PointCloud2 subscriber. */ rclcpp::Subscription::SharedPtr sub_input_; diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp index a906eb913d863..ab7d4e0012304 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp @@ -17,6 +17,7 @@ #include "autoware_point_types/types.hpp" #include "pointcloud_preprocessor/filter.hpp" +#include "pointcloud_preprocessor/transform_info.hpp" #include diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/transform_info.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/transform_info.hpp new file mode 100644 index 0000000000000..a4806555695b5 --- /dev/null +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/transform_info.hpp @@ -0,0 +1,43 @@ +// 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. + +#pragma once + +#include + +namespace pointcloud_preprocessor +{ + +/** + * This holds the coordinate transformation information of the point cloud. + * Usage example: + * \code + * if (transform_info.need_transform) { + * point = transform_info.eigen_transform * point; + * } + * \endcode + */ +struct TransformInfo +{ + TransformInfo() + { + eigen_transform = Eigen::Matrix4f::Identity(4, 4); + need_transform = false; + } + + Eigen::Matrix4f eigen_transform; + bool need_transform; +}; + +} // namespace pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp b/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp new file mode 100644 index 0000000000000..7c302eec20431 --- /dev/null +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp @@ -0,0 +1,178 @@ +// 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 "pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp" + +namespace pointcloud_preprocessor +{ + +FasterVoxelGridDownsampleFilter::FasterVoxelGridDownsampleFilter() +{ + pcl::for_each_type::type>( + pcl::detail::FieldAdder(xyz_fields_)); + offset_initialized_ = false; +} + +void FasterVoxelGridDownsampleFilter::set_voxel_size( + float voxel_size_x, float voxel_size_y, float voxel_size_z) +{ + inverse_voxel_size_ = + Eigen::Array3f::Ones() / Eigen::Array3f(voxel_size_x, voxel_size_y, voxel_size_z); +} + +void FasterVoxelGridDownsampleFilter::set_field_offsets(const PointCloud2ConstPtr & input) +{ + x_offset_ = input->fields[pcl::getFieldIndex(*input, "x")].offset; + y_offset_ = input->fields[pcl::getFieldIndex(*input, "y")].offset; + z_offset_ = input->fields[pcl::getFieldIndex(*input, "z")].offset; + intensity_offset_ = input->fields[pcl::getFieldIndex(*input, "intensity")].offset; + offset_initialized_ = true; +} + +void FasterVoxelGridDownsampleFilter::filter( + const PointCloud2ConstPtr & input, PointCloud2 & output, const TransformInfo & transform_info, + const rclcpp::Logger & logger) +{ + // Check if the field offset has been set + if (!offset_initialized_) { + set_field_offsets(input); + } + + // Compute the minimum and maximum voxel coordinates + Eigen::Vector3i min_voxel, max_voxel; + if (!get_min_max_voxel(input, min_voxel, max_voxel)) { + RCLCPP_ERROR( + logger, + "Voxel size is too small for the input dataset. " + "Integer indices would overflow."); + output = *input; + return; + } + + // Storage for mapping voxel coordinates to centroids + auto voxel_centroid_map = calc_centroids_each_voxel(input, max_voxel, min_voxel); + + // Initialize the output + output.row_step = voxel_centroid_map.size() * input->point_step; + output.data.resize(output.row_step); + output.width = voxel_centroid_map.size(); + pcl_conversions::fromPCL(xyz_fields_, output.fields); + output.is_dense = true; // we filter out invalid points + output.height = input->height; + output.is_bigendian = input->is_bigendian; + output.point_step = input->point_step; + output.header = input->header; + + // Copy the centroids to the output + copy_centroids_to_output(voxel_centroid_map, output, transform_info); +} + +Eigen::Vector3f FasterVoxelGridDownsampleFilter::get_point_from_global_offset( + const PointCloud2ConstPtr & input, size_t global_offset) +{ + Eigen::Vector3f point( + *reinterpret_cast(&input->data[global_offset + x_offset_]), + *reinterpret_cast(&input->data[global_offset + y_offset_]), + *reinterpret_cast(&input->data[global_offset + z_offset_])); + return point; +} + +bool FasterVoxelGridDownsampleFilter::get_min_max_voxel( + const PointCloud2ConstPtr & input, Eigen::Vector3i & min_voxel, Eigen::Vector3i & max_voxel) +{ + // Compute the minimum and maximum point coordinates + Eigen::Vector3f min_point, max_point; + min_point.setConstant(FLT_MAX); + max_point.setConstant(-FLT_MAX); + for (size_t global_offset = 0; global_offset + input->point_step <= input->data.size(); + global_offset += input->point_step) { + Eigen::Vector3f point = get_point_from_global_offset(input, global_offset); + if (std::isfinite(point[0]) && std::isfinite(point[1]), std::isfinite(point[2])) { + min_point = min_point.cwiseMin(point); + max_point = max_point.cwiseMax(point); + } + } + + // Check that the voxel size is not too small, given the size of the data + if ( + ((static_cast((max_point[0] - min_point[0]) * inverse_voxel_size_[0]) + 1) * + (static_cast((max_point[1] - min_point[1]) * inverse_voxel_size_[1]) + 1) * + (static_cast((max_point[2] - min_point[2]) * inverse_voxel_size_[2]) + 1)) > + static_cast(std::numeric_limits::max())) { + return false; + } + + // Compute the minimum and maximum voxel coordinates + min_voxel[0] = static_cast(std::floor(min_point[0] * inverse_voxel_size_[0])); + min_voxel[1] = static_cast(std::floor(min_point[1] * inverse_voxel_size_[1])); + min_voxel[2] = static_cast(std::floor(min_point[2] * inverse_voxel_size_[2])); + max_voxel[0] = static_cast(std::floor(max_point[0] * inverse_voxel_size_[0])); + max_voxel[1] = static_cast(std::floor(max_point[1] * inverse_voxel_size_[1])); + max_voxel[2] = static_cast(std::floor(max_point[2] * inverse_voxel_size_[2])); + + return true; +} + +std::unordered_map +FasterVoxelGridDownsampleFilter::calc_centroids_each_voxel( + const PointCloud2ConstPtr & input, const Eigen::Vector3i & max_voxel, + const Eigen::Vector3i & min_voxel) +{ + std::unordered_map voxel_centroid_map; + // Compute the number of divisions needed along all axis + Eigen::Vector3i div_b = max_voxel - min_voxel + Eigen::Vector3i::Ones(); + // Set up the division multiplier + Eigen::Vector3i div_b_mul(1, div_b[0], div_b[0] * div_b[1]); + + for (size_t global_offset = 0; global_offset + input->point_step <= input->data.size(); + global_offset += input->point_step) { + Eigen::Vector3f point = get_point_from_global_offset(input, global_offset); + if (std::isfinite(point[0]) && std::isfinite(point[1]), std::isfinite(point[2])) { + // Calculate the voxel index to which the point belongs + int ijk0 = static_cast(std::floor(point[0] * inverse_voxel_size_[0]) - min_voxel[0]); + int ijk1 = static_cast(std::floor(point[1] * inverse_voxel_size_[1]) - min_voxel[1]); + int ijk2 = static_cast(std::floor(point[2] * inverse_voxel_size_[2]) - min_voxel[2]); + uint32_t voxel_id = ijk0 * div_b_mul[0] + ijk1 * div_b_mul[1] + ijk2 * div_b_mul[2]; + + // Add the point to the corresponding centroid + if (voxel_centroid_map.find(voxel_id) == voxel_centroid_map.end()) { + voxel_centroid_map[voxel_id] = Centroid(point[0], point[1], point[2]); + } else { + voxel_centroid_map[voxel_id].add_point(point[0], point[1], point[2]); + } + } + } + + return voxel_centroid_map; +} + +void FasterVoxelGridDownsampleFilter::copy_centroids_to_output( + std::unordered_map & voxel_centroid_map, PointCloud2 & output, + const TransformInfo & transform_info) +{ + size_t output_data_size = 0; + for (const auto & pair : voxel_centroid_map) { + Eigen::Vector4f centroid = pair.second.calc_centroid(); + if (transform_info.need_transform) { + centroid = transform_info.eigen_transform * centroid; + } + *reinterpret_cast(&output.data[output_data_size + x_offset_]) = centroid[0]; + *reinterpret_cast(&output.data[output_data_size + y_offset_]) = centroid[1]; + *reinterpret_cast(&output.data[output_data_size + z_offset_]) = centroid[2]; + *reinterpret_cast(&output.data[output_data_size + intensity_offset_]) = centroid[3]; + output_data_size += output.point_step; + } +} + +} // namespace pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp index 5b22986a1b6b8..f11f37397a142 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// 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. @@ -50,6 +50,8 @@ #include "pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp" +#include "pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp" + #include #include #include @@ -64,9 +66,9 @@ VoxelGridDownsampleFilterComponent::VoxelGridDownsampleFilterComponent( { // set initial parameters { - voxel_size_x_ = static_cast(declare_parameter("voxel_size_x", 0.3)); - voxel_size_y_ = static_cast(declare_parameter("voxel_size_y", 0.3)); - voxel_size_z_ = static_cast(declare_parameter("voxel_size_z", 0.1)); + voxel_size_x_ = static_cast(declare_parameter("voxel_size_x", 0.3)); + voxel_size_y_ = static_cast(declare_parameter("voxel_size_y", 0.3)); + voxel_size_z_ = static_cast(declare_parameter("voxel_size_z", 0.1)); } using std::placeholders::_1; @@ -74,6 +76,8 @@ VoxelGridDownsampleFilterComponent::VoxelGridDownsampleFilterComponent( std::bind(&VoxelGridDownsampleFilterComponent::paramCallback, this, _1)); } +// TODO(atsushi421): Temporary Implementation: Delete this function definition when all the filter +// nodes conform to new API. void VoxelGridDownsampleFilterComponent::filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) { @@ -95,6 +99,19 @@ void VoxelGridDownsampleFilterComponent::filter( output.header = input->header; } +// TODO(atsushi421): Temporary Implementation: Rename this function to `filter()` when all the +// filter nodes conform to new API. Then delete the old `filter()` defined above. +void VoxelGridDownsampleFilterComponent::faster_filter( + const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, + PointCloud2 & output, const TransformInfo & transform_info) +{ + std::scoped_lock lock(mutex_); + FasterVoxelGridDownsampleFilter faster_voxel_filter; + faster_voxel_filter.set_voxel_size(voxel_size_x_, voxel_size_y_, voxel_size_z_); + faster_voxel_filter.set_field_offsets(input); + faster_voxel_filter.filter(input, output, transform_info, this->get_logger()); +} + rcl_interfaces::msg::SetParametersResult VoxelGridDownsampleFilterComponent::paramCallback( const std::vector & p) { diff --git a/sensing/pointcloud_preprocessor/src/filter.cpp b/sensing/pointcloud_preprocessor/src/filter.cpp index f0b716c73b5f1..d5843be395adf 100644 --- a/sensing/pointcloud_preprocessor/src/filter.cpp +++ b/sensing/pointcloud_preprocessor/src/filter.cpp @@ -124,7 +124,8 @@ void pointcloud_preprocessor::Filter::subscribe(const std::string & filter_name) // TODO(sykwer): Change the corresponding node to subscribe to `faster_input_indices_callback` // each time a child class supports the faster version. // When all the child classes support the faster version, this workaround is deleted. - std::set supported_nodes = {"CropBoxFilter", "RingOutlierFilter"}; + std::set supported_nodes = { + "CropBoxFilter", "RingOutlierFilter", "VoxelGridDownsampleFilter"}; auto callback = supported_nodes.find(filter_name) != supported_nodes.end() ? &Filter::faster_input_indices_callback : &Filter::input_indices_callback; From 7b6bff236710cf7bb0c1b097362fcac523b54846 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Sat, 24 Jun 2023 16:34:19 +0900 Subject: [PATCH 016/118] feat(obstacle_cruise_planner): change cruise color to orange (#4065) Signed-off-by: Shumpei Wakabayashi --- planning/obstacle_cruise_planner/src/node.cpp | 2 +- .../src/pid_based_planner/pid_based_planner.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index bf705759e0422..0020ef1c8e960 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -1251,7 +1251,7 @@ void ObstacleCruisePlannerNode::publishDebugMarker() const for (size_t i = 0; i < debug_data_ptr_->obstacles_to_cruise.size(); ++i) { // obstacle const auto obstacle_marker = obstacle_cruise_utils::getObjectMarker( - debug_data_ptr_->obstacles_to_cruise.at(i).pose, i, "obstacles_to_cruise", 1.0, 0.5, 0.5); + debug_data_ptr_->obstacles_to_cruise.at(i).pose, i, "obstacles_to_cruise", 1.0, 0.6, 0.1); debug_marker.markers.push_back(obstacle_marker); // collision points diff --git a/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp b/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp index bca5ad3f3cf41..ffd2f97b1eb89 100644 --- a/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp +++ b/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp @@ -314,7 +314,7 @@ std::vector PIDBasedPlanner::planCruise( stop_traj_points.at(wall_idx).pose, "obstacle cruise", planner_data.current_time, 0); // NOTE: use a different color from slow down one to visualize cruise and slow down // separately. - markers.markers.front().color = tier4_autoware_utils::createMarkerColor(1.0, 0.5, 0.5, 0.5); + markers.markers.front().color = tier4_autoware_utils::createMarkerColor(1.0, 0.6, 0.1, 0.5); tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->cruise_wall_marker); // cruise obstacle From 40f931129ebbcbb9c63788ea53816c12e18ad2fd Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 26 Jun 2023 07:23:24 +0900 Subject: [PATCH 017/118] refactor(lane_change): use common logger (#4072) Signed-off-by: Takamasa Horibe --- .../scene_module/lane_change/normal.hpp | 2 + .../src/scene_module/lane_change/normal.cpp | 55 +++++-------------- 2 files changed, 16 insertions(+), 41 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 e79400231cfb0..6572d4f8221b0 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 @@ -107,6 +107,8 @@ class NormalLaneChange : public LaneChangeBase TurnSignalInfo calcTurnSignalInfo() override; bool isValidPath(const PathWithLaneId & path) const override; + + rclcpp::Logger logger_ = rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()); }; class NormalLaneChangeBT : public NormalLaneChange 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 96238ecfb203d..548d23642581e 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 @@ -561,9 +561,7 @@ bool NormalLaneChange::getLaneChangePaths( minimum_prepare_length); if (prepare_length < target_length) { - RCLCPP_DEBUG( - rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()), - "prepare length is shorter than distance to target lane!!"); + RCLCPP_DEBUG(logger_, "prepare length is shorter than distance to target lane!!"); break; } @@ -571,9 +569,7 @@ bool NormalLaneChange::getLaneChangePaths( original_lanelets, arc_position_from_current.length, backward_path_length, prepare_length); if (prepare_segment.points.empty()) { - RCLCPP_DEBUG( - rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()), - "prepare segment is empty!!"); + RCLCPP_DEBUG(logger_, "prepare segment is empty!!"); continue; } @@ -587,8 +583,7 @@ bool NormalLaneChange::getLaneChangePaths( // that case, the lane change shouldn't be executed. if (target_length_from_lane_change_start_pose > 0.0) { RCLCPP_DEBUG( - rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()), - "[only new arch] lane change start getEgoPose() is behind target lanelet!!"); + logger_, "[only new arch] lane change start getEgoPose() is behind target lanelet!!"); break; } @@ -621,9 +616,7 @@ bool NormalLaneChange::getLaneChangePaths( prepare_segment, current_velocity, terminal_lane_changing_velocity); if (lane_changing_length + prepare_length > dist_to_end_of_current_lanes) { - RCLCPP_DEBUG( - rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()), - "length of lane changing path is longer than length to goal!!"); + RCLCPP_DEBUG(logger_, "length of lane changing path is longer than length to goal!!"); continue; } @@ -636,9 +629,7 @@ bool NormalLaneChange::getLaneChangePaths( s_start + lane_changing_length + common_parameter.lane_change_finish_judge_buffer + next_lane_change_buffer > s_goal) { - RCLCPP_DEBUG( - rclcpp::get_logger("behavior_path_planner").get_child("util").get_child("lane_change"), - "length of lane changing path is longer than length to goal!!"); + RCLCPP_DEBUG(logger_, "length of lane changing path is longer than length to goal!!"); continue; } } @@ -649,9 +640,7 @@ bool NormalLaneChange::getLaneChangePaths( next_lane_change_buffer); if (target_segment.points.empty()) { - RCLCPP_DEBUG( - rclcpp::get_logger("behavior_path_planner").get_child("util").get_child("lane_change"), - "target segment is empty!! something wrong..."); + RCLCPP_DEBUG(logger_, "target segment is empty!! something wrong..."); continue; } @@ -673,9 +662,7 @@ bool NormalLaneChange::getLaneChangePaths( next_lane_change_buffer); if (target_lane_reference_path.points.empty()) { - RCLCPP_DEBUG( - rclcpp::get_logger("behavior_path_planner").get_child("util").get_child("lane_change"), - "target_lane_reference_path is empty!!"); + RCLCPP_DEBUG(logger_, "target_lane_reference_path is empty!!"); continue; } @@ -693,9 +680,7 @@ bool NormalLaneChange::getLaneChangePaths( lc_velocity, terminal_lane_changing_velocity, lc_time); if (!candidate_path) { - RCLCPP_DEBUG( - rclcpp::get_logger("behavior_path_planner").get_child("util").get_child("lane_change"), - "no candidate path!!"); + RCLCPP_DEBUG(logger_, "no candidate path!!"); continue; } @@ -704,9 +689,7 @@ bool NormalLaneChange::getLaneChangePaths( minimum_lane_changing_velocity, common_parameter, direction); if (!is_valid) { - RCLCPP_DEBUG( - rclcpp::get_logger("behavior_path_planner").get_child("util").get_child("lane_change"), - "invalid candidate path!!"); + RCLCPP_DEBUG(logger_, "invalid candidate path!!"); continue; } @@ -927,18 +910,14 @@ bool NormalLaneChange::getAbortPath() lane_change_parameters_->abort_delta_time + lane_change_parameters_->aborting_time); if (abort_start_idx >= abort_return_idx) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()), - "abort start idx and return idx is equal. can't compute abort path."); + RCLCPP_ERROR(logger_, "abort start idx and return idx is equal. can't compute abort path."); return false; } if (!utils::lane_change::hasEnoughLengthToLaneChangeAfterAbort( *route_handler, reference_lanelets, current_pose, abort_return_dist, common_param, direction)) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()), - "insufficient distance to abort."); + RCLCPP_ERROR(logger_, "insufficient distance to abort."); return false; } @@ -965,9 +944,7 @@ bool NormalLaneChange::getAbortPath() path_shifter.setLateralAccelerationLimit(max_lateral_acc); if (lateral_jerk > lane_change_parameters_->abort_max_lateral_jerk) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()), - "Aborting jerk is too strong. lateral_jerk = " << lateral_jerk); + RCLCPP_ERROR(logger_, "Aborting jerk is too strong. lateral_jerk = %f", lateral_jerk); return false; } @@ -975,9 +952,7 @@ bool NormalLaneChange::getAbortPath() // offset front side // bool offset_back = false; if (!path_shifter.generate(&shifted_path)) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()), - "failed to generate abort shifted path."); + RCLCPP_ERROR(logger_, "failed to generate abort shifted path."); } const auto arc_position = lanelet::utils::getArcCoordinates( @@ -1094,9 +1069,7 @@ PathWithLaneId NormalLaneChangeBT::getPrepareSegment( const double s_start = arc_length_from_current - backward_path_length; const double s_end = arc_length_from_current + prepare_length; - RCLCPP_DEBUG( - rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()).get_child("getPrepareSegment"), - "start: %f, end: %f", s_start, s_end); + RCLCPP_DEBUG(logger_, "start: %f, end: %f", s_start, s_end); PathWithLaneId prepare_segment = getRouteHandler()->getCenterLinePath(current_lanes, s_start, s_end); From e9d4e9fa7dd03935a7752556ab63eefa48aaf2be Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 26 Jun 2023 09:08:29 +0900 Subject: [PATCH 018/118] fix(crosswalk): return if the stop point with factor is boost::none (#4071) Signed-off-by: satoshi-ota --- .../src/scene_crosswalk.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index ca39796c616ba..2ac4521c4c79e 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -234,6 +234,10 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto return {}; }(); + if (!stop_point_with_factor) { + return false; + } + const auto & stop_factor = stop_point_with_factor->second; insertDecelPointWithDebugInfo(stop_point_with_factor->first, 0.0, *path); planning_utils::appendStopReason(stop_factor, stop_reason); From a3c6ea22d3f4cdcaa810ae9a85fe44652014f2f0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 26 Jun 2023 10:18:43 +0900 Subject: [PATCH 019/118] feat(avoidance): set additional buffer margin independently (#4041) Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 9 ++++++++- .../utils/avoidance/avoidance_module_data.hpp | 5 ++--- .../src/behavior_path_planner_node.cpp | 2 +- .../src/scene_module/avoidance/avoidance_module.cpp | 4 ++-- .../src/scene_module/avoidance/manager.cpp | 2 +- .../behavior_path_planner/src/utils/avoidance/utils.cpp | 2 +- 6 files changed, 15 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 f7867ea647e13..79aca0867cce9 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -33,6 +33,7 @@ moving_time_threshold: 1.0 # [s] max_expand_ratio: 0.0 # [-] envelope_buffer_margin: 0.3 # [m] + avoid_margin_lateral: 1.0 # [m] safety_buffer_lateral: 0.7 # [m] safety_buffer_longitudinal: 0.0 # [m] truck: @@ -41,6 +42,7 @@ moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 + avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 bus: @@ -49,6 +51,7 @@ moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 + avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 trailer: @@ -57,6 +60,7 @@ moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 + avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 unknown: @@ -65,6 +69,7 @@ moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 + avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 bicycle: @@ -73,6 +78,7 @@ moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 + avoid_margin_lateral: 1.0 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 motorcycle: @@ -81,6 +87,7 @@ moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 + avoid_margin_lateral: 1.0 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 pedestrian: @@ -89,6 +96,7 @@ moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 + avoid_margin_lateral: 1.0 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 lower_distance_for_polygon_expansion: 30.0 # [m] @@ -124,7 +132,6 @@ avoidance: # avoidance lateral parameters lateral: - lateral_collision_margin: 1.0 # [m] lateral_execution_threshold: 0.499 # [m] lateral_small_shift_threshold: 0.101 # [m] road_shoulder_safety_margin: 0.3 # [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 3dd5668f43ddf..187dca71ae6c8 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 @@ -58,6 +58,8 @@ struct ObjectParameter double envelope_buffer_margin{0.0}; + double avoid_margin_lateral{1.0}; + double safety_buffer_lateral{1.0}; double safety_buffer_longitudinal{0.0}; @@ -159,9 +161,6 @@ struct AvoidanceParameters // force avoidance double threshold_time_force_avoidance_for_stopped_vehicle; - // we want to keep this lateral margin when avoiding - double lateral_collision_margin; - // when complete avoidance motion, there is a distance margin with the object // for longitudinal direction double longitudinal_collision_margin_min_distance; 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 229ae0eb679ea..f7336dad3f895 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -586,6 +586,7 @@ AvoidanceParameters BehaviorPathPlannerNode::getAvoidanceParam() param.moving_time_threshold = declare_parameter(ns + "moving_time_threshold"); param.max_expand_ratio = declare_parameter(ns + "max_expand_ratio"); param.envelope_buffer_margin = declare_parameter(ns + "envelope_buffer_margin"); + param.avoid_margin_lateral = declare_parameter(ns + "avoid_margin_lateral"); param.safety_buffer_lateral = declare_parameter(ns + "safety_buffer_lateral"); param.safety_buffer_longitudinal = declare_parameter(ns + "safety_buffer_longitudinal"); @@ -649,7 +650,6 @@ AvoidanceParameters BehaviorPathPlannerNode::getAvoidanceParam() // avoidance maneuver (lateral) { std::string ns = "avoidance.avoidance.lateral."; - p.lateral_collision_margin = declare_parameter(ns + "lateral_collision_margin"); p.road_shoulder_safety_margin = declare_parameter(ns + "road_shoulder_safety_margin"); p.lateral_execution_threshold = declare_parameter(ns + "lateral_execution_threshold"); p.lateral_small_shift_threshold = 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 ac98eb5a2b59b..8c0d6d4acd48a 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 @@ -620,7 +620,7 @@ void AvoidanceModule::fillDebugData(const AvoidancePlanningData & data, DebugDat const auto & vehicle_width = planner_data_->parameters.vehicle_width; const auto max_avoid_margin = object_parameter.safety_buffer_lateral * o_front.distance_factor + - parameters_->lateral_collision_margin + 0.5 * vehicle_width; + object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; const auto variable = helper_.getSharpAvoidanceDistance( helper_.getShiftLength(o_front, utils::avoidance::isOnRight(o_front), max_avoid_margin)); @@ -3285,7 +3285,7 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const const auto object_parameter = parameters_->object_parameters.at(t); const auto avoid_margin = object_parameter.safety_buffer_lateral * object.distance_factor + - p->lateral_collision_margin + 0.5 * vehicle_width; + object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; const auto variable = helper_.getMinimumAvoidanceDistance( helper_.getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin)); const auto constant = 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 321a5a72cc7b7..90dbfa960dbfe 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -52,6 +52,7 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "moving_time_threshold", config.moving_time_threshold); updateParam(parameters, ns + "max_expand_ratio", config.max_expand_ratio); updateParam(parameters, ns + "envelope_buffer_margin", config.envelope_buffer_margin); + updateParam(parameters, ns + "avoid_margin_lateral", config.avoid_margin_lateral); updateParam(parameters, ns + "safety_buffer_lateral", config.safety_buffer_lateral); updateParam( parameters, ns + "safety_buffer_longitudinal", config.safety_buffer_longitudinal); @@ -82,7 +83,6 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorlateral_execution_threshold); updateParam( parameters, ns + "lateral_small_shift_threshold", p->lateral_small_shift_threshold); - updateParam(parameters, ns + "lateral_collision_margin", p->lateral_collision_margin); updateParam( parameters, ns + "road_shoulder_safety_margin", p->road_shoulder_safety_margin); } diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 06ca1c3cc979e..8d33faf82e645 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -894,7 +894,7 @@ void filterTargetObjects( // calculate avoid_margin dynamically // NOTE: This calculation must be after calculating to_road_shoulder_distance. const double max_avoid_margin = object_parameter.safety_buffer_lateral * o.distance_factor + - parameters->lateral_collision_margin + 0.5 * vehicle_width; + object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; const double min_safety_lateral_distance = object_parameter.safety_buffer_lateral + 0.5 * vehicle_width; const auto max_allowable_lateral_distance = From 261a1b2a0ac445cc0fb16b055dd2f3b85178b6f0 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 26 Jun 2023 12:14:16 +0900 Subject: [PATCH 020/118] chore(lane_change): add z-pos in debug marker (#4074) Signed-off-by: Takamasa Horibe --- .../src/marker_util/lane_change/debug.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/src/marker_util/lane_change/debug.cpp b/planning/behavior_path_planner/src/marker_util/lane_change/debug.cpp index 8c9734924e14e..1ae1f8a03e0c0 100644 --- a/planning/behavior_path_planner/src/marker_util/lane_change/debug.cpp +++ b/planning/behavior_path_planner/src/marker_util/lane_change/debug.cpp @@ -185,11 +185,12 @@ MarkerArray showPolygon( } const auto & color = colors.at(idx); const auto & ego_polygon = info.ego_polygon.outer(); + const auto poly_z = info.current_pose.position.z; // temporally ego_marker.id = ++id; ego_marker.color = createMarkerColor(color[0], color[1], color[2], 0.8); ego_marker.points.reserve(ego_polygon.size()); for (const auto & p : ego_polygon) { - ego_marker.points.push_back(tier4_autoware_utils::createPoint(p.x(), p.y(), 0.0)); + ego_marker.points.push_back(tier4_autoware_utils::createPoint(p.x(), p.y(), poly_z)); } marker_array.markers.push_back(ego_marker); @@ -198,7 +199,7 @@ MarkerArray showPolygon( obj_marker.color = createMarkerColor(color[0], color[1], color[2], 0.8); obj_marker.points.reserve(obj_polygon.size()); for (const auto & p : obj_polygon) { - obj_marker.points.push_back(tier4_autoware_utils::createPoint(p.x(), p.y(), 0.0)); + obj_marker.points.push_back(tier4_autoware_utils::createPoint(p.x(), p.y(), poly_z)); } marker_array.markers.push_back(obj_marker); ++idx; From 435cdf909bafba40832472a5337cf72127a50ba3 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Mon, 26 Jun 2023 14:17:16 +0900 Subject: [PATCH 021/118] feat(mission_planner): add mrm goal modification (#4075) Signed-off-by: yutaka --- .../src/mission_planner/mission_planner.cpp | 22 ++++++++++++++++--- 1 file changed, 19 insertions(+), 3 deletions(-) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 7de19df1b3b4e..6ac62128c3bc1 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -503,9 +503,25 @@ void MissionPlanner::on_modified_goal(const ModifiedGoal::Message::ConstSharedPt RCLCPP_ERROR(get_logger(), "Normal route has not set yet."); return; } - if (mrm_route_) { - RCLCPP_ERROR_THROTTLE( - get_logger(), *get_clock(), 5000, "Cannot modify goal in the emergency state"); + + if (mrm_route_ && mrm_route_->uuid == msg->uuid) { + // set to changing state + change_state(RouteState::Message::CHANGING); + + const std::vector empty_waypoints; + auto new_route = + create_route(msg->header, empty_waypoints, msg->pose, mrm_route_->allow_modification); + // create_route generate new uuid, so set the original uuid again to keep that. + new_route.uuid = msg->uuid; + if (new_route.segments.empty()) { + change_mrm_route(*mrm_route_); + change_state(RouteState::Message::SET); + RCLCPP_ERROR(get_logger(), "The planned route is empty."); + return; + } + + change_mrm_route(new_route); + change_state(RouteState::Message::SET); return; } From 80d59309813412184ebd3f02613d58a42d38fa3c Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Mon, 26 Jun 2023 17:14:25 +0900 Subject: [PATCH 022/118] feat(behavior_path_planner): remove redundant process (#4077) Signed-off-by: Fumiya Watanabe --- .../scene_module/lane_change/base_class.hpp | 4 ++- .../scene_module/lane_change/normal.hpp | 4 ++- .../scene_module/lane_change/interface.cpp | 14 ++-------- .../src/scene_module/lane_change/normal.cpp | 28 ++++++++++++++++++- 4 files changed, 35 insertions(+), 15 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 94a4cb9462a2c..f8d80d8883b38 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 @@ -85,6 +85,8 @@ class LaneChangeBase virtual bool hasFinishedAbort() const = 0; + virtual bool isLaneChangeRequired() const = 0; + virtual bool isAbortState() const = 0; virtual bool isAbleToReturnCurrentLane() const = 0; @@ -197,7 +199,7 @@ class LaneChangeBase virtual bool getLaneChangePaths( const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, Direction direction, - LaneChangePaths * candidate_paths) const = 0; + LaneChangePaths * candidate_paths, const bool check_safety) const = 0; virtual std::vector getDrivableLanes() const = 0; 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 6572d4f8221b0..f7c6cdc07a200 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 @@ -85,6 +85,8 @@ class NormalLaneChange : public LaneChangeBase bool isAbortState() const override; + bool isLaneChangeRequired() const override; + protected: lanelet::ConstLanelets getCurrentLanes() const override; @@ -100,7 +102,7 @@ class NormalLaneChange : public LaneChangeBase bool getLaneChangePaths( const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, Direction direction, - LaneChangePaths * candidate_paths) const override; + LaneChangePaths * candidate_paths, const bool check_safety = true) const override; std::vector getDrivableLanes() 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 81df39cb8f789..26051c4d78f3e 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 @@ -67,22 +67,12 @@ bool LaneChangeInterface::isExecutionRequested() const return true; } - LaneChangePath selected_path; - module_type_->setPreviousModulePaths( - getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path); - const auto [found_valid_path, found_safe_path] = module_type_->getSafePath(selected_path); - - return found_valid_path; + return module_type_->isLaneChangeRequired(); } bool LaneChangeInterface::isExecutionReady() const { - LaneChangePath selected_path; - module_type_->setPreviousModulePaths( - getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path); - const auto [found_valid_path, found_safe_path] = module_type_->getSafePath(selected_path); - - return found_safe_path; + return module_type_->isSafe(); } ModuleStatus LaneChangeInterface::updateState() 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 548d23642581e..7f0d84fc94aed 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 @@ -89,6 +89,28 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) return {true, found_safe_path}; } +bool NormalLaneChange::isLaneChangeRequired() const +{ + const auto current_lanes = getCurrentLanes(); + + if (current_lanes.empty()) { + return false; + } + + const auto target_lanes = getLaneChangeLanes(current_lanes, direction_); + + if (target_lanes.empty()) { + return false; + } + + // find candidate paths + LaneChangePaths valid_paths{}; + [[maybe_unused]] const auto found_safe_path = + getLaneChangePaths(current_lanes, target_lanes, direction_, &valid_paths, false); + + return !valid_paths.empty(); +} + LaneChangePath NormalLaneChange::getLaneChangePath() const { return isAbortState() ? *abort_path_ : status_.lane_change_path; @@ -472,7 +494,7 @@ PathWithLaneId NormalLaneChange::getPrepareSegment( bool NormalLaneChange::getLaneChangePaths( const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, - Direction direction, LaneChangePaths * candidate_paths) const + Direction direction, LaneChangePaths * candidate_paths, const bool check_safety) const { object_debug_.clear(); if (original_lanelets.empty() || target_lanelets.empty()) { @@ -706,6 +728,10 @@ bool NormalLaneChange::getLaneChangePaths( } candidate_paths->push_back(*candidate_path); + if (!check_safety) { + return false; + } + const auto [is_safe, is_object_coming_from_rear] = utils::lane_change::isLaneChangePathSafe( *candidate_path, dynamic_objects, dynamic_object_indices, getEgoPose(), getEgoTwist(), common_parameter, *lane_change_parameters_, common_parameter.expected_front_deceleration, From 68a24de12b57eb1687108fc6ecc48166f9170ca6 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 26 Jun 2023 18:01:23 +0900 Subject: [PATCH 023/118] docs(avoidance): update parameter descriptions (#4073) * docs(avoidance): update parameter descriptions Signed-off-by: satoshi-ota * docs(avoidance): minor update Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_path_planner_avoidance_design.md | 82 ++++++++++++------- 1 file changed, 51 insertions(+), 31 deletions(-) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md index 42d3fad3e49bc..b023b0dff9602 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md @@ -588,13 +588,13 @@ namespace: `avoidance.` | resample_interval_for_output | [m] | double | Path resample interval for output path. Too short interval increases computational cost for latter modules. | 4.0 | | detection_area_right_expand_dist | [m] | double | Lanelet expand length for right side to find avoidance target vehicles. | 0.0 | | detection_area_left_expand_dist | [m] | double | Lanelet expand length for left side to find avoidance target vehicles. | 1.0 | -| object_envelope_buffer | [m] | double | Envelope object polygon with buffer in order to prevent shift line chattering. | 0.3 | | enable_bound_clipping | [-] | bool | Enable clipping left and right bound of drivable area when obstacles are in the drivable area | false | | enable_avoidance_over_same_direction | [-] | bool | Extend avoidance trajectory to adjacent lanes that has same direction. If false, avoidance only happen in current lane. | true | | enable_avoidance_over_opposite_direction | [-] | bool | Extend avoidance trajectory to adjacent lanes that has opposite direction. `enable_avoidance_over_same_direction` must be `true` to take effects | true | | enable_update_path_when_object_is_gone | [-] | bool | Reset trajectory when avoided objects are gone. If false, shifted path points remain same even though the avoided objects are gone. | false | | enable_safety_check | [-] | bool | Flag to enable safety check. | false | | enable_yield_maneuver | [-] | bool | Flag to enable yield maneuver. | false | +| enable_yield_maneuver_during_shifting | [-] | bool | Flag to enable yield maneuver during shifting. | false | | publish_debug_marker | [-] | bool | Flag to publish debug marker (set `false` as default since it takes considerable cost). | false | | print_debug_info | [-] | bool | Flag to print debug info (set `false` as default since it takes considerable cost). | false | @@ -604,31 +604,52 @@ namespace: `avoidance.` namespace: `avoidance.target_object.` -| Name | Unit | Type | Description | Default value | -| :--------- | ---- | ---- | ------------------------------------------ | ------------- | -| car | [-] | bool | Allow avoidance for object type CAR | true | -| truck | [-] | bool | Allow avoidance for object type TRUCK | true | -| bus | [-] | bool | Allow avoidance for object type BUS | true | -| trailer | [-] | bool | Allow avoidance for object type TRAILER | true | -| unknown | [-] | bool | Allow avoidance for object type UNKNOWN | false | -| bicycle | [-] | bool | Allow avoidance for object type BICYCLE | false | -| motorcycle | [-] | bool | Allow avoidance for object type MOTORCYCLE | false | -| pedestrian | [-] | bool | Allow avoidance for object type PEDESTRIAN | false | +This module supports all object classes, and it can set following parameters independently. + +```yaml +car: + enable: true # [-] + moving_speed_threshold: 1.0 # [m/s] + moving_time_threshold: 1.0 # [s] + max_expand_ratio: 0.0 # [-] + envelope_buffer_margin: 0.3 # [m] + avoid_margin_lateral: 1.0 # [m] + safety_buffer_lateral: 0.7 # [m] + safety_buffer_longitudinal: 0.0 # [m] +``` + +| Name | Unit | Type | Description | Default value | +| :------------------------- | ----- | ------ | ---------------------------------------------------------------------------------------------------------- | ------------- | +| enable | [-] | bool | Allow avoidance for object type CAR | false | +| moving_speed_threshold | [m/s] | double | Objects with speed greater than this will be judged as moving ones. | 1.0 | +| moving_time_threshold | [s] | double | Objects keep moving longer duration than this will be excluded from avoidance target. | 1.0 | +| envelope_buffer_margin | [m] | double | Allow avoidance for object type TRAILER | 0.3 | +| avoid_margin_lateral | [m] | double | The lateral distance between ego and avoidance targets. | 1.0 | +| safety_buffer_lateral | [m] | double | Creates an additional lateral gap that will prevent the vehicle from getting to near to the obstacle. | 0.5 | +| safety_buffer_longitudinal | [m] | double | Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle. | 0.0 | + +Parameters for the logic to compensate perception noise of the far objects. + +| Name | Unit | Type | Description | Default value | +| :----------------------------------- | ---- | ------ | ------------------------------------------------------------------------------------------------------------ | ------------- | +| max_expand_ratio | [-] | double | This value will be applied `envelope_buffer_margin` according to the distance between the ego and object. | 0.0 | +| lower_distance_for_polygon_expansion | [-] | double | If the distance between the ego and object is less than this, the expand ratio will be zero. | 30.0 | +| upper_distance_for_polygon_expansion | [-] | double | If the distance between the ego and object is larger than this, the expand ratio will be `max_expand_ratio`. | 100.0 | namespace: `avoidance.target_filtering.` -| Name | Unit | Type | Description | Default value | -| :------------------------------------- | :---- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| threshold_speed_object_is_stopped | [m/s] | double | Vehicles with speed greater than this will be excluded from avoidance target. | 1.0 | -| threshold_time_object_is_moving | [s] | double | Forward distance to search the avoidance target. | 1.0 | -| threshold_distance_object_is_on_center | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 1.0 | -| object_check_forward_distance | [m] | double | Forward distance to search the avoidance target. | 150.0 | -| object_check_backward_distance | [m] | double | Backward distance to search the avoidance target. | 2.0 | -| object_check_goal_distance | [m] | double | Backward distance to search the avoidance target. | 20.0 | -| object_check_shiftable_ratio | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.6 | -| object_check_min_road_shoulder_width | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.5 | -| object_last_seen_threshold | [s] | double | For the compensation of the detection lost. The object is registered once it is observed as an avoidance target. When the detection loses, the timer will start and the object will be un-registered when the time exceeds this limit. | 2.0 | -| left_hand_traffic | [-] | bool | Flag to select left or right hand traffic. `TRUE: LEFT-HAND TRAFFIC / FALSE: RIGHT-HAND TRAFFIC` | true | +| Name | Unit | Type | Description | Default value | +| :---------------------------------------- | :--- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| threshold_distance_object_is_on_center | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 1.0 | +| object_ignore_distance_traffic_light | [m] | double | If the distance between traffic light and vehicle is less than this parameter, this module will ignore it. | 30.0 | +| object_ignore_distance_crosswalk_forward | [m] | double | If the front distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | +| object_ignore_distance_crosswalk_backward | [m] | double | If the back distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | +| object_check_forward_distance | [m] | double | Forward distance to search the avoidance target. | 150.0 | +| object_check_backward_distance | [m] | double | Backward distance to search the avoidance target. | 2.0 | +| object_check_goal_distance | [m] | double | Backward distance to search the avoidance target. | 20.0 | +| object_check_shiftable_ratio | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.6 | +| object_check_min_road_shoulder_width | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.5 | +| object_last_seen_threshold | [s] | double | For the compensation of the detection lost. The object is registered once it is observed as an avoidance target. When the detection loses, the timer will start and the object will be un-registered when the time exceeds this limit. | 2.0 | ### Safety check parameters @@ -646,14 +667,13 @@ namespace: `avoidance.safety_check.` namespace: `avoidance.avoidance.lateral.` -| Name | Unit | Type | Description | Default value | -| :------------------------------------ | :--- | :----- | :-------------------------------------------------------------------------------------------------------------------------- | :------------ | -| lateral_collision_margin | [m] | double | The lateral distance between ego and avoidance targets. | 1.0 | -| lateral_collision_safety_buffer | [m] | double | Creates an additional gap that will prevent the vehicle from getting to near to the obstacle | 0.7 | -| road_shoulder_safety_margin | [m] | double | Prevents the generated path to come too close to the road shoulders. | 0.0 | -| avoidance_execution_lateral_threshold | [m] | double | The lateral distance deviation threshold between the current path and suggested avoidance point to execute avoidance. (\*2) | 0.499 | -| max_right_shift_length | [m] | double | Maximum shift length for right direction | 5.0 | -| max_left_shift_length | [m] | double | Maximum shift length for left direction | 5.0 | +| Name | Unit | Type | Description | Default value | +| :---------------------------- | :--- | :----- | :-------------------------------------------------------------------------------------------------------------------------- | :------------ | +| road_shoulder_safety_margin | [m] | double | Prevents the generated path to come too close to the road shoulders. | 0.0 | +| lateral_execution_threshold | [m] | double | The lateral distance deviation threshold between the current path and suggested avoidance point to execute avoidance. (\*2) | 0.499 | +| lateral_small_shift_threshold | [m] | double | The shift lines whose lateral offset is less than this will be applied with other ones. | 0.501 | +| max_right_shift_length | [m] | double | Maximum shift length for right direction | 5.0 | +| max_left_shift_length | [m] | double | Maximum shift length for left direction | 5.0 | namespace: `avoidance.avoidance.longitudinal.` From a31dfdb49a95f02c6c906b094bdc23e11cb84af4 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Mon, 26 Jun 2023 19:17:29 +0900 Subject: [PATCH 024/118] feat(behavior_path_planner): enable delay lane change when necessary (#3991) * feat(behavior_path_planner): enable delay lane change when necessary Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * feat(behavior_path_planner): add a function to judge a parked vehicle Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * Update planning/behavior_path_planner/src/utils/lane_change/utils.cpp Co-authored-by: Fumiya Watanabe * update name Signed-off-by: yutaka --------- Signed-off-by: yutaka Co-authored-by: Fumiya Watanabe --- .../config/lane_change/lane_change.param.yaml | 4 + .../lane_change/lane_change_module_data.hpp | 4 + .../utils/lane_change/utils.hpp | 12 ++ .../src/behavior_path_planner_node.cpp | 6 + .../src/scene_module/lane_change/normal.cpp | 22 +++- .../src/utils/lane_change/utils.cpp | 105 ++++++++++++++++++ 6 files changed, 149 insertions(+), 4 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 de3802b070326..95ff106eb4c00 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 @@ -15,6 +15,10 @@ longitudinal_acceleration_sampling_num: 5 lateral_acceleration_sampling_num: 3 + # side walk parked vehicle + object_check_min_road_shoulder_width: 0.5 # [m] + object_shiftable_ratio_threshold: 0.6 + # turn signal min_length_for_turn_signal_activation: 10.0 # [m] length_ratio_for_turn_signal_deactivation: 0.8 # ratio (desired end position) 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 85a77df4c1e0d..4def596f78746 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 @@ -34,6 +34,10 @@ struct LaneChangeParameters int longitudinal_acc_sampling_num{10}; int lateral_acc_sampling_num{10}; + // parked vehicle + double object_check_min_road_shoulder_width{0.5}; + double object_shiftable_ratio_threshold{0.6}; + // turn signal double min_length_for_turn_signal_activation{10.0}; double length_ratio_for_turn_signal_deactivation{0.8}; 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 5b16a67f5349f..9570ffec56576 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 @@ -174,5 +174,17 @@ PredictedPath convertToPredictedPath( const PathWithLaneId & path, const Twist & vehicle_twist, const Pose & pose, const size_t nearest_seg_idx, const double duration, const double resolution, const double prepare_time, const double prepare_acc, const double lane_changing_acc); + +bool passParkedObject( + const RouteHandler & route_handler, const LaneChangePath & lane_change_path, + const PathWithLaneId & current_lane_path, const PredictedObjects & objects, + const std::vector & target_lane_obj_indices, const double minimum_lane_change_length, + const bool is_goal_in_route, const double object_check_min_road_shoulder_width, + const double object_shiftable_ratio_threshold); + +boost::optional getLeadingStaticObjectIdx( + const RouteHandler & route_handler, const LaneChangePath & lane_change_path, + const PredictedObjects & objects, const std::vector & obj_indices, + const double object_check_min_road_shoulder_width, const double object_shiftable_ratio_threshold); } // namespace behavior_path_planner::utils::lane_change #endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_ 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 f7336dad3f895..0384a702ff129 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -787,6 +787,12 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam() p.lateral_acc_sampling_num = declare_parameter(parameter("lateral_acceleration_sampling_num")); + // parked vehicle detection + p.object_check_min_road_shoulder_width = + declare_parameter(parameter("object_check_min_road_shoulder_width")); + p.object_shiftable_ratio_threshold = + declare_parameter(parameter("object_shiftable_ratio_threshold")); + // turn signal p.min_length_for_turn_signal_activation = declare_parameter(parameter("min_length_for_turn_signal_activation")); 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 7f0d84fc94aed..b56e382cc52ce 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 @@ -539,10 +539,10 @@ bool NormalLaneChange::getLaneChangePaths( const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanelets.back()); - const auto shift_intervals = - route_handler.getLateralIntervalsToPreferredLane(target_lanelets.back()); - const double next_lane_change_buffer = - utils::calcMinimumLaneChangeLength(common_parameter, shift_intervals); + const double lane_change_buffer = utils::calcMinimumLaneChangeLength( + common_parameter, route_handler.getLateralIntervalsToPreferredLane(original_lanelets.back())); + const double next_lane_change_buffer = utils::calcMinimumLaneChangeLength( + common_parameter, route_handler.getLateralIntervalsToPreferredLane(target_lanelets.back())); const auto dist_to_end_of_current_lanes = utils::getDistanceToEndOfLane(getEgoPose(), original_lanelets); @@ -725,6 +725,20 @@ bool NormalLaneChange::getLaneChangePaths( {*candidate_path}, *dynamic_objects, backward_target_lanes_for_object_filtering, getEgoPose(), common_parameter.forward_path_length, *lane_change_parameters_, lateral_buffer); + + const double object_check_min_road_shoulder_width = + lane_change_parameters_->object_check_min_road_shoulder_width; + const double object_shiftable_ratio_threshold = + lane_change_parameters_->object_shiftable_ratio_threshold; + const auto current_lane_path = route_handler.getCenterLinePath( + original_lanelets, 0.0, std::numeric_limits::max()); + const bool pass_parked_object = utils::lane_change::passParkedObject( + route_handler, *candidate_path, current_lane_path, *dynamic_objects, + dynamic_object_indices.target_lane, lane_change_buffer, is_goal_in_route, + object_check_min_road_shoulder_width, object_shiftable_ratio_threshold); + if (pass_parked_object) { + return false; + } } candidate_paths->push_back(*candidate_path); 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 37ce67a2927f0..919541f5972a4 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -1058,4 +1058,109 @@ PredictedPath convertToPredictedPath( return predicted_path; } + +bool passParkedObject( + const RouteHandler & route_handler, const LaneChangePath & lane_change_path, + const PathWithLaneId & current_lane_path, const PredictedObjects & objects, + const std::vector & target_lane_obj_indices, const double minimum_lane_change_length, + const bool is_goal_in_route, const double object_check_min_road_shoulder_width, + const double object_shiftable_ratio_threshold) +{ + const auto & path = lane_change_path.path; + + if (target_lane_obj_indices.empty() || path.points.empty() || current_lane_path.points.empty()) { + return false; + } + + const auto leading_obj_idx = getLeadingStaticObjectIdx( + route_handler, lane_change_path, objects, target_lane_obj_indices, + object_check_min_road_shoulder_width, object_shiftable_ratio_threshold); + if (!leading_obj_idx) { + return false; + } + + const auto & leading_obj = objects.objects.at(*leading_obj_idx); + const auto & leading_obj_poly = tier4_autoware_utils::toPolygon2d(leading_obj); + if (leading_obj_poly.outer().empty()) { + return false; + } + + const auto & current_path_end = current_lane_path.points.back().point.pose.position; + double min_dist_to_end_of_current_lane = std::numeric_limits::max(); + for (const auto & point : leading_obj_poly.outer()) { + const auto obj_p = tier4_autoware_utils::createPoint(point.x(), point.y(), 0.0); + const double dist = + motion_utils::calcSignedArcLength(current_lane_path.points, obj_p, current_path_end); + min_dist_to_end_of_current_lane = std::min(dist, min_dist_to_end_of_current_lane); + if (is_goal_in_route) { + const auto goal_pose = route_handler.getGoalPose(); + const double dist_to_goal = + motion_utils::calcSignedArcLength(current_lane_path.points, obj_p, goal_pose.position); + min_dist_to_end_of_current_lane = std::min(min_dist_to_end_of_current_lane, dist_to_goal); + } + } + + // If there are still enough length after the target object, we delay the lane change + if (min_dist_to_end_of_current_lane > minimum_lane_change_length) { + return true; + } + + return false; +} + +boost::optional getLeadingStaticObjectIdx( + const RouteHandler & route_handler, const LaneChangePath & lane_change_path, + const PredictedObjects & objects, const std::vector & obj_indices, + const double object_check_min_road_shoulder_width, const double object_shiftable_ratio_threshold) +{ + const auto & path = lane_change_path.path; + + if (path.points.empty() || obj_indices.empty()) { + return {}; + } + + const auto & lane_change_start = lane_change_path.lane_changing_start; + const auto & path_end = path.points.back(); + + double dist_lc_start_to_leading_obj = 0.0; + boost::optional leading_obj_idx = boost::none; + for (const auto & obj_idx : obj_indices) { + const auto & obj = objects.objects.at(obj_idx); + const auto & obj_pose = obj.kinematics.initial_pose_with_covariance.pose; + + // ignore non-static object + // TODO(shimizu): parametrize threshold + if (obj.kinematics.initial_twist_with_covariance.twist.linear.x > 1.0) { + continue; + } + + // ignore non-parked object + if (!isParkedObject( + path, route_handler, obj, object_check_min_road_shoulder_width, + object_shiftable_ratio_threshold)) { + continue; + } + + const double dist_back_to_obj = motion_utils::calcSignedArcLength( + path.points, path_end.point.pose.position, obj_pose.position); + if (dist_back_to_obj > 0.0) { + // object is not on the lane change path + continue; + } + + const double dist_lc_start_to_obj = + motion_utils::calcSignedArcLength(path.points, lane_change_start.position, obj_pose.position); + if (dist_lc_start_to_obj < 0.0) { + // object is on the lane changing path or behind it. It will be detected in safety check + continue; + } + + if (dist_lc_start_to_obj > dist_lc_start_to_leading_obj) { + dist_lc_start_to_leading_obj = dist_lc_start_to_obj; + leading_obj_idx = obj_idx; + } + } + + return leading_obj_idx; +} } // namespace behavior_path_planner::utils::lane_change From fba97f90696148233b57aa58b7d00e20a512d0f7 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 26 Jun 2023 19:27:29 +0900 Subject: [PATCH 025/118] fix(occupancy grid): fix launcher (#4063) Signed-off-by: Mamoru Sobue --- .../config/binary_bayes_filter_updater.param.yaml | 13 ++++++------- .../laserscan_based_occupancy_grid_map.launch.py | 6 ++---- .../pointcloud_based_occupancy_grid_map.launch.py | 11 ++--------- ...cupancy_grid_map_binary_bayes_filter_updater.cpp | 10 +++++----- 4 files changed, 15 insertions(+), 25 deletions(-) diff --git a/perception/probabilistic_occupancy_grid_map/config/binary_bayes_filter_updater.param.yaml b/perception/probabilistic_occupancy_grid_map/config/binary_bayes_filter_updater.param.yaml index afb776d9fd961..4e335e35740ab 100644 --- a/perception/probabilistic_occupancy_grid_map/config/binary_bayes_filter_updater.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/binary_bayes_filter_updater.param.yaml @@ -1,9 +1,8 @@ /**: ros__parameters: - binary_bayes_filter: - probability_matrix: - occupied_to_occupied: 0.95 - occupied_to_free: 0.05 - free_to_occupied: 0.2 - free_to_free: 0.8 - v_ratio: 10.0 + probability_matrix: + occupied_to_occupied: 0.95 + occupied_to_free: 0.05 + free_to_occupied: 0.2 + free_to_free: 0.8 + v_ratio: 10.0 diff --git a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py index 26c7482943333..355cc4bd8b5bd 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py @@ -107,6 +107,7 @@ def launch_setup(context, *args, **kwargs): "input_obstacle_and_raw_pointcloud": LaunchConfiguration( "input_obstacle_and_raw_pointcloud" ), + "updater_type": LaunchConfiguration("updater_type"), }, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], @@ -164,10 +165,7 @@ def add_launch_arg(name: str, default_value=None): get_package_share_directory("probabilistic_occupancy_grid_map") + "/config/laserscan_based_occupancy_grid_map.param.yaml", ), - add_launch_arg( - "updater_type", - "binary_bayes_filter", - ), + add_launch_arg("updater_type", "binary_bayes_filter"), add_launch_arg( "updater_param_file", get_package_share_directory("probabilistic_occupancy_grid_map") diff --git a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py index f6cd4200f6e4b..5b6e0d1c3c242 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py @@ -26,11 +26,6 @@ import yaml -def overwrite_config(param_dict, launch_config_name, node_params_name, context): - if LaunchConfiguration(launch_config_name).perform(context) != "": - param_dict[node_params_name] = LaunchConfiguration(launch_config_name).perform(context) - - def launch_setup(context, *args, **kwargs): # load parameter files param_file = LaunchConfiguration("param_file").perform(context) @@ -62,6 +57,7 @@ def launch_setup(context, *args, **kwargs): parameters=[ pointcloud_based_occupancy_grid_map_node_params, occupancy_grid_map_updater_params, + {"updater_type": LaunchConfiguration("updater_type")}, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ), @@ -116,10 +112,7 @@ def add_launch_arg(name: str, default_value=None): get_package_share_directory("probabilistic_occupancy_grid_map") + "/config/pointcloud_based_occupancy_grid_map.param.yaml", ), - add_launch_arg( - "updater_type", - "binary_bayes_filter", - ), + add_launch_arg("updater_type", "binary_bayes_filter"), add_launch_arg( "updater_param_file", get_package_share_directory("probabilistic_occupancy_grid_map") diff --git a/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp b/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp index 01763b00d2a87..16de17b1c2e61 100644 --- a/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp @@ -30,14 +30,14 @@ OccupancyGridMapBBFUpdater::OccupancyGridMapBBFUpdater( void OccupancyGridMapBBFUpdater::initRosParam(rclcpp::Node & node) { probability_matrix_(Index::OCCUPIED, Index::OCCUPIED) = - node.declare_parameter("binary_bayes_filter.probability_matrix.occupied_to_occupied"); + node.declare_parameter("probability_matrix.occupied_to_occupied"); probability_matrix_(Index::FREE, Index::OCCUPIED) = - node.declare_parameter("binary_bayes_filter.probability_matrix.occupied_to_free"); + node.declare_parameter("probability_matrix.occupied_to_free"); probability_matrix_(Index::FREE, Index::FREE) = - node.declare_parameter("binary_bayes_filter.probability_matrix.free_to_free"); + node.declare_parameter("probability_matrix.free_to_free"); probability_matrix_(Index::OCCUPIED, Index::FREE) = - node.declare_parameter("binary_bayes_filter.probability_matrix.free_to_occupied"); - v_ratio_ = node.declare_parameter("binary_bayes_filter.v_ratio"); + node.declare_parameter("probability_matrix.free_to_occupied"); + v_ratio_ = node.declare_parameter("v_ratio"); } inline unsigned char OccupancyGridMapBBFUpdater::applyBBF( From ec6387afd0efb504ef9b32b3a38978402a2025ac Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 26 Jun 2023 20:11:14 +0900 Subject: [PATCH 026/118] feat(default_ad_api): add vehicle info api (#2984) * feat(default_ad_api): add vehicle dimensions api Signed-off-by: Takagi, Isamu * feat: add footprint Signed-off-by: Takagi, Isamu * update api name Signed-off-by: Takagi, Isamu --------- Signed-off-by: Takagi, Isamu --- .../include/autoware_ad_api_specs/vehicle.hpp | 33 +++++++++ system/default_ad_api/CMakeLists.txt | 2 + .../launch/default_ad_api.launch.py | 1 + system/default_ad_api/package.xml | 1 + system/default_ad_api/src/vehicle_info.cpp | 71 +++++++++++++++++++ system/default_ad_api/src/vehicle_info.hpp | 39 ++++++++++ 6 files changed, 147 insertions(+) create mode 100644 common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp create mode 100644 system/default_ad_api/src/vehicle_info.cpp create mode 100644 system/default_ad_api/src/vehicle_info.hpp diff --git a/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp new file mode 100644 index 0000000000000..4d5acd544b41d --- /dev/null +++ b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp @@ -0,0 +1,33 @@ +// 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 AUTOWARE_AD_API_SPECS__VEHICLE_HPP_ +#define AUTOWARE_AD_API_SPECS__VEHICLE_HPP_ + +#include + +#include + +namespace autoware_ad_api::vehicle +{ + +struct Dimensions +{ + using Service = autoware_adapi_v1_msgs::srv::GetVehicleDimensions; + static constexpr char name[] = "/api/vehicle/dimensions"; +}; + +} // namespace autoware_ad_api::vehicle + +#endif // AUTOWARE_AD_API_SPECS__VEHICLE_HPP_ diff --git a/system/default_ad_api/CMakeLists.txt b/system/default_ad_api/CMakeLists.txt index a09cb1222d2f9..28eec2e8eefc0 100644 --- a/system/default_ad_api/CMakeLists.txt +++ b/system/default_ad_api/CMakeLists.txt @@ -12,6 +12,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/operation_mode.cpp src/planning.cpp src/routing.cpp + src/vehicle_info.cpp src/utils/route_conversion.cpp src/compatibility/autoware_state.cpp ) @@ -25,6 +26,7 @@ rclcpp_components_register_nodes(${PROJECT_NAME} "default_ad_api::OperationModeNode" "default_ad_api::PlanningNode" "default_ad_api::RoutingNode" + "default_ad_api::VehicleInfoNode" ) if(BUILD_TESTING) diff --git a/system/default_ad_api/launch/default_ad_api.launch.py b/system/default_ad_api/launch/default_ad_api.launch.py index 1cc57d5436cd0..c9a3abf9f8e5d 100644 --- a/system/default_ad_api/launch/default_ad_api.launch.py +++ b/system/default_ad_api/launch/default_ad_api.launch.py @@ -49,6 +49,7 @@ def generate_launch_description(): create_api_node("operation_mode", "OperationModeNode"), create_api_node("planning", "PlanningNode"), create_api_node("routing", "RoutingNode"), + create_api_node("vehicle_info", "VehicleInfoNode"), ] container = ComposableNodeContainer( namespace="default_ad_api", diff --git a/system/default_ad_api/package.xml b/system/default_ad_api/package.xml index d99037fdc42d0..3e11cbb2952ed 100644 --- a/system/default_ad_api/package.xml +++ b/system/default_ad_api/package.xml @@ -28,6 +28,7 @@ std_srvs tier4_control_msgs tier4_system_msgs + vehicle_info_util python3-flask diff --git a/system/default_ad_api/src/vehicle_info.cpp b/system/default_ad_api/src/vehicle_info.cpp new file mode 100644 index 0000000000000..cff7ac5cd5eae --- /dev/null +++ b/system/default_ad_api/src/vehicle_info.cpp @@ -0,0 +1,71 @@ +// 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 "vehicle_info.hpp" + +#include + +namespace +{ + +auto create_point(double x, double y) +{ + geometry_msgs::msg::Point32 point; + point.x = x; + point.y = y; + point.z = 0.0; + return point; +} + +} // namespace + +namespace default_ad_api +{ + +VehicleInfoNode::VehicleInfoNode(const rclcpp::NodeOptions & options) +: Node("vehicle_info", options) +{ + const auto on_vehicle_dimensions = [this](auto, auto res) { + res->status.success = true; + res->dimensions = dimensions_; + }; + + const auto vehicle = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + dimensions_.wheel_radius = vehicle.wheel_radius_m; + dimensions_.wheel_width = vehicle.wheel_width_m; + dimensions_.wheel_base = vehicle.wheel_base_m; + dimensions_.wheel_tread = vehicle.wheel_tread_m; + dimensions_.front_overhang = vehicle.front_overhang_m; + dimensions_.rear_overhang = vehicle.rear_overhang_m; + dimensions_.left_overhang = vehicle.left_overhang_m; + dimensions_.right_overhang = vehicle.right_overhang_m; + dimensions_.height = vehicle.vehicle_height_m; + + const auto l = (vehicle.wheel_tread_m / 2.0) + vehicle.left_overhang_m; + const auto r = (vehicle.wheel_tread_m / 2.0) + vehicle.right_overhang_m; + const auto b = vehicle.rear_overhang_m; + const auto f = vehicle.front_overhang_m + vehicle.wheel_base_m; + dimensions_.footprint.points.push_back(create_point(+f, +r)); + dimensions_.footprint.points.push_back(create_point(+f, -l)); + dimensions_.footprint.points.push_back(create_point(-b, -l)); + dimensions_.footprint.points.push_back(create_point(-b, +r)); + + const auto adaptor = component_interface_utils::NodeAdaptor(this); + adaptor.init_srv(srv_dimensions_, on_vehicle_dimensions); +} + +} // namespace default_ad_api + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::VehicleInfoNode) diff --git a/system/default_ad_api/src/vehicle_info.hpp b/system/default_ad_api/src/vehicle_info.hpp new file mode 100644 index 0000000000000..c7171ddf52485 --- /dev/null +++ b/system/default_ad_api/src/vehicle_info.hpp @@ -0,0 +1,39 @@ +// 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 VEHICLE_INFO_HPP_ +#define VEHICLE_INFO_HPP_ + +#include +#include + +// This file should be included after messages. +#include "utils/types.hpp" + +namespace default_ad_api +{ + +class VehicleInfoNode : public rclcpp::Node +{ +public: + explicit VehicleInfoNode(const rclcpp::NodeOptions & options); + +private: + Srv srv_dimensions_; + autoware_adapi_v1_msgs::msg::VehicleDimensions dimensions_; +}; + +} // namespace default_ad_api + +#endif // VEHICLE_INFO_HPP_ From 52099a5a643da06ee46c9f26b2e595233e9e688b Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 26 Jun 2023 21:43:18 +0900 Subject: [PATCH 027/118] fix(behavior_path_planner): fix invalid access in avoidance module (#4081) Signed-off-by: tomoya.kimura --- .../src/scene_module/avoidance/avoidance_module.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 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 8c0d6d4acd48a..91f1c23c3008d 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 @@ -3045,7 +3045,7 @@ TurnSignalInfo AvoidanceModule::calcTurnSignalInfo(const ShiftedPath & path) con } // compute blinker start idx and end idx - const size_t blinker_start_idx = [&]() { + size_t blinker_start_idx = [&]() { for (size_t idx = start_idx; idx <= end_idx; ++idx) { const double current_shift_length = path.shift_length.at(idx); if (current_shift_length > 0.1) { @@ -3054,7 +3054,13 @@ TurnSignalInfo AvoidanceModule::calcTurnSignalInfo(const ShiftedPath & path) con } return start_idx; }(); - const size_t blinker_end_idx = end_idx; + size_t blinker_end_idx = end_idx; + + // prevent invalid access for out-of-range + blinker_start_idx = + std::min(std::max(std::size_t(0), blinker_start_idx), path.path.points.size() - 1); + blinker_end_idx = + std::min(std::max(blinker_start_idx, blinker_end_idx), path.path.points.size() - 1); const auto blinker_start_pose = path.path.points.at(blinker_start_idx).point.pose; const auto blinker_end_pose = path.path.points.at(blinker_end_idx).point.pose; From 3e12df8328c341c9a66b71a611a9fef0b1c7a745 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Mon, 26 Jun 2023 22:29:19 +0900 Subject: [PATCH 028/118] refactor(mission_planner): use lower case (#4079) Signed-off-by: yutaka --- .../src/mission_planner/mission_planner.cpp | 14 +++++++------- .../src/mission_planner/mission_planner.hpp | 2 +- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 6ac62128c3bc1..0c9b27a685583 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -391,7 +391,7 @@ void MissionPlanner::on_set_mrm_route( // check route safety // step1. if in mrm state, check with mrm route if (mrm_route_) { - if (checkRerouteSafety(*mrm_route_, new_route)) { + if (check_reroute_safety(*mrm_route_, new_route)) { // success to reroute change_mrm_route(new_route); res->status.success = true; @@ -413,7 +413,7 @@ void MissionPlanner::on_set_mrm_route( } // step2. if not in mrm state, check with normal route - if (checkRerouteSafety(*normal_route_, new_route)) { + if (check_reroute_safety(*normal_route_, new_route)) { // success to reroute change_mrm_route(new_route); res->status.success = true; @@ -455,7 +455,7 @@ void MissionPlanner::on_clear_mrm_route( } // check route safety - if (checkRerouteSafety(*mrm_route_, *normal_route_)) { + if (check_reroute_safety(*mrm_route_, *normal_route_)) { clear_mrm_route(); change_route(*normal_route_); change_state(RouteState::Message::SET); @@ -470,7 +470,7 @@ void MissionPlanner::on_clear_mrm_route( normal_route_->allow_modification); // check new route safety - if (new_route.segments.empty() || !checkRerouteSafety(*mrm_route_, new_route)) { + if (new_route.segments.empty() || !check_reroute_safety(*mrm_route_, new_route)) { // failed to create a new route RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 5000, "Reroute with normal goal failed."); change_mrm_route(*mrm_route_); @@ -591,7 +591,7 @@ void MissionPlanner::on_change_route( } // check route safety - if (checkRerouteSafety(*normal_route_, new_route)) { + if (check_reroute_safety(*normal_route_, new_route)) { // success to reroute change_route(new_route); res->status.success = true; @@ -649,7 +649,7 @@ void MissionPlanner::on_change_route_points( } // check route safety - if (checkRerouteSafety(*normal_route_, new_route)) { + if (check_reroute_safety(*normal_route_, new_route)) { // success to reroute change_route(new_route); res->status.success = true; @@ -664,7 +664,7 @@ void MissionPlanner::on_change_route_points( } } -bool MissionPlanner::checkRerouteSafety( +bool MissionPlanner::check_reroute_safety( const LaneletRoute & original_route, const LaneletRoute & target_route) { if (original_route.segments.empty() || target_route.segments.empty() || !map_ptr_ || !odometry_) { diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index d3ca6be7eb63f..4d09f72f81899 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -135,7 +135,7 @@ class MissionPlanner : public rclcpp::Node double reroute_time_threshold_{10.0}; double minimum_reroute_length_{30.0}; - bool checkRerouteSafety(const LaneletRoute & original_route, const LaneletRoute & target_route); + bool check_reroute_safety(const LaneletRoute & original_route, const LaneletRoute & target_route); std::shared_ptr normal_route_{nullptr}; std::shared_ptr mrm_route_{nullptr}; From d03c8af7f4cea65e8df8a89cf4a0aed68cda70e7 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 27 Jun 2023 10:36:55 +0900 Subject: [PATCH 029/118] feat: use vehicle_stop_checker for judging vehicle stop vehicle_cmd_gate (#4060) * feat: use vehicle_stop_checker for judging vehicle stop vehicle_cmd_gate Signed-off-by: tomoya.kimura * remove unused include Signed-off-by: tomoya.kimura --------- Signed-off-by: tomoya.kimura --- control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml | 1 + control/vehicle_cmd_gate/package.xml | 1 + control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp | 6 +++++- control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp | 6 ++++++ 4 files changed, 13 insertions(+), 1 deletion(-) 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 9fe692e16d962..7a49d3e5f82d3 100644 --- a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml +++ b/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml @@ -10,6 +10,7 @@ emergency_acceleration: -2.4 moderate_stop_service_acceleration: -1.5 stopped_state_entry_duration_time: 0.1 + stop_check_duration: 1.0 nominal: vel_lim: 25.0 lon_acc_lim: 5.0 diff --git a/control/vehicle_cmd_gate/package.xml b/control/vehicle_cmd_gate/package.xml index f2a3fc83e8d63..df1de9f370cb6 100644 --- a/control/vehicle_cmd_gate/package.xml +++ b/control/vehicle_cmd_gate/package.xml @@ -21,6 +21,7 @@ component_interface_utils diagnostic_updater geometry_msgs + motion_utils rclcpp rclcpp_components std_srvs diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index 8af8c2426b430..25221c652e81d 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -51,6 +51,9 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) rclcpp::QoS durable_qos{1}; durable_qos.transient_local(); + // Stop Checker + vehicle_stop_checker_ = std::make_unique(this); + // Publisher vehicle_cmd_emergency_pub_ = create_publisher("output/vehicle_cmd_emergency", durable_qos); @@ -145,6 +148,7 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) emergency_acceleration_ = declare_parameter("emergency_acceleration"); moderate_stop_service_acceleration_ = declare_parameter("moderate_stop_service_acceleration"); + stop_check_duration_ = declare_parameter("stop_check_duration"); // Vehicle Parameter const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); @@ -492,7 +496,7 @@ AckermannControlCommand VehicleCmdGate::filterControlCommand(const AckermannCont const double dt = getDt(); const auto mode = current_operation_mode_; const auto current_status_cmd = getActualStatusAsCommand(); - const auto ego_is_stopped = std::abs(current_status_cmd.longitudinal.speed) < 1e-3; + const auto ego_is_stopped = vehicle_stop_checker_->isVehicleStopped(stop_check_duration_); const auto input_cmd_is_stopping = in.longitudinal.acceleration < 0.0; // Apply transition_filter when transiting from MANUAL to AUTO. diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index 1a75d3700f346..17bfe99d45251 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -20,6 +20,7 @@ #include "vehicle_cmd_filter.hpp" #include +#include #include #include @@ -70,6 +71,7 @@ using nav_msgs::msg::Odometry; using EngageMsg = autoware_auto_vehicle_msgs::msg::Engage; using EngageSrv = tier4_external_api_msgs::srv::Engage; +using motion_utils::VehicleStopChecker; struct Commands { AckermannControlCommand control; @@ -219,6 +221,10 @@ class VehicleCmdGate : public rclcpp::Node // Pause interface for API std::unique_ptr adapi_pause_; std::unique_ptr moderate_stop_interface_; + + // stop checker + std::unique_ptr vehicle_stop_checker_; + double stop_check_duration_; }; } // namespace vehicle_cmd_gate From ed325ef7818d689729ab51938839f56238cd11cb Mon Sep 17 00:00:00 2001 From: Manato Hirabayashi <3022416+manato@users.noreply.github.com> Date: Tue, 27 Jun 2023 13:28:06 +0900 Subject: [PATCH 030/118] feat: add new yolox model (#4068) * feat(tensorrt_yolox): add support for yolox-sPlus-opt Signed-off-by: Manato HIRABAYASHI * feat(tensorrt_yolox): add launchers for each available model Signed-off-by: Manato HIRABAYASHI * style(pre-commit): autofix * fix(tensorrt_yolox.cpp): add if-guard to check empty string Signed-off-by: Manato HIRABAYASHI * feat: download a calibration file to use the new model on TensorRT 8.0 environment Signed-off-by: Manato HIRABAYASHI * refactor: change variable name to adjust to the launcher option Signed-off-by: Manato HIRABAYASHI * refactor: fix obvious missspelling Signed-off-by: Manato HIRABAYASHI * docs: update README - add brief description for yolox-sPlus-opt - emphasizing that ONNX -> engine conversion time may take long Signed-off-by: Manato HIRABAYASHI * style: change file name for consistency Signed-off-by: Manato HIRABAYASHI --------- Signed-off-by: Manato HIRABAYASHI Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- perception/tensorrt_yolox/CMakeLists.txt | 2 + perception/tensorrt_yolox/README.md | 10 +++- .../include/tensorrt_yolox/tensorrt_yolox.hpp | 13 ++--- .../tensorrt_yolox/launch/yolox.launch.xml | 57 +------------------ .../launch/yolox_s_plus_opt.launch.xml | 56 ++++++++++++++++++ .../launch/yolox_tiny.launch.xml | 56 ++++++++++++++++++ .../tensorrt_yolox/src/tensorrt_yolox.cpp | 30 ++++++---- 7 files changed, 149 insertions(+), 75 deletions(-) mode change 100644 => 120000 perception/tensorrt_yolox/launch/yolox.launch.xml create mode 100644 perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml create mode 100644 perception/tensorrt_yolox/launch/yolox_tiny.launch.xml diff --git a/perception/tensorrt_yolox/CMakeLists.txt b/perception/tensorrt_yolox/CMakeLists.txt index 08263d05fbe83..01ade9bac43d6 100644 --- a/perception/tensorrt_yolox/CMakeLists.txt +++ b/perception/tensorrt_yolox/CMakeLists.txt @@ -63,6 +63,8 @@ function(download FILE_NAME FILE_HASH) endfunction() download(yolox-tiny.onnx 97028baf73ce55e115599c9c60651b08) +download(yolox-sPlus-opt.onnx bf3b0155351f90fcdca2626acbfd3bcf) +download(yolox-sPlus-opt.EntropyV2-calibration.table c6e6f1999d5724a017516a956096701f) download(label.txt 9ceadca8b72b6169ee6aabb861fe3e1e) ########## diff --git a/perception/tensorrt_yolox/README.md b/perception/tensorrt_yolox/README.md index a8332ad9eeec1..3c253a0b68489 100644 --- a/perception/tensorrt_yolox/README.md +++ b/perception/tensorrt_yolox/README.md @@ -79,11 +79,17 @@ hence these parameters are ignored when users specify ONNX models including this This package accepts both `EfficientNMS_TRT` attached ONNXs and [models published from the official YOLOX repository](https://github.com/Megvii-BaseDetection/YOLOX/tree/main/demo/ONNXRuntime#download-onnx-models) (we referred to them as "plain" models). +In addition to `yolox-tiny.onnx`, a custom model named `yolox-sPlus-opt.onnx` is either available. +This model is based on YOLOX-s and tuned to perform more accurate detection with almost comparable execution speed with `yolox-tiny`. +To get better results with this model, users are recommended to use some specific running arguments +such as `precision:=int8`, `calibration_algorithm:=Entropy`, `clip_value:=6.0`. +Users can refer `launch/yolox_sPlus_opt.launch.xml` to see how this model can be used. + All models are automatically converted to TensorRT format. These converted files will be saved in the same directory as specified ONNX files with `.engine` filename extension and reused from the next run. -The conversion process may take a while (typically a few minutes) and the inference process is blocked -until complete the conversion, so it will take some time until detection results are published on the first run. +The conversion process may take a while (**typically 10 to 20 minutes**) and the inference process is blocked +until complete the conversion, so it will take some time until detection results are published (**even until appearing in the topic list**) on the first run ### Package acceptable model generation diff --git a/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox.hpp b/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox.hpp index 2bdb9a83bfbf9..bdd6d6fe66861 100644 --- a/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox.hpp +++ b/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox.hpp @@ -81,9 +81,8 @@ class TrtYoloX const std::string & model_path, const std::string & precision, const int num_class = 8, const float score_threshold = 0.3, const float nms_threshold = 0.7, const tensorrt_common::BuildConfig build_config = tensorrt_common::BuildConfig(), - const bool use_gpu_preprocess = false, - const std::string & calibration_image_list_file = std::string(), const double norm_factor = 1.0, - const std::string & cache_dir = "", + const bool use_gpu_preprocess = false, std::string calibration_image_list_file = std::string(), + const double norm_factor = 1.0, const std::string & cache_dir = "", const tensorrt_common::BatchConfig & batch_config = {1, 1, 1}, const size_t max_workspace_size = (1 << 30)); @@ -101,7 +100,7 @@ class TrtYoloX * @warning if we don't allocate buffers using it, "preprocess_gpu" allocates buffers at the * beginning */ - void initPreprocesBuffer(int width, int height); + void initPreprocessBuffer(int width, int height); /** * @brief output TensorRT profiles for each layer @@ -169,11 +168,11 @@ class TrtYoloX CudaUniquePtrHost out_prob_h_; - // flag whether prepreceses are performed on GPU + // flag whether preprocess are performed on GPU bool use_gpu_preprocess_; - // host buffer for preprecessing on GPU + // host buffer for preprocessing on GPU CudaUniquePtrHost image_buf_h_; - // device buffer for preprecessing on GPU + // device buffer for preprocessing on GPU CudaUniquePtr image_buf_d_; // normalization factor used for preprocessing double norm_factor_; diff --git a/perception/tensorrt_yolox/launch/yolox.launch.xml b/perception/tensorrt_yolox/launch/yolox.launch.xml deleted file mode 100644 index d8c67e39e0b8a..0000000000000 --- a/perception/tensorrt_yolox/launch/yolox.launch.xml +++ /dev/null @@ -1,56 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception/tensorrt_yolox/launch/yolox.launch.xml b/perception/tensorrt_yolox/launch/yolox.launch.xml new file mode 120000 index 0000000000000..06ee1ae877c0c --- /dev/null +++ b/perception/tensorrt_yolox/launch/yolox.launch.xml @@ -0,0 +1 @@ +yolox_s_plus_opt.launch.xml \ No newline at end of file diff --git a/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml b/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml new file mode 100644 index 0000000000000..43f59e944f889 --- /dev/null +++ b/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml b/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml new file mode 100644 index 0000000000000..d8c67e39e0b8a --- /dev/null +++ b/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/tensorrt_yolox/src/tensorrt_yolox.cpp b/perception/tensorrt_yolox/src/tensorrt_yolox.cpp index cddaddd1098bb..515ff1d3c6e9e 100644 --- a/perception/tensorrt_yolox/src/tensorrt_yolox.cpp +++ b/perception/tensorrt_yolox/src/tensorrt_yolox.cpp @@ -104,21 +104,31 @@ namespace tensorrt_yolox TrtYoloX::TrtYoloX( const std::string & model_path, const std::string & precision, const int num_class, const float score_threshold, const float nms_threshold, tensorrt_common::BuildConfig build_config, - const bool use_gpu_preprocess, const std::string & calibration_image_list_file, - const double norm_factor, [[maybe_unused]] const std::string & cache_dir, - const tensorrt_common::BatchConfig & batch_config, const size_t max_workspace_size) + const bool use_gpu_preprocess, std::string calibration_image_list_path, const double norm_factor, + [[maybe_unused]] const std::string & cache_dir, const tensorrt_common::BatchConfig & batch_config, + const size_t max_workspace_size) { src_width_ = -1; src_height_ = -1; norm_factor_ = norm_factor; if (precision == "int8") { - if (calibration_image_list_file.empty()) { - throw std::runtime_error( - "calibration_image_list_file should be passed to generate int8 engine."); + if (build_config.clip_value <= 0.0) { + if (calibration_image_list_path.empty()) { + throw std::runtime_error( + "calibration_image_list_path should be passed to generate int8 engine " + "or specify values larger than zero to clip_value."); + } + } else { + // if clip value is larger than zero, calibration file is not needed + calibration_image_list_path = ""; } + int max_batch_size = 1; nvinfer1::Dims input_dims = tensorrt_common::get_input_dims(model_path); - std::vector calibration_images = loadImageList(calibration_image_list_file, ""); + std::vector calibration_images; + if (calibration_image_list_path != "") { + calibration_images = loadImageList(calibration_image_list_path, ""); + } tensorrt_yolox::ImageStream stream(max_batch_size, input_dims, calibration_images); fs::path calibration_table{model_path}; std::string calibName = ""; @@ -231,9 +241,9 @@ TrtYoloX::TrtYoloX( } } -void TrtYoloX::initPreprocesBuffer(int width, int height) +void TrtYoloX::initPreprocessBuffer(int width, int height) { - // if size of source input has benn changed... + // if size of source input has been changed... if (src_width_ != -1 || src_height_ != -1) { if (width != src_width_ || height != src_height_) { // Free cuda memory to reallocate @@ -315,7 +325,7 @@ void TrtYoloX::preprocessGpu(const std::vector & images) CHECK_CUDA_ERROR(cudaMemcpyAsync( image_buf_d_.get(), image_buf_h_.get(), image.cols * image.rows * 3 * sizeof(unsigned char), cudaMemcpyHostToDevice, *stream_)); - // Preprcess on GPU + // Preprocess on GPU resize_bilinear_letterbox_nhwc_to_nchw32_gpu( input_d_.get(), image_buf_d_.get(), input_width, input_height, 3, image.cols, image.rows, 3, static_cast(norm_factor_), *stream_); From 52f375288015b2622dd499a19b1ae0235cb54157 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 27 Jun 2023 13:51:57 +0900 Subject: [PATCH 031/118] refactor(avoidance): rename ununderstandable params (#4088) Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 26 +++++------ .../behavior_path_planner_avoidance_design.md | 44 +++++++++---------- .../utils/avoidance/avoidance_module_data.hpp | 8 ++-- .../src/behavior_path_planner_node.cpp | 14 +++--- .../src/scene_module/avoidance/manager.cpp | 2 +- .../src/utils/avoidance/utils.cpp | 9 ++-- 6 files changed, 52 insertions(+), 51 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 79aca0867cce9..7c785efa0d5a9 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -28,7 +28,7 @@ # avoidance is performed for the object type with true target_object: car: - enable: true # [-] + is_target: true # [-] moving_speed_threshold: 1.0 # [m/s] moving_time_threshold: 1.0 # [s] max_expand_ratio: 0.0 # [-] @@ -37,7 +37,7 @@ safety_buffer_lateral: 0.7 # [m] safety_buffer_longitudinal: 0.0 # [m] truck: - enable: true + is_target: true moving_speed_threshold: 1.0 moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -46,7 +46,7 @@ safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 bus: - enable: true + is_target: true moving_speed_threshold: 1.0 moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -55,7 +55,7 @@ safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 trailer: - enable: true + is_target: true moving_speed_threshold: 1.0 moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -64,7 +64,7 @@ safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 unknown: - enable: false + is_target: false moving_speed_threshold: 1.0 moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -73,7 +73,7 @@ safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 bicycle: - enable: false + is_target: false moving_speed_threshold: 1.0 moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -82,7 +82,7 @@ safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 motorcycle: - enable: false + is_target: false moving_speed_threshold: 1.0 moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -91,7 +91,7 @@ safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 pedestrian: - enable: false + is_target: false moving_speed_threshold: 1.0 moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -104,12 +104,12 @@ # For target object filtering target_filtering: - # filtering moving objects - threshold_time_force_avoidance_for_stopped_vehicle: 10.0 # [s] + # 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_ignore_distance_traffic_light: 30.0 # [m] - object_ignore_distance_crosswalk_forward: 30.0 # [m] - object_ignore_distance_crosswalk_backward: 30.0 # [m] object_check_forward_distance: 150.0 # [m] object_check_backward_distance: 2.0 # [m] object_check_goal_distance: 20.0 # [m] diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md index b023b0dff9602..b290a1efa90da 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md @@ -608,7 +608,7 @@ This module supports all object classes, and it can set following parameters ind ```yaml car: - enable: true # [-] + is_target: true # [-] moving_speed_threshold: 1.0 # [m/s] moving_time_threshold: 1.0 # [s] max_expand_ratio: 0.0 # [-] @@ -618,15 +618,15 @@ car: safety_buffer_longitudinal: 0.0 # [m] ``` -| Name | Unit | Type | Description | Default value | -| :------------------------- | ----- | ------ | ---------------------------------------------------------------------------------------------------------- | ------------- | -| enable | [-] | bool | Allow avoidance for object type CAR | false | -| moving_speed_threshold | [m/s] | double | Objects with speed greater than this will be judged as moving ones. | 1.0 | -| moving_time_threshold | [s] | double | Objects keep moving longer duration than this will be excluded from avoidance target. | 1.0 | -| envelope_buffer_margin | [m] | double | Allow avoidance for object type TRAILER | 0.3 | -| avoid_margin_lateral | [m] | double | The lateral distance between ego and avoidance targets. | 1.0 | -| safety_buffer_lateral | [m] | double | Creates an additional lateral gap that will prevent the vehicle from getting to near to the obstacle. | 0.5 | -| safety_buffer_longitudinal | [m] | double | Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle. | 0.0 | +| Name | Unit | Type | Description | Default value | +| :------------------------- | ----- | ------ | ------------------------------------------------------------------------------------------------------------------------- | ------------- | +| is_target | [-] | bool | By setting this flag `true`, this module avoid those class objects. | false | +| moving_speed_threshold | [m/s] | double | Objects with speed greater than this will be judged as moving ones. | 1.0 | +| moving_time_threshold | [s] | double | Objects keep moving longer duration than this will be excluded from avoidance target. | 1.0 | +| envelope_buffer_margin | [m] | double | The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation. | 0.3 | +| avoid_margin_lateral | [m] | double | The lateral distance between ego and avoidance targets. | 1.0 | +| safety_buffer_lateral | [m] | double | Creates an additional lateral gap that will prevent the vehicle from getting to near to the obstacle. | 0.5 | +| safety_buffer_longitudinal | [m] | double | Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle. | 0.0 | Parameters for the logic to compensate perception noise of the far objects. @@ -638,18 +638,18 @@ Parameters for the logic to compensate perception noise of the far objects. namespace: `avoidance.target_filtering.` -| Name | Unit | Type | Description | Default value | -| :---------------------------------------- | :--- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| threshold_distance_object_is_on_center | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 1.0 | -| object_ignore_distance_traffic_light | [m] | double | If the distance between traffic light and vehicle is less than this parameter, this module will ignore it. | 30.0 | -| object_ignore_distance_crosswalk_forward | [m] | double | If the front distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | -| object_ignore_distance_crosswalk_backward | [m] | double | If the back distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | -| object_check_forward_distance | [m] | double | Forward distance to search the avoidance target. | 150.0 | -| object_check_backward_distance | [m] | double | Backward distance to search the avoidance target. | 2.0 | -| object_check_goal_distance | [m] | double | Backward distance to search the avoidance target. | 20.0 | -| object_check_shiftable_ratio | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.6 | -| object_check_min_road_shoulder_width | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.5 | -| object_last_seen_threshold | [s] | double | For the compensation of the detection lost. The object is registered once it is observed as an avoidance target. When the detection loses, the timer will start and the object will be un-registered when the time exceeds this limit. | 2.0 | +| Name | Unit | Type | Description | Default value | +| :---------------------------------------------------- | :--- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| threshold_distance_object_is_on_center | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 1.0 | +| object_ignore_section_traffic_light_in_front_distance | [m] | double | If the distance between traffic light and vehicle is less than this parameter, this module will ignore it. | 30.0 | +| object_ignore_section_crosswalk_in_front_distance | [m] | double | If the front distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | +| object_ignore_section_crosswalk_behind_distance | [m] | double | If the back distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | +| object_check_forward_distance | [m] | double | Forward distance to search the avoidance target. | 150.0 | +| object_check_backward_distance | [m] | double | Backward distance to search the avoidance target. | 2.0 | +| object_check_goal_distance | [m] | double | Backward distance to search the avoidance target. | 20.0 | +| object_check_shiftable_ratio | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.6 | +| object_check_min_road_shoulder_width | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.5 | +| object_last_seen_threshold | [s] | double | For the compensation of the detection lost. The object is registered once it is observed as an avoidance target. When the detection loses, the timer will start and the object will be un-registered when the time exceeds this limit. | 2.0 | ### Safety check parameters 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 187dca71ae6c8..0b016db9c9c2c 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 @@ -48,7 +48,7 @@ using geometry_msgs::msg::TransformStamped; struct ObjectParameter { - bool enable{false}; + bool is_target{false}; double moving_speed_threshold{0.0}; @@ -134,13 +134,13 @@ struct AvoidanceParameters double threshold_distance_object_is_on_center; // execute only when there is no intersection behind of the stopped vehicle. - double object_ignore_distance_traffic_light; + double object_ignore_section_traffic_light_in_front_distance; // execute only when there is no crosswalk near the stopped vehicle. - double object_ignore_distance_crosswalk_forward; + double object_ignore_section_crosswalk_in_front_distance; // execute only when there is no crosswalk near the stopped vehicle. - double object_ignore_distance_crosswalk_backward; + double object_ignore_section_crosswalk_behind_distance; // distance to avoid object detection double object_check_forward_distance; 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 0384a702ff129..428e064e6bd90 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -581,7 +581,7 @@ AvoidanceParameters BehaviorPathPlannerNode::getAvoidanceParam() { const auto get_object_param = [&](std::string && ns) { ObjectParameter param{}; - param.enable = declare_parameter(ns + "enable"); + param.is_target = declare_parameter(ns + "is_target"); param.moving_speed_threshold = declare_parameter(ns + "moving_speed_threshold"); param.moving_time_threshold = declare_parameter(ns + "moving_time_threshold"); param.max_expand_ratio = declare_parameter(ns + "max_expand_ratio"); @@ -616,12 +616,12 @@ AvoidanceParameters BehaviorPathPlannerNode::getAvoidanceParam() std::string ns = "avoidance.target_filtering."; p.threshold_time_force_avoidance_for_stopped_vehicle = declare_parameter(ns + "threshold_time_force_avoidance_for_stopped_vehicle"); - p.object_ignore_distance_traffic_light = - declare_parameter(ns + "object_ignore_distance_traffic_light"); - p.object_ignore_distance_crosswalk_forward = - declare_parameter(ns + "object_ignore_distance_crosswalk_forward"); - p.object_ignore_distance_crosswalk_backward = - declare_parameter(ns + "object_ignore_distance_crosswalk_backward"); + p.object_ignore_section_traffic_light_in_front_distance = + declare_parameter(ns + "object_ignore_section_traffic_light_in_front_distance"); + p.object_ignore_section_crosswalk_in_front_distance = + declare_parameter(ns + "object_ignore_section_crosswalk_in_front_distance"); + p.object_ignore_section_crosswalk_behind_distance = + declare_parameter(ns + "object_ignore_section_crosswalk_behind_distance"); p.object_check_forward_distance = declare_parameter(ns + "object_check_forward_distance"); p.object_check_backward_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 90dbfa960dbfe..816ed94e5b822 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -47,7 +47,7 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorobject_parameters.at(semantic); - updateParam(parameters, ns + "enable", config.enable); + updateParam(parameters, ns + "is_target", config.is_target); updateParam(parameters, ns + "moving_speed_threshold", config.moving_speed_threshold); updateParam(parameters, ns + "moving_time_threshold", config.moving_time_threshold); updateParam(parameters, ns + "max_expand_ratio", config.max_expand_ratio); diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 8d33faf82e645..5fd1457042693 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -107,7 +107,7 @@ bool isTargetObjectType( return false; } - return parameters->object_parameters.at(t).enable; + return parameters->object_parameters.at(t).is_target; } bool isVehicleTypeObject(const ObjectData & object) @@ -951,7 +951,8 @@ void filterTargetObjects( const auto to_traffic_light = utils::getDistanceToNextTrafficLight(object_pose, data.current_lanelets); { - not_parked_object = to_traffic_light < parameters->object_ignore_distance_traffic_light; + not_parked_object = + to_traffic_light < parameters->object_ignore_section_traffic_light_in_front_distance; } // check crosswalk @@ -961,8 +962,8 @@ void filterTargetObjects( o.longitudinal; { const auto stop_for_crosswalk = - to_crosswalk < parameters->object_ignore_distance_crosswalk_forward && - to_crosswalk > -1.0 * parameters->object_ignore_distance_crosswalk_backward; + 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; } From 084c7e20d6fda5fd7f6356ff4eb3c0738b33c548 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Tue, 27 Jun 2023 14:12:08 +0900 Subject: [PATCH 032/118] fix(behavior_path_planner): enable abort lane change default (#4080) Signed-off-by: Fumiya Watanabe --- .../config/lane_change/lane_change.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 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 95ff106eb4c00..420415ac64578 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 @@ -48,11 +48,11 @@ enable_prepare_segment_collision_check: true prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s] use_predicted_path_outside_lanelet: true - use_all_predicted_path: false + use_all_predicted_path: true # abort enable_cancel_lane_change: true - enable_abort_lane_change: false + enable_abort_lane_change: true abort_delta_time: 1.0 # [s] aborting_time: 5.0 # [s] From cdf26944ec86b23b8eba692c922e3778d0168874 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 27 Jun 2023 16:01:45 +0900 Subject: [PATCH 033/118] fix(behavior_path_planner): fix route update condition (#4091) Signed-off-by: satoshi-ota --- .../behavior_path_planner/src/behavior_path_planner_node.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) 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 428e064e6bd90..d4e9fda75800c 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -1252,7 +1252,10 @@ void BehaviorPathPlannerNode::run() } #ifndef USE_OLD_ARCHITECTURE - if (planner_data_->operation_mode->mode != OperationModeState::AUTONOMOUS) { + const auto controlled_by_autoware_autonomously = + planner_data_->operation_mode->mode == OperationModeState::AUTONOMOUS && + planner_data_->operation_mode->is_autoware_control_enabled; + if (!controlled_by_autoware_autonomously) { planner_manager_->resetRootLanelet(planner_data_); } #endif From 06cdf326a4aee7d79fb4c79e156a2f4d7f047c53 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 27 Jun 2023 16:20:25 +0900 Subject: [PATCH 034/118] refactor(lane_change): add namespace for lane-change-cancel (#4090) * refactor(lane_change): add namespace for lane-change-cancel Signed-off-by: Takamasa Horibe * fix indent Signed-off-by: Takamasa Horibe * lane_change_cancel -> cancel Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../behavior_planning.launch.py | 2 +- .../config/lane_change/lane_change.param.yaml | 14 ++++++------- ...ehavior_path_planner_lane_change_design.md | 17 ++++++++------- .../scene_module/lane_change/base_class.hpp | 7 +++++-- .../lane_change/lane_change_module_data.hpp | 16 ++++++++------ .../src/behavior_path_planner_node.cpp | 21 ++++++++++--------- .../src/scene_module/lane_change/normal.cpp | 10 ++++----- 7 files changed, 48 insertions(+), 39 deletions(-) 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 6dc0b2bea85b3..6150abdafe7d6 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 @@ -102,7 +102,7 @@ def launch_setup(context, *args, **kwargs): behavior_path_planner_param, vehicle_param, { - "lane_change.enable_abort_lane_change": LaunchConfiguration( + "lane_change.cancel.enable_on_lane_changing_phase": LaunchConfiguration( "use_experimental_lane_change_function" ), "lane_change.enable_collision_check_at_prepare_phase": LaunchConfiguration( 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 420415ac64578..049303203ed44 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 @@ -50,13 +50,13 @@ use_predicted_path_outside_lanelet: true use_all_predicted_path: true - # abort - enable_cancel_lane_change: true - enable_abort_lane_change: true - - abort_delta_time: 1.0 # [s] - aborting_time: 5.0 # [s] - abort_max_lateral_jerk: 1000.0 # [m/s3] + # lane change cancel + cancel: + enable_on_prepare_phase: true + enable_on_lane_changing_phase: true + delta_time: 1.0 # [s] + duration: 5.0 # [s] + max_lateral_jerk: 1000.0 # [m/s3] finish_judge_lateral_threshold: 0.2 # [m] 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 945ca579c434a..4b9d04794e43f 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 @@ -240,7 +240,7 @@ detach Suppose the lane change trajectory is evaluated as unsafe. In that case, if the ego vehicle has not departed from the current lane yet, the trajectory will be reset, and the ego vehicle will resume the lane following the maneuver. -The function can be enabled by setting `enable_cancel_lane_change` to `true`. +The function can be enabled by setting `enable_on_prepare_phase` to `true`. The following image illustrates the cancel process. @@ -248,7 +248,7 @@ The following image illustrates the cancel process. #### Abort -Assume the ego vehicle has already departed from the current lane. In that case, it is dangerous to cancel the path, and it will cause the ego vehicle to change the heading direction abruptly. In this case, planning a trajectory that allows the ego vehicle to return to the current path while minimizing the heading changes is necessary. In this case, the lane change module will generate an abort path. The following images show an example of the abort path. Do note that the function DOESN'T GUARANTEE a safe abort process, as it didn't check the presence of the surrounding objects and/or their reactions. The function can be enable manually by setting both `enable_cancel_lane_change` and `enable_abort_lane_change` to `true`. The parameter `abort_max_lateral_jerk` need to be set to a high value in order for it to work. +Assume the ego vehicle has already departed from the current lane. In that case, it is dangerous to cancel the path, and it will cause the ego vehicle to change the heading direction abruptly. In this case, planning a trajectory that allows the ego vehicle to return to the current path while minimizing the heading changes is necessary. In this case, the lane change module will generate an abort path. The following images show an example of the abort path. Do note that the function DOESN'T GUARANTEE a safe abort process, as it didn't check the presence of the surrounding objects and/or their reactions. The function can be enable manually by setting both `enable_on_prepare_phase` and `enable_on_lane_changing_phase` to `true`. The parameter `max_lateral_jerk` need to be set to a high value in order for it to work. ![abort](../image/lane_change/cancel_and_abort/lane_change-abort.png) @@ -301,12 +301,13 @@ The following parameters are configurable in `behavior_path_planner.param.yaml`. The following parameters are configurable in `lane_change.param.yaml`. -| Name | Unit | Type | Description | Default value | -| :-------------------------- | ---- | ------- | --------------------------------------- | ------------- | -| `enable_cancel_lane_change` | [-] | boolean | Enable cancel lane change | true | -| `enable_abort_lane_change` | [-] | boolean | Enable abort lane change. | false | -| `abort_delta_time` | [s] | double | The time taken to start aborting. | 3.0 | -| `abort_max_lateral_jerk` | [s] | double | The maximum lateral jerk for abort path | 1000.0 | +| Name | Unit | Type | Description | Default value | +| :------------------------------------- | ------- | ------- | -------------------------------------------------------------- | ------------- | +| `cancel.enable_on_prepare_phase` | [-] | boolean | Enable cancel lane change | true | +| `cancel.enable_on_lane_changing_phase` | [-] | boolean | Enable abort lane change. | false | +| `cancel.delta_time` | [s] | double | The time taken to start steering to return to the center line. | 3.0 | +| `cancel.duration` | [s] | double | The time taken to complete returning to the center line. | 3.0 | +| `cancel.max_lateral_jerk` | [m/sss] | double | The maximum lateral jerk for abort path | 1000.0 | ### Debug 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 f8d80d8883b38..225b093018d95 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 @@ -145,9 +145,12 @@ class LaneChangeBase LaneChangeParameters getLaneChangeParam() const { return *lane_change_parameters_; } - bool isCancelEnabled() const { return lane_change_parameters_->enable_cancel_lane_change; } + bool isCancelEnabled() const { return lane_change_parameters_->cancel.enable_on_prepare_phase; } - bool isAbortEnabled() const { return lane_change_parameters_->enable_abort_lane_change; } + bool isAbortEnabled() const + { + return lane_change_parameters_->cancel.enable_on_lane_changing_phase; + } bool isSafe() const { return status_.is_safe; } 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 4def596f78746..2a77419092189 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 @@ -26,6 +26,15 @@ namespace behavior_path_planner { + +struct LaneChangeCancelParameters +{ + bool enable_on_prepare_phase{true}; + bool enable_on_lane_changing_phase{false}; + double delta_time{1.0}; + double duration{5.0}; + double max_lateral_jerk{10.0}; +}; struct LaneChangeParameters { // trajectory generation @@ -63,12 +72,7 @@ struct LaneChangeParameters bool check_pedestrian{true}; // check object pedestrian // abort - bool enable_cancel_lane_change{true}; - bool enable_abort_lane_change{false}; - - double abort_delta_time{1.0}; - double aborting_time{5.0}; - double abort_max_lateral_jerk{10.0}; + LaneChangeCancelParameters cancel; double finish_judge_lateral_threshold{0.2}; 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 d4e9fda75800c..f9791b8b79b54 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -825,13 +825,14 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam() p.check_pedestrian = declare_parameter(ns + "pedestrian"); } - // abort - p.enable_cancel_lane_change = declare_parameter(parameter("enable_cancel_lane_change")); - p.enable_abort_lane_change = declare_parameter(parameter("enable_abort_lane_change")); - - p.abort_delta_time = declare_parameter(parameter("abort_delta_time")); - p.aborting_time = declare_parameter(parameter("aborting_time")); - p.abort_max_lateral_jerk = declare_parameter(parameter("abort_max_lateral_jerk")); + // lane change cancel + p.cancel.enable_on_prepare_phase = + declare_parameter(parameter("cancel.enable_on_prepare_phase")); + p.cancel.enable_on_lane_changing_phase = + declare_parameter(parameter("cancel.enable_on_lane_changing_phase")); + p.cancel.delta_time = declare_parameter(parameter("cancel.delta_time")); + p.cancel.duration = declare_parameter(parameter("cancel.duration")); + p.cancel.max_lateral_jerk = declare_parameter(parameter("cancel.max_lateral_jerk")); p.finish_judge_lateral_threshold = declare_parameter("lane_change.finish_judge_lateral_threshold"); @@ -850,10 +851,10 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam() exit(EXIT_FAILURE); } - if (p.abort_delta_time < 1.0) { + if (p.cancel.delta_time < 1.0) { RCLCPP_FATAL_STREAM( - get_logger(), "abort_delta_time: " << p.abort_delta_time << ", is too short.\n" - << "Terminating the program..."); + get_logger(), "cancel.delta_time: " << p.cancel.delta_time << ", is too short.\n" + << "Terminating the program..."); exit(EXIT_FAILURE); } 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 b56e382cc52ce..28d1b30ca5991 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 @@ -387,7 +387,7 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const const double ego_velocity = std::max(getEgoVelocity(), planner_data_->parameters.minimum_lane_changing_velocity); - const double estimated_travel_dist = ego_velocity * lane_change_parameters_->abort_delta_time; + const double estimated_travel_dist = ego_velocity * lane_change_parameters_->cancel.delta_time; double dist = 0.0; for (size_t idx = nearest_idx; idx < status_.lane_change_path.path.points.size() - 1; ++idx) { @@ -454,7 +454,7 @@ bool NormalLaneChange::hasFinishedAbort() const bool NormalLaneChange::isAbortState() const { - if (!lane_change_parameters_->enable_abort_lane_change) { + if (!lane_change_parameters_->cancel.enable_on_lane_changing_phase) { return false; } @@ -945,9 +945,9 @@ bool NormalLaneChange::getAbortPath() }; const auto [abort_start_idx, abort_start_dist] = - get_abort_idx_and_distance(lane_change_parameters_->abort_delta_time); + get_abort_idx_and_distance(lane_change_parameters_->cancel.delta_time); const auto [abort_return_idx, abort_return_dist] = get_abort_idx_and_distance( - lane_change_parameters_->abort_delta_time + lane_change_parameters_->aborting_time); + lane_change_parameters_->cancel.delta_time + lane_change_parameters_->cancel.delta_time); if (abort_start_idx >= abort_return_idx) { RCLCPP_ERROR(logger_, "abort start idx and return idx is equal. can't compute abort path."); @@ -983,7 +983,7 @@ bool NormalLaneChange::getAbortPath() const double & max_lateral_acc = lateral_acc_range.second; path_shifter.setLateralAccelerationLimit(max_lateral_acc); - if (lateral_jerk > lane_change_parameters_->abort_max_lateral_jerk) { + if (lateral_jerk > lane_change_parameters_->cancel.max_lateral_jerk) { RCLCPP_ERROR(logger_, "Aborting jerk is too strong. lateral_jerk = %f", lateral_jerk); return false; } From 6f5af963f4ad01e549941d1547609a86b1ea0b2b Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 27 Jun 2023 16:33:22 +0900 Subject: [PATCH 035/118] fix(lane_change): enrich lane change debug markers (#4076) * fix(lane_change): enrich lane change debug markers Signed-off-by: Zulfaqar Azmi * fix testing error and add some info Signed-off-by: Zulfaqar Azmi * Added polygon id Signed-off-by: Zulfaqar Azmi * include valid path Signed-off-by: Zulfaqar Azmi * remove unused marker Signed-off-by: Zulfaqar Azmi * update documentation Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- ...ehavior_path_planner_lane_change_design.md | 31 ++++++- .../image/lane_change/lane_change-debug-1.png | Bin 0 -> 171140 bytes .../image/lane_change/lane_change-debug-2.png | Bin 0 -> 219621 bytes .../image/lane_change/lane_change-debug-3.png | Bin 0 -> 143759 bytes .../image/lane_change/lane_change-debug.png | Bin 1204325 -> 0 bytes .../marker_util/debug_utilities.hpp | 4 + .../utils/safety_check.hpp | 5 +- .../src/marker_util/lane_change/debug.cpp | 62 +++++++++---- .../src/scene_module/lane_change/normal.cpp | 1 + .../src/utils/lane_change/utils.cpp | 12 +-- .../src/utils/safety_check.cpp | 83 ++++++++++++------ .../test/test_safety_check.cpp | 14 ++- 12 files changed, 154 insertions(+), 58 deletions(-) create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-debug-1.png create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-debug-2.png create mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-debug-3.png delete mode 100644 planning/behavior_path_planner/image/lane_change/lane_change-debug.png 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 4b9d04794e43f..91c3c2a219a20 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 @@ -319,6 +319,33 @@ The following parameters are configurable in `lane_change.param.yaml`. ## Debug Marker & Visualization -To enable the debug marker, execute `ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner lane_change.publish_debug_marker true` (no restart is needed) or simply set the `publish_debug_marker` to `true` in the `lane_change.param.yaml` for permanent effect (restart is needed). Then add the marker `/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lanechange` in `rviz2`. +To enable the debug marker, execute (no restart is needed) -![debug](../image/lane_change/lane_change-debug.png) +```shell +ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner lane_change.publish_debug_marker true + +``` + +or simply set the `publish_debug_marker` to `true` in the `lane_change.param.yaml` for permanent effect (restart is needed). + +Then add the marker + +```shell +/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_change_left +``` + +in `rviz2`. + +![debug](../image/lane_change/lane_change-debug-1.png) + +![debug2](../image/lane_change/lane_change-debug-2.png) + +![debug3](../image/lane_change/lane_change-debug-3.png) + +Available information + +1. Ego to object relation, plus safety check information +2. Ego vehicle interpolated pose up to the latest safety check position. +3. Object is safe or not, shown by the color of the polygon (Green = Safe, Red = unsafe) +4. Valid candidate paths. +5. Position when lane changing start and end. diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-debug-1.png b/planning/behavior_path_planner/image/lane_change/lane_change-debug-1.png new file mode 100644 index 0000000000000000000000000000000000000000..7b6c4cf58cceec5ff304154a9bd896cdf705fb43 GIT binary patch literal 171140 zcmZ6z1yq#L7B)PJfOIMyf`lTSk^(~*ltnip(%p@~&>+$slG5ENAuSz4BRzE2cLwjh z-}nEs7Rv?B`_6mL-uv0l-upQdpeQecgGr7Ffk1Fx%0k~lAn0%i7mY&s$O8Di>xRuxhn7)XpP@bf?CNX1{b$+u*i$Ct%S_7Rvos$ZU zOK{iW@|f|HgX=CvN{63BP-s)v@2;IwgDOZ;X)MpZQq`3nImHku?9dR=9BrS?;` z=^?mT_0iuN*DwZhU2J$jm#=)baLMIq@>60czP%~&;k@K_gTP-#n9XYL#5Jf_jX$10@eS*(5 zL<9simEYJW6Gtvb5YQ2J7J4GXGSv+(7|h5saf=etoVG7X zs4M}6Hgb_-gC~PAn_9u`>FB8{B`ud0)U2$XbQ$-k0ta;mvqY1p}8O^oRb zt=$tS6q-?3U3}lUAz2r^3!+ly&T4FI63+h|4=fpbHsJCF8*n)0q>2rlN=94umYO|R5 zc)=|`3=9lvsvxj`cjlcDP^j0&GLgKVi4$EqeoF<|ab^u-l82A@`D0pe2$b;GU7Gs) z`s~i)yQmZ-&6=B9D%sfjmkvVtz$V`F+yvWNtxcZKl+xEPJ+p*(Tk|p>>9LI zyuc?1h7~F9!}*p&_B^5^5KvF>Ta=^NxBIji5ufP2 zl=VjZ>s#NHlN}<{Hl2i49I#67+o0`lenf})_}2es{;jS%QMK%jC)j=A=E*4@;wOeC zDD)(zMUEDzz=+{d$t`mP#K*|}E>~lHnxB6g1nwOXP+2XC%2?^lu;qoZ3Gnv~(xc>D)On7i0tII9VIXe&|%G&taaRdakEGu@i0hL*aJELGV4cj1~gH zIxRaeHpa9O5t)SJKO9gnUA2%iqd^&!(4#0MYgx%hfLhvUe}H<1Dy#5%^``^omw&Ev z_x>&TXo00Y2Tsi_>$_=cCV8xqnf)Ups}kwJ3`Ibwet}yN-@ha?M!~L>l+(^hiVcUAOimh^ zn6w?!I8?)Rr^ z$?SLFOM81DbS_uA>@MosE_Hq2D&KX0i6M!jq%>Rd_!#ti2 zw^N6@lzb%?PZW6RIHL5Fb#o6wSJe+_USgb&Ej`&_s-!OyW$So zbedmTML-t?l9Y(M-+A@=HQ9T70wu)__0@)dVWLBuU^!DFpBqG*KICxye05=IH03r6 z-4QtZ8VP}jnNB{oVgL!jx^HOX765e=xk13# zo2R9=!~s7LWU|GD8p`oA>q1tQ4zJ4n>WMF)-lz>}O1 z=?mYZA~4D(pCM_?Ay(n4JT&>6o|%~^cP0F#+{<6r5G>nCzeE_b@DVBkn;w{t_^9B( zeY4NT$%YJ-2c%V9X3j?uw-&n(t|nG#HLK)v8W@=h1YVqzUnJ?|be1}OcAL_O2qIkE z%pAz7LFQ!MG-1~c*Y-Rtx2;Ub_H4g}5Lt=tmoFv#_@HS>!wGoJ`qhI>3rRItLJK>2 z1ej9xKRkl``0)dq8a&Li|DP{iXLz;&U&3Cu75q;1G!n_K=*Y$2-kZj*@bMP|TXZ=U zPJxZ~%-N*`ne>!mK~9n|H)lfuzJMu&WG}$66g5=Z=acT@B6lZq)L2PXlL5Iq_X=03 zd;b%t5yWK`UV|8wC?8r5UB5@|p?##I`zEbD-_L6XoFx(IEKsDgy!pQgmY_Phj_EdA zf$)+Y_e+!rYthj`rh;$G{}Lnc&rBp8lC=i@c^71^bdJc_@cWV7kC7k$wOM5V4pOjA zF;yYB&6@I(htt5a8gKxfslUDPI2l7QVBJ?p+N{*P_Fu1~%SGlXunD?8sMFouPl|=M zuEPEi40NI=-e!JN(An2=FIS#{4IuyUA4W|YB8`RtyvqErB6=VpvD0q$k_=^JRmSP|3D~&p80#88Ma7eC`CzYTbGiF(Wegy)W;6kB;Vg z0a!bE>wh8_FusHqp_hKhL^kw4VvH&A_9s9Mgz2`5+0PM%Q>y83A|+;)*yI5u;_?{( zCq;h4VYuQx1sG^#^g5dT)2{qCB;$n=(|X%g@&#lB45g-(4CT8C<5b+Ke8fbzU-k9t zy|6l6!0*qzk%1852riQXfa2poZiif%?Emca@^?zvZ8#g18=9 z{RIgLiT{bR8!gfx#Eal*QpYzrJr?ffz6Rcjsb(@(guE*-N64)$aD6e55%QSx5dmZ5 z%MC7O?Av5)ZyAw}@JZf}kQeqX7$&LoNvRkMj)feFvTj(5VF)h=h=B#qh-M zU-$Q|Z$TUHHm`>8pn<)G(r5pNAWSNH!(C2fH3@y0kq;03FV{S`0$|*UB!Sy}%isd= zB96cP*pPbO&GEYs%zZ3~XNyqCeQ?>MLiP!HSeT4~!APn&|7R0__Wm(Oa=SB^? zgfS(tJ55r(SvwI)Ng~FZH4cf^PX*;KLwZy$>v~f2a;c*ZBJ-nr+|f;(I|%6IAKx5E zb#FXMUnoJ6oRIGzYe017fx&q&N$ZDY0cBXu(1|NZ`j&_dfsGm0Pla7dA_+KOMENta zIHTI@6E^+*Wb-$9MKq&=f?+9)Ig$r*7?KVFED1C z>hh3Zpg@p;ynHBsNxB7bO1*_Br91#H}07W!}^00&ND1YhmF+%WNk1X5E>|*F|;e1XhWT2xH(?c%su?X4@4B_VNFy$2+bfm^Rb#Y5X! zW?}F-Zt*ptutu7S%*x8@RJZ3Jzj_ob=1jS`xVU?rhj$CB-lRyBPoFQd8J8zsCV@aa zJR-**YYr!Yye%zbXvpY3bN1ij7PWrl`+H=OMwh|~3R^l%QIH$%K+tv`2bQv*{xvmA zAN+_+3jif`i$;Sea06hn8Ex&mVG{d2jnh3 zvAhyi`0Ja(RJw)_KDQ%Jd}?!H^H+lVs||y$Wp|W>DlcrW z1my+E!n-|0>^`HX+i%-Wb`VhE*ys{WDI|p^XV~Z}$lil6tEs1&8olWKyOVad@fu3G z_-5n9dk&ElByH_t0*u>l$jAU0`NZvL{f?h^<&(qZ1Q06OBU1Q7UC%+m2Wbw~G-X#< z#!%Ozi#M+(C?L_qlz9^@bCHw(G~#ey48QK!rg?q3=)-|3x1z%UN-;w=cAeR>f=l@M zVf}S;_Imv0kmV|zZQ9`K?4!}E#{I@n?g8(;EcHRR-g{w{F{%ZFZl###z6WXh>D>KB zrCFKHr=9A$f+u$cMmH85Aow*NG>2FuFY2zbiU!6-uWa8p?#K72{4qI5)2@a<21OQB zM&LKJweC(S)Pc37cXJP@kwD*2m|=z3=9oQ|i7DBd)26TfqMsR6c!kO5_V#8xZ;G7K z&78ne_h%dzGlPd%gd|NER}@%}%GBKQx^v&BuQ=EY+Vn1el=Buf{V`hCSl8dnz~JiS^X@cCl)+}jHYejzz#33f-uT( z&1zln50PVz#aR!B3AdzI4Dp2*BEcTj82zxWG=6&l{5o^ix5+N#zdO(%FIHY-4PN)$ zeA(u{E{~+$S=-%kvCMmKRI~VdcGIEV#Dp319SdP}z0cRGhvKvF?a?#H{OV3st?NL< zg}ZeB18$e5aF#*gi&vx;^))Ac5orRHg9X?3y4f2BZ|W6wm}8UiAk351;)|~UP>}vZ z8rJ^;CEs@r$86nh|2a^yFbl`_i_m=9@$mlpT-k-P8l{0dAV0;4`aw}6uD>+P#*F+A z!cm1Ast+C>-AlVg7ZU*j^`}(j8t%S1HnjzkR9+jOlVwJ+ZVm-3(Vg3h#)8r8bAaT7GcK7a@NHgL#lwtRk745H035*((TGXQYM>k@b7{{L;WM$6p3iT*@oHS71 z0E=m6`v5mntXxE~l}mhlewhqo7J{u6BxrU#Q`H}|TI?338ZQizoDQao;dGJ_(i6L} zop3Yjej-qAfC}6~|FoG3vTR-cAStADWhaegN1%iOOJ(?v)ml@JlE=8V2=0v6>`ud8 z^t7eXFLbSjPMprPp>(}#lboiD*##5_NO+H~;Lcsj>j4klZt|rn!7c~Tv_-PPfVY6~ z-(q$9)@&U*1H~&vP?&&9^3GT>#TVZAD0Cu0lJfdQ zos|28kvSxUdS{%XS_}__UA-pMO{94l!c6W;Ld9pSjr8V3a&a z%wPD<5`NxGBsz-EytRkH?6EDU!p-eJ=jfT75i0$w={f{N*5=V0-JS``_x0zs7HMwM zjKAkD@k$Z(RGf2eEaw7k0ooYH93XoZf{65?q>_OetL7V-Wl#-k6V)> zm-2PrCO z-FNuq+rZC*>^9S3ih!gn4w`D}eZ$4bhJ?WX8WNaBa{M!EqLvO5X{=|MoO9;T-YDglk{7oK}xm1c;wNW|L;LNOOY7V+xJ}TEP z^r=n1Yi&cZWwp1~&DpH+KDe@M!1vwcMSlHpi+|dMLDb2d>rMA^j`KA`l~-MTK30i| zsL$UXJ4NLW60?&S38EPAPHL=SCz5m%>*VR3mmfZiPFrhB{B0%6aoZ)Ry5lfXm^A2C ziy7f^{Nju0S9(G6vEDba1BqUhi*v064^~Ru6c7UMudbvF=4^e|jz$Zbif+~UiyXs({ow~m+FYko ztC(g@w^RH@QCAwyIge?I%%0_92Br+R^L3+!)3++a+#1JK1|i}rJwKi}c^CZ}v1sa@(?$)Sz*L#7}&6*#S zvEcqYNGg)EVGIyo_w^g-__8oy=x%W>kG8pD8M$V2iU%gXDA)^9@nnVZBe< z=%d1_gUv!F1vkY0d+EqFv$ zOLE%-)dw8T*?tAi|Lpv=cK?+3{Si3%lP9x~_a^J+PP#JoHES=VeWO(ij>; zvy*yW&Y(@VQ1C0qY2*1JX{h%*DzC91wxf9=`=Ybo`4>K%F@lvAlIJ&Y_WPOdD|lg3 zNA!y^tiJ25K}rrgbMvrJ`^hYX1s?r*CzU9wX(Ql^N*9Cl-p!h`LtZ1FlReEx{k`4j zaH&1BmRZ*39C3KVM11>~vTKEBpKn8XG+i3jR4)riH12h|D4!_tkwsirUEm+IIj~JL zPfexf<#_`-E9m9|*@L;U`@VbbIq`@mwS)1VJa3K#L zX!(fTzP;%}v|P(Mu4f5wGVx)%CjaXYU+Sc)<20EWG=vpRz5n+nF%&16x}NI1Jj|i# zN;<0{3Zu&W$n%VYI;Vr z(Szic35voyl*w>ryG+1T)~G$OJ!eg#E(b{Pn@n@(?XVALU!-|l@xB+iA*{`+uAH(+ za(aGvqehF628C$9HGn_P+bYO6tZ`lh%$+11tbDiC+v1=F`(V(gHXezxeb)j;0vhW@Q4Z*Tsv7 zixb^mIsQxX`rp5<)T%&WEmVqOb!1dow8g5MQ`)2DATsd6omRKQRiCjf*(c#1In1%- zF?!_O^oSI9{;CV^e)iB{)~;^4`ARk~@2Npw0|5v*ENYYb75kXt36>@edZ#)vee)V6 z{AxU6z$!atE?shrO*A^FA|i5{PVQLo-V3DHDmwRQ2we7PT;t2xngj6qB}{C~Ub=Fx zBSEB=@vk?xu4uk2NAhmd4c+#T|2?mZ2*4Y^-JIS1rtPk@t1{mH(x^tSzj&2|1<~Mu z>Sejfz}=vo4ry2@+&z^Xu&!cwoVpjSj=F?#bHV;L#qkYzmQ2m6hpG;}zCW|;99}HD zd;pb6ELJ~pFjHg2{agiMK?4`pxF6_G*o8Nb4Rb&yNn6=hO*h`ygg)9_mmV|Yr(Z~_ z@^htPNeCvj*#x!OXf3r&E_B+7Brwkl2FtWj9sU$MYU^~CELNoO|tNBhJ;o56R; zs2%hkz)bWmKC(NFsSX^|kM)WQEhFPqzVh^RRazIX!Q274LFm;NU)lkAg@TC@0IhLXwV z#cbLAz^L(eMIQ&HeWvI|W~WIB%@g-YLUD?tu^@l*6NI_u%GVz^zIju1xDSB;(;o-% zYHbg9=Dx+4vO{_C$2%s?Xs@u(>hhbzJzeHy%oG%3PBlZV*``^y6qpY>e$!!-7M0A< zpWw{#ueaWd`Y1D-?gZh5SPHA3VlwWuZ!bLSwNqrYaoP3`9A5u0j|1VVqv{?IVyCo1h(A}yK z9ut5j4zkmZpEYV+qCXx6I!eUhAS?PZaQA$AbFdA13Cs`dgyVkQg=f>$1y6qa2G~3I zn&@`6JW24n==qD0Gdr4kCgUd17r1A(yFx`ZSg_xS8wU@qe$YCf3zrjGix^Ax@Y8vQ zfUl&R=M1`?Hl~_Y0FUawW5VU~6u^R%9i!#=-5JgNLmk2jm+@kgfVzw`^9-FcRKVUe zoqV(-k1x6JamQsin93{9Mn=cMAU$H4{C$W@a&_yq!w z&CH5KUGEe4xA&C?oh=A;2?^HE77feE=CYpsSvo#OSr^r2jpd!;=0mqH_&BoHZV8o6 z|2%Vg$0u}l3L5TUSA(Nc*ZviOi>@~wxcLgd>=XBQIXO1{=-@XkwMQ+F?YCDK?QI2p zxo_^+%Eb$>v1vwT-ygV{%wFurdr@^xwD8>T{*~KbOWJFZanG6Dw`oVMK_XKPHXA&L z%cL3|>GlXx`#2Pbf!xYvmZIo+%SnfZ>XXSrVGnIF-Bb4C^Iw;{NjX;|=CeE7TW@(b zI%q_23knJ*9Gc4*#9$JW3$QlF$D0H(9@-u53|1eO3q*!o?u}bTB6SYFU;hn|Jdt%D z!4a5g24VTQ=wY9sBV91+f1|KFuLrY8UyLNfMXBCtet1GkVcNHi&}YKvXz#7wrZ1Zo z(W1YUMR@-NClSkI^HVu00$ExYUMwr1Xk~Db)iPpgziy$k9$*`~klucXm=<}zCi<(X=qQJ()y>5k z+tNrHffiYfH|yW4XGLbxaL5%lM&~ddD0&S~`&@(40OvppoM5_ccxrv)z9S^xW#H~n zWPQR7j}*cU&0#JIrMKXh)Kq=-5bV8Fe*d+2}0hx1hGdn$jv8n$VtV?>0Q!d$U61y z8>+td(O?6y)h?tqRA@He?dO+uZ%)qbM$MBstRBzRp>N4|7RtD}0I_b3cdbslvv!p% z{CvQY?)ZW)k}KU-Y)XOMl8nL_!{-IbdfNd(iARc#sSd@VsC?9`!Af<*vPX-lryuh{ zqvgF_MR8Wvl^}CWTYR)1>`z3^x*R~p3HGsOTg2Iwel+Lgn!w)UcGGj+!K*Dns;R(0 z&9KoizX{$p2Xf1C#7xY|Q;@my@?NQwb~@LGfm+L6GjY?(xi(GIRo0g3l|DU4n=vcA ziI}LSPja=Wl!u;PTd+DQXY2G5tZS|*G;)(-|5tyO4jCt@E+Uw$@CUtniD@8uvI0ZV zJDwiwUpa57J*b~sIqLuJF)1wQVRTsdnSKy<)hYcW6p^FEsSa??Oq$*L%ra~Y+|ZQST&zm;<-@qSE_Dm8z{J_ z3rm6pD$ngYH^uJo(JeLBiOgylu6xyMx(aL~;&JWeW*QiYvp#nH{5Z6V?mW)tfC0ZV z;qO>*A$b{iQ}Y$^V&~a$nuNpf8A(fSs3qC3+dhGT2)r$M0DiJ$?pMiQ?^a}e!43bj zcolr+)oEm8i2-*RSb-nCvvqFz*%>apruO2R``Ty$#}SMOQ2M|y?>3@v@(m<006|rJ zr{2~tpc@FLdoX0{gs6s(M=8e!D$|zxHl)9Xjt(ALhZV6*)v6jct5{y;(hxQ+IOT>F zK}^*u=!cm@rN&A*G^CZJuM@QG)kz`S>wLm?QHSCG>*qT$u7LuNaZmfF-_y;RcaO=> zUFB+PoyQ-<+|+*e)DK^6g;y7?qC;vX>&9!vpxYCnus>I9aKT<*Zk;d%Qdv z|0>W}7&@D|77lPMvVzamt*9z({Y>Ug{<|xo7$A-&@n~XO1focbRB^@kNO}h&9xr~Cl_m+z^E(czTkei&TD9*CVG;bzq}OF6tP*( zd*w8qQsQZz>0)-{xzvHQu|lcDtMMil1Iq^0SKEs8J>Q<2ifr%WmNTonUSy#WtiU!r zl8(P9m8WYyx;{C{>L-+^(X#P^T+QlIRikU;TR=Fo^&kS6c`0=kpD?@YENu14of zhTD7Nme`^)4>;vi(X*3SD}m(M?N32Uh$g{Y%Y!t^NuR_$%gY4`ZG zi!c)9yG;26MrFPte1u65=A~pC9XJX#ZkoZZCL->?xJE>F2a8tU=MFlzNXfdIMCeTS z=ME3*3;h1{3^efv)HmxATpb5ZjKquOUbrjgySo!W@LZ5$y zdokL|K_D8Fjtm>`j~v;Sp8pJ0-#&8M7i7}k^ZLc64;lkH?i;R3b~JNVl;%I1FtQUA zd|IC$?u43<7m3HzV_7gY`0#(5+kHZdAX6 z1Ja?A;}pfz_hOYUOhIt5b?40Ulr zNp*XiEUHaZ#VDQXR5>Ik35ZZ?639lAOY3qa5q~eJo*)d1oQ1H|tDAPEaim=8#>+I^ z3fi`9HkW?t=L+b#)}8&zeUGV@Rd-Qycc$suRpdseQ}J|=YwlgGf^yn|f$`1N=2qbN8`O$@ouPA*W80#N_VJA z;+7->?4e5*AMoZE{|2FQxA+sTz*^;w_!mpF;!b-e>h^pLcYnO|v$4MDcC26IG;rqF zbWOddez(xHo{%X)p~JUR<8iH@4x>NiiSnHP^AH>1TEAD>gfTqY!QPdwGs!kWm7QCp zzE5R7{*yEPPdt!LTLwg=K+lv`T?~U;x8Bwm-+>q`?>bMdzHWKc&Kv@Z|X2j?cAp7ITwG@ z-SdH!zcqG7uIeWm}~UzL%hjn%IRnjb_;m>p}1?JXZKml3{S#TOFPpKz7i2MIK8`x)y$Su zADU#lc>0F1y^zWsP3xv+M#N!nwrQNQJ33b2Qd;JI1u$0{koBndL^e+(mpER{H-+nV z!@M>+$)Xo0-hAY#Lc{D$e22;Iczm6IlBNQpo361>T&m<#FkLw|mIWMB04Uc{3z<8Xq-v zqzw~|5kmBja@(&(r?-(!BvU}XOS&rflmzdYMo-OOggqGJ>=K;Sd-A40%eOSWd!^VQ z#0$(GbKtC#t*dW`wi=Ui>&sBM@<)I4)k|jhvMS+yic}god!$_5kgTUgqSxM3H^X3y z?in2yQ}-2-b-+e!i-K%j8$29nBdJLEVeH%yBH4>K=cH=I?qd4v=aX4q8EYH$9UP^7 z?KUD8*SmlyfvP@7F!AYwXK||Ddug-z%;k?CKc3HS5CgRbYB=!jYa1QTZ$DppcY;)N zDr}C^IO-lG{Q(6++Z`V~+&io^qlR4oKax&`s?%wSoeHv1c|1{zYHg|ze&jx)HGnyTlxe2d-(@k&&Zg0k^;)q2c*l}Dl+b$qQq zt~2E2QD?Sd{xNpX*PN=-s4`VrGsNBrJ)LTZbeJ0r0BWadmPAar#>)GJ^}uYU{K8+A zvD?(+mUc^{)kWu8Rbg?&jILA{IE};Z{@`KNhznqrd1+;v;nTdhPDzn_6bBaf29_e+ zgU<*o9yd+i9O2-MONMI4$Z_TcpVD5p>2A)Dl?^ZLd?|;2bV!(PhCeOSOERY#YcG(B zs>P%V#C@zr#QDPplg+ddQUkAnI15o-E)51vAb#0l@cK;cRI_5ZlB+k(d`3` zK1DYo-|PFk6$M?yO08N0_}|X9Uyhs=cRgd9zM?$h9$O#Nb>Fxv{9*60ys5)g9il$k zrbN)3cWiSkD6fqo?4u~%{h4hpA+6U=I6;v&KDbW)Iw^heeJXL)gfezCzS&Qc+cW!L zUWGkL#1vM(req`Ycrr!Y=0NxSmn$ZspizcnmVT!tq5GzzDe@*n-YI+9ttt2l6N0}E zgStZR zxj+;Fjob`vl*g~8>Ar(L`^p*X#BdHB-PwYc+A&cFC{6#zs4oqHAf6eB?|@nooJUdG zur~VouaiT3a8>2aY2$v!*%~|JqYvmHdY442Dm!}6#$mI@1Wn+*I1JtPjynQ9;J|oZ zJV@37J29}u^G?~IS+>jON!wY}^w7~rA$ffJwsl*VP*HHw!-y(#yJ9`@Kx%a8qig7E z7qirznu;JnEn1G057^mi+ehy9nv{a_NeIC;OIqX3O7W9`S;l%TvtO&QT2)jovNx+3 z+M9@e&To26Dkz`IHuvuq#Au;)8MLY**34e+uzq?+lwMUQS`@lw6x-j_wW&WzNCaB- zU7J^s`^FH@%DH5$Y>9T~2J4#Xlf0ou_s2;1IM|cY0Qb3mnDdYEvIh! z2%ESEqKRxyB-h{E_~WAro2K1AC;BpX4)VM7arTSH|EdUzLcyJhut5i@#ZjXz0#_Ps zCnQAg&3deNeZO!FXMS&>P{%CiatM>mxiG@!lIcv0UTGG_a;w$-jFjj=-K)TX9iVKb zv#_4srFf@^JiDM*%EhJ2mjKEO=J{Nf-vkYI&HkR&sN{(H>CLfDyi#Ka&J~DHE*n&2~2!Wz}2KG5-Dr9Q&l=ZGcI1q}_#SIA>7*qHd8_EbSjf*N%T6QAsblb;uP zbQCh3A6vCnEOn2B=Ee>(Xk>K|@x|c`WQuK$iuV0Bd?xGmfy3Qt_!*!DdVmC$K8s`1 zr_kfqkxM*jatMA(|B#8@o@{v1PQc~G#Wg(uZjCRA^rRj_>r|JilgoBE3mf}cJ@@oq zAH7z3xUSimr~FQfXhwiw4XI3?nbFvqVc6OQXa1nec>kXfj5HX*q~jw6*u%7CECF2~ z{zt8*ZRbpfCuV*R9_( zRN?0GpW7vYcfPTt_}zPj#1NEz|DPC_1a-e(2ao+pXQhV(4rE#A;mTlMF z-jzmGp=vteO|Xr{$%Y}hi7`1j0>7|`vhJ9>rIeUB9;j&1;)kA^vfMQMMgJ}x?d zS7pn#w&seBFrE^Vbe-tB4~D-eo>;&NAI)?miZ9}dyo!`P6F&u`v)RAB=zU>p%oEy4(oobER z`&P^ zYJpWi!x-P0OdKq;J&U@ntc_c%ZT*%|O-;>DxU$9)ZDXf#JY&8A#O~0tVRW7Q!riW) zW4b4Jwzwe=A7EXBk;In?GgkdlrL+Bf?@f{l7m{*qTz9$ic6K-Pz>ni5ORyoNMoXuU zQuMS6%2!v0*o2d3O1$XnHJ}WW-aHRfVOC^f(Rq& zjMB0%vb#^t=Ty-}H={vcYXvQ9H!>Q}x+b9}Vu)-|X%kwT++ zKW0@0{zHq)*YD+^#FwF)!txx)R`t6(k_rW{@DVN=oy1C=YE(^XBktRQ_NK5aHIC%* z=c*%ne(9D^EiXOg??^`xO!N4#pK(z}wtl@*D%|u}*p3xkJ4W0+W4F~#ec7FmD;zbP zgaWFJ9siVccL^tGP0mt5DACDOR4W*nDygact^^13pgd2bpJ`(@XbsGZKtcAzkQpYL>|#ay_ajW?;Z`!mg9|2mD16K1VIRK2@Z6wAiy2 zPj?9!r}`u*@;2o`A&D^%qa2m7r*1WTFsfdXk7cVT{mVTdvB?mVc8zecnqL}Fa=7ui zDu|CdI+9h{uasFOwiF1z9=rmIs#pm|MlqP?6^7opD1@L&cI?%`JTEWB9rx%&l-BXtMkf`_!yzt*{H||$L4nwd zir{YP$-om`!5g|NlX@X~x*;wTK3rDSN7(gde3>H09@LsdAZ`EoD?&$Fm6erdI(cCP zLS9!VWEOF+fMftV`5SLYU*OfQ>D&9xo&0H>{D|y z%}@F$Z&Tu#NUIDD(@lSYk6wHwpvU9gNu{J@1g0L}3r->6^niC~q_*?W>Z-rDKR7*O z;lY=~^^B-|8G{bncFbNzp|CNbB1jhB3y$9EMP-5cSgQEUgpJQR}3>N(Kn_~%z zCA)LpyzXXCp5!!bQjg5p;f*|40U{qsU1Q&$op)tSpKX9bdRPk%=opVCt&xjg-*(eY}1pxy8=mvjSsSi?!P0ZR?ylGn;%$o}2+EsSU3Gwb2*KQXa>c;z__Q-P_ z@5PQNJ!kD#c*Dd3&YNcabGD~b^YT%bxm4Z_4?aKoDn5Q!!F_KB#th#%=5#3EY_$Pt%VKoPWM=D%YL66hb7EBE#LT;V|8CVM*PAtK0+ zDuygg2u(4(naj4|B5$8w)O}ATA}XID6j56vbx;b_B*i$b0=WpUVwKB=%Lri)hcr^wj0+JYbT!rX5$X&WzPH+p=;`sLkj&$noeMMhiD z!oqy?@2p0fg)Efqy`3GY3;aWl`+l7Gbgp`b0hWZ5$16t{P6N#(qw0eqA3qla^X6uR z-S{?arVf2OJBiIv1M$lRnK`Jy1aG1PlCF`+{FRBV~gHs*O!SM?4%v&RAJ z;d1CE%?>B!iapxVi@>pm!DmZ5sGFnc`4a=8zJP|3-#D7w#ES4e+(!NESnjdkbAvy+ z@aSlg=~3DApzx}3i@tn?^Tcko!q(J4#I+7&2C`60Z@z-bGkeU`A_ADOceQ#0(}H*)$aij;{RuzPs7n)-47v0KND`_Y+y^mjPfk(evt0Z8~*)HZqa zgU`)&?L5MW>&}TX#V+}q*AGu;pu}o=+a=y5&L2b)@oyS+VkU=jjG-SDqUSYczam2N zq*Dxo_;bjCprTP*n_*%RRbMKLjG3?|^h$BjRIn<|C6QI0<6}nQ-o=?@Tz{WQ#!#P0 z7X{95>3hb@S{f=}0WIxCev8CgU{B^Z+d!1O{$(AUm+c%B`C8l{taSh78`-a4n$@zQ z%Vbioxq*}m<4c(6y-$)23Z35^Y+sxVp~DWWaaMo?qmAQ0qTRiboU3PWn-r)cWPz|O3UcM7ogFgZ&8f~6cH{TWDftzk-8k2zMPH?yLZ)! z3ZRO!s}4*jks6lZi<`i9k0v%mCN4TsVjt&lL-t#GM@;c!Y@e*#zLmkuMU1Y;N14|% z=q&L5hhZ0MC`EU-7r+oRQ*@8C)WZWO-QJXjulVEW812!zQ&;2O`89^6c7ahKZ~zc?$imFxkksslghHN(!o@Tc=% z(F*vps#YJ@OSFdw0LYf;k1EsY7ehfReL({Tvrb;XCr1Ig?rzjL>3JH(l8QOF!nzEH z%Q`JQe|%|y0VGACp~L&=ny;zW+-CI}=U@Qod@7e;hkfQ^Vq!?Eucw5h0<|TOZm@;r z<58~_WW$4dg)C%TTF8u&-5vmx$B_3;sL-Oa2fD7nYP`A4Z76;^w>8i@q5%QS5IB~B zRI6`UwSq640VnvRw?3!P?Il&E8WHr{9z=sPJVuRYM*cCP? zc65fBT5>;1n)3mDgBLh^Mo?jrJ-^x+ow&GPkzVoPJx)nVkzdyG>sYqxTeh}Z{>3tn ze#V@oY!bghU#Og6li=jqCETGrNNBZ|eg1v!dDF*Hn8g*PlKqQa>PLSW@9w`r9?1)I zEl^quw8Wg_b~b37%UMQ{65yURX`|^!TzvHZC5IECH8vkGgbjx)35|y1#VY7Usp`f| zGUPD}NC{rvl;P)?)PhMVvM}NPjf`j7XR3|F;QLWXz!~_nGomzOtD9^wKykE{sJGCsKqo zNs(pzGr6=o29;WIn$^RW8^Wb^|JLNBd2d@%Qj@7J(7=MO@EkWO20xse2c5RrSBIwl z(ER@dMx{JFZ}T z2<%fx1uw7xCg}rhX@vAdbX5$T+Y@hYG^;gxBG{oA2T1Qk?vY#-F2lc;#{mo0G1uMZ z@%dzx%QOk8K{vBXSNQ|3!vjTNa9{#%wx#gM9bm3HZqbLJgOj9LBgC@OirfnbTfc38 z=+vg^4a6HxxA?xP2KlDXCQ(Rjtm!$fnTkwOO!nuM-31Oih0#?B0--g8AtD@ zt))GAVzGEyPvZ?Na?%ezf4BTI04KCzQu`ClrZ#4{INSp{*?oMVV)?vmv)P|63389N zK79A!RwL8WX792?V!UN5IF@ipZ1?;5>nYzAs`1mYx6Lfo&zP#8Wk`EG9jcbNoZZ@93@IbUy88IG-jjoy zdvEU%3uu7c!JV|%iF+_+&hK)F3B=no7L{)#>%LX}NgPSf`c+Wr_0N(7Oo>!E&%ML@ z&#$*Bg-g(v(J=!*2Hn*gGBA~uoLN?RxQ|;2r=>M6_8U$YhxlBJ7+;IDOrjzsbM$bc zH@jV)b~647W!xy(1=x|c)^X`j=> z0J8X@|Lf5-Lc}AU*`8j!jhu15fU1PAW+J*+Z=a5>zY+WK+wGP-SOue|w^!Nb(%HJA zzhc$KIzXDPA#qCeH|NO4P?a93=(yZvOIDC}0xk+NHDAjgleaZdGUDiy6-;vCx|v`9 zgwx4wy*K@7FjZCi{`G?uwOGA7p{S;7YE>at=7Hb6_8Q-63nYICd%g`~Pm_+S|Ro&cPJGG+zLOZ?AhAIk$hTWIg`EEH8oyxtnd6K8yNFJeD-R7vB@8_B9Ck2 zf6JHM4Xdn`C-cH%QOwzXcg_1IunT3Pb`hmzI)0N-X zQk>1`w%B`*zKlsR2s~$+akDm22#Y(oRwsKJfgM51qoH0MuB*vf`cp4)`XSYPP^(+2 zACKH&-gF&j9ki1KeFPUiQg2SyFA1zy^?I&vrD2XDebP!P zV)s^S%@$RSF&tX?pJJ%=far2Nl zPujzPJtQH6?#Y7M0+#;xZMb*+Po5Qxu}k};)lV<={nNqOySnl^SVa)ROeVLXXT1*wF_qpPh}J$sB|eJ3Vq-l2lqc~nIX*})rh0=kjNMSt8E zGHdoV6%N|GSCl`T>S12vn_05@hxe8kp$T~oTaaDN+a;EfEdJR%=K;`LR_~7dh@u4} zUE2yS@az?9Zu8arp(_cU{d9aDVKvE#MHyVZJWgXdUGL$*(POnjAs zSEZgfx{bY+&PbWe+!)!0@!IqlUP@<`P0?}vn9iMFsqnLfxgu_(UXq@1$b_A3v>l$} zjuOVrf^EA9bjm79VhN5H?Db5luf1#4;L>l;jxlK)x6LZX{4 zuQiQ~;zct8&>s$ESCZw?Zad4 zKIPOE((K^}sIdIs6@_^jhL7B4NP;QFV#D+A2E{l?L-%qje!u4jyanqa9u=nRw%{+_ zoU8NQB{F5HT!zOKlMWA%T1n_)&ZA{UzB*@i$ceVsh;%mpecifK5fYNO{ilD_WqUnd zn?BH|CktzMI4u7=j%+DK01`zt_4g$0sthrL25eH3M2UlE+!Z?UH(NnOJ7>rxpRvRw zbejtcIi}4t8P1K)`~_Ne457DUzwl>LC%%TcYAv9H!Ew-)m z6H~VoN2g&C^>STkoK0s8XtlG=u%dI3&CqbI`|Ej1nL6>L-)_IX8~4a@zJ~*k@J9L2 z>Y1>g*6qhHXcEjeEhv#xW9&( z)VjSKRGTKLoG96S|3EOIV4KD};e)xkDLAGe5Cb&Q%eCuwN&IFYGYDi79}oUcfJS!M zwI7j3MqY+8Yxx^TL6Ui4eOz*VVfF9U9qgY|oy|_f zCx1SFp|Ga$IVv+mfCskkcwEkNP+iK32&@kao;nX*8fLH~mhMQl_kNxtyDvO8A~v@B z?&cPe6DkxPS(@Xn=r=`Y{rR9RCw?|D)1e<6e<@8xh<2?m^m)@xwnSYKsJ&ZcU*;~< z4}h@T1siV7$f=mRnmU?vgb?gnzni+!50Xr07BwmNVNkb_tbylGvvt#Sm7AWA^wV|^ zdq01d*owo&jWRX2+DLj|CbuQs?D}M5VxZ$^u$feYzq?AiO8kP~-sZ1qHbpOQ36&1n zLwG4)ZcD4}M6K+5NfB1dNH?4z3u#n{{O!`Hu)GK{y~GJoXU$RzOpHsEFeD^oI{ok- zn-D|-`M?_QVY`7;Y1GfJKHvDV1v@l8(Sqb?KhpBcXP!1A(u&7&Emii~aeR2U%h^id zl_7j9^ZxzA$mdZ(2BFVSZ1srmXIG3kFCR{uxjfg^iakv)lUsu?qC?53 z8FO=U#dI_0z1Z&zsL&Om)$dIOlPP(E{^YuN`&Efka}l)IP95XX?mPLj-(}EGB%Aei zmUNZNzH@H5)%@Viw!q;BGvV8ZB>5Xd-+9OFY{inlev)xgCC8CDnHl;S{a&$#X|7;b zQHR;VcmGVM_8zlv5Ef^<_-#7mUg8UfgZTtqUCBl>)lLBL)>$E>UC zl$UFHbFSixAPrM#R~`SFy$8`_8C&N*$Y>r_D_W|P>ICwhhF?B=SB+(6n1ID1D?Z;i zT)jJB3eN$)Y^``~y=rAY3uI=0UCe~nyA$=Fb{>JNN`aB(&Xy~UtB* zjkkj{r;NPPzA55#&OWrFbnq6N%qiGQY9+ZjHou3SU`tN)1X9bi9O5r?w<&@Ztq5m# zsn8|%V`PXJ=9Zo8+LXCVvG=AS^|bCD-v$YiUYyJitDLQAqe8mDR;XFxh*f>+tKHP? zoXmUD<$;aI$Lno;;F5GMukx`seav-Or0=yR5_Jik9;a`8&>Yvc( z6%9+IVM~jQLQ9q7J-)?lG*B|=k=36Pg559sUvyqpP{+M`63H$1J@N5=(V*4W2^R`O zPET~2^U@yQ&wmq)RgMZnd;ZY7&zeY=f1sC^yx>%~7O$QQqkJfW{h?~0_3yV~6WASt zgJlP+-Ql(k?#KQez7FrOg^u;J6w_ii9L4GwrwhK{scWN~<8u`3P0_j$x1C=dti=|j zPIpphD}YSmtLfXibX8vX)1)dBJI1Et_u{s+<>Cl}mfF?=RbqP3bG^ zqfeWb=EFd@OZey0JNY{gm(v2xf}px)f}c`Q#>G4K;D*+{<(-)DvzB)12Q!yoj3QO1 zm8?dmJ&j3hgj9|3FPVAGxTBlf@QX9ba)#;S5aqGxt=4q;)V3Ik&}Q_k6j{op3W~uKQ3-X`lLSdQw51l+;pI)uqZN8 z=yuq^Fj!(I)BiOFf#FeNMpQtV5sl#pG6>=v~y`%b=6PkndE7a3<`1a@R zblG%lq6_;>sfJBPKtw62erBzNn{cMG@1GLyGmKK@sIWf_?SFE=xe;; zQjZO?P_Di%a)xr4jx(NlC&+nmj~ULchE&>@>#p$lTTp+>*J!FQ}={@XZN^n4|rLn&O9ofV_9Mk zOOfu8>|qUj=siCOv^mT)PLW-Ep{-5Ue6i6FA{|pZ4%fjzBk6FGRE%@lkmH3%v^a*j zaK`#*wcl&tLVo~n3(Ztx@RT}s#S?kI>@v8WVI71YBrwfCo%c6O!;{`RBN~@5fAdAA zTy+%=Tzg@)s^m#qQoxfK^NihQ4lKUbYPqrwkPTQ$r3RN*aY|4Ms=lsFdGii@qBx585RP zjh62Ya=>U;EeH`Q9cqjs=^hwUgTY;`8xw>+|2Q?guzbnF^CaZ0arejQ5RQ2ArO6#V zgV;ZA3Vh?MXZcgdGV@_zY5{U9bH!4bjQeUE3*pkqRX6O&zKs0<*IBUpSLE=L7LPXQ~Ehywv+br5;wchO8gtbo(C7=6^B(Tt)2p=!OMIO6~l&4*AqCv#aD~?LN!RvWAy` z()PR+_bgTzU(xgqA~YiO=eTdZ?BHv~uNGap>He!9dMGko@w^iEu&X7E;T6QS?9H=c z+8utJ7{jUMBCwD@7AvHUr$DbRGtPI{mYZ;Zv1Aw?FTQEtZ&u-dx7V8q@l%tR5q3MJ z0z-_Ypdav_$ zmhw$?^w;axT0BJu)w)xqV;fg4)}ntMm~oO(fyFItZ|(I1U4_z-a3Ky{uAZDDIcbQ{=pr^_Yi~_Luhp<@BPTsh6s>Lo z#kvXkG|ys;?lW7>T~H=rBGGbbfHQR)TH+wd2X~QZ;l^?Um5 zMNVPr>SHjFk?H>uJV2>;-J>UK_OJdt(td_I^<@t~MmY#Sfu;hP=El#q`t5$jchc(1 z{VPzyYO8SFx=Go;dS0wmy3>UD@QReiW}1C*^A+6R-sGQUM{2ozXnz5x=G*eJ*yf&d zh4bM7y+K&)sF0|)i@s^z^|sdkPBWu4FM*nx+J7jyP)VEObBAt8p)l5GBF~Lr;=H;z z1W>_RQg*tx1VfRMR6>44%Wyp6!FCfjJT|X0FhJankT9Gl5<^A^CI(gI+fV1OSRi^5 zk3LQQ{JCrNL|!^vxJTm0E9L$mP3#2o52{&#?d|O#63WYuoAb}pQ$?yg=ePYsCS)yS zVdG|lMvaA7rhju13o!vnLqKsv`J6eoIUsL6!bem~vdv^aJGy06b5ZC&Ec$P?W!fCl zk?uq0n$hMYYi#9)wrBxM(wFC4n9W6PFz*K6)kF;owjEjioebb?~QwcUxN%^775xP z>2i=f1z!`V7UskCsN_+lsJ~G~KNI2$dkTySj95(jK9wiKJ9c!muyUH01i{B^F}i4M zbZ?nPK_2xjKkQj^KhaDWn&_2zPOHBr;BU}JM@Of#S|9-7hg1#r{fprsabIAmJpb=$x#9{$nw=j*RN)qq z#}B9TU!;VwLC*g*!ZYvGN_6-A#b3J%S{6aZtBnZ1DK#B<;%|;a53D^*+&rx0x}_pu z(TVYu{~Ze}91t!E-)cY7mOkUFQctJfdl4>+0S8mace4H?BWS<`NPIU=rU>wXceu4u z;P8dcfyvGz0w3-Gb6Cf!5f2U=xCzWVT*1t=ms3$AYH1{UDq!07e;)(Rt=zjGPdaSh zO#$le44uw&Lj!@Hp_s@B;~2&N4(Tkl%x0k>h2LG}g5@fK zC%zeNoC2cocu~2Ftwy>KdivdTv~^kiP@Z+X|G&@2Q3F54e0{^wA8z>Hru9Dm0>&s> zT4IAm9Zn@7eMM4i^?zP~(abMqwcn>3&;<^gNb@5(G@~uIN8;#Fkt*bijT2Rv_^E^R zUu~`UfhotuS1NTdN;5M&S+iGW75!V}h>Z;IT@?EuErvLf{GU}qa^J=NdC0tD`~U6Y zFqLA)QU%-Ml@igToTrJ&pXt4s$Z}n0UBY**nC5;-dMJeOBUbDHk4_LzWO|-nl&E9B znS;xei1~BEbp4b+gc7m2h{$4#NW|z+_?{w&gJ1m^3i7w$O~cwbPMk#9H?|8 zuqGi~9RD`*j)qHf{Gq zw-c+opX_f&tEFs?h-ja9Ahp;p?2T4~m;v@kd^Wv>5FjYA56zSaOD_nopAZxZN^`x^ zo!KjSu^$m>^Kr!AMp!ucetFx*Mj#`NFL)B-&2+?9Z3$qVT^T1S$}U*po-G))jF9bemfv8zOm45vd`to52!6%?g36J5iDCP{(AN7rAt8Z-mxlnc zgF4?{gb4>?<~eYlD);vzrQ;J}(MnG`ZOrgTQ$>t>AIMYH5<5j**S};Gm?!WpxHFev zyA`bbdlqce!=lO%%fR~#spfu3LU1R;?r&2 z*Y&i?y!J;?X=zO3)eYq=tmI<6xMWmnL{pQ~3=he2Z3lF=*fbQb<84wWMgyK6!Ka+? z$>#0?R^lMw+p+&xUbaZ*Ck|a^0rvnsN*BLGp8zYEXh)aHLR9vJC)%fCm0-F@!8V6> z;kvp$%~@)XLj1(XTi+dD)Fg8VyMU>S{7w%6?+XY~lL&2@@p&{Y zXVQE#v+(IE;$_Tp2K*3CMnHzh^HA$(4|NEyW~(Oo)RFuKR)O_a&Sm*3?P%NwyF!B5Vab}0yvhT2`pMC3q5YuqYO=P!CibvV$>(X^A4nGyigPh zb`u>;_Z+Bz6e|7{EC6I432G9zyyYtzumQ|hiJ!wg59wOalGA<-%fa^VgMW9?On@!T zUT&x-nwnrf2a>WOl)A!e^71i}+7nL{T`!^yw*sHvdKL^%^8Z#B)?>?Qq;HH>>jG+$ zW%!AGZSut_DZSJ~r;Cz9W6}r-qyF>#uIv)tU7u1ZVMFBl7JX?>_UE2F8m6X?m0P@7IPTTD#zQdfgUTOLTUr3kv1hDfUC4+vPCqOPu~vCiPcNR#|qHmO6P%HK{sAn#xoE z6DZt_K_DVVe`;dF1TY)u+vP`?V&&DV%s=F;RDT1+xvPKn>iZ?rVCL~bC_29AJlfnb ztlv(DoVYMck`VaJKPH7y%2r;A#tlnlDiq1D13#qe4ktaGeQcD{S$o*1(-n9A(7kzF zL+~~9`}gn0DMVx<5oi;H(jPZ)dC#{zO7vqJ^bViyaz2iCyB;+3SF;?FCY&IAvS%>8 zAj247(y2_P7%kt~eTK!gcc*ri-1yjG&4>?0HU|zz$xas}Z{U2HbG5yEBrc& zlk<$1_PDMq$0pk3~BUb^Q+YO3Ig#bO@UKD9+>yv?8dPSEmgh$TTVnxFS>d2y>#juEpOqSB1#?9ys5#C+}C5` z;S`@evqt@~Y*O)v*;sY>>2*Al1z6kY2SHw^mpIXifa+4b2=oc2lR!)O{-AyG^;5P~m{8_^19w}gzAqo!r$_986B{Zk1hYlwUBQ!i?|3VFq@y9f8ot6+Cy zS}du|gW>xcS&y@BH3;v=TZX6Lr|z6p^sV!M_#i8JE40;6-O)hVMwn<^=!uLr>7NP}bKmE^|ARQSSn42k5~M8eu?cLv(8!AP06 zZ|MyZy+W5o&Rm_XH&-Ti{5@QUP?ad&0WwBgnF~dm+>;qRUGxt;|CbDA7jAreA7pgc z!IAzwY~n&YD8A_$`;$V4TeI9SV!Ae2Cg1T+@fRoOj7h0io18i-ypRtfxA&8k7jE>r z{4FB>7JB(4_!{$)TTR(4yU1>_ahjjG~BD|kbbx7^-$`Ps`Jd%ZC4N}0df~` zF=eDMAr~j(eKn9bC4Mi9rOH+d$IS;~az%s`!yp6JpPwXg=ctFn0943AP7e8}KggZ3 z-%DS?b7vd}{06)aTlt;H9%bs`y|gNZ_3YT!Veh8)Cp)eb+sq-<-?>i@)t)V zn5p7|gs*i_H6PTEjUwJ30#a3v9lRCn9a(OY3Tt27k);o_|1RFV8e2Yh9VO@nnBPAJ zI0nqqcm`$;j>%l>B$-)kvo1o9QB zqMY+x2m#$yPOnkM9HNppt+OSGI;I+_Pdv*0;wh$pq&n9~Orxs!Bi#$<2X75O=kEtW z_fL-a%WgpS!dvoP(9^4y&gw6-&AnT_n%#9U`nG!5(ql~_%F?%Y!;~j)%A8Ez6yf<+ z6f^gUQ_z25wy7X*&KD3ZwddGK|0V8+ji+BhQ}UN9&sY|oRU`kdyw;|mY*;`N=Aqm% zdsc^w{!*Se9Ho=T6J|CgvrZ%JJ^b)EskGE0A{+^6T&V~d2?gnK zjjfFCE7sQ;zP!5YI0c(iMR}DjL!awBVDMf}v1vUsZywF%8jl?zS_vPlSL!JCpqxkT zsdk-OYVNykklGka)i?&?o6f5W96)>*^r%{Y3H5$-*uAorf~v(<-^vRH?lI>s)cz;i z2IY7oAqXd#e+-%L;T}`&!SD0^5U+i!^5L;K`k)%po|)1Ratg+c4tP^@vT~lxUZh!} z*TwOWu(gMn&}L@XRvg5|@6*$O4O~7q9d(aObgWr?`b9ls5tikyP0bpckXo~s5Vled zrM<}7MhW(v^m0x29)pUAxZ6HUDuJJK&fKE{1lFI@7H~^_K}+@dz8Qzn&ztEq&G4E; z_45lEbR#+jyOe<|h|V2>y=1=KYs6OIk?uT1 zf5J$jwg7nj@zX`n_V47$e5S??g3y&HT)YR&1+tcptJsZ0$eqImx;8PT!`gRlOuo}t z+sg;#BQtc?Ul^p{#QyL2+S}hrgXf`E0ku-$G+1n$GFJYNUfGdt`ao`c=BJ?)R(XQ- zZo$9j7lAXo_M%Trnm1+ZqeR!T>Wn9CW?Obt(j?udcu?VIuEI$zcPnR28Ko%s1?PhiB&V0REPLdgn9|Mt_=U>bJ2lT zt?{oEs2*QX_oVwVF7kqr3$x2C0gFv@=FN~}^Ua#|R%Axu{Vi9Pr0LVmETRW7ZavYL zm+V_ZVx;&}!>*ngrFlKZ<-eno(BZQBMw?o`IW|CYwm3f;4h+94DA_IRmK6=W-W<(Z zt*q*igj?~Yyk08aD>=4o(+#&_F4&y+U-PR9*F93G+I(5uEBZe)nu$Q8b9T+-?9o(R zx3JrPltyGkY+(0qnhWqQ;cMI^$hC-W!T#E@TRD2S8^_fB@a7AEpL^YI(P83QO%JLArZ3ZTn-uiDx&MzQCMvba7dYsctfa6Q!BIvoP`;6}intgNH!?QC-`2$Jl}pHk|Xh8wn#z{n4rpnp+bg z-hk@kwXH)87f?7&@esPL9BOUqkeQKrl6Fp&$?M&>?TLbQB!5Y2K_+VAyXMt0p?VIG zZ6)I2yKs(P;A8to4nq;XHD+cBb)9F}!4er$n_pH}Om3ihm49`^2rpfDuDv4nW!==|TE47Cs)zrPq3*;Sq+HFg<9OW`Wim(mj z5BR|AcveWCuCr3{L8}Oq2;DNVISx8)GFgXoej{+_>%5CPG0<_{0I9%rXZbDpkc}-@ zx2*Np@uxg@8)wgc$G+Os`Oq>;MMM8p{CL}-m`V$OvKkohfMDOYdeV3$M>3>ADM=wIl z3T#a9Y}BSzeU0{gx1ctY((es8pLmgLOB|q#GnJ^fM+;IO)_PMt^o?UWFHvbJ8)(*? zY;J5#Tku`H6Mu~~&8 z&#M+zur*GO%)L43KG*`+i}iO>e@xU~>{1PRs{k`cHVjEmXIRk?PGR3}>;5%l&a%j| zLbp^|RsBH!@09Wh!Hc3>ISS^4-qq2yK(Ylp7yo!%6!x|s&_cJ)WjQecf5;uRz@KGP zwn{Y2$G;qo4%Ll94C79VRo=f!Vk&9Gi$odzC}y5lWQ&4Kpq?37x|vBRCm*ad<)~y` zz1%^#2;Z7+SR-2+*N0X&U7u%r{4&2Tn9>~}u#QPFisozJzR76>Q{QtZKwd-17$0?Lc6` z^TQby#tntX%ulrL#DX29Y&XIR861qdZ|%UV0YC!sV7!&#=F{Ccp#lcvTEdo)lAq;@ z&vYW-3W+cOUtVB`1z4C6`kEW`8ayqOOO*frdcDq`H^&Cm7JkKC4m5ThEwXtv8+L#a zh5pg4XXvecxUMTd7|w@EXD7LO=rBhKe7Y7B+at4+zj#n(6I!3C9&BgM4XUXTSigGp zis%Lg#y(j~n(e+8GH^##84~+7x4ZjZaLpWF(QnciDWIwmuh_mN)N7EPNLX@VjyzpE zl4ZCF%{FBO+JjaGJ-#V@(?ZBe)o=}vBGNNk9#wz;7MH2*h2Nk+>Wd=+wkRd=_`^o3 zPC?iMz-X)meOC555s<$-%4q2$kN`BhP=)@q2XZF2ckW!Pufe#)z;N9#0G=J)y)hSY zSCU_0F3J6-xr3uRejegwea$$opCrn6*pv|Rn~qNJe;7;pJv{|1_0 z>oRzrqo)KyfvsuT+f7bai@?#qz&w@DY69i;we=gR8!^?QSkndXplZq%!i0O}zWzo+ z*gf0gF}q-SYE0y&;YYu{2=%zizICyaa>{HP2y(=*6n^0E@zu1Ti0gV%d~Qmi%s2(J zsCl#l$jUr9V$ z9)B^GIGFuVL>Bb(XT!|dA1QZld(7E4^^bEB>lcF>3shmjnqznH$M1HnMrUUuSD4{? z-gP_k2gM`5{W=FX4X|jZDy@WSR!hoTPPe=asyXOTr)L|eQ)O)!-p`a}DBt&}@w2kY zde5p>seKKuab)jUS^F!Q`6}n>KIAa)E|@ld!Jp9B^;WU*{PYWO-@E9%@%>AVpiY5V zEN+*adQM7uauLm|sY7?I;gCt(sq+wi;`#_n9AvOu+Z!~b08S=kP+ydPPYSoTj(1$G zE`;u9S=9NJ^{=M!HIwakC^4=#Ljl#l=LlV-j}(3US}gGf+)XeFor`6w=VuB&+l$InPZZJb=F!O8{HooX);HI(o}@? zsd^UV#I@>Xu}_Uc;^+qMj;iYF=S7K7E#97FUTaIW7%_9bsfku>dwZpR$7{_wG?dhb zFO=1q4|{C4mQhg*JS9Fg<~e&WR&S3;Y)>DkU8NXx7G8N(?Ve57S;}czABU=qxA+Yv zYQJIen&=5PJQH9f%k@1X+UnK_wp)2$mGNX@y#{x7%slt}ToO1&`+3U^{Kp`)lOz<7 zxUD$pqXu<%LR7R*)4#=T!_{cAuQo~;wdFFw>H!grs5Lct)|NU6 z?r$Ny(qhlPSS(36X}#67xol!L!$b$d7qu9|`O23hO_-pzc9I&CK;yWWeQivU>g`g_ zm)Fuhqqb>WTyyP@8a*1*w%b*{%<#6h{UO$V5mQ@yMh4Z_e=zQQzs%T+EIc*efFPG5U_G2 zX?&S6fK{eF*RpRsv6A=yNwP9a9rpYS7%5F9GH<6=V@{b1xf{7|2xivtx;(r+mRE09 zj485|DGY98;z1~Ls?XtIfELl^tvePZJ}#2dNalKp3Eb?$JgpiR@pp@cv30czr=EJB zjhBJodAs;ypgD2s`#yea8nC9H(DA<8i576&=mGEk}FUt1AJHqIs4L_v@ZzNL)O}NuNIV@xc zAZYiQIy!HV%RZP^9T=N$&WZjjV3&!-A1YeIPyCmoUe_I~q*F$W7!KsX&o3Ce!& zndF%S6%bMG%>P%~-=i1XQ83JdzD0)~#(OZK$wA%=?Kw%xN^{?(U7S?GwvB}X53qqH zEgmc`{)fa14^2Ty4lsDG^x&8=jRS+-<7one1;7yu9WT4B9xb<;oimjG_|bWoE_zMI z{hY4}ue<7WXv(Xew&ZyvV7F7IrcOd^7U_lBq+RT3AZ?o?2JR>F{z(%oCmH^2^WSi* zY9n-oGzt4U+dj5JY#6Po37c)0iMe+y!qXZL_iSjKb6fgwI3pn-w*6cljO<#p7YP2>%d z^>M)PPm<+Hf|8e#@l=*rcgSIsX(s9ugD%k?2@+C*xTz+v8ysDS@9xk};=Rh(BK|)w zz>FM%_k1%Yz{=L<&~D-XncRt4#MS`|mJzaxWbFDA6WY4gAzg}soW|GCdHwfBIe$X7 z#-8D{=XSN1jUvzTd_CL~zR&nt5k^cE6F)wQ&~cFnAWB}$JHM*qDJYkFo%z~mX*N%( zOuaB7A$MpIphFyx$?&+6 z&aR{xUssDuI{L54^EBk(|Hz4)yu7(v;OVOP=QF|<2Xdy@TaAwWHo2d~MUm~<1Kgo= zOg7mebEqLZyL_WAzipt^$zOgENl9P=6EmuxzoqAc_fR)k$OoIvG@y))b^Ri4+A%FJ z`zF4rpSrqoYrtGj>}L!Kh}xUfEl>j?#J=%LcUry-+Ib}z*aplELR%U1Tz_iBemr>j zXX!#&9j>cBEayFG%r|@jnGiLa2>}mtISig@`d&WhoX3R@BLX-s>~>_^?+H+gd((W0 zV{dlR0fce#iUwU(#XS@<{;~ulS>Cg?m>OQl2-`vyqT!^RyalId@Qi||h0DKZ|BHJo zqsz^MLk&zbbPvb@>b#ERRNg8jZ9M}IGd}1bd6exM^2iN5a}VBf%#5{j4?S1_6RvJw z`|r=wOSo_hyv7|D$ea)wxkR{()H37uXV3vxI-(|K#|?cNz%twtE%RnDv@R#dTokap zq&Q3!I{NgvcRrd7Y8N)GmeGG!X~tfJ_L!(S57meJUaQ5y z_3b1rpMW;J_Qh{!)W97OI5VGTO{FLn8}fNv>|UC;tk_9sZ0IZc*{sHs<}AQI1Ho~{ zGZ6GmY&;(y&cJk*l?9vftv!L#Na1Qw^i)jstS5^Q0U%s4RyHm?bj$>?&W0GsjzbEI zh%IY}|`b6)E1bQ_M z=xHu*{k8m82i;a9cpj1WrEn{C$4u43re+=`=G>f#8pJZuha;%-KP%JtbXY%cuNgt= zy8ru9Deps@oU-3(Ti&&_d!Ft5GlW73m1>fU+4%Z*L~vKN)8~knOwSK~8e&f{RG8O`MZjTKWoGbkgEU=yN>uek7}^*msO zo&jbwXK%1J;iqwP58)E+aIt1KP(?<>HXq@Ma}67<|5?m8`_^NKg~tEw`=xK3Yhc$$ z;8>EY@n(NSDTQhsygG@~IvVyGEC)3w;Q}F$`fhdQG#nuAxp(HEt-+Ab6W?T#Kc#0+ zbFXzU$X+JBqI7CU5GUG$`3$?!e@hB$>4xdsYJ}~(#uq1ocCvLQKv|GVuV zt2Uc#(KBCJPle`W|QN;g@zXuFt47>daW$~&@F#|EK3E? z+NsKC-w^(i*)N^|sRoO)P3B$WM(->8>|iJH=$TCYwxANBRVa~G_>An^g|L**5%T6k5?IT&b6S8sAZyniakD=jKv8C55GCa45o9s|6U5< zAjl?Ipj8d(YWbEE*j*%~l=3H--*uFaWV$uLyw*uII%sKd&)B&#+{17cETj*8#$k@4 z1OE4Rto$`{)04pJH`_5R%+EaKO9-0mESg8aG{l<3?!2urKH{bm)558;(8Buba_bUV zWW;~};)$WF@ddd=cKN)G@FZsKVuUV0Knix4P2F?=#z=H7V|k>7^N_Q@KxZbH*rZ_5n{=Ot~Trb7|!Rthnc^$@D3fZMRA;ORox z_K{}-k={^J|Bpp#nBG622|X|XHq`7xH@i4GDU3&-adt%=ZRoU&z8f|nxVZ5}k6*9` z5DdTfmm_+AX<`1paNh9UUB*8`9c;<1Bt;(;=t9o-Oe}_}@zSSj8O8v0$OurjMdOMU z)b*v+qrT)8RLf@q%wXPLelbY}^7qb%K+t!?GFn;iK^+8h_g0YzVcvS6ZXWe%Qy{pO zu-1^In|)9qTjNfc&&sOQVelEJyG_oxm);5YSLya4CTkoIA&o@2hG`ee2!rGfgw2|LHD+ZB zia&qHj=q5p`O_1e4k22P{h88u(^u=lYBjMsMofT>mf|bQ@7Stb z&^5~BZ;x-HN;p3pMgSU6|54VqdRk3OIYXQe45~8)QM*bYN_{s_#<^P2C0FqdM81gw zO+CwCEs5>$-8~1?yVU2ulFx(JFsqn(?mnN;QlvDl-7U2!q~{&K9(B?eUb7m1wu7Q$ zu$Y{YG5F8^$I)3i2lHNuJxX78yI%+9#X7=TOqB{XF!OLn82zKIeifR@tXLbueIsgSq%j5 zKlhF-pvf60N@e}nGjdUsWj*kcDC7uLm$?)J<=4#SGeWv{9NhSeJ!T+2VuEyyluj-T z=LuHZY4}^l6<>uT2}M5O5u zgNboN8u0{62G#|x&8{7vPeMi>S?zcA>0e9lcz-RGz%8&=clSS9{4+atbiQ2cpmttu zL5%LMqRj8&QeS?(-UHf|5MsGhr=9y@IJ?Fdl0E7xd^g*d*+trq$jE`k8!y*SZp1D) zKeyd(aM8rfqfO@hKof;6dyLZGOG;T$M-t$?pwHkcDhznnf2es=`JgX`hS5UQ!`-=r zys|$<7Wm45+l;1a%)E|(wDdK{-36VaeGB%?P>V!L*Th5xc5F-vh3KUB8`MkH8f$ip zEPsj}`-TUD;H^DtQPaB)kh=h3AB&Oe58-CAuy($=vOC+uxA~obGacNcSQ=$50=TR?c$$17<$x>(p!5I7(SSuJ>BqaPT+R@@t>c6 zOo8mmo+HLGS4;WjjUh1bNgq0;1tTD>Qr6SCXY5RtqofP>swbmh7(;y)XuRSF4*X;W zLyY=Y2PdgMZ>2W~>MMuQC!$_twFggPYw9M^XFVS0C+m+&UJh+@&Y|2v)u97;mRM`4 zVh$$x(VP;(;ACrqS8JJ_CSVI3?NOS3`R%uDpabIprdd1xyN3f>RyyNWI-garPBFr( zc!(_1fa^y_$B|fG?GDy5SsWf^3>~*(+U*BFu%}^Re3TKt# zTj7gTQe9QDx5rEU_-hR~X_*&V1eZfCj69qKR=$BBKKGl@CSjZEVyH$$R21eKfBwyA zBl>iD*2@JnMxlbt5C9rmA#iQ^?EOwhM7{#?TjcG9Gj0#6tm51px zx?b>b{J=@+K{REZ$=L-cj*AwY4HRVsDLtY;ziKpMnOYqhkTjwAf4F+ffGE4|eHcVQ zN$CzjLO{Ax2~m*}1f&s>ZWy|y8x)W(0hN~SlI|RVp*w~K>30u!&iVb{`Sd(~aeMEz zS6tV%)=EH8dOOPldQt#Zu2Jf43T8ndU?2%0gEr=+u>R(oW`$R26Wh}YfU@@pee)eG zz#heYAs6C@AA{jopmepbQZyUys-Vv=1$uZ9z2jSNd?lgd0lSyy4;mUzQuBy5H1SGI zQRw)OTGI#2o;hEMe>%9oEWZ3V_&$iHujHjP3^=Z*I?bLWZuk;93GMrXoSA~?AjxhGmac=8U zjPSThI9zMBo#}C{{pe9b51conXWWUk+my|!kuH84vPWlo^1 zA3hq{R+=e*XJA_|(+?=jX-;SM#NQrn6!%&4ogZB)yL;~Pe0oP!Y0iz=`(P^hq&#`V z0Y_6>Q}oN3YI+Zr@NG~%QkpYC{t!RpYu)? zVscOBJVCx1^TwuI+P9hYnfT-Ii72PbF{RP*pmDI`TB&6F9ckgdPWtD#L^QwVxnHM2 zo!9LS;msr8Qc+I!*X&+DNe=laV~-?qfc;bdcfC-k0m&A-A$R8>yR~eR_Jvudh&jBe zy50WrPv)blTa@U+fz0VH7MR@JJd^hVq~_np7ffFsw_h` z=X9fm?npRaSiE6)%ABMyK61r)E5Gp^qJqaNUlz|YADg`4MJ?u;og}Lz;9zQ4fUu3k z1V@(BWXX*$L$uMz)YQejV<#2%jYE+;Zi}$!W)ogIdNHXDeqUn5rb{|HJTL((Tt4Gm z%76~ziHDRESVu`|Yl{zAd}YN=x0*u{RpvrJXA?ADezokby5)>Ko}Z6bkUO!dJgX$( z{1ESDVYmR#CCX_dOPy1wRoS=98r_+U+#W1gB?EtSZC4K;PQGj!X^d2aA>Cz8sY zP!>YDK0u5Ta9f$vb@c0qM1TJL2wYF-&Gozh6S6a8Hu!^r=t7=nJ#&$%9<_X+{7Fge z?Xg?MhX}T^W6VIRuB6nb$G%Cl)&vrg)ozERpX)EsdUI36x4wZ;yh!WoL5`~AfBSBUqbV}LtJ2lrKujf_g?zEm(F`erQ&RwCrVhO}h zjI(T8D;&DA;Gz9@Wp;?|VBJsY}9vf4A&)N<@gfmVq4MEUL)h zTBb7R*Vp1}F+mp$wM-O$ zimyG=;VR>SB!bCi_!$q^NOTLr){f`*d+cPPd~9cWK?x@cI-K6I3$!>W@n$xjGAZc+EB$j;Ugl_a%!>}D@Wc63vz$bml#0BAQENT zMOg4%op%nrz&y2pYa&zY_1PAI4eRNMlu-zNKVNF-*jMx2hGUN*q32HFEjgu3c#A=M z>Ph19(W%Y<&NT|`J_D>WwW41`=-rTm&!o#LDiE#`{7%1?Zk*7sJgLqgxbX``osF*C z3yr6*%G$rHX3ihWf=8?7Pu!-mD1(<&*vRf zWz>OtFong}69R*;G&~ud#x9T#6|pCom+Onqw5J@hy-O|rmvc#>x^eRG`@+Kee|Dw> z7QFj_4~KVva(k;le~;hY9Wqm78T`_w?e|M)-(Z)Pd}qTtT6Vr3x*%nyV}X|tF3~_8 zv+Jh@wV%HmVlJ=DVuJ!64#fpoe$$GE#XiwA4C2;*HKh9adp8R7>!I0aK4&`1tSK(A zOHIq%+F!nSex(leFBhC?$VI_4>C-u@`ZMAsi9(TsGM<0$uw{F?JXW?B_rbJRD551G zCJ5|wF;t1Y@ek`1H7FUjMYWi@1i@3456@Ssquc}wzPpW@d~Q4>@4em$^DMdvEL}@G z?7=4Y4*A6@;zh%K;dh3}r9LC8gyv+Zz9nz!_wC^68qinVqOLR~A!Bd5zp^;=WV1aS zRp7l|ulSHlKTm34?T?*(^&~`5A}wA5HW92j2*V*ehTESHV)l41osEq^KPCrDXE;z$xa zUe-0m`O}6UCy&nQ_0X;`{uSi*i5X=-Tm6eocq{K@~`U{*GRFVysWyK&_R{ zt6ccKsAei64MLi0@!^i7bmX5W3)@#p<(c8^#06YEeF@5fD2?qGhz~T5;RU-vji|J>oy)1;UYNHNe_|U1WrpD1}=M)%0JBkS}vIgcM3p`jzOUo)85m=H-{4`|_g(gLa9MNU zZI%p$Wa_yc6Fc3Y{zFfJp9hccx)t>Cbs8CeY_=f2UIJaGr@F7~xWk@j-B|pFTbsM! zmcx$R(UdNsw(b4VG*33o#i*`9L9d5qaIXgu2?TV18{{)1bHAQs-Zc38_57$i1_PD;_{EaPRSzr?)XuJnZ&EI9If$i3QVgu+&ziA#lHrB3EN|n6NOuKtc(sk zQyAD``s$u@N&@e%M#mAH9{)+nV!=G?-C||hNCQR)BMjOux4QakEey1fGp{jh5CEM7 ziz5ZXq6ld{oPgJ45Yft1xaeG$UO2YwtT#Z*)YO#jVRJbZ{JSM*BC?o|#4k(u6$c&O zQAYDb)1KKT&2ML+5m(*l!h_IJkkm*MW_*78Gr}ZWcKZRo~F$CdcP2>(u(`K02*`HhLST;>C zAl}{_VpR%hczck<`&8hdqT~<`>Y4iqE+WkMlT4(*h3LM_KN}kKo+eXC_gZ(^qkHB( z-)*i`?LuMkvdhOjg82^E?jovr#jIc@@~*6%MWck)3t4=^ow}*NrFB1_h_k29sso;1 zjq-T>vuBZ5+!d*=yt}+ZLvkvm#S<7txtNW5WU|X78EEOLKXF9NvBASGv!Cd{JrVf7 zAtdr}v}K}YghRl4rL2P8{BhF*XEg;Lc%K;a4UIdJdfhc{XHBilrf{Sv#*H_izangc z2erh5J(5}IG|i7KW2Mb4e6cH+p0pV!dZ8AUa1Q60v>C2PR#T}=jcKUb8#hiQ+q`!< zw!2U{R~!n%+$&X2da5vI<7cgPkCaTYI$zDg+bJ#^M&Eaq|v+6 zKLo<#A(%>a};p(ouubw;hzl=Z+X)7he^0jv7vIm zPNr;jtdp*SE2>2M}HJqgG-Nx%)pqTsOg zzw<@7qCJMOP@Ra-N({B$fwai91yACXlhJXNk{@OackhXBR~GRoilCt5Q0`7$+#F3D z0-t>Bh#7<6x|hIQj2~t{z5&+>es^BHd;90ST)rr>O8?#XP(=Qe^|Ou1u?Jg_A>o7X z*SO0A^`BB(GJ$s@oLo{6qRy+M@#0El)ifm8suEeHzR)>|1U5g@oz+vqXOuKmLTHX* zRapCH`N-;>z{<*i%=aIv4l@VXtBdf&TKDnQr!QZ=^h`=Z{LL+L*)&`OH`r@l&dY8CYHT?vcgEz^4L`PGr5(9I|CTHQH{e_*dSmi0v#I|b454y96w{>+3Uh;%-&8A3E@H=x z613L<0{EqJ5o83m6PT$QL!a(=RR1U`{a zzAw?q3Y((jRp5WL00AgC@mypdG?c3;haybkOVDIca!C50%BhB~O=E5l&y~i>c}!YA zcSZXboF4`+(XWu*crDPT`n92>2e?kA3#S@4{4uEawCTh{+uHN2uedxqc4RD-7J*NM z7@nr!`J*A`vW# z`oGDOO~eh_#HgjXe9CQ$>!G>Fr+oMl#sSHt#h`PR^N@v=Kdtm6<(%*J6BA5zjk_6x!t#XSkza z)L;g{^xnL||7SG@!K44jYBCx!z|Nnby91t*Sq#wPLuSv+M)TPl5l|cP7$w+d*I|2f`y=$EGDkR#fmK3cNc= z%s*Mq#k78vGHg8JL?8lZNy!RpdhR$vzjEn+RKG0ijY$gJU)7b|JSB-pm&zREs`O<4 zDA0SX@r!HwrRdj+$4{xEMcSF^fd#EX*!uATjo!+MHC&%At(Nq)K1TgMu8PP)rL`8K z&V)gY^6#C8zxa=}{GXfzkDft@?0MEX>^W%q8+XbTdC(x+ds~d~W(vLcy1?Bps-fhP zxPGL$7^ap1`NJ{_t0h$Me=og>hx+S#xC%I1L`UNGW0B&AmQvorbc!>>jsDi7vsF|g z-?twn8wz(Uo=+Hw`cB~Mkx&h+cQua>=cZS`=u z_9r;dl!K+r^r=igzT;K%6v{3@2Aouq*sHP7o$8RxUE6~u9%1lL2n68&?KZrf0Ib8ZywcUZ5!6W$(;|C_ z(3)sC71>-968O-mTde>0ZQ+67ZgrT>$?4xJ8R*uOvIh_>RvF)9&8Eaxqd*|GTYe^VZ>l0pd-jS(y%$%~*{)hLsX zgp|GMNqJ>Z1PKYr!EG+R|NVu~O@8>`CO`ZKzXkjke#1N3ps1N5C@VJS#fK2Men?5_ z)OMg4R%iFux2O4l{Pesl)@IjVeMm)=#ikGMv`Hoav!u@MYe&FT0~Q^&bP&uyKWXT0b@WvQyk z23bwD(7U%a5_0wZl8M-u#j-TZ&tAb^x#y%W;UbxZJv`!EWSM~N8|<5yavBriB=-MsEJ7v%A<*J%ZoBb&WW$@a!u6*6d8N8%m7C7jL($uH>=7Ri5p*_O3kIsiL9)ZyR`o zoiWi`L#M?Y-=zO1cIu0#%Jv}YpXgcX?wg11o1j_n{H=UBC|L1iKK(Z#quY>GR>y39 zzwUukxw!o8KQF(s*KgVaynJdA97LKQv8YITn#oOOre5F!kT@j$Ity-E0^HZZZOJpP z!qh*UI}PWqOj~lR_;%EwceRj2==Iz<51tJz&aaMx8Zy$!i`t#!TFk1iUj7h;6cn_P zaS|b00b2$q218(M|57pyAxyh2C~Sw&k3+|y1Z8>C#bh9} zzEe7XeNerZlQguqy6Bcxuuf(o0e8mTp|x|&JiROGU;`Ew{BC^X74DBU-75LBjtKWd zAw(nxMAAAlp}Y5V`;HKY7H}(>qTfWO1(BtCr&p%S?OQ869+AT`58pz&cm7vIO0y&K z{jR>)!f4Lye8Hd#^CIb%*%{)0=O>e?4 zM!memlK2feA^NA@3D-e5Wz_O75oiOV{gU#P!4Xqh8c!x`D7`LI8$l>&A7aCNc17Nc zYnaSBW4ovn24ohhm9;0vMTF$0`LAcnp{ERx6-f5^ZO#R$*K$O48Px19%vZ?aEd)i- z7gsy*yr(M32l*lP5sPD0JP9ZYna*A@D)RLQlI6^K1Jl50{F8Js0OyX zej~u&)gX%Dy4&x_MILV8Q3Mc_Oxln9wb#6egcnZ+2Mp$FG?s%zNT>WAzjbbJDu*IB zCd4`$H|*Lj&nbq;bGgYK<>E3R%P2O_LG8IgJR1n-G88K`u35tuT;4Z0k(;*!5R?V` z)DqXl1;9~zS(5z~-Wel_WIc6zyl!+sdJ;QTV*h$|u55gyF16=AQ{2ZVt$~vuQ*3vN z=m;q75KAotGeiLprrOun*LiP|VD<*hP;ToP=#$mbNfb4F9|i%kXr2?aN0u}9 z{z1Pq=uV=zKa&W4gn|CB@y29{HBGRiuq@4PBk1hgE^m!FVZ~?5fJt_{H+Q`2x!kyN z^>I*6?#+3l$d!_`(rJK5^<8&s@1*-F2wuPyHcgoA;gV8Kd9qO#I^VNnk|4eLdJW22 z>Y>@$kG@as0vX!PA4xxZt*nRMynha6%i`DE`r#L_05=?w7y&V#E&l`B6Pq*DlY|mx zuX&;}8n5>|<~oZ^>GR_vb-LZoT}yc7ujZK=nE-`VDQP|uGQI^$0#lihA;#4}GH8;cFi=XNewX&3 z)6~*JRKv`4|KmWT-Eh!9^YPV3j&lm>iW9bZU2!bwcnD?UZjls}FqtTq8xVkm{gcj5 zslLR(c~zEr-K@odj^>!8RX?l8luO4;?`69nk0$YD%)3>W0U%3IV0Y!lHEi(`=8OL} zc&daosi-NMN*2eo0n`)Xb=y(^YL_u*=hgO3+O(qnXMyiqPIZBz_}|AX+`&7TFC7t6 z1=(`6S0B+}!)1?tnhZMx4S>hUQlI~Rp{X3336azMi+m%IpyT>)o~%8a0)Ohf z1(`4_hpN+gTDWlzH|&w`7dDcIOeQvm1~#Rp%S^2s|8-EnpbD;#28dS(n_QfUe0?Uh zN=T0DbolG&#ppv>(p+j)z) z6khkh9Y@>_`jxC~D{l}DUYLOt`usRh4eZK|{;jh{{cDpXxF*=*N4;B=*VuBNi~bYg z2$31%gGBaf%KJN)FyjMdlfkJ&sB$S4Dh$8{;9se&$BR1Fy@3RI-kc9wIKKVqDgM6o zGM>v{#plZxR-3WBpD=2vS#?m5r$XyWPF$R}ta_hR-A|Gec($%uGui{7>jI5X$SI|J z*44+Q#wc2w)ZYvHlL_#vqGboi>e1}-M7PEU3ss*T3IwT+VfZ{td4u@E_okc&Hyx#N zL*6bey%@cZ>|HnZDY^RBpr{9N;!6KXS8|H%6^(0%?87r8iMzy)c_G-TEHK{|xa18l zg8)`oYFNBel$rlZ9-xX3dU}Jrr#ei2D>;ZYk!kUFcD(eg1W+ARN^D)QUx`d7I#E!I z{k;cD=$@*7@Ze~RDU_hr_(Nk59yuE)4I3MRm7p`FY?$yk(KWpmUpEKW?W-y&d8fO( z2Z8>BpRadj1~mv}$wMqi8D4c4|8dG(+zL$jUl%%ja0B-idZH>meoFz!^$*{pdZnO+FO_y9nb;w9KrVbML1GQ%iaM6?bwHfBE-r z=r0n(x63T|9%#2OZtp?gRFF*&>x6Q@JuP;nAx*$_baLSo8hGDa`)VQ<8F4P=(*F{2 zkQ;BZ_E@lto_|#8&`#wdAH^LC#>@fdZJmuF>9cEPNyfP@n-Gw<&cDqz$HY^vHb&g#GAjL+9#&@WR3%WJPGO;izU{HD@l}E)NU_KzqHGOshG< zZru^q@->DACZ93i*Ct?FxK2rFEZ%RlwNw#nTd{6|Kyr~To#JWY6Fyn%Iipp&iAH!3 zB@!t-dPh>FBhs80pe0w4seN> z^nlkH!<86!8*MBiW76vy6nlNcS5)B1RsxD(1kixV7u8UrT2^3<#S~lceR9}#ai!P2 zYM$|L@a7N^uAlP^Q2*KMI;H17ADpzsGV^15F1+wtu&~=Ur~ofp2O*mEWp7`Nv^AB1EtTPlT$2?hg&>6iqBn)Hl9@wGVcE$g978 zmNvUQqkgi+wMH&L&E*C;x5UN}1&>)4r?9nTyCY=Wp{K^yusQs%;)NG*fu~dYKGoK6 zc57+-(aRU*g$`uFb~&_TXGmsW1P&WOx1WCbyZYp*VBux?D3S6(D2Ia<-l8CekXTU$ z-I=7|5Kr5TpR9-Pe9SZUrnfGlp#j%5P$hvIGK3S0m( zf`hrnggITYDGNk@HysZ*k(htfSY!yK^#O2$N8M!pvS32pOUnfbrBVzvw$57A+239? zP5maEKKFY)vSjv1@weh7mjzplUK`iq6zr=HJ-l|%uop3ql|SU|tR=u(wYe7K?Dxbd zbxW0cd-%nsMLgdzz`VGaa*ZZ|=D2Y9h|fCZ&*~-@EDo)2+FQE%O(oYOst)SFm9M{0O4T-nyq zY2&rbl58%jUe?YIwKay*0WwW}jvUi2qpVgG>d*tpl-au*laHz0{<&ZDk=BkcmnTC$ z|5Wjc(>=?)AaPt5F&g?wu1U-AetwiMdpduWuaySTRuJ||NQpDMNzD!dHfqL=p5h_{ z84=Ep<{c#8>4c}Y&>;mz#N*0jg+6cozzu9-BDvc{RpNqlOH=3R1fLH7*9^CN1ho1u z$MBPlMHO$(r``{9);sqEGO8jUAD5~fcHHOkAw+}F{=ngPbKG$z^<--EX?btpfi6ur z2N_%Jiog1sG0{_HYZzdbxL&+{t$`&lXZ2r(35_9xF(YHBCJVPj1oP6Tse1T-pZurN zQo5xZNBLcgH0DgkDeD|}@lJ!4;JJvnTg-!8yksT$00p2q@g%@~_ zR~qLfTT$7izRG`n;l@Yxf^23q@Jrq+&e}ON3l10Zk_e4>1o-~;iT}Hq08rUe|9Ssx zP2dZD#|zk9#Gz1$Zmf-P=uJ$l0WUe?`*pH*|LFD{7~e{c!h%Wp(6i%M8mIW>1)xFS zyg_QY}OTT`hLX@or2CErERkP6UUE*iBx$Y?7*E8FmWpX`QOclj0a zvH1}DXJ@G3eY z;stfSwYTR13ck)1xbzau|D%%ue1!F%?2h7`cP4BYwI{s;v^I*g54V^XlS_UGbR075?qV3Y?ZeG^wEV%c{$ZMT9es$cxd z-_sb$bjFeoIlr8gEhfErdY8sVD=d_T;%Fd4i7yc`gEx^Ra)1hid%;onr7Nmy63)TK zYBkja$bQvIiPTB-{Dh5QK@%V+%><6R7^W33WVV~Q#8xy>zNu1Q=qPJt;vJK59z_=Z zJd8%fN?Nv;garG_4H;>8co?llT1KgmhV2YBedPeTwK?%m{5wX8r z^3U56!h-(P_ZanlS89q&#E|=VoI$^ddwmToZ69-9={piqyBs_2=^%^-T#8RWKdLG5 zK<$K9CV#qa3G-8`a4e_zz%*eaDrz~s$Xau_9hqD)(_CSqOx2SUNLv2Uhe^gZkE}A!V8FRV?;#OQWsr zcSdm)^jo2I9@W-uAum0$?f|WnsDo(ZD?5XnJiua2yvBs^HKXoFj|8wqNLdG4#*uFq z=Kbs|<#<_{l*l3vH`3SFrSvQ4Ak!Zn`fVg}PGK9&hF z#zBsa#L!^`P>%NDs|z%fC%b?~5`VXu5f&JwKQi~e^|w_=XiaGGHwT^^VtJ|D{1GN| zK(L{*T1#1aH}kvDn4vVl3aGF$Dq82CLez-!AxWbJVfPS7$>*pj@6vs41h0dD$+NfY z5iS#_qD@-5JnX_mAA=i5gs_|s;CEPVA@h_S)b|alIZU=l=vzzgd%rGgCp@AAsSdJ@ zYjS99PuDD^&0Jq&UGP*|EtN84f(CU)z5ecX@HKAle)RRp&L@HsBM$$`!e+99+}eV# zgF?s@-83E8r~)l?Ri0@WGOO>{E_PyqUeGm67hrQjaf}x&X0COZVB`EI@|k^o=-pqu zZLa(;buj{zM4(?awW4FcfTT{>^r$%6`#%NIJ!LgDpk`fK3V6MidZT@$b)rXzui*v-5TdeSJ2{;OTQa?uI$eAqdLg)+^(nH1bH@tmPdY@N`Bd)Js}`Q> zf%LUiIzk9ZO_<&v2L^a5^|CHp+s@7ML#K^FFu2R&ZAgNBhPXZ-VAh<2oYY<3g+{hNY9*U z%1i!P{j(g9QbtcqZ#yuB5Vls=QttNQ94z*AEbjSjW;lcl++eT(IEGJuO9wR2?m>f| zjrH;SI-5C{PBiUsT0g9wpK5apLnP;0ohJxY7g2w^J$kB)r((lYB0yq?@Qs=R%CN=X z#Rhc}P)jMy?D9iD=E=YJFYayEwwUV8FikoJNl0nU^WO+O(qhPw)dw-`Vkd4q@O{aJiSrK ztHYWK2D9C)naxaI-M(_B?xR^AlrC&+rK@fBqLr+x#H6HXpi~9%_U1=OtH4A!_IB;D z_@Un`08+MLyD0t~dru?bu~R;)`ihd?kst~J3e~?V9eB_;HDp{kdy5O#ARYoBS1K}} z$vXwl#Te9u2nEo<<}lFf6y(zNZICPVStW$ymeFLYzTNnBv`KW7pyP~^Dz=M-zjfcr z+^VRWs$ieL?wePS@g~}Ef|VT9eIRR)R;IX5NyLG3G$$HkMJcI8-BRbtt-PNeOufHJ z7?|6bSy?@CVfJ>&&ybQ8f@?GN3A=&!ZEouihH6)kfn;bX5$IdmfL)9y5(5gc0A&*{yMj9;)fINOfV|ClbNB+pig0yx1vjJ@BZFdY(>bhZbK)+r6KSK zy37Y7C%R5R>tS&Q{1~sBGrGUu&d8fHF&@s7q9L8El4=Knh3&mezQ(po-*^7M1|M$% zeovbIqT>^fMUGU=17QM} z&=G4yk>OC|Srh|wKq@6@?Y@5yrC~rlBwe+=jkaK{b}oF{uvq?m9dQ zh?|~H$A!s~g!^_aUG9BeGAnp4dciPDJ|>0%`WFbqFes2bLr<{*z7T}-P8QHM!{N%_PJ>3XU+9_j&R&G2EkZ+gF{Nnsj<# z`W4}aQl4M>{0Fha2pfN-02E6*e_~=op)}X5$^z2!3`I=1ieIdJ`f~^h{uE6{n);6n zu~=h+3up!IVj50trpCJnVp~a_+1DP8Ix%XwpYYajRQozzrd%fUo*!`w&|^b4y--{G z&lherC+Q{T#o4YUQ!d~}oqsrB7CvdfSsq%}E#mlQ@iW%RLPY|ryo;m`yMoM2mLEh! z>pPZB=SoRF{HIbN`{f?ysRFaWZ+>@Lfq)mm6g=>c2O7IA=06c1%u7xBn%Ddgm~akr z>h#lQ>)Yp+xoG{U!N>l!@uJ{?ExTdtB;!2W$h*H!&wV=h2o+F2^1kla3i!j`(Oz5I zNQDFvcd}r9v6b-wN0GwH^^)%n1ci?q(BwlHk(w(F-4x|eB3u{xrR=HPh+P$Ghc~Y} z1r9&%D4Z%+j^k<)80YP~!V=nN6%7P8^0MkYX;5hbCYP`SCZ&B;0BjGiA%I^L{}&+O zQtp$Fa&&0IBSA+hURioIJv2A`W<;Np6e!}e>wc;()QAs&P+Rv477026plUTlkH-mz z5&>!Z`f(y?y0Ot)ed?eAbWDj!zr7lT=i2~Tt{sEcqFZMA?Gy7;&*6|t-mFl$z)9JS;!Hma@R+8g?jow?q@tR zr@h7q&`**ik+LMmilk=BY(U^!FPRi$YQhbGcLyee$I2k|XR)6K$Y7U2>8lbBSI$DF z6xK}*3P1=l|Jx^^GH!s-MzfHkK*{{Gp2DFO%O($LG2+5Tq@66T(ey9fEkV* zo}7sLwP^##bqy;DvL~y(`1zsE%>uLGsx>3+ZE}rD=$CLAb6fKyQpBhC}Xy|j+G{`2#%RL%JnnMGhl z;pY;b4_R00lY&_#NE&?&Xf11hTSCP+p}O|XMK8?6CIZ~FH}P3;ho{&73t+8frm~7sd9NH-1(~;{&Z$4YQ3<}-Nj>^;oM9;5QCe{x zW!-BpB5pc+*Fj`scXVhfVAQYi;sHr0fVkh^lN5q7Ue6CL0zk*&U$|eqX_x`umvh=5 z4!{uEOe-|d=(V@03rDB;adww)ShMdVUpLbe| z^%Di@*DfZd)azZJ90I;vrh(!2-Xc~xDDF*Y0etd|@!>;cqvc^Lofn9hlJW3I_5IQa z93b>YLW)ZkHKm|y>{;Kq!@Eaq?#lqhQDX_k(xRd8zh=b)GdQxS61co*Aj^)3mN0{2 zc`2g^{#MEnRC)ESpw*B!*%=qm&ALJfN{e_(9e;JTpBdXW*I7Meda3@GzkfSlewwRR zTaJlCtBWQjpT!LHYeuZKM{NOJnVjoOF9Ep8_Fow6bLkI!m>~|8Q4gSU2|D$s_AZ%h zJP&Y@ye~gBW^U%Q*6SvnsX*_FmXwfoT;|{vtiKWFyj=14YcM((acEpD-#WjO)fssv zMeO_pVk&bcSq(02o86~n*| zwgoycsEPdxIm}jplv2!ZoVs2w96hy5)<7pr(Jg2@8uz?jf~dmqSpIzP&@c<;d5^Z6 zU4OCty>{hpzyJ;3$VcG zQE>JUjsHp6c`ZOPG*gr^#G(-!n_;rc{u=C#vY3kK^#3hH{&W|0>af;ky5xxXuY!+Jlj`O0^cXN9a?{uSs&-20jk>)aIx}$P_Klg>bx~74(>u zvZ!2*ax2z9uVtPql(_arZ)`y0&NWXjDD5oXp1-5*)sA+dR_oDriStE&6Rl>TaUCmmRip|2_Vrr9s(Ci)HV+tjYBDVJo zJDM%N-dq03Q60u`lR=9Kjx1fKrL=yt%L9cVPT1B)ED#a<&g67Vp9xuY9Px|s$6F!# zCDUIH@n)7IKIjYAmoGC;tRMZO)|bA#z^?Fnr>b?GvdACKlD_FiVG$|AijM_ZQVT^N zo-Uyh0?D3FwEvXAr3Y{Stk$D5@m!>7x9w+j&fQ!{5qmXE`}IoL6;k0?+^?-t!?ZSt zX=kWuqWDnnfeZ%_#}UqjOv9<(lhl!$iG}tesg_+WD&MqhboP!+Vk@f)_5fEynqBVd zm3AvXFRUnx`xkz~vHUE_I}M91(ahZPi)C4nkTCpFtH)|(dcI*)9GR}$Fo(T3+r~`m zBl{i!Uu(m)E%6&iWr0#NYd|apuC*9*JeN+-XHnwcF8o%ZTfO51oIV4+7)oDXb%Ye9-jx611b5bJKikPxZ#cCaI#L0Yv}+u?#fl9UQu9+)Eh|;Bz#h zJriKz(l@n)mOi9OX&1Oa6#sqYrDZQFOv7i$NKN=0t9y&cgun$~<_-*br01Oc;hh(~ zsGI|!FGX;U=jQ;end1u&mu-f(&Kq08X+?edNxnnDD+I+E7AT(;OyLxf2MD|g!}!1aR(ljk zUoq(Ze0|56)5&5wqiEOw}!=&pA3 zc8tQC0rY^zoTlMVhz zGPx45(6h5iUu3^+;<`a=B10)%E-eVUlJl@{en($~fgYK`mvXsd1*Do9zLs`GAtDtV zoZ8-Rzj*o2Wvo;$trnLU@@0yX4!x0n#_{;^eW2CY^0;~oH-7yjF@T`AV{xS>iL1fh zy~#D$5zCXIT?w?h0m_k5RHYQfu%^AL;PmGn2WQVzF`fChfeDE%KsESC6sLi+F<$_< z6%a7ow=YE(yh0ByXwLkudNGVB?a$6pj7p(@&Bn=WR`UZ3t%cEIB+fjeH}p?-L9Eq0u9C6CYrHx&kD-_&RrXPTGT4QgI~ zi@hE56_Z+A6+Pz?Ndc_wxEUfy34j1+P7Yqh6%DLQ6|Lk`=hq94%Oggpi8;g&92_3i z?G{Gg=d^y7I*H`+3S>3y3dd&h7^2|TDWjbUT_RZ1E3t*S21>|p= z+(_A=albX@KB0to_+1+c0b?B*1Oz)yB#k!iHKyofBL zna3I-)6j6jEOkS>ws*^WzkP)XLr!O@!QjC(p8ta~@YHaks-QY+1;Q)KwTvTczD`UU(O!|-g< zPda-Kl8t5%L+~*xmXSWd2cW%Qb5E3AF$Rbo33D5@Jk7-GhO7Ae31JqHEHJ^d0X?UB20C^pG_`x!;F*%7Sq z$$LsJ@g%uk&oR$l_9|q6QrOp~VsYn#=?fpL$@I(`4&5X`MmIlalP;!_fQ{8zD&xED zTw*$nRptJHgP)U0t-K;QEmek>6mfRKQc?>QJt^!80;*sn@99b6N;(5J@ww${F4DBL_q2HfSYvrE`Ed8oWmk|?#-Wx<(NZ%-0# zsQ!HbJPhA}RKHHV1jKt8p}S@a=FW20{OsJ?K}j3dk}-};UdDT?d;1=j_$QcFeYHdg z5q|gj8T|lgI;9r*%lwhBzb(>M;_O48&ukXBj=C?Rv{J`}7PyZGiRCN2NGQ^gl1v`` zuh4yX(-%t(9%n;~X$QpD5DSUc^x9fHE$Iy4Dk%PDz@9#TA!-bSe|=~3T;^HvpGWWw zC(vNk2)}&0!O#3U3{LK!D_8N%QayD1g7Aa~KvA-{c%VNzn3wT0xM*GnHf!s6@HSzH zQ|b^3v2H`t&pkJ|9(IqYwTCxvgrL*az!G$aEH%eaWv|j?HpvYm;~p}$2=8h;tNsY8D=L3DfM6g(cE!%nYpH1CnPQR_Lu z7^qYpsA0%yB|E{T9utOIh#9fYUcoEXCm9UB46;bprc`a;$sM47Gx6I3DeswB>Cu`Z}C#l8vDH#6g0dF|Bup8Vq(ABe+sc0CVZxTq@uo0OWJ`%L74xo zz}~u>butg^Xy?tzZZ}mCo%M435YICWox_upgQO|1Umq5U9HTeUt>;)h^p^Pobz3nb z8@xY!-m3Cq>}LDQk+RQmsh2*xv)V1CUSUCVh+aM4u<5cF5zo26CQ8&uEBXLh;Yg9X zQ)0Tv_`Kt}`ee$YpO1rZxEgtftrEuP;q<2&q-!*^UtYhT;(uEdqGpR0ZdV;5*gH@n>Q3?aOJyA)C*;6_gYKCEZd%N@QSKNh&TDZ2Uy0E0Q)3XP0 zg#YNQ`;Z>+}0JCVhsB$}bJ$1})?UQ!(!M_eKf=PEnwn|wyt5^i(89Jad&rjC{o;=!QCnDrATp#yTjm6++7BDEgjtTo8J50 zKY#LsWReM!oU@;`*I9e*vtOInowsh$o9GOmMAfU*=by9=M&5fimGSL|*^z zr%Oh|;}|{J;|ZO(pb4_YF3gZX`o~C*cR8A|i#aM*z)E*{d-UmfN5Z&Dz{ljJ{eq*9 zXJ;`%S@1j5yO)V=QIfLgji#?MzJ9(BuU$EYvdqW;_f0l5bv2w}Jat?ManM{JBvf+= zGDkbn{KOV!8g)u@A%s!Qoo1OdX>oE2F8-r6YSj=-nd&M>^TWM^hfqynr=3L#!5qyL z6Dp>P#{?}^p_yi?|G_)e4%Z}{;v+$o88iqEtq40#3i?!aMXrEDzBowuF8|em%kqgh zHan({DJ$15GN@zXv%_?AH+^Kuw?R|ZHA2wV!tAt0rf1wHlh?DWId%+TQ-GNx1 zv7aGVtm?=ORFFe;b#)DMf3jI1J?K9bogjGb8CmStal2gRtdCn<62b8#J^8nWZVJ|o z)$KWe)M|$dp6@Xl)P=Yibjs>KNA#0Zs<8dA{gzXgC#UuUUKp-V(@-5nT6dguajJGs z%vGKEw`^1A9|orEeHQ6!ORCnwqEY%_I;>IVjL%q?9vkDBq2XRpKcdpj zCp5q4pxixM*jQik zAlf>9rSU2~bNn0hd?;GV_;;5*InkE?ux-$-&FY@}*;T5+cUbF_i6*Xk#`g;S37BX^j&8qQ9E~FBKAnYGY>aB$;Q;F>^(|WBY{Fn~F6( zKQ(L#b4d33Xlr{LaOu6EEYUKuDR=a2;Dy_W6G%{J%9|*zaQG6GX-HrYKBS=VbajOm zX;7qN54F-s^ob=a2uLL*o{IIc(-qe-5h)J#(4yeU=4ROu!;>wd3y_jp2Ghap{VK?f zP~JNwUV4(kl!|e0$Dqx!^lnn3ER?egUBZ{&8ge0?Ya?C%C4niSBM^W7*vyV+#5~y9 z`<=@LH=y~?U@XSBV2S3aO789>ENKc$JdN@cdM9B-6m#k(8Z^l=gfitd_MXR&pS_s> zw*4#ss4u&tyq3e^%nHc($8uK4$|bT2ad(kJ@&pGYPgK!i*E4fb^#SV$A)9P9S6&AI z6ZJoCOz{ICpW$|-`c^t*rS1{`o12bQPy7q!@jNd_bMh=?Eg_X9b-xsyyeo#gj%(Jh zIB+`;b)0RnElzK4j>N4=pbtF>!>U4odVcNU$KAbazZDZZ!>kj8le>R8X+KNM+DtLz z4eA~=dLQiQxT;=}b~hc4`}<7(q(9}T-FiZ(={XmeV$20Kyh|r1?$zE02Ddmpx)nqe zv^Y#kBsd0^>p@JFzCa122 zps!CS8jLijmmf9VVh=O(OM|7$lQ&T3Q>;iIId$Ijms{Z{zlNeGgp>1AQNHSWJtt0f^>oR4rV5ujegk>AfP3pqN1uY zZZWcJN3BHsU!MFAmr#j_0-X9x55G1RlHQ^53C3xV<(}~`FlN4Z_QzQ;PXCoPsZC5wv?{Srp84aXqRQS$z9+!!G+~lGn|?ED@XM6 z*%yNLjd*oQ;#$=0Y9mmKwTNaGsD1FON0tdTQ*jx3N0_WZLo{&>NcPc0%ws@}nQ(+J zg_102juO(`d^@CWvu4tUe8m9u?O|E=)Ow#T)ztvMm#}~Nm<}>b%H1g#rXmm?6w%Es z@1AZo{^VAdG9>>~uJnh=ZkcPmp`cY_Qh;pU_rF2^^8!%BjO?TQN;Ko=36(@9SZme zpcr6qGFRCd3g|?H4$?56zXeE^uf^L@KdUqKC~ythd833GrqU`LAgJTilNpIWec*B5 zlk4$@IZ8KLiQW?fBKGC3(e0MIfaE67*1Ld_kSjf?>X}W)u_tEw?Tv=VxB9%xP~eI( zflu~fe^u2}Xn0dICO`T`qpi~-y<`mmcJM^O+HjpG1OHXUwmK$rVBxJ76CL2l`aP0} zAeY&sM$mZDtj1JfCgNn*vvJw5On9yNRr^ccfkgZ*r>FJr?d6plN9UPT+(32{f4;=j z`I~#|kCjTl`Zz|LXprzKD(V1uAXc4EXv@I(njCm@G<7J5_#R{+YiJ5J-cSd~qC=9W zX8!iO&t>=6ZM>m=9aC9~BV$0jzPg$lND_NSQ&%U6%8NDoMNtgvbc{x2$4InhwNQ`y zAve-oknSK!A!Eo-Yr>B&A#_P3d=!d}4hIvSLcvzS2ep`?xe3g&QUyC?Bh_WnFgAfRW#kL2bl)&P8*&cJ-`%f>?16G)$~#twWrvJk z%ehu3cPo&FUD)y|cBt!_X=@G=zR}g3CS>@MeL{t?8+KUZF~v2tjR*4`SEvRBiQ??x zwAO@X$qlT)XlBEUt??Aw!58BV5z>r*=IEZzj3<&W_!zj5{PFpc_p8^%ec5ek-TOLi z<0Z&-S_Z-}x!ok9|Iv@h>^Q77;l(dd$6Fp-E?Ija3I98=H2@T!+w1-z7z3n;`+Kd^ zM+-t}>M$WZW7d%Dpzoz{ZB^4fyt3sT*{eu34mb4Mh1h{khVgX_N$vI^)z7QRj-Flt zr;V7$x%2yLke}%9>Gr@O{g%%7pygNfr`ILWNo~)&M~Zv&G`hd1xZ78Jhsu%bm!MARLnueEh?z?ONm6PK9l`H4lM z1GO!Yim|BJXM*p#dzji^Qcy|59YSgh(u};Iz`D5W><$E!qT=2A=7Q)deKH?m6-;%P zxbpt$p+Emltg9+-Khm>bFN(&`iB^A;^4?~R%KCqu!G#$Qw z6W$DW*#$!cRpbY)+9<8~*qyEig?bH;NuB@X+m=sw#T788jq@DJ^9hEE%SA zNiRAgcm(nMT_37eUaKq7;Y(n$tGmb$s z=oZGv(^l_XS%DlGS`7%h9S{R=7P2cTsbEWE-J@g7gHkQ$GbteTN>Q`FcVvx$H{`t^ zkK7*OWI4R=rxSK?7?8d>o4H)Pg=V|m@iT&Dh9|H$q?hqC`9FpOb{-(?h7AXTGK(Yo z`}+zV|8SFM`|DTTLbvs&3PIejnKO^Adq#D*9tC{M zzN91+R{cyGqI1O-@EN8MDJA|Sp^T4$4}Q#CYsnMvi*{a`oA|RPj+A$>BJM{HVV+fu zZErfkx4(~LmB{ClNsC6=l)|<%3g()r&4%<0c;PyW58bM51~f3}=v%6RRWUT;45KkCXKDe2PEm!YIJcFo=*nO61nh7B=ghx#0SJjagIptflx-v}-Cr_*Cq=FY*Zp z8I$BmXwEjoCSp|Nq)Y|`;CRio;4!Vqd}K@IDA&x?XoEv&S_&K5Cb*W;h9Sf7}DZ#8qR$FQwe4*U&%_HKsJDNAUGMo*L|t6&4mI7V!^@-lewpTXI#Mrg`#+o(SkU zJeJJ+y-)J4JY{s&`2q6YOVBPKfCB7_1H6C#f5es&l3(1XYJ@u;La(PG2?g%o;ooa( z^MS?)Tv8Bq))yTnaar?vzWeVyXurpp$Lkn?^Pc?r$l*(aM2mk4si5DMT{ zM?9yaXsGP#MUv19ZIBqqLPyrE>Z5Ug$NLHE<6peIy+>Z*Ja=~PaT(c6`^_f`nwG=I z-XXFn{>_aw64Kd~9pqRGmU52->>ZL7W<2Y&?y%m%wREJROE;7)7~;GU_Er@bX({dd zA5#%=T3#HwB!hFG%*kWWXkz3_3~^1?@PU@U7s3GMV(^4$dh}6f>PX_4m`~8%=Mes@ z6z#fc;*Jb*k*E2=huojpO>B?I%)uY2wE8(m+q)aSTe=PNS59zI)c^#~*10*u8ZGrdo=`m*($HKxf(O>;_<-M?e>y z$*-Ufbkf~?;=cXbGA}~H;iepm*n3&iG+t^AuSnm>t7KHlZmx#EK@x`9S4UI9mAu~G z-Jhk|{_2dhsQ*s3{}4iN_JHGV1nXOfxXEqQnWTLrAqj~ggotQO>7#dtACbN80m1nw zKBs9dm;LMOyFbaZktS&ER2x0AG~)BvJ2t4%LU$HC>$s(gaX0baxH?9-NlGcV){?aR ze208ncYHuDo6}^gNv{_7)W%&m_WqA^wXV-TEnW-O-u-O-L=lfCdx1lxMt)QYM;8z0 z1_Re3?*_RK)sVr`Zn8_Ka@P&^tb2k4@3g8@NO1jA2TG2z|oBjQpms9nec%Y!8a5{NNipi-7> zgb&oSyMzcx~Q5cnyrfz0(JY5WlaHPEhEEzuM*)>b-`%=%x7_fwb zmv1m`BrWK|DY}G(Q&2?$UOlT-{N*qQZ2ubOlo&AlsB>6CUsZ}rrNc)F?)BJ<^0J&r zVVib$>3S1#Gp4Yjkr3+g z#bm`I#k5s}A_iAlFq&W}79|mm)SPN>UxS_!XR+Zg=+6Y>Zz*qu>*qoo!f`7@mROA# zHWYSsv05OVK1+V`ucPfQ;+4Qp$$m~hZSHYW^2aWXV5pJ$6dH;OI{t;v_b4zuLk1UK zu$^tOp|1MBBQrz>6aPwlwkcex;!cp3J9)sd-@phS`f(ZYY&;Da>(L45=)L%vwK?hK z+ui7|f=mlP8+%9q6pUU?0D94UpZ*!qIVB+leysH^Eu|9G8Q#jMYvD9b%UqXA2=ZCA z=D)ssJim>r{t6z45V_H{ey*ajG!%252D037u)nlQ8;e;r0-aC=p-h*Y)y^5!l>bFI0gg8hkX ztHOkzC(RNfG1z~NwSV;fgL&c}Q)vF>m9vYUA)Gwn3J55m>ywIz(TSj|S#i|m2?*#~ z4&^}xiPMKyWAmw_!xzn|C}Z-ZRN$<;4ChEyD0RE1Txx`0+J%{Szy*r&B#T2YRzOm| z#OZ_Ec`6l01{c&PY08ZJjt+uiKO~;8bT%>QJ#*=p$FFFrB}_vyS1B=<_aNoq8svEo zQ&O8%E4${<3|~5~p%it6`9(ZL%FoI2O_qa0&3YH9cG(I&ShtS2$h^vg-tNU6<=PC~ z6oS$^bG?M^od9+0yy}_bTkY$T0XqjnA_=pdJ@prd=t8?B$yh=qA?9E~P$D zljP!H{xx|VQ#!((VetFiO2(Nr6H|Tfbn@|r3eXGcN|xY?9TFyd6m5Gof}ive{3LN{H98>_6T)A=@&JDy-LbP&nn zwC2dx>9zO#ps=NrHp`fgqXb^+6?0LL;CorPo6{6F>(FZQ%<0V(4zzMmSsSeL8+P3E1m|6!R66YjIC*1Wbbveg z!K^QDg^#tRZ^6SsM+Ir%wrFBrkt2k+2R~Mm_q4Y2q^gcKxLUA&)oCB4?pWEa=U(&E z;Kz#WNq(y7Z5vGscQC~mL!v7cakWb`toq0&?y%y@2RpO7uP7S2ku}hWlw_r-#KZsU zFG@6u3`tS;)r{c>Qu77FU~)x;`?*fd0qbvJm-QH=z4t;KqfvI;efO|e$;ol?AK2JM z@Ii(;C>u8;Rvi$DRgWHWol3a{jODY9rK#>G%j~a=yfgDTG|BQf2+)$Dq1<^&2D06R zP!Tit<=W&)YTRUdpH9Af^LZhLgHD^HD?}>1HNhR##4e6;Sl*U^O9SjJqZ5W#!(u!B zn89cb;w#eR@zzQNuQk;3Iie*wnLU?zHb^=%5m6#_BH=_(XHzG5)~Ci-GdX}w=ur_X z%Z&}@bLaw<7dnH*@|oi0so4?cf@@*VGMEbEDJ=EjTD{XkFHxush)A9YIq@Ll1bHg7 zPr6Aj$z-quX=94~{OVsR!zG}n@6|v4gdH*!6XY`$I}lH#3|IpRK8yX!RpSxNW>0ez z5R#i5jIjuBiPQKW`R+dx77Qn9EP`@IsTpy`M!^F*u>v(hvd|Hsr+)|A}Vn`&g(u$4USVm6hz4Hk7A4Y1bwJL zU$DBYKu<$6G^!fM3-qXFUR#u=$?4Vju2PHyEA6C8%zPeBvEtCa6RAA|`oai1tvT?V zax8KyLl<1;X`s$zM%1UL=~pcjp-Y6ii3v*N{VfGQCm(_FbJp{R1HRJGc6dY}yj??_ zE(j4Ton|&?Kb_|rM4Yp2V}TV%CJirwAJMl@-IbJBc?vrmsavBdMn49bswJgaCx6t=p25^& z&L{knIty%O=K7&cm$uXt7Z-~0gRP@so|nXqam2<;i>U{(cQ4; zUfFB9K`AUzh+{1I)BIdm7?+s9L%FLS1B-}T+&Mg>MwV(&gTeSI(*IP@T@ zJ6j1A(4+b5L7pYODD8!vj-+t#z59c`{H;%X%4Iz{Mt;2-g6r)ocfD|q(jYi67+L&u z`QG`R#Q+3&++0_WsE_78?xU80wvW7sxX*7c(PT(s#hp<|8uv(2q8=%kU#RFDc1o^B z4j^ms!jYHw0SkNVA7YFbliu43C&rTWYrQ#5v%B$m_n%V2VQy|N^e}RG&jsU7S|d7pgdPZ@OEc0Ww7zjm== z9gvV{a69XrjXnTYvA0G2R(B)x0K(WMc|Qlct-fs2i|(t6-0LZ1Tygkt=j0hb^mJ}7 zDYl;I=2;z!oj#|Wn8h@{oila6{(axJHGb|- zrY1vpvHpwTGG#@8h<{F=CoWAU)_koQbeHWkno?nnw_zNJPA#Hri4~@*1O&ukcXbb| zuUE%)*$;Tn3Gj_T81^iJfUr)Qpp@pKVvP=OJ z0rOim0I9c9(q|%7_-X&qJ)7 zk4k*+WjF&lMT4+bB3-HR`Ir#nY#KTy*C0XpV^)7LjQ$thIiqNsNz8wKfNymbbwQ6s zywyz@5+AUD|78~t7J|PX@Jt@_%M-_o8*&Ps3&yx4OLAvV12rE_ptH;dy~VLCu=Lu zh4tslaPiA&vZLwtjF@89{Fy+iex47bsQ*=>_qrF^+T5XOOU|%p_uoQ;%kWAhu(S5_ z_1&|-Phn$GH|n@*Wl%`L7J8lK6$SAk;>t`*?n_bux!D-DKJBCO+I&bTQIEGK1U zev6r{A7;utjCyDB;#8Dz4sp=S>L#{BO@nd6o_+RxbcbjSeCK^GuFz@}#rK1QTCqkQ zVJq|yQYGLmu^He4;U#d^;FQ&)#hJQ0GM8!6^)T5c2R}jT1r{9qr(I)uDAjoC9N{d7 zy<+<`Ge*TO_Opjq*8PhswQU8d?+a$Hui zYOzqngPc2*vz<>467l|j`>U(Ih%&X){~+mto7ZA_Iws)$tr7QRL{M2A9UT7GxkuG~ z^u}jQwA@qZ%x>r3c0d5xQ^nXV5p#s2 z9lifGWd{5^#$MzzzNPUR-&;%RaR91#(7sSQU7rrd%}=B~Pn%MDecudm)Cl0|^%gbn zJy#b?AZ>pkj*RW0Z5X?`z57vBte3~%Q#qe9Bn(4DpAEq6idv?axM@&Z$`#a@s zBXyEzXjZJRVt{@^`v6U57q5o`1M8nemK=&W(|M!?$I^Un=VsG#|8JRla54pyy z|48un@fl$y?X!M69s*Jl{H~sUAgz7AAwsI=KXXR?#zxy!@zXeKi)q{dLeHH7&mlD% zRZmsd+oSg|Ghi#%bvbd?f()=6@OP$krnnvAh>STq1YQL3jj1b?NO37@WljCtTx0)z zLxbzg9{ZIuZNts0OUC5 znnJNL&FrJj`$Z_yYZN)t+*VI~-zy5M2QH3G(F;?^xeH_>rLeuP+~@Z4RMEV64F_S5 zFU;YB%2?CQhpUpDY=DkO)8v86#^p3=J$o4L#WW=vxe{y_>h|*J6Fu(RydU#f8(*3Q z{-P{i=x3BG>@`|G=!JR4?p2yARaBP%lw55$)3wHiiUxOne2Kk7+*2}kUiRMdAO<_8 zRCF0%%Gdj2KyIXjMO>NP`XI*5WwW+hms;`@Swr@24Vj7J+iIQ?&@pA^@(r^Q`4PYj-m+fxrmd(qx6sW@?Wav7BlaHZ~*(ak!-bh0Mr2-FNNlsJVKtn*w2B*9Mkvzu#4KKJ;QdgNI525Wq(=3Yi0yJj0RS*K1J zziiWVk%2aRXIjWp&bBiO7oms{1l&*k=lD_$)^fC-kDz>i zrC2{cYs=wJkOKCG9Tp{6VXrnGbThBtR1uw!fNkxsD#}!+r*FwpA7q7`)mo6@N<2Fc$~OLLT^L8zl+2oo-{630C@`5t!dBBvhQEP&uzz| zWU}Y8o4SB8x|+9{)Rz-$qiMzNH;(R`BK>30b%E4t{moaaGv6s_i5kNu*1kSlB5`5a zH8XjH4TmitUaf}Zmo1*ZqfAthl{d-`zpO(gy`1nr9J8sQiTAMPP&!2*2fS^~{-Z*Sc$-mmlf1b)bmASb7m-3;~70-0fP8O@I zUYswVfz^idK-gxypQ$(-;fO4!ceQ(N1VItKJH0?2ubcpa+J`@tbe5l)8_Bcf3|@+@ z=XmEp4U=90o45BtZO8R^DDgDn-y9bw%Y6|O8%RfWpO|>cZudu$e&+=J@*zAWIy&Ea z#M*owx^Hp_TGe^~-WBGia89t1REXJ=FI3ktP!HTX$4`IPF8MfiIS^>=E4>^m)_a1?s#yI*Q z`(EDDVNUyYUN|H3PdMqmU{Ab64T9x(=<3oi-!C}PMA-EjMI03rt*XlE8O=@UhAhAr&0TaI1)h$S>nDw;{W`M|4kKXO8aTPtBi@}cMzxIt@d~9l|GKf!;w!S zewU?dB^C(F9)BS4a<9WS3vtZlLdx>ELg&}hfVI0+f`EA8wR;v{h*ggz)v|DPUeCN8BWC$0lA$dGvZXku2C;Tou7ae9C5)aGKGkN|c#)2R8~!t>`qaIl`@-Q-)7kd6nq3$`US zh9JA_(D{k3trhC-iE!Abt1@Pc&;zafkM%=3EAFV(S}9ON!PJ)f^Dd%DcSG61Pp2_L z%rC0!#>Qy*k{EI>O={H1@+Qw(3gIx0JczhRIdJVkcTPXak%nai0?b&t3A7O*2FCw} za39BPdEG|cIeCn}l%pw)XVcHGmWlQOPj=%mPgKNY+HTaAj+Dd7(@$Kb>uw7AS&)Ui zDsbvaPwGwjXG&0UoYFdCvl>cx7RvH;+JDK*-D+T-!^-oXr%kl=Cy0dR9yxh(C$%;F zZTrNKcJe-+6@BQ$l;Bu7RhP`uK!Mf4&jHDyc z_N8geIZY%v@{gNtB|-*Q@;d3p6v=GPI?2Z5$0sz>Lb5K4@Qxne6Oi|_aVK7jfS~2; ziC6AaL>CcX-6IrKi^!f|=Pi!YUMA?paNO-zA(yJpv^C#t0m0=n=b7Or#PB_tLYYTm zFv83pi)7meVz~p|WTIaNWhO%8f*q=AiSEW%4Yt+U4bP~9L<_5n|YtX-3^34gy zm1MIoz}>G#YCtnwL-%%wF%$&?u~nyK-N~`pOO2&7$DH+ zkXawF^Ww#n#-O1;01*F5sM3`6J4V{e7+|PwEK^um^+ob!X}!515NSBif`9aO`rUf! z@qixyka?DEgK!1&t)aDuv$sfYR`-E#_)mLcM*ZWck?CvMBY%8)px|%;%vOaxkyCgmj9PiLurKRy} zJK3GSc+oc=d1JoP_v*Ao+9O#7CPy6E=^OKl4v}DNKjnb;A_zr90S%U zd#X|{nO#K5$e*m!`3J0Fi@^}j$bVDW_Y4@`Cj2(#SZvqBlyb$uovI5WqsOTJYbV3l<+{0;umJ3(nGf3>1*(R-49BJ0)wC-!J; zf}(qRS^IYV*ovXcf89xe&}gD9H#6AQsg7g#YvgOXZL%8~c~W*ut)*?8WnmvuAsQUC zUg%u2C8cunMyc{_Q_TL`j;ZJ0Wi+v4tzMUp*OGPOjM8kiWdESR^?y)6E6fc4m-wYV z28lZi1qQV*9+NKWX2Gqn>&~}}0}dUI2QC0%3t=l_rUGogx^#-x-M>&+2?PwUg}|x{ zFXlw8etDu~$-AyIvwkweTANuNm>D4W_qFdSrjGY;*gF8eusp-nkjc_c zV>ZER0e;w8D^7z4j>DrC(g0W$E2wJzL4O3zGE>fN%~ih)=ocsIG#}f~&-7^Ru}fm* z`MhwJ=(0`X@RUXx+v0;Iv%hVr8LvZmHqd+rg?XAQF<1K&pKNC1i6fFGePaP3@FE+* z1JG8K()t;+4^nk#{t)TC)FVR{STW}Rf|iNDTIwv#^VQ8bCTr>b+G_0p-&6j*#g8(V zkCe^v(Hs4NMH6RR=eJwF9uB0@r*+cpx8eYx8&->V)40Xf(dl;8Rb22Fb};Ht$VfOF zbV;&M6y)Ed4zPEW0-o&{StvbG6cagOFgovEg;f;#jF}+rPI6)l z;CrCo8qiqy1*FI!JDT!fcq8cG5QAHujzY2XBW@!BHVebq`e7VoND3 ze43&j;T3pexKHB>2!fsNd{q*8?6dcI1R2S5uW+#F@*yOAE@+?cHna+^S`2SA;*`gY zEz%~8EtyOL0|t()@UyJC=Z%aE-FYwH|D183f)F^VesoGNH9pc*Bw{p9^=p`a6-#** zvOUylg;T#)m`pEx4Lb=#EgrjJaf}gLS>{@FuEh`r4{Daqcz)uE{-uB!4mV_?i(jEp z^p$>=5<0goW<@>RxRnt+$WRnYZB&w6>)a5!RWu+3eqZYq`ZfatX(=+rb8)|+TWe|V z35IAg>9HzdXQ|k2I*b*MYXzo3`$ztSe!^PfSW9FDBxFInrAaSct=0ofi-LNpqzJp#Yk9mM&8 zN>t5F@y3+D!6i&~4+Zv2PH!CxaEre-P^_J zhuC4#{$5~tglYDW ze#J`2={lm;^}1fz$oJs=x!oMVc#PF~Yv{By2r^y;3O7k?x^L*G6%93#BUOfm^uGeu zJo6f?KML#mdY&&&QmrjilJPBUX}Cx7Wet~#dcp@?9;+s^0MFiwoJ5j(I<7)HAKOJ^ zPX$nim1z6!G@`bM8cKT!>8g?963-tsg)!!;sXze?xW%x@7(79EPd4E0WX+X0NzxpS7+> z#7z6H6ZjX;;Bkj>6$qMV33`3p`YKZkQHeJ#P{7HAsyEro9^m)e-YV?LD5 zjpEJAb~J|sAZWm2IldfT17ue>jXPR;TT9;!2;g*CeR^VNuuM<-O!C#A;Wb>UR&^h* zCYjQbtS}Qqc_loDp01bDu1;4tlN))}2^5(+ddiO$N*?N)x=Ess|AE#i(<4&?Rs1QI zEQOtJtN-g#Q%EQ|ITwOx5@k7VGNd79yPC}udg7Kuq~_X_(qdXF4E(vUXPS+Jf%h~l zoa$f5^}(hb;I=_5gxW+sCt5GWFFs7f(S{{G+RdgES`92v&qG!>3~{oizB`>fslX{L&4nMJHIzn z(AwPGp(V&@=;BGze^)urpeYYS6Q5DT3;Tm8LBe^RFdi15ywR3ts&+j z4O>26B*%{Cy*;`IEUIFZfLB<}Zw!{;A6%Dn@!mQ8ew!85cMmNfwG01DGq+o-0A){ zvy|rL8|5E}hL8p|{I|rwkEFtgaxtC8Ral2W`~F z89`351{1d%d4(roR#6#?P6b%^_ic* z*78j?-mPgl<*>eS1-%61a*Sg|*)|Qzqy{}8_mni%fN%|FjoSRcbwqWAzEV!Vt@*?- zG0hOQpr5e-)*cv)DZVp9IQmL4`#tuA!~~2$cjj8x2eWgB7$V5G#tK`s`g7PuWUB6u zsXrMJQl-{9+We~;(=(0oAquHAN!D(aWBrWQcJ_;KCsMcP*LK$z$KhU2|=y467WHtA6g z#AFXF0WiriqG9Eu%p~EJ0$LVgD#OYxGQa=fN?P~W_*z*lo68G#Psm+8;wK#5X;&1R zCqq=fpi)WHiSAHN(|Up4qO2Y${M<&%R0>oPp63zxFGiH-HdwfNU zYm%@o}EY_=ZuGzXf7DNYcl%TPbXp z(l@^tL>A+wV@1hiqTe`=e>7h90-+Zp}*-CHMfLwe=q33a3SRBU6>*Uo?b%?-{e(<|C&uvW)=2%0!(~MTcSrG zD!sG6En^*M@Dg&d12KrHE-(jz<@IcWa{;FctrXdC**?!1{(ss)$t+Vf<$6b=Z^we2 zuY2deM=ChP`N}`)bFKmb*He?@$D_C#$s5_6fjsvgz(OT1z=@sr*|)o4!=pFFxvCBy zh3xkgbEmy#-mZjGqleKn5R|}zf%81Pcj9G~)lz{G%#Q==RLB^Z;c}^*_*th~NTVYD znCnYya+CoA2wg2kCfyxl&r^B&Zf?+oxj}FklGKh$hzIfj z4HWp5(IV5CFT=JrzfLBd36{Q8v&z(pre6x!trASyB#M0yTlw@`o-f_`TZJ`UYLM*0 zk(kF(N)z-Tzv>~)%xR2ikIlh^V@gQm zLo4(x%|XeBAT+>4!?Md~O94B_^kf@153;w&ysWr>SQRBPDK@x~1`TEUP5VvzoaZE2 zO}*yc2f*ury6X-*K(j-cKO*pxVP{Qj(gL3E>u(pTW5F_C2xm8(l{nX)R@p=;c_);Q zwV6LP8{mvQ<~e*sLkKmcye;AVP%6YJRX4rt*DUTmL|P~w4v98kH_20&8Z(4pXew=X|AFI2z=_E z|N2^`wQTQDw@sgzJNi*nASYkvgUk4z^J$-K$oI-Rw!HkGe4h>%j;3>ih|YL^jyQd? zKt}%k*c|E?=ysByC2rG;xas!+1F+HSW$bcodJpniC2e)G>HzetBD|m1MG7*}sMfL^ zaVHPh^XWQNJKj65H@zZ@q4O{ISy?)AS~q2n*93IP(_lL&IZBd`e`_dHD8ai7FfbuV z_I2QbC*I03H(8Yn0Fj!dW8rSXWeJ(bT@aFzDll5KHPhYc44%gjqHkZ>EV`-Z7RAUX zjy{*IMyM}if0sj$p{&vk`lJDh8awDNrlWLciVJpfp3?dgeUXeYTUQ0fe11mMT_PQv zMt50nfAFUEjo%2Xss5DJw&|Pm-80CMAJqVUwqdoVnFR#M+jsoD)}?J3(p92mPfULi z9tvyYXUFpaG8>tV30=mWcOt_I4*ZB+M@wv80Q`Uu+RHY*fN(JR^{9)7WJ_uGEWVwC z%o4JZ;%dtk7^)GxDFG{ut!IRXIn0TE&T#haUgsx=TgJ|?hOdSn0D;dpTbDywn{h-r zqP-)KUoa$HTj$GsY1+#6l^S{(corco8DXKyqpXMRX#d9TESsKwC{|ABp(e%Ti);l|E z!L$2FCXx~TXR^&}FQNL9mKv~aK^szYJSWl)-cnr&eMehEqA(Qkg5TG}T54y5p&L4F z4M`^QVLBg~@jgMV5PclXZT7yv;D!G|qDp&JzxI@>0LtIDSQce3nOgV3(eKAigBZ82!%aOqWs!!^|R9 zUe;-&uDtQj48+BQ@3*VXa4LcBbKV6@txui4y7mPd(p(YWv5Rs0P#e{bHSHVGAyaZg zcaY4b?hB(HG242JsCWs{5c=x}W9082^f#jOOv~p6?kwczQ|D*&j7@60=+*rSC6}VW zjnV$K%S$vAT)kk(PUSn_uykHc+T)x!rhmwZ6nMNB?a0qZg0I_KAnCk21SP5B)7yzG}3rI~8n#p6ftmdD2(Y7hnBq zj)8N5%Ol#2{ONr(Gp#Z3O)0GAo%wa=3u%T&P;+bn!VC1vUVw9NU{T105oYJZ2J7xM zfqzoS0jvkWiZVCxI$Y<4k>F+DA8M-8e(kSdImEbnz}=bJqOqBi_G`+hrAmwnk z$1|GSfGP6G{~Je$$MpH$_c_G|yqeeI8sO1Q3tc(o23;kW-M7}2$nkw^T;<$Rquvvn zV-WKh>r>Hpqz`FG*8cnmNOankfO1LYX6^J^ys<2CRXGuK=;BPEd^^9Ti=PJj<7GJG zfz5NKRrN5{2IFfy$o~J)^o?Clig&yPIgV2Y}@v8=KK3U zFZQeM)90MM?uF}G*IpZI@8N`Q_~6qmURwXnPxEd=vj5Gb3PfAl%`M`|mqWGN@5By@ zox0?Q>SBGZrnA)XP39%*wTNh`HmS5%+X_7303;-ewRr>RL?-3e#aJ6wSpi)*D!w5f zDDn~xz#CqFkU_rR{&X5S#FDpemHhzkJ%!R5Xm`ciQ*!9eH(AR$+E`F0>TDgR{OeYm z@0KyLDl{b323omP;p=C^Jfvmh#t`_qrY6F7y zMn+r-P9aHURj(Q;erd6sh9AxI9b`O1mHOW0Mc{?p1ye2dzl)u)KvhyYx@cFIxH&)7 z6W{bP{cRiNtPN&+smdbrj;vZ!NCCiQo^x6Iu;?8lMJ#gU@6QOF+_1NcQCtHZ{@^kJ(Av*eVcU3{x0j3`? zZ*j-iL02tJZUwlZ&P?Jt%OH1gW_+D(#3Q^tgS*Ub-}?T$I{GqaCm3pR^R@r2yhq@t ztcP_OKqUd~OXwlc2chhz?Fwe=DoBUJ-w^Jr8)C6gC%GgVw1h5n}*yzCmFfh~d}agW#UCT99B)kvtMU~0QT#PFqvZl%-V3e?Av z89NPCsOK1~>*^!Wp!EXy`Uf3ArO)>?^nCWYK7Z=b>2eijY>4?`|k8hpSmJ9eW zJ9~Mh;HqnB4e-CS_snCln(a=jKgVV$Ps6!b6s&_}s(DM_P(_s0$kRZ&co%cDQMhcGXRL{7-$_q+8s0rwyBNuj&CPpLcKj z%z$qf+|VS)=em#%C|fOKn6OofLooQkWDH$}G&= z1_qef30TkFz2~YL!4?EXzwAyW4WbbwdB3VrYfW?ZvAMyK`razl2_?^?(ggdVP3UuA z`%K zXYTgRVo4(xw~y;ux)0qi-z9Iw}2OK?>yYEPGuT2Vz5L%MtZb@9Oz#=CVnI+L!i8< zMaNmzo^-X-e>;I2tNji&vnrUr(UDzh^%=ost%teo6) z9sNjnIn)9OBJVRHr<pCbk>;ya`-|>Hs2o-_M;3T^_35x}Fb@6l5k0Cm5K%0_OccoQnqL zvp8D%_}0j7W1&r}KJhNXx4N=JH=teyx4!06TgpC9%k`gjndXy!3BJDH`zndiMpvkX z`f;LbV7Cjf@{T*^J>cnIMBqSU8=>D6HGlbQn@w^()ST)!MkB3&RXzG3gMwa&5vx$Z z)R)uj*%R1v%KMd;LWV6eFwoq_$vaj|e91%$|22Xp9wysUvC;R)+g{$+KTpX`pI?Ei z3{o}FR-0SFn&stu^1c@R>dqR0=~SgfpPL}0{QGoDsNNC=e=<^tZp`<%ZT;b+5M-CO%%=F?3Bp5a{GMyyxY zOP1pfpwV*l%8r>`PHiYLu?>r@5#3L_aNTd{$?GU`ONNw-!-hRc;d&G49pman^#lFh zwM3==Qq_&;2h{e9|MUTr?N?>_Cu%$Q)tj&xQJ{NY?a9VpK0d0mYv689QN0YNeo(0F zayh;slm&jep^`;+i~wHL98HVOQki=8R!;$Nfqo=;feS}b7?z4lIfM$0Cp&vy`-4(P z0ieALj)7cScb5aFd)C7X5@DG84c@ya;3_|f3FDKP%Cc(T%1i+>7FO6P z!xZS&_;nDiY@H`n^BLKC*D>AQV&ZEI(Y4p%c^hl>Of zRry)8vz3VDzZd>~MAtL1akR-+82|wqUG)k6Jhqy5BLlUV_ox`b*&Q~DgBYFQE{)T| zXE2@bUY)pEi6V+h!dfsL^esFS_2BI>&=0TjRg>fXz-a63MdwA3V9D?SBR@dhYg*3t zdD_Z9_K#SOd!qjp)Mw0WiwfWYYwNJV(O{fv>)F|^_C>E_?Q+#)x$rF|_~esbfb$-D zq(rGyU?W)51f4ZF1NA`AV5<>2z%g@OJKD=<7obi%G&4gS)!qqX%FiYLlaVr4yo5Q)$`!x zLbbluD!taEwpQy5;HKWb4#3`@-~zjX3<)Uc7o_d)Hu~#={0{7mb~KCvAZAV7WV2>M zlzJ}J_`m*OF|V_T!Je~XVzQtV#WE@;Q_V4SRNDI*Hb>@u63*H68tkZ8GyF)EL7wTU z&)e!g31AI~urQeLqNvT7xkBs?6{-+oEp2>${+8{##?y7_8gJXa<+SqjZFm!sYz0{A{N|+!=lV3&A17n?|JKCb+$RT2sku^xRvs^qH!_RVEP`2k(|r@MwR5?{7{h@iY6@p#hh z4u|!3nR-ie>=;H}y8F@V$%KFTT}4q#3u}#N9kA@c{(oW5NnVYvkV|&Q0o+YY%u?m3 zd$DDcZ#?QBu&l3h2c~wVd!QHg!u5Fb1is}WDcau62EJo&b=>m7?a#u~b0n?#rQyNj zpI;tLT(zaO2AngUwfy4<=4(H!YF?+8(3bn+K48F|cdODWxu<#4t6glH6%38*vjk&q zNEr&lEeb1>xwFirl2f>ol08<&%hdt|zUZEr9?SjF#Zipjsy4ebm5d(BBX*mUV*;O# zrLwx=@A@CvTJK)3x{}VAdTK67A?fP8PS`DkOU>3ctnh1m<&tBBd9qv#TtDVFtOTT! zKn*oTs=_Gf)${ABpo8!G0qzGyvSw%00BVv_>ECL$z0>a_1V8IrUr^ zvKsV7nNZ6?hZ#F)`Y_E=XLqgN1Y0X)SWe$`W<#Y*QxW3JGiM+jjSR|^MvVGQ?#b;!y-{a(P zfejme1UBI`r|x2cQ2B{5hAHCZNWzyN&^i2Tfd%X1c*XC1iYSXy_m=JI3x5gl(NRLi z$b=yTA5j!EKcsoN1c!!jAMW{ummYAYx+qZJ;_wD6*%AYN_Ncs$v^L{&cVg>>jm=Of zWIL^`O0-!vwHdrOW7IyiP~HnkWjh_HkZI)$1fnr@>%!t^LLLh^fq=CVL9HEZ{XWz2 zrdN$HV{ysH&oh4DXQQA^Hs5q-Z0qK=2T;{GZT7Zka?hRwr0k0Q>vDD!(NOq)os^oQ zt*TN)Ai<+*z(nv!%V6F36Txy8cPam{`(LJPpC9IUhTLn z)OGRqi<4b-QAv=;GRb)wuhZ!3=4>#qb<@eHIh{YC_KcSdi(jZuT?7{qCMlDl%#4#? zN}=5ED2zzV>$StwU=M|cwPp!?*x3Urtve+ft+(K6h4N#=Z(Rin)+MU9Ye1rf*GwqG zF(%S9ps;ZWECOc_Cl!fQMp^y>BJMv|eqIA}(^Qgd=2)bO!~dnKSWz+%f`2v({w|50 zH|){STT?dStu3{mca;VGFD&9%$riu84mt0S$u>T1U>y%^pXcQb^>n>9&cpI@0Zz{R z9y6zZAyJ3!P@8KrRn_UnVZHQP35@~=HQEe>^QUjP(X^{4^t{|hD!Wur8^%f&jem8y z&_0iOJ@300d?yNRK;Bx}8tXB5g-Gz-Z;NPw(j?eV34AIqeam$Wc(oGR>o)Qt%JbVB znJ7HmA#2)>^Hn-}Jo>!qy7z3Fos?RUKg+*cM1Io}oIC}jM71+We^2?a5k$vaI|a@-1?xowvv{aKcY3AVoo!U+DC;zX|4h}Y>8?&=C{Xm z^k5=lSe{f(YlM<|mEC%3T`_u0FbG{XoN{V3b@N#!` zmF7%O zzx|85U8r6h&%B#rj14Nbl-|u_v$vfOKIw$&LauhOUv<*-iOCv8XqPo-I*ZIg*~M1< zk0QZE^KGWPSL*bHBTrqpdzs=l2jRPgrSX~6XE2}86|q7UWg2F9Y5rQHw<@x9w=ej0 zcDvp&E7?b0udlLE{u##r_dTtgx`_1{o!b0cc<>u1bhDivg3`~GSmNWCCtfLm)=X>vfQG)=Cr$Dc^|oNc)Q zZz00o2Y*5q=}5r_<>6eu|H%O?35$L{K6(W7>>>SMQ{tbg)tEs$c4VZwp&wU|6eK%s zL0ll$B+dRMzNEp$PUoTMZ_kBRj|9M^^(OO*Vg9s;y}@;G=^+s-gbWGV2&?OtvAnyBV|o==-#mV z4~CDBzDHB7v5oCA4Pc5!T&C_PhHE(u2*)QqM z^}TyS0by?DJRjkq^*bVP{~+}saDy+BIfjToYPXF+lp zXkyIB1}9W*gnYM26b)7+<)O^UXkhs~*}o!K{uwUBSo|ME_ChrlcMB~*bXVX&@uQQB z?0~HkZGeO^5nkZlnZJJ~eu;nq`imXu2v1)k* zfo_on_LDuZD6#$#&}At8PG7VSHe9r}cSBxbnU#N-7WhE7_3YVWBky~W(TsAQvhh2m zG@wgLrP_)KJTBg17)j0kKnxtYwEsx}ZUj-nX&R}H0j|0zzyFh82z?qPTlzT7zEeXe z1PW=khi1HigW&zNMksj#lLlQs*ZI(L9}rrcD)nCc08T+vz@T0bW`Dw5(iI}wM`g0c z|9V~21`r!eZW1p%7Dh|qM8zwIsLvoKj21(NvM1x^>$iRt4u`vNKOhVeE~q#-LGsG% z%Z^oNOlo1o-!g0Rq+-PtJ5|S(|=+jW5s7GC9KAzAMD4wj@!SeP`UDZ{(EHlw=- zPWUU0Qxoy(`|~Hzn;{2w|7U#e@qd0TJ@0JFeS){@eBKjjNzpP*TxZJy=rJ*WuMd<# zh$tCTjh!p#8et5AUF@&I`%=ylP=&@e+K1V1F5S3f8rw=U9kt ztDp53$nz4w{|3>FURbYfWqMv7$QjUo`B=Km3w*WLywsbWVN8m3o#MDU7%~b($phx$ z_J`!WN!y6{zuGZcfhRw^PShNWDdt&=J}#y^b8J5kz>XsxiZCPGm8uSg7UO1zOcZu`n ztK=R`vk^m2y>1&o|B4Xo3( zvJmg43}v2~oS>MD?><{m75;J7K_{@u2yC0+{s%q>NP*Br3*0S(x)2Y<|NES45{HFR zsS-i6sryKD$i1#isZx?5olI@c^5$EL85yl9>^xBUQhgEk{rK$OqHq&ogj`NxUy%2U zewr@f5?D)*5mxm^U5@Yqn;l&GJ_2||8_P3?J1Inm9Ig5if*enyK!)G=cb(^kq2Z^H zmeXE|k=X{CZCSHGz=$QVxD7m*W#D@mJ_C#)8NP}|@I@Z+Ki=?h-t{}`|Cy)_Txt3x zVDs+<3eyq9fiaRSo@<9QiUQ5u)g9|!PWTr8-4>dy=QbWdbwM&aOw|t*k4O>Y+F^1FMc2@m{xQyRmc>e`RdfkR8q+3 z!orMM7RJUI>&we+%#08%sZFh|Nz!2_n{>NA6uRB0LyY%c1`jsqe1+Mxg6t`U$qs~e zG)Z%XB_-ied&se&Gdjhi@l5E*A>y!ZC7irJq{B?Pb&Jr&$ujdv9mr;AV<_ZOWdqu@ ziD`e>>fP`b?L)FIw3?5$Ql&+$7^PO27@He z@}uyH4o0htV>r{}N%30j7=)c1fg#J1HVH$8q1qOLHPck#zIIC{hF;@zm+`K(JPz%(5U)r!u0RTU;E=ztu6q zCy~rOuh_Hp-QA(wq65v^N(EspRG@c8%eV*A&A z#KmpbNPHJ2pJrs9<+`_2Tye<|gTL;2)U)7bSid4Ye+Fk7!m+Tkj(Z ze#aYu15lfu2%dSaTs?qo#Y@2>LJtS;xY?H3h!J-n_8#1F-1*hxMR~Lyuvn$m5O`Pd zwe2YQQ9!1tS@i3c=$lgKUb)`^g^>d-?U&QC#}g;uGr|#nmL(1Lj-+9!C~!!T*Tdd2 zurv{qD<(!xm$Vw*?cSM~EDEW4Ug(jVp;|?Eo?%qR@UNvS(fLFY1N4NYD$D&; zqwUWD87;YB%Jk^O*h+MXu(oAob9Bf7!AbR?t6I=FMa>kl?5HG8{-D)SBWP_yE=}EN zQV_&)jP=&3ssQx>2KR?6yL=Abta3vMEp2U-NMQ^Z^yLJ~BM9&t^fzZ~GGba`U&a$@ z_%&y1TU&}!3|(8<64Z7(Ou8%+ds{v?hN7q7i>he^Vl|m{@t7L0#6OQ0w*R6TMOn5N z>%f4kQEL0l|6rtL{x7#nsiG)Gdu`8zp@tOl{*ZGJg{uoe;H1KlWtd~0r9ywT3{JZy zrMp3UK?hE|R??Yng@#>qI6lY#5I>`om0Fw)0@#k~Gm0#x7VSXI48khrsulOh>AtOq zrJ01j*E@P%F1av-5|!gOjoxjuopE!Tf-~~5(=r`#Jz^)5Z4`;ETF`eF&Sr6}`)tP) zU5uK+KZG;<&YemD+t)QZ6b=4w@$qMfh!->P7tqJ;qlHJLwqtNtKV37&rel@^*kP_P z>IGbdmAt2X7#pZ-FwgyCC3eeDUn)j7KYH3;Xc4Qq*#i-QwYk_YF*?MXm)Cxxnc7dq)q*t8RVt-^+9o-5wH3~o)Se^ zPY+LJ1d^mK3?9O9oMydJAZ&Tisf!$iu4~9q4vQfMT%>pW=f=6SXYgX11B?PSx|ORA zZ)bngRrBnb`YU7X=}+m$nC;EgWJ%evh8jiF8|(&rg1l*;K{HNSni*W+v?`Hrx@^4J zQr}8UVS+8)nt%fuT$;M%wt3KR+nt;sZhrTAsEX&1j(Hs~0e{7{oEddV|L8*l1MmAv z8gw9L498ojiw1>`;ua&_W9Iv)VHhU-!_|O-``oX^I10^OND6$q;1b#WTOInUx<6fc zPz*D=%GBtiw6PiBTCvL9wOu@6;t(;Ypj)0Qiec;4kkfZKv&jb{xvGpx=0mJ*^s+t& zHpE?v(7Q!}jHmR-sfx(w>h(m_OE((*`oPKFTIdQNr{7I=gsMwVGbt}Z}i`^M)f z$^h#-!Hz!9-pft}5+jx}S4^Os`qm~C?DfBmpIN465EWe7x5Kcs&Xpg9ffNIsz;2{o(u#TqX8W5Ief%pYxb3F;o{;iy0o z-Nx1U8yXeV19aFMjj}QZ&Ta+HR*A16sbM7o9?l<$o`rlNs$~%>QuD{UK zet#<<@EOZP>s{1Zb02zy?G}QuK2tCD1V8r+mCy}p<3iuGs@M?Z2{AzXb70j}ZLhtW z?zp2fslI>M%*-!ScTcRESRjrqaWsYyd!Do-P4YixdirhC6>l}JWW?(M=`&UWCLVP%}t~w#m&_Szl8$-2C0Jl)O(EoQ`R7q zFFlDH_{Gf|uUCCRxM+)1G)47$U;+BE;s?_Rgg*^UIT4vqkw42s^$w;Stahas~#K zCQbBMg}7 zQQ{??@FSCEQ9!ql=Kn~Mw$;SmgB5CqH9gKZq%wyejijBUI0hbQ6y9XNEj~n024Xddp$;}}Np1;caED2t)>iA>G zi>SUS-#-N$ls7Tm3&QJMGf&lfr`9M0&B#1Sm*SAVqikthN2*#Y%u_qF{N9(bVfkzO z{7#Y4eW&}Vkh!C~d`WKL6v-Rkr(5Bjki+Cleneqp-`aEPc|8zNvs$j&ARF51IlvNE?YR@97R21$wX?imEA&ig_}HAzX~#4itN)PaxLr`qhdDzR z+IMY!sHYVWnP+ql_xTzcICSvkyi)kA45Ucs7K{#KuU=70w7(yMB`|A!OxSvTz14^u zhgTo@4hxjsrC`0giHzu1OuECGI{sm0UL5(}euuN#lc!Fr*i<6j@t70_`v0{6%R|_q z)-*U6WKsD!7Gr8R^H8&e;tuq3iMAUmL521~!j=^N+?Z4Fu}yHF|U z2_S?|p%WY^jH5I*=vL-i;Zk8CJZSo%J!q2B!ZlJjH&H{<(lC>w!K1aawfSXf&Qhd# z_FcVG=b)>hLxQyRU5vMoOH8BXDMPPb+J^WQ$?w}qH}yCdM(=6hW-5~&nq|G)evVn| zs+#!tlnjJ}=`MMw@<@ig*;1`?_$Mj>&J6SwXcr{6I}UoivXc5jxzof3qk&%+=Yd{R zmPvku8aQK7<(4DKWe9rf4!VgFGd?_)0yJDBH?OkKh2L*$ZBF=WBp<}%ibvwn-XXsjmc<#<|DE#YU1^t@h+mU z9X?`BO#MBZ8y#-O*OuCARYimb&7%bv??re6628=DNHh7 zT!{Dr&xB6Rw)@!-%fAm+wFxCycPzAVxK&kyMHqL{?*ztFXzaO$}NqUQa z)n@JYwV#m}pZD#|Y^#l{858#Ytu|BIFY$1K=O1Bci}ulym}c_IgFvk^r5K6214g;Y z{sVz@k8WCm2NuxsxEc1SlWQYkw^fGT`f5V{NBU>bwBa4ktIs3-Xa>fjJyX9o z8Wn{o+~$Ml)jmU>-(AS7stK?MhCSPj=^Ubh#3;~ zBB)?ePhmUG9Q|DFdKZoGm!_FHV1F%dQ(%F{B7XKj)uH`?ncOEDq|C@NA&I(4e(lDi zCEWgH>dg{nza~vnUmPwET{ugfX0hi@s4GlQc=Uq_XFMJI&mnYjwYEdQW1>9&RH=;qJL;qy zBP2~DB#k3Pyv$gO=T^XJAhHSO%^Ic2@dvy>A-0d5gXh~k-B6SJdKOPW`K;T1Kq&kV z-nlk|>Cz_Cs_3mJYqXElt#rIxlbb;U5cZB~?J9o;cHJQOeyLZ;yaGCV(yfOik+x;A zifa=Pkr(f9S(_IZt$39A;yiOle-|(@u+9>XAvoIk0$_yeUpu*?`lL-ybj;?-U ztWk^b-fPHWJaF8)>x;P1wXS(tLb?`8-|Pr7#DR|pKMd&3xobDB->@Dfz}oElx7Y$- z;0?ciEjeG>ADO?ExLkNM8~+pXT%4PQ3u_{*X$fu<{yKZ4~|rBFcY>%v}$n_YmrUPK>c zf5MV!m64SQKeHU$hn&?lS>esbV*_XxT)HoHtZKgK#Q)9153U)IakZqEcQ>N9DNLX* zOIbpjA5GWrFZhPDxrTZGl6=EXjX)|=ubf}Wp<*DzB$55QLin^LvnC__NEZ3Gxh6^K$`w+Nyd~a?f$66 z$mqfCIYYt@W(@i}zbYN63sZ?I%nl}WHZ^b*{TSj7y^%sg_s_?C>9^pVDlBC8BWw{< zX8!20BdbsG(ZjUO58Z*;#D7h*0TVT*YCdcde;Trhle)j;1Uyb0C^X2XHa=`PmNHUG zbJw6sWaD|1FCrL>mWcU#UNVJp+Xtd7J!#sp#usc1=h$sHqxUB;vyQBwXSv@^hWcOr zes0l($iQ)~a=~imqC6(?6^|h)x=khwWLjx2-#8WY0=AB6j@IA_sDOkF;?>96-y4Ng zu56V_2g%+D)x9N{}w%8Tbvx=!;1gu zZTjH;O_8ta_3+ms{6AJE;CYwGd2OhbNf!4-$idCaC$z=$^J5{Fwhb)%wo}bXABt(0 zp@K*XZ60RA#XD*9K#08Ij`cm#SGxMg{=AGVZz3!x=+52>GbvK?Vl}xNUNAlgLVcPLn}_6ZA`{$hcu2hP4~LW92k^A}x*Y6WDjk3yg{(w9gA6_H zY9(>V)l0FO;`4@-NPV#ifD{GhtTxirZ&~xBy#L%u6>c~JH6NXYN>Zv&7=S&H%$aa7 zlZOx`xhHPQsWJh&*4ID=O`;5dbu@yJsn;%4rzZ^~b^>cUDx}Xc9V3ewj**Op5|p(? zy`iRs#%4g*#@lyN%RyG!mM9u@DIzC`{Nn~^umT26jG58iwR3C=5Wk$Aoa6)(lceXO zH~24#pR%g?yD^Kt&c@L~am)D@UNc@efvVN!W+49NYiu~Lv*blpd~t=U{r$3`)os)C zk~U$l=u%8xtMP_BXyuvYEb*LOZ^y$kYSoWRKO;+H22+O4 z6LN3R7KD9r@;@eT0i)t;i+z8X|-s~CvdK%N+Ld%SP9~~ueq^RPVWQ64O-LGnOZZ2^~;7#_=P4t3i>fe z%Z*>-k8;y{7$}jBZHEz=ea6tv>i;QtzxC*XE5W-SblT$AWH&J-`SRwy#ZD{Y(Y*ds ziYx&xI>^qlfxvt+7)ZM~Z|Kz?b+j5Pk!Edw?+KtS+w#Q)^5vruQe1UDPd2*4s%V4H zqJ_dO6ccD!zTT$uXy^PUR8QIdM1kBNNZ^Zev}YOjITS5JP)m9 zj9v;)+9bm=Yf8JpW&Cyddw;l6!nY*VD#qTja>5m@v>eZ+xcn2-9@#5B?F*Q@lFey* zmC~+1_-S>;burE0i!|sMOesK$taAviWQ38Qy%@DsNhuayw^em_S~O~cHEEn`I5L?b zy3lbMC|*oKFu>a=u;L4~sZ}SBpi?P#HpNot}w7|=aem5Lex1J6{KV~?Ah zmILQS|6_o)<`N~@4_7{6+D;({9#EX!C#ch{MB!F#K%SjyEBsy8P6cC0<>2>gkW3-p z4ht;MNufZ6>XW_rWt7+D>VHsJj9g2A81Z?@GN%y~(GgnwogywFSH;{K!9opVibSxc zigUUlk!K@%2A}Is#w-Fzj?6y~@psrmL??-H8|J1WTDz0OOi!*MApAyY%!-j2i&-U_ zpNs27klg3QwhRSE`v@u&Nog+iYZntjRw|a9Za_xEc`EG0rr)jv_vG=*Jw#c3vH8#*cP-n&}nd-(dr_RnijZ8`13gdu&<4?kyA|o*NZH;1c}GWtwA|>4OmB$vfJ5 z=l|3Gflpd8I!Q1IX0_RT@f&L+o%G3bQ##fU&HzetM?5*sJOXA;MN*w8zn+wnC#la< zAi3jbi(6RVZ0N$C-YOdWfh`3`uqG@6x-N9;+^CC>hl=6^W&MvN>vm0_XXF+IdRz#Q z8*6x`U&6M)Zp?1mUfPZ~|HU6>`>sXYgYZH(^22lqM*{^KB;s_f zclakU3y@Aqoa*d8?f_&59+dDITswtH=iyL6TA_)D4O_DP$|L>Hg>+3F{iV3th+6R$ zF`kbuYOHjmqkX`Y8a=fzGiRp7^rwiv(M)^QPq7caF~q~V5(&Xtnz*#6GF=r=yYFOS zz0qMR52~_t{iA->9MX~Bg3+Q$L767Sku|u*b<*HQ4;qRIL`2`*DnQRdLYbu(l#KaV zhwH5Ioge_#enyo{nhtmff$RnpGb~Wyy|p702T!Jgxm5~lOtVJKW}MnagYB+3^jFKJk8g{q;gq>I7dcV(l5a3D zZ5DlGL9oXq7hmP*@PGHJ6bl8b&~P1ZM=W8P+OE0DB2U7G#wiU_q9TvR919j10=$Xh z(UAO1_JZj{Yo%>5bYOdqGQAQwIG7Ngu#tH`2r*~{cgy>pbd1XXE=JVDZ`6!7(=Fn9 zj6@rkmdC)T0QcAZ1|vsrKM89ND?|6D^OvhF{pK_h#!k-IXG0AVe%BckmEIH?f0 zqK@{mAMUJf-?Nwwb-o_Tn#^?*GK~JoW@}wOP|m)rOHcluAhZ>I-0@dG`z)q%*7rD4 zX-0-G6woY_aVJr;?ruk;N=Q0M>V8jj=xcy&gV!vJtmwLKOMQaYk2jM7Y8j|@)f-C9 zVx=`|7i0_gA#~B6CDu)YR5K@!sq0gbG=o%QR111XkEz4`a>c+RkxdRgfla9rRgQxK z1_)8`z^fY%d0&+@$C9p0kQO=~r&-COgM0FwL{ z-iz_~*GIjS5HXqHCZGp;FVLs{hCrxu^{@|LjFqT;sue2rI$U z?^@O^H6G!|=aXj(OAgYZtE&UP7%wKV98}BZgg43{RRSCRqIFM*;iE7eN-6i*X7zh~ zAY|P!eIp!a384sC44=oCxhS1;CyTmv5*dqDIz>De}xace!*Ej7 z_pQ9MTMN0PS)Rl$_JAWm9^>S&Llq_+jm*csIrrK`CABpoGqp!DJmM`Yx)ZfI#rJ&+ z?oNP-7PDeQ^3N(>KGIc4Axbu{_URYGEDS512HUvkowMptqfQ4~i{JJi+pXi}OrSmT zBo+0qf;RwKEf{Qb-#r|Mp0vZR^;FK=*PtB_gPBOeED&YgB0qT&aqWZs{W_DoVQnQb zE|`t*C{h8D*DBWd$JIgmpQU=-q7L0VExF2iNZ zx2}E(hXyOgGbpXqvm+qZG20;AFih+Ia!F0{pLWTOUSF!Hzlq+7xh43jXSs@`Jj^!j zU-(|$xG3_V_lL{(Dd4!*SebfrT6m@J4{=wInAy>p$LlIcq@-~+WZ80c1f@29O7O?HSEj+Kpu zcxu7~wd-J~%5mkdLZG@_wjH_?zG%N`4Q7Sc4tq@?^-#5+cS%bnn8C8fa`V&LhxXDy`UTfPNRaSQ2=`Qqs3wID?rpYFyE_ zWM?(fD7olDHZyinXUpeRx@{^yu*O!7djGofs1Ef{<*}RNlzP|R%dwd*c6o~>N0_|k zv7G2)pby*?g-j0R(Nlva5eM>n=YBq;W&hUu4ilZu^$KW$o-6$bzzd$OMV{#HGu8%< zW>rtz|GPi7C7<&#%#}ec$c$wDMafP{-faSHL~7#UZSr!5+!x zq5>p#93>qu0Qk z$qoz4R;Sl^d~r6E+L-{@H2m9_dkOo)TvJ+U0g`Tu!)cj@-YuWjSXe{_9X>`@H>R;e zkWNfY17GZ{7Ee8kZIlqc{?4UoX9Ab31tEOHBM~VpeVVhkhF9pVsLlUa-Ap6$Xt!Xz zuy##9pY}ouigc#AhDZJl$1jE^xCL1>j=Z1~*#ucj<3yy1&~w(H58*ZBk~)07W8eZi zeD&tf9GqU>)5mzxB^#7`UOarutFFns8o+UW4ZZ~=e){Xwck=RUW#vQY%JEW*&?>*y z;12Ilx5N0YvPMf|b0P2~|8wFx+-2dbzHytL%ovH+s}|n$;@;W?;%~tuli?LwTs57@ zk&fitm&JgoOQ-6{>ZRCHr_r@@r+`0Vl}8=7apj>?#7$=7?#2_``_8Gu)59MV?j}U? zT)M%~U+HvSP&!uzQOYA~ zv?gv0(?S~$cD2G(%Js}kQ+9>f=hGnIpzNU9wv#6=HA9187AAs$*;;ywo6fCXYqqea ztq&pnLAkOn{KJ*uG`c*50}PYm&E`rbFC?)1RFRP-kK{Eu7Ppe5;!GB7^bQ+zR(nb( zw;A27P&47a0$pJa6L#!+opWq-GTQArzP0wsn3#$T8P+V8tSRcum_sMyc}U^rLL57D ztc;U^AQ28`;}a2%M-}@U5wy{@DCAYS?}X)xo4k0W}qx zQV~~|M3*34!%okaK@S?^$MvB`LLC$=X=Z4m&`H?jZdmD(#?!Djo*7B}pWs;RS`|R@U=h^2yqA^8Xz$jtZqsKDsU!_W2 zGosoxY|AAKEeRylia{xY5^kg2H_xizn)9HNyz5*{ztaXxMqz9EdVMrM0sF)=uf-^* z)35rqe@U@7a!}x#T0-#Bt|&HYiMRQI)1e5Chum%7g!@U1(ckBe)o(*k-NU=+Bs{6& zhXL=b+-A_t{z`G5%y-Y)12%TB^zmiDVRO3G@6bDiIb<>~EnV3jw)K&iYnmL0S#0>O z(9d)HO1l2EgCz-jB;8Z&?Ya(3v{9gJ?#fAfk}$jsrOmCprq$#Euda2qFTpL39$+f1 zynMfExk_rN9M_HqkDec~Co7`qEe?-J&0_A7Dt;ymwF}#cUhoXhBF7AW!n!BiB_eP| zzHq}h_xLOMv`JOXi4s`gi>W>valJNY`Mx0a5C-M@avBvE+==}Wa(@VfE%dbi<^PaC z-q#E2>a9nB?t|x^MlDxz!dOB62a=OI%GGazlN69KXKC<*nbqpfYD+jrU zz1IznHK$~qEv2KpG|SK|xfeiTl+{&wO{ki6$$aw+_z%!FA3ur@SbGugzelzI8V5Xdws>C0oMyzZAinhCSPOT)MuX0sj;T*iy*l5FmPV&zSd<^?uu%#3 zqfc~d$+?ht(i<*E6+1bYB^jzJnf+!GvvrSF=^kSkmG*lBX;;_Asop4}`v_Kc5Tj?1 ziN4OpgU>}Pn>MOWs);E%qthxbe;@y>pxH!(QsOPRDvl!z)uX|`!LOw~5_dx$O1dIN zuJL<(U!mz+J*Vu9WRCuscjfhEMz{p>3EPm9BZuY}XvQQEC^^yBT<$14R>QNFgQNZ)Z~c#_HT-G^@az{~(j1 zM+keIX`FelgbCj~O~;UhpC^I%&f9=b1CLsBi`&FWlQCN6eIO~$Kqo{owryD~{Q0@l z$@a1>Pi{T@gEPWb<4xE&rqi>J0twdRVk)aOG%juxYDKP3IrX1K7dI7V)YS3 zL#;iuZO435KS=|44OH(i6`?nX99Dl*|Jidst>=7U_4Ly7dX`0T1~Yt#C8jzOPZyUD z#?kb``BPbI#uwaM@MNVV$k6p1Mx5K}cduftlUk35pGJltov9|(SETFIK#R_~4GBIP z%#&4#r3gRJN+H#vt5JScD^oDF^f?JnR=Grv60ZWcW2%F~jYsc}7iC-AH zSfUfZypfh*c1=u~XHD=tCR&3YM4dS>oD5D$#;~!Jam7r`lYKe+vMGExo;IdrWl1S$ zA*iXPUE>cU5`xag_S)xJ_wTyG-}GY3zIJu~v3HEgQT7=+N8bsb1IGr)z>i#pZVQ~X z)oXYLp>NNV0xy0-&&wG(&|CEW5ZR92yNY`xeUAhjP2C*H*AwxS9b$MG2E({%JL3~H zy|x+wMSK?5V^*d#GjqaiO6jNm&B@TjHCo!)=8U(ya?op;pLKUB;oN^$;&r}j0*<8f z=QHX<-??FZt>&Uf)ghoq9b70J3AYZ*+C8S)Xn8JeM89h|tY(=fi^o|c;vL?IhUgC0 zHxJ^Pl~F$}i(qFb1-#7cX?rGQ$DlQBbKsIBpLEo#SiK{s4f;YwPm-@YlBaZ)t;YmX zOajNL#XAab=QgcRJXE@=0)qf}j z$xQQ3Kf-ZzcI(87{9JkaT%W!1YAof96$49yK`CvFch%42Tfbbg`+hk-@po$3;@2L~S-Bx`d1ZutreDKmP`z!Lx0bfixw;&Jbfg+FSK zjl8A9Eab@g_K>W>^u>!H7&_>>)J^W-cP~ykqH^OzOc!PEfk;6e;B%CP-rp=30P#+1 zh)OLKylj`%Qg~yUF-nz2zEbIZdVbXs5dSx}FUpPiQ5Qo}!PndFfw$}x*=U}VJv+b7 ze^+KzXTgViU)OU*pV1$>}2A5Lxz(KRf(QG&(?nnT}EKjNgZ|_#9 zV6CaPTB5?@4a9#W!ic4Zwh*oVZ2o)l3{99b;G0V6YSfdjduQhrkSiaV(em5!*Oi3N zjatidcd2%{0e`ll7c}D6v;I`?FTTW^&&0WvCbPyP+qM?;FLvYVE#;j&1KRp84R@TJ z)Zdd<&Dt~F@m9^Nt7PDqHaMg|5X@8w@g#9)nsyg9(fGq_qgC@Ye%I_cVz&J13Y5+X z6lfYk$M4=_=v%|}p**RIo{X|?O$JDG(pX z&L4RCIUxX+0EuU~CCckxq24p|9q%tx!JGHJ9}j#E~X}c$JI(oC}W` zLrmQ?6B_L`IQV8++!83)CM_iPvm<|R0PRW<7dBTQ`GVUgiBwuP+qWK4<*^#xLQd9j zz=^;?Lt?f6uvwW;KPPB-U}U52r)^7&9_N}leozbg|CVV{(l6b-@3^e`zBiAPw zA7MqfK@(OnVC>|v1BX%XK@(ISJp-&X?9pD=TdVTor(JUY76@D)IrU~DDSoOR}Ss(JqMX9MJjJ5O`qytHw;o4l2E464pt znV5nx(PCGK9#9S|&Pt`d3K)|i6CgXGtwk;BY;Nhl`-RWQ7^c(fPVgyhvg)Fu7Hw3I zu6i%7M!28n9NG!#cr@Fl2iFmI39R^yLQd3}T-}LPrExM2p4BOY#N351X^l?fXKbpA zYA4o5p**Wr7b`;xTqGQye_-7!MhH7ep9?n?UFdyP4!)xKx0!D;g{`>3;OGW}G2Jvg zQuRgZBBjsVz(>Gq(A{ubImI{Vlgn=3@h~Reo)6Pwsgi$&S6?66>07O}v}E6nsQ|ad zG_ZSnwwJCx&KnPU^juyL!zEO1YtfU?qyQhx`@={g_3oJxMrr+O9Ao|m!Y0}8=e?*S z;k*MqSyFw&8c{r<>)kx)Del9V|D)02qYH|l2@#6!LeQH_X!qG@CNB|yZ~gtfSNXzm z%#QxthB}+31%Ci7xxVd~4aSy&10BEP+P=nsC8fi5}Ouno#W6 zd#U$+S_3W6UjENKPg=PrAV;UAtvEdSGI_+IQ&EO&cYl?h5P8eFQElUCXS;Ho2R8mj zrlV^;c9X22Ya2Q3FNT$w39#C$+&b#i)gxtTnJ}PZd_Kti-C$q_)Ow zeYd4ii97t^5Bz)=dH>e=yP7rEN5yM0%R^Pgg6p#1cr@bEb;vr!~Bu;J48 z+L+y@75=4VGd~-L*=W7yj%fmq$Yqd#j-NlB@>)w8oGsW<$e{^;=d|=CnM6yMozBcv zN$-}UFki#`l1cC=?_qrhxP2yRiCCIoY<@oo)J(qf*O%^FxWJqTp7Jwo)6V8 zgcN7d&39YrjAXAAD*E;`c778_^6jjMxqa`ShlSv`jD2fZgeRSYQnXi}X@bGv!A$-% zz~y zt?b*bBsXb33V%h&4f|l6?2A#F4!SN=s`Qr}w1?tS}&sHng8hzOsBsK4a+ z^oo6@;1u+=s#IA=%cm0+{RksfYw^bX7YmN;b_T5$6E{3raq#U1J$u`0k7Ebi-Yr_+ zU#v=v$HalJM_U)PH3TqHr!@9Yq*k9iiM%Ezvn3kalArGzA&TU29mz4x7k&lbH|g5p zPCzs27~l_M!XJ^0%*`n)I7e$XC-6(zNMteyXRmq2s?<2^@3CJ=ZtjpcZnm>oJeK>^B0o`KZW;9vUc-?@9_ROxEo0z<|PUWc7XWW+km=U{e{pY-Bxn zPXwfKTe%iWIZTKx={&t*FEOiSioelIZMdk#%e!~6rTefKT779HrI@WFAPd}|e;i~Z zTPUtOskn1}vHXfRWtQ8Az0R~z5uRHoFT)daOdh0)&g|C`*EV%JA$qP&xzM$uKmBVe z(cD&HDU2wglc27Yedh@?f6hVH&kTF{i8Lx zYOMX!2Mi*D(j zkb>IBGQDmkz>5N)oiYz+?$Ff79v?PW9m{z!Y(G=Hnd`EC$lnx*yd=~A)E3WYXX)^x zJw?MRTQRM(w)hjURuY>2R`a6-u54;A<<}XQ%UM^#HX}!C@UIJ~F={@+>Fd9$9!x`efTlUw;N~Qa<*+Au zZfyj>G=$_asd*r(H=$n6|3zmL%9pWqT%(PyL{HqDqaXzA7;(peip1smys*tJRp-_> z``j)`srYT^Ul%WqLbCBw%=GR4t^3`eaHdBIb+r0KShRsk4i^-eE?hgmdN%eXWZqNG znBiklf`t#TdCwMQW5NY357M!&a%dj5pJxI5jl%~0ANYs!J12P8&EtB9SJ{WN0w@w3 z&RN5?cNk@x3S<9nahqGr{&@j?2Y7eMVFb+Q4tRvY_MD(j&Tr(2E$V(LAsvRr3SAEa~P-0OZ<0n2RSAV|woLsV_kbr9Iz{g{D{o=PO;hkJ~7W~#lJl;U+s zQ8rP$0On?3tv?G`X&Rd813V(ZdlB>Au5vBJ=I<#I68PB^x+}JRm^$wDe1}@7(Eii@ zHUML;ddyQGR4q<^j!Y!BD3ZTw;vf)cmo~&(ig9G-)(# z3k+sHPM~~`@i`~YYp-v&K-;L+7-#cKlbLNjPXx#c~bR}3CfSv$)_|Moo7{2On( zvepl05kO^#Z)EV9p5ZRlu0eLs;q9!rR}^2Ck{(d3?hP70BD(5!0#9>`96H@Pb9I@` z%8sk47N~DK_W|Ds}vEpD}F2Za%BY zeufieC9mPHjVDL9WRqR_Z8!7l!nYHzwZ&hZTI3x?>_6B!`w7#)1Mm}-Ucot|`ah_- zhhKxs>?+q|sjYfUJfx$d-$;X(h72;V`nSyVt$y)&Lypy_*(6KrSL)yUzD<|jP>avZ zNEyJi`5Kfh$>qeKkBmy5S)t;b)ng8_P5!HPe4`>TxEdkBHwRy**WOVnJGZBUDOWym zOdM;g19(7e`DczI`W4EiWgPA?*IWA%uH{(;+`87H!-%B{->1f-z@dX@b^QLopVjcA zc^a#LLu9fQ&i*NvZzZGZm4p$j0FK?Jac=V1|M*_0ocKEUxd?9f!ptOr!6kTqF8D zwutcgpgA4hoTy3oy5S@fw>~?wTSC}PmwBys4MiS1$O!)}uKYG^Q0$vK&;BCjUuj?U zCICvbDpD|O$5p?gDYYdA6TNI7(op)5T;7vbB{AU$ktS^L6cAp--j;B+j{b}L*MTK; z!od(80=|lgczGX=`lGwBN3&`z<<()xTwm@DcyDM8*Vv02ypy;nz(DC&*^hx?uIj6T z5c)G13*RhB2I7qQsTGWiM=X&;+vsGx#OtZ?cXumGJ&aq!_i|ph@*%vN%;6g~dH0HZ z{3LK!6HVp?e~uyE^NGIUr|xK)Qsyk(QuKABwZN0RPR00Itt_$Hne5LGQrc7Oh|Ec--voj5V`78v4>N zO`~?*7rTRg{0V;!%eZq0ndZ8#0q`~M}^y&6P9p;6f4~06G{G~>T`m7i#)FjMLT#PbY z?{EnYO95g|zi}k5hCkgWi(5lkcY`ckfL<_zZU;3LKDvwvZ7f=+0cb;k%8JH#)iEgm z_X1nM{3S`R1LX=|PabMbInq9S&W~4R+3{z8l`wsF2ULFX4jw(noOj;%JP)$_Mla!< zq)bh`^A6ZiFE-fNb&8tbeaEqYPX?>&_@2JeLb)N=T2WEa+QA|INI?2I;1)Md%&CHm zi5{lMExTV%QJvmtd8cgjbk>Zf)js0NgS>@g`}wbXcueUk!%&4czbkQvO27U1MtvK{ zI-;`*ANi8Zp{3^(^(wLPP%~Dz{eEPn=IMsYLU3(|(?t-DCcVhQ?HAP)b5Pq1|2pYC z<#gm;jvhj2X8+CM9ZVqy+5R6gq4G(I5O=Uw4u954pW!aX$z;AZGT3JPcC~W6ec|~O z+Sv7XXQb>Q)t;H&wE(8187FDomo55<(skF@EJ0HcCOUPbj4k}p$~eHgd~oUcqN{4& zHJknAr7iVmlMF%r1^e?ND7q|0y8u_rT;!d#^_;PnlrXw^0Cnux;Gd}<Q~~(E_^PT+utzm6>5zAW=|rs(KuFIyCR`6I{^!^^V=`17GBU z1uTs({e#K-LN32(tr9wHun@4o*N!C>tRr}rd62uX8f1DP=hoRZKt$hXl9I}GM@{wm z&@d*A7)FVV&yFhFY}Ntl%00duIsVm%#>$ELZ!ePjQ5-M%9KvW)`~Nnt*y-4D8j|QO z(r%wv~TzaF*>xo81yL&_Uw_2T_~o;)?8(g&-bXJkUQAd$;HKGrkcfBl`Lh%5ZFH|4mw7U zU$@}d^Sp4wtPc8EouNtbS!5878R#KNBq`_xv9Qjr z&=a+H1TS*<+Cw}KFbE(cKi7F9;O6M)Xf<`1VUMWXdH6{-Ki_4gQi{LIvl7aeTkJpV z_@|26ReaH@j*CKCnHK02%{wn}-*3{(>3rhGN8%0ckt{HCCeZ5aVhEZ+GFCc|j2a$Zo$@cBVcn+XuUpIhfXFI$ zy1h*2wLr^1EnHZBlcu+O{T06Dt z^aDHd{SlA0JfYLI!FHeaX%+wH;zWDhO z1eR(AWgknhs_&i9{#fa|{XtcKBTsl@>alewuxVGx$;l&gSu@$#n{`A*bHgh7UWeE- z_S_>)W+l=Y!RRf_WxIk8XS4$GANL?r*d*LlHdygiQ`lkyba?sV2oN0XX8ehFv2Cdu zqGg+$xp46Zbey@6ENyc;StMV}LKjV~XnsGCJ#+q#KYH_<)ENYpSHg)WzFN8P*?Wl> zfA(6ffd{Pctk-t88H|{qKYNbr&`qCkHb^9-b@x#4l1(T2A#t|DNi=f0ylHGV8J zHBSFp8k{FDA_H!_i6*WduV+9SbuOy#C+4@}jy)2PWghT>N%y2w4!_&yC>}FtiXz!$9d%hg^ayOiuW`5P^bYx0Sc9?Wf=$>9i}|sy04{VAW zSJ%ofvz`0H@|{IrexvWt%pH4YyH=NuOFDGja;KefiDITv#j94Y;;~0V*i6K4 z!;}K?;_o7d*Y-(t{>}Xn`d8mQO?;cC!AeL+^8iyN`_MHJ|F-d}q79nq;^&(*(-p1; zNu^bx!yEIs^P3yK=qLdGXMw}LyDOe zQ;+HZG~go<>Kd3Q`qqg%tl@aKeX0ceV0pT7ssv84N&P0xJ57JX$mn+IZQ5fhDEpNK z@OnQWtpN#}qa4H89z*G390ki_KRbJ>u>+r%jwOCySOIN5dq+WLv2UTHQC>_ccvV^l zO+Oq{K-xlisfn z=c&_H)O&86Yz`F~^3bSm!fV14Cy)n!N+xr^`ALKvCXfD@WO2yBXJ#s5gk_e!5DR z7jr@T|FIg&Zxj^n4-Em-VV~%IgxtrwP3=NGLaP)2nOpPl1yksOLqa6&hiQYTJ*!Ou z3r!{Owgy*6o}DT#f1`|-npzBhYWi$936N4{&ENu6(h_*z2<-Rb;f-DYXi z<59)82*8m{t4W0SNlPaez#T3?S1CUv4p_z;9I&QW5 z`82J|E+Yv%@H^d@`#qhht3SwN`ufP2A|vIp8o^JsG};rRxZ$|!pd!GQ?aVHyy(q$U z8!M6A{L&!PU8do>CkJkEc6^p78Xc>_!5w9U$M+6*em6 z1>lMOrzmL>Izu|TkLzor5Kq;`PQcdh?vCe!vQpOLR8$7P{-`o6dt`Q@+oHEJk;48> z>Vl|VEI=fRfoREaau?G@($i83&u#9@vopFSpF28q4AI^eZ3?O#GmI7THhI~gweacn zL5}t;xwur-1upzcgExYn-7)X@;Ma$vg!pD7ein0mkHqUs1=OCij5Jtk?z+wAO8>}@ zUi3D5yyCee#Z9pJjS&=M@?Mq8``0OPqG_L&q4&1xPiN2>EHeX2)i%e?s0qM z`F=+C%carSqN_=E4_9a>!0 z4Ka)^qoR)K|IPx)fct%`yxZo*?5_FHIu8g@KClhq`W4BMh+S=4yVu)1?{dYrD#jva zB4C7I12`UChE)9ZnypsC%#U)Sjv#_fq05 z6~$kkAnfG55LXroIGzm0Y_@-m{Ljm-x~3@vaLFFN$;~DeO`A0OlhrP2)L^LZOs7&* zR5BzNrQ5i&PBXZ^!2@CeBtF}DK&zh(!+KMZ^F9zkO6Ci zg2)&7i1R&|kHP3->g0IFY%fZlgzlVQJ+pn+v4n0T_;vTqjs?b=MV{Jgt>WBR z*j2&VbJ#flX{Y{9^=cme%Y zuyDT*jj5^T)PVS^bWi4RDurV4J3uc7gl^?>81UC*TV07uLHZr?V)j_8lbHhem@3@Z zwBL$G&lb;JtJ)iGR%egfFR^fNL}}~UKtXJ*_VBR0k=(WH`jx~-;6j_UJqlaa5C}aXA^(??pLS16 z;J8n0@o8&y0vjH?Uk17-Oe%?b^PG6Wdw2UTOALeI(6S%+p$Y8R8X7hHne4jEKf!<0 z;RF@onnarKvo-0)+PN&&wwunYKDM5UeL_g4+TelTEIe>&y^Faeo>W%NF`Aul6JBPH zt>s9fpG7yVW#VT)+zrwk{3=@=a(sHHSLMY3s(hSNv2avJkMFMqX0G69)H zoHh+5D_0>)2#vqxSuo0LYu?(0rFu8VujGG~*LEh>Og4M!f=0M#JT4g9A5qCL*mG-w zqT{?T=OD|3mL|6|cP?e0O>kFxJL)t9BIQ?~9O4#`JRY7}NtEy)Qz+rO6RlkW-ZqYM z?l=0fmCe=4L}IP_F+Q0L)_%=|SERf)Tw(0mH?B$yu3e)XIjJ>%X)`%Qm6^Q|sPDl2 zu%q$QTt5Sg#idSNmaAm^>PG_Yg&}~d^m&N5O@x+6-U`|Jygt(bl_0>hhsM@djh}V% z%fRGIh;}3fkr35!c~8O{)AXDO8%??512fz}ZcYEP<;vJ2OF672PEpZs4)!;fL_ImU zZ8ahp_@1Ao>4-D4E%+h}aZ8{9muOjq?h-6f%u7&^4FbfGw(a%F?B>T06%*v{ zH4WdB&hp=#eUWEf?1a!m?f>P)*bQp^y3NMOw;6&fK3S6~|S1dS6kV)*W zb6$<~Odk~=jvGu!yQ=dKg%3mHSo{x*uv@U=PKU*7 zddcVs44_3AozDmU$Tg5EYDyp-biF%yezKfu>9H2xFlP84>PPD~&@(`7?d%4iP+|$S zyA{Z9y@x~D@~2Sl=jd*%XhCgeB~C{tIkA*yV>`nQtpZ8;=!B5E-qJWbS`U(BO5_ zd8Gx_>2~IkceE>D5ST>#3B>;6z?U1Lzfph}jJFkp>w2_n_h~azC~;o&Ld3DMGJh3T zW+Uk+y7lW;Q^Hkt@yTYZhuF5?RJ-Oc(4+N{tlE0hlxR zhn*3Nk?T2y8&I<%6A;k;kJpjSPh@vvB-N0pDCSyLs*?eG7D%H-K1-Zj^1|`pJ@{S{ zcGtGMj<1~q-f?5{Cu$-ovhsWnzT5xAmQm9er_J}P=yrcp%rAZ8U z9dy)P?J9GUlYhKIYIU6ZNn*Wo^UfRK?Y(Vs*lJdVg)jGN1nL9X`|IhDuIGeJJhIM0 z|Hv##QBhHe3)J@zW@46 zGJ!JIrgko-_@@7H_0KAw)!zM9%L72B}0u}_Cn$40dc~N*757cc!4KrS08yYzl=*u z>4s@-U(p=TN&)Q!%Rj%Bj)gcN#3(p*pXT|dv*F-;E3qzGdYsRxpfD55v=D$cI98$E z+)UrvvKBwpe2%F9gOptO?UST!&d~&!Q-{ZXO$4OSUO5dOqJ`|J&&JaiG~|;g2%ZMc z&d2u0{})d1|H4T+N`#TInJNKjkgql#)^`I@5(ZPBH>TQnSm(MgJf_YUy52|HvC@hQ z<4kYkTQoT$C>%bEeP zM_$#Lr?|sMn+LU?wGPPFBVXkd96(!aac&at-)YzG2+njfmi7NunjS9Zga3hy89`DG zYbxrXr%mMv#{&9`*|Je)u9cMKA_5(^8**Mf0luYllu3rI-3ZXrB|SH_ce`S6c)?aE z?t0?vX>#^pE1>1emjxr0{h~NcseKWfTt8WuJcAd)ssjdHV7<)#YsZ6a_P6POpX$MB z0iJ^GF68l^TEc}z>rjt!;S8L9_sY!TmSb=59tm;Z|Cq?Rthg*DYs>|9jEO$d47(TY z8^w*vi+Our2j$#9_gFWjxaq(9fUOTRCs^ zm6J>hTRf-+RYjvu!S;V0*EVr8YiMW-92nxKR(!=<*ueI*psVaa)2lOg#5vI4O59|j z&Jf%&Gs(d*Nk0Y|J3?7n0>$+oEIt&eTHoS(S-SU;!eDxRQo020Vi5VF718W@T8x(VR7 zH|f$7-~oW&-;w64D&L45Ic0U31Y^H51>!1HK!X<);OBrQ;t4u?UXO#zJ;DH@GAHjBl}proFPiYcAw4 z?{BbP0z->2==$>8Z&7F;v^Czl(v6jJ7pLPqx-O)WnV|WPNMm#CIU&O+%kqg{)0DI3iU z)HhC!JvYRb-y(b4jl|kdxo)0YFOB`#?DKrTFh%Q^IqrG?y!DH&*K?%mICAYj19JYK z0iSa^GWtZy>oGCEhfH&x?RNg1sV21eFCD2 zzI<{*NOk?FqL<40*R2wq17~K@h3$qPm+25M;zoZh+m55Y-+x_;K(7=`DXmi3K2mnY zL$f9iVL8<4?XbvXK`3sklu{Z;HSS=7bwIxs4oU;b*WnrP%l{1wR^HIqwt9TSxHI~F zaYyuXA0;JZcu$xzRr1$0s9)8_L~uiAo0F`FC2j=?))u|IY)iCD<4C<-l`2+ntOdShEFBTEX(j8f{5+}O$fOY@fJRfA>w%rbb@q! zH8nHF>0$g6@gGpmBP zXQAT{Z}%P^fqf9e9z+#7^Y#QMq* z?EC^B!wp>rQ67x=`|f*GX8ExYy=h2Eh{%uUe!(6!P!s+rn#HQRurVsoqjz}c@AWUK zhD)4KOJE>iBfj7ik+ZPhvcGUnJkK=vjk+-as~B&Gz4VzY)jb9GI+`ErvfZH18JYxC zQz!rpdMYa8iC!M;e^kNV{{wmzdGc_yd-jGlrFSF+4i_r3B;~hDe`#*O^@o3Myz&6? zGdl*3KYltvFAOlOQJ)&r#7XSEHO&8J=1iXvR{>f>qzrbSK%ijMF7v}sR?n{qn+M9d zug_W>%{NA{fiVAfDQz^Wm))IXYr{_i=HHVCrP3g2r{{}B%jQCNU55Vx#7o z_9$nIU75Hs=K|&bkMU;qC;`!Dcxn;*S5QCD<#-;782)ugJ)B^}zmY46qa=r0f~V|W z|FNz0`FHdBh6a8+nDW#-^30$5!@~|>{JLv}yxnh-x*fkX0)Iom?Wd3(7cgzdFqYNV zRXNiHkZaotpN17`0kMRZEQRStgrFoQll*lXf$yY?%#-ZDnPj}C@rwOhe37;Feal)U z4uH!|6r0E0WrU7kYq6DUZj8c4fdA}6zvMmji3HS;?u{tb~H!~pjkY3t1bfN>JY8!{4SQ`)CTW8?*k+C z9p=K{9ajJRDI2-tHh(jW*K;ChH2trEjMC5M;!1v(O@p$DjhwiPXG3hVBlJ(wf zpvI1hi0};!2ZnjeK%)LV=@F}SpRqg<;k8F1zkOhQq8?=7t|0I(y)DlW+gjUUV&D#t z>*D_{J4W^+^tXx0nKE9Hij_&xAA{Wwelj5eQ!J*e}r&7SJHDn(OJin~)dqa1Z=R#Vh=zv5FdUlHu76bx z-x1~MkPxGK;qrrbx2D!1x2_;Als8E)5=PkamjzfUr-K>T?kQ|uiyo&6Wu+z zTa8{yd*QQ{#W$o<1s#_{V%Gwr{?q{ZaSjk-KN?~m9dXSiK(5c{e{%@()-@y^&$51R zyEf{HM_AjgW^E#!uH(;tP?hY8d%Rnq#lUO6-i%*bbrxI*pLduOw2z}VY2g8!R)X0B zPoyEmN9a)Vd08w&fix#o&nmm*JdM*#us`2e&GCkp-Y5+ z;mm4BrayYYVyskOtvt1a_U4T8N$m80ncI)X4&|)c83BXDYTAc;>$+km{ad2DK(diD zcQ?m;B!Yn5zE5x6eL_?p9!P3S$oP!Q`>*BCDGB)lZ;q~?9p#iVRWA4?RaL}P%`NPR zBd4l}Yqv!kBG&!9bE5+z?raxo?OvKa^ZSgl%mDAD@&5g@Jl}hqg==npDDjW2Z4?&Y z7Q72P-|h^4sLOSsnN^jFUYXW;7?+D+m@kw%W}e(F$gpx+h@adZZ&CfV=jw~xFE$i* zLgd(ai=)7j%GXh# z$+driQ>}9Lo9Qo1kJ;TEn|DdKGcw2!UjDKP<{2;D2NyEuFDXo+!_j&h4qV(t2k9&6 zZqw|ai%kH6%Bc_aFZV^|0S1ZIE(EE2;QEK+x zJw3BJ50c}omyV^xA+?Qpb$AzMTTBAbkT=XI)ieR7Ehd<4d_(MPh7T=Yqc`A(PT?K; z)6fha*522jf8cW!3M)s%)&kz z;)rTi`NR~y0*^CaDy93|L} z3{Z^S=7l%ZmsG>OzwImMXIv8%^{QDKG#3FYizAsb!-d5x8+;iXTM%v zO>20MFL9t5vsA3h`90u@4d4unhh`%S=DpK`lgZ{qPsvIHT)2Rf_c=DQK#>E;T+p(RFUBD5CGV?Q9-i*hw3|5G5MAXJ(CVF;kez2D z{<3$hHzKfAc?pV7)>N+dwGqFJRK8roz8T63%xw}d^tzw=(*=q3`D^(c;monV#SR3) zw$I|u_YN$#-g{C6KEo#_rleTmD_{U$xZoHi9{fw_$LAtK?(f)Nz1F2$t+~Y4afjFi z;Qv;gG`}v|=tB*7b)Wh`92dg3+mW{w122`t;;$+EU6JEb{&EvID?-XHg)-UeKQ z#M)iI)Q%?=CDx(sei|9cpc$@}d-q-6&Q=rY8_`!-U4>OL#osL;DeOqdV!e_Zu2l`~ zes_RNIo4ppD5`oDlgf}AT3AkNZpRTWY^1uCmWyiN0jgFX_9ol-{x(DS81zWB!^>4@_nL_kjm^!M}$X5_X?DL1c9koxmV%0j9mtTa#}xT2c( zyZ^_w#^?428G_*FKqU?^fK_XoZ@RE-{Mku8FwVQ)Gsc~~qf-S}aJ3-t13t%>W}czT@n)Yy)KTeoS9Qqrd9!Fr&heFN{vb)yQt-5?@SX8k>{|uDqVu zk&dCva0dhHK}y;yEgSJQfvu|M2sW#%2oOhRCWBNq(kLKXKOm_~7!@BiB#i6DfdXr% zR(zi_5Vy?)v8ExgbEw9`fDy*ho;c|n6#w54JH8zEGa|*IHI3j6%58r z+7MlQ^*lFF2q5x3ssbKqppDoAd?aV=578|Q?$ejI*S?m$4ZH@Cm689QvjHku$;BQq z?^Hroq~$v^XlV=3x8r_tIKg>A5GQrc(z0{Kp`j{H-J6#uA|Tdr%0=LK#ou)8Mdhna z;p@ieci4GYs^PTCHjz8mdJ;iBxOZhbCWcxxAM;O$WM^f@7>OuLXQMeG6p` z6r!;O-^@Df0+S8O@@$>wDSAACt&Jl`# zc#McV#I0#6q)teB125af8ZDmo5Jof!+MlcCot#v^M%g)k{P=!v{6PKe zY~x}o`jFO*7XU$<=eRZS5zUlT{s84oK^-$|u=~}6s#7{!9m-j#lnnew@wnIKnx?_e zknd=Cjg?g`64K)Iy-+;R(&6R2PiSiGaNc6OFK?Y_3-N~{<=&hWxiMt!sIa5tQODWC zUXDPeKa{!V(4hj1a0jjm&QNe_vNHN8uro3B-6@pkH5%Qkr>Q(t;Te+u`C#Jl3kt%^ zTFdeJk8CW{hH*uu+iiQ=U(>FWKM_L5J%Lj#(zk|>=B6vgPty~FmWABX)bs(;k{ul7 zP?GHcNff7Q#%Iw+*~ps(nvxEy>FXsVr~yQiMW%6+}u82 zb$E8YOgKLNHMu`bu(K$QEc{C@1V%3pl?#jJp~LuwUB2^BTt?C%rS1jNowt9o+OT8l zSW}5xratSyCvWrryyJ;sj^G5Gf>st5LPD{i}h6Pb7ZCyenl_FUJ4AEee>0)2yqcG@2X)zk!cNmYH^ z$#t|GLpPZH9by4)QeM5hbfjv|>Q@Lva`{j#M)ewzHmBuEZSlok~|cbds?gVO2d zo(kVWMDldzaZeDE`S2**186N;~eo{ZgPH z5sQ{dbX481l z?95WsHaxxF*D(JLeaJ8p@W;(;usi8Bg3{vxwT+IUhtM?Unu6W+AiV z+^hdb)nA51*?!;SFo=S*N=l7N3ew#zNF&`XCEYnF-74MPI)HQy4bt7+-7&y0%>Uy4 z{JzKWJn!^{9&??s_u6Z(z0P4ZWgN<)-4Uj_v&oBDIwAo{k2i=Gk54*CA`}}i2*|{D zUrr<+FO}OQySeC9*XZ@2mQf)hU#((m`^l*LzICym-{!-`iR4P!q6}63m5k+BljF<1 zmJ@b1Gva3uJRGs*K-h#+N4S40D31Y4hxN}}ueb|vOimu9+S08ns50n~B(vb+hTxyq z{-<#fPY{Zk8g(47vhxQIjj9U2|4$1bwr0m0J*#o&bHXQx^+8{%XMP6N3VGaT4n2P- z2L>G#Wh#viQ<~qyxCxsm)y&ZLPFm${w+K-_SXclFQ*w=&7jKE)%nYprSVdRiZgk%$^xsptrZ}e>;V?3tEcC9=7c}mFL+_x+t-zhIp>;+JXfV@YARyM zq^P99x;&OU*<8f#Wz0968VeCS;GdYD=(yDW@;*=`T!N9Pbb#|-Uo9^%91DB0xw1Z$ z*dYLypI-arNbZPDdHObXY}W|z+qw!lmE&6NLb;upNZ|I{Y|{8PNW2`qHdtY6!hx;U z?Z|tg6N#{~!%db}@RNis)Yr^^mag~6647V`eee`_;x*RG@R6|fG)v?wwT1eKp4i?) z=gRX*H9q5wo@+bjB4ujJJ69pgtfk648?manGdfx`Mn;;uXs!3HXT<4hMQc?HWAEOf zj7EP{prw_vzmNH4;i2kx{7kC#N`So_Nuu_N9R+fhQmjPMBL_CVce)gqmIg~)Tbwu| zJ{3O{ao>r>^!6Y zak|M!s95AQ#xC`BIVh(DQ`v@$fl(S?=!tIcPH5^-jGK=V9RAwOOXpu3Wt+O;$3fe2 zm4_yB!DBabn#T3k8Px6j=4_Z?;V)CyKvd!JknvtZ!OY6nyXa`au@Ee(qNTM~cWH4u zJBvf2q`wCVyd|P*Mfr$_#%l}~3F}lapRPHLDCD-$!X1~1dW?qGci?1%P9J@vCu&G%1z*zSyW|bn^9-m zVV)0y9^&TOA5z-T?4D5q8Dk;5eyyzP#K^7m?^*jg!+&M_U{T?tvSY;sFQhJ zSjV#ES&JM&8AkW7MtZj*b_FXEReW6MLE96=ru9?P(;RefRks2CY7}EktjL=+2c{BT zXX#nERO_6d|Fp1%nwlgaG%7#ZLX#MBqk55bY*g#@XLw$Naw;-Q+V5jZLzKD4xnXQg zzj}89LE^f4#&6t*=0@RD<-UDCs_OuinHMo)ruHeUNT zuX>YP+3Ne>oU$zENI^l5c~=(i9fR{KI+xWMqdJETZqnO1wX$0wuw@+rw}zVwyX$>#H&ZqIRRIB28L@4{TItHbr-Pf=9 z5lzGJC7lbCi}%oj5vf)f9%h-Qv6W4}#WY3fNYk4e&taC8IJ<;RZ&G~5eRQ;lk=|q( zs(l_}NjtkDY%P_v)Kh8cJa2DswkmH*rQJzD{xnZ)5zgE2>1ag>fKi19aFPV3cki_QL^}k-2G0G9pv(Dh5oZ9Ld9TnRQDG#V+GnlEgUy$h9j)74(wy&0( z<5A!L;fL!F20x<_Ie$?K*h$0=9M)#=Iw_3W4jm(#mF(bmmpv+KXpKr;_$zRxYRPCd zRfdLxk>too;L{{;Yg(xhILddhs@dsMjo zPRQ(6h2PyLm8lkcuG|}6&(9Mo=}OI*nBp^A(aO&cpw%E{)%g>8l+p-RI$}vl;a!2A zeH(oOx*G5jYIQM#YaFJeBDeWdBiqe7BQq!0hc^ZFzLr30rCNbCMJtQy);KvMg*tGMVOf7zcY zv(n5uLnLoTF>l55&&rfS;Ggn{6Ri!St?_gD>(W2R8G9a;eYGVnG->dIG1J;gxXqRBOY0d##MX9TUeYWF8WfV$h0DO%8h*Aj~V$!G!(yBGS6L4Jvf`A%x7tOR?~p#pij{#E{!TwV$DTW zH47>wi>{}$P_4Yw{e0Z~r=`25vJlrN6k%Ozp0wybK` zC8l1m=2{Hv=dSpp1tbRU)d{RtsJUfQG*e~^j{dvknixd4luZG1MhmAe*{ zRU3Mo8LuAkaL#ZBHc|wFF^nI*rle04qp^J!3I;;Ut(LnD>&c)@gs9b>vy%0%?Bc&uA$t3|4`lT_;) zxIchX-icdn;t8B>ju$50_4^ryuYS|HpUAddCWyqAvz!R8P5w`ksjkaOl+Uk7-m&QR606>{p6^10kS zlaFwW7`N~ByI_MGrVF345C9b@b?WGdY#%t3RB1cG@=P_JGDW&)PtQ2-+0{8C&xr=L zFWy$BweGZmg?oMIGsW5okZ(*kcRK@M=)#u}SB4&Ee&lsroaj!NFeQ_$0kas3No>{n8N!*r9;jtnLx6yT@j_b;*`YgJ5 zsfv^ElNVDZ-v##rVZ~5jTLQ^0M*~XoldH+W@_k3(T#M`WWVs0I6t@>I_3Bn{P7xJ7 zFJK)mgpeEZCge3?VFZ?L5lD9ZymdWYAi6Y?mHMhy^ln5$U3RRKiTz~po6EebYh=RN zP6p+4XXy6#rF?+QjDK)?J#>NBscxt=@H;T<-kHrAvjOFzaT}1cRn92{) z0Lp%O_0R+WZsGw*1{aHN6g_|Nq@aCwr9E@>foS3GT5s6RgJ5;obA1B(pQl|L#Y2iO z$QO3%O^tlNt;3OW%c4ddf2m1kg2KC?H$u^oG0)zZPJDco>Hqz2+Jo$pwPh|3?}Ya% z4u!2qS85t|YV7U|Qhth7{{9H5mwJ|;Z@O?wt7~qq4Flc3ZLsJ1g&YB!EjI)v@?+%j zaKD6&fKgr`2Pe2d{xrABB9dK+AV(@T%Av1c4&CG>K`Jv&zBeM=mPo7xlB{P#wjfwJ z_%m`MZtgZ~rV{)hs-Hqo;dlECz+>q56M{4=J|wgrh?J$Wtaf!nxr;?FZTG`Bw+}v@ zP=I-O@kFd)CkNixszwS?@d4pii%T5&O^H3-Lwjw5@#H9QJZ_XIIyyK(*nuerU_o%g z2AxtA`cem*Kv3RA$(IsgCL4p9{m1lK(viC&E4DzUB(2-*Ko#8yZiNOEWg*}Jpt`E6 z(qVI*wZHx+Fzd-8eUUXR-~Kk?^vsrjNc=c`Gg&$ z#s~X+MUNN=wy=bVzR2XqHd5!hRu<_YAqut~H}@T5&%R}wo-{@{`Sdnu5NT~c6|&v~ zKuhJ{CkNN**A1n5`03&HT(54Ic#k$*6_dkw-(xQ9WTB3_Zaz_v4%R+LuiW@%)5h)e z4v5^Y8UQ*5iYz?WR1ZB~GHZTwmh79d*rxl|EhSK-k1t*0SXd>5c;K31QWJ?Z8h$?q z)G^;XykYfc4~{q3NVi5hrH%}CmK(#7h_r(VBwKemt%@8A3j_hw|g z%PSFvsuhQesD}8*m~rCVbEBQ-~%s@I2>U&?zLNaZq$3E$%;IbAO)5FhCK6ET*XV?DM z1*4}Qt8L|OB}JHM0Xdyl9X&uoDR~SB#Wfxh=PqOV%TAJmVmaX`06KK}#J(IP6>;nn z=9FX@2E?Y-6VKIDzP^)8@9Fg&+Rib{gJvvEstsWxdOh%%J%es`664dl!<27uU5Y%o)1xxM~nJ&9gl`NDh=NT>JG{0yi84?+!TD zny!Ev43tbMRFgyNyM1Tcnq9Q`%fZl$!eZHK+H0u;Wq-MDoz`8amX_a9H=>Jd zLDXdY9Syv-t>sjsE<7ySvKt*{*18oxHhoUcJz{sI?5uMhii%W_Rce(82Vv-qCt0jW z$Sg@_r#hA4%x56PzSHlyzdN==>u$s5oy4OD=5r*E9?<7IE#3q^dZn2vZypVA{NTs< zAA*pQ^>ikJ3}SMnui^uS10psKmHeYNHa4r0_9svMQ#$|GaF&aXKnq!{Gw`WHe zG+K?I?Z$s#7#`DUlG|BDXL2bcXIp3|2I;>9HEDl)@DQR@nTsSWWK}O_8UNJx`R;2P z>qmUd0T~u$J*IO#npEOK-u-J6{@l>edWS#M*_(sY>;y;(Uly>VjXQh82s8xHL5nTpDI3^dldPBq6+0F5q*K+XP z_RtLam8+AJQ=qqR04s%&$`=;uxs1gFcUb<)KvE1VhTDgN281p9ipC6LQE}BC%aB-D z$Hc__w6!&aaThP>2qkT1Uwmg!X9MZ7_9}P}Tf-2_eVN{Gy17r5EUyi9*e{`MnlgT~ z^?RbvXM-Dau)8>4AcIEO)hPBr@zzUfXP}it5)-!k$Y7xgS`Ho{k6iAk%`|8+^Jor% z)c13{UOKXG2p92Y;ep|B)bEYtQTtb67W6Fjg2&1mxbaA}MV9gM*3{h4L^Jq#q`086 zj?UbVpkp$!@?Pk$#a7Z){Sebx`Kd$)cA!XNI`>2W$piX{@X!gB+yhp0&325LCF^I| zzVGqBSIrKsPgml^R+qWIp4c2QW*ka8_GG+j#wSXt^F@x$+;5GxbTo^a+$PMaX;%(I zEdvQ8qC9n{rG+6Ev>?LEyT(I`?ZHg6HvW@B6yxH#Z`KHnrE4PK)_oMr+q;qp@xd`o z4lb3&z#NzP-m(7f%WyLPV&~(n40@3lU)h-Ilw|NU)uBF=n>` zU`yE@2sfVy{$NpocJWO`PjBGz(E97}97p~Rk%a5+dr}xJsLQ3bx~5eGcDsE&v(uc` zVT3>bT9x zfB=lt@1vTn*KF+kK;&`$yGPaQZr1#~ZVwHOoR1gq7bz!xjH{akkB5Kvw-*>!6sS$i zO}E3fKj((pHT0#o-$4eN@yf?r8=_#EZ#)5Njo%edy*O!`W0hzPjj{{l`an5=svZMw zcFJOM`%qNg<_os&g<4P0eHl!Co8tr8SH62q>#-O;Kab_Tx>NOielZ9EJ_rYUb8qKL zAWb#8`7Icyb~2R@eg}>+Yo2;n*pIwDZU7s@w-2r{7MsJ(iiHopl97DqAR))t1=xx( zuPqCps9FL;-;Q&@jj=$6?e&o(od8Mkz{&aos2tY~Js~50!q$5z$q|w0KFMopgk-S- zsks=Sw*ck~^E*vE{&FHegk-DY^a)yGPou|PhjO110 zN#Osi647P;e=8~VR1PN&U|;xlcf7bCrm{y{bnLeK!{tl3@kT;XGbDFzT#>B@rI7+1 zJL8L)l7|#!DGg{snJVJGtL*{9-eeP*Pj~)DP+>(y0p4ZjhzTpqL5z;=bmkA*6~^_U zl_R7+O9`ZDPmUM@T7Y~yh^u3 z1Zf%p@=T5zVC`v~LjI8K`zyNk>C@Y-OhGnH&0Hp|KUH7UoQ_T$m6K)1(O}!r5rL`3Y{W371S|0J+A-XBNvs5y1&6f5CFqXO6eLVQ)D>6b7a0>h>V*kYEWrW1RS zy7~|D*L@DY0%tIAyI+y3dLl2^e6qg+kq!LUxJY?H-47v^F_FpY-;pXVS!9VWK!}?4 zP=B^e9sTN6W9*w(g^?;`W1o0uoB*1im;EK-Gcz}$#B{r2CHkRIs*eNd z4N}R>TomAUG29@ON96uN)ZXC)WmFIQ%6_0RXg%YWsTo1Ere&8o4qa5y8m;_^r9sb^ zyuou}pdn+Kh5=4QZ@Vf#S)G?0j8goRKUeIybx(LaJg`x+vm!R+7XcPJ!vPWXI&EGG ztS{Q*Wg64OK2Ma{B5(>rz72D5pEjFBwDy)N(&hS6843(P$!H=V4TY$+8+%zVC#56j z9Ah8Bku2}L?f{@KmX!FP$>z$BI>A`UZ3?0P!ZdqWDvqM>iwjixne;*GlGqA5Z^acs z+{zZ*Oboplo11iQ$MqA0xbK^w(1#&>(U~3mo~lL41(=2b5VxS>PcHo8s*_g)fm%Oe zCe*&>Nw(*`=*XfOXV@-bBa=O^b=~r$VFRRo31CfzLWi-jmd3b%YS(m>X)*E`i9LK+ zGAoLB3bd1YbiuZ+%v*dy?1ugJ{7LmlUxmqShSFH&T>mli-%X6FLL%t|uPTTeKl#>t zD-2}5p{T5dp~MGHxc29Ky?{CJfc|N7nH+ zoczstqN1(acg_p_3dVhiI8`~CL^UMm46#&uS8uVvW1q}e6TrEP{(0%W)NO9~x%4g50#USPO>lH=w3Jt#=R0e+)>x+R&lm^Pcp2iGi{hS{ zx9%GyUg|xg6T9!EG-+7)v*8~6e6TK%*)XTU+g#LxZpy+Ma-8U%OSoJk8KHKa zNy#2ZU5(TvW)|I4xP300=hv+;b>`#9zHDo<`a+3*(e_d2cit@OApDoaAP)mqzTrDr ze}}3Kc|jbb@W_ACX7#!GKS;E;&{pO8iyn&2?L|MYL8g#7Yd^3n5hqNqjF!7Z{e7M) zX>8rwfCv^Kbw!TNk}}V!R`J^q<#B%%#LIouta&a>ojGO*34grErIypWefct(D|)6k zYOSo8!DjHwhtwYHt*vxj)o)rFC7fhu@3D9lG8Mw7n(w?JOD*J0BQiB}3V~z) zYUbt$^*(UD#!;}c+v-?1-R9!TzT^k|%wCwTB&4Pa?EiONgnzL;CVkQjGBUD%6iJ_! zkDJ%10Gr3d%5TLeRK<+zj@uNxBwDXtzZ5s{+r=Lq!QLPxw&UQjL;VS*uH45ko~Fw& z-gC=3;q_OFbfS+g1Ql~5V|53L>Zg_^qjP*oP1tZRo444@nI;olF$W!<`&-ur_T}D) zhKHTp@YePgY}h|hJ27GzQ#L@mfUGpVN{)oeM&6ztdL9JY4@@S0;eg!X_Fy6JcYv-c z2N;39uPhSWFV9+ZUCoJD;Lo68L1H_xBCxr@8kfnTAe#LQ-je!lk9eaUqMBGL^6HB|J1Vu4t{_ za;Bir%#*Pd3+yPmIBWX8-m$@KPWsW-Z#1)NRlW;BHQv&YImPy&5f%0&OR|(gHJ;*1 zB*Yz=4EIn-|M#<|hT`>?ZiB!v*^()_l)1rDy9E{33@|PI#p=yje!aeegH1<4X>)pf zm)Sxs`}AJ^_}A@q>xp`wj;F`NL)`_X+5lCLjhzA*u*Qx3b0|_+QzoE0jU7r0Klg@H zg+1cu*#7>0Q@}u?Q#k4^@4f_Jm)i|3ghDfK>OE5?9=G*{#HE#yL)DRcQ`lcvtH8={ zWttwid~Qo?*YDU9*u%#q@pwyO)l8lIntQSU%`5W#s1Y>>&zD)Bm+Z2Dy~|;JnW_}A zF!7-KOx-}{*!F z0w?Uw7`e`m7g04NnTuPcXk^LNK{t#uAI2q(eUT80rLYi+_#ub4UUbFY89FnC@% z^%!~(*{I#LM&bY)`KOi9O6QIG$>AlMCEK5d6hVPMkr$qgb|j97<0YYt)P5aK%U|2h z>@_9f1f`{X*$w=MmAKVN8d_DGGo%FjzCi2y51T8WKB=cFr0ZxBUppzJevF?P2&Sbi zwsWb@`mECz5rqTw;Nz<(!9;WXs)+kq2`Tx)Y|(z0g~_aYwvtaHK|Ug)K7T?I9j`n| z(Bp9RGKF*QOO=zAAEM3R28D^0mHz#E>-x~gI|$+y_90^*W6wJm-t;GE9BAHqEG9^w z*VNQReUgm_{PcrJO%1b1s^-2gEO~g_UNFBIgZq4i2D7!{>QYzpOV#iE7;Kp&H_Gkz z6lHOP2V|OMyW)0e81!a)0OZ26ql~MTjGPfOPkn(efqJ5<^9utQ-#z1K z`9?v**B9U9{NkSJl6{wSuUZn_mI$N_7+&cC?x0@+uv@W+4esQA#5af^f}RWHO{yUe zp}9gnj2gB;(wMVt8SLKHmi#7E(|P~MB1eDR_xBfY8hM~xvU(a=*^;_6IxE}Na}qXt zLs|Iim7Ie?2rmz@i>QQ$(ISmPhT%%nVdjs86xR$0=Z_{IFNTBc5Oh2ntL!;rV>^9{ zk)r$x9+nvTTKjHx1&zf8YU(+Yi@E~d8iYMyza8^AGI+vr$Yy0Yk70B6s9E3(&IsaE zvd-hxdlr(92EDU;9ya+SGR?h`abscPGnGCqvrYPzrg|i=mGu&ulun!C&6BXxMr68Q z+z+y{vhEaG@Ot>Pt#=HtVtMR)Z{Ed@!Y{tUN2Xr(;HxKiIb0<5X8ktSTpi&4qT4J$^CUc{ z^E_CdP|oG8W%Qsj>$TswDHIF@MN=csm0CZM(!|(m3mv;T5ASb6n~(98j9Pqn6+>1-d#U~nZvMFQ zjwvt2y4_uVi;F8{#rDIY=GWml@^1-yN-4vk(6jzTxhA#o-kXJ!L@&dHb>*Y&Q zw~Xgmu^7G4)SX*cr4>di;}UtfKPm*X&U*^&r#8Q3Hy6EWu4?NfknWZiy6cLdsyiV2 z>oGOql|K&zw64s@i1$CbvD0++G2#V3S9Vk6Cg7mQd2BHKcZbxe%1Pq-2mwdT?B1W7 z4UyU>w>N3U__PUDD|>vp%Gu+ttW$-dV|yZ?JK5~_aw-LIvAwbyp-~a~CT7Du5AMd+ z{+1IziJBsO^{kmLzA!%2MY}R#vdv~Q-1%DDV6XbAE$pP5a_|x367p!K*ZzNH6cVof z-J`NRj`#wRf6(;+vmjFvNI73wmhG`1$ri}a2K))u8_87`?H{>lfIqh97^}GP+>aIg z7B85Dx_YyVW;5Ipu%s*^4>Wa*OBrOe2=(Ls7B`>UyyNkYth8|y;THbWoPO}P>h_ID zrnREtWQv0CYXSmqGwC&a9UXmDmA2nK9|>1|LeU}%U+$b4kGm-}DwT9gRCY`JT~MrQ zZ+p#Y`M0{_N0x>9q;g$5s-3g@odWr-kITEX{e*Kk={~1&NLp@FwHCFddr@F4h z{X|)~_X*`>Eq@orJg_+sMh0WAkLc(ImZtL9mPrX`MT3L(L^gTeQ zY;0>Czsa3_c(1GYKwn?ItH08$fkiM)L$3~RR?@_Pse-lnKKHux1Tr9~=e?JJ0$dZU z^Q;H@gcE4@0;>pq+xMxFb)`?+Kk2DDQ>$=MhK}3ZmY?b0#>I`kdslJzk9MzT<$Px- z?S2WJFnF>PugIp4NZsJ?)0&!updu{-cscmV3wVc1F>u1teMFXTJPGT_d+9+0u)&EI z^kaC$!Cx0oSHyo+R}iUAe5B=<(5o03py~?govn7IGgmTRD$2rvsQ_Cz$#+oA>9v;t z{*SwT_Z7Je#Xha;g);IxCCd=Z_Z>saIxVx@iC3WKuTZeCdevFBlKYudub?}GC#7@R z5`phyKdQZCslh9s|6WSYzOVTKs+}v8BIQG8eAayppEWG_X2(9GV&YfkH>VA1#cy zQ~+;2l>Zyxbs4uN2sM!cTI!Avedq3CJ7#?2`2S$|i`*ulfw*~eEJB|Rj3scb1BxiqRO$Q#Dw{K z<~g<048D0P8c#aT7C*mw<~ijkwJ=}poD$|mJoOZSxa2d-L2`x;*}6?b$Wp}wETff% zQ`?x3$xp-|`;upS59}HquUQXuR;l>^=t0D)(@vNhlz*6_2Q~23$xX|W?pcS46*ta z$8gcbOz7x}z2AkdpH#K}33Hfo-}gXe&2XxTO2l$?5%6KP{Fd09Uj}~=U%(lR6h6it zJjuBQKF}KJqbz=BJo5JO8JjRaJx$H&Vu*97c=G>4;{ZUIC2-SlTl{-Q{Dte%Kvl<_ zW&K+<#x2{nB%tfoZJgI0BKTD1#dF3#Tp|!UFyJ4!WO?G2B|pI0ULfH0!D}lZ%EY1B zgy+OdTQp37v0KL9c!@u3#Bj1w=tUO>6~%Lnm#w1z4D%1QW~kAXvgZvXV1ALQaKgb> z=*SU`3W5ADjvvH`g;mtzN5*;X zgTLq(5nI$FG}OPDz^Ad39o1bT;N?9y(M$vk&fa!UMH|R4D7DVx%8^wXV}ED zHBB#`oGQz_d0ac=N5@Fu53Z`J8h!D<`~Kfa7%u0FHH(Pdb4w#L!{v=>{fXokIhd)` z(2&;9z$rz|>kIoXs(*Rc?72wAWdOWC8X7@Vhz03u4pFmFTC43qc9!b+2=)Gv2AdbT z(XY(5?#;}0{oBT$ki-~ncWLpcF2b1ays18nnOViJFxd>6&FH*dtwkDuSX8b(?R_ed z0P{)9&8-0p??3(Y=~JihQ{XpJhgB!S9xZ+S#LUd7%_hcy!%KFY^I!QD_L6R4kLvjC zVa*=%L<3~A(XejLVyT;!fVE&yfBIxYkOHr#uz-`ri~>L~rgd{Fgu&^6B48~IcXD!i zbbdafFxXxVsk>;qsdMh>J0oY>%>K5HeHZrpFZp`3*nl0$B>pUjbMu zIK4IV%74}ez!tNdyYD#tOAiEu!NApK)aGWw-xdw~#0xZiw*N8f3+#Q~$6W&#|7O5K z4@9k+Q#eni!Alm14zvUf=7bK?im*^=XxthPg%T1HkB-lOud0D*UZs6a;}bo2k~!=b z!RMg=&+eD-r$tpqK`q64fkUSV#0=1b89f-j==Oln;0K+3+rNRJGeu?b$(USOw=LfZ#l0X2GsyV+Z5+$0x3l z6#0IGI$W5F_h!|?`=(n>K(ZDXL{+*&76ZqOmSLv3SgZ;$R{(SZfRa24D41#*-dh>$ zgB~s4`qKRyZab<9*>^s?0w-OZDc>ELp&UQLPGrj3!U}w)90twGkt2?O)Bd^I3kR7ai<1g^0{Q zyOg=r|61LQ=`5iXK zqH+Yh=^E;klpb5sj5N>=`IYGQ(#GB~VBYss-`DA^lPmXI9H1AX5jwm1k)a$}opa;+ zD8RYCLg15<#ppx{x;!a-L3E6=T+i2E-h%4Ve*ELWE$~}J8AOsdMMV#zj%g@3$%v*M zu)hm4q^z@I2Ljjmaz*t2ti)fu<>KP{!Os%cyp*#*3Q%3MJ_PA0`r1z7u?GjZSNcMG zuS%n*OemFA3Du>$O>0&i`TkL4_2szWZv`Bp$to(fuQ?jmCc|t77pVO=@6K8`&N7%( zRVD3RT*iick8hq7&HG$6liohbaR=*_dHiu+Nppc2Qnv1x+-Fut;8XDW{Nym*E+CP# zbr~jpbXA%d;lcq+69Nd8v|d%73APz|83JOn=Cd<^m^2^k z#D7_7ylin5re&wz^-q0mf_q$_A6$i{VF<60a_TiP z*QubK^#!WB29G)6BQO%e5~5odPW`Hsy)1*O`7@5ync7$`hq$V0syur<7_AZCs9(sn z3E3_u*;m9cL=9gf1WvL~VQHyNeJGnLaJaifvj6}2twXKEMCPN)Kg}`2px!09$_Bo} zjn_EnhdhFNdwYYK{Ap-~N*3!u;l&aCiFSI9d=%!2{T*wLm!!#|8xzIKIvJNVNeM<| z&VG%88JuM!n{!=&_JzW9^Pf&$+^>Ql%4Q74Neq{V3#i@{Y_ZV)4b}76q^HMy#x;AO zXuziKlcHk6sIWrjBo`LQAE)=utqZVD1(dSt`WJexkI z+1dOWL3P7aQn&Q|=mLp*ll&^v`^m^GPW-ec&}DpD10gnY<$A`XWj6Oy{=CH_r;M@2 z5*e`s_DQXr(GSmo+PC$tMMmTrcdxJ!k^FRBSz<{2cmzx&!44zM^}SwOiJ*{?Py&)2 z`Y5j(aiNkub$uT|@ccL{vt%X3>jAu=oHn%E(+>Z)U|AOkS^K1zx1H`XcIXbw*YJrv zJg;eJ@Dm)_ta1dM3r=oxjQU!|R8~i=1e+lQelNI4P&M7=H&qf1O54pwvkKr2&AEs-;#{jo$f|We> zzsGAO!d?JN|2pmmL&BpjRko+8r>frGDfU2g@cu_^uIT;@`_LE8@bGYR#liJa$!!kn zbsBYzg6xU_#WdcRAQELcXDs(LN*o{FhpqPm{H1HMfAy*)A+5#t5{3$%FY7owr@oo) z{x;acFGKt0RxH-yQZJbN&Bx)+Mx)g+Ttc^2!bwTyW_g88;KgF7z=$lMpfS0VKyue| z?H}P&E2QVCXdR#6u<08W`59z)H=i!tZo`)n-w$hY_`9&b)Z3J) zH#%z9{AKoD6NSrJzUfy1Xpi-iV0jFZag^v^l=B=xf<2@O+ zoQW(S6)>ZFNsjndQCS$$rNJ~`wql?YSEBEY%kBW3K1z;L+P`h-78}j&eW_|(cs{Sk zw&j2}6~M_9`6w{GXm(N26ZYg(ZsUZLeaKn~cbYlKw&lw77JW%eZ@hepu6w?g&BRbh z=-cPQ9`6@SzwxFze?!$nSZ*`4i~+f%NUG4AJ={np*{Aj3BJ*)Qy!6essQg)e?2*@x zk4(_`The~06z|-aDZLqk;R;ljS0<-hsa*w%V|1swi;f)uF=M!4+gyW|MZcZf-@L4T zb&O<>3=U7A(bc!Y#8}UCd$wH;>Z(Q`T4()v7*O5oN$+-hwOEi1U= zfpUV_n%c*ihtqP9hTRG03K#e5Tw{tI|H8jpCqcEUBInthP~5iN_M)45v%?G_*hbac zvh6sbPxrsKEt@Hj=K<-;IIUu0X)UstrNsEv9xKi6z?%;ldQ(|WmX6*2GY6OqL%7Rz zoJj82LE9sWS_i{24|1fgKq1cVNi}MR1CUZ4MH9^13p6W!7$J@G*%lEap$(%e(=BfE zH~?f@y{ay+v%C4#$mx$7z$!pyq)zy9#gD)h$HiX+Q2ok8h5=fvFBRM)f)w)0kZg-- z5LoKW)A5Vq>-f=@tsj!?Bt*HM0>{y`4kV=m(Y77=*P}~+U1U_6ywprk=fCFxlXw`u z3N2%=3iI+2i9vNlI4et0ZWBHa2Ygm|()i3p`yI4W$R8oR8`^{pOd%aL*|vb%G52^g zFifv#mE7YM=}aDqT-V!rOHkw$;=)?!${q(|bC@L*jNB;;;jD=d%Y6-m8$Np4T=HnC z)-%S48SDV&-tRoO$kFriPPfUdu{;j;;~UnVrIQW)(-#p{Sc9soE(EvhFOO!{TMPfT>jVc5< zM2tkhL)Acq()A{M@*RK9br97|tJ|sGEXP*_-jX660T6t;db-9J7p1(U`HlQqzS%9* zsT!&(`T7cFDuE79{s7(1W)iqz?2NPbl{KL82yN7gJJHLrGd_j|IF@d-gF1@LZ)bFl zC=XLi&hpQ1phkK6Ufc@WVybfyD5A8xmjuhiOa zsUl`DQ^~t`o@f-Dr>3zbCZY80>f(BDgjyA5WlMj|z57r-oF3ht6jHLPwrFjJN|{AX z<`9qC9DVcI^0PPm^RFzI9GySFoa5>zc^Td(FZ=58;FQ}ZAepLy)f7Kw=;SR!CLIuH zVm!u2&VX4*;dkwzY9>Z#l$q**d$y+@8?nFC!6h~d?m%jRarIiC2nOseuk+d#$=Sie zN?Y!oY^;?uDkLL*AR>c+|9wLgVHtthG5Gs&(ieHuset(kpV8Jw)6S3)KwJgP)1KeU zvjVi$N5cOcg#Rnwa7s4zi3v)AAxdSO(`UdOfW6+(Lt>o3{Iq zWmeJ6joTi!TJ2?&a?jU0Lk0Rf@Au_Gfx{qWQ^&mY6}xl%_8r;Wp&W9-Qf9 zDP!TQ?9v6(d@rhfN1iQz3fuQQn{ZPXsFC*Vw};@)Rt>4vZ&W# zIOq#)-^Z+wh{zB|6y|weKfsb$Z{JLcG`6P7$&VejuQl3p+yuXg)>LHm-IhX17S@&rA?a1eBQlmm8 znPIRQ6Sm~DFUVKI?@%YEE!hamWq1WoWAvg}y;z`5y=(F*q4sPh%QvLEWR1*3>YTeG zI0X+S=#%5Dqtv|tHk;Aog#N$uV|1>-7cq4;FD%Y0DtQv;oVeRz1LnOhtKFoGye15{ zUse9M(^@t*rPYb}Iq;$<{}oB!o0q(#q@{5mTL-x-N>urdUT-qAeN1By3}tUfl=9+| zlau{HGh6Penuc=2*A&o)Yg;IC%|}j7-paq^F6ZH(*>AN~j0xVhf;M&DS#nX03XeFH#pkAcY$fH?dg-@9>KGd%hu@GM6$9xBRT+4v<$b%$!R2f1y00Id1YrC3 zA*qy0B>Mup+2qmLH?82@6)ysvH<+5#C9fVxiCe4*33G{U7{eXzUx?TO;SppNJGIL4QNM268tZPDiRe_%@S z&4J$4YN1HTcls&3i1jS|7He_~OWp|^|A>D`3JekY#(iMOcyy?e0U~h7nu*mIQ)w)$ zT85Xq7NGx*$1k*`7)9;Cd{l_kW`KSB5B+hDTDUI!t&J^{O(cHJRN&QyVB5i4juEMG zm#f*CW~l)w-d)2(uZ?zNbigU~lKc&_JsEnlN!!=ua{dmbQ!|kHCLa#qBPAWaXERY}`)nTuDp=v2$-u`E$jg z%d+maH&ST~4WFRlOi#CnQubgl@ZZf)ce~x*0^y3EsOm|x^!mQ#sgh7Ph-G0yj6Iu+ z$ZYXepeLg|r+&Zj=s;*q#}^aB6tRniLz|V8mZ!qSYGv4*LccDsFY-I{iz}}0#Bsj$ zz8ymS!Syv24VDIyvD2uC^aSB2GrrrdO4O@E3?dsmw%66w%|ld*y#;nn&kLungFZ z7ZD;oi(02&GQR27VGDC$D)7W_e}1?8K+9az8tO3kp?M<~hOvWeN`SKp|IAN5hFO0# zXF}N#y?oDzrTdi_l6Nd=JsZ6>p{F9Gh`3jJ)M&8s1LN-{&L@vEbcbkIk&%Go_qHQG zU_tsZBP1kbjp{of(sAw^M&l6*?Wr z3Jn~eGP=l=xvQ)=^g-M9v3FgihW9WIwgN!!Nuw6OkrqgQ=*t+yD_lXhAmGvMB=)Sr%qdUT7A9xL@Ul}^2thb=@#UB<1Cj^E}banN)5h*@AmV3ZUU zPgA{5Pvg^-tP@i|X(?Kt`DXPid>Ly7jrx2}71@1AUI-FT75l*%0Q40Ax_JjQvh1iL z-u?CMSOy`hf?~LJbSF-C$csf^q$yBQWdp7efpT7ZCN(%+cvbqFAJ{ynLj^lmEc4nA zICoE=zwD+_=PrIlc4Ys?B$V&A^>R~3P|66+8-IA7nii)Cz&q?{g!D)a;>Y7XU87;U zKHMrJ(!W8I&da{~*5Nl4H7e|b(wbSl5mLk(5jY&+)b z@HE-G?->+H`BPFMc}Y&rqRz2%I?s*8eFohPPKX}GSrw9Y<<8W2m<5)|RU!^0}GW8*u$Dprhd}X*m%)vcOq5Mu;JS*k@X9#@ACe*8oQCp)9COZo-B@As-B7 z26@%_o+z(X55t43`RJy1##FrSQOo4%3Q11f=Y}!n$V2-D)-_==_VHbBgahZnos!Wgy$LC$b2>nRngNU7 zn&$of2aAsT#CtbqSZ%TQ*Ra^>q3uMLR;WB+&MtwI(Vb>)xm?n24SQ_wLJ&w;m83@# zU*2rssr+0L&Svo|#gqEn%ZKBL7HJGbhZ1ssLIG7AI^R{FG>bo;gW4qM9X)N&EO6JP ztglb{q=#_(*~h)<3Yn!v`M>9XXUt=5eQ9yD!|23?rUP)*87Tzg``i7)1TmSjj@swq zv5!v2OGJArU^Yc^R-vY$sW_|4;5p8@<|y^xjQSQzh3;lDUhVJV8w1sHle`!W7#9mS zZd><-0mK0O?R$HcMWWSM&3V97l`FC*pgduWXX`GT;ZeYS%F?w$y)5UYr|JeWpEXVb z$qlqB47N73-k?t_LPurKq4{SW{5ItHOln6ub*-)Q9Uk>N+WK?5k_h={C+KrxmRQIN zIw)mtB;J3R!Nw5Z@tIVM&OVzjQ~Y;_>n7#zj9qU$+N==3^|Fc~YN&rR_7O>5%ab%pE8`xvh>DJPjbRko5)jD*1$Y~aE z1nkWelEU}e1#iSejaoYeBY29 z^x4%8wdZa4&8_}Z*GiV^5P$q7uU{pNUkFX7>k6;_sIhW-@`#>cy*jW{sF?MI$}DmD z+9MCe;Y9n67qi5r8-?d7(2RD6JWiXy)Ze0{W8)b!P` zAcR$_VmQ3};g zmI9L23WlD1pwD|!vC-6r!s{#VHsSc(P$HwBSL#&JBVn}(!n90FCipcdsSKy5H*reg zWxBAl-|-MUM?4h|p&0tJ?0|RS*9H{f|1_N{8@tDkb?29m+yq35J;=N8nK2syMo7kv zSt|BGVQr1u`2v*+>Oroy~>wCBT(V~W`j4Ea;&cqkUXrG4eg{UZ4O&NJj- z`mlCx>#iC;X;6%r@kK^;JdcQE=R^g_GR zXI4GL=;&RGEIJnJ4}p7WaW^(~iri2CW$S1HXKCH-QN;?&)fS)1GC+dfoZhy|#pz?@ z7u@yctgUFdf5|ca^Wjxjmsw?5)m=n?Kec)1^!n$Gi6tBYfYH}5SO zfA;MRlx6yO^7udAW|4jP^$+trlhEp0eZcEZ+9v^v?TfvmfHQRj74hz`8^e7bWi@7B zX_dN6orN%t%N+9E9Lr6Bk}GFRxsGyZ@~b{ntnDladH@^eY0-ZFY^VELjF7$CrxQ0Q ziY|7eJ!`e9FvxeKvL&IZuQNI@s5wZx%09Corx>#7Md^DlbBb){HcCn13bH2EM=5d4L%=JTud#D)RPw& ze(flL%tP;Be_zgzXD4>dOyq_NrfwYJsR@1zCYlO8MK~N#LZ6uZj2t(r+FW}nOhsPIO0N_O6_3-sQ6Njc6YX5D0=6ySLqsWDLAgajBsS_qhISmJ=-VEEF22)2Q-T@k8Ys7g=o& z-I?74;cmwqoSl0wC2-Z37CxyZ(qowhxp9wE?yoQ5iLWdfjA|NcUR656a-1vVt1A+l z(03V+L8GKGTW1>Ke>P&kgh$88wzi7k-+uY(=ImzWV$d#m>Ee&V_hw`k5fsoFoIEnu zbTX5L3u*0E!1nYtiawo5saMR=v-cHoTC2+mWqOz~R;7sKy|b;JF>@+!jkA#D4KWit z_va47zu)GM=-c~RV1aDEtQnCe8e%U6Jb$|-x}*z=49X{7^ZbSn5!jUmS zY#u+lG>bkL7Y-5`*H0?&e_YH6cV2){_6IBw?y=tzX&&DB=jfdFq$b5qXkn?b0k)&h z&on3xc0wb{e04YL$pM}F1RA4AkgOHc3=Yi8S-BH--@{>HVKG^%{91%H1%lpZEj5|j zCipEqVZ6qN2;$mI>a@JPKZuFjru}zUd9;A%9Tf8W;w_TZty(Wj0s=Y*@qmxWVkO&G ze7ogPJCw@3nSHk>^@U@+FYv}HLu6cE4=7%C#Yqqj;uaAq5ye(==x~k?hCK-O=FEnM zah|h9@DVD3C;f9Z@JmIP*^g*5k58$eYrR%Z@ILuk{e=O}xfs-#urw?;`>RtK?{xj* z2NM%DK>P{cJIV6+v*fXzm72{|CDK}Li7zmm)~st7!rNVC*|bD-6z9v~+AfHA=mQq) z8=f9huU?u+G;0_#Wc6^yddE@K*`xUYbd`cEc|vudCrvMuxJ58}!F?IZaM-hTJQocr^j{qB#fz}|N` z8vavTQkHP=VwmIlSP%q;9Di&LDWEW~=uZ8DQAp_=JZseYWKi}D(ZOE`Z$m%eMj}bkt@i-_}nO}f&qG`(&(K5Q*ts5rl+wM#Dmzhg6&B%&=YwoV408QZ(_$P&~zYc^O z_b_nf9@Va?gF6NHLL$nSaGFcetd+fOlEe@ZdYqP!B1qid%igQzpp1G-YCUDCik6nN z7+BJ+6KJMDQ_)_z>Udi=al~$EEg!HA3sp05`+);3^pf+Zy()W?PK8^P?OoJRVRGDu zz>rQ-)NC7Gj*t>_@g?@Cf|-WgT)Hr9YRDB7a9>XE@FZ&$r^w@kufx2D<7RVxn#fMv zz{#YjMh%Fy^k8)71)?;1J@X?z#5__WBT7+$z@mus&XET#OG6{d+dZZh+3kdY{-#do((=ohMS$iLPH8mvN=Hs)y-PG4dPC5H?edfu+(@;`B++ zG;e2?JrTC&4>~&B9v4XhhrViQ9P_oB4)%j9?Ev%=JFl}EhaskPJzdM(0-_3j zb^)3xbZ}$_sCVAh^pJO%{<6wF+vxpdszaF7(Hoi?9xT3aS zF07L&9Q&6`g6YQe1tu-@JX6odAFQTxeT*E3Ww$8sp|;_kB34U$;O+-2{p^Pn|w zM2fr8hSk7wqWScst!mNX^@OkAFA>83;9FO1dsKrp9X1m}_=NH;$AvP-)Fk>ir87vw zrH~@pbxdnG-89>?8{xfkQ$h-dA8rZJFu4rw?Chyb+!n!2#{(=6n2Tw9zdyafFw9Ex z%M`epf}g_jBWVqFfaEfAwA6J#jg0EBJbJ7{rzI12ReSiXv)pT(gDU?isWssLHhjj5 zVCb#?*`0)r{gC-BLzi7G!TT?|XrP7@Y9jbwVmW4wU6cJf<=5Od6kSRII@Pl!j~Bwe zx7krSn%rO>y&QJ+9xcQtc~tvBv+W_)^_r}HRZ6(26CFhg7^}OpXCuPiwT0anLjnSL zA@;L>d8~anV>dZWX!2kV=ArN=ahGQqG{(-Zhf5tk!Z0wa(Dr-8nUddjcDp-6_0?FTq8>IwtcjRErM~GHE^k0a0YSz-V zt=AaAGo(S-qJevVOS{IV@``1rRcq&P)Pb^9fk;5UKRo1G<;vg3_6`2%9tje4kvr=k zW%g02Ly5%ASBsuq7a^xf3^;z)7MTZ(fiN({sr~5+l@;@;-KHY7cri`(e5=canfRIe z{R>u`&sNVBFPYG3*RUlDP6NGDvkO zYrkEIeD2cN{J2r@X;#&C2WR@snyKTyrvLlP5&B>DhmaI2@S5WLLibtKc_i!a7hAqn zyZz+Jk?J|2MUs~HkI6>7y9Oo!UI}vzjhxYIX{V3R%>P+_79b!<&^+;{lLJLEC=Rd< z*tp;9L8!vEP#COG7%;<*%lJJHxhQr;@8$1WLiQRHL6rX%|Mnlgg&Iw~rS z=q+Q+_7Fl%#r0SqWzJx6Jr|dvz8!Tw&d1j7v{2Sk%2KTTmuB9(ccDR)8oF=`HuWYU zq&%d#cxDr-tfgp-52Da`r9e$>gwCg8^NP?Mrl1Lwr4MBk_o}Cx)pno2EF|0p=2MfS z9F>gNNAtN7e9@%45)6-(=gZpex-=NFf%lK$@2GLH?(e?H)c{r#&^@LP6Hb_nX8F@4 zJ3Zme11B@zh!C^j!6G)x6L&G}Q@c@x zC|{kwM%zNEq)wbZ8#oW8wPi9q*lG!7N`Gi5wOVD;#vwxm`4v`!@~Hk{x44|*oiF9F zo6>L3H{?N|Xe(piPBEEs*jDfNLw7{iHvUKopsw{2IIF_Z0` zUW3s=`PiLI8+^y^NzvGVqM=N|tTC?0Sx3*FwOjWkDb>zdKXUBSokE*Tht;#8K^Gs6 z2?@_x8yDczbd(-`kxr=+3CJoWJoHM&J#EQY5SN>^_WV29Oe~S$57CYH>w-R9;EXck zz>S!}$W2U@h|GM@Tr!YOfna5qM)VPQrv3Zdfv?Ws{@_U@A4czgPfmNsRzvL}99OO^ z>5;2*#PDf_o&*>tGu49KN?`d6jaUqtWm2oR6g}f_a1B5ThMt1H9ZVH!c)eu^Frz(c zv>iS)eZyxXf^1@f%94 zzWE^@xKAh2;J%GG=&EZU?zH-VOv zmoo^k{SZ7|+OBUGBO2BE=yF3V+cB7(i#JJ@X6hLB(V(c{nB6r_2mx~XWYF8Xhei2< zby8A}kXgXSNDepiX0J&`H~ZJ@w>b2@K>uT@%hvk?L^7LI#-=k|;}o``Ip*bx=;0sM z=y;QehI$U=CfNeV#1X0KXrLa~T~tU@{pM*sa2Yjvh?0J8$f{+r`5AV;_L3sxN+(?Q z;Va=;?VFx6*4w?VRa~-)I2q}Y_p6RDq3Eo)V=|n$gw4&LbsY17DzY;#YM|0 z11ZN6E^`OSsCrNfQr&+C+L;+*dEZy*3`Lrs2xjkngzw&y3p=9_h0503J49Mzt)IB{|`Tjq`Ag zmMeZ2k=wdsLCS+y(166xPEk-9mt+H`aV#_W(RQ(n&it}D!+d>hD^0@}dkccl+((Zw zcWiq)!oPLt>-_;;j?Q1bw88LVn{Pc6$9s9g-dOc%ooSMh=xkGMjcJwm+w>swwAu_d zAATy=1sC&|p)R!`UIsp)gm=(b6qicl?_nXB6sHQ2%2+Y3lMC`W@tzJbZZ9y2-7g?n zYut|eYEcD*9Ml$i)sZSI+mWPJh|msbtUwo&uf+|p6vg*Fs8SI?Uw(G z<@|R;snZAcG|Lo(`I%wm~ErkDxLcE76A{b8yWj6 z+BIjlh1vZI+Jm5!jAda{^7WT^VZCqPs38{}B=|qz=$X(vyo`HiZ%OZ#%%7OZ=+%ky zt%SUS$d*)>ik5jD2jHVdsx>>cg9wH{neh_Q6EPLX!4i$vG0CLKZR z`rG}_*87$`KBKuh9X^W2W)!c=tXL_~2*GYS=glG3vq$eD+F-%@+PFCX${MKCuw`ZF zNt>|uDdqU7!C$BA1ijj1l{|)bS96z`vftcNAeRw46pN?aJj;4t&-+Q=U}-CN+-Tn3 zP%q1v^PE>>-|=7Ap@}XDZ!MHE)?o5u(U2r(&(s1mACOm#H}8*>FhR7SNk=KLiq!h& zw7;HEKRBKtl^s+w$JUE5^*19#eA9KSRjmtYwXsJ>j^O&0a4;OA$@>(Kkd;He&co3M z?|$t?eOyXk48D0|wWbahXLlE63KXUN?2@dfODx&5a~5n~*QeTyq!%nb**})y|DOd| zVDtJq0N*CEqq!q-#e?7J6(mDU89K4Q6$oDo!!1TMZt8jU>wWDKaR)N^s+O2>%KK=ObB;#s z=YEGhA1Js6b9ims^n~`fqcy@lBYl$m^VWDK6sN_BO$ps3|7I&vw)`b>x}RzSxsZgL zkkFzSdi*%6i=hj2{t=~zKj^0lwy43oPX{IBKBrjn{3Or@9i1mF`;s@n!lOP|;j^fV zg*DSq^I;Oe7tAe7Zl&qURy~&f+@q>J!Y>^YO_vF14xh&+wxr}s`CV2;e_pTGI?~`n z)ut!^noat5N+t0-%9QqUvE-eaNu3H8n^q>6;;xM(>sWYiXGP__$O#fL(aK~vs#NTa+P*c)! zDe3+@>wat&Ggsf{OfP#M)qJscATnqxkkVAelXy&C?aH|=lklJDVP``;n{<;h`f{v= zOCL3Mv*{am4xV-E4MWJZi%vw46%xMaHc? z>I4mqbQZ%i#H)i_XCbLYaMgj7ldcGiJ-#m0 zwLv?veJ2)n!G~E`d_2VOoPU%tNM=t!u6N5So1-ON^6ewpdb;x$a#zlMHdi`J+c#9I zt%iu+jFG4+=^VOQGncY_oW7_P&c_@1E3KHW`Kt3tFD!R_hH0~3CA z$s^7W?XC7{VK>}upsGHnu?EhWY8qzD^HdyguO8ORNf$Ui>wV_%9`p^Mpct%bN-Wl8d$sQ{>n<)k zCwGsQlfV8lFbKq!sfNJNRu>ftM4kXU+VOp(iTCw&$jP$QG-&nUi9fapw3>U>vY^i! zZo$rB=ch8G)VEFiVB;dF>2o1FSlN;cZ2qpc0Pvi6++PNEncCu}Gi-*=?9PHDV^@AJ zuBY^8L6h)(Ggv}mlNb*A;AgkbXWkf=cBt!z0fh(UZq=W#dJ_^$6~xxlZ{{0l@l{PIg$9YW_ZVTFM{}H1>_slo3vcILxYCEA8xN5PWv4k){9;gyRMp#6~rVj;o^Nv zfj;F8HB%vT9na&*5tF}1z;Zp6(_l~2Kj_o8MWY*OL(5Oi6e1@n5K0w#KI|7WlmSJOQ3|VlsF#0{84+N(A|`0Bs9`r)oh9uL zNqkD{2bnAM);Dy}M?>vMAdAT2j%`+pJdQ1Yc@f?UAjroO{Z-dXi<>a#yjV&4nz2^w zE!B?6H}Ww5)I8fa6L-0gOuoU=0@C{j+#OKj8Ty8g7TxG@5D!iUPVku3+yI#Xf@(C@ zI)h&4848;7;t%f`$49_QKZ&qMv-^D6Uo!MWdUEJ>cqqKO93WDolt)S_nDIO9n99#+ z!Of@+%I?VG3nT%nxwMNZd>3Z~*W@p=xW zxE~TL#>KUb3ZmypIK!0i7{CJgd+S-w()Dspth{w6!FA|#zJCDn%ZB1y(!yOq?WO^p zve1G0Rs5P8AGDVnZpOxCwdvBIvXvj@_Bfx~|GZu17hL^%R5Ye4-5(=D!HiT|m?<-1 zddj%}^H;>jj%kpos@#0}Rr~H}VcJz;o2dW8l`@%pj5H>C-qFFKV&)6?d*g~Z866XM zRF6%j@2(4>DQMUL^+K@XM~zHwgBC7% z_d4mEbaU+wQEct$jZvEtc`5pG-kbgU3$@Gw>N3Xl37jPbb)SHhvJvzPzc3VOx|}i1 ztOTy8Z(FeA&LJJLn;fx?&UJmgZE@_~UvDt^5~@Z1wkJp1w5#e((YIC-L!Wq&K7DWP z1kn?={{G|F+HGslJ*H?@G4~XR2YK59Z*ZjfK8x7;Hf(9bePGsMfmihI~UH|x3+4d zLtrmH7AY}jp`IkT#~esj0MTtZxN;TB=xL$%iR|n@^Njb{$+92&S4{sEzty-i97e^u z=}88$h_dwk)x(I~vw$L1K6<0a&uWLvoqFr$!?s30iF@9Yn};pyr+6S1O6Is}o4-mF zCaWnqwxPEDm%ngNftc%-+k-|do_p5yG_tCzyE~kJdn2Oc_eDHsse#T>;GhpIJFx=w zI!aGLdJy1S%$K??jLjE+1{plx^6Tj4rd|zr_HKMQRn-)_J+nlaQ34~M_5d>*)R^wZ z9&3j@+r29Wd*e}wRu9KAd?47uWqe-;UdFTz4isN5E9M`r`xAwe4tU23AAd{WK_N>F zoo7au%cAGS;XSb9tnEJWc_hpo*Pf+C8B+I|jkq-vLvRt~g+Xu_!ASJWqcyZDO&bY}#8*T3j6YoFC34ty`LT7{0_YjcaHnHjZqwr`CWDLpq<9zWu5|K{h zaNrz)HE&*RaKdeH%$HM&*Blf>;;OLKo%hrFFlx}M|7^e+=`hY5aTN4m|E0}!k)rFH z=GnfseOc1Uc$+O5DSh><^aAXuU)(!HcK#sjm%@qh?m(Y=BmGO~*uXplWKj2{Li@|O z#Id~80nROypEXu(14bnaQ8O|~RXKeMl0NeNIZeFKD&E1C(*2oAM3ojN&%5Qlp6uAZ z8zQxs%cl{gA;tECg98%^Ro?XELyONgxhU{FgOq7t!pss7xh)p^3Bl>1QN^7kf$Pft zUY@qe83MqQ_jwk<)y-0_%-GS@kVrJ%w#W&L`G=rpav0b$|H7w0h=E32= z-QsPGK>=X$X2}3*r&&3o4K@}yN9>&DH6riDQ>51(!x20kb|u&x+P-lv zPG>e{FfQT$TKWRR6S_BA8OY#&^N(P@;<)HL=%v#pUA|BM)T!gN_N1=!y2jv_%4AxI z&9@MDsgE6f5!#4|!emuOGxwA=hue|w!pj;S2Fh_AN9?k6^lrktS1RNVZWI-XeO)@q zzMm?mi%*eww47C!+$2S&TwX*xS`)qx=1df^v=qCERwj~V;18eIu8Xlczu4P<1Ceij^i;||PS7M_@xf2b>7{fu#(iRaZSKySDi6i9k~Xam?jQE?4`b2SaI@(P(l}9P=l(O=g(F95kW$4was^(r>0h@l@j{0 zxr{tMTw&xRegYZo7Uy{)Zgl6r=Id2IvOczB1$PzhyUB%*>CS%b(%wa|w%-|DB-jHo zX>sg#;e zxp%@f$c{+m)ZYGgUQ8m=MrZg8z{sY@RxU_6&Xa!@@ZNf#7?3}WkkLH`2pnpzcRbwl z&Mv&{cleZv&`lewp&pM&8G?U4+OLUmJ^F>+{dO2uk>WIvY?o-*9@yX_wS<4koacRK z6Hr*t(MRKFB{vEg)P2g|EPf5VFz!oPZA21h_R?yi;04jEMb9r$Mu)9LvM4o z7p*y+?|{|7hDFGHDd6_xw+-`xMB*>b7s3(8!ac|X>c~P|O}9^BYO+q25A4rf)4$&w zIQ#WYu)dMu=ZUb}+FvdkT_JBk0*YpqNtBfVO_hu)2YoCJDJpPTaFy}-2^8`1Ua9EV z8GUHnJZbrgY4Y?Df1P~J=UCgjCl&x@13LnmF)h7>*A4xDI2r(osvvM z&c<-p~LV&wu?XXcyO47oe5!nmPnG zL2KI|*RK-i7Brk~@accxkW~2pz@hHnOgd`q^4$C0h`lKFR%dr^r3x)xpvmwr=zuD#yf1fA{4H z@uK-lY*}r$56uSNdw8*_?x=Y}6FJZ~<@a3YI4iIhWsSJh5^W=vXtX%e+01C&9D`1a z#z89vXd+?qmZ#vpx^bL)7VnIw9duqBU+_6!JCQ|t%DZ{? zeiUEojJod7n3%ah3f#+|nn|Rc+C{@UL2KKU)6*VC&gC`LtLnVMHCET82H=`Qkvu8q z$)AT+jjJ<$a;?q=kjFR(Q|(6`WI*^VV*DS18<6a5Tv6j4NL1Zfbkkl>qQlf0$Y^dR zO4WDcmEoUmy4za5e)KT5M4}v}$xZ}dw;72FRE6saoo~<5*@_|8Vh&+rg+~>=`Ku3l z!w)x!_kVo{U%vAHjQTBhf4bUSiz63eU>EgYzmm@3MCb< zBA;QwKd9UlF?hn|O8=(w1}SXOfUlNRhso~p1WC6SxbTS!>KPS`#rD7gv-imPVu9;r zNz<9dmsMY|e?U8>%sK5*iJwcDg8LA~*F5_^uj2J}ipK~1x~rr3fJ=$LoexB#DI`Zq z|IBQSqV#mNz!_sX6035+%!T06gSmc*tTzmEox?Byf!9ts-C{~EF$o3de4;)IEAU~d+i#qmR+`yl*qT;R`r~~r4 z{cwv<-y6FQqfUbsD@Q$OvdVaP5ovL&PcrEb@6*K_FR>g0&8C150>H>GM>jxX4G-Q( zEeKzK-JYm{7BBCE;3)zeGv^vMnXn29`{IjTN_vA)YR0rrnLeH z)q4#(`u_;bFY|kj-p+t~PZ-VD$C@t206o?Z8LOaAyG`T$a{31!8lH{L7kS+EX6v&_ zZjD!@zj&LmX_veIvTGz+ZK_s zq_^07v)OW;JFE4xP1&yYBwZP_8cErXaGrTbhg=(?kyXRY6oQ`EjBsQ+e~37vXYFbET^deGmNk zyXCh0&24ETgo{?KbMcC)U6${)Bkqho+Sw)n&((sJM}w0yp33bf!mB17U%TyiZ( zM;1Evr?G(XK1D3A@Uqb>-qBg<Ca;F6hLn zwizdk*~85-hK*3n;_>-PdM9Rsf8mRW6Tx5ToCg2T`?T5qI)e)Rif3YAKzsz1Nb~(C z>!h)>g=fuf1%fnm0F(?sT*(5|rxV66we;*61^1LzBG!d#O_y*$Y$8&5xpn#w%r@gs z(~0c)Asg#cdiEw9Kf;aIm-UvaNrkWKf~TBD$Z3+tY>Sj>yAVU9BFJ;ryGfVAIH`m{ zhyQN9ioV}dQ(5wsTO-Q%0r7_P>AsMc*%AjRUu|d%r%P~0fy&X?8ka2)#^N3U^joM1 z3RXXCtauE9la zhuRedxd#c`>h^5ix9#Xhq37H~sAP`1JaemF@A@#ciiNaAV~q0{MC|C_ij0gOJeG}{ z!5o1P8ugB^WE(x?(Emg4ps<3f^B0n{@JnjE`HB%MGMM)_T@l(o9T9K5X*TV*s zCHs&>AZx@7DY_#-2|j-*p3bHK z&UcYi@wW6BV(6}{3Z?1xzd(mc>1eJ0r9g)&@VR;2x-XV;&Km5nW3(ibC;aw1KVTe{ zXy|}7Lk5oAYw-(Jj>n?O*mQf>Z{`K6z_#(%6PidLpB&^rgkkA->y zLoGJ`h_&u*6O=``)Ji`0kjeILF4Ihv_&Dk-wTNnbz9*LyZn<6c3Vks!ee$Zt(f@3| zK!QAt($|=-o+aeXZnD{z8(XEz`QZMrhTPY8zm^CQY;O#w`R~os{2zh~ly7PG|Qmp_Ap5nXMat9{V53H=LifSr}2`8_y$cSj#Gc$P0R|O!o>Yv&!+)B8UFWpyd zyuW^`;Bm0d8hb*fKUBCq`azu7@9+=3_3>jDYn=~$O0TLjP<)Br0u0*+>QyptEic_=@l6 z>zXrha#sHDBPdWj$lP2SfdlFmb{97sQh!OrQ!aUO10_OKWT{N+_Cj1IUJ2*?n|?R0 zXiU%>aJ24u=jS$triC_H_4oh=VWn?2`AxEu#!Y{35$nnl>R1 zw%X(NbiDnUrp*LD&i#b|xE@V!Z|*!fz#_&=U`qbWFkFE4`522AMgvJR259EXVZ)|J zSYo=fC{zdx!XjZHEUj25Hj+HKrsn}6zMz2WeVZn2DaKDe}WWEaGs9=+nR zOcA!mAdaCLDcj!{3bFMNwK4LYGJ3b^YlE2hYVX!wPxsUy2>(A_>-EH+2X9O!La2fO zm4KqAE%ot@X}|A^HF)Sfr`713U;;(jvP_+p&M zKB3fZO3Bv=_UUsfW}1A@9*>Zg*1p89cdmrdG6z`G`^m99n74IX|Jj06JZNL-S!E+P zfcI-(>Ziwb(IY!QmbMpKz90V%#jh>u1=-5SDvm)adNR_t_ zt4(h6+;0yLKel-BDhoL8ly*x)RFo|}d_`ZLE|paKCozzsPTHyYSxbvll3y2x7+}p- zqE)!KULESI1PE*^6FHg94%o|qdHx8gWDM|Ap-$H5d{O^*i8tWwZSeKLe4%c}2)q|I z&VGzz?P}EgPj;1$)AW|WVkesQ>Mr>mY_W7kN3inqB^{L5n3MjDeM8XQ;LK>fz=YCD zIYJ@5e_e|L41u$>LY&bamBmD-w^)e>QlWT!VoM>6hs>p;S#d-}@_*wcaDML!4st!v zvy6#H(sO1d8h)mK2AbAOcvH-1kIC|;3*SPS6#eYQle3`qz1;VAJup@LRE|G7u_BG9?Xl&X)eNn zrrl?}Xdu(h0-oyCPZNT0EfUwsbTjjF%R+ zpfC&|Fi=*jJN9`qcxrSqdEpP&XqhoFWy=kfx3E_OOSOCtDSla@%DA+JPGKqjvE1K%4y5P*86rr8 z`*4nYFRrW0!0!7qw>bd5_Zu&38jFwrW>lJik?S$jhYyKnjkOZ&!<+iLyrX&MIs!mh zWWoJaNqDdP>t=B00yuQ&YbcyZlmB0Y6#}4$vT~%!JpZ2spi6kH99RJ>ySuwPW6J>h zCr-Z1SDl+HfJ$?;hggaK&%1AWQ1-PFKlOUHCg+&t0b}?R zX_>-JU^gb-%>TAR2V!sql{7C?05}Z|@Clg|Zlqx+iXpU0GWOtjcz(dL|3r{BA-RHz z|60fz<=jEJ?y?r6zP8pAuO)Fq0t0;ht*1>nGWpm(4NbK>YR;m^sIn{fizrwdcRpPk zwVteuAmJC7sF^4&L*>0$4wQ6CLvIQDH)=?Y>}#VT2!OyI$ome706x_1wCFZ@N%O#d zLgfus+wXCDs}6oQ5|7PmTWbX)QD6sd0ra+Jz;F!-D{FD8_nQY`wh}2mytD@YrqRXo z-P@Zj0t{VU9k9U9wp~+c-gKW&5OVpLPp3ZAnt~@n(l@&sifV6OQg=(z1SoS#Lw1fN zg)&kuv2a@0kS#THPH?i{{ijJaeGkK>UufLpD3^K5Lqy%3kR;o+Ii>{=4t`j9dBSHK zWjdom*Z^Z~FN=Uo?Uj+ZAQ+r$#yKFPO)z|S2mD(Y)gDqx8GuW7VW95#f^Z{l2TV&9 zYX}9TUmF#6Eb0=7WikitegUy)gK%D+=D{IM?0CkpsE&brnl4wSr5?eTp6+TCsSn1K zz%9ytvFP!FO(`9O-M7)Oy8UW1@JI%jp(hHjl!BDvM=#Rgw@BB3$_fZmAf>)<7(hi5 zU?+iZL-qv>ow0M4gl)wK%4uu8{GfCjlpTlPSkt<#7=OKOf24rC_f8l50m+}#U*NDL zF{AubE+fd@?)y%@;t4z~((UOom7Q)y33|2QKPrTm6qS|fMMPRlMjsLsM@otS=;Q1C zShESSN#MX~ht+DXV2RlNC%UBANdcX!qY6_iAcCvIH#fLZ>sqgd80W;K# zUR3AufRP{a@-+cn(p6w$AfFf$(1bw{3e-d2IK(v6@d1_gbnBhbieEQ9#`!iNe$mTN zi8r6r59Pk*l+OS7p)_Be)f6v29(v%^sdf8jwWa_{&j8~3xtpOpJy@mabL+363qV(iU0FeD9(q~SD~f2sj=)^~3$B%Z$k&Xay4{4~1|wzEIFgGgRZ_#+?FI>Ca=ZTF>*&GiN$DIXKgpujJS2> z2!H+}7#VE>j3?IRhQf9Sm?!|m87%kianUMx2j@3v%)C~N!3KFYM@Fn+;U0=i>%#D$ zm(`z;A$>=vhkLg|7BaO^*FI{tc9J7g!;1Dscl*TefyDGj;!ZBlhSSk3MATOaBfAh=^*+q)O{CvzV=p0r2VM8>$fo{9#* z&F?PB>@m8;c7c62Ipte#j|dF)Q*f{IIS%;&%)>GtbynM_Y&q5onToWs{V*kP+0ovz z2H>kHQE2IOBMyLObT&fnaZaLP?+{^fZq*n&K}sCY%NlhSdzg-31++34Zuapz$FG#5(6fo?Mr*A2_f%GDcJs8Zzkv-Z8$w zXBi;wf^0z^aHCPFiNt5(Ct;t>)Oqh)&U{$KPYiiU>qdn&({pDh$*CDhT6cXFvW{H0 zfSSvqwpz(d?!1J9Ma#^h&DELWlv4(l0^4e2Lm1sgDo3T83WS58G{wn*JDzePJW=y)^(FcOfK5`qF9J1NKwYWQm`S z^N{xEc$o3e?9R?s8L5;%nw}qDs{xCvdhODG0=gLQ7&JvzVC`Xze{6{2oz+T%`gM87 z%oStG?R8Wq9UXxNu~gEz1Favq{fthRnx73^wPBB>Hima z-IdDE%VT^b@br5EvH(k;F{$2%Tn0W2=m)o+74PuH`~B_J(+-~s=%Cu2W+cLC8<*U6 z_Z!@_Ba!f}i2}Cz9yrA0m^UnuN(*}V#ht_qQSSs9b;*=S(LmS)v~E?}*DA!xuCud6 zCKEjzoFw8MCFA-CMom6Dvun?o@@lNKl-#S8e@y-2`Vns-RX`rtJ@Gotjs2 z>>8BQ*V34cSF}P}UjLPCJgEMGh75%V4@2A$ynlC7AX6uUIj2LML--yy66xAzR#yZX zN$USVD*njzWMIU_M%01Y*x*b8lmXOD_2~wG@7v7G-FmwO?`)4d0F2xd(+bL4k&_l@ z;DilTpP2(u78cdbO-Mr{jG8)ZYOr?JNE~KDmoil^BcSqd1+S@#adT^!TEWHqy$^(1 zG15v>*M{er99n$lo0raOs(6zRFpW5Qt(@ymhgw^QWZSUkDl(timoPvJ=PVI*0i|^C zd`TNlf#*_|)0!Twu0Zi$V7TotNMmnCilZzz5j7e;2HM{4RZYpm{YegbMb>Y@3M!~$ zbUs;Kwx?f6!)`q(0FS?68+-NLs9niQIZ1w`mv5aWFyk=mIse+)}t5P%OajS$2#cIj&qU7v=E;{3g9YJjyQX)h*;E zDT%d#<2XxYVB~e)H<&Hd0&e_z*eGCimsbojcc_*d~+5E# z8j5^%6Gm99PucYAyd|l@lv2D3t&21>(VXH=SS_kki%<_(yKM5EN!0C*7Wak_6W4sR zth@xzKfECHfxmX_P!A#BUr6?mT^2EDwV#R;ZQM^sUT%wB{%O;4f-%ojs?}#^eWWpa z&YL7>urcru{*ze!oQqm9b?V&~R3@HjoKhuSm^wILi^*7zUbf1{kNGKk@^8Y|qC=vN zWG9PpGcye9Z=^fd1| zO~ibILZ0{*t$gv-_tDGkLP-W5xsBMtEbdF&!0mI4?=k_Z4!t{}ZcAi!R4X>GNyl(TG5!#_#q zP-A9ZUcL}b)zTs@K6R_g>b-fHnJON-7JPh{DC@Tze8R%ArPCqj^77w`ziaI7;#KP5 zSNQFQOs6sH6uR8n9eJ;w`Xm^xzgo`4!$ix<&Z-$n4ebsmpq23b9bXFDqSM>(+MiaLON=3}||Z77M4H-rfN`0WKg=By(HBm8YGZbXDjQ9X)| zA&1~JZy_!MhT)a&N^1taAx;#-SKZ@LSWX*Mm3nY;Mok)uk56Pu6>ZjDe?c87aY6fQ zx1J^wLpFx z%Lyq}ha+8fvDBSM-0!fz&s{F{mfO7Y>McGA!z*h=U?fm@j&fduc@daNzeyO0egFC*(W}|TVNYBRYrc0bfP$G>IVryhWo2bWA9r@ndxvOXKy>98_VZ_O zo5h#<*H4}-m+~hrT{2nt9BkOERL%N*ea_o8lzdF|wus+$Fh3c}@_vIVjXl<#{gK=3 zh7@0eUDoL3OldiTe^Ygz&b=PnY>qcs;f}S`c_mRMl z-8vHvY0Fj__^wi8E*j3xmAz+0d3o#ml3kH>j+O?x8^De@Ik||asPbK?fDm$j{J?P# zD8oa13{}@8(+#RGbE~e}R2I$N#d}eh6#CP8uytK6o0uC5YGr`g<9ikAc}08k&^xrR zjTk{psIkLYYx(s-mc^V~kvwnE=!!J{un3!0VErpv;?it(7fsDL-nrej)-@xND z-EVj_k%&vE33T1IK6oNSqk?iw6kCoa*w|u;=(zk;Hn5VSwa_RUgX`7DTotZV*_!XP z_ge0WQXbPpqSLJux-c`x?ZB%DEiEna5IWdXH6#v$kAq@yZ_ppHlKPK_g$flAU7s3H ztj1O`vkeAR@9_|-KeMsqBE=G;_yna56Q9z5v%L@9I6oCW8{MsO$UlPL9PKw9RE6Bm zo-T!Ub3g}1G2LI~?L4F0DaeG?)lgg2-L>cfxYa^%aa37qXTPzL-s(~;cvs$gb3f+w zx7?fpJxnlL;uxzGFCruIzDb69hRcAn0u}H(=kXtVS|;CbFh5Z{fIWEk%gMYXZ-~HG zDZI{#EAif73Ax?gB=kPzSqJWY%IesX59WD@*tbz<$8OW93j-?fagAwTu}qkLN!MzB zGF6@jiX4<#N`&7CLcqYGQHRHzT{Wb~>uM$lUoU%^N^Y)ty6-vOr zTB4z$!Nhw%9{hCii9MXGLC4couqca~0#`QS)R|rIn@%MuCX{D;@0S9q!sQvWkPsP1 zTd-rLII$|Bs)~wlVIg-qA!2J(G24B5+y#yvdq?Kp;l4bd z7w)vl6FS=xngl;J^YnnplmxMv1RhBGnyF5~rCVlDtp>0ELcJ-rCe?8IuKcJS4_=3t zmh#)FV$D3dsX7tC5jjX-WR-%V@oCB<-iei0JaQJn)52Ck(|8p zq%J&a%j=3~Y0)Yc=b+irZ*ErPHNEE|Z&ikCBmu=+cXBCRnKC`Be)ayb!`q zoi)&zLH*PDKsbT;$O_+&y0X zb3Dvmx5EpD=FixRJ#FwQQN%!Dzr+I~BX6@RuilqR=s4$!O^)mT?387-GJ#n4oNKc) zvTK3j1ONH&M|p{lDNfA4XET|hTRmiBI#7I!2X=Yk~Nu9I1P(KGsGBifzneAo0JC#uH zuO<%D3|}nKG#X;C3)!uTd=lu824nHTscgs;FY1EhAhx!)%8c5A3C_Ayl0(Ht#xx~G zM6`BZqY@yk%H>>%V`OyXUtl>lX1G3|`4=I${m?q!kWv;(;(yJOuN_g#t%>VY%b55g z!YV;lUf#C6z+MC_i~Yfu@PE>lQI0TP?8QB)SZ)U|hx4ffqRQ>Z#~xQk5b2JY3wE#7 zdw8`r1n6%%%fPkb#~#m#%ial*s>+X_Jao7!AvEr;Pu@PIIct5GC-o3N6JEu<+p)$- zZM|(PerK&=`brhQNQs zjTfTtP8KK9uejaI=YBPbeV?Q}%?ou->WEp<^NQ)u?G=lE@V%Cd@%gc&jZogn$l<8R zpF;E4QxYYpE_Z#1-t09-oCn-k%!T_;O2W#)#N?Zl+#RJNw`t!sxt$3E zsCOR?H8o`(iE5SEyLaV9^;*1zhzUPw#`!F-mQkn{^YNQT`k)OBY% zX~6X`rw85ZnyHf(8dxZTd2Lz*zL z>fo2?=w{d9%a^x1Mte$GgT`uZ$KStx11LMnlNq z}7vQOwFnw$Js%!w2~4z{l!U+K%8ojDxV`9n+u%7*UECORPS-d~#~Bd%-3l*NTzsC?C4?fJCzC0ST(pUW1{ z6X%~R5ZT|PrD9u_V$@Pkg(dy~+k#xsTV3HVpnCG?twMK$37%KrBAii)s2HM_WzYni zRub50#qhB1VrE%fz0vjnq=eKhTT1#ZNvp?+KO;6aez>o$#vOKFX0BW`+YU~&FrIxF zJH(XgxBElxh}F@-dvAE6&6-CHgPFOAXkNO=z}}Zj!#G{w5Wz&)>C|n5p3(ha^OK^wmR9!nEL8lMn8_v| zpX8kL*IN$E%vr_8I&LQdPHcyc;7+n()nSlZ$S<2=5ztF_Rv*yK#e{Z8RcFUl!>41a z65s5FZJ3Odu_=XTU3(;pbauJa;rTQYwNUAYO3U}8uKykzSE=JkwUnCu%qvK#*7-ul zQ&vh{Q_IO0nAF`ko)5`fFdZ1Z9ghE~&jm(<)%KiDKM(y}T^4F^sJ=y^O`vI| zO_haU9zKCgcMlF6$3{l_^^^;%kvJqnl;aLVU&_ayS|vdoStwyy&7MDq@0*~Jz6l;T zebn#)K5gN5b@^;}-wLho4w{OcD&sZ1zRtZnokRTSG}cD>B64NFU_*@x(M8>`{aVXp zkyT5PSuYWsDqDsAK`Asyq`7H^055^^9wd# z7+WP?X`PtzrRnukdGrt_redi`1{W`l4?0|xaGe%#Uw!kkEZc{I9#jQYL(9_1q5)f* z?f9bZhFvk*k00B7U&H-Bz6=PFg-?d+dz@zQbK@oRHBwS|T?xoqS=$hD@&p-{W&HS# z`Q+I%Mx7#dL=!{j;RnIr6WOhX%{QO#N~_vG;3eoBQ-42Mih|#CjoH@AXJY2|XtC-& z3gk7dd_)7C@;446)0iRqqq7mM|Xo;}ZO@2EMH zSMm3UL|~R`OB@*kS*m}V*sA%3cmgojp(9xw+22%`l!Bxe(1+bvv{K%*s;b3UYVylX zy7-lPcPdaOr)_ph+AiJ8uU)wmJi_>GXGB>E=%*K+6-R1X=}g}-Afy%b ztrfcr&q*m7leDTt9sRzr=DbB@Tv6m?S8!6@Vc5J_{LnfD(Z+ZE zJFK%C2fqk~^rZ@6*)`S41B8A>4|2X#+)M<8mB+)OU2ZLSRNaU>t-aTG7<*XvuV1qI z`t-uKfL}F9c~jOJ*b|$|Fn4nuV8oA2w<|{_LHR)u^P62G%I4;DlcNgJa)luK^(EYY z9u13ecN&8o7G)Nf$KGw8c1QjRnkHA^QWq0BDdglt#n_lpIR*P5gn?0A3%)CEgvuBe z{kzcbE(75sjyoeiG+=8Z7L4f*m|t1~P-J{n-r_i1x=6=^Z=FY20X}L^_ZHJjlW-UO zl1QmE=Ve|u7^fx6%^g^3mu`(!fm^7SD?3w$)|x2?qaKi?d1lZ5tzM$;lB2<0hW;^i z=tnSIMshM4QNz0RHyfi^hi+>!eZ2uHZ!A4P{4S(0c&~$Rpo@1;g7&ceqwg!MgDwW9 zFL7?$Lc}#$_4V{jOp)-j9TEX|r|2_WX6B~v6I&>dnwlC;Em?>hG>d-WS8s8%7FVO@ z-^9EPsl-(;(#7ySPPZLA!rhpmj^=qgdqrJ-1A#+ySktL+1H-`SV$5l2I9H|DNBxo~ zFJ9n%`0$~&o)8+iD=)9t0-i8)@8LrdaIx5Xu06R){j|Ig%0zxhNYs}ffOJrmeq_H7 zdC(c51wN4Z4BR?>ngyiIKum{uh z-8&a+kU<01Lh8A)GSZ)c;pSoS-$;so0*rIX_wSf;ScEIOAOho1f*iMz-lFQ}=ji31 z1Bsmh6|S*&8FZp9+mn7E`36jgygX?%$bf(K_D*TecKwqqHc;;~z!L?t{^ zqE+XZ279cfWeI2i9mg{Xo8akXE}&tdfr04AqtpxfC6ME30w*}j1Cjv#>yi;X`mt|| zp|q2_AiS4^I6uQ;PX8M#;o37K09|-S*#pwhx0$dK%xQ?64YNXW8`TtVV^jt)p7VCiIneH~n^wQyyM8r|W4idH1^hVN&N2jF?{HXzE>zq_`luB*TG$4an>@kgUKAzD=vIjwl^}MD$SigX1uruZx*)F} z&Q_cjv&8_d((PqBqW^b6vFy@f2X+!a3aGkpl060U69u9M0~19`2MH{dl%FFNAj?#^`CEid%7&y&l9m&$DOxya62<-27{&P_LcMV_4FX!d=*H;BV z-Nx7jy$>+HjTaCLnqUr1VxwcVeKOH|-*fEywwLkTnX zm;r{&D6QKxn_Z&D&56o-XElT&cz4jp7JAb7IU3@&ti&itnwRfa?NNm&V?shFODnFy z7_r8POmS60BSC6`|B!8@K*DMjc6_fthdAblU*H8#pN`>FdI=3-)-qUCty*WEF0_Tj zeEk|WD0$h(HTXnce$&e8;okVg?tPLBc9qYuI{_=5is=1GXx;ryYKgadw}xp_46nT< zNmB`a<*5!`tw{|vo-c0f(~Hp+# zG(R=5)6E6Alkl+)3t(pnk?zaaapoHME+op%dNnU$^Q1U>$Kqf7{}#hU`X5XqzTc{ zkqrgy*f#N5W(8>rg+6xgCo2Bi>%G#xWUTH7 zfwf{5pi2<|hsw$zDR)vPxe(NMKX?4XP#q?CwM&}l*AX=Ae9+0Nie^(4jMFk648zzYmeofFXuX_n1)3Xl`DwHKH!GC2m z(vN5vv|O!c!(5Jv0^Gq$ZK`N$k^{OC5FxtlNVom*KQQ!P5Aa7J+^tg9#(=Ow=XPqt zi^@ve-aM~gI(f!&FzvC@wU;6Eu_lsSK#GKWvRnY47S*F{q7dsl3EWHrUZ(LsA zjfId*bS$~czK7Du`ZRFbd24Enx${xe^~cop76$Z}jC^ z{TPZGJF!}~#>S z?k$6$()g@og5~~wOrR8?>TRiq-{=?Fws-1pX8`g5WL6LBC@jD-g^#)P512CGXUiDt4@i#7pmR@X`T=P@WA|-M-M>2JgmPK zA2?m!fdg_5kjAfEJG)9T;8#9UP7b}o(CH%~#wbonq2<=C9x^#XbQI|rxo>hbzYkuG z(*pF2O2u34l3JYjq=%W8y$0{k;ALosUpS&e@B>r~2)DjHjgI{cDI)*iDe=uKl48dS zm<#^J1^?}q!BG9h{fyz}<0v2Lr_cOXi>e@y2reyIVsvza45eZt8gCRpEQJvIuX{ogeeeJg?zm+t~4qaVXc%JDc8n~j2OqLN`l1DOx>~_)^ zUBKst?15JYs6YoM?a|9a^yA0O&08@A)r`6&0(kw!&9x1jo7`friJ?^w+H(9`2P966 zlo3Ocf7k_!)|vnnm)~rl>7|?^N(?DAYQqfPT-V)4d@TzYkY-a(+kX9WhgdQ4sm4sB z7V~R`-|ao@k5oWU2I^n5gf-2JmG| z8pVO3p=0y!?{9{Y-G7m`eKp5U@Nmp>HzgPUI7I~xKdP{~Jla!%$4S%Jd*#5U zGf#a{(Coo!M4(2M_ZEwoSm+-kSp`M{6!<2vrONIrIH(Y~yVTjvdAJmS6`L~uX*X!V z0*;MNsi+I(EO@$++5&ACzjDfb#w#o=Ec)|jWEVIzO zh+Q4jF8@~i=t8C|F=eLiG zyFu_Y0Vq0MwsG!&HaU4k#eZ_Shtv_EsT!&M%nWTvY0JwmhZkycadL4{d6JwMg5G?f z62P0Mfmw!FOygDqM#L|T#H!9D4OVbzIh*big2Zmpg8-H4DJWq4OP{j+RfW({&zPzA zoj2E)NT(;k&c%h>(b2K}dM3c~zG>Rl0h=n<*y%VhO1r#%5MaTCa`N)9!R-lusl)7l zp8-onR$3#{#yd{y!&@yk$GL! z`ic9OgoKCogb-@rU`GjogI&H<{6y&o_QHZH8z?YiU|>*6dDl;yftoc5QjO(*zOy8z zEp(prUI9rFCnwHc{ZS;22C*vRL-FDW)+~DI|6MBmj49v>H=6i|?r&0oYbwWi{Qw67 z%GaPaT?U*$OqB88_^YAMD~h<;EHIEOnOGw9sSam|1j?sc1(ITB4vstF15A1}CPE5@E+aa>E+!MP#nj3|DpsF}nBh;53 zD5A|oDS0_`;x3F}je*ikRy$-P{R?qSIv5%-6!Up{-+!t(Zqk1hnBi~pz!)Yhk`Hw<82VMpQ_BZbZ_Ua~a^t^V0=4~+MA#(PcZ$3CWW=?Fyq^9;04uj!zb2R8j zef!1={CU0}PJZa$u7a2lkmvqi_d=@E2aRNtwa1(F!>QQBcTtFENKSOK6?+nedc%GW#tT?|`4mmGb`~Cv+mf#~ThveUFUNzq zr+0jH^sX<(GW}alE>?DRB2!W>!n=+toP3JmGTC;-=;FiEoUpN@i?#bN5{Eo^^rSDZa{>sp z-K!h?6ok72r!a7iBbf7=sQf+66L1#q!^V90ElNt*K^9lEl* zDqAw~(3OpO(|;{(bg^cw0wATa`@pah6DgOMm-F;+E|7c|c+qQuo*!@yJ+kY{4O?zM zjY&$10W_C)cXu1^zmgwojb@6>ytHd_z%aJ{J7srz%-u060Ce1|KYzZlG~;bn_pgQ(pfr z1x2pQ9eEUMKww!VNP9Da&nLP6LIugerr)Kux`hr**%+wpry(8G29WvH7eFTdr|pSj z`3X|Z?Sq1XK(tr;%iB!|PJku$Ol~nW1aV*!P}>+A8xMlIHTz#^)Y=ZI{R3 z;CNtc{J!LQF50hNj1*BO!%G+9oSYky)3Y!0dY^qO1mQJwB-xCdzkZ(pN(H4W@(w#U zDIoW-e@;CdO#kxDa9f)S4YL~?_h;&ynOSo@&)sLwBs?VXsJ}4^jk`#8wzFg30Te4b ztrTxYMzh!4;Lg*hF#?{|JJljy%45H$XSKq@Uo4x=o|)7&Yu5Kpso7p9F~doIDi%fd zb@;^T&-?6o7v}w$a?CJWvf-9*JWW}{5EjL5N}*?pPJ%@A#nQPyuV2_%5ZNz>`pSi% zZ^PNLV46EtJ+ZqrYxIFZK}>vn$~&*S2Z4jYf&ACoTtrt_i^4bw_>mnY%M3`sqdQzz z65yCVRiwmIw42D%4+<|6VCILDVXSX6+1K|9P}~n`GX{Pc7akwou;d z#7~V8%DjKE_I-5WA%q>rey36_q{Q4j;0%a&dG+fyEG_{zQBn^p=UQ$_lNz7j<}2A~ zu1-wcy=>+5)Aafc-OE)PVg@f(XK|G;tcJh2ad#WxVZ4nB{y9;zhudiCLQ^s1LSVPGXS-yeBzjlhQ}x4EbI8#h`nv$DoLcI8M@w8HSd)@TpL zXO_IxZU6rAGki8g$;-Xr#%X>)RbcFmtc67$g^vvjvyiU$#R@wIhY@hA!I5vh0r@M6 zpr3BBTl`CE{T>?fO%;c_=+d6BPv}AEKza&1V`z65!tk^t~!QdgFcmJZ;CIsJNYO zZSxDEf3P$l&NJln;pxyv5>#^DvH3Paaqo;_Z67hGy+{-^e^m`Laqn>QH}->%PrKF^ zLWIC4u2E1|ixHmg`G_oKhHUdeTo*8S$a#-vzve&Zt4xJ|{HP~Bx4G%t%Zm$k-`Fr5 zi_G$ytiHIMNJ^vsv}lYX7tHRuMn}>a;rO@)-l*3;uC--*h6m^c4(kebea&ZG-n*Q=5M17r5iQ}cm}`5rbNI(^a+`FKAHgR#Zin?aWtz;+86 zw+617*pxwHVwh5kP4*2jke`#2;3Db3!%kFY=tq8WvBU7waWJmT-5E|HR%10tPfSHM zpuA6GS23R%!c8fd=OHz*+CS>Du^1eL+wZzBbLn_=*z4TgyLCRJTU9)~`#8IpAT+{x z$C`>Hdp?MwFHyM2l8!wJU+3`b09aTN4qSG*l}%he|W+}%a!v|uqL3K;o^24KMnI<2fRXhjWuJY@ZiDKLLMm_~G!nb^$5 zgSff!OEI@-76tyS#|AF{B>{~*+;`mq!#wq#$+>-(%Ca9;Uo`7{`tAG6rG7N5z|pQO zWri;4^K%E3lM@@stBQD;&6{h~##{YX3<|-JWnf~Wx1LMsS3*jt~gnqnRWH>L4vDE22<2_5} zb;+q+-Y(e}X9hotkH^W&Ck9Bvu#b}J;2?4^A%%M>KbO0Dg?yruTJWio%KlDOgbnPo zlzp@C-K=_D-yTzOhOSR#{T{YF;&9X=^6InMf${mmHks#5*Y^##G>Og3P&YTxk2iBN z45To!pY$pz?az|2B^cOte7<)-Flfroph>^|6P1{{mIs@C(~j`-WIqpuAm8zVd$f|= z&F?jbO45sLTwlLFa;ROU<^ns)W;^ad>^sOb>(A19HiGVwwJF$2#muMr1Pt>~9e zmw4k+&Ckq=?t1G*@~&@aA=xga$wyGIdDrWaq`r(&LC_2sniC*lV^~rzsgqv7#t%Hs zaQG?FDI-uT-eRb#!f-JaBfrpz#RUdJ>>4d)pFSmm*`2+b2q<d^n#xDQW1=KqQ@*dP^$wt$i0AdEL}rObpJfd+(U-*4aw$ zy%5b&9hji;a`&p?A^>&Siq1E4(cm4D7wrP}Rd4;O=6=t2PzX&n&AG9EiNC)zcMF@Z zKiW1p_c}`|^KS6nYjmX7%*hd&xR?)k7vgqOHCJqNRJH?ZSC>O{kkx)`aVMp$aIoJ_Z46 zX|XEW>z)Px&C>hK`1kVul(MawwQ8w#hP~M3G-zI3~e^cz#f-Y7C>F~g15Bo7|=H@Mh3{WeQ@L+72A*xyW|Y_WgXOFcGL;p5%j z$yt5;nya`*u``I`LtQBJolOLZ*Y3!`yx zw1_%nU6+183Awz!qjg9zbV@=Lf{~bS!VuZ$;CdV+Q!vI9Bp{ z*`W>$=5Jb|usp$Zrkuv7FEl(_#S9FA+lf%3>-sbhY)wFIsdg|Zw3(hZ|Io0Rn4L=6 z^@m6thGO{K{4_cI(~A36;yC*I^PS^5St8#!E*b$aZjv-nrukOf0F~DxHwOf`XpQHs z-jN>9iwB$taZrVAtehyL%Dn18@2o z8@i2#-*Xn)%&<{a)Z26RZbJRUYiP7;NmQd+HRd;u+BpH)H5N-sM&^K20fz3u!6!fk zkXbGS&Uy0t=7`~Cg64scaO;Z7-a<&-%`oEoOXhd|Ba26aJF#%_y$TmjCum3vi`k4* ztXH$D78VkH=~UH{t9L)xKWnlUa4q$hy2^ZH9~Py>ZxW30Jl=KB!nSPZCtq~ zZr@ikq&+hHf$1MedcZm|6^`omtR(2G;j7g;w5VqRST;=Wo=^~0yeoq+cu$^`$T(N} zaus8L;Hco{BC$V1h!yHu-r~ESjBCz#RguRNe0_>Xn%l_);pPoZydE8)6K{8MgT9}L+gi9p=NNwVI$q*qpJ-3c~6;oflV@Y!s> z#AkdlPOF}V%hc=*9V#>&qk5HEFT_tAk|Kry5)uNbo5{(dsTC1~sRQ;5X!+U?ky_W) ze{7(}0vKoG(fd=yqpd3mIv~^i)Zo#;Fze#f2wR&lPegBGJ|F#s+O@Z`?OE-oZX z0$3l~)qPY8s8C6XcEj7&uR^CqL&=)$u!*c$1i*P>fpy{JmbwHp$?Q0#0N7H1mds?! zt1hXx4b-)0&7bd41AJx^35|W^Sm=8C#wMh|C)xiDi{XmKwq|7x@-^V)8yLo)G?$GW z&2QhQDL{{8)$ETgr}OZyM@vUF>j$savfA&uK;=m|4g?&oiftgq*z| z+xPN_c^(8o`KD3c&*>C390Y$?b8IUpz~I)+>+slf-U%aD4U~hTE1-aU_@uev>B|V; zrYnVTWht9t1)}$B0}W?Cdz^CSs$qlCEb+kK_{Pc zw^zFz&8ZSWfTV-mAtbbWh`q*Xzc>m{QU9>+2B0(j?4(VH%Y!)`Ww@~ew9B!VermtnW^c&qy={Bi-Pm) zdBfR>sLP9HErX|tk_{J=1av>`Us5E~ zYHs?o$?DKpBLBtBA@lv2_PFAJ0ZIu1kTi)mNdXLn;#B3@hAyXV{pI8 zYI%Gnc(zQ>FWu4|V>98|ix{(??y((AR&Z_ay;^Daf{}cg5(u|MXn0 zJ&_Oeg5oy2_;rseLvLJp40w(9^oiR-ppASt3KVbX6sZe!ITqH^>s($mUjHtO59cjM zUH|jLQ3$-#7>KwD7d1MD$)p2k&*0lIalXdWqOMYv!N1Kze&TL{f24XoqJE(+Xb!=r z2}Z*raMIQFMN0bh^Cx>OfDRW27zat_{`y5LH2&3DN*7gC zREfTZ4N4`5rL@eZjTb2NrCK-Hw4zfn_-rHW*CIr=<)Dy6k-=Uz$CL*A~!-u2^v?^>lPYoprUxj5B9Ih!#7 zj}3&$o%O`hS$keP-wFFwGnZuk>wNnm$)B?-zU5{Vl+oNR&`T<|2VLrX)EH8z!?tjK zQ0&z&`A4Z;>Sp+2$mia!29=S6B0FSqF=O+c`nlcK6%%!XqqfYyW zu9u&-*!DGpn9|_AK%Nhd2B85vkN>HfZDxX;@0yqBogYnv;xQnD*^_<|7BVwfSXw4k%j2^i(?b(jh?FLhPX-A`T<5u=3E%)gYCrTsr$eF->}efR$@ zJ(19=C|eS%sZ zXHeEJvye6Qg1VACjGJ_^KYxMt=g((zS12*rfv|fiI=PmSeIqZtAh3C07r@A?{^``M zKn~KJRMPBPCYo=AWAC%QORZK+Swxm@2f?m($-$qEZ)`TlRWJ?WryEf5=#Z$8675`y z2?|(yb{DZFgZZvBJ^0Ygdao@~kI|a>Flv3Aoqn+H3^P7Vef09Pwdasf4|!aG zy>aU3(T%|EZI`5!6x#yST@SuX$8w$WeDj*k8PWTxbUs)5>st$t<+X?cYF76bJWPGO zg}J2{<^Qzf5%4%JvHLZZp6Ej@IP$uINB8o3v5S}IhE`CA5EGNKiobR4TJm+oIVNt1 znHN;5it8>mip&@Jevld%eU?z2jecyrxq6oU@cx=WhwZ5Gsf?b2gp3Ro3v<>YhtBhx znR%=>!zD$yoU)W#vU1d|%OA>wCy5;|@C3UaN z*-5bTbr9AiyTC%#+9sKh8YFq63rAA^JtfohWaDV>V6oP9a!g^<=UXQ{CG6&?Idl&g z;F?~%eaj6+;-CZ6ZEb^+nRT(p z%=x|PM6H9Xy$@HUrMlIF#ge7F_=CpA%_J`6!u!=Gwe??D)CO)7V^In&t0BHY((U%nViroY zi|YgDQ@_b#?N9uTzo+?jtnjB2nMQc1G&nvPSS*Ko=C>ws@zgLmpG((B*ZIo#hBiFQ z7jI?|t{YdL+~>MEeH9r9j*Xpf`z3X$e(8GVCk;W?Je|^_`T^be>DP9=SK2o)kB1N6 zzi;jC93f#*6c_gK+YY&CIQ?66Oqt=eS=&|?F|pV~1RNPtn!_zIJcJGj86r7zDp#(w zLq z@?y#%T+mqDgQzPP@>}0%o=7@m(Q_%;U(&qwOB0{QQNg7zRmPVdM@Y{Mrr53jp8Gnc zRrEL-XODYtS8r-}@8u|Ky^(eEo7jh?nLj#Dn%}jiR;SZ^(|)y%w0-mt!$HyM`G^!! z&&s0ZiQDBn6A^}mE^fml@odh)hX;eWKL~Rrk=$kCCmQBA+k)o$D=NsEU=Gfk(`vDH zYIC*1^wT?J{{Di7#4;SexkX;}9D7TnsQnM7$^6OWWMznbRo_SdOe1=(FIE-$wxUC= zzmEJ)*kTZum*HrL;Mgf?c*lRH^OuyCuhU|@(^!*FyOCE?E-T4}m9cjBOT&xJc^j)8 z_7a&p4+$rh+7x$CW@Rqitfm)AT6{M3%yN|)BCs>{d_jBCxfT%$14SIJIj_6st%`hl zU?c1N{7JN1v7Go2b1S+0RBIhCd6zYa&4M_SL5<&>S&Vu?av#oKn+^Nj{NiZigl#(1 zk1N^a0$X>EL*v}!!M&Ix*WLF2s>>=XLqj>++|p9CU1zgAWw1jy z!F3Cf?pzs6?baPUsazE8?#g*iQ+ncr+?lKP=HFfn<=m4SSsWowHI4{zuSq$ouYTNJ zbUL1%)s*<|oo9vdL-GRE9xX@v# zM?IhJW6&1+u4bD zqP$rXaEH@RXC8k+jReO40{=9?BFyJY4RWB3f<^f7FW*TszlGx3Y}`UFA74Xj-(w$9 zthHn2@5smOGG1|#U9G?g%@+pk=lhPMelp7pwOSP^c%Sk)W6C&)KW1gq;**Bu>c$v3Bgl?Xmdwk8PI> z_n9m-8x&eb4qB5vXh^v=k&jJzw2Rh^mbN|`9%o_-{FDh%Dc*$H&30-ng?Z=N?*Xt(L-M`eChtnOBvn{?UITaH;*>ouO zSv$ZU&FYAchJ(X$<|F31LF=LzwN!I+b4`7H3ycJ_CoRE;nd(|&cXxLR3?WDos5q5l zo~SY)oW=IolH+*lYu%pIBWe>4v)pyrF|2YcldtTjlW*MD+&}S5es^c^fgF~=)T%1} zV>fs=(eH&MhHvBz)4CTm_UV(_bG7aLr;BU*&BD~Ax>^gZ(wUZ}H%S2x|X;T?lgR_=N380VQqhQ?#L zHgO70P9ZY0o$21`2_=2CyYod^_{Ez(A8^_Cii;I3B89%S;vHi3@_#018;S`!+F1BW zn-v#(54l&^v_v+YEKlb=nw8ZS`D$`}`SwJ7OfxZVWqp9!c}^HtUzWolZe64gz0LaQZMO;qXi)D6Q|}kGib|MhKsj{l zCiqs^HHlFX+;CCSyVo|iDt`YU9$w>cPP4(896BUdwwHV(-zxfkN2=n1CLW%%Rs-+! zaL;5ml{R-sR``v{kLZt1P9t?Rgc3pvN-!<`9#`Bz#ZFVo{D3-Z=PLcs?99w2+j&tj z1)8+v>a*5>1L+!rywW=D0JcrVVyJx_jY7aZ$-aj@3yY2<<*-Hp>Pn$6R?!L(h6}zk0=u25Cxin_Q}3z0rWf2t zwdPc`-1j*8j92OJhxVKfBd_E*7Hdw2xs);?u4_NJ3e#$fcQ=h1_l8z*qa$F2YH~y1Z|P^J6n(Fz9g_OT)V2T;-_%xL2x#9 zIKZXJ?2(eX3?Y4`StPZl$1tee`|Z2+od@#`4ClYauP!%)v_$_nhko|0l_Siv^xY5V zrk<{~d5&li-Zh)SgRj1$er05Q#Obz3@UG>=)%^r-^W}?%TSZ(Yo3dvs8?z^HiTii% z7*T}4Mwn$pnAuOCJ}sIs74r!3t=io=DYa#3|Fz%lt(|&bUx=ZM{ZHFR@=oV$ZRtB+ ze6fc4*Bv`;&HX+uK@OP$qaQy0qWRvPrPb9bzgv3f+NMnNryTfIm6VRGp?nVF1@%-8k1b(%bC-^23hVlhsy@nS8Gi; zb4+W?dz9M0y?l*bNKI9VF#NzewRp#IwT;;7+Md)|G0oZc^?^WmL_`CL+%UHE9?i)4 z8UkFTQge$;dJL|Wo{L~Ip`xOqn!UgBSso5+A8cGu!+1N8fVqarOt|~;n0sT6D}QS$ z>5Njexc*1U$08yOt}D@UXIk@%6gl={Vm#erd^iH>9oQJBWp=sZfA~=!9rNXR+I1;< z9~DnhVWC!6S66*q-L&@NZmrBMpB9yf1ER(^&9N5cyGx%_nEZ4Iwh%T2-}X^JCY#C4&o92FBajfpo#I-BG-qY_fI793pGic-1brR1r_G(y| z+-|okAy8bUsw#sgDwHk(CA1IPG%li01C+yY%;G6x#BBcL$sJ?kgg#S**-TAFN;24& zsamC-hC|+sU>-i%q;k3U;w8Fi)G!O4bII}M+3AQ1{{_13^`a8{W(m1dS861?!*~yG zk7c4QIx6`aJ=bg5&J|=I=@$04c*Ss{pCCqFRbELYOe>Sv>CnS4 zUts#<4N-n&p@jOj{maQ9_dzCy6_rxV+~+4vQAA0%omqicm*v*KnoBSWh7D>`1vWwM zbGQI**CoH#WsGVPKUxpFKiS1K-HDRy3Z8f`cWTz@+plLO1W?{xRn-7!b!`%$@s%Yq z`pafzWz{z}ik8qL9=&jsszQ2Z@0*#OCoELb+D^ry@x(-)zRTG)mU@lQY~uhx|>scmX2``iX`uYb^k5*xZ(vi<34`1J-&P` zYv|>uNePB$I#gxfZI#)Ts@fB@@-$vfPTnbM0rWqvT7G^y)x7&klzL6oh=eaYu&9O=F*ldxiiHx_^}Mq?zi2$&2p5*t zaunmX3({tX1sl)k|D$`Zr)hg?HHkBD9@fPyjyDpEGW+G$HlF z%-f!U1byp++$XY6ob+C86p6jd7U{m>r^?~RjIu`;HJ>b~+Odl}^mL-W*`O+TW96mu z?grz;#H&36Ma98n#wb}?{8Ei5n>6dj+MFeYd?nx(lr2S*m-NxV!gns7{awAl3WGxfup0ryBjTx{OHqrw-0CBj}qZcirY?7 z2?+2RlO`FsNjNv|6!aXhZ;_%>jee&SyiKmq|7d;g+K#=Px^!RPEQ6?kwvziEF4e4w zu3|E5r0hJqNsX6HrQ=j=l`}CxAlBVYXdya>HE>bYF+4nkH`rJyNJg#mYA>F*#9rN* zD)jE~V`eJm?th$Fd`-=*JQXUBqdDp6${QOSpMo43BoWSwVxpoz4H^N*=yO}#t|s9~ z4C#2hicOhm*KCgdT8_JJXZyo8PwJBeMf&5aT9b!N~yP1`_6GH0hzrVTxjpq60;b_6KM{UiqBV~jhrfLK^b5>dYhUS;!yxwvf zuMWM85}A5Je9GKTzz#T&$|i$$voi9`r!{=EvS$2gzs|2Orft}`d{hxEHR@;()Xz8d zyT7%r+u3)~^pO`TEmc)S^MU1)?#$rjm93L=**eDe92~}Tbv|>ZL2x!h4A#@<7kC2 z=0w+P_hyM35EOQ1I4qdiJ2)_Kb+V|PX zhut+_B=O$h!w|RSFoA&6ro_iGXMTko70xuU>Im2F&o{a;K05>P!e&p!&1FYRy^5hv zkQKRbgmySs$mTD!(?=H7Jlx_&*v9GbE~a#PvJQJoTj&%^48SuNf_Q~PJt;_jt-;NLjH?aui&$00}=leQ3Y3=PAPGtsp4OBwa zmrp+J&TI`~tdO_2R}vp0w&F;!*Q$4h$nBai%sTTa?wau6gzMIPnN0U#H=`cI-G?es zoa57}Rx>lUPd1j-0$7f3JdWGc{A#fls&as|#Ni^Os%^-o@%;Jf%DWHQW0**GT!%b- zkNCit&q9Wl0`}9owv|;DI7hIy<8(vh`8;BxU;EmW4ED+9>d&}g^YCVAl;jCDCilG( zRlk!GtFGse3*LtTDT! zIf02!(xJ~Zq+s_K4OIZURomV!>6aoyk0GfQN-a+o27iuSv5rYdR-x9zuT~FN*rh7; z7{;Y2a?HRwEvO-h;wDvn(3M>BGzul2^n5HaN7tlA z$)rZ!eP=Al#BdmT0aI3*58aBj7^`8yPp5cT~6i;itNfNQRFE301g{syUI&& z)YTQ(v0Kr*TNN~WDPbY?^O%Nd`(s~CdVj5-G4cYr+{0iBfj}WiTx<*e?`b?nk`od< zkFFrczL@wZ96BYrI+s^gl(ImuXq$*Yt?q8UChagDs7lyTcaL(pQJL4$KW-b)&X+^q zSR3jo>v%=>x};=MgMb}zV~WO|ydbk{e9z8q)$SCnQic|T!L>fN+uUEKT(>ZO%~IlM z_LiTsEzU~{(UXm@+2e+^zr}aTdX@-Ry6I<7j| z*0Q1Tiuj zIbYIne_>Oiioo+~*LhUPI>s;i>-U7BVYThyEA-Q+DwH~k%EMhqVlSJ7l7{z&vMJBd zdNwaZS(V_4`$Iy#8E#@hWL8$drBWy&Ly)R>f0$LuZ55R!fxjv_OExA&3C=$EcqxfFlfcPV(?m-pEE?7YZ{|YM^mIwv2D71APuk_=JKcU zo93_%?&4B5DKK!+mq>CGS5=$3u(Rm1w3o@@V$^0DAt7pGfPcrI*Dzbac-!b9bNg{1 z=RFkWP=Y;deWfo#iUbs50V)6W!rrRaNae|t!{gL^V zS9R~}MyB|%pWgl@a)dUATc`NSrWm$?9}Vd>Vl&CJdx*XKEQG`PU-zvB$-Hx0<13kL zW=n=_8vnw^l+~q+EXgDnUe$nr*NXf!j5dW=9iRI0IwmkE z80#NdnshCDZZf6j2W-A)hn$*TCRI*?9;A%P7A!HlWR8xfR@VD#XO}L-VvJIY9_WAo zEtZ37zezK6hP4%|$@Z>0vri>m9G}gwPD7#y_Nr*2(OLcddVofwW-L<9_M?7sNRpR) zO#l^gpvRv@riR9C|5|$`$h^6lS``!*cHC{AO_CdOlhW%DnXZ06G_upN#4IkbZMVAmjpm&+ z!Tw>cQfeIgR$`$=1kXaW*JguRSbf7wz0aIU>Gv37F;Qnr(ESxM*Qv(h_VS5+kFENP z1ecj7CQqLhn<0`I}c;yADQCk zs=6ceqz$%;V9P630%5N+?5^$|b!$5NTp&UPh6b0ncE(RKzoR919<|)v-Y|dq^sb4? z$G&8w(pMa61Wg~L^cx}s#UZ~g3&E7ieJ!mN8g|FZISm9+epG)#PI`F6*L9Jid6vii zr+5gtqeo;lOx#f#RAUoV2ofsm>RR^iG_o0_k^B4mnS~D{zKaDpe{t=@D(e-u zo7FQpnlEbiN|Fu6rWL@0bDgR5CrTc0Y##}<-&g=bfIF{ zOhX|Ayjzfebk3(wp$!vPiq9dHO80bi>#jK^aRWiQbm4+f$$q4g_fLe}0sS`b&;5mP zy{|e8B>zr}R8PY5v2!JZac=!!7h$s|IzhD`CnwDyRnxHs*{NfMvGE-@nX&PZ(9l`; zc`9bx`T2RX2m~P-!$c6wswe*YfxEi9YkZv$=CkFST^>VjTc0Wa3N0lvySszdQe_-w zI^qK92Z7T=m8mJ|l6vFVQW_qw7fL$>k>e*^j0+mgMwnO9^@8ZV2XfjlVoj;MxQxC$ zEZzEhX{wAO9DEmh*@Z_G9FxLfQT!agDub-4!_C?3-x!~Q_GDePm#b#t>b$u~y z;C@vygcgXXW1>R5Gr;~J2S>S%F<^0i+m<19a6RBORG7MYd!Jw~g87Mzs}n05jRFUeU@sW$7JJ&x zZPlNzJlm5aUcy>=!fOE$HERT{n>3&8&N7SGhy3>HnAWtg;7dRu^!FHj!JVF!r3&-Zl!Ff+ z`POx7onl~0%8I@v7p!>JzY>O*Tunu zuz~Gj#jyLh1>!MM_lHS;N=fl<#&9y)&ROLmVH;i?pMbL0g`NfXrojdUt@1;C}YBt5FDuWj{TmVb# z%cx~TXV`gU{@cL0je5UCqe1A1+T5>iFQbG_yg~RtppjPC0mK03K?G8lh<6NF7B?Jb zaEA3HGRMYgq>>dXRBEaBK=Tj6JgNTN+O}H-?6>(k#*Bpe6RfoXDgYfQf@(cnf+eL4 zK*cI?!$n#(`l_m0YFIWF5qjM)(LVaa&$K`ftn9#%*ahTVeo;|Ie7tNxK)|2FM)5Fa zEg!5X9)?O5K*A_#wr|bg{(S`>9)$jAL_;!6^ebyXSb!Vwq`CzXqCL*5)(Li7U{cEn zIUi*8m%XHE(Le!~Wbo%lYKo8Yg8O)N^K8Hw@jzD+BIN75Ugw9m|m3D&(2}=B6{Sra#pH>Lgqdj{MaLL5`&3#!G=Y z+`k_l6&>A2W<;dyNmda_c)VoIPwMlD9c;2EqMK6w%am)4pvscONWnng!?7gfNEXzk zpxdFp*e+Eo`+@Rfl+hKS3wI%OfK^M5@L#2y6y)ms4#2PDP5oJl@q{mwd@&XHl3)Y(#m;-$1Rk)S)nNks8~hvbgaj2+y(plLwNWPM^ohD4=A)HCfsr)>;^&0JWOfhsg#wS@JShB-9nm;UG5Xb(+*lIylcc1mM%VN@Ayv0q znjz;vU3Dk{)Cpp>?|+)Q`3; z23&GS0gQ3%VGau67QfX*DgelT z{RgX+H(^tlywWQJD0Dd2H2Zt+x z>Hp4uc##M59|n97ObC3{RT$#G0uuMQ(Jl3G=#OWDOpl@q8?yNk=j8%BI~ZB7RWdtq z{%D(K{N4T^IV%6G<;t4LmP{s52c+Lo6=AdxLrCY$UF zsksoqNi`_BL%V_##T#D>{6FU7OEEuhgO+BjGRRHC&d#nnj!O2jeF61ne|D*Up%Pl8 zu4x{#;(i(7RBn1NESLAVrF(gzfdc$OmC%oVvTV7Y4=4=sJ`J~8$_)f=g@wg~)@vTY z1A`%UZEvh}wYPrT%-U-Mc^n&p+w$+p*T<27Qc;*Om~>=j-*8Q-YgvMC=YTnaKf{!uapVQD5>~hi3SBg7j=AVl zl>oR%amvWG|9~y`zfS~oU{Kb(ynn#vQEprO;8R-Kof|hiGqo~+Cghtnoi^w}0{zsm z$n&Q*HrlY@g>ovDfoxxtk%=o?K!RU@mjrydMX^`qx!wgbm?6`tQ&5NQ*kPnU?jJx7R7S_wWzy{VS>a<_%pIx}%KPZYM=yyN;d#)z~OiB<&@s6g_g$BQ{QOn`2W4|$BlRsUJu_Vye{6>qw&92xf8S3@)KES^ zR>mG%2|jM0qml0sxPYa91Py{Ho&9tB1(rz@xl>9toubP~d*_PcGps@I-D(l&Rzj zDXTX4X1;uQObQGla*gvCK3-l$z-z_z%H!X;!hg{9@c>^8Tw#}O2Z}9wQ%_G1b}~T{ z08#d*K=9^2reQ{*h?V?@6Jj@1d zgq>{PL1D`0ycFA?6+ei&?z9|o{~!$`Yw$2>YH+`hC8#A{{ok&CA4NYQ#sh^`pc-y_ z(5-OW!JtP+`5r~|HZXEJfNYg?$RJW#TN8?NFE6m@F|P~d0hRMO!mG>9dDY$_vV2xK f_lQR5+_uc4*{8Qys}rOtj8s`cO+Ndk(To2FRD(kf literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-debug-2.png b/planning/behavior_path_planner/image/lane_change/lane_change-debug-2.png new file mode 100644 index 0000000000000000000000000000000000000000..42e9611920128e8ca6db5e2d84c4b8faf6ad40cf GIT binary patch literal 219621 zcmaI81yt1C8#Ov~mr~LK3W$_+gA5@eFn~oPC?(w>L&MM^p>#+H5=wU|h=6oRBS?4W z%sqqe`+vW0-Mj9r#d3kn{7yXQdG@pSK7?wjE0Yk?5kepkk_ReKEeM2&3H z=V+d?B}E5;us|L_<#pUsH>NF(wI9#m?&Lq1c>QQF@4W2^mn4-N&g)LA@EYzme8HdV z_ZGHlqPlCMau#YLByw15BBFl!{%*?79E#Ij%S(C{5FZV{a=Nvfx0W$jW=@xC*ohin4B zdHB(NLky;8Yg;mBUjFN@L`Qt$sGab)@LnsbN*8Bme7LQZ)ip-#eL>U`*~^*K+Gj^+ zMUF}G(BV>EDHNs@YLE#1ozMrh_hL6*=DvK^_)1vh@zX8?QVNQJ%nIX~Hx-qYCf^DZ zzKmwYxwz6f4s%)IhJ3hy+>oMNiZWh+Hr!NInVS0MpZa1J%1@-5aH>|9zXc=y^vaYoUN78FP(G3pn zzvi=2Xjg2ej967lfZShoQ#$$jF>dj}7p z;3cGg_nj!Su(0r#?Q9kB?f51UaZ*B}fRq~gKWSGhB;2K#z!<_1-GAchvB4Tf;9{+< ztu68ffCu3zG!tKvny;>|j@Lylryzo>va?zLw>D-viBE~cN{u*JSyd@h3X5VglA>|; zmrT39mCAe_UKoH)-#2R zW>qM35PTwwprCfu+;s{HShntGt6O)vxiy~~-t5M+r)9d$nr+f&Ce*fm_yfKDW}b~q zB$1KmePVxaSgNf3upDeW#e-M;v}IlzjZ-h#h0ssC#mY*jf`>8!Ge&=YW=##P2CpF} zI?$j5mS78?@!K`s#dr}M!ex6P!6;EL@drJ5PTLAyo(ai`t8c)nTlBwJNy;*!(~T0} zvl!oW{kw6Bii+;YTpILpan3&ivGVQPHxMh8Q@LPIZdKgsPW=7jVX2&gDHezxlJN#& zGB7iW!~4Zg+E<;yEMU(h(xT+uSXH0Z{t~yZ)xVm|FNFVnF$U7wZUh~A1Fju*y!iax z0FwgN%#{Kov_>2gLZOt6Uk2|D4-XStd=CYKE6@c2`a`uFV%&nXdx;K{VChCfvg%GA zbWA~^?OM8?b?89(#@?Qaki61DSErW;P2dN+vjU!L63-__)7z(jg1X4DOithzrr4K z!=4-Z{S!TxGR*Dm=utPWY%GSnu-Fm20d`pq{6OeK5YZ)dG>?*-o2XLc4K}ghEF)Gh z&eoR~;|^uP?kEK)G`8q&sobkqOTO62VB3OoyfJ?N*b9TBGD-h_=*^Y?zn~A!^qW|9 zo2qdbZ^-qOYi|R~5A&fFv?AVctw%@KVaimheybNan_=oNJ#fOp!*>^d2RSC)M-Q&} zS>-jNrQYphh``@xp(gNc_5gSj z*Lz)mu-kAVbPU9fuL&2yp6GV$@RPu;BI!oSX|%u!UWqaruvFYs2ZYFRv}Xo4$BHYkrm15S)Ii&JwuOAbI|IwcPT@u?rlJwihc;RZ1YG zy|3QBG-S|E|7;y{wG-hW8GSO~Kvv;{M5*`x+KfQGS-hjtU5$5Q6rzT1Y`PPZ zzjd+xw=L}96$j2BeB*Ewn(t3lCLvVdrb>~1)3!4~ zpZO8|FcbO#G6n_gzVXUa#ML2TrBm;DB`EUL4jm)efm+WEF(A)ATjlm7fO&Tz~1+zgttQ&kI(IHLk~kKeMDnee0e@jOwBRq|Ic-ZH1qf zc)T&+5FLgu64TS8iYHG{#1tftEG;d^e;f}&p%myN>EIxcuHT@!1!9V`m1HDR8saf} zY7L(W2B$vfO9Lw}^Nz{ir-7hD{01jG7#@n?+@<}mR{Sn`t;A(zZGE-ES>U+jVGBmiiWZDP(@x{ozKc2@h7IgP65$qR6P3htI7RPy@3qewp_MyInx#^*VfzB)N|+JO?u-z`Wr(AD7K@+oK|u zGZ_2nEclvReUFGxEEYqri-UJ_{@i;E#vYpYe=Pe=G$Q)8Cv&~jQ>FL z9nXI`i+x+J=YJT0qz0U}aYj(mVgj>_cyX`6F2tkx0yc+-aBM8?nndR2O}cCM`wcY5 z_njQI+1lIh5v*trz~{gDiwvD_^Gi*U{mm{YK920H&etO0$n=}6+5M_{iJ5tMx0gy~ zIapQM+rZzCgEIC7KbGz6~S%Z=QE z;y-we2t?b*|Lb^I(9Y?~j-7EKpM25{{pWD3kzxMDZ0Pr1W|s!Fz}S>qU#zyA>|Td< z+TV;pT=Q!+ZrPGPM28;bTY;R87Taoo1wqE9==uOKPtn*X^ubq!;FTVeCG_)=!yCc4 zg~n~hYcK%7wXk^IlDAffIREc4m{_~3sJ08t4|K%#UQ+`!v;e#TtbsVX%2F?4(P^ZH z`~N8F0lFXw1L&Gfc!L7=o1l6|HeR9G*Zt}_l$+!A6|5e5 z3JHmzAp*(0(1Qdcy2#swbNmX;P@#7boScE}^D*_rYj~@rJOQ&7Yp2gw=b}D=HTXYc z(n9lZ$-kX=SMLtMb;IFM-R)@VvGdU1b^yPiqXeK0?kB|&1!V2*lr&ehjc)_}DJn%H z*^M~{=p14}dm}2`cY;#b^}&2!RNH0;0K2@&5*3=)V1*d z6TP6EysjG)H{A%JP>07lI)TeZp7Q9A$1Mh>6F@xZVdWCEy;ak28}F+%5>#;#>3`66 z+{au0oPLtW07puiUH@jx$%lEnjRQ3_IAr1`hWlCu{oHFHm;DQ1zKxua`)psQ7=VMK z!pY0q@iv_1hXEl>KS*z1WB3rxa*^CTwSEZ|s`>O6&2+|xzHP@vpyN5)jf+8BW@bSe8MNUrbz&ul(G4|yOIK|2E0 zbl6lZ1ddU1ejSDyFLS`UI|RKbVyGE2`+?%kX3?t#kXhYVWz z4Ze{7k?x5e%z<@t;NWeftUx*@9SOr9Fd%PSiO#41K0zY+glmOIt_8Y!ndh$35zKJk z__OJ_e10>MQUQ8KytVJ$Cn6B~9Woc|0^4SKuD1d95%wtJK^4?D{ft zj5H>~r0a!CuL|5=hwSE%Wf`F!O=Vd7>0qUHGU1K&XgNpH5@h_kd*c1HvQqwd8Vst5 zZViL@m)C6#d6p4$j{ilR+e^JaJ`?(OUX(7#)NUFxS9ovEW^6^E>}ikx`S+Z;?jHZX z*GgI}_%FTahh@iD4vQ-J-|PucmRvHwBE6Gf&+JiQ%#fRlm29JTYnGRRhNg7iBD(KMzg9?9yKkha`}ct%XKS8DjIyM`L4UXp6WF3fVD&4g5wFr z3Z1|;i~x!UhGaTVxV5aR*<3bhR17Y;;xBe&K^lYgpqoK$?Ep~!K*W+@w0rb2&(+CN zkl6m;-De|Hl90p1hdIcoqJqxAia+-adoD!5LSaLa@)&z?|!U zlmZD>y9Y*0xXLHR?Jf;|iL@ivxpOWh(zPA3I$a%mIWFsoSt6O(gu5LWD&5JcuO5-%p$2uz z5INUrsJ^&Nmp~Wb#C6SIruSrs1-g19$Lh%;iLv4a~HjT?8|^Ae$> zH|Ihe{t%k+ykX#Ssn1R?ou6rLcU@ccuTuE=E;4@F#rHl&_mol2;UM=B?w5A{PiM5X z$FoF_^{j_oE-q%2S9m!$PQ`0KQka@&P#%hXwrBJvUZY0o^(UTgyfBkK<%9UTU0@4M zd*Vrjs1r#(acpN=oN*)58iP|f8GvJC(RguZ+&m-9*wGQ{Ei_rh>a=^G_KEjh%chJZ zqVxANK6t0qvvhkWqueM&)vVDSi|#kCD85k3Fda_e5w08-Jm0;6DPf?YrO%6)$Cv$jmOxx1A=F-Ultw+xa*C zHj~R*ak`s39o1u=?(flsy0#QR17*)3>T8DdH6Qq+`v?*V?c3@~05$$arz)@h7gl_r zm+J%sjOVo9JISlY9W(&)e?tURVZO|f?9-)5W9fxY2!-}@v2HldSkFT2;fbmA%`X-% z)QtYq8h7uz8N#8RcnPY{`Xum5OrzToMZ5u?=Y4TYR3k7c(t6aX*;kj1h3=mF`y`_6 zu4m6VPljCL+Nv&Z6=-FxR!N#jTdO-WQmKvu__h$}xF~hTKWJolEyHt|ZsYV^!TzF9 z>bFeP-rG5uHQL2lM^pX#_W#?VrRD3q67H53;$njN@#|#CC zBHd=W@%xq9ByFYEP`etmGN-hsZqv8NAB)Zm&bX7<&|ETUZlL)64tvUDYu#_gT?}I7 zSN+Nl+p2c>qfCJlvPo6mf0A@g-fzX0+-=97`6qg;-DQKAa>hRLgQvo%z`2gl%x)55 zeY{iBgw<8{h&_UtM|not?LI}m9rFQ5bM?&L49JQDMAR{Tq(#&GEBD(Pib%$4(g`vH z^4N=xXhuA1gfJE>D<+zJ(AH*iyFnR{)v!cnKb?UnkbMm>%PsAPXmrmi@vh4vaBTfA zmO!&^QA3J)bZ^>tAi=s9Sl3L^=eZ)q5PM7TyFAMW~lhUx3cVF_qsZ!mm z8Fl(eRhiq2v>JyWy}dJFk5VvkQzHB3av(5%xw61nb9z>A&h*K&^%N|9-n*X}-lMOb zBN;+tlMIP-+bOiA)8i})yw;v$3nj0ti=9$(7C%{(u{Tl^CLiceNO{XWVGx5r_yTYO zX#vE|%M!DbxG!57_|{0s*kvdJxBSt_W6%!y1J)&G8w>Qs?^azToLybe5RU?;{~<3g zyZkMx6p&59YrmPBm%u05-_eUoD*?k~QJ!&=i zjHHt{%-aMHH6dPZmo_!q7+vyp#7?+tl@c59o!FRq_q^dv|J6pfOe2)A4i69horIk~ zi!I^{?&Io`SWP{5TX*4a3FTtCN`T{vMcbM)%1)4XZC}2>UXC%W7Em2)iRy)Le6O>#m}kA(O-s>J@5Vgf`Hm z*POrUm{dr3GIPU1nPtScWFW_+RO&{Rwz>kpA`fl5=g(Rd+wp*&<@6|bL$7alK|=TX zK3O4)gn&NkzP16*V?A!nGaY9dYA~7yWqrv!XO}xs^wDP_Oy3H+c@rD39K}{ko9^P1 zVfniJ)bE-%+5XzKqn>)#LK~%zwHYmYFl~1cXc*9bX4f=vUSl%_d8{ny-^B&?$IrTB z7rj4q`$Q1P7O0<-%)CiD$1>=#?Pu5$c<8D3iZJYrNC*LF6TfNW)i;ZvC`)?U0`vI7 zIklc9cEgLw9hMH3|@*-{M|Aboi6| zG&Ae7dZuvWO_F|ZlnqpJyUNgoq>hL%D6*C1UIv`-eIGBicS0k;gJ;Wh zADWwp!SBlt6<4#pi^BvdM1_6?V!~QZ+ei}Wz+RT$@9pb zWopwtBNS<0MLV`~O|%5vX7i=2S;NU2>|+VfkLyiPM{nsmqT^O3?K=+;28I*5S;Z6B`{8{#f0F5q#qC;W zPM6bYTzb!)mzT0msU3FoEUVd$?T#~lC(YjKUh<}igp2zW$tsLFY2=_`lwc*af6Qgd z**Wz%1tGiRz~AlBEYB}~1Clud3vck+BEIo;)EmV!IOB;`Vw#_WobM#>Uq7BL(9FEd zmX&jJdEIKoN|ziK7PfQokPod)4P*j#%`Z8buC|-jUh94{WDFS!Xi+pr51LW_EAa&y zzoMqZ7T{*Qa%`-Bk^_xROegh;ZnJ zrs|A``{VC?HiajGlzofspyW&I0_h1Zgga6&2{r|<*SC$r+$ znUo=FM3-{PkW8J{^V?u`o$h-RgbvH=zaiNOMB28F*S6H*M=KLPR5)1wABf1NEY z){cHYbi{BXfoPNkNE6Wal)V^1l2r*xsR;~ORjeHBtplEXcjeHtM%uQvJ5ydMf24I` z7sTE`OhJ3p|+K7S^#MC4-FSQ4U$V_Ps~sDo*Mdp+B<~Kn9qxmR+yi zhssM_j;*)hg^+>G7Z^-x94s#~AEqR{kg~2S_*HXpS=Ks_^+#q$)ScrIMbMrE^~ICK zoidP)DEjjWCn%Z72uo3><8wPQ6NQhyU!HqgoUG4cZ-N>a>^9|YQDu{$lQQ^9p|w}^ zh>=0Y7m$kf%W0;FG3o4QR^ZvJ7|5?VdfzC{)*8;<` z$4%$Y+|)@KIG!MueKwd)u*%Lk8w@E8eT1!M&*aEokmP-6xpypOCX0LqU4U|L7K;ve z{(9`sSWs-99@+DaD0cB!St{ysQ9Dp_29y8O3Hc9xW`7C$&JFK-8D6)4calK9FniH% zCNf8VWs@YKn^(*wetbP8yXF=wp z@>)Vmy9VmRXAfkUzodIIxM;|D%b8w#4d%O{%uM==qhPefb?rv>QL2v=?cv394QVt6 zx|unoI6WrreS72mbAOSb&VW>9rZC$~IfyvfR7e_M<6R3^W(P`%@J@LHLEmlXou@qi zdI1FE;*8(Br5A`VoSMf@jgyaP<{i)az1)&=R}GZx)%~gG3vy(fj^R>ycxHuSb-3|p z8;7yvA0ce5W4tHQ+Iek~a7-b+YL!A${{GjKVHIvO5rxrJR@c?KXRlu(pY@5;h?C9C zqC>G+N%JFRZ${HbLc!8g5DrcQZ!M5RJlUt^)UrVzN>1!lvj8@%*<%}5mu~zEd3&^I zpZL)2iY1CWDcS&%aJ@Wwx!-c-E;VxcgO!bZhfjL6yCFnn?>zQ$r5%9U_XTI0rticDJCPT1rxeCOb_cV*(&ILt_6Kze91v<;a=l(Knt+^ zEsKYHr)|OP3WT^Oa1Vkb21+K^#B>PD*^a%ITlEL~%)wVdy9-oh>B7qWTb#07S?%q4 zqDFX_eg)^b%~fg#Z>p1?9^3%$L8=ZX9<6c9vFxRJd7U+0;_8;x;bIh5<@aVJlJ;eV z+^06X+AbE@PW1Q&!8oU8MQ>o^nBT!QT?kY!-lc(k^qw3giW zf=(MX?FmqQ@v`~$*9Z6(LYnT4*{0Ik51}@}8c!djPnNA+e=t8E;5Li{S=b|EA2Yd_ z^M<*f%w?RXENkw1qYI;IctzT|mh2@qVYD(i<>5=SOu*lD9Uj6Wb5Wj*@vikBBqF$F zD1$;8wewWztTpj*P4rK*K9o#kz@d)X*Xzhm$g}u3@R~lo2Amy+~K^=7)wK_Qg@?Ys1fwDPw6ydgM{mO?X7Qmy66hzqg%K31sFc0|NQ z?mIuE(Jz3ihPmw1N3JkPEA=N1Pm?VCpo;sU2_W9(g%g025Bj&b-c!4{Khti!p_;<8 zMhD@4dm)%}?ra9Dgg^BRiYUEpZhDl=7s#a3XNwp^`xt4(_c z2`4v?=|4i^4DO5k*{KbN@eL98``FfJ*TI5wG68YsifRi$WY2Yfmm4b>@UMzblgzZQ zeL*K$3$LDA&QuKoxfyf;cO^z8EyD^Pl~?NSO(n1O!j1`6oc&o?AuP1S_17(poNxNO zrC)P6DU%H%V@HJb?R;*z~h^pYx)j-S<3eSW+Y(msZc$! zdQLZSi3AUne$&2Ez-r4;(@>!NUKI6Paj$C&=U)!3Dy==e>UX;Hk5jw*c_5*U8*eCENf;Zz0Y7Kb4eL@fiyh-r6GfZ(P-HJ z>S6_pGc`(PnW#`_CqI{HA}%E*)4u+ePV-Y$1etc=^{!Lk6*#d6bXD|6QU~OR3-!)x zavFP{*s^$)vCZ)71O4VADW9LWg|s6q+zH%BSYTr)jCo<-ifh-`jyGDPCMMEFN>ISE zFyMEzDf5q%d8=Zc_UzEbHLJ3b#IQ6e91e}wbS!t8qs!!Hp!lXyAXn-(Xtv?86MNG4 zl9-W+l$JPKB#12-V!_Wj@$DW%b1SEn_O}zi;SVLefK&mx0cmnK`8}zP)aPNr=S&Ds zrXjp-)@8rupavfD-*B$UiR|I?km&Cv0ES@Y*zgFQ@^s{8^F7GSO*0<$}{ARg|BEj}|=Nlt7E))?Cy)RLCAA z*|LOn6R5(dJ;CMHb=!sLrco4kH}_5}9mQO`g*ys}^_HuvWs+wzmC*>?j2Ty~Ei(DY+s-6eZS4YZTKRcLC6@+SsHXaS98=)> zjrLUtDIpmiu@cMI^KXEC{w~o*aIjZ{nZ>O4G9tS8-dECMt+lOarwvisScaj3`|^=W zgWd{`&Y=JJoc@+PT9I#lT2ua1^U^fUNcBWW7hr_zfgu%OKwm{08BtI1Jb|?cAl;3dQ9z#G*Zkl>Nv2 zb18v`W*$g@z<6cQ3+9Vd!qUTpKjw;^s+sFdLyM*$#8wU*lYH5mjiw4TAz2e_lsb2E zBxQh>0FEDz2ePRHKk!{q^FimO>e|}1zPAjQ-eI*-@!kd8 z^zRMzM!d&4x zNNSmnbCyM}!o~cMuOWvAGF?DR`wMG_xE*foaQ^uyi&D z#@|S-HCp1cg;Y*2kGqsvt^`|2P6GVQE9yRnFXi2732%Ke@0AC%KTao(vjpfU?^tNp zO!M>j@MU}4pU!yKr-v8|DRT*w@DYIHLx1ioLn)(vz3y0A>ji3~5GU~;Yl!cO1f&!L z-(d``$c9n>b;|@yX&UaB0_0}lEB{D{W=6s&nu7$|At zQVcqG=0z2c;o>?gLNQh`LMXor++ErqhE2DW^(qN)L=Bh^8MwUGyc&6QI3;u*4d8oZ zuw#=b;27oikP#0N~l~21UM?drzdV4;Qo8DWUwF*Z>p*4`LKxx}$%K^_D7PV#rWk@){tRV4 z*rF4r1GHh>lfe6-TNHTG8dz|!(XVp{!P$HD&_%zKIM;f3h4wre)EHeVv`6<8mo_TtK-I;YaYX&E|oTDigU?7kB z-o|18$yjGIi+SB%qBC@is*S)68KJ}mq;?7e#+!W^CzSyRi_C;x&Y*-+Wp+VByg3(0 z?c>C!_E*6X2mFoz)+7RsropfjZ5#RaO@{Y~10Cief>uJ)Wz@K4{@8j?M*Jd1kJ5A`VJiq?CXtr^IV`Ca7N*gZ%$|}?a z6;g8iz{lps1ZtZVC}Wo8se+{(QX6Sv1Tzobk`VV>d~3=DZBPCHe2Oo!$5#7) zja>NyppX|v8xJ3-`>E##jEJ1L7R|k22KkbrOL5*+q1=*9YKU~*lIS)^ySTT~lw0d& zr0WnaET!=UwIh=^K0bCfQy++X*l`!IP3f1Dc#+E9@86PYqI?xPZ=$>kRts=5w<2#P z9C7Tv`T0IKE+9KCBtp?mJ}Z-_YdOHx=|Em#* zquZA6;Jh!&mrMd}7yxVj>rCev`vxX_ZlS7AuK5WCMbHZXN!~NRqIIP``{M$cCqN&QfF}J(DQQ?q-M4@bgB`Z^)EWo0s4FMU;l>y4L5pcB zIa$BzaJUZZ2Of)MgLe5XmhvwG&_zDbF$L-*<`_)*VIiB>f=T)3yy%2cZ!nNTKreG&%gt?tw3WqK_6^@e?1byY zYFt}8XsP?ftHc%=u(&QOp9bE17Iba2e2Hb@+pS2bI8S{9IR;uF8>7I4iK8I;LO@!*^#4)1A@xOaZtP|K`N5zd5lB?7$0V5~;TX z-**^+i}hds8VhTvnq70~=tEvC${*<>eT!UWX^wPi+s%_GoWHzhg}zf`X6>Id*_$q# zNwIj^Z{zyk>}TK{v(e==Uogo2d>;-_j7ExE8&pjFlkfc71X$z<(ubzaPKaj5( zla*&&V9rnB_>&*a@h9|3FW8hWk^Tj3^V8zuWj)dw!|6w(>v8MW^#_g-HG6{vXJWug z2XLo+3J931Bd%oe$Px*mh(cf>xcUj8Ox7u}F|gUf5A9DV|nWo797y1YNz^7F3B z(#m^igG(j#&s9OM3E*u>F0H4)@oD1v?QoGNRAK1hGQ7Y2_UMQ{d#B9hr&NLK=KXe2 zBW2+y-6OyElh9hugzl{|P@T#CckQ7a*zfK)kje$f|8aNgd`7v zZ_`%efW|L4Y@Xq4(>jY!lA9jVf9;Pg+7=FOO&9>%AX@$#E$^eM5S@mL4p&ZQh3>9r z133-*?b|GSaWCoHo13BouDi_SD#8a9E>ux1>3B>^t&wA_UCTt08vBQ$tu6x~2cC+!4&7y%jh6=}t8FMpbUCe+mN~ycUT?)9x!+ z{qCh(){av1`L6LbHCWDS;w1m?WNtq>mTZ~gBtu^OZcN|7R{;($XXV$1`DAG}j~Kyk z?N-(E|1RtXRtaUH=FJ1a`D7V|VO#iVGsR(akuURVY4aWY_A^Jve#c&yY=t31pT~Pb zODLo=ITJ4Ad_z0yR~6L_J}H_ewPNaeW-m-+g>#oMt;{)P*Q3alpS_c^B}xG!`*4!S zl*he*L$?nZ|2Tc|1I0e31chQ*iy09?XfJZJivPVw0W4t9_!hLxYk_uK;vxNk0Aeqk zN^@589T1mLD0}HA4kUs3D#6Z6vx5p8Ad!16;Ve!&aRACA!c(o8iv%cC!G9WNGv_qM z?jN@wH!>AfII}DdgbcWM8ewlneYvh#eIgFtL8IlmN&IWfTqNf-Pqtmg`e-KDn4GX$ zuVT`I{a%Ivac3yU&3D;bmg_%zzikEe8880v@f{p=^R01GqgYG##Fej9az}lleup}K zF?{$nz;yu^s8T!=A1h81C$lOh+tVij&5$>_O?`;x+hd*)^~QX~Q0U^&PV+fWe=#br zZvj)6$5r-B43yq$72NvjKxuicCQM8X>W)R-p(}7$*o{LzzufY$Xx3!V>U;AFb`s;s z;@hLBkqvYvqGW?kb>#(V9|fS}uzjqr@4Lysk&5V$+@`3s_Bo^YX!K_0_~P>G!RR`0 z{iwEX&EvsYFd!8vBKOO4b@v#~T&zv>kxeTKxI8`$q|-P--;v8~nqmq*^Z_852m#R& zAO!5P<68Rud?h1jOEh4=2i(VuaC(JJJ6oN{q`#l98<@!2o0Pr_%9EYtvKsTQW&(1# zqS18?07<8V&|?`C@~D@3MXS3i}4*e#G+v$(6ThqY<*SA z=kriS{K6wXZrlUU4Uaiyv>>~bgv7cOHIkp-4P=65$vvIN2j!M9>g}C5iL+;|&*ncg zo=R+RJPC8X=fVtUw=(jR#$2A5S~SVm)E5J}{k6}fjTvg6f>u_ScjC_|u*-QK)q>?CgxS+V_O=@7 z3y+Qv>!H)_8bTgw19iKH6}p2 z;dK|%;_cj$#Ak{CN6&I+_m`RJyCF>t-7{ZtpyvW@}83aUq6dq8=h6Z58>fv3_G8r(613*$9L1AZ zF=-cVOdcd^7yx`!{^vVvL84p<_KcE@K!iOO58OJpi{0PB8b8gr<$q*fU%>ReVX@g> zLy{rtIyd$vux`?AH_`Np&f@mwMXK0ZDrsiPxf#j;HW|TGp1x~%Mn;_RhGF;OQhsD6 z_+rvl{xS!3ZKIHQgM@zKrx?*%vW?0wZL-`ELeNDtEO6kr$Kt8XXh&a2+C_4)C!ZgC z!B8!-ppvi@=wySIBxm7*DD!d`4^&OR!9P$pS6(UY{3G2ElaWpppF^rHkR>{(n6sT; zJ7|y(JFN(9oXp<)urYNCT6cQ2gIcDvSm#f>@{!R(}`u1Pvr69NdR#6$mXu2TAt) zqyO$O0SmSuyn>!lKA5D(#tFoKO7y<;|oIvF~L( zr`+{k(fDZH-15DfPyW(Wqs5LNVY>|q`_C7B#+yE# zy?^OMBGE}5ZY$`$W4JAuugvvwOg-YPJ!sqs6#%?A3{CAa7_wied7w*z;lQAKZTge_ z5mMKM|FJTjl99WNE6Vz&6p$yX&q133?3JzzL6hi7_`#tp{*qiMR?%uq}9xX5-*;VGIh}FS5>_QTk-%!uL{)4lLNt8N^`UJweMh!5o5|GEc90!!bJFqC2ALjFeDA)x5<@_b1qZG-Q6W8%oWr&CIZ--=qs_>| z+#9t%&1AqY6^M?MGY9%rF}E}kTiOJF`V5MY2L0-QJEe6>k0x}kY0G=6%p2}91Z z++;YHCg;zOB9r$hJ?tF)hXYS+?t@ctzuczi1Mph{nJW{3G=&Pj@O3G!de;{{cFQ@Y zNW1>sl>LFUq}lV$bPG;_ijtYJ+5?9o;C_xnWw zJdK9t1YL&_i2K?TpT2v~$)MM?YN#)8{hjIjd)FEZ<=FtPR8or~5wtaarCAs6(c!Bu zVYDq>3v?mVK|%ICcLVtN$eJS5(D1n8Sq(t8&iHT8WgjBCj%aUne(Y0 zQg3d&Z)7S3R-<9QQI^ffG4PQ558}cpBCPM?Skdeq1OnQ3n9%WE;6VuiZd0#m%cqvr z?PXTCdLAN)TzdO2>hZO*pU7y*8nIczgT{yetA}kf@reG` zh!6kaQHG+;M5OFt-~R2nkW(MNwuZ%9?s@So-ixt2FJHEs|Ab&-6iiHH&KP1{KDCaW zn!3BP*4;%#k{@68KBR4-^;2{ro7XSyarceS_Pt{8?bG!jaNS_I(x~lZ9#7?R&*{Ok z#>n7Z37>(jH{L9l6MWbhOBSxix3f>)(w#*v3uCOeGH--kH@wc0-5T*vDMeqy5$Yis z>o4t||5}x7v*X$5Z(7rW2GqdNb0wFxGpj%eltJ~1ph;KgAnLpME;R!9I_CPm`||NH z$`@1b;APs2XRWQs0q+{<;5r(E(UwUgq|w(-FOEm|f!1DOS!EL|)!eq~d)my`b}>r> zEFIbVF`svG^V>6Qas4q0?lNlPdgE>U>jiLimIDU-59)R&7hG=_6VlcZMNBk3_IKAYonI=a3uSert#nhBj&fckaXuhPw z6AO4|>Pf?~1Nv<*2*7qLPJI)6Sy=Fhv7Pj1-O_C{;GCK>iUvR`prnmr=Y22!J2kJq zj9k<0)1qloY|OZ249I2&iG#F{IGHSY^=CwIeLyJzvGa=P6E-5{%#Y6*W?ljgIap## z0)4lB7u=$yfcevv0FQ?Z(VM?l4;~LtDMN)oTPRWCR`K_a3ryv~^mPC01g17dPS8&) z+9b;$l|Tmy?$OW>j03L}fN`oNHkyREStZj=qMBm(?4lwpwV$($I;b~QHeC<9rFOIJ zYthgH2$Lo)%TFq+EOh+P9SbR(OABEe%*`vqg%(9^TCvKrq%H zZC?~wSq6tOZ?LLzDjX(5$dPp|eq-1SZ*R+IY5qQ}He`;O00IEfe^dGfP0J2mPbwv2 z&;Cw4f+GVj%m~K(?=BEJI-~u$xXRK6k25>w`iU;IhC$Ed&t)Z_(zY7&k#3D|RD7Sj z-vZkv?|3G-O|r%n=Qt_@0xXe)6KET)`#Y3NKfumr-E=ZnjCt z7>>JvFT$d14!Fm`+?WA5lzlTY+)ICo4d7eW)2o}xbW=v>>d?>}K#y}uPGrTC2bQNh z@lN=-Wfe#RO6xa_?v~h?!;qrQnvK5l4OIY3K-}_JJOoxD(9lMl>jMfbtK?T0dj?-2 zymiq`Xxfzq+`_nC!QtZ84!XfOtA8$24JUC@?AEpPH}dksH^iPPNZ|tJNKg_X59YyGx4DN9RZw?te zLySHw_1&xxRIIivEHVbvnc;cV)zv%1$5(V0fKKmsZQWMf1P;ykEV?x^G-HP*jE;Kp zX%4&JpxcD)4-feHF8Ki3#DDzIX4G+FL@)lN@mf>vhaNzOTApp)Xb0*MW;T^BNBo#=gUV*^FH(gxN1s zi;GTq-jxj%C5wgOQ|bh+3K*CFI@{lhA=d9y51BRdpN+=_av-2?BYmH6iz(I5D+7Rj zQ#*+LG0O-95Pc9|vvtN{Nq^Vc1hbe-yMK_7gM=oboqn>CPkdz&&Sdr(z1>T z0?g=WQ=;L;i0aif@9dih5ayWRFEr2`|E>0jYudmYu>yn?vHgvLGcGA6N<%l{;YpvZ zj5Z5R>)Ndj!+>OnFEDjQO9|QIz^0s|xb9D9o3}IN+e^gkAA8|tvO)-Pq_oL`%-6DD zZjZpau_4{XDVd@dSBI`H@Q+Dw2^rGQRr*1-z+J@3^-;8Kf57+D=V(icf2*zqg|dz^ zD>1wMw&?z+Or$!RF4 z2ptn|=T{&ng90Hy)H8u!MDo`e0%AA%a`!nTSHyT`^m>;>--SN zJN5VwKdH_jY2FPC$Scz5NuG>8b7x|Rir)LNBEMGo98*XO=Xum-@;M5b@SDGbI^1%! zy6I+T_fRz(PsGbGsL-|(sxVuiglFm6v1zo`ktG|bLq0}iC~nk zH6P6W+xsv*4%g5j%E%v||GZ4NJo5Q-x`2A{c|7pvzPr>!xm%wOD_ivVgj?ZRmEPmM zo*^aWRw1sL>ZeXkM^xgXHmRd7ceasDVPsol{Syxgvhj#`EJ>X1r>Q$GA13zFp6ooZp{yocIt!2%kTFnlwNGfyiOxNJTtw8fPTL zQBdmqE^##jxp_jhc{Vu=FmSVw%Ke%7wL)Q*nVH3J4%L&E+Mzs=vxTskJG`2U$!k$>_5M$ zd*>+*mp4;o$&jv?~laIY8i^J-s z2}Mf!?RznUmVZ7T-h_Rs(1|lUBIz0&;?!%lMYh=9h!Hx-2Z00?Ha1SL;6ospEifjfpE(EJLDJ~Qo%R~& z7XA%J2&6}Bq#zUNpiML)W`M29T@rJKP3q`OPHK|nf2q+38ha-^GqAqE(R`CT{e=Xv-0`_}sY z`DQJ2DKqzd#TmzWoX2&~xP;rCVZR`E-Jj=Su!KeXTF1lAzadl3+FP_UzwoX1AzVM? zqTB9ySXK!3{1gq0r?{v{PWVvp9M}0GgdEotbFaK$6wJvhz+}AeKcgU zc6Z+F4(#gRXIHgK7txg{$H{vGi<6-J{5r{6c{%q(kUMk@=#@O9iMgDpUOYPZK+17P z(h^;@$C}+F^$kbx`ODeVws-W-W(o6ovIOS2cgPLq35Juk+90LK zTMEwb-LGwIpHld|2hNOe*=-12hr!AN(Ay-v3qz>EOer-jrF5{ggv7+MbML8rPF__{ zj)-#^LLne&cvba3^E163){!adfw@Ca)jVi|Z`1p*$eV`Xt zpXre3`}FjCo6}K;43}jPF!W0;tpw+7kqd?wSJu{egw8=%Ll=mML~*Q0dpeSxeGF!p zH8iA5CGztXxDKPVQ`%=m)ZZ^wk&JnInuUtApL6jCKYyMFA2rk-85vnUsNdoeIvZBG zGIh>g(kIC1z%O&+^+aXG(gs%Uz+m4DeYKBc>@i}GozzHaya;Jg#f@)6j@w;RFZetu z2XnKqwG}wK$g6gCVwK~U&sL$aJkMt;4M(ERe)BDu8#1p;mqJ1b?$|IO8N(w{q;J!} zx}$zBo5Gm*oSd8{wtrrPHp+**{dlRcBsQ9c3{5A4sQtd^$ihd-18$JjH}A}P=Q;(| zdBL2ltY_&r@Fi!yclA=X!4@e@;vN$xXRgTg&!3ACjw$XQ9+j2WNrOsY0@scD+I=NB z7S7%cgLN{JE|RXHprM)OsRSW_U21TV>z8T>JEP4m(IR4EVpd%c@E>6ET*Y;Db-|%v zI;OPiuEh5Dz%$RlOHT5?xd0YUn(vIwhHMG;+ZfEF4p$-^913m)KH)GRCVYH>3=JH) zA3R%zW*hQ_p(VTe#oeQ`_rOT9RI?58-v%LkRgXhr-AJ|TRF$fwxZ`AZ=H@Eey!%p-QA1}Uwb-GlT^~oPs6T_|o zo-2i4q_P>Z0YkrX3aYcIgFm<`6pyp_lCHdqdAW92YRjxF+OxtWnCtwi_~ONjXVdZ- z)`YJLNe_)ySzlxXOTkMDF8$~A$hTvDFtyPmI5Z+knH0{9yMNb@jAQ5>%FCcEQaLko zA#1IGW&hv+>@qCp-(EC4Gh^fU7r6TeCD2lW!O%WEi$k*yq@Wv`JH*AVeS3EvxEn0* ztt>*>ekX3oc2*dTZ{jnx`_*JrZzb%~$tRNRsmvGYYYg*|V`gO?COU1rsQ4K?c+3&2 z=K|aqL{h_Oe*ze9;P9-fnMUp)ceoKHk$;^>9WYyH^hPpj$1&*Y!z7Dp0~y2}**u$s zljYPnF4N6br9MWRi1`@yi`nO3#zW}ro}U8k>wm$R{sL*fqof5G;oE3`Zf5@a5QAT5 z*Mcd2k&%sZ;d?nI$AOa}fpdF#k~Q#~7p)ykG7+V;rQbtp=bbAz$=~~Jm*6yjD{ETk8GP&o)`_)&aJnhw|$s#%1@qcUFIu!LE+GJ z_?|%8K5lZ8ABq~V_AePtO2FO`4JeK0QqcZTg8lgx{JMHF1lW4ioTJdl^sqG)iF}gd zEUJ+KvEFz4^Wu7!di|2l$soR6i6|&&ednqx*%5a47K8uhG-3=SDK7KH#YGEi%ZFer z##2**4kOT(LE)^sC7x2J?4=k23HcN=?)>@ZQWBwM<5mMWP&zLpO}D2;$QIsrg&x!&^6qmm~k>kO3;TF za$J=Lna^_@yTTwlAf5T>ibOxJ_c<$czxqb_;1XU zf1r|$Y*MbS8f71jC}1H3kZe4q+}D4RobpG*e1~IuswjGIpCOr7SG9;bm-kgK>2?pl zNHUL07^9t+CEtAva~j={0N3Xa*KS+DH(xuc4MZXrmA_fVPA{vBmu0$d+M@1O9}0t* zcz_zuBpeWX03T*K(%@&-W7EC-wz3ljbl~TFUgyHU}+o1=GDkDgD{{U5Mjq2@H6w*o-^sS(fC@<^Qw0W$=PE# zhXH7d&vCX5T`DBivP;Ia#vUbjBRsoWqpHzk!F`KdP=AI^g->V|MW#ZQ%Byke(66=~ z>`pk4R2n~=uNfel^WvE)!XUQ!u~rzRx}B8&hV`T|a)v?Wk;v-){l&$r$(712L2*o~ zI)yJJV_tLQ8uN7VaMA95^8r{VuHuMZu&RO0fh&IW1cWxFQh`@&`65<4thy==6M}N- zue5~2aw~0sJ9!okjJ&ljzE2tx=-wEpQ(S&<&^OXMRb3f8emhavTsAjBWIlot|)A zO!|4cSjw!d#JyGK-XUxf_+0Jy(5RpZ$4~0y7z{u8>qsLda|_dG@RUrSE`fcXdh%#C ztlRx0o&|n*K1Osq>1$8@>2Cj6^W@fxJB4+)`ht^Ly~r#8r1ek;B~g@T^=tZUqke9t z{Pp%EHBUoCfo;87HXP@mP0r=iG}fT5CosbXAGYW+PTY3OnGM$+5a%3tK->j-nYV-( z-!5rUXky%tI2vB0Pqf|AAE3Nmu;GGGJ5oTY4GuoIC1hqez3#LiYe0pGkMGIWLx_7h zcP!mzKhAZ@)@8M+EWj5Oj_mehn7+Dp)pQ&*E=~;A79ud#f=L3|$uwZ~d38)ova1@( z+n@{ri)11;x~VIl`=sR_*ba#a5u57w=36!&zH2BeXDEJxkAe4uQ-NIC_k300)@ju- zrKs~Pg(Ta2oHji(hq=e*>&>Es(ioSSlEhs8ycTV?MzNimUhhhewBt(X2NfnyuK+YEfE4P`^rE&Bapz)FiyK4hp1B z^-g=prqAzGx<~S#6_~BAEH{0gSx4q4DtODaVGrbmTDrdPS~zYC<1>E@)m@(fcR>NsDnMW>9@_jWe{=U1ckSF4~a<|$7tRzFF zI&jH>eUvgv2bm*ifQuA?AL6o>5{R1po>QH!!I{1qn`{#8 zP&_fJ8+jm9mT~_fd|_V5`7nI0BQ!_sUP^6>JXOsu^@a7j%G7tor!VF+M1|sZb4PZ! zF!DlD4S6p*#80Jt%?1WHY)^7YWNk0~o=rRwI>gmK)a8W_kw2*nszlACS)O*-L>Tof zNe?^-A@RpdV;w+oHzZb#ZA8Th-cVfBbIB6B6J=JFH$RCS{$a`4JrOxLROXT5%(-2cc%=n^MrCz11gv0&B>%t+F81yQeZuQR07URkLHX5)1fHw;eFZ+8nObci4v^8r zboLPADGPR#okh%5V(D9_O$~RP3P7OgZGai@_VZj$EzL8VtG5bko0z8W=t(jGb#)sS z(<8#iMJ*DykT`vf9f#~8f>T7C^UTERj>?&7a1wb&;81izL*RaK@h zb8LkAP4csX4!1%v0>wk=wo?TcXzHW`+vMw)904TuD<%XGrA$p-y`ZqL=Pb-*%I&k> zJ)C-!)wbwZ07_VYA{u_7tFSDStz^N-tQM)zJIR05W`Xhn)BqE3L&Ttx&#-nwo_ge0 z#-}u*gs^e@b~G=Y^rVZGz@sbZzq64GDQ>yiCn*IlOk%*<^Dh~>(L;fu)Fa8I-mj+6 zY4H78p_7J2rIX5%5}?)Jt^Mhi}8-xQx4*}$+aIfi=c9WNND;Zkh# zUGYua1H=QVnHiY@2(p95BX%M5Vkte<`qWpYil!r{@eViYpjbDjji@wre9}zvp#)oj zFHOzk{+D-EJf$88-$r4(IHR29`3Z>&*GhyJaQmFb2UrDU#|2h=+V|X(;79s1 zMZN+JQaLM!!nDN2T7@5~>9=lJ9S|}vu|&{m9lJx^2#d#IdYOv~f5K19lBMIGgMng0 z9@A|45aLwpVcPLw&AOR#LycxSy_1#>ijUcNpk1msiGAW|nUQp#L5xiOWW`2pdfzL- z@9C|?7KBBNJJLPniEOOJj+3plTlYH@viO@8tJ=XfYQcL$2|xgm^o$J<0fq(#yk70O z{ZMkSUtjyxoe z5vhC}80K}2USBmUbsd@AABL-#i*22=8^KTIbbEM*JEzLkZWY@Od*zap5YQU18Pv%U z?h_tQqZIHtH(;Go)l(<0ru!KyfZb4j?{9gL)Uu_>^yuBS0e}_=a$E8xXrW3U=JP(X z;81o|K%5G{43}mh(y14!{GEddsV~gsQ~s{!I`2`5ml9WT?Vrk;+g451r7UT{%BxN9 zG}?uUS3aW5FBmOTfb*}`n1tb_V+T%qewmC%X&$>j!~~_O4DJ}M)yuzeO+wPa6+K`vgW>+7)tEg9{Et}7?5LhrR^IJ8*VpZXe#mk7z@|a_k%m%##u-3 z?S-lbKTyj3b_E(iEs|11md*Y)Le}IuktAV-8_iggtNu=hmiUD2A3qY|idhZ1qblC& zIkK*!R-3p*FDQLN{ALgD{Ak)Oz6sbYJfK# z!faa2WF^8+Ke3%ZKc7ZTR5+I_9&3%FcJjn}T)8k;LhSj%1XQ+`0>V865_P5ni79&& zcVX!1V_9$x2Jl@_O1r{D3?e#sN!-jvs*uV6OaMX+g(m(uYo|61Ume{xt3gU7S^x(3 z^#J6YF5_;;XKtsc2=I%ty_5O+=RxJAiTI)C#m7eqd-j2I+g$}V_>%YggcRi%D$$j>%(3N`edD&S_U@x9tJvj1@jQH>fGJOEZ_~ZL0q?GY2tlp3vW-Ju98JRY^RSb0ds5S{5!>V>UYoNX#ZCVt&DA8#QBTx|Q^XdDFp z0hr83v5$p@`mV)xA(2~k;||EXmmNb~|Qo#3xdJ5U(=hfzv<(ZUw) zxR~b?Q9d$s3{K{c`VT#@MWO2u2hU!}AWDP~GEf1kb!n}ogD-4eMV zzTB|a)3Q_34aWt29dohqMxBRU&e~+ z%7U8t-&teTs5em{S}9d~II?{yXWn$P0$F@TQEFnDluDST!uAEXM%RiaU(kRT6rom= z^y4b`+xeUoMCJoSDdj2F>yB>s;XC_yd|Sq^a7!DR5VPwiR-(Va_wR^f!^HWs1;HZ% zm{L^TNBpS4w9dXGfI5~A->n8pcG{OFZrj4Qz)r(R&UJ%0-e;qNyd!Xv0K|AA|EJTU z(`Pf+iiW~C*$a{aof6kF_E)`NU2|R-+uv%RFR!iw;ArA{78dJiJ;~ryfG~HOlVD@$ z7}dyf7)WwVo@?}oYzOHqREzpRpqOGj=8!Iwom0WxT3VScXAXxYd9+(}Yn@X+@qq83 zxKz#t=c*gq)btU(onJ4kz^Fo(krBElJ8;xlYo19GBxBmM5|3)wtwfn2)EB2+3ibjJ zFUmAW(XGYmgkv0|+f#0V!jyrvx`DCLGNvj+Wq;dB4r%_J?|LpL9SI*<%i;#;E0-_V z8a0zuHcKzt{>a|ltxt-+;mHpQ`Nd020D-CcFPasPEmV~-yc3)gHMxEG;E+F1Sm8a;XU`% z6B{GlwuAk$%4%A~veO#NnlPUjv89iv7&nE8z=j(^1n35Wa)_UR~lZi z4AG;eF8nzO%AWk?X;jaziAa))Nm9$WEB|6E6*e2MK*qsmsRP zajXw^}Jle+sOzZ>}qc*408m{rc7CtP>#_g=;LKYoPAMGE(4;Zs16=z}s zA5TN51racvr})c?KgloWtqLXJ1NldWP(y99eDK)}^Dcfh5d3ep8T?io99qz0>+?oN zFD1)x@2lQME|fp3s1aUXb)FHO4s9KdX^wpErkQ)&CnBn7dRiMGnUNhNlH7rDJ&JI^ z;PdR!wddWfW%0>-M{FLG{NvTt`70|*T46L%=B}Dcv*B{ht#j_K{ghNkLkNXK zkKU}Bz7kNZ+yj-{85j@Xw*2cNOXuD;YtH!l-i>?rJdEP~rK%ZD(jx z9X5yYEf*R@gQwGUh#nj=ibttZ@?-r}_i>YI2fxqrU>T|kUGq4O_T{VM{hsnjW(Ml8 zF}6Q>toE`c^zEoo2agydm>0SQ;$BBaOwNGp@IO@87l;b$V2XitivEKWI#_T-M0=Ll z_ZQrEvO|Uw3BT=C1S?U8x{H7*uW_H&4)C-)Br)Gm1a#%_+(aA2;iQV6@muQ&CQK$g z{-E-jTJP%5Z*^njiOnPdFS>2q4vjXWNrqT$PG1jv}CxbayDj#ej2iM%3ISn4)&wS%gCt4u5h*NZ%?7 zqk#w)yu-&q29x+#&Ug+)H9o z5ythGq{c+J!S0lVE!W3Jf+&10;p<6ho( zM%?7z`>w{KyH@)&Yn?I|C;O?SjZSk$w6yN>Lb*BBpC)=a0=fQ+Q7k*v1tBnNhZJ09 z)?T8j_(lC_eItt-Lqn6I8Y(d#D4i0=TtziWs@*{Msu!`A+`vh!0f8)mBNPz~-9_YG zdO;C3YETzC2BFU7KTQ~zv0lL(XEyRgV`<;Q@GaCbh}w1O0m{~n zIoZqyz_8RxIjcY@>TkwA5dJ~fT>Dto!kV21+3$_9+c|#xBwWyeN^r`cMD#TMd*vO#cF>8R0&6 zOJV4+j?LJCWzbCFvf!!5DIZ_(IngMe?fQuRLbtEyu$k4};$`cllk@szf@LuJE!JfH z>q%MHW=99unUvxbKHt1sF)jVJ^TSbm|0}Z#0M3*+s$`DD*j=83 zST@i#3fW38T^1SH`tF6Ra?eFzS?*$8{9{1_j3I=2t`UA@BL%KV{qq3P{Au`k3taN? zR0T~S_EIZusA&R?{sB8t{nK>APAK9Ue*}Fi+8ak?A;W*$Da)iC2K7Gu5Ev638hXUSI^uogo^PU} z&f`k$&6O^~COwV9F~*4Q32Pl6#_Py&4&NDb@5?i#^>7)Yqdq zRMhTJ@Xu)RU+^?Hnj`8o4GM+t-6}Zx*%5N>B8>MJlrLslufdMGL7U5Rk{_byVZlLv zT3QQSGKc^s+&LfaqG>%A+-@4*_A%?tc48cMta8N^~q=R5a`jW9~yT6W`=`7NkfMdcQF88Fxt+$cMd)OG7L=nOF z#YsTTK$r0SRa;PCj_B?))hUlKFs$J>{L+D1#X^VED9e70CR)sV*h>q2q}y^KwoxE& zuM5$QO)^M3cvOKbU9-hk6XD_b7_KdlP^oI>ZThg)@QBKK;mv&``s_8YNvAchbtj09 z$@UVnN2cSCV~aXM^XJIKm6W8`&f)X@I2tsY90nBbR5-izGO2Gxypu%m;)4={AjW zOS=f{agYbKQd3!|axkhsK3UZ@SoJcrFKKwDQjipcODbWvK0xzfeQkC9ZM-S z23B4h2UhLU0e_4p`Tht5ZQuQz0>YcOzoCw|aX8Q(71-jQD<5%+n3WJsxrOQ8HBekN zIAxnm)hpk_u&x~d%2M+~oGt_MLMi#Q-7h{$<)Z<3!4?K-+*%#cN_qLs%(7T9&IPY& zm*nLrvSh#dL%?R_n;)aC6YOOOSs1L%o(@KFQLS( zUsZu(V(k~gQ=L1`(veMBDIX$~m%NX50gYqVyPGj%@8o@$xz@N;965epnnlQ6byj6Y z)9mB80XFd5KH=2?;hiOdgub=9)ejVPuEi|gCr@Ke_Xn6=V8mlT-@M(-rl|33JZF|7 zie9D&qNlu-Uo`Y1v64c&!r8GXFY{@CT#`a`V6}COx$C1$gC|T)9=GA*D zbjh`!&Fve?C3nTJ=2XW(qM)yvy#4FD~xe3EvWAXkP!oLElGbNz>Vb0g?=c%e!WxV2k4+?zj3Ptg=9D4ShtNb zG|M~?v#ADZz!Yb4S$GVcWhE6ev5`xSuJH-6ZCAM`F2rWhqQsDsObmb z2EENb8QIien!c76BqEvmN&|Ng3dzd7)Uq`>&vBsqLZDf|!rfHbd542)7+}~3Ro3O3 zr#B*RSun!-{p(L zu>`*NL`oU#7^kl=%^(!6iJcH6JZZKID?FUlL#IvCAuaWj_B25q3VIbrQ@efdd@RIv zBBJXbn5pcXdTH;a!c{wptC=;C@q4blHgTX%2iW|?eBfraHULD=KrsyTGS$+NAU~FG zPSBglRwQ!@^pu(OnBz~TY^o2okiwgS1cr4RzuhnUh*bYel_SWBltHY%3BJw{(id?3 zMP#qZz156|f)2=}v&iKm4Pid!T8N~0)VyfFy0T*ghzqWlkZO`%!S=`CfVV#A#=mrH zSg$pExISvzS!KDvVBr{SUt+>^lwnaNXfTlnKTbofkcF5PpkCUh{^(E7HM;5#DL?J2 ztP&3e2lGtv%VVnO>RhJ{m9)X_?~+ma29cnN5wjfOpTl>_KCUv?axJQL9(^+Vs;_Pz z!Kk|OP%^XNC@yThlMImo`f?GY%59g3-^`eaF@qkMuLYR`|ISw?A@^rNGgx`RTVI5J z+LHU3`^;81)qbw`y{OWZ&OgVRM4~yKWiw4HT@D__Ju|_wy!6uE$|fSS@}bGj-9ItC zz|>+DqedFBfbB4e;NvgSvFd$THvA_d08XAOcUaI`*f^Kvv_I=l%Jgv@cSa3;PnyZy zZlEA6@&Fx&I2PrHvV%i66P~ny;PxzZ)SAW3{X-yze(NK7ao&r>0THfnKK|QSW*WS9 zgFr>Sm5{$5AIPy9ZDCvLNYIW=AJfnJ5t$v?6^+)lR0vDH3)1h=vKnaEfEbaY>KB6U{zEJ8^=RqP|>Vd-v7#Gza6k4(jlW58> zEFAXB<%cv=K6KIExthlhI~|c2{*h9v-)ny}6qS1}w9Avx>=4lo6uo)#b98ji#xH%F zy-+77Wi$Fh#ALrXMx^n}PTNQBKUlAJHL?=_nUP<_9ApVW3p_C@2EHFa74$OVQ>=lb zxBN!(QM-U{z7#d?>32=g&3MNz@&5^F3G~e*YHIhkPS>AXT}#k+nKwc zaGoH+ON^9CkPT?OS;XE-1WNLjo4OuYT}V{71pO#UQ4=1?2RxU~v50*!IH($pxM`UR zGWXTw>8$OIaY(fi8?wP*b#Meaa;lEopCL*#Z~n8~U>RQIf!YWt-#Xz3EJsP|%$f$J zHGN{6<9%XjR-3|$ZzdU}Kv?NZGT!X}W-|igA{^DPc^>(7HX--A{5hD4Lr)*g=%&jw zBqL;|0M|l$Jh`SxF>a(V5P<{On$dri9`Xi^31Z{0Mua>V%-5<}C zjs&o8tF5{m7w!(o-Kp4|iMiD_J6v|Kmj~Je?H4|^LA?C|QCYkjpoYo;%maMO=qMY& z3zE4cTi1MnWN7`!ESC?Gb<6NmYIGrys-)GLd;rQdA3ui#Oh3NLq)S#tjwiosWrXgd z&d>a%T)OU5?}1jGkcq8zOr!PWi~Jh5D7Ft>0&8HT;Z2aT+QXwB5-AG4AF_QFZn7x*RwClfN?sAXCq>|;@|n&{IbIIv9C~dKHq|!mBc>FrRC@um+%z=C<}-D5q)(!i7!KEH6Qt+TCRHlNz{_a}UD9#-27 z$ag@yo5}93Xl4~?H~U?@uy&WU$X4~Uc}zw&c~ibg6_C^fJPC@+!*>@x_d7>0?raq| zpY^278dK6+at)RXbgmkfI)&i!hB7Rytd;aqGk31Rc$MzOdG}nZk8GF0-a?(PcPC>e^+3prl3&6%+fkkn!T*~eQc>e^cLQWsd{Tf1uQFxNZ4etA(xBz>Fsa7 zfGX3Wc279fQ3e58C_q|1QEy9=Z2-247nEJbqTX!#?{Yr@c(%6>w4YirTsD?S=8mOU zxwi8@?+rIaN+Jn6)IiZ3K~N!?J~1&k9dLd>1Ss&K)^g^0J0;N{qgZ_wThf0^_*S)b zl+muKR?f~XdswfCiHXTXb0sItt^cevtP1WY&kuVM`Q73B5DlGwOT^$20WF#0v8dOo zfJTVgVa(N1AO`0+O{^9ZD^AF{3sK%&4`QODlbxkB~?@KBE@D2Z7$i2KO=xu4mp}{NPP2 z;=^zuSO7R20U6Dc-giF9?0xoCeCsDE!gSID8+L{bUB7p=)#$FOU8!6%BH56a! z>HU4|L+ZG6$6mC$OeFtHg`(j2fO^~#Xm$ZNatj@@&3M9sbDy#~@)SF({*y5xXy z@H2>uyxDuKq~4$$hrx3H1`YIgNQ(mj1cwUK8%GKlldB{Z7246UbGP$pZFA#%@YP3#*tO4LM(4%L*-E$V~ zhTHyezyX~p%i%8q(K~Jga@PUV$BL85hl;Uxw;=A!hkS8l2>Pbfj(H`!vSQkQVzG}^ z{^4pE)V~eeU>dJ^(tLc;cezi+^?*`Rb~=!ZOq!trNLE1+p1-pF3N${u#>=Hm!EuAb zdGy&4CZOmv%>trBsPj&LH#Ho9lFWISTL&bI?(f2f+JfD#$kytQHC0=omIkaM6h@B* z^!G7Tf$OBzu zQ8`n!%QE5a$DPG?w|gV<2xa$d*2u~_{r*M(j5pqN zDgAM+zN>r*P|gZnMQZ|?AM&BC3SgX+vofB%Yv+B4p9dnO+c0TB1+t94)de$(=2PCI z(pN1s^vXN|DEWXdpTMlYbu)k%DLsa;q?6Ui-6$?*bY_|<*IJUG&0Ign z_1w*^7JN}TR3%68yY%b+QNJ-=j`n5-4km+$Ka)=Qn8&OR*>a@s1+7A-VE&x;0X9WW z#>t|LSJNomT_OfGqo|M=P%54?D~>kmF+D#_a3=_yxdMO^K_LvQ*X(EP+H9$zRA z(;x+%<}JEEsKROl<7h@AS~0m+pI+1_3T^z9xHC z1K>JK*XAdryI6|wxS|v&4+5YhBFJM{1!R^Yl3$R&x^oDbHs}O!TJO@nJ2=8J`L$Q?r&`u4+c(-v&%HCD0gfeWpK07LLD6&} z{2zWKfejSeK2yuknI~5?2LbTSPGg9t5%TWoAT5wRO%Zs^#(*)P))>JwWzK!LR31hA zZ7)dD1mri6<`&!*(j)HqKLuy>q^`ArEC&{`>u@Ndn*~$`h3OA1r8)wIgcdw&kDleb zPO2yP`SUjMgOzy8A_Jm{@$n{-8Vj+(E48_1+`)F9BycAYy>ALZ=ZRzB_NYKq3r5IZp{$q zoxK1W768ov3sr@r^g`mtS1wR!WQmOKe|IQ2?XNaQreX!C2;?|{Faqpdek7p+5V%-c zEEv>+DB~BQZ1*&CuC0w+Pr#-!bi+p%`AEnVgd?L#b!hjX_`Scae7>jjBRw%xgAO1 zTl}BXINa>euB`&S%^z=m>eRDntDSB5^aJSOUmf9ymCFe(xy#BNgE|@ObUC$r-ch8N z0)PcbUc&&WSE}VGa)GD=j^P!pyogXWbG&Nw-&JLL2K7v};x?zft=rmIn3VW`X&yHiO3ldu6Q z&_8wQgWUfP^4lsD&E+(!WDyBBDX3$s-<*W;ic~^`3uFX7JHD}_`RnIthQ2MXt85*w zx-Oci&Fr2Bh=WIX7RYEoaEI<>Wv=eK74c8V3CC}!J*X!c8)LPpFms%)Y0Chr98ha! zoU)cubj|HT>YdOkYluu6KZyjj6uBN56CHH2s_r&1?8wwoXVx=O=B#rz^>h^z-2psD zLL21MZ`Z?1vylNWDko8e*+@{lSs+hwk-&hVp>mM|o&Fm5ej2D_6FDxjRaSM7QUG*^ zwKQ-x*;Su}+`0mpGt2K}{*!4u_Xw|njw@iLL46So2f^lLAvo}xgcfAe0|znw0G7xS z_}Gis68Ui*9fb|W6Z@dvX2a)WpnWl3ozcW?rvE_+I?^|$3HVo9I51Ej%D93<9mv5e z>Twf+K}>`ICn9=YAhr@w$z~-~HyFd3&lYU}iE$J#uri`pToD0$YlZ&UjX<4o! zvR4QUtw1;Yf3S5V$cBV~$^+RDgu?}cO6`ci-Z*X`OZwk6+5eelsErYcZdkAo;K(GEybm7+RzQ!P@R9ZZ?|#HxTk z`g;H;&q?`$YP9#Yial1PlMAq5C~hX-hcx^H|A|kq@X)+!-D#9}8fZOpv;|quQv<>1 zClB-HRu+$dW+qyK0r;!(YPosO;5+6%?ua4V!J>m( z29!~2RU$I0V}_75BHEV2xYfxOPTYf8w5Gh~?#NbX^Z@b{lU4;n`R zRn36jUj-MrEb{Gco|JbIz8iNdiyhoWlZuK+s{H`ff z#i{`LG2~-^4}ff>=~9bC_PXBAPxr%KbPdL^;8?V{e|5IAsAc z(A>nl+Flm@Yq*ug> zdK7z@cH=#lfnRG8RMyoGoquJxP>L&2=WpxqxM)-5gWZ~`B1;KxQaA1 z#@cP9s>9yHDuXl9YujSGo$#k#!jTB}e&JQM8tL11JD332yYB98&jQ#v+MTviM+Vu| z1T$tJudqzw75)I4dgtvaP#WVCzO%W9eG{5vz>u7 zYwO_zwwM6MxzC5Kf5kAS(XHuV@mLHCWv`0omRsO}C`~DS;0w>U7w{)q%28%7n#2NJ zj&8o0-gmfGmH?hUF%y%vdzs+HUj2lAn0H55u)Xk?v5yFh(U5JvZQ?hDHZscib*kom zXFS%|8JbJ$sk6YaH~mQ??|R!XHlnrV$wv4G3f%Y6+0ti-|4irOul4eAHjPq)N%sz~ z-bX||NX&g+gTwpHD-+wFQ?8z~haWqk5vTOY;|WyS={KH;XcoPGw+HwI+=Pqvd2=O?jH)`Y_nvJ*`9%iEgV(QF%EjBe<_I#%A^{xb{xeNA4*9)JXBG)p*ltj57 zgE4k1z{zI6NsJ9p5iK!`VMN-NQ^N#SE~C0h&ulK`!9%x;_-PjjDLwJ(8&9mBWgz8m z;XKaFSE~H`o~N;lrDb-Rr?FlOK?|)_o&W6O%IAtV9$6 z{%xsW)%LDoc~4?iH2(1f;0_xfhj<5gaM$n&YXJd$E_{Beh~sN$#4#&fiSA57+ZEtX zjOzK%EYR2UyLh)pN?|va{PR*pq_h7f(MS~vIlytG{mOCPcmzyF3+UQhRceDVGxc zrC$E&2FIL-s14lP$Ct~RGHHam(P*>{=hF>>{$9QWjohw=<4xBOCMv@2(O|CXs=8it z(!s;iG=yuaETJ(9Df(JH8*;34@~Pso=zZyp?Cg?Mjmu>Y|BQGdKpHVQI5yTXd6Vec zz1CQ8+p_FLXG)eoyDQYEs%KVOwjEj_Q=bzS#z8T2e+zvA5{&m($KvA!|b zgJI_jtcnJgGi?5KRF#F)5G959;`F~F)5l*ZU=AM>@O!(HfquMjyvqV&ujg=i!G9V= zKf~3_zyYWZZu>w9g6DPMZjJasRFlA8k40${@nckoMQWAdxe@rBO) z(#B2oSyY=^T+%Emq&SX+{|73**yUzMNNdZbZ|bwQ0*tsE3gkxy5mbo{oN>!^;@|P; z#@u6NH*`y{_o=w^U)p!2o5Z?)#GSI{!;fi%zwm&4_6Skqh)NWBYJrxs)Oi%2E5!Y` z0)rUvhJ2N0wN9z)80rg|nQS4U<$H6ousp6-54@gosY2EJ*Qg;$E_92{J-XwV6&KEk z6&FmcfS#*ywZ^@VzY4{K^X{G7>+YG9qG&E9=shqp_%)M-92w+nRRP|L4Qp+wf5VuG zOmP$#&-X_*2^Q{83HqKi;-ag%XzO=^k@T9Lg=05*(q^( z40nj07bGN@LI+?7=i>^cUB3sFK0WVLGg$M|A??*mN+JP$*$vi@zdp6LxV$O^3C`@W zK4qm^lgV(BU$&>G*!nCH{wG3}@mh3*@?vTSD)w;Vu-MAgrWq`X`%niVKVX3Km9r-S zVZ(Z>(sH3h?*S%6!{^anu_*e^;;@2>s9WS(z!eLrFzcfpRu>tw^5|5zSP(C&sst-| zvls@#J-u#%R2OMBkg-+?c}svd{qeLc-SIS*h(@S)V`BoL^W+n**-6(E$(Yn-KR+5G zT(@Z^My0T>781~O$JPFR>b3{f+=`2C_50sCw~IdsxYU$2k`wyBZON##o@gzdX7ct@ zx^?NhpE`-$W!&FWZ`xb`{{8U4a&4=6<;ka)@!X1*h?p4->O9xO&(9HG_)i)QqP#C* z=LHWcb{$+ib^c`hKifQ=4_~=w+O#bhD}IF2k!m61498a*+{2C`Bj0EOSRktM>JtcB zr$-gV)qTM4CSXbYYR;CkX7Uj6b(cw(u?h=%_!U!xW6Rzsx!9iiikRkyzUtVtPh zPTI)Zsu3AGaOS0Gy7Kw%VCltbyQ9~Wt;o?Jzesc8Pc{vq{Iw5q$`p1VzPQ6ywP@b) zmLZz>c9|&lKDBpvhQZ2p2oC|^^Pl~`caUbdaHAp(e@-^-_*JmAZC$Acj^YCXYvPVy z2zzXMaEl4Nd2U9t?cC~E)6?Th)YmHCqk9F63d-JVtIt(E&&?l!99d=!%tl4nIXRom zAaG2XWv&q~*0pOUEuVVNX({dPlJVt!{hTyc0#P2n?~lc2+a~Fb8*MGuVvBQdGJCAl z;Hj+MF7i{v`-yVD$u12?g{)MIo={=GtbTG0qtvYqxr5 z0`E|J-nrfokz%Pgc7lu@S=Ly$nj{VJsZm#AvVN6Bt(rxv%tTeH81Z0s|NX^m($IND zmW$6`T_9QMyg+;1^5ZMQ$*L<)Uy}IIMHxE27^-j5!6;rXlil(VX;3@#P|P$4-~LzT zyKLtIo-n>-TS3+lHg|(3Al|)HerV=Q^)k0Wxkr z67&pq#)fn8onsdJq3@$F7w#N?F~3lKWR#-x_QIVzBgKZ*wZ)?6IEDnT)R3P;D46~5 zNb3Jl?RHmvIyTT>dxKHHIEveC>1LepmK63aGUN^|)5K3!3X^Ydav!SQIiG#xlehFb zxS8j6`x`5%ckkwk7?=c^OdcC^P5gfJm4R4l|C2FK$k0_P3dO%aUL5=X_<9SVIJaf} z8v?=If)gyby9aj-?oM!*;K3b&OK^903p&AF2Pe1(_y3!H&bj;S``!AgW@=zy3ToC` z-A_OL>v?ZVG<0|E88*}ThZ5z#XeCG^Z?qB@8b`a(2A)xtBy#BYismXud*!Qozc3@g z_n~3YGtjG);(M~OR6|3}yl4bbz8ylV}ys&IB`RR86 z8thoe#kp|i&40^u;LWd&cz8&A49_-xVar~1($05&*eZNGY+@)Mmq;%g8A_OY>- zD%Pf6hrj#9n^yadH~tF6rGgK*fFcCeqv+|%9UTS9<#}b(Fl)FltDWM_mlO&4O?vPB z<4!ZvM#2Qi`_~evbl%OD@wh9&m*<7JM4*3+z3A!9ub6>_X4n?tZPzCBm$D|?F`u$> zMx7tX^9tvB#+37`^bdOOhxP;H6>kP}uyV*Tq%)W+HhG90rwGa?s3u)SuLF@zH!ymP zvs5g@-A4(6J_!3j2Gm8GEKwKMU}*|t)W?a^D18&>Jldwh(A3@(qrq?s5$o-ff4l!t znLc@cWH-Ew?Fxyv1wNEI;#>eVe_JgB@+aW|Y;k}U{lw=$Gmfrzb7Qu`Myn@k)9K8t zV#-1D=|PCn2A^md;znjmv6$jz%$N_2c9W~}<&s?7{8eeid-WlZa55`1(NM|QJ}YV5 z-YyXDh3Y?Gz5lN=42W09$s`5qDKvY{4 zs!$1^{e=fC)ke7i8O z*xoVCyPum6O<6S`X>jr2TYmTKPAu1F9}ET=e2%munDNPAvLnB<4e7Ka|81)<*Qgcl zkO5AgvXioC(1AR(-LuMmqib%vF;ZrGr016GRYMP}u~gEgXz&HeCNSToqK)hw%BBR3 zNPARSyQW!iDQy(X>=DQC4y$bN7dg1#9W#0%5h|-i0n({l{L^Sq%`=wrSlnpa;xMVL z);?u+LH1WVl&*DILs~)-51bK|{aoIvBUv$uatVssq@2gjXZ<@N>xE& z!1d*x7K_uKR}}NvmgH|6Q*aI*mo@P2hR=+WWd3!;w_g6P_&@~o8Ou}os)}+-z&7{| zgk2IZLVB;6?G>6#nSom12|DYv%pM_klt02`Zz3L$C|;HaJ{6Y_pIx3U#6P3DW{}!@K_EFo z*!Y(?wvNvWpLu@roh$Qc;`_v=%Ubd!d!tCaJ2RFFb3($@`inUuL%`m4p&pL??2sv& z7!+RA^aeMDZi?9(!&1jCf2mODYlwX0VB@dGx&AlhcQh$7N~R9{@<9XrLq)@^~NRk&jUtrEK=s>POY1FiHh4eUC;T6UFd zf2-5iEjT6?^YyE(@H8ygX-Zklz@DjV&-s@Ws`i5P^`d67`1DOp zC$wy&?BX!<8lP}pamq-_djAOVW@fX#k%KAp$dGbL_J@>?pqSGqFLOt~D4r0u&6lhY zI=Atnb$J_(lmE3{TAX>)OgCq;jZTXN6=!Ga54wQjbe+UEx@Y~Kp~BcGRGs=yT)`mv zJ0)P)%M_Lf-gwYaS7oKY3`Eoz1hen=tK z`|%@VI`vn-yx`>09M&km1({A$rRwy{FFGEV5fUy8x@LOdGr^DrE8|yU%h1q+dK-xV zIqe{710Jj;(gpRXz>IJKE4(94fhhnyR&H%9IO`os*I>XjU-aV)rh3#lY-gz=a70-f zsrn~GMXsCk>oU$twGc0tebPeN4j=c0)=Wg?7)C@74^qT}DVQl84BCVMPhkO9V-%ZA z7v%RN_tlYfT(dRVUWBJNbCsh}*G5lsB4n|CyX@e4NPD1~-la>D6d^$+(m){DE1`2& z6>DpqSS!W7Hr&5G2rES%8Dl^­uBjvM?rA3gx0Qj~e)3%r#u#2l?JZ?HTi)GvMRj&`h|&S|4e1SWx$Xy!FCnwP(&n3hLfO?gU^pDU zjKn8vm|QZPwX`amZ~u&R|19_X$^?Si*5TdoT{9xZu8c=L<;sA}!UVWsA#dF-e&2mg z@Q<*+3CqeV!G?&9o(Hl9D?3)dW#$&i;#OV|D88tsm%H=hj4j~gBp!N1ZCUnTfG=D&Jy>f| z=uwDxgZ99SP4bPZd-IhUV$n*tPza3}@YU(e9iHthAAE@hsx97`m%_S!M3>-n`?bAD zlXy{+SfouS!XX%HhJ`?<-)?0(8ErW#L!%U--6&JQ(PZ|CMg#5*s)i)pKtJ52V(@gT7 zn*XV3fK$C=%RPoR+9Ln z<2#97y`uAUHL|Jy=#jX`Ged8Mq${_q&wF`WW_h3Y(Faberu5=I?*-iw)MC%gBRyus zG3qHh(%#&sHBM~MPMt**lL+*;KIB{9fNgbx|0?Nj_}1A71$Fl(rGA_P3E|JGZ!M7b zL58Bd^$2h5Ik5{v8l5Ms($KS8M&S|-&G;d+HnGK~Y$$Tl}L)q8f zjRzbVVKbU>KWwyA+9a8`QMuaD&06feYr6^+a@w4O4UBXUh4ZsZFo7rdD?z=EguS%; zHF&3MZ{H4=41PD9v+)zA>18&}Q3}(j{0|H8%AA!j;Pyj>gVpk#9KIP=vZYv`CdD&_ zFd9SzGqwBoJbhWiCC((7kG_++#3G$VHHmpO9fXSHCgpjt8^6?R)vj zjN^wduDwN0+>$#ERgJdhj$eD+*UdIM-48mw!@FeP)drpl6h5pj(mn(S^8J;7`UCTd zsf>@Me(ZnlWD(#twrNo4Vv+W^lFDqi#c!_+*=llZDI+S18fmC)vE6E}whAQ}Bo!0R zbA%!|-+0^J-(AQ?ELhP?WbkU&o&eu>^0+o;yX-UZq{z&CjW(i>J|Zhz7IyT7J4TeO z?x5b2rER$J5PP~5tEusKq%IKh!Gm=b+>2@#P0UCvgZ-F}`EVdd8m6S5*H>GQ(j5go z_1>(d_`~y9vXl=o1?SE<3J4)FNG5qPcKMFT0Q6Y#D8lbDQe`u&-Ajr>8 z;%HpuYOI@#86k@8gF)R`xxxqqg*f;)2%vI+;leUdO?4VqqvH7n#hbg?6->1prGQTx z$6b(#mwq&j#|P`bPy1=qFepZvwTBt3W@FM^^lrh5j-_+1A{*I|Qrd!{EC~&S0v7-m zT%=xZT;oVM;53!18y=PyrcxSWHpapXpv@O}xcf$?rbs3^+6V^>#Jx@e^f*6}eZSwQ zX-GeK*|6V3eXzIQqSp_rl;#IY@xOZntL9qterJfIPb*9+Bn0a&8rUIM-j@?YuMa5> z)p}r;KLT@0|9Eb{ncxAj-nz*w#ja;|c<1U#O=R7|@rfA`G^m9yFgkrlYPDpuu<+^R zWP6#7Bqg}hve33%v-04fexNx0T;#2R+o(H!_z9ESra-zyTyH%JMV{HdFlTb*WDySRl7uVFQ1pTk zR@@0*fqJ=0`5en2RTKt2jtH|->3qq8t=$T3oKy=gChYiNf2?Ey$0ee8GU5gM*4MAZ zE(OvQ*h>|nt!uKpTI8836l{tgJ?scbEJeaPKW-WQcS*6IY|j2Pke&ZBIW=}Wm!4(+ zOnGl`Pl=&X%()KuKmAblu6JG=`Rkkq_vO|%(hAw#N6zNOAMhUAlSbyc1kFi&qFO=3 z7MuGlII+a!POI&LFP>4h_1>n5JLLJgFIkEZh6``vFU3`6WDD#^6Iumhb*fI5_M2Bb z#ky0zeiFK)iTAs?erys1idTExg~)? z6GAKErO?bo1#V0CE=0>VTpOJZw_Vg+8_E&ekrr49w)Dz~F4nBAz}#%Gw+FR;98i zWAq*FZGl`&!NJ$T2NA2p(KjQ_)rJ_Z$DWzgNSchvsp${?ro$i+BP|43nz}Ul1DABq zP6<_xf_OnU2@@}zII;wpZ#0DvQl9X=%+P~MxuUr>QBxr@tM)ApTA_G>XEs&rSV zrlqO~s@Ba@Z8C)z8@zOW-Kr*2!_-lnV&67*E6IjTVHToG7LF*q=&6y=LfEiyCfMSH zdRF9tK3HJS)yj~?6wrA3=e7y>s}mOaiZ};aP=Gz2j0*9)){xR|?O=<<1T1pvrgXrc zIy=35hlA^LLh|PhK^-fngpY4(d5nfA2}%>Aw88)OMK`408e3)AfF9pxUS)MPkwY{`wwZ_n9ShGO${vox0vX~4f zs?++2_veQy?|@p_*c$GxQR4}IBdol{;7qAWOtS+=mBhId50M%cXyK1&&?{|U5W#i( zM@RWgU`am%l##lc#NIla&mE{qDnw8|L>=>BuB!F-JUGg_6*=V5EHITE+SX*1;k|Lx z5zPMc2yf}>8EYCkg5KB^8Y&yDs+!h2s@l-O(WV0i5Lw21B=YG43S6nZ--)tjD6yzU zwZBiY-}JsePTeoZnoPYZhd^ZNT7mT$`?>0G0=_sZL@-i}FFXJ)L2y?)e8Xevgt7*E zsS5giAvzrvl2I)ijPYTb;u))I8$%V!1{||(MBmH&25QHcQa>_=ij!+WyLzrfy}S~{ zjwE9BRlK$3BigJILfMWPh5|CtuKL=$VM{q_b!b=70^2Bsi}7}n^Pl9Q)Qs<_HHPo9 zpv59Iq&lXn@)@Q>I$0&+R(ath9_WiYPa_CpBrR zJK4+#!bI+<(P~Y|f2re1Xrs&v?OOGr%- zCZ_n+MBsz4P@U}zaFaNPIN3LdPK=KWGU(&RNh?d1yCg&TwxLd~F(ym1v>|e(ViQRS z17FdB*ETu@?JY$=LfreNXb<>vdc?@~a?$N^py35pVu^}guJOWf2VVr;d{b|^!)oZ#_#kPr9uvll-LHKCOqHguRs1kAbSG81#aB$gie)dg#lUW z1Bg>3}t51gh;=y>i__uQR=Pz^9l1Xn^|(&4p@P$M>W`9u5a7 z3nA?%7fk+wO>Wtr+1HXkr8{DuCq5JN$ncNb4pzpoU^7>U{H9%IQ`BA)D-P+-%Y(o=)QOe`$Z85C}I=!AMEr!H+iY`gw=wg|(wIEDt7(#X9 zNcZmOLl&s%nM@jTyPH!?X~W5~aBV7YE0D{ZE8A=!=v;op#D2qHpw7{xAKYZlQL-if zO7O`oBhbHwBT#D0+-Nd1Nv?zs`c5fDLYAe}ePTcv&OR=DNhgNL- zk6^f~$V!s5Zvl~&Z1znWwCR3y(LnaTKn4CQv&zsC5=G)gQ zpLImX>=ny%u*)x!6h5ws+a1Sip)>W9%Y$#eUAvS`wZs2ArL;gL6)Uh@4rCW!O<6Rp zaNR#ph`xgSD6c18O<>hO1fe|wHgqP?F4envI^h7%XIy1ib-%0_{0mWl|I?8ZbWJ}r zq55%Xr&RHY2H;sf@wm1%j{U>o{LUW;_#8vZKrh5kljvnl`l_9Xr%(s-+=Cp3*s8zR zME$1`b{%Wz?E_JDcZSuEu}Ndk9`mMk6B#}^ykZW9yE;djbjDYV5n|WAim^;i(#VvqDgdf5@Cbvl&v%~xuIfquQC_q+om@H*v^U>GBr1*UVSwqYg zP18p#=pdso5hEJ$T2*K)brYW@IT(Ltxg7tp#?h;tJFkO-1Iu0WcR$V9G?SxK9Hj1P zRHUoFw2eQmq;?=86l%h!Mfc!N7AZf|&ZTQtG)m9}6Akp(EQNR9eu^II`}XNARE#B} zV+Lex@sE#MYFj>eztTbM{KQ|ipc4wX;5$S0COLl6h(OKlL)HA4lCH_IdyhoNO$*{4xx@HhUJUtuAAq)@4=Flr3v^94|1f&!GhNSVP-al z=i6Y%YS<0-;lc%CTwY%Og5~#K&(%jg_s*6nj4-2g#I!zZU*vfn*Uu&*(P6p^&W!Yh z)O;3WJrZy!Zx#o0p9+#){KLPn5#1R=WqZ7Tl>#u0W?(lA0%hxUiuCKY^jRNc=^6F^4&S3{`-Hom5fJhH0B72RnLHfn6!$IxN1t=71; z&z}L2LJ5#-(Q@S`(*|;0%|B|=ul5el9-JLfeRI%B@B>pp+}>VeCd(7T&_M(z1h~-7 z@h+g<-?>GP;B0IqAUrtOgudm=$woquvY6JiqBK-1yYxN*S?bw|_m%O)v^ZviUu|^7 zy#+!%mhHf%+eI;-Jp>R46Li0P)X4l{bXhX59DOv#3r>t!Xx>$*@@#+3Y#V>zEh2*z zr{4+K`KU^jL6oDfbI%nQ;{vKpY-HV8!X3LBMcOtAt+7Qcv>8@Qv7wF5jmY*4u)05y zKdWBMc5@!Km*vV^kG6x=ef>O0CvRnvlb>fG3On`xk_+OPq{|75n zq26P^JG^9}i|Pfz&RyD}<~7svX1~DE^7X&yseXaDzrdw-YXH+Y^}F*D(%fMMNGbrH z_@Aab4~sCs@BonleaA^puvY$L(Glpp*Z+UvmjP}ubO3s=;e5W;r+QtB)HM+~S0YCv zwukN=8_B2DoFP3)#*Y9GZkD;Fa-uXx6M=f7HSf~hsO@W(rNpr+uBq4sOXf59y%*z$ z`rJ)A9XvW*0?5~J$ECy+{X$B1Yq|XbRR;o9(>D7$DKHpwwO_YYXvA5Q#0s}eKqocJ zH~tDBH)^bi$@aQRCF%;E(8h5VojoX3lf(1FBOPm&3&+uPDE2o?O(t*4WQ@x_?z%qF zRjWtrRoWZRcYnXCRM$X8JGf)8m7^PPs<<;9?oUYCerk)EhqNPmY0kCf`{mTB+wB|O zrHde1v-6rAp4n_NWzQA3zUy*Qd9ytpuvtF%aHOa0=2zvYBqDf-&teLB>jJ?2`Q7uH;=kB1 zKHnv3T%tnnLvlLhiy?Tqtu^1c&UDA`9&dh!htG4iEBz3<d)MZv zPuhP9rhf^3kLyQAKbt8*rG_{7UikO}WgbrDBx zOQU>ay3t4-^DuG=cFd{ix);v|=fq5cs}@|sXUq*sjM)ZMdahpU zU=?-m5(!&d?btLUU*GhpzF3R{+ANFh5AmOg&|%n2ok69^YlqW5-VV`>6+ZKE-wwt% z+|RXL#{`+44d|0h1^RvU zclN%x6=Qpn9w|&L=X?eqZuk6PJa7GeFa|Ax+XN1{MvEa!h!|XrT-_D(48nZ}I-RTa z$lXuy|MdC$bL~&QfvB^6(+`Id{&WNRJS&bqt>oGK;geK6cbDclE!+URA1}UIaVr~G zv|}yR&iT1Z1k%%$Ou5%p#EUa?LL?|4B#K9s`a9B@wmjD%{4DKsCIJL=gJTWePQbie z`i?r9w;G==*J((l>H@N;gP=djaw+DiJlECo$^k%Mft!>^!7Fx5ZG=KM%v`(GD&=pZ zVg-T{PYMG>?ZZ+YA?M6qRDEA}Dbl;6!{L5_D|+UYG_!=#MK?Cx#* zHFr9M)F*m|c)17F@{y~X8%*d(&16XdkDB7bb=xcOYx9w0w|QW1-d&24T`whx*KL+&!Fl-&bkHWhD zVg0;f#kx^putR{H1H8H5@$;frv1T9OxLWqX6acvdan%>?@H^C1rgWwEV5 zx<3T574*PbVdQTcM3EIzHkjRQSSpA$IR(oQH7R}ZsB(YDxxai6N!1#QtljpQt>kd3 zw?G90xMy>2_wkN29ETOzF1`U=`CJ~W9j*D+4P*LW8g60;2DLDM?5c$YlCIoD>C}GH zt<9FpP05(&kO)CdkTx$ZWlgq{%U|7EN~>tH{Nc{(+M+k0eYjH7b4zqYw9X!|iR_+J zAF66AT(^7@n?2|5Tpy;{*qIuAd-)tK6nfXyTSrenB0?Za%ki`KNfkt+l!KJoBnjGw zfa11;fs-!wF5^haNgmAo$T~OT>&+NhnYZqR?8_D5lOba93@$@nYo0GVaog^uCJ4-1 z@RpOh0{fUx=2V@oSM&Wdr4WDaIcHvf_?psk*ZpFzBPh_~b@U<7;04*q;MGKxVyXts zYgIVbm#s9;KkP*WGH&0!I$>X9g|1u^xahFERQFBhd=s;f*!>^&IlIWoH~=^usX+^K zm-yiSP`XdwNTUCZbNxv~Yutga^BLTimw&KmuV_ne9xIq1MJ)YOgj~2xRnDW|nsB+N z7CBvNL>{3-(6L!(!@hzlYtUgqwdX9@acd@@0*j+Y)V4W`-hu)Ba3JyCd#(kHe@b%$ zq@ph-Y&q&LdUjBKv|DXFi!`(9ET^l3Z6|{#+lhyi5+wNKXGry`dI1zUsz+zCIfoam zO^$Up;r&O|)oe?vgNB>evE8)H>XkzHd$usWw#^#Rj|I$*xRvkIIz}ve+)Z2wJ2J!j zbOb+w7mI6wF;1Hi%Fpt#0LM_MdeoVhs0|+$tp%U_)u~ma3N+v-BF7-yiZQvKAd!*z z%sV+I-R+M5ye56#&U@2{RB=n`+zB4{b1&Ndef)VZabHK2?zQ+!tuY$`H4u7|QEoKk z{_D5|Eqv8Qbi_Ki@*3CC={ZhJw9_&jV0-t9i0k}Gl__@lhdFpI3 zKNhOyX^l@$dvz69usnlWzVB(4o-e;MuAX+d{!Nwv5LqSs06>-X;$XfxOH{BZ`TiHi zzI%6jp>1w)K9Sicrv2gA7bNgSj*I3XnQe$6NoFBD*mw%@G$2iAKg%J;;5PRT z?r@{6(Oq6!QQHxOmMcg`&j1IVnmoG;^n`}tRTsc$2>Y|yejfpAoxGpe;f|;om zurnqoJdya66uqQR+KB?Hh>imX?y7IJOMmP*)yR(C+BlKuv$iYN?x`un@~sQ?teixL z=OXF8iKTlxI?fPxghz&8eRV~+J1;M9UnGMY(y}HB-AI>_<;j(A5Z1Te9`1YMx(jc^ zPUPWwg_yZ%?{x)sshrSzH3VNZ!-ulvdOu_8BvhyVmmUa%l}S7@d)b*_eccucSEznQ zeR8|mdh-`O=68*%#1U=)e7YS_e3?$4oyPBL@Q3{mMb`N`@rn$jm+L9X(yY|5{H@~d zNC(55qdgSZORQ|KKO9-}eEi)80sxBM?Tvp+=MQ{6U3=}IzTup?r$l%j8h7-0FxA0& zf`I)&aKVC98plFs+JO#*%3)$e_p1iM@#ZJt8pMDIIZW3dmuADm>0E95_g6+3DJ=Zr=4|0Su{AGLIp9uJL5R|V57R-f)ea8?-&(GYjJu}oimlF9 zZhN?qyI-`BvBl3tDU4Sl%jBgz9vHu$C6l# zAyOpNFKy!C?G_{3Ng$O!yCM@-GBkAix-vF$w~$i1Lcb>TUAVHX?@0U)*Z!Cz)@}UC z(%Ie_;6?tALTKx2&Wt6F@A1s2?`iQ=+Huk2vTWp)&q+Cw_s(lSZRKkqGQi&f;~6I@ z`_118dX!O;a_@?ZF#cer{hk#n-~NASFgYam;r}(il9HB{zV)#6Ms_eR{mEkGXrYNa zp8K;p><{xA^jqJ4LlwHWv0r`~dQXP(%6<&@U)VF=x0gd8{sg(LzL-wPU-X7p1#;;+ zi@+y^9xsw+o7LnPSTu7&LPd-&JKcH94r0wJM|f2ek-h%YDzoaA+VP;xKH8Pwq~q_` zTXSCFAq(x#-$tp6P)esLnrdqs#_F^++f5`*%jYS|-J6R}e0;eE`ynq5otxT>f?1+z zTFV%yIZqOt)hrg5zcYKMdR@-(W|cAZndaC|J-aJ^Dss#;2J7nD7-l~>j2$CdZB z!iNfyz33jIU#EIS)tDDZQQ-vaxTWX>{7`0uS{r2C29$7hc~}DgO|I-)x0C30IPY6$ z0sZ`CRLk(s^n=2lDOY!XFu{ELDVyr>V9CXxTs7|uwR`Z76i~0N0bq))Q|T+PWw%&& z`6{3?GGenwZgmw)Wy{;S05GD~@BhMO|MoEquRpo3lV{4X+}>@ELV6!Bc`($o0f%Vw zk3s`@tptmjl$3T){VAVvD8tW@{$4%&tyW~`+tD;XFy5>;{wa9k5b#vcw`omR5Oh)` z)qd!w_34Nd$lyzU*=7*ZDnVBFBP>&ryP5Ok9rE z2=b>Snu}PEniLmo`$BbMUFm*to{&&oWc_)cn*Z6-zPJ&kX>A7!H9VWJpr6kzL4-5AeI9bPKX@D+0tJM%b+8 z!AQ-Z9$G^wal%>=mE%spC5#5A;@GeiX3ptg*63t+>w zX8Zcs>iL>`3?~hyGP>7Xh9MIP;OIGj&a`ZMu|NydN+atS$6bq&YD0f#|CGwEVq~H; z*kG4>sE1u>&mOK>I)A|BN$*+BRJB3`C6HpFk!D#|6NJi28XFv~?NWIa^eGf#Nkv@;i(y<3ZQk z518XJwvYdZ*mcaoT`)T+RAjjfX2RGF;% zrK41($Lp3T-d4EQ{lHk~BZc8MT8qFN&Y`9wO6WC~vC27M?#z6=n+Ty4hk3Uaa1(wgkV0vlTelkDdEMJmn zwq<(Ch;3Y}Vh~oPWA!mbV}@3f_qj*-1f_)`O#*h)wr)w4{rYC4?)-_r>gc?`zfVj# z$=EDNDzM66fOSDrvjiQfXhEw1;KAemxsLB~K}PqF`lf#dIdNCLX|w(_?RZfR#G!)j z*8w8!!bOIE+iI@X)76)HByZneD84QZ%)yiP4+0vDwOS$J%Qg4{W~9jN>a#Vk<4!;H zTmoil|MG#;tq2vcyue`Lp^J5f9`#1H*FQ#j5cLGk?3Tva4Hvm#>`=c_zUg{(l41K} zxEt%fjViA}hXW-9p_a#WvW7OtY^jqYWpSc>S~e;>`E9nX!ako4CaRCQ(As;vw>ttU zJ-OSweB9c!{aG$7X!oj!R3^-L82N;}8X4M0Kzb9`c^w0rSdLNP5!HBc-YHM~Qu3_q zJA03=pj8afXXX>!T-j`i^73N$xXo`Q(9@i+!Bg%2x~>Y&Wbg1?AG1q9nf9=(#zr}k z3iRowLbe~nok0jvyJV$}@gkTz+nzDYajx86Kp;wyWTbDnu~Z-?_S^}azfP`nIKG)! z2Dk5xRddS$rnNZgZL&=a+Bav`obLm02bL&C z8dC6-ubir+WaIpn`J(_K$iV$%#yKQ7_>FMq&oP}y3Q1Oa27hafAyaP~V9w<5rgzz& zCH>}#IYYiqw*({Y&ZM}wIJQz zEWgD4)r_iQR)ME+0N^AM2%X&OMbv4@Oz{61N!9@ab6@|S=mkcEhUzVpueCKMyr`N8 zAVmp@Q$c(Q0&eW=axw3*$Nh!Kk}6QrL%B_noU7Y$evXgXzMJZc8q z0&*0Y&!#UVK0W-TBV6AoW}-!zbZiLjkEcW$%ND2DWO2E~9#s-WYM4t_cmoY%t`YcE ztijAQKA0q-oG_MSyVytU$E{Dia2N|IS;$}-8{|I!1A@yL@8(5;ieOrlBKzU{H!xI8 znt{}Kcz_|8*9xSNdTHalDE4cOa zh9BXJp5&v>xGb!r@pu?+wIy5j$aJee2qe@@R|Bu<@G5!#{^mi!xcZDfIhcc^K%?qI zs}cEW>mFN;G3Ah$@iGVnKLfYr#uKKhvx__BXAe}r!IBIa6PD!qn(RHtC>5w+#@||Y zxDv^G@KZ68?Qk&<6I}Do+s)n^{+(==Rv$bp&_JO86BNliDk|7LvrV_{Z@iHSz+WpR zqYlEsdK?+nQT<`Z(+d4$J|~9_pT#!esCXV&=VBCXUaKt?aNzgqS&UB0CIw1}6S$b< zO<^rp3JPZ5>!>Z4QGl`HTM1>n`i@$Z*;(CQ1OIXRhJ4^5xbC6b&uFEUmYwyG9TuGw z?kVr5_WtK9zRzFUe%}qP6rPsH|MtW`|0!L)G~o*=aQLg(@MO8p)^94WjstSA6F>R% ztoY@cOR9M0=WnwTO{7(@U*av z21WeW*K<$CK< zweyaDB!z!;7@MwjFL+O?YW<^CpM(mX`ZxVnjBv4HS6xRv)<~QLt%lUD>_<2VPmi$u zo>dArTgsOQ^)36ZkQ=AG8BNO{W?*#~!SXOt_Huu9qRAp}^HTraJbFS_#mD~QWaax9 z^qhV4%!I&!k>a;}gzu=D8Hk^$(h45zHa3-u4^wjw!!QO0MA2AH_frHt3uBSUX*N($ zkjuWdmIVtQ?4=Tt=aI2berzo3?V+RqF21_$^gXeFIp0(SHk4LP912;rRLpUdUMs{j zOy5&lhLx&Q9uq-aOgv4IK&=cR77j)+No@`tdQ9P=&9cZoSl(6w=ssM2K=ozq-pz5!ZRIF8u)I&BB>cKCC0<|Uqa zzw}M&O%D=)|F!wpmxgc~NezT_SgHcgjv^=s#rm<>1w$EqS(WY$;WzRtS-;v!2~2XC ze5(Q(wRdmjNU{r%W@JeMS-C53;Tw8!f1iW4c}WGqmEN+**u0X29iAlTW1S#iEZnkOiwCV76`Wwq6+($R&;+{X#-PiIa-L zxG5%tvIU|Q?Ekg#k^kEG_D>%UlFAh{n-2%}EMJaZ#gC)e44%HDR9smXuCu}ad(Vrt zWD?B^KCxMmyx>7>ahtxQr)czr8bT(JuGSPc-^}}FouG(WRF*y)fn1<&1K~@_m7+>D zwU#M1in0Zz69zb>(q)T-2t5|WjJ&v^%N-_g94 z_)%npQN}6ZNpND%`&Ykz^YEabkG%JHrqtk0VUrxojnPI5F>#8r=(T7S^7iK%%Me#? zRG)K5a3=RdyZ0eRAlW5(s;*aJ+VI@tRX>`WRhCU>w@+`rb2~rdx6Pu#{7OWau8R4N zd(XMt8FA#A6}U{2;eI@$K1=m)sXI8Pv=qF!ua-Ot(H~?Iu|3~rJNbrVKMa_EPDb`D9u@u>d=Q z+i~1|d>d!aJehCgbHTT;2<8r_)aID(0h4jeCkk(WNIdGQG1kt+36E^^Lj4|rp4(QT zJ9rW|p;7E{vxX8Je*PF)Sj8YkCj$?X_R%A=%gkJJhkR$K1-^w^IVSP|$zqqfC7aF1 z9@G+Ljwk6~esPIdew(k9u_3Y8X9?PBeV(0JsBP{wGL;4Tb5N6XogIw!=bCriv7w5< zH#1Jz5O9^)ya&2wpH-s27f)<+-l``b?aX44kgRrC>F<0ySJr1{!XY8az7!l$8;AX@ zg#4LZgHOXT%^5FqddU6htVWkWa>uZ$^OQ%1VHWA`0wj>SG8w8i7aKu8Y`;z!q#ptP_UWm?Y zFf?4%EPC0>^K>U8)qMnO|FR7aIayr7^pX<31dKY5hIl!g;QPAsI`9u>KvQ&E)! zdJE@Q=fg48tdMwc%F!?pYh{=z+ zi*LR%!7Iv6RagqTais=^!W7Me!9m;a;aCPYxD{BwYOC&C#1aoW4k~&zX|9b((UlBW zQ%)dM@Z0>I_WvaU#y#Q*IH&J}*Wb4ubYRX`dR}}ygKgxpFJXnzFw!lz- zXawZK$bm>O=~SmznCY$3?X&;F|_V@qbiEx zhF}kK66N~9uqEM9n-9irJ-BrVJDIr(ctEQ7fIVI0y{!7znVC>~fqqxu=RTCjot*NO zuYV`UG1AE)w55ZAxX;4D>b$g0qI$P}t=ci#nd5nSf?!v^sWuwsa4CoDoNmoY{V>T} z;EpN_Asfbt)i(M2F)rmW)vAGEw0^YW4~6;!{4%Yo6z5WB_&vV8i_+2RbD5TCc1s9t zH98V^p+P3EY!NiKbiEE!{SQ@J6_b1C!nbaWj*MGgJ-7GiueaE&XG2QWhgy3T+c0~) z5I3m;9kkWT#a5P|F7G+c*uIxf?6}u=gCKb{=Q$}16Y9h1zK>{CysPg!Hm&X$!|zOY zzH%C$8j+6MSP!tDA{T(@4|fjq67c)=%w?sD>}84yHYLc##TkB6_1%kd&sh*S+AsW% zDHPJXAOv_g2M5ifl#8982#j+nHFF)kq&%Y{jsBdggG@&TdEyhBe&(-<`A!Yo3lm=1 z+irX6_^MF$89v9!s~#S@2f96T<7z8JPXy>>NGe(Hb*m3s$6Axtqn|h#8SPWKJm&df ze;7B0m1mZ>Xd3jldSd#;J@;9*Dmpc&CDJdz@0J<-Vq2?zQ!{gHTE8SGH^42)v z=d6MqExJ#pCXC-WWC$;z)ggJ9LgoV~(o*VPjS`pz6e*1-sZ?UM3hQu)g5%(53^Gc8 z|8wgLqtWRO5vIZwcVkBaaP5zNu906gzia+mTK_p?JSNhWI*NOHewmw>O#DWxcTF0f zyN>LoY`)yuY?rL2ceB!-?xgU_MJRRU*YsJM~Pv|7@nYSP*k z{1<*0EQ=LcaU3ks4T*7mi?RKv>YZ+JvT;Ot=Lzos3z1Hd^~Fbw8pU8RNfguF1TO)u z_qYR^U-m6~IWrUNp6RCeaPc9MEV3Xq@yXWCOaKuIesjwz>FMLm@Ue2<%H~=RkPtXC z#=QHwGg3xJa7D1vlRPO6E__4f$0Zn<-vK)zPp1ts0>0h)8lSf?!5-TEQtpnv4{3YL zDMo*s#MAGGNN1dNrZxBHWghy_Qe_U^6L0_67Lwf(!fpHK>ffe!Sb~BGsloz(PM+7Yy>jaZ@T1?%C?SP zgdD5y(c4`aX*g{QtIz$e?%}!zo{AY##!7FsV(i}Z z`DWlCBphg!Bik1F+aZ8^?@-=*{t=0k)GzB9kr^T*dAyp`IbDm9QR*&~J3vWSS_eJ+G=4OKFP~pWqOJHmp$!_2&Z0m4qMDwT} zF&xRSsdJVrcEws%CNmUaUN>J#r@8_Y7|+=s`5)}44e2pU~zJ9Rx@-aDf+ z_O0GnIZ8l`Yjkr4=ilMKq+&4LL1RB6fLMtI)8KF4-4MMPyDoA5_(hPho6)HNuiOPScWEDNp^r6c$hYncIpYR()s2Qn`%!7?|gBa*$r)zC;W_6Ji(J z@+|P(z!FziX8lUfH(jps1>`=f&mn`E?49C zQAw0T6sdmoc*F7%Nt9J}rJG}=SHa>PLs_u8KrHYXuZf|E5;~n_d+UK`=iYbxlE2_! z0!3;UJov4%EOPaKsx$@#MFjrfIV2o+9UlPgU7R}-qmaLE@peM?iTNOp$_AK&epewPOP$`Cmt5XiEWiVjII7JWZv=FL8#L- znUo-&AD?zDcY_$7IvySEob9$jJmluzBurB15s9m@|y7~ z;;E-jPz~E)l|k6^>w<5cL=J|&Gvv5-dO?M<# z?RT>6sm9A?(6Gf3&Z<$;**6S4?%OALm-Mjy;+;96_rbE>Vs8Y85)IRA+8qyDxA6kR z$+fU|EQK=0B70PnHGYdYoi<~cS^K--iqnySoGp1PksE9D=*M``z#Pj(l~_t>VZ0 zU}|b=uX&zc-D`EbP_;vw+MEmF<}3-#9Y5#$qIchB%410q+t~W>Ly^%iUR$*G<|<-Ioe~KuDCi`<h z@vA9*mx+@~{zQQ+a@j^VJA)^~0T@FKte z&na5GO099@CVjCG5Mv0VT2*Yf{UZKe(*^sPvtRsI&(8pb((C9xcH7y|amDU5zUIj6 zc6sNYF)ws8xVIa%fQB2O-}9D%oJ~${hVPTip#LfX{G*k%U+6GS#m1d5UE#~oO!J- z`kK%!LHQ#5uRbyeTgul3!3BT4ybb56+LtI9Tub z9J4Bh<$eQbiR1rM#A`|e(ogJ8smZpbskM3M0mY!2G%sOGuIbEzZ_6YVclQvim#LFk z6NmBuN04IjFWjX$K_^c^(xO=^ia+5-dJuY;4fI*dub+Y$yGmG3?vYojW#x7j|#?=3`KG4I85I9B|92pDb=TIpk0>ulL z4s41tXtG}X3J;SBJ&S&lHq9AICJ3XDx{H0URT?jnVn;=@4|L+Mys3x~V2@Dq#6&`3 zSDh)tRgfaAQJNc5qxV?4mrMuiq#YY^k8Rr9;J8YL9F&BT4@dY|vIIf5P#mM9*z3m3 z;N8`0*KYCbYXhxA&i2-3z7AV-c68&>N~HHUpON>N3CR$KL)`0@2Gh&SDK4=?&BAc@ z{@))Dv1m$Y{E>Y^pUeI#GCr)6&3ZOXJzF9*c0G}yUHyosU~r)Q=|wn?ev zhF`|MpCsUnQGA~4sMO`j1^ueYSq$|~vaCeWNp{26Gf+4gSiV%RAtv%9XL2n?OWD*5^NAickk zkoMoKyCDc-7ND7oX?%`r2Uj~;c2_9Mcj`J?{Sb~z@W8TCEjmm&A@WfzUj8nz77XI#?F$LQO7vBi-hQ0LYG7h^~VbIF5Fxx&DF8Yn9L zQ-#kZb_pq;8>TRuVeXFL&tayi%kCPSs;mERk3C?@0>s2nzGA^u6yDU@8rf^jz!w|U zGK#I14)LN)uk^~gAKWOi#Jrd8zwB{RCFAR)C`un0h8WmhUZLkb{9P$ z^E$v@M<0d3W>V!XD7Da!b2!g2yxRlkp@oZ^n~M>Vh=pO8)vWp4z_^cVojVqQ;9BMC zils+z7x2ve7@Jt^p7HS{${*aU>$*1M(`#-Uh{2wSgjmRvY5`o(%R3d1~WO z7+T5wD5P+8OUzc~IBsKf0==ME))I`5BPri{vwZ|`Q*r1W{^TLq^>Z&G20pglej8Pg zt-C2Vn=Ou}<4xGDeX9x_D})X6aS!|3RVE(HU=4#!a>z{%Ja@xDi=Bs~xyPI$L0Hmkp-aSp|`JJ7Xrd+#d&}38rq8)69|7ZZ9 zfsx*S>gwNEpi!?VH<2fPwSWq^*W*2wmPYuSzW0bNq_1UOr*Q0cF4IhZwCenL5`4{h zQ>PyWSQFD8c?ZLb47hmzOIhe=;VvPg0Mit2+}ERcTLrnBapo+2T0!*R*gAHSJa&o{ zuB*jn?Z7sLEwqy2PK|S9_zWOqfD$6X{WeU6VJ9JHe|R?~iVCno>I6)csz~Yr<20r< zNRnAX-0i`$z@2}90*FC)KTVe_K;}@Rw~hjvzFF6|9{9;7Htae}=69^WA+(0kQ0x=E z$gmF)2T#fRqB5a*2oc0Wov&s#O7T-@DdURwLw*vS*?G38O^ z>&gx>5sb8!%72!ML>nK!g#7Yo6yD-w+(*)hQ7B z5ov0u z?o9(mrSCl)jgr`S!v|Hwr-#=c+xiDIc9Hw2r_aO*t({kMqMyeuh|@#Q$X2?rWx0M0 z40%F-*n5bFU)Z?7uB08gt0sykBG8j@{7O&cf|)-?IkHy&i(pFcMPd{cX*hpsHHmo$ zWpWUPi-EiQWyRtv&)qZphv|f(UnLRU-6R#(Xw(K8MZBp$<0E#Choe|)f{tPOvUy-| z=xB+`bM5F8(1T=h^b$B-nv^Ym@APkF>B<)C@**vfai!AONvxdjl9|pvnYYf61DCH3%@9!G6Lf1{Y6JrZ|F5fpV zolT0@m0SRl|DOt$!BIyL@KS^Z*m_d4od^u^xr8a}p#wROe0Qk)irl+8k-4!SPGr3k z(fzG0W`fKO=|M|lbRN-iJB9>*Dqafcyi5KtW*|8nqJ#!+IWYOP#gTh! z>I&0hbWpX-w}!ZQ(q~Wiy9J!vD_lTL7mXfO%~vj}Cbauhm=47yVDL}(qVGxR!x>~X zciKHpjq6@cV`A>2!6l$2sf)T`_#l)oxHYGimUDOt$f=R2!S^=t&aB*Na_W0iI@NXr zhp2sW?zloZej7cnx0=k9lqx9Y_50LBzmU&}QuDNig6+G_Rnmayb_=1FJG#Y&a2qPT z(ngtnMjIeiY#;Sq5_*N%ne^jWnaH8ibG??SdsvkzmqiYV)-8BQGQ+w2rp?DeAoxiG zLOWvD?Wa6F!7q6=r?zcUgz2&JxKP&i{zNm{$>2$a^7VU!!rhhfB8c-{HBgABC3zeM zm#{1vXxiY!lytx8x8`=VVC)rtjcQ49rEZpeO^Kw3@dda6SlVcufUo@sYPW$Op%C}z;7Pw`SpO&P zlP944*d_Rfu(S5ycrh_!_ks*~N6-O(aT3CM zaiW;7S2t%{SHCDd#**M()Km$7bo4jDmgAomG42)--MjF?xU6zRX0PH@eb4fO2mtsgenz%tbHJpMPHHTYOvq4O|I8}i0s4c; z2CaL4g%C223u^6BTR0hq?}z|Lx`}=WgnvdIM$4QUosO(ODDi*4y65+P!-J*y6{GuC z|M~;f#JT$_TRElgL;0tb zQ#&e|W*bm2sdyA1#ztWDvhdM6!CsWVd@GLlrmePn&t!iU8_OC#Jn~y5J_M1xx1%GgUu{n7N|*u!IOu!i zn=cCG)HXC%akST65<814_%i4&1n9Jxj(O89XxjuP3FSkWj`oM=@PPK-XPkVk!4n`E z(KBtCOleAPsTpM$HT*nG#!@%W+^8JXO{^$mVVKvIyO%Ct6eqls{VXtPTqjHPe%Jq3PU}!Gv7?u*C5go%3wTCp{iN%C?@5 z=o9CwzyC!e)n)lsVc2k^#yBft3P`Fw5XYhWKy@%tVH{^Eo*ehf-tYc`E!)*%*wg~< z!SPM%%*CGKNB+!3;TH_i7T+m+jMxcp<%{liVqHlz0rIu94`C?{nZTU|X$V|e?M)B# zXLde@%BMg~PX-8wC81`qOTE^pRbRZRBB!~PFhQg-(-ja9{}CphU-Am%vn#fH&n6v$ zJG1yhJ10AxJ+cEXbPP9}S60xktljOr%Qb7(->iK9B$p){1nJlriZ$&y5gqm4xW+o? zVN4y{72YYlW6dlK{yz66d@nW+*Uboyl;0vw7UpIMBNl;*>q1kIx502WVeR15mF#^9 zmIVLlSS;S(-%iWRDBNGDZ=vsbY1wPdMB{UEkP*Ar*_+&C)yGV=3WXI=8uuHYAQui2 zjKtqcIpMh(IA%U2DY;py`7%c{TLKqf7Kb6XmRln8%U#Bm)nIZT!H4@j)J|ilSFIv~ z_7>B7;92bq@qFLl)ozQG-_ghw(JSmaqg(l-^rsk3Y(4W2xvxv2=9UCACq0= z`z+{hR}Gb8&d85sOFGAp@(s3Uc~GeN2!v?am3bLg#K|LSSupx^DQFlQptj7Qsg9s%Pf&%>}VQ%Qdgx7>!l(y&BaIrq7r7r#e>6B zXAckMjH0^JPQsYz5)_CSZ1!=be8)cuRl-Ss=41Tuh3?27ntY2yB(T?%+o|?@FrM)KiaZLR~uk%0=$T-Ez@? z=m(l~r6bPp-HM+-LaBp%iT)X|u}U**iZ*NhLupVb2U#H-z|fSidIXuXi>ANj&0~>s zcNxnP`rI1)-1-qB)&FaIKV|ce@M_%=R+|k>wh&On_SW<_U8D$!(1Uj3ti<5uXo;g6 z{k+vHBo!L?p8$YLkwmo4)zMMkAN9LhPCPqr!8ex-Ne9$AO~$=1?kGc2{rd;IFDdt# z7Hq(fgmAx9T$*Z^Tk~_vNGUy5o;FDin!x=F)8PqIjBmK+HI3Cm)~M}j=HkO2b`aqc zA@Nv;HC%ET>04c9nBNr#6Nz=_n!-_=1SNY7p8G*}t@;_4J)Fk_{44?Iwyp>FROT7+ zb)pxu4?l#vH78ozA(HB=?7<1KyU%mbHvZdIm@Gjis?oP-@i~j;^@NSZ{^%0}^?r#P z)V)?2kGIKhJIVRIFEcCpA*&=uYW!{o%a60a8S6OPQa{FjzG^PoY zb|Hdt<=Gq3#!R=oY4_s8-tD1Z6-9K4pYhWl zOg%AV&&Kd^uFb>@5>Frmk1vsBmoVE>VOT!P51*qYLx+E>%ymi>P^Xb+7#fNnI;xZ%Z8k$Pg! z5!wIy5uewM*{JafptPraCCBjw%Ykl%2G6m~^6^H_GXbN>U{%v``M(ZiHH^LumE?f# zl8-tg;r~9cWcJlUMWC7|PwZpM_FrC+FR&M)bvtnMHb&?=i$e{%Jx;o^jtMNgrttPl z{nD;=34YtyAM9~Rt=9UOdBf5O`g&3wcK^V8*0*D~K80#H^zPwNRyEk1v!t0`U8ro% z06$Zo@qD{9Bx4nus-MCnw7+=sU`ENmdgcF_6*hxcBhyTKbmdhDw3A1^RL zHD!}C&LvLdA&%AlAiJB>#b6WM9GmB-l|LtFwT_QZL>w36>$wI~w-oaHU8k*VpT~Rg zOjZa~nPqObTaYg)T#)uB-cZu*Il3rLx&9i3>&qsAV+nmgZZV_gq`7;J`z%PKMxA)x z=S9d*@nv<00VQ zgJB-K&fso)qh6EII9LD{IaZ=~(1XR>QP~6x(wi2my#fC3(c>Q7=Fjnxt?PB8M+z{6 zGvmrf)oYRO4oq@@_0GrBb+n%T(wGub7akrT^;$ckd{vaj4h-fG->STtz3gcz9L&{q ztj~j3a2d$jIbbqjm)4)aR*#`2t4u(gqMyo2#qd9^U^*Q_)q4Od0YAty4K0-N2d*=>KWsRBlSR3UEn0JTVbq~AZ9Ri`$`r%X)~xQo2146eqvR2D zs$CWz_>rX3TO8)jJJ6dGo*pB0?_J&>oAO#W!@DsM zGI!3OjH5Y(T4X2o>rmRPov7>zB@GKIv2l4uZAR>T`bqsf6 z#^%PZi)p%<9`s$BRM;iS@p#7B8&4Y)bHQdY7~cnmsR$7XGq)tk;DlpuF5dg!B6L=D zxENgto3Ll6DXUdg`ad}NQ@xg!DZ{hKH>XJ>aM#_1;cvEeyB)?MF#sE9s`Q)qZru4n zL0~|8hwX*+;PXx>bi`n7O`DTqR=@hOh4Q}fPKM2kUALw+=sAzMUq5-W?{N*O5Ueos zIe8sE`lkR6i#O*31CfK^7~kB8Z0UDurRFq^l2gq!Im!f&Q1DI~K52(wUg0kFuK|+E znSQKbFTsNk>D(St9yBdz-HDn?@-c(k+zw5R%0@ckecJ_8I;3|o_|`R@WiPIl1UT`D zh_(#lHMVvN7xn-+3x z`U(~ad29p(1fUyaVa?Dor0Mc+Q5gyw$g-BJbScX6+0bf4pWG)hwRdA0m}GjrZglO5k#`5Y}3GXKRfj6TP@DTA6VyRrOvzNQsJ zW~fSLURkPq<&*6z-{EaBy7MY);&bJX--W4ZYh^vtW;x$&Z$50FR4h zBIXR&Z`C-)>n;Sh&~{1eWo5gE{N9n+brh-VP2s`Z zI9wtjKga)>DbDu9ZkVI1kR*otJnbwA`#dIqG#YP-8mf}8^|c{baQF?U!!fHXLfQ3i zKPY)`ZNsbG$`QU#$rudk1v$ya)J>igity0xUG;A0>mzYCXxvSU*ewYNxl?dC z`A|RPgXu-sv>%<6@x&0njs|C7PEC#Rc>EVVq1|Xhc4G)^3d3XtC_-*mH5(0kD>2!+ zkgz{fQ^Nrt$t*X8^oVifbVM8g?7l{J%A!a+^0~Hzxn-*I<>W9U^9eV`1Bw|F#Bw2{V9i}h^@B`=*5-E(Z zfg+8}MkyF~tfP5hc9s-wFvhEBrWb^KzxgcC8yH${XHhazPI~0QUCvFaIw!6OCk^B} zwbV%HSd-nd7TnyMYyJ4~!LKFf`z%NMkZhxlghsO$!u_w^?7U%Srg5qwxxQh9F7-S9 z4o#26f9Ib8Qo3KdYghB|{)UC;P@~bz{aaR!^+c~-S@w_WE1x6Z7qX1EOKV_|_k4%# zKSYtbtPh&Zi&ygKVrj{#{^sTWW|(`s8(DPin$P4V%yU<&hySQ;7TB>!4qOaKu+cgz zXDDu}ESoxyx#xdmBp++{*&Hgn!{UK{8=E|fa)sF<;Ao%h%t)}I2zuAB!x=f$7E4wy=E53dYBf)PU9$-Ns3PJy{0^q3|3RX#!iB_%=<;f{>% zIM7uQUw<4(?Zi%{S~Lt8qb(v=YZfFglKFLjK$W`ZMPoXA1&l&1$epzntfQxDS&5oW z99o|85fb7xyaIbz48{1VNQ4NJRp?n%(kKF2PpVXJ^+E?6Tn=2*4nbNX^s1Z`C{&`m zHadLa8|IJ&@YtwApVeOUxTg{<*3nVQbd}Glv>I@VZoJ6F!kM#{Cj^%$y3oXoG{w<^ z#>>pa!ntyFfyIZ2pDy3tJRTP*kRX+g96!Bg@gbtXkT5TF$5X>SEYZbF1_1_WjZl#B zl6vwz1QUO5Z-ib(&HgNBZVu%O+?^g7&OHT#I$AT`zD*vg2F(lTS{Oalp6(x4QTX zM(#hbtM@lN9U4`VbrjSzdtZ)d{>1c-rL(iKku!;x)zkp%p9If$tX?VI$mln2HrcbU zHr!5J@c_%Xe$Vi~`K5HTsvDh{WM2iw!eRri{vv~FoR%kTp00=YINMA?U;Zy2KQsw? z`Iq=T@V1MDQda#3(;c~cl1~gPW1>GlG}^5WYL>-z839%cn00Q zN=VN3m)l05(gX{~hiRb3#0%;sg)1-(Ufv;YNJA?a_dBou&9L%pzo{@q;&zxH)W!M zA}k6KDS(H?2$}+ELF*2Yixe=IQZuzt$~hI~z8#TFulCN4N1;CuYCV(~I$y!#D1rP1OWhN)eiLQbGlk z5QJ)i=_PQQFA6d`r2~F0oMl2*}izQJE z2N~P_oikjM?2;g#3cS6XrL+i|;A)x)%v{hT|?^E&5TG0P!fjj>+*}$q- zN0#JMu=J&y@Zr6xQp9)bn!@Y<-*VVSc4p##yg9|v{FicIHP{9x7LMdoMXXE~hOGxq zODi$ru|F0j6Hn;9^JXCz%{OL(2VkyyxchXg&VUbQceM@w1`Zew%2xQ$iA^2WSs8KI zhtq*;z-adCnp$K|^j~PHZY&ZoY9AipBR1oTfFgd_iRChkMg3~-n)~4K))WMB-O`;>CH-Ex)B^Y;io+(a# zdV%wIyaILJz@i&U1_Z%)=`&=nh{#uZtBT6VpO{Q!Lq4u! zA(p=aT`}UMOBOr47~>_$u^~^)h4N}@VoFNV;SyxT7!EZMARRW{uj_v(BV@0;;=}5u z{`!T}qCK;?7*@!BxCx=Q3eO&gA(V)ngzAXRg`x_ohk+FQ66B3gw^2@`+$#be?jVYw zy~$b#U}ckZ8n}4)7WzM z|zV7C>7U#MoWWUpZGk1hxyx zkl9yT4VGERc2$6*aH6ht>uZ^?vJZtla-9b`@hj?!}1iltbbOCW()Y2mahNhBXKlN+eFI z-@J0}!msZRb137SEP47j!`$&PQ^~d*7rFYECHjk1vS#?lr3xicSu?}a$NO0d%kF*U z{%aP%YWRTN^o9~pjVwD*3(aKzj1Hq#n1y8H;kbSqo22;7{tUba7|tj#gUwm$U0h00 z*?yaceUN!8XsJ$2_Cr7J=6@MS|Li@cMe!zF{KBjKLXiF7#bVjz_na}>qf~$K{QaHa z)qGZJ=w|)yJzMb88@|8o6|P1ZZK;PD`ploX-^s{&-CLa4*Me^kelaI$h}|;+Q@2x= zID>{<#IP-lEwO2M+rXd?2Y03gC+sD>g_4uSjBOElKYusB4J(i~?ICUQ=Cb1l@Fb-x zXUP|s0_m@+T3QR>+6DS^5fAqYsXp{Me!?XMTOV{#D99B_X$D$NNw&m={;2{ z)(i6chnfX=;bbFw!?>C=d6q*qBb2ydYL@hH1t15nQJu_$I=GO%iM@#{ro_RFOj?LE z#j9h^gBk1N0J2o+40SQwD}a$*(T9D3aK7qd!0gMH6ufunqZ^LJ9cEew_ z;x`i*8GGZ;{3w^A43{_p%w(PYkjZ+khx`B`j>c?1cLRxW7Lb!lE%I3FtV~n=!-Ei=+uK})-CrjM zuR-4H(4VF(vf|^f)5NjF_&e?5M!AJ%tMfWLzgw^gGo+dr8lo_!7Ba^NJy6Ok@Qv;L z0;}&xJEEs9pnR{F>QV_y?m_BeX%wktayL^$5*W-i=G21g-LU)L?8=gr9xLbSt8W& zkZEP>mSb0SJg5ObLf3Oa%6YV*=T*aCy=?_1?m~4WV9imR7uI}s&27cUL_q7WvzOa>aDz;C~9(Fazzr8x} zDw*F|-0is`Z)(p_AutxVmb}S-@-s5JJU906+{?RqpdaMUyY~#{qdt_ zY%28QXz{izZ>{HsTKf@f?an~%YS3=R%XV8=baAS{<>RmCd%km`eb-}GeH(nkpLLmK z5iDh}kI3idFOkm#gtvYZErbR)Ca(?m1Xk&9@8hbJ3{vc(2_$G%(ADyn`|-Z>w5eFT zb!yz?$%3c8nX|i(9qm~Yje?_dT`l3Pz2-~F?HL)`fmu4eqChg?5b?Mf>utsNO&jF$ z35?sOTk2v98yo064z1pYhs7HwiHO~+7svgU8gtcRDe^69U=5rNw>mJtCj=p8KSUW! zv#3uZ$`Bo#9FVeSwo)|^CCq|q?(H3rVH%(-5DPgF!qO6hCt81KG!{1C=2O4qFeZ5s zOg(Ozq;u7jJ|bGK-gsBn)T5zQKLH08h)B3)r)EuKI>8Ruv~NXvLkGs~cf~{UzZ(sR zOMr=7F6P;T(>`xmmR#n=X_C-1}tctM2!ya3) zm`K>y@2Yfb2y0#79pPnoPoyH)F@EyPJxYJevS*&Eh3+zL`geDX)Dz>W+SITuj=2qv zRUmFM8A!{u73+#*_wALtc|DUD*5$pG6D+Ot*b%gNJShz);BN$AJ=v0*k!)eIq(=?YRcOy;gc!*5Ep~Jkiy%NZREG)1|PCHWw|0GpEHMPgw_=rvF z9G1L;2tw%K7*_*Es16mnKc+5P+MKbof}|8FjuiU?G9GmF*T)se`S*Kz?Yl< zS#?G_?5lD6&1S0oGP3@#t)MprUK@wJ&i-X8gF)X*&^x(AR^j4eS~s1Rx3{h?3y(<7 z%L-n4s8@Ea33VXP?o`QDV>y2HNU>OJ|1teYu@*Pt6SgJ29PpU>Hf7RfK^vTAI5x*$ z7dBj+b9n|a7t+|iW(*(E)$B84;1qv{nO``|>&(aIJdYdyddR;n!jaieaA`k=KQ1T7 zI+2rW>nGmvVIHUZ9Wf;aW#Lw~>;o=d=8#!~g@FlJ2y6p}DY1mf|Dg;X$!l&7F(sAa zBcvjXH4cg`YNEvbxZpA@YYN62vCnr)o7yz;o&*XPn%69^3F#~z3QCdV!554i%4-1U z6ZjP&x}-+ndm?SnI8T^Aq8p6|ZgCR>Vl3jN{biw|U}$RK=_6P@CVz@eBoK<+#3hX; zLI`6JN5~p``Nt1iywg-ceYUNH$=&kuYAV#9f&SpcBJ;RmQ+s?la$F;0JXQ`~gcm%~0oaN=#C3ZFefmHH|qx*FxCgj%IL(#c?f2j7~N-~T~{`}0FWHoeV zxuaL?ji9;rJeM1Cdf$uP_lVAGC|I2W)ibRJ0a3Olh-Gw=;@1V!k9(4}^NT#j^ z(zVoc$JTsqd>#s;*6nAqjt6o*6Xq5CBKqy3#W#4XM=ZBud`Iz59aGswTMIKde#{;59UuvscUH6W zr|6dlcDs$iS`R3Ql;ir_8~8f`r!YK1uOvLecW#Yru8_^tciT2p?E0CX`*yDumyXRp zBPBXtvg?;i2f8YmU#f$imx(ssV)fqYE>ulCZHnFUWmOE&f4)6n>E8w}x7@DVk#MJE zxx5a3^R-F81L5Q2>!lB`ei|_^bX+RJ=Lj9l+0fjn=gz{n8Ba@QSQ}u+K-L(MWj=qj zj-AdG=zYWfW^!=>J~mJl=~y58A^2r&m=y!>1JTh^m^m_P_+r^#ZAJU5aO@#m?ulI9 zSWBHgQl+grF7{!raMJ*HI@c+mA9RS5mrQc#{%Ho0^Mp;8Fi%zbFZdP`MiQir%~hpF zdi2Nh>_#+U{RI})!%^m8qP8I+AyNbA58VCkU8BMA*Y2(%@rWjAN(4bYMszld8(y2U zR>cvo-@Z@(a@WIrYs8?g9*Tk%s>6ie+PI9@l0-gJT^DQ}nmbiT;b@swe z{3V!VtU0}tvP@?W)Pk|RJJ(~HMC`r2Sv>E2E=^6d6u5_@3#=Sda$~p!Y`c(gsvu!cSI`?(c}kc0mAi>|!tYN1^L2yc+w&&v((TyII-cIxqg+Q(v-5bz7E8lal?q|? zNTD9LGdS2p!QLm*QT?Vbi9=*-Q~FY;0pH5U|8-Db;zl;X3Ft^{u$YaGGQCekB_7YBckBqz)$9Sbn9!-Z-7`tj15L8RKQ zpotRjnt$+UJWs@7DJQTU)Ih?q3!tsBE^2O0v0#fh_v$ldu3zHo+)uz6-{kTL@oH#^ zMv|YGSVrn?W#g$-Y97cv35txEtSA-jqR~~tv_qmowf=~}p;w1g%`UHQB7qrFO`<`F zgZ;A@!$OkMTCr0&f5@CIzKk?o(qA3S6H<vBe^)ZLUFOqyB10EhZm`2_*JnJ=&zyg)>h??*a#ZR1{JiQKMvGCy%Q=&B%XGeMh=?pH@d zQ#q{xx8}>?RCrv+*}~QrNA+AGBG`Jf$2#%r+2tt^M3>&US!K4KQK43*9&Ly4mK&qz@9nW*I7XYGLiqT-xSFR*tyB z8g2=J%-(S;QU@qb#5&L5^Jh(^q5Tr*Zk2c99xlz#!5?Nh#F$iDkhduj%IvBrQYQmK zMCC9(wxCl|qT1*M+R5g5M@Hju7QB7}^GFNi7IyacOa_o=VgrL`IR_5_2r^J+Bx|02(am8JwQG~*5JqJTE(xzJXwhu>+dl%U66Vy3kB*K* zXKPFyYvT%|KLMe89?Fh{I-mIBQ$j1V$6K#F%-*Glv0jo(G@ zb!3P_cF`kZZt)q_yMXOh1d!uahowe?lv3VZkf;CXOdYDeJ6*xYlOz+miBOZ?99spnB-5hN=jvyD%|FpVm=D|Tv6m;@C$_L4(HPM^H@foZVm49yYHCx|V9u;h( zhXj2P{K_i$wP>}3K9#)IHG%Uk4)|lQ9aNj~bF0_fRwqE#MMl;o3K}Uv=JjMFAoFRw zy;08Oldn09j}WXuxt?+;$Q=x(1c8L$3k+&j+o2_)<> zJdyd_w60o^0oN|z$(QtvxCZw-V*lrs@DQ%_HG2eK@OFVvA+v0t1seit^n6~E;Nt-g zoT|^{paX%;I&`%IKQh%hO0;-b9JwV2+WLm!JeTNzP1$Ez1elpv!#oGQ)DY98fef>g z7E*2Nf}Ywx5LuTS3#KK_Q`*~m1Y1q64$3u1U0A!Re6ftWHXwoM=r3%z@WzIiHg={M z#L{=(KNLg?VQBDPGU!_f-#kovPD3+Q)3+#CwB!_G$0sVAh1TIbZIT=Yg`P9K1!5;G z_!vWNy;^GUWF0xGw`yPMCck`Uk_8-x?A!Tx&I_9c6k$SG%B0A{#S6e8#x^!tIZpg( zW=yZG=fdldonAm8$;agUmt!vjE!t~JqEr{HOo4%tt)tFQIq_a6S?I_d0kP|SK{CMh zS~!ed0&p&nVrHv0%9_j1V)}z%yy;4owq~I=JZlKsZwQ7eZImmu!-T3%YUZxA6>n^x zaxR|^{~c`k8zty>Yv4O4JNqpJxb!^z@{N-Sx2Gu!$F4G|`~#D$_-`Qy-Ltj3;Lw;5 zLaGvEv}B7G{0#y)I)`DcPumdq<^7p1i((zsBhq6{6xPzCqELD=<|yy zd&h6~D=3Jih4w#8KY8Ev1+bjPRRyemzuI84#tXCWV?7Qf@?^ffv2>fGW^Fq$635Dg zCkmoQq>*jhd^dBc%CfUnB^bK&#W16TimHUJypBAp^`)X)x8PSc0xPZM1()O3h85)B)$P2zlX z!SP2$yaLeKMkOIZG&3Kh_UDjLHI(PQ-xvHau+nedln8#(-(M7S%Jh7rqJMSQX<$Z} z1so0lN|dL;wkHF6dbqu9|HTDU%`p=Ti!>YV=F8)?v#aYClIKpn77IGMW=gQ_vU`q% ztsX&&C0e9dxF{)jIC1l8~GneY$Q4VjvWCuc5tZ*jne+x_Mg; z@2Fb{igDBbxYvuS0SOx`R?)s{%SZ*$Qcv&^K)VrKhBQ$!e$#dT3VMCY>`wDhj$d6B zyI%K64>|XReL3=ARsu+xvLaz(U0m4SmG3|Lx(kw`&Gf*gO|+p%z4S2Jrz4vPyNab1 z)>hjm4k_b~{Lgq7j6alYH^ORia(&DZzsrofk^bO+5sPxRxpTokPT1Ovl!MH{{lG{G zQNyNED&>xxa6w2%*Uj9F6}Yu=-DE-2HkrZ2y$!*={bjiG2K6?V0u830`5hj_uR1k| zY2B+9$h&y=db)DgtMMOq-{1JZ6kb*N10?eLKJ_+QP#HiQ(94mVJr74vVgKS#dDfT2 z7jeCLNm)(L<5TJWB4r)P`qxZWUbdV@MPxIb!FnSUuWN`Ms@BlN7g6bFjF1UFzuD$8 z5_91P+wL;Xfgw#nykkxiFI=6r7SDi}uu)CFm|uV45F}?Q!o@H~*qNI?bPi}Re4But zp+c2m5fBJD?>-2oyTpnA;bs8Q+J+4;T$~v2TS!8NZ#mt zYZC8D&bVp&Y-Tdo&sABn?#B(->xyy%krz*X&rqPQ!*L6z7>fs8)4m zfZgjmYW{QBjRqU3d^=*^;b^HuNHCI)Wp1mElffoiX<)4kkk{olkM{JeaY z+98TN$x0aFQo7ysPhSjw8$0Y(qQ_8UXwV!1q((^SX)atTgda9_P-k1@Ot{kkA%5Z2 zj1K=?Pml*5`krn7*A#iwYb4CTt+IEz2;F`n9bJK^SKs;Q>TMstNBtTu7qML;;*7xY z)gR@s965#W8op!icrw_r5;{?QO~FhL4F1K>ZZ-lTO-g+8H%G*vGf=FUrR{XFZN)xY zM$^|COJJ{Vpy8Ns>w;&|^G&=ykkIAOQ&z-?BhZqDbf2EoENkk8I&ixKqzfh%hopsU zRr;X@`nXsUnF>{`OE=m#4ikIytJ^I$HE>F4DEj&4_W3|QI`nxfk27%1XG0rcy9^EyqRTO)OWaN0M@n>CVcPlBsTmAetwi&1)O4o= zEY!r>;-r-biTLnONhVFzF#}H&;-4#0VGVxEQ0*a6CDHC+_gNr>d-S^Qf^xylfpr(% zFWdV^Y|MV#aIgYX2*cR%Iq-{T5dUxNqFG4(ME`TXa6OrFsum@A*Jkne@3ytx4ZC(s zg7i1_zT%VXeJ!{31&fz`KhfRmh8kLcdQeT2mPbzEaz70(&>|B59sJYoT#%kEr}O%t179v*Rq>3yHl+_XMT>w#L;q$3Pyhf#hn8?6NYa<$9<6B4LkKY{3>_- z!y8ZrV}oaJQ`2V~G#A{`F{K(ZO_Z#f@f;3rr+67KZ`CsJopn0t+j(;;y8K0Wy>{6|9 zeY@b>inyaKtE{BR2)imc)#38Ef=dsNAD*d{elJI6th}g)xnkH5rsQ{+5-b$P*L9s$ z-2DkpBKmKXr#eo!?y_Mc-fz2g?Z>1y{w#!Y*Gq`G3EjBCDD{UpH~iiOAX(jXPD) zz%YFJj?Me&Atq_dmKD0Un8&zby)z~KS8UKdG5mS=7K=ht0z1Hr)>2`M_h&5mowcgs zA`ULbnAn&n{e&_+P_psKO4ERg$nBYh!t~Ltdn)2A@_3H*P4x0RJ#X0yw+;xtlm$cQ zGQbB+D(J6WL6S2N5-?B!aLBz~%91w=3qLC>VVc9dX*?|DPo4HS)?>=rUUB5L-6ed1 z!M^UreMJxQeie;ABf}(gF6*ScFLGJ_)u7Vr%>9>Q2-%QfsNiicphJ_XML|?>;c!X8 zLuyY$e0^n`<+PuPwA*)}?)q{PWkIF>ZdcI{U{DTwI!o+jkZ> z5;BF52T@^N7ZG3Z_5pYKmO)6!_71RJGHVy)eU8qi^gSIyy(6R8TvPLJpnj~PeIdJa zjbRANo`(-K8k`?^G`AUxt+e`G47C{zW%_`5m4#$v#FDI7mbm+%`5Er*DBo7~DE>O^ z1tS7y-#rT6?%f@ej;9+XXZcQ!p~W!@QyifEP-D3>7MV%B5ot?Ztl!!fxGU?#ODDbX zo24^Ecog+@gqRDEbQw=&sf-BUXN;u}c2sc15__eWHrVb=@2S{;T4Dx5Kf#8k zI0i&~won?nCxi!|3cX`_!2xZ(u#fD8Z-u5@zqXE|j zz?TDLllzlg49$&|_hYtg*K5}1y5_)nU^P8=utY|V6FHTZgFSwhl+&bE4G+L$$ME2N zI=v_TvAEQKX4^f!H!KLgb1M2D+Z6&R5>!^un8Q}vkIhFFrM`Qf&$Ke_X^TO);HrWY zuz8Wi$0nuPChfUa=#G3wB4ZYBKaUzrMcoP>B&qbM88X`nCO4&pu&4W+fLmqkp?Sj@ zwce)I_Kk}`@{^PVa7UhZYe|+&B`9fWdJS(V547%OK0K!~h;3yOn(dAOWUMO@Dzp(2 z8{NVaT7C`aqGh`O9gV=O{W^O>TMlpnML++@l4ZZ0ZJc^pz1f(X9&4#!6O!L(>=eIH z?+j++YLWG(1JKw%F@LXtj_utol+se!6U(qo8ENK=4_V2=`;2V_wguXFQbkX?Kk>9D zU@65)R0?4c`TIo0H+XiBOoZUcruo9JA0gyEI3m{Z zxOq6;-#62pOHR%{Bkh!$n(K(>Wv}@g*LA0cTXLZyT=Vl89OzY^X)} zbpzY5sX#fedMW9p{zf-_6zL*pedl-jT*SAL3eN}=6T(?n&-H446B7 zuAay`gl|ri`4?=Dx3iX2qP%p-w|l28F;|1A+Tgk&V`Xnr267$_TP*2EB2Wg|_b>lK8I{{(G4a>aQ~dX{)FxR^^ald@2CB5z>_@q-#*;3o8?#{29>#O{V{Cn z|4@o8PNmh6}rJckgx*@I>%n`h|2zu9Qd);i!CjDA#tt- zn(hA)wIS5=&nY$8Jo~~iJt?mI)>6oF)*eRE5@#M*1Ak%ONQroyp9p)WPW*5LR}1YZ zjRY=h8MXK7VlmO$Q^4~{MW$_V*q(gC-f=;E9n@U-Bz+4gH6z|poX4J#i4&h75IaW( zF=rM>VUO#7NeWQ;6ZWd#fq4$(G?q(dw=wp)Ct{sZOUvvBE$_05p8cN~n6e(;&xY&` z3Ipzb?zF5*Fbghx+S2e9dA|Kuobw5Ww<1nY5M(3Nz?pd=fgNjS}&~v)6 zFg8H`yWFd>p~_oFO)Z+~sJjJP6nthz%p{#l^%3wtkQla`ig^g!s$aTWrqxGb6oADw zs^_@mVe|c#>|fP1qEf!ulg#rPFrC;+Gk>^b8T0kOW&f@;2t||dTZu>!$G`ed2|QSi z%9R=e{!Lpxl;LJHguA6!T4HP@2u)k)V)eHFQ>e=ii6>|9=KUJ}bit89$1`lK@Y9|3 zZ5J)5acz*V?Sz-cisoIzNdhb9V|)Crdxd2u8J0h=)5^+9!u_rUW;L_HIXRZY|Ax*8 z=XH7&$ch4B7SYf0Y=qBiVUF5b=DO;_<7kHlA5iegj@a5g{Y8 zo%tCfl!;IxzLC1Nu%^+?Z}GsT%D$wa6A7P+qOx8_hKgzgE*~P-3~^MGUINz{)H04q zTej|Zpe6AmGOKctd+76!dwBDZYxI)7kV>$QE=-*uJrdqD3Rjst(DhlF?7v4i5dqF^ z2sO{ZtdSy-PY14GECMJ=6pPlJh|HXbZYgPUukUZREeKJ}bp;Myn?1#!#vlno1h81F zK7IeY7*5etQ9TZkcO6in*_)!#?dbp5)c7!6uVa0@b#Uyh>lV6AUfY~tQANwtbjW)0BvrmFZ2Q1T`n4A(0lyCCj zEbbo7t6E#kbb)Q#wK=Ml!nPpIbxx^u{hE;d5M%;7aYi zwc0nxq-|EkJ|C6H$E?)l9gU1F(`PEu`;qBNeopd~sx0N#i`e6v7x+Yx*n-tYSJm9H z1wi!OES|q9m+$AxaX`Z4vm|Is!Wi<9&&-POzV3KMSUb^zU~Dj=aLs@CxnZ4MrYPJq z?C-9G74KM&^<`6ff6%*kc_6c4@E@ZTp=6^E8?XO^M_Y=Q(a`4A&?d)O1dqPwaMG)e z#jVd6wD@ z#+`iqPVxx*ty8DtWd`*wt*?HDuAu-xB9ix+_Oar7&RFk0?4EqLKS}o01r;3^2^Vf< zDqu>vGLJu(L+0h>)!Exo&M=WTpy#&i{vg#gLkten3R^fIVoE0zLg|XKi7CqFER>pt z#tO!gicw(~ndj(c(wSWgE3X!D@ZH}M{h-svn5YWC7QVSF9W8QQkH);iLcUJfyOiF8 zY<$Lu+Ca;0k?e$jM0my5`?meuHQVp&F9tUas&0{%1LN_!!jCnS`A+o8bA>z|wx0Uw z%$)gQ3k7aYAJtz@5`&xY#Y2<*zai)Pn4Z4SoKtM zMCG2qPPH<*VR>xH=Q<;6J5)li?dOs8dj;W3y+XL$$wlrW@lA?&5QeWm-V)4 zIJvsq*wX6AZl{18iRvpyqg9dIXY$-5C^l?OcF+iaO_-aIH}P$1TEv1EK%6K(D|KP~eZ zL#mq11xbJZ&nTSF_4PzgT>L0hW10D;xjuZ+A3GTUT?L#MoIGsf#${M*xBuDX{ly z_*g~5e`u@64S7_&SCOsu-a*vC`u9?^x^;Sj7!KuHT|;1_^PCzRpkA41k_E?FC|&s> z_~nnXpZ2(9O&v{*kd{bSNy<)lqGHw6DUdS>VSqXfrjC+>y*ECzx}y$DcNIFr_$0m6 zGWMx18N9FVhIGvUq|?CFX0#yB0M|Rg4Ul^M<}~m>0qZp=>BeYb9t5#Y9I;Mc#QJ`Z z)Fc#ePDRjXfUD`sPoB={`sFBlMWLem9}DZH?y94}cu zT(q*$48^j%gQ2u1HhZa^J71pYrNe$v*zw=Ff~rirp8x99)Vg6TfaxFHtBrcW&EgZ7 zOqzCO&GXsWLP)>lwGv^_p9i`tbEa3&FD&C%zhvk>nf&pef;FGK`k)~cp(7dv1{MlQ5(R*Y64{kdZymNBT=XiB~=amt}rO$C;fYBtY z^$Qy;a}}(-jGOo#u?x;Lbi&?)*JCYeuq*y!ABQ}NnbX^N9W_E1)1^XH`u~Xch@c>i zdE;8}kEZ-(OUwVuiki*6pA+`jz43TaU*$gFd(GLFU#g?R%7zJG^>n z#{0qT(E|l*ZdG#UNX-u=s9QeaRcnb%zfetgp@H0C)N*-@XdIT>|MLhzerU09T*`fd#|hM zEcXC3ZUV$<#pbsmBMEwXFmXT1bY9tH@fSG&J)=}ph5_wG&|N^;Lhc|{($#&my#`&B zl>i>fUz$ren)XQF3M4iGJ&$ zx6)^L9Y?M=G3Z*&)5H9=D(c~u3BrnCODmHewx4Ck+$Q_ceGfIV`_vC%VejJ$BjV5z#ul~VoVc2rm zqK{$w-h(d~LFiNBk>+@xxxSS~;@WhdxyPcRUlJA4{gV|HnE4|b{>~&%6E8D*vVw>Y zxzWQ3DCISY@=g~QPx(Cr74TdJ~FvO zDehcN{_qS6d4g4tv{$fp7b)6+6FzDU*#HBBEMLpZR1*xTwALjhs z8RuRapw*+~|3%KsK+}s+@qgAp3Fg)KUd#gp_RHVfT1Zc7#~G9D=-s0-19>H|5FbrV zu8)dN+=Yg2QMkvN?H-G1EuRiSKRh0*P3JiPT2V=m$EX;Pyv>!SLB!k8qoGAshzgRi zV_;;kDLV91VOH=ZdLQKlb}knGW249nv{IWj1HW|^K_<(ab;h*BFjWL*caYluVD_W+e zq9BX#Rj|AI=ZeEZ8PSNiP-w`o9cpb_Z(CF)l*sPGd+#WbvvCjJos{R+y?#QrIS%Cu z!k?ZfHc&pXyGShP{9eiPeHca(XjsB8j6;swi=StP4?D~j*&B-^YW434ZT)ZAegN&< z-lVI;2WWC=VUW*WQ?$2kQ^KS7_=D?%9&^|3XIm=zhCv*6UgJ5NIsHd%z(%J~W!q98 zH_m_ohRJ^B|BuCiE0POx!hEV={0sWw``?<)Se{NE$N*aA+i5v7&&<6m)z94qhb8(A z_LVUs>lhp)Xsdg12cydXcMjlLK4!7czn_#)(LQYrud(bM!Gz+VCSsPQDSWKS=}u$s z$47xJvl!7Lm4~-OfdYSJMQ7HrSCJ3dVPV!m#c9j%#)rDG;s9QZ|7-KBHT3}aFso1y0*iar7Hi83_Gwg27bfOBtFVH%%w z2G6pAAv90~;o(=8k%ioz{Nhrv<8aCMl@laMqouz9$0Z9?@4qj##DKZm*fipQqx(MN zpXG%`5F-Sx?-s`;_%2fy=CL`c%f&80JevHN7R=g+@xLWr^&QtX*V)NLxjCJgtsFb3 zmLD8**im&qpHb1zp`3&4>Q0sMr=^&4t!Dh~AB;X+^ez_^vTRRsFpB*s>IpD#Ws}aY zS~y^Pik3-v4KjJuJ3hAj_yeS>B@MWF`p#m4*MFcVRKkit%&(a%yppSv`cd}F6RFWA zXJwl6%KX`m<^4I{&xfi*w86nHDapWbeNb1h_`+j;L<66K7gJ2bLU;PP3Ue;1w9sumTUWeX;?)P9Tf|jgdhDpn` z3cIw=>cJg;aUDWYzz5);na*69MPKs3gT6LwvQFxHQf@nTHLY&n7n;)!j|DBfk0VZ# zdSVBEA1*1Ffu7gdOFJv^F$ZHwXr8Czl6!k`e3zw%4i`f*srzOcMmv4?Z6C++AJ6m? zKyLcOzCL!nJ1l!=UKE1M%}g7!(P^~NBbAFxRb z4fz4PR5aZ5`;s5d6X`ASC%q>v#o8A)ey?-rQT<0ESK&MNKgz!V-Zm;Lko4dRDeei` zZM0deV(x5z56k?qtN%gAMBB9SAshG1?*KQokoA|9Ix2CfHger!0?>!~Q+%xUpas?_GJJYUy+D&_P$RWYHpFR!%or?@hT;q#13L6z_cc zNxjKyT5m?0zp9B--A27|cpP7@xPrD=xL&pbNoqmIJG$yC{eWsm8tc>3_`?PC zoHqVzHP8ZEnnB{9(k5e+w0P&tr&nVY5Jm9SZd(m@8$I5j!PClR$bmza)lUjpxpx;? z-(L&a%-^AVYQ072{pzXSn1z19|H68&8Vu>+F`r6^Jz7((;oGRGtJP+lTj_k z>+(~ShzMFcEuoiUaU*glkB4-i%hGmYPrILor<_UNI?b{D3y(DdqdAcdE-ciITQC;A z`2(n8vtfFbx#?GHIjQ#@8((b(5r~H69Etqh;HO%)^v|HzIs>=BGxT5{(@;)Bq`WKv z0h^TT(&g1c{sUu6OSyxW13HrX&BxOuOZOPr(7rf@Zyx6n>+FrqA&18+-6rc9t-lXf zqSQOToZ6tuYrpNawMFg($3W1{QG2a>Vk!t~B1h&GDU|;jA5RgS8}nX?eL=Xi2?X8t zo?MuxJ-_wBz_<_R?K!b~`jy)NbcHZ;z;r5-JTY6I@-Lm=tqQ&NlW08sV>$GdZAbn! z7_Rc3rkgQlW6UClsqX(#mg^Y`H#N>Xm&V@#UlyS8rxQ<7vCd~RRx^cc3YPSoI|lvS z=YWUq%Fu;i0D&^7F!h>@R!h47K*u>CB^3>H#p^TcumtxOU_}hK;GihImkX82+nX?H zw&4mQYeF}-RYm>%F0vNzW`XkUYjMwJ5{SH15529rT&i<55B@tm_@sgE4}krgLMV_Y z^C-sGam0hRa*D1gEMsM_&W7EgPXp+C+@G&^k_cgY)T2FJ=26QNB}%ty7MxgdF@#i= znJXoWY+G86*7MgUd74@WY2u2%VyQ3>?4RTTJoVG_HfNo^s5~aZ7w*^bBF@MDR<}IL z?@{(9kaeaoSl`@_nVC5TK1E~-5I~P92#Y+Xn6tvcnJq}0npC9t3m~7~xcA&tSQ%ZA z4zLXj;$6)P&0Oe6hu7Qm7d?)d6Tj|R9J0T|!W~mubn-yba`!R)>(g^{#y9dW-R1>l zTf2BvkFR?1wUJ&*3ZfbVEgqmwFY z&sM3R{ux!gvO)3=H)D~e9L3Akfp<&$(gF!+MdVV14_5ak5=i=|p(e+}nKH#dv?RUzbI&NQ?MziLcP|c^dWja9fG29b(A(fMEHzx)t zjJ|6E2^%~bvs-shw0#8{XS?n>{3N~qzignln@1kW?v zIXfO~W5;`icQX3f&;Gs&xrXF@snh|d>?w6dXBdIk58b6xfbgrD5p$s=Q5NKn*2B*DK}$V9CtL zE#alrCY`G)zVI$yK_*7VyIss%Eb~fGh-sAB*49%?TSqH(M_i4p zZo}o#D^Au`ESVCUhe&;2NodYCv0fv&n=-Y=a>&BqJj#i*+BkA7*yeD;y?1;15RuP^ z*OnnOi%OK~%tT(2`j5?}7TVYQx-Uas8;evwcE)J`+8wAd{X4ZD2qL`FTABWMm+pz_ zDfcrHA7+NDZfRpuVdV>P%*&(gXQ9Tw1ug~|3h+Lw0X;>vk`~wIPfNF-x;vPaSCX?{ z@2C0S&+_+C%&73ASO>k{7aRpbNREn1gWztRW+m|SY2ARlPfM8)>TQt>voMFIJg1L7 z9@N@(gMe+Cu9kKN8S3grm8A;Fh3jz35?;bMgVz+7?-QsCn?&**-s; zDJR>&Cn$k?Q<|Hk?zMIC5(Ya1l!cj20O||*SEd)9>!HH z8yg=Lh-m#TSB3>)S^%t?}xG0YEl?ITm_N?~Mi%k6qbYK{Oz`PH%Ju z`-)xn!Zp0t{4d;!{Pom_b1DFWxs>9*yel81wUke9cF|+8wK`UU`8P>)a$fsHPW>!OAvae`9rw1T{=ua3!Q|{(_O#$~-6TKareZ%lz-2%kv8W-k z+9AoFt$TgFj94E&p|Q|E2xXigW5S zQ0@(YjJB7rz>Bb$ZRD$yjR~@Mvb1!ZpZrdHM?2$eH1sQ6s${9KlmSy7jY}#d>ERwA zIZBJW8iZ@CLf}_@#`v<{3OliIC>ng9e^H>1#ytD)2b=CKr9(~-q=eEina+U17 zVNyl*-zT{&ZGX(F^=r)m0j&k%xtL`~Y1ikuz@iswnQD4K1aeCU05$oB%RH5&ZQ7BQ z4>_3S(=#`gs7~&kEDX?0W3H^eGtt4Tpsg*GPI5T$eCET3Yqyjx!9=lKlCPupU4F^M zb;%IjCQ%lxf!BR?z_rxGyuU1d2Sd>H2atYDgI+3u(3-iog#$(hkm#DPw?H+?CHTwz z`bV4*v~JBB1e{>_f?<%qvzR;B>*VBT3!Lh`Je?^U={3H0PCeel@oRaRU>+F#{VDB4L_;B2hUny$?+?E@bqX2KIBohko^3LbAvnhDz zsiYI>Fb(Ji1+?{lv7U@;Y+fVC_l;s6rzv1+srr?Q2zoOJJNRZU-Mba(D$)M|#qM$Z zEiK;2Mm3@%E2Ax$kCY>D&_;~NRRVS}qpY+R&+Ba6EbJMeyY+Yk=M6Vt;f71T8h38c zg@(#a`r_*9em5f0X{+o7<^cbqk){?r_8ZRZIHRz|u zi>pU{J&vD29H4grd@#O6u}8)=WxvHij>2{P@oz7HL%r?P(~B=rV|{|_jc>Wp5=_am!YX-XsB|>199fV9 zS6I>AWD4PS7CxUC5zd^MAA3c9M~DKK{dSn8$UqQ+C5l6;5O-fS`~0>Ex5*71rqz(_ zFeFJ3DV_!%&BZ~}@{i2>L&rbF>5k287>}7__=3MPUe+&2m?07ng3Y6Y0=$=~P;o^^ z#(j*|WDo+1YHa0jrO9!AR)&sC#e5eY4&D+x7rS8tA2f}^V^|GlHTiOE!L6C&g4n| z31)ZS!;WtIznQVrB}3oVpr`Khj}zk;x*BM23ZQ2I7@Tf|0^DP-u+fg4!|5x0H78Pl zFFwY^#;WM64~7IFF|;!PJl1F0uRufKbFj4MfAVlXRSX#M4(wH z2!Oy{oTP{4N5;|n#dG{7bhyUpCL7Bk6|C~iMf$8*b}npFlX+8@Wg~~_^`7v4$yp;h z`^ltgN90pPte{>rmd8VlY{W|Zz26NV?y`FVV&Cah6zb?jo;0*7qo%YA_uus0`XoBn7_d51pA0&^Z6}LZt2a^YhDHe2h z+RBe%)HJRwHiiqusKkHs=MF!HHk**CASSOdV1nc4-(!(8qc`E1_b&^r7q&+bmK4X72ac|zgY6+s? zhu?*PG$k-INcK%Fl$qpua7#=Fk?xorNTo4bIxYHT#=^-uC2lU6F1p+g(RxqR*|QMc ztd!bWSt=D_+7o~98ittEZV=sPKR)546+W%}X3KR6JlfGMIpDb!u~njVsa?B-U_W8LS|HyND$r5%T@XxKeFuz@CQet}1JnMzJc_}SN5xQpLuyYWaiNhyKFr%P z4D@7jVT`u1tusoQq03j}N0qWw3EO<4>$VDDMe|RVcwdfYQiRCy1&6M$od)7u7SiFj zX(1K98Fp7Zlv7!QEQMx{lduliZDIC-kT+c;R7r4_#dw+!tvN8zaDz3cJkXXtx(a1iJC`GHrvJdLD*do-@ftWk=R8H57ZYit5NVu>g< z8lq+qZ_&E%H?gXO?mil(?Osv1ZnFKdS2(NoJ zWEbyGSZ6{mh^7$*PNyFZ^q(lA*F0{ereS#Ac(Xa46@264GZRR}faZC2VbN(^d1EK= zxd;bSRISE`D*b@vc`_7`&pc`(-ciVna)IOYJv-QI4ZpP*8G#RAi^R9>BY_sF;&j~! zeO)@gFAX?C^8_{tT}F(Np|W!02fJ0?fNO?T0>P8EDzw-N8EPZ((EX(6QHru#j;xAl zA8!9#$yq$~*DIz=P?#UE*o@c5zbt{UtR)<>Zk}O4q~v`X(#F6|ED?vy6=rLZDn9yo zRYExLkC)fs2Aak`qi0}yg?X~l8=ATiNwSlmfcw( zK7e^l=14=Ql_V%@EjetSmeA)7!juQqgxXCRP**3?6xjz zT6$darx|bGIcgrO_|d0Q2QvoG>-yxL{0Xu0H+oy$jTjlGP7xV~KtB9NymKqj>JlkF ztg}A-@~ypXe}1{8-p&{ffDYfZA_k0hkM=At+2P4e#wft7_xJaN?Z`EOTa36L#~$!x zb$k%=zoz(y8hpg~D!d9ccO(prhd65)()W{whPKLWbnz2Q5F_P#agSr7Q7e3%=m2V4 zrz$?FraAIJPRSE0N#ucbB2h>AG$NZ&U^2E57z)dbs`g6L2Ke>XCc!*hDqVT1D z1|RDHk_^`vjCKki;sGs26#6EeOHd;w1gh6;GrCqs6glKOm4@CD!mu^}Sp?X>w_k)m z7j-R4AKI>^!|&i%g=SQc@B_8aoDSshLF=}QozVU0LZm`+?R^=~cGCvpT+)6%$ZEpg zP6aiO&DWvb+6lMwt-aEVhU9xBMIIR-$iQTlWb{cz2Hty^M7vw<@!iHuI-pvK83E0= zXr3t~@mDA&;)VbM_C^<8*AIs($@?#w5H|)Q?fc`B1%GSKmh^BNNe^UZdczFctxS%q zH$|RZ|C^^?<^8DDRG=plyjlH+WC_Kn(3o?j)#2nw9DBd>)9GP4Ju~SB4hVVp$X_X6 zuJYdac+Y%j+EHJ;T=O9t$+me1vZ1|HMGU@hbl}Vj^rIkxXmglEf{zrrjm0l%%0gGx zFHk!5p@EhFVf2G5ZTk+q@yyrrR+xKtFu-n64zALtUeZNyGN+e_tOT18^qK)8tiO!u zy6|XV0FO!xk|ZTs1Xt!4rrYQ)XA_SH8$=fd3=QGw0Y&jtNLQ@?*Tz*x2CwVm6t>%# z+e@XRzJVVg@hm7FZrt(8OMF-To7EJ&&s)_i4iW~7zL7sW2aA`mmAXOvneIn4xUI!|nE8+ZB};|D^5Ma~=L)$0it z0YTS6&K>@mKU|ims(sSvB3q1IfaV?+U6n>os6QZV^5D-vwa4vURHtWm<3!!CPEZ2G zqgZ`&#$EVJU}07q#rsU&`X&t1?5>*J`9g@HH}s(qltl zF8QdcXpGxpKc@@)xvOP?`l8|F1k~}msNWgM^Z5YW)};7n&7$xrwG(UjsKPog8p+?ZeoORjB7ZT@k^~&UarX*%{1if>l1UV1 z4W@+sYH`UfNvuRwwyp`Y;wFU@I0HzKxOxqZz7jV`t{_=k=r0zjA;Ke+@oRNt8X06n z(WP@x7$nW6kA{y1A0Z%YGSI8cs9+#Y1sd_(o-4ogyEq0`NyT`XHsGUhNIN<>`0=r& zsc<7_nZw9hDf;X>Ai0&ZiEV!gYZCy}pXY~di0?2aB;R;`=CHl%e9uLm-;t<{oo?PZ z?9fWpq`OqTcZxrmg1&606cZ#!;pGie1*_RY#)^-04jF<6;ugOo54bSj{6`j+8%dwvs8QjhTlllRJsNwc&g+#**%P%G8Cm8VxVM;}+2;toq zsG4jr1#Br~VfT=0F!Nx#`|&kmf@U;4=z1ub7+-i8Na3Nnn)xXpAjX{+WmJ;<%48Q^ z zim2{10lO?)c$PYf}NyZ5!e&PLlEJ(aqsAw0-1BZ_KcVsN6{Hf(wN8Pc)*g+ghTLu?27dxJ~HGZ=kCBjURQR#Chx(wG8jB4Tyb zAbIYBOr-24yIP6hy6t6s-B>wx?xyfOUCYGzok1-x@f*pB@QljzD)LWCXr zTJWWFBR)33$E$~`L-yzK?%;1Bn)KgU2j5xPf3GLw5$4qh9jEWw!A6P;ilIm~t0zmI zdSh5&;#Eb^tAy%gXF8yHC&?o$j-M<}r9+NBW{*T<&$2ugkcrziX*f`=Jub5LCu{hP zA#gzT+Vyaswjn~9G|5zS0?XoUQoTI)H^H9m-0+&uiTibH0y1%Ll4OGCD0_Br>h`*| zhz>C(mM8;FW6pflu?arrG6s^PiivHD5~X(v@$^xWn3sak$z{UH3m?aJ+BAnGItyrM zX@)Cezkc2Sx=<_e!aqkDC$WCvEeyw8q+m?qED(B-!EIo4g>|8C!&%UMDs~f;mi*Hz z(zcJQ)Pd{ZH<|J1Pjy(x9i*eRln~kv*h2s=4q=@{zqgMSP*Rx_ELHD& z0VYbylBIzPTls3iIJ;W_5Pf>SGQCTkyMa;7z3@9s(eUq7aZ)a=t*nI8!VNU}??Oe^ z<89$}J(<|UY|Fen4r<4{d@tM$J#Ed2aU~L4Jp@p*29f*?e%^PROfcQN9(q9V6T&^D zD+752WIHNC*>8ONN-{S5C};S7-e^l8p?lT4L4e+^89-adok}l+hk~el;*FBzc?AKM z#dmPTapg2b_9qgI^^Fd1L-3p4UuIxJh)oots?QH@-X!RSJ`;(mMHUD#;X`=n1=Pxg zmZ}8KF?8+VthwP--rPaYmkp$7kVaLX!g&OXwh=P+2Rm_@3h~Ah%cZH?M$W7c14~fFJr6$QJW_#MDKEf8k}w1Bb;o4P zGv167k3P22FWfgBMA${wA8hct1b%(7FFgGVi?tGGteSw~K!4AP3HTHLIqQ}(nGTqN zbG}3=z1*sT4Oa{1YxmD`7OTy9s0@_BjD=hH2x+`9x((;}Jfv`~WteL2@Ksy{MQ)LW znzy|^zc&py(E%7h{phioxEr=vwwnU+1tsp_tevxw@%DNf8)4iq^3>)H*yfE z1hw)0D@=QhG=revYUVpAE9B6&Sp|A16WD(l{f?Xk;)X%{M96ku9>Tf6*<^i^Q8nzg z(t)R~-&1cb3>$#)ZMChQ=EhvQz~E^qu1fG4{@J$o)3WFAC};CZ%ISsxw7J{FN!Tj@ z4&(LrGAvJ@Hfmj_*>30Xw0;{4kLqX$$$n*-zb75|OGf5AI1c@B9tB9Ub*|=T&9h!f zJkN8G!BvBRJbxA&bRHf|JPPQ~Y7?jblVu|4YhPK$?6y}R&{3_mVxULNki^n)ZxA^5 zw{_|YFxE!ZL)CO+O%;7Mck7-6l#YF@Om5&C`+S<(9}j=$1)!Mut@S z{duE!Df7xQ(<*!!pJbeoFe5(ZCH)O(jS;m14?>Q0rG(c-V#y#^=Ox8*<8pMOzkq&N z0){B=J7GDVxk@z=8G6iy|1U>I$qZep8h^^jz<)kkF&7^WP5wOGbp8{I^F#)YAQt!W zOQBbPuB~hmY3-;>CC*Fy4J6*Wz?&un!+vI(s>kwtP(jk~A*wplr7hZeT(=fvL%#@4$7NPe#Y0$v? zQK?So#+^0SZ+G$bmdDH6`+x*3DlmL|d%I|oC$^e1O|JOVe_C|jLQJnYn)9!vOx$B6dYOJl_o_Lep zlaN-HcLQ+58Fb$hic5IIJqG0L!(l=6OL`Q`Vr^@}jNua4r9o$@1OrUvDv6=G6ROk6PrRTLE|97`B0 z4=Kb$+nY8L1iMCf^&;p>iI4WN@QIuQHwq#Kthk#qdtD)b>cu8PKIeIF@rgon>E>l~ zld7e)#q#_VQ*Cb7y=6^3rJwEMGw|>c_TwAur&*QO>94Ift1y+>_RO$pu#QqM1>p|; zz<5^2UpC91uiO?S@n>Hi7!G3vf@h0fU_YhaMG*D&_Tu9wzkJ+SSP%0gd!cxHua^1> z5c%&S!^|Uc^;Na4kxb}z`A>UtD{XTUfzI*IX#Vu~fUx?zsf|AWjr@@HcfRA>*G>J1 z$>;AwTc#jXeTzgH{JH)!g`q?(A?%K^L6*uS4P0qlus1P55<|z~QtD-=|*&!;#2N#h>b`IbM(P7cQa$fWo`!}I;y5Nd7Sm5GD znU~E4154h;F+Uw4O}Fur~ti1VN06jN#`#L_JEMIeQc{TkG)z5x)Y$uQq&kk_xUZyzJdZ zrJ4ms8!qjBU+gFO1qA?JLxD&5!TT8oOXK;-9bQ~*kNGl#D%`rFW7zc9v6YsSf>@2`BC3KVC8 zPXs$7p7M&jEKs>h6Hi(%6W$$aaux=BepO;qCv)LO-AcLt=|j zsr)u2Q4HP__IEC=gn{@-qjgq`WCvSS2L;}n*UD&VnuBJ7RRanSOXfq6H3zVA-!)R4boMsQYH}HiSm!76yS6aFSK-tmRmfTDU;h6b6(_+iN?eX>y3=bn1Y0)( zwX}PotA|l|35~W6cW!y1y-nE43L${)fD{1|Se`^dJ@8pO6sUJ1BG2_<-G(UXT0itD z5ejE~)Mf!uh!uKCMPZr>pP5rg=xabgfaYK?undyz8jqvlH+^s0k&Vzfqr#G$Pmvg( zcHL>5Bm9_%kcvVEB`L)IO{;+K7bdLoeL0hpKDhV>UZ4*ZznxPZaB4?OX71KnXXqv2E21F6Yen3*)_ zu!_j4IPr2AV-5uG?}Uo=Z22*Ht%V`T=9C|Ajx%~FhuH~XzbFbo7tJ8xWg`X3K&=7Z za>lFrl23=iZ}9Q&A4bepWa+fo+%TB(J5pdm)w42W9i+E#AKI@osLY1xrk)d|ICN{i zN12gg8~_X}vHkqD|Cg0gJG+?LyEOiFeLioBXZt6%SBv-x8&D$|%&a0$TR;nC+m3}s z$vWqsx?VWWf)wvGp}G*_R&Jg_)okgB!`P2hhZ zSTwQl@E!%f^AfRd)rqDg2F`Y|6)wYlS$cw%oOAM*WU@Jq%MvvcJdlSr%FP-XVw5hz z%pP@jN`SSR0=t1hmLN{uE-Y|#_U)6&w6IrGD%X1ijEBG!ZXpk2=NB|Wz^}8&gNj2x6 z1#)mMn%uhnDpu$y--R(mtL{MScnm}naT=;S7$mgu!5}&7EPcVs<5GK=z7ywjlpp;q z^)OCp)$Kq|<;JMe6ILQeA##O|JGGvLuj9bd8ZJE%>=)uzH>0J7eTBjbs#Yb47fn2} z$A5bP6t8Go9b0+G{PFHtjQ^6Gs^h|x(4Sq--Oq@A0Y;Zd5X3*8;m9E@;%LlVNsCP| z!MZUB!EZ61W|96WXZ{7Pp?F>!%7Mxz!ZX_*E#;)giN^BG?cC?sRx$I=9 zRYeG08sLy57dTAQJw?-F^398tfeo-oqXTAm0M9>+LSVAzJfb!_KT#z(U?|{pLOj7dE6 z|2QzIgm8eNr9+{1gJ5CHIfkWT#D@C}5t~C^%O#ks3T1fYWs$DUhUPo&XN|0Xd$`+H z$cJWw0?yP|SmOurqrQ0LJl+%lZ>SW|cLp;eL&3i6y(qLXJ#wuG0WL{zYU~E@!3Bzj zX0roNG}BvdV}Jl-^#1lkNQ&z)+1nJ-cX|TVv<2AC`sv9hV9srM+vVr-xXa9Q+==#!U}q}_fvv<#yhkow znVsp?WO&!tLlPElR{K8%OK0l1ARui65)U78T$-pNJ(Xbdufat(2HPUYu4snt4??2}I&o|%99pS-Usi&M0QS| z>dT%{6WEPDxYLiPyr^)=9gYJu?y%C(`%&IvCGfejl1!w=-FpuV~IolgD` zNwaVHWJf2f{ zz-@26>IU0M3Gp=e0Z&6UUja_g-#68*+@^VW;QIW>=(6-(0=oLwrON{d8!PL3Ks*4p zCt8Hoht4A}@dk{=I^;6+HIj%?37x}n+qp-0v33iPK*>yp({V?OEx>LQQxHdVZe4s5 ziUoem)X)Lu0T`U@K@^1b&MdE!jnt>%QM$qSCPjv07%^n*X03VbG8C%9A&WLjPS}MF zEBWU_kboU$Qyu<*sR|!%>kZ=2F%SH8hM|E&g_780DL!0@J-{e@mBr*T0{;>oVfqcW zEKXIS9{%RFZ}p0DWyfnb-?x0{fQjZV_s-txsdBcPRXrxYfk5R^;UJ)Ka}F-P^ieF4u9B`?6z)7WO^g2vTx?|n$>j=-b} z4^UcAb^592aGb(gq{`9MtK^rAvp4ffZWk9+Y`mNP)MvroT$XrR+z+sC$gbdqTNGzU zs&Gd5uG;OdMs43y|9B{Su98(-_9O&DV&GUNtkrUsW!hNQUTnc$=mDw(06%bgTiH$w z^JWy40Pv@n2W`O~(LG7Y%&>NGUA-7~*Qr%L`Y-GUpl$q3JoFf}XT-PMuyv(x93FzK z5&8cnb1E5;K2r-Dvf^)Hg*(o#>jO+=85Sye1}jw@=YXMFtfpkw1yax;qb#}~gDf#~ zR0QfB$JY`1=28$XeC%1W(*4KRQ%o1&l&zOwh;aiijaw@W5SVS$PCT*|{C2- zm7XDA#zr~$j77R!^FBqCu7`rvN@4^&lnFfC+v1kR#SPemrlx)HN`voeLtcIN0dcuU zIvQ*ZPnEf&@%WrO)?=Jw%`5ionaPd*9mwINwXgS)D*t^?bF8dJ1c{8`)EYfv)?@$9 zY~!7I%ahJi)MedDmtYpI{VjcaXN-@Jj{yk~P)oH55LkLP@{-jSu9!yak0H^}X?JmU zNTuZ)09}Uwfo8_+_BhP1Mhm8YoT2i$8ZmbH{P^9ViN3wyt$2Gih7U=p<~ge3H6U*O z6VHQUH_YV6kGGNLeJ@qOzIP0)0jz74L5z~M;X%Iv(NfDDEh8pSM-|zU7p~_2=6@pD zj2*;trQA&DWpSCqg3rkL3fI?u$%gsA6!-O+3tFYe4J%qAqYvryBSzfn*4N+Z>2zsE z%a#m+F#Qm&kbIj;#t3L*9mcWTGz_dr2<~X`Zb5xK2M%l)7-(lwMd($tIMrc3X6!rl zX|*MK{c~muFVZ=A>)}6VjM(ertMn2{bZXe%z{(b$7Gd+B-B(^u!kWGJ4;l=62tJsE zZy$ZI20?FJa7OA@J!Z-U{KU@9-1b>y)?5dJVtY^gPcWC+{T0*}Tvd+buEXw%oOQ?d zgSuD5TfH3{kOSD8zh6Cv-`I@^*d*U$RK;^G84Zev=_Gt=m0}4NpoL?TI$^NGpq`32 zg42V(=RJVQOH~>E@*4v+%EiwpoRy7d{4c5bUnJ&}tb9`RumK4$eDu?o_M4hH1>(mw z0e!Jbc?N1@`)ht(z|iw4W+=3)(Wf>oU50w!9Dv^8KokcwU?4r3BrIFwmORv!q?h)X z3s(>UfJGk|8*v8IJcMEPvBrUnF2U&lN+d>tegF7rjUGpr%W#k|*Ltr*woRAI9V}!q z3s_Tbq8&b?Y15NVkBDOE*Z9Sz9#*+{{zAD{R^;VzEAH)-Gld7L@N!_GXgW7=P@hH2 zZ}pO5j@9;ADe>9F{Q12domi+(v5o5<-bD=447c!#?h{8=k3JUtq_r1B88@3k0S2az zZg0bpi=7x`X|d5j5i}~ZW)>f)z_)MXrBVF=ik@8|=G)LqI>_U_ke1!xOKG}a0@dm@ zyK@8>E93pp2w$F~!>WTLUxgq*uu!dVm2HE~KJ%?xZR2Y??0BW)3T*%Cdha_IG&Hn7 zW~cvTfdNwc`ufa?ZBE&Ufd69cf@1qpp!q9$f!OA&=o+`HCk-|bZ7KuQa^Ud+_QORk zPW($A`14sBJ0O%gg})1w3hz~yMkD=zx3=6VO;$O~*oP6{q^U?P>wjEDU`jaq4X+5p z@|U50f*=laCY=?`>#ZUj(YqS@*47V`QORMz^q%(=Sh^_oc0Qjg)FS+KGT(XWep_$) zvrU8FV`xPIy2MOn!&}BeIY9~m)EzgpnB!Q>^Bz1ZiT0#I4*piemCxjXz3~z%DhQ3F z5q34N5?18lBvh#w)PF4LaNvwv@9i!`v)3(RhKvhMyE&^NKAwmWJf0fEcwTWEIK(r^ zzCr|9T4I!_nN{8#qb<29;~-uN1kYRzw?w;UYYEP&EBTdsp~(|3S|*#PwEWuRvLk4y)IrTlTAh-c6c z#8UP0TPS|Nl=Cq%$X(UHT08_o`_fSVFDCaspxnpTaMjHdn`9J0E;ClH@Zb@Wb_4$s z6Y3W1bV|eo9=J4O{U1!z^lJrK`imHUGD?1g~(L ziJpa9={zZ9x1MCSvP+tJ@==;=Wp2y!I2~Hv?=KqNbt&Na_9=^V)EMUR{?3~<^_LKV zu3Is@-i=2xJ`4j$lOZcxDy_oEjNN75s;}HgA#34-Xrf zI4L*XUZ(XNmM3FQE<-@aso?Mq9`Y#`FiH@w>3G~i@x*bo5oNr60&+TKNloOb$OVIQl?L5V|FHC}`oc>3eFxf4>eRc`~QcHmkH zgYXe$fGp}9Z&xk~XBpeZ$iNni)IbPV5@$!(NrANzhXW{W@A5PxyGVbb%7q6>huKl0 zCI5z(J!DQt8m0r~$&oNe_$svwC+aezhbcLbykt(!8l_87k!nmy0s!Ox7Z242tTC^^ zb%T*|!}7yQmC@7D5lN-zQDyMn!K?RAx3}^)nKNvY-#K<%9Sp1XZ@0IS;UP5bA@te5O#$1BOXKBw>wMa>0O8QzX2RYbdby8>Yokwn$Xgb>=L6G z=`KV1rv_s*8Y z=(}kHCmcZPf%~fTm7dL zEpSKboIisG?0p%z0;$=BEQV*gPd$@xzfOAF`HMMQ`%;6r0=8WBe2u>Dv-(TU)lI$$ z_%)Gw8)?`#67XPGe&WJRM}Ai!rpKYJ#S0Iu_+|zx5{Zm4&|BO^hwRJnP=qH0KU9dS zAm9sBJv?pENfYP#%{n2YR7tWZs<10wjQcw;e+b}}kO&*I@mO@us-qg(6XaH!isdp9 zlGnq^V$yb7V~Mxfc?sSg?7m1#(}O>rtb*`8Ub}p0tle-`-r9C;>$I(JpI^O5(Fpml>Nx1_ z8pYfM45hIc0h8yli}dk%c++5M6y*@3ax8L( zO?Wh5!iSG5c;Xvm`Y;1@UJe#wxCr-QN+PwICS{c4p^j(ligRan3#Y9PAYbALT8oiW zUGQDbA$szvgzv<{RDzrSiEXz~Decrqvsh^hruVn?wk9NhN<=(G%a#{d+}Qen6S(Nf zi0Z*-Ix+X{DLq?i7wUT;PgHVSrQZ6X<83ytT=QrVLN^mrf$f-7@0~^~FKU+B>+tj0 zFR>d|-lhURHCHyX#_2Xt)SoP?^R?uG9oyM8`c5l$gj!rSg*(sm84???asMMk0&i8Z z!b1j?O)ZqicwTowXu2RQ9g9pq?13_Wl>RRlW`t4xFBgX5&sqcsfOh5+k#2qJCy)=o zy(Y4tj*!8N>!mcUO>aKO=pY#(0gG@}4P#m9>!Ec}Uy#W0P-0NWa3Wy?t5U=Hef(_0 zzQdsRZ#5tl_}Rl4WT`D%B}`d#>I$OPB7?DU<=n1x=de*a^Mt0@}YCQ0Q)t}fJOSud5Muxu5V8;&8Qo27js($;$>ia_`C_`#Yx{E;AcfPyZ$n5CsVjaQ!q zo3?#1QT@VU+NB_S>M17i&|7nx5sI&x8SN^WuWrX~)^QU6rp?J9?f6Fmh-}T4;*QZ& zf`G6UVW8(E6n!9skI9NA&oZZr2vCEc$X2^PT6Sq5iV9A2=-+Qhm~eS`(x_oe;g+x*pIZ9K#p}Eq)%T)QJ+e0k z8W|X9N=m$LKVaL}V{A<;f-4ePB(vYO=y?<%^GArs(Dlqld)k*L-fDyXP^L3lhp*Ba zQuiNUUOrlHxADkCD#!dh{uVhQP~)-DBuF>#7G)0r2}t7Q|H=0=EG^`&DAhdezrjOK z5I3kFItGM{*D_Hx+PcWhMQ{qqpafyvV9i+BFQ%olxQVE2fL)@b@>nrQQj=9mTEf(6 zx~zVcbmpocJQ&2Z8M{6J6>WTzn*T3aO&oon}xvS~e)K`&a_COai1YHFj zIXS}%k{=1ObwqLIq4;o+IH_5zu#F-_;FEb)otqMgcKQRMPZsA|^w;qCW)nx>gdH{b z7dB&ozw1jczR~yp7TbI6wTBp_cH_p&^HPKX zQx`yjk3^VRPene;$4+H!UM*H>Y@mI&TB4`NV6p*+3q%3WE6$ZPl9ub67|gDTk6seW z2^yV6Hb|>!F`f)rR}(G|`Rk)TpV7kLBHH;a7*LBXDR45M`Z>wWo>%vqFgwD7CN;l# zABp@utB>1Oxn;u#z|T@Ea{wsBi^oW0i*22S!rD!T@5JWJVO3SN{zl3ym)i>Ko)9;M zmXQ)lAV>~;cy`D>2hZn!2HuH{vlbUkfQJsA#k^qf>_I%R$8#I!2vq`UQiZ|2hKyx> zz!4?-23G>#1=tNR@Jl;2uQd59j|L@Jk{M%Tao^f-7u@e=hqYc0tKbMa$i@Pz+Cs1L z2&=CQk`zG?O0NcGzYrr^u6kdHjFskBijRyc_x`PUfH?x?8m$-t(Ewwtm-Z83-Y!2-19}0hp9tU2CnEn=p`5dul=YU6DLW zw1vIhM2O;-ZsUCP1cNt}N_-AHlN>5OxF!&Ms_UNx!tF$FG8F}1Ieg0YQ*+tQo7QBn zL@8_L{pbS~yzuNi>8Cx(w1w+9bM&?Fi^f2%f6~Vy&}l+}n4P#>x4_8zI=X`j={mOB z7X(V|z(-R$_+C${1cL6~6;^k3Dy!SOIBZ;fdn4{U8~AV`?rt6tFY0SKLysQXDT1gN zvu@L0-d(0+6LJ}ur$_>14~|LP;4sT&OrNPBOBSnzK}F-S8BlFCIJkN3){&9c*}&>T z&Gtu~MFzU&j7bg`JQ1f&r?)So(j-s*%A+qwv_0x-G~>3icbFgyPV=dVt+5L5etz&UwxI z1>jib)Y637dYR-ik_x&FL}outgqb~!hr=SK#}2(%)S-+P;tGxs;`c{?*ocW?l0)%v zo5UJcf zM9!^`I-0JsP|rGH(KVhY<0zx|{sWHw9`YfOc(-vIAiw>0nfkr2lMK7H6=t@tZP&~H zU-KH!!2$3;YF~meWmDpY0i7uSP>@jRjZ9WE6%614CV(v>g<*Mc={qA#`JR7 z?B3l_9yB!oI%lXs1n|JBmT=S4Dfo!}sL7ep_8gohnzyX2U_5{371+I2)PoeKo9a6V!jN3}s~^qJM~T84z~$Zey^$&VRKL&Dc$x&@a{@ zlBYtepOtvMr!qNir5kJ8s84`IxV&^n3REF|h)V=n7Z0;m@2t3p9`>rhXG|chu1-&yr^5JXJ4~5yZk$-$8%@zQuG?YSP*7@_!rgwZW&*>kH z_*^d>R&I!;0WGw9w#uGej$C*1p8Emo=cpjML{bU)Gr;1&dd|}E#du8%I#Ien`@*mW z2Y%q_p5^(wFP+pl$mf^mT!7#(Z2o_U4?Z5l4sV>BI-+KdXgKMKY1!G*Uph64Hx%}D zJ~z(&bqhza)nY3G`upD=5qiOP{ag^o%3h{(nXGUFOam&_XeCZ4NjtuMt4{zsfX2GL zKeo8U%XB+6id0q?OF#4V)EZxg7>Enbzz{hf%?d7o1{#D=0kn|f8MX6N6L^G9EI>jd z`v$a3l=cE%aF}lX2@7DJtTrieDHi5k4~isnw6L!`zty`J1m5Pkb`N||$Ca||kI^<~ z!2N1F_yqCv2;ACQkF$^YxbfhF-}d~EJ?Akmr?2+bu7YKCeU=THnaK|I(u09mEmn29 zwWZcJ9;MTqZnyYp&D=H{S|V1eOS9Zpj z8sdN!pG_?lCGKjls&&_Y!}g2t zP)n=Tu9(+ekBFTTly;AozTYZ#F@r0smqNxBd@&wugl3s5dRUGQr!V;hu zj#4Rn+v_Xud>jbm)KQp`gNjUMEh6c7>&V#xT-axS-vKo3+3inQc{%?h7vxLe*aGvl zS(;%=gzh`V+gSkJ;~(dVm|N?!=o2!^fM;k>E;-g}?2>0pgV5Pkqfgce{*Ma-XYKW1 zpZdQ3LJXB1;IgY+{S91Xq?kgA)_Ct>GgS+MrLzY5;||p7YZHYUQ*sR^=tvs7oght( ztBHC&L{2reu*e5Z({FjbCKYaLA^Y1dt_JmUk@|x!k_9Z4)i+gq8-&qc^=tdaOv{0e z;=bhyU}D)t`a3>cX+x~&3V^q$#z(9^MjWP@*-ww@|b?rlnl0vbic=-$7+c}G$|La_-kIMB{1k?4n?~H|>)v8&BbTGqAKK)2eAM2n*?QQ#l3(!DBdKd;i&j}m z0g$D|`3;6kFOdtR6{=QYb;F*wI=#nXv|+#c04x>_yzI5Pl0BqlFe))R@a zYQ~Ro7C#JCp`DpdIr0b9KX4aE0gk^eiGcR~cOkVuEyI0XH#>~uDJD5OKmY3mh@h&_ zz%_RbF{q~j#99Mu^xSHy5H3j^4A0Mp+$~auY;{rZr7a;q(4@3ZbHc(ri zAw7G|KL1`(xZ=a#@FD(f4722;iudHDKWID z9&GLQwcO|AI43*X1^Uy~g_1jzKt~a8x$mf<@<1-Es$XYs+O*PHrfHSKAVJzYVCD}* zV;gSoRk`M`RRhp$mBpqTAqdXDlPU&sGO%{p#buTrIU3%=d!k*pui02vqxc+ z`&E;WgiO)b@7GCi{}fi;ZMJtA7WrjwX2Eak=P0+n$;C^I&`Ogv(=%?M^bN797v0|#IWiN{0M|cdu#;380}vlD#{)gf0L~9j z{W$YUy!qq3nWYCg9y$vPe|g6oZONqnf6JF@LB9*L z)o1AbDcL3IIxU1NZq0y}6}!Yx{!pyYQrU=C$O><0Xc!)4u2BmKuw>!c{s@Sz9HS`L zZxehcy&f?F^c-=jxULPccmC$o0fS+KRYo}WLi3qK;7lSXSDNt+dH=0|`73hlRsoS- za1A!_#MQq%Bj%6zh>l1hZluH<+>Dg>H!&D1U;IC=c)yIP9(qS6XyuIny`5*ho%wz5 zHen3&T!{g+$trid>uL#fzbgl-jgQGk`i>NXXncEBDE0fqx&ergY~^IQnmx4c>ou(D z{mCds#?^?_+@&Lwtb`DgJrZUzvAv(C;M&@{O&7WtR9(a&ucLG3*+Ljy0hqt`=Sna= zwKN@`tHOrEAF<4oK2T4}muo8k2h+LN%mlU)Ev$&*d;z`RWo2$K=M=L))SCsaNy5;o ze^Gt}iDF8hyxt{{up6?@G{NSeFt)fcUQTd3>hW}jm`L;$sd*zP%w>P>__1qycX>ca zNSNc+AOWXGu9^MVUS(ZqTxFLEROKgU*_3X-FOGG5ISGp|6G8wAEVcmX#CgZ^ucp|S z$_kY5)p3Ky%M}ppsNR1%Oi~j*z6}PN{AFe3IXvhAi^7{hW1Pi9=17Eo;?_j*mra)* z`7z)sI{}x?IXmAg$TIC4Gq9!0I}(iU>kTyupWPi0`x(pP%{aExg7=&G!v_IErHm8x zs)l_RBEc9Wzww`NT~>JB=w`S60(858 zk>?YYL4r%_axV*=*GlilIKlexL_>D9h(R9bNtTXH8$({m?^b8SVOZWq)zqIsTA5F-9R%Y7K? zr5bcx@}}=r>4scX4omGhXJwEr@8(qWP=nR@A#Bf~)aoxG787;?oT)Dx7AafEl+dfR zfe+H@WQ^a6w8Ug0>^~O)jR33b`uG4V@Q+|DN;ksfhC`;2y7>y3fetm;@+GpumT-T! z+c9-`Fv++7INHz9eEjDD>%b>B!*Chzcfa^Xl7NtI*9e%Wa9UbL21P?e&zfR12T{-h zD9A)bpRKnvlY#D$ktebFzmB{B#Pv4YZ#*YJ+vWv%jyT6Q_a5ah!EC?5vjhKFyqtvIXq%EMN1S~P>d4zCRK*ZmU zWo7&J&2gC33Fmy#PnOW5C4a{w?`{NQ)Vc?k?dH9a!l}a3 z;c_8jCTadyuj3z3e%%%hb-piqQSv$C*=nb+5Bf`lbB>+fJ4$8UOVE)bO2ohBgHSYS z@5+aC_VgwPkiYUj+8wf6R`Y#-p5fYM4{ZhgDehfZr6NHAZ|u+G=&hC# zr+Zt+=^}hv#sY-y2mOm4O*6U1vZMhLuD+dYY|%wk|2R-f=eqZ)jw)daYSXOJ*Dr+6 zD7%$Od4iUB#0UB7#W%h;ZEC~z&b~k2 z?x-Adxw3uscorAfr@sTnz=+a-eEr-lYqgjNvP9bQPR9T$XN5@ai&E3iitmgVc?XPGk7B07Gz9eY3gT3;wDTuZGS&)Ug1 z5~Bz2{{8o_p_Z0kvn??0j;V8heCn|8uUQLl)M9g2X6Z9UtJdhj4!yDOG4RpmOPK8CGdEY}6>V__6Nj7VW`N6gon}@Fs)57|*9-r0d z5O9Nl9%$^(4El}-Qow5@L%P@QDTG)niiC~x+D-^CJAAls!jY6PouG3Mfq8G(yMXvv z0c3>0v5noaap4#mN(q+C%uLpFS#t|(X=p0&A0!%7YL3sYkGK$t%1_qLP=Q;UMg^Cu zN2D1r5l#04H-`vv9NQlz%M$We+Q!YP@m`{^QGju91E{JPwO{9Sb#~{BcDN8z%m;o3 zw`z+xR4^iO-)!tOabb*)udv}Z6WL3;4d@qYhTid`GrFE5`zrC`pef6C-7Bnc+F5@yuD{(T{P|IjN;u_w~p+dL^17) zYB8-PfjfLxIaLAus1cUO*STK&Cr-i=Llvb#XIt(s4=@F_XN$lY1MH)a$c98d<)N0($n12(id~&4NKabHu+JuKmhCL)sSO?o5G3a3n_LJzf!Aw`1B40N z?o0>zX@DK@WyNpZ0N4oszCzHmq1gvGA;Hn2n>iO5XA_sG!x_QH*T@4qH{TsY{GVb) z#~lVYkmNIyTu95lk=2>ucb{gvb|6tD&vMPPri#rD!QtWe1(jCyoG&B&`fy|5?d0f- zBuU6oTWwe8I@D1`$~e@;%o3Wz`XQV~d4kM5^tZm~PiX3aGJpCAEIFnc^o>8`6 z`V-602Ratq<%+ZKPRDj&IJeff{B3lt!+h4Cu_DMEyFTv-d~K>$fwxU3Zq!8P(h_6S zD}X6$$|ZXH@}1_^isQYskkEU1i1(R}<-7^5`*J7cFwbmEZr6I6gffx>{p}__H1Bb2 z;zvvAJY>}DB28Nya$YQ)_!Whyz`iKgUqBbHzGpU;3dz-t^cXcgzr(?V#HZ_7bRP-=K^P*C6!laY0# zJMDQIDqaUvDZkJ>*p98Hq=YS3SfoMZ(*kpx>^`5losBUv(j`eLTro;f8f4hT+~d1R zV;*zY#GvY|Q;3>p;n|(O8nDEo+E@snsp)UHL2KNFiT%;s@Hd8x0_s^K_2TaY)-n0Q ziaSSm(fP?Z`N_EcNeSz(!xwwA+;@@P)-t&zYx>eO<>I~4k_r6Bv4Y$4jz~;hYS&j3 zQ~aC5Wbg|Zy1-Zasvp7YMXx^2x+f+fDV8KyA6P>iC&F8d-n#R*jv-fT&=)?oh=jUA zxs7f<2xvPm;{51kTuo^dyk7~xPrQ`+p6RQ>{yCG_>)3ZwaK^L4=a=!q47BP}3yc{| z#NP-ecU?-m*D!h)R*@oJQ;YfJt}GYs{iDX%?zCdGs1#x@%Y@0d$1z)>6fv04RG<;^ zLSCTwRg6F!^vKz=R*AGiuPFE7j@(lrNN|&myi^ri&j+}rOw_c?L01>9D0?C#V$}AN z6(l;7xFz8mKk3$4dF1sy1Jz|38Ia?g_4{;RBqj}T!&H^F7~Ob%c7yzxZDK;)<1(-O z?97~0{)Ym`fYsg#OQlej!ae1+3&rJ5hJSyZ5K2`3J?Z1@DYA|0LNuL3KlF0W6i7SY z%gXv{q*ds>Q-H`os1%7VaV_IAx=fJk3v3{?6w;rkaSG2HsFDE(2|<5IMVFBFp9r!Y z)>HNU4kC*6J5`UvR_L*w&TC(9J4Jwmi9j#hZfdq>Xx$2m0EsWs*S)2{IuNk7QS&#U zS=Z>DU4z`DU}doC&~_LT3qW?xiZ>)1?=-+9oOZVw94CxvUW}i+Np~SUUz~m>48V9c zQD->sBrE$!27Qyop5BzI%-4T$S*5P*Ev$`!uc%py$5$Qvn$_HDb@`+MS)?KZZvog0 zdw=p@+DXE40xg5tUm3x?`}{ywziiYtdmp@skAG8#Bo-&^4I3KL=U-5bLD1N!G@OC` zJ~&g-B-n3(jGL3_Txr20kM97yv2mJ!liQjhW6ps?cGE0FfziARUa(g{_PM67Wt^Wb z>$9}gJn4KIZa6AK0J42D$I~Xs!u2K}Y>RbkMDyLS;;(K!FB7S1@nZKUU(@@YCfeTL zdO#MkrdM_kP5XFyyzWy7y$o7Q%qH;HKWa}tYO(FhenV4!cJHWpe7c8UQz*rD7_k;} zLO+tcD92c5ee|H2IY_s9nNDJV_uFr>pff~H(`vp{SOzu1rJXpSqr?15mle*69a0Jx z&6i@80L7wN>UO;-_?bEEO+=TRJ7+m&AGzzsl8=6!uM6?2kOO9&Q^``I#kB}1xPRPd zJWXG}vMFuBreybcyd+2OnGBUC`)9!^NuKw^7kxUZQ&wTDW@-Q%&7-W{q)-ETSBg?c6osf`c7$)!kG5CX@vWf@0C#bmdXbIr`TblMzNhs4>aGe7_7O z6$3{qP~t6|28_in&3DX&KN);doo;QG?xKD;B$}}GB`T#Jw#Nxa4Nk!#4MXmXn>~^8 z>mKPgClqk?xc2%C-UGX(@o>1SH)vY{QAdz$iqqWVt2APpJbB;8$j<1rSE77&Abv zC}L_@EZ*3T@P$U6taV8Pu92CHXD`$EJk*QhaPw=Bwo_ z#BdenBGngbKjLQ~>jvW)oxCd8Xg`iOW)MidKUVeZSDZ=X?AWbXt8^c!y(!p=CLsZc zUlBU~iU*k@l|xeR!SbiOvBH3PJ560Pk61n#fjJpLj#vXHdY)Q}?Tr!z@)l@-NJj|P@X7>$2d`*&ODhK*M)k#4 zoF;7Ft`NN5N!~VP4X7BT?$V{rsd(+e{=uD^LI504g~QY8%z?E@#NiHZ(AHK{wo4{m z7|t!r60L}Fnph0`Xi@$$dRXim00~8P5lSXk5z z&6>o5F-Ux`;bo~OE?yB+g^!i#MdbS4qt8c?RB2N@V~u^@|BXE25ZV@^Z#|Eae3OGeT7a3&z9yel)<`Jf2N_M?)D0-wUiu-Qp{1pP8+O599b&h%DV?3p zGG2@ebW*W6f8*pknH%KzYMK?X6<6hbsDaE4ywoiX=v)tH1lU@P zScYU<9FN<<@52M^Jiik8z#n)p78#hy zsTIeA0fO)=ZD3OyJ~V;+&7$nu&QCMGVZZ?AUWRflHsBtxGOkv^aHFl;<4ez9qh1Np zH-92JKOF6;P|L@xKPs-tCIM1;O5QzeQfQF^D*e2V&ZO&)OGlP@yHi_;l15z1VzTZZ zG*6zGc0u(&C4_>&#;iB#WBZQNJGW{)LTGW4w+lEGI>Jejw0C zZ7)F%XJ(LJzTwy-B%$)GF`4Z!$f(03txEfqFjh}ls2vC9VP2fCAyJ&pHVY8{fx~|3 z#>>mAs43#=3>1}EaB;-adBTg(C;#sT`tibV&xIbo+!tm0+1!kZa+$uZ;W;&`92$a~ z9RdPBfGTC*TZDmXJ)H9QQD6e=F5!5FzA~Ck@p6XuR8vd4@%x?l856&%BC0f-D4|Ak z8mc;Z<8&1pG&MdOIm^7@H1JI^P*~KRr%rvt+gD4s%`nq+Iw0a!%iLB_i+9u-iyJ3D z!AAwT9VFeJ7bQz=kn}ay?4=SbPr#`I5ac2%&zG;G-o|B#nxSU{coqZzH@il4x3tFD zlTcCbKm^KHn(z8HCSDVZD+m1S7IcuV4%-(h!S!v-!@jKYAN)~_<3O&V4q`+3^T#}A z>VwIx+{vDs7r@*$?B~DoY-t@zj{G9R{IJ`J^g8RXNbperwgn=C9u! zz1^px!z_xO+ag=(rYeB{UUHNjYdt2(wzV9c&&7svA5Y7czD0C@qF~~-vZF~DH5hPN z>F5oPwoei3@tT8{SQY`VS{KSv3&<^XVhNu#Kb3eq@a_4jVKuHWglERH(^wteb z%8zm?o+3v%Y>JHr8zhPrgaliz7A3(Q0Z<(3?G)T4^xehg*4Dj=^eS`!Y?PpIkK<=t zsv|VF z2lYpVUY$cJKC_Bc8&o1NYd*@|9I zdSf2b{KrOpl&%+V)uC=LLCZqtc5tR6BI81jT=BNJ&jINid9b_3ZyOCx@uPa;!8>5L z-U2RaM9)S6h{^M})03w0BT4wU{`0PnmYY@~E92lDLh#*fI#wFLvsB*%(-ToJD!K4s zc?p65e!p~uW|Ik{r+Zb#M#UK`u|&+l`dRTx>Duy1Pf#f@7cEltv77pzDa+LvTRbTj zkm`Hl>{x0m;#U*wm3#KGciNy1<+CcmyQ$mE*%F8H#4{Y46?^p4-rlP0CfwYQk#B|Z zH*=D3B1>m|%HoaL`p?n>L7>A^hXxcA9=DRIG>2Bx4>vRtU)rbv@ih^C8Hb0y;eH(n z1vO~)MDi~kax&tUp>%xr!q_nSo*sia93q@rw^MqWIT0ycB?4QP^jEtyGPfx3K z5QMP=Si>b4mu@+Jh#29W5p$q7xGj*64RaQ$$4m9@PL&vBGwHRTCtt^5n#8k@bK?{V z|1pPwP#(Fq<;4WvHIc-%uhV~rdEqw7kJ`C2Md!1uE5#U*$K#+;Zkq68m#}&$tS-xCidDwi}zVLmcLcu!;CIE{PoypQ3 z93C+OpG)Z_ITCEnCHl0;J)qNylEr}kesLaV^370(+Q(eScG#+WX6$BM%mrs5(DG)p zjneSiHb~UyUoSx62uZwig~=4ikI!sqtHRZH#{2N@NTo@rsLX37kk3rg{>t@7zDqqM zDmT}-e)zy;t&M5TPPmw4bc$eQJaFS^vg}dfQHx=9E_%622wnOCPB=gGe=$Q}bdO&- zbF`Rc2^g|@wID7_Mdi!S8F zn_)x*&HBnS>GEVtEHoawXu4QBKJ=`VGBU(`ok6<_8%0Bg0E`qJ6Z@GGVLT4XYZ0=Nyl;^E8enK3MZz1^iE!r_ZA&z+5 z%o@X#v~p-GIk0?6oQ1Z7oOq^VK$WTer}bxX(3&hgGag>MUV6Rx9Vfy+1e4;*veFJx zUKhptA{jDvD88^onBQ%Papm-unrI}Y^y4UbK;khzOFA_sNfaee2rShZeBnJ5{s9Q> zKohfz*Ig^w(bH(gI2foDQJK|H>_%G?8^@X)zG9f^Df%NmPWXl4iV(37^dG6M9k%1I zJqf0*99SLZ*(nFMpZ3w*|ir-j~o7d6)CzIe?o00i13; z@%@kmHqNbY#w;$fTvoVL7CH!vlW@%C*N(o3u=?W}1}JCa9#yeo8(PtFMhkj>HH2d2 zyC#4q;3jm<_G#>=wtsFYIUI|P#BlgJe!*B?B zSGK1I(s@V^@K|W?egSGQk!3oBu5@&(a5*tS@c!hns;jp#!3}_E_9#K%s($N6t`wrbk_xee51NdyLTw~ zg5lboFQZ80u8ZrimcsqYS>>EtRmbxXSD6cW(t@4r|k+KEmty zq9z$pgj435cL}CRY+sP#Bm^C7*uCtD51N$jVgn#=NJIm*)uuSO0cpRNA0-tDg_LsN z#4DLmTlZHH9&@#DN^-Akazq4j=WfusJ_foCM%(}$y-Q+Mo++Z~?*-SM87-g`e5{UV zQC0(YsW%JOk8b2DE!X$g<-HbGKd}99pgS4Za9~<*D0F%Ar{S#4knyhP&lZo2Rx`2C zeSSZt&nG=Hwc(Cu=p?n*m!6{SyK^-f5$vNSJ;7V`%K%@J5MSn**XG|XQ?7Y3-8>zs z9PO$$KR?fEzYk|MU&jL}!0I83;rh|L1|cxi)K4?aO1@a_Iw3HS9EoQ9ShuG#ql8!% zMCA?^)!fR&q-AVZ`!=Xz;C^JCsORfEb8k1L&avQuNNm$eWzi_5!Q)V86><`xP`UP% zyA$#%mV+l&9Uo^%rJ~ zRcGjBYBy-A{D=v3pBmckEL`d%iw{1x-;z)jKV)%(A-`3KTn>WxrJr$|v}9-|IS*eVQ{n!MjT`+C#y zr(nr8^*s}4c}z{PJ2J5T+j6?C3T78bd4W}i?PD%=%ivqr*_31`r(Tke)<&2jgLHdO zMFI&NiY)f*nHyN_MX)U>m#kp;j8|a%hfRJkVpgyZ*ZE z+GBaENAu?dnaiwusiwgFsU2`kfaXTpgwxjF<5F(hkG!P(&A1Usv;PlQUjdY5yRH2a z(%oIsjdX`}mw?hpcXxNUbeA9?-QC^Y4bt89KYn|kea`+JM}5a}27K1D*0rvk$}cVKz=B6qW~l>f zJv^CRaq^oh$um4-9|X#IgrWMjPxQgM1YR53R6J<7LlEBTv&Xc3#vZ3_b`9t>TR^tj@)g6EF3L=)bfxwr3 zv|5Z}^9Eg?s|hbMEnsW*XV-^42k3V;R&Y0CoP)Mh)z5iarQ>u8E#>@uQ@xNYy#>o2 z>czGzqtr*>?tCqzp)1D2PUOSYC8CRT8@JSui&-L8=6>}c*88vy`9$3WbR(nPQ@JF= z2(&k3(9q8P>KWHn{R7L+W@3#8h0c3E^iOMr1_EG5J%jlR`C+g1|2XjgQs)w55I}F} z28xiT$Whild;a?~BskdOmF0irO^m6frLgU8GB%E;8g1!*wsl8%k%XTJBa0I_`#TD* z2nfNtn{d|%N5|Z3&3o@h_!?|%_NJD*lZ%6S?ZN?yuC^snjvSCBj{mS2{pTFU&%Vwml)3QNqt{ALQOp%7p>`}*Zh@K!}FXsv_whuCCnJ-m)KB9 zwu~a6g!ts>NWVm!iIE4xMtu{hqVY$o@l}?CEK~!dXhKcIA){tMQ8Yl$nTg8keF6yW zs3?0L+wUJEn%$A2tT{Nwa+@fwd)*CeA3OyjOK<`R*&!4_z=@LtjzUz%V+eXrwJ31# zkfsjgYz@`LB~zO#=S~kB62`R+Bi$~)Y8T)nxbmImX3d!$#P8XmgX6?zqS9;4lKBB- z5?L;-qd+~X*X6X=Lxu!VB6bJ|9RqM@H179uY<=gwTOm(&54ndkvri)NzT%uAY2Oe5 z9c7k_`=yc3sro9->095E@hPvZn?`w(UJVWU4>|&o@b#Y0a^+AnKR+Zab68IsO!uPT zKymH$a%9*W;Ac4D{avipWTW3M^w5UZx-kX>s^ewKzUxTUHn8nL#nN> z&ueT<0XRsqh++!%H??aJ(j{SD3bt~Pt5^_#z5+P_Xd$?Dt%&sSmp=>1C0eM!S9_si`>k1XZXa3cTbm?fXr`>BlFw8A^UkOaHSs^k z3CRFrjfcp8gBNgMvk_Y{GeKB+&}1gc-jpN=ih<@&n)n%96D=bNmoyW=KSs|-gynRL zCmJ$H@lnck!9e|oH)}5cbP`)zvVw?2!H1nTr9`g1i146nFT@|ko(OK+L?ixU)Obhc zWh=U89r>yu>>OV`H3iKCL7hxdrBG`0!iJ$=>AI~k6-^^^I#K-A@Py+y$f#g7T@#lf zizS9;j(Ye4D3PH7bV9MrSeoz0+2vVZz%26enxMa^zsZkB$r%C{G_L4B?7rcupiKmOnk3kStYyQ%Yn7 zFlM=aTwQFueGLU@b-m@;GiMK6WRI^$qWfGx_Vo92_~o4kgvTdv7F#@gd={hOi`7*r z6j65^=Ee~>s_09i{1hr?@ZY!&3`zJ&Cb`vX5d;H!rej{{?&uIZt=P{e9$ULwK)YKs z$qqH~n0C}c`3q;oZ*MT9nY16wL|W)O`d7BKyjT4ee@ZW~zjxCyf`j;M7ha`a!^7ik z)S8#>f?m$G8yxHSpLVSkS+Zez;8*_) zN=vjHeTe~+a_Uc}SL6gXs|0xXbJ{Ziq88Zb{2*bld+FXrJ<9aQ<;qs7%9o1R$>61N zlw2W`F}$?mM(_PA*s84sO`ej_kIh)#6EB%mJLjTUJ37L{!eB7EYU8XWe6J|pC~iD!?9(dY}V51np`j9MCf&w-c`*2 z$wnI&3c=cCJ$UAuyvis#E-L4jH(1^D_Hm$55@+P%1*Ktk+7ZyItp+(v@Nh~YwOxcq zRBpyUrZi2+g1kq$a5SpyKVS*Ga`~!Om(#xwAJ(q*7V0&utg(ByD(HSXQh|>iEM|yX zhuqBST}YSmff6#KhE$7>e>&f}-nvM_dMW$`r(n70JF{lZB|^%ltp=r2*d141p0Y3r z0yVk~Ag!u@3F=T+GjR6cCEBP2ix?icw3mX-(rv*4%2Y;LX6yS`Sp>*R*EJqy5Pcj> z*4GB47;XaBmSUJ42(Z>hX9jwIU##fQW?Tqgx(U_Al|;dqvhndmQG;GO$I)R86t<6S zpzdbT{YjvphI;(nS7=A*xu-VQdR%D3LbbnUh`InO=IpJ?NN6X6cBS%15v+G6!RXwv$!06Ha z4lrE8SL)#c38^OQ4MLdedq))R8$tX^AldF!31~?O5L+zgJ5d7@>xa2QjPrYYLgfBG zb_j0v#l3CCjX_}y37I<4dfP>}*2+expbv36&%l`Tqp!FWLTakTU))u66lJ(P z-|g1!y)Lg*>9$-QVt_6Vh`g8_nru^Lywj#gb(oMY-BlRX36KEBOB3UiL%8#}RGq3W zbKiNVHYLT&UIks=+FY8OQusukd_84Sm$7x548Wz_y_l$wQ`qFl=n#|ya39svBgTc8 zSQvqV$WIhv2DRzLIA=2f+atggM~sil|HY8C^#$jEy@nJzX z%wG1`2o@sI+a)oVKfk9dr|;rv)sbjo3S?r+M{0I>Y8Ej?gQOXMnK5v(v3*T#G%tdX2OK%4~dK0r{eA?@l;I_t^xU{R|_gMmHaX3wlWWwsjZx7lu?| zOVJ+~Cx|RR!m^m7%_#}%+b`!1_{|QeAPbS#<7QIvRrkM3AcHJUZ3fd&170(Pax0+o`VPdic4<3{n^Y z?Z3rs9H^xGbw7Z(B27#bp{Dtu`wc3$7DL30hJ0)i9^Z;8GyH`LO9T@R(L94+357`M z&;_I51$=1QraoxH4@Ci8z%HuQ%Sf=_dOxy5!On&H&G7PpaW#Ux^&b?4s8fIAE&K)L zF>%9NIzG^*@O+Z=VP;C@ z0fl^}oF=g(UwnLSwnlC?wrZBIDPjTXpJm{^);e0^)A9RgsA{)HXI7ZKExDx1PNkTO zyQ>wVT(=KBXNx4Y>#~A!0+4WYCH1=Gr|%dN4bWR85O2k<0tXc`K2B$TQh zP!9EgF46;dE=MYwg%?t3fDLwYtf8FiIC8hPP1D-;J5Z^DFNp$v55BKFc4Pi$wY|U+ zv7NUIc?c(gQ@*~n@q0Z!L}lx`B;@vxxOWo}tiSb*luA~JfN5m1W%TblbkyAXNj z_GLk$F^?ZwD!%iYPnHth6C+R*g+_{Mw%=&B5n~14j+Dc$tk(z|m|j>~pNK)tI!vBV zmj#c$pKx1Eyu$1)GkW)+KhuKU`?Z{%FSlnE{G!k%ytH#i4^W9(THt!sjt2ac0qt_+ ze>oBV(71HomoT<}Mo6SGIc!tMZxKK%QXY?9y!uXN_f?jW(NFOkR8=d2tPw2upNR2&Ea!NX03Q;UjeZ#RZosv2R*_~T04D*tQW~CU`o8= zL4aPs1PR1>&0oj8nPd#HYt#bQXmciUg#AdtTiC%{en==;Hjk1Cv4<-Mr1KGIF(PFd zbKIo`)yP8tHtS~hXf)<~A%K#@&fM^i7`F*pDogyX5(iX-REO07fP^nEy1`p-Xqhec z+i@8z*uuH)%hbf4Uy(7l3e~Tt8Q)JLI2;{++1^_X?+}tuT@@vSfaUy)UAIF0<2Y3y zx|fBqm?$-L`jOmke%9Q!(>qhj3e(wJ=;|V7#EI*4ch@0&M!~EnukR7&`s2Od?IQXI zF6ZA&W*s|RunG*0+qn{Om&5pKqGZGFYxCXN>y2ZzCMBF$g+`wm9lnjf~IQ5oJK2KyafCOj$9 zR?LG)ARGDd@eyeBaDQ8WQ1SB03nra9`A`Kv#d0skvg;?S?N%=Q}Y2 z!jdE@*}^E9j@0Ni{M5mww(^hdmfJXOZD(@+a-P{x%9@k~-|qD`H~|fuK$3_ON|qTT zua8GfWH^#KNTRBmXZEPrUK5zy>{QS<*L^1&(YIN z>jKWwav3x4YbEYjj*MkNW-soPSIvXMd^qr!yZCyl-EF6u&67LkG0!b^bzzDbDD|}V zTDb8RuZ$-Dg4^rGfMxID$(aNaWhscawV`Kc>X}}8O%4jvhG3w}?W7**3<`#Ui(=tk zBpc~A!UAj3VtW<(C`8`fxl$ya5E3*}2)L!zW~%9Bb?4517pry(ctG3!vEgC%`i24+ zCvk3+Jg?h`)O9yJz>~(Xy7H0d^!s)Ez{=H2qqdXqS8+7^zP~<=j#GHMq+z>zU7e4` z2p(TvSseClaoMzg?^~ZE&9KkAdRW$6wom}XLBLjjc500C^=`FMYUTKoCtMW=V+9gt zoxD-ET~NTl@E73VhLZ#ZIn$OYL>d1-X*Lm?vk5B~NBHx?bE%;^*kUHcpXwXrqAYA^ zduC#IyC}&kYsv!CZESa5+{zzpQ(=$iEl_`ew5>5b&M~_)0$!gto$cj~5 zS5wcBKMO~x1eiOx$x<6taj6K9 z0uJ1EcXvq$knXEz|B!2wS+*kk*1n=W4;T%K`mz6bIQr$Fzc0YbikHu+TsYsKEGO%D zO2=Jqa%IuneyD7&GM9Y#(oQ}n8?U=FLUl(NnvrJKY(?qif+@L80b@}6c|#H?n*T@+ z2>wsvNa#^S7@YxLRRo}mYu+CkZAH)hzC`d)gKVS=uXJKYlEcD@Pj#@hl$ zD9I%65ZMR73bQ76sDh@J`|LD9zST%h;K82}&s_D~^^1J>Pz(c)tWxvCR}_x$D&RsU z=TcA&M-9e&T<3v`3v4Igz13p;KXD8KLLyd{ZUUEDWObeS$Y0Wh7fMSZT&ckG=mU;N z*prq5=dhXEUYKjLZRUD-rNzJuE6&2|1$%Z8TI;#y21K=X#wUsI-80bO3lR>!O6)rrn3P|+s_9QyYI>l- zvAQ1c!!tg4U2%^&sk3jTpWoOvL%E!=;pH{HEmIcbz`Cr?+>Z?jzLgF91*hx0_?&5nY0 z5rC;H;QQU4eou79h&|M&~62vGWfPMAo$($;C;mRj9ZJcM?Y_Jzj z-o$Q~wQ_p)r9iI0B;G2|Fdde^Z(%)2F3}tPQ0AB1*Yg*d$=Xf4&7))6m*6@ONIcTl zp-Jz_5LY#mP}_^x>&VSBH92G~mqg&%iGpn)6SRY!O*u!BCVN5bOddG>Nhm(2q})&G zX8eeMzM7s}<*Ce)*aS751n?q1M}(Wh%El7ikRdr*l4 zQGsxQEU^z{o%$nr;zi@7so)vpuHZGBD&de%O{g*axA6{?B;@q~W0MV^^S`w#4RpDG zhT=a0f2s2- zG`Z>XKLxt+ws|D4ayoBIwmBDN(#w%YIm!$MtsJ^ovO+sPZ@0HC)5_;`L~4uRwmc9uY3=- zq#&W65!-JaY@5YB9zLVBJ>#Ft{YB^xxM1OlooRZ9O)*@Lwdr(Rm%>kZ9h9TLs?lza zYvS8ooJ1GgZ4lJLWqWlQNXVV97_x=q2r?$l?*H1kn7Nu&Q1}x8@Ub>+7F})!wMnXHq;aTJxg z2c)=e3pljwq*&qL$u!zO)u`^eY&7J|jcogM%=TDbht-Jxj~8HEs~<}Y>fN1>I3jxl z8Zw!1IXZ@|aph?N$i36jg7`u=i zB+0?Igg9ptq7pL+?M5V_20f4QRFm(wN4r1u`Y7~;XbSEmp5!osS*5a1qhuGBR(PJ$ zndwTt0LS!*RlXc#GNOKA`!;1aNov~eDez1Fl|i+O#SMipTSW$cofYvh%v+DZt`ym6bh z&y`A;@_q?Rv0b!$l$QdH`@G_hVe1BW4-lQXGo`)T;@${)LcecG(9W;9ZCVCW$@)9b z1e30K`!A{tE)|2_jW}cWn*N7l1rZVwQZvwuIph8VG7w0+S=K~^T+w1;wXy6*iPO6n zPO)J6W72ap>KnNp&E<4-vhre<$YeSSizdM6<ixfWCyX2lYaM-!-& z9WYTQC&4s6+z$;L>L~_ARM_hE^pBz`1Gw(oM$9(xS_-zezE%FOa-`!e=Ozz9B1Ion zV|3gpc)sv^L@YmD25-RtOaD{Y#bY8(SJ-T`p;@-n!>ue;%Ws|ZQqyz}c9`I<$_-HG zHA4OQq~1$o;A?J%L_353ev+Sdu*cyX-(PyA${}H<6fm&zT^lmAzbnPW2ykowv|G_(GY;H{@IaqjIOePF5P%IQTVX1^MUJ$nz%?F z$%#S=I)E0?6E)hzBbeGb@_y^k*qfxMVbBajvx)Gq@O>75TgA2FfDHcjj3s zh!B5SPq_-Xgw|4b<0l&(EO<@CXfEP{o+z~*>Bu$eI z7ub>KK??0}e?buo#gYjZ7;uIy{~UBa*ksyzYW>IiE7+7CXhCsj$T}TU_w8gyCp$;Z&0W{Xu3g}? zGV_+L@^Izjt4r0+9_Ow^<&CRu_m}TVFP&}LGet21qCJE@!m2jDziJ@9kMpw{`8()k zd*v=wF_`ha-f!f+_Nw@%@SO;rz(5+02EHDR{J3K7$$9(ztk>}b$M*I(p1bJyH*)~c zGGSmdxG*`zmDKG$liz1Sph(qIGH13WvCv{LrpPX6vqFC%J}8@aMe zG7@rD)qFsn1u1i9UW z5WP(s5>RcGw*fJ+E#8EVBR>8>)9!3)=}@R?zog~yW~G`pVQ>_DhwNFblDZ?{k$mBL4J8{`-q zXQUdEIbcTRQFZej{j9wL@-2FFCe%WOJayeZpoMPFX@`>GcWXUC)Y+(tMhqX{S2U~J zUzbQa6ByGEz*&@^zWX1saGAFE7tkru6-; zcl_H?mujt8jVH1)0YkV!Lrw})e|&jF9Mdk{zSZzr;7Gqtv@dO}fs_F`N;Kd#C(pJ~ zezG+;PikHKK|=rSI=03MUi$ojwbA|2RY8(ltsw*IWz_|#^*!lnIgfeo(c5IQ_<@ZSoN&q9tV5t-U}UuL&@ z*k*;iTbGzp0J<&Tb%pq>slW5CHYBqfb^pIpKP?|G#2S-JqSC-)-!)iYt2SJfj>sP0oNQ5 zN;VxHUK+VH7i_3@Gm*%27@;s%NO=6tg|%^MWnH8V<41`Pl%RU^B}U38tn)UhmpR1z zhpYVgVFXBMl4xP1GuFT;B9224d;%QA|5yM5ex^pX8UIge-yIbaHV;rYVF&5}7i~^8 z83Is)G8Ow0Ieq0~epZ77j(

B{XBkRXczK)ArBLZ?j=0*cf|ktO~32ioKhuQr5&M|sJd z-u$Sc{?OLuv#h@Nv389Jk-%GuGyOLM85$2{ifkW!QR-2l^qIDeu?*DC9c13iGiYNr z&YHoYI7JNSef!J zi!_z&&okG&lDq(SF7lp0A4Rd-zF4D8D{kNY8o%MKbQ4c8Z%a186sr@b{H2#m{%I}i z6cDfw4G-^PpUr=Xf$yxZFE|mL1Mr_s|h8`itsv>lwQwsN8n>HTnB`SV*g7{`ayDET{2U(0>FQ~vIG9nFwDDpt+tP3~| zgyNawaJkC@Me^w(u<^*M7El)%fMYF;QDaA>7~>=JpXY~?pmE!K^M+5O6qf#>hhS6gQ*c*;Tcg?;)5mnSOhT+jDEaKnncZrwbU zggX+nO-@%zOf_rjU6eS`o#&}7%CeGpqMGJPTeS>F&{b|mGt?@SRioa^rj=CEMfmFP z8IXN$qfn!)k^02ej)5(3^^S^@v1M4Gcp{UpG{xRy+Yw6D^|hSu#ariU z@Y$mXjyJ}pXFJR)dYr`nZ`#ozLq`QNZ1&qQHx2o&22j$ zA$XY${umBwuST12;#Oi!fhU5ukJ0|X!UG0s{~jYTo-{VN1jum22iAeNO3f`v_)L*1j>8(YfSaFyx{1zW^!v=xKqakML|AOG(Lx^h%f`5<7 zXikd2!02|_)w0d>#(BR!)8oj-`4C$E`(MZCP$LVztV&T0Rkz;DTbd|{L+JxN5h1PRKCS|}D!=OidFkl_FP)=%2U`dU#;WiWVsIgHTg_fKjQ85ct$QOR6_gU~HmjC{WP<4x&XClR z02J(?98z_;m}Eu^Yi9gK***x}qQ^WuHt<8$A6djRc_cL&X?Vp%tP^P@BD&fq1h#rS zGh5t}_1}{k76rL|lDEi|ze+L9k1yqe#czX_zLHwE3n&w;S59?DF#W7H zFd}2GgUgK-m9q2o+V|i(Kf!{#`Y1MEtNKHNxYl903EkA{lsA_>X%$Z2&0*;{pdx0^ zP$HrkA}&QmMO8W+g7CdNte&C|EIb07d?}9?b2M!$stVJVD?g@zRm!cnwmGkX8wh96 zdN}fzH)cD1K_v3x3rK%MN#&^DAVcnGY0g?XAIF_+_lQqL-3~rJT5Q)obb0OI%j(jH zZh`Vz508Luf0?&3Ci13_2qA{=;KXzK#46(I^@%ZA*m3kvzB&JJZa<4+}y~kpQ%44JZ)%6bUAf^b$VUoHX`w7_#giU z>%4oUV$1dr2m?s5f?u=R9{e;m9l}1CGX)BQxm&+BChd=K3*L7=yc8M%Ur5+?#CT7& z9YoN^??2zvR#=(hA7^!|yzZn{#{+<}Jz<1#)A--& zh4kl|&c4Ct+``_beMJgXGtoepr*z_c<0#}*PRGOw>=@FRqIkXQCBFG?Rfh%x2~)xX z*+}GXn@n$MtWk~?Hnx?U&47p{%f7WW@B=PrA3fc4B=nscqOM#zkPjg?9S!a3!rDJJ z(8cT9isq2yXwI+|@l7)g7CSv8RZxO|#B}#i*HXQ0ysfu1OaLE;WrZ)T()p+9KP<}U z90o2az^ml^F=_>awjteAlPTB*JCe~lMph;w?&jv~*;=Y9JA%pdDBkD`;#nhI2)3@& zhMl1{ZGCF-V$yi&yYx=~@e$XShDq-WECtx_rfNUIRRUhvvV>-yAR(b{!|<0k?*>}1 zY@drC<)e`}A88$BrKOc=Xy6>By3xY}FtDMiY2aexKQ%f6DQ1%JJah!{q$&f=n>OR8 z*+rT@2%`Z9h^@pmKgF*`(N)&(@uzen(_BX|oYyXr_5#N@Se6`7yl3NGr-$!6Nr?sa zW@?UDQ|4+Ib;i z`jPSLEe)sg#PYQf{Pb4!r|9{rZ}pAqCqmN}3@o<}_OSIhBWee#M$>LBzP7qnNfMt0 zB{pp2?A_E9Kfgxpu6gn|xx5gM9c0D4<_=7b8c#Y!GB6klJaU!T1kRW_*t7)gUwad^ zjiSfIUF{#+G3eew+*iNeb5`$V+vwZ!NIgzyvb~@94+e>lejs`9jgu zum;{Ne}q3``t%s&YBH9$xomL(I8{rJJF<9C0Li~ktS?cXp5i$C20T^FvX2r`B z8Ob#9@yv#}m$w!S9Vc$51s#Qv)B}$VpN7+xC2aJ24KkWB_ z2pk@Hl29sM_C0KIxu;Vp83&o(=jP_YKn^RLAGZvG;G5Zao$46!B@PEoA*xWNW6~sx zq{#Rm(St&yZTxL@9fy0|h%tH@+;BGE66zghBL|!J&UGgCvP+e>>yf+uumT4z{YyL;;ADtyMP^>R-%vOIZ&g69#U4(r7g}2uY2kCXOs`BH6o3mQ3`RCws%kj0_&Z*y8 zfKBV~Xcc*9QP~+buD!Cbve&8UgJzqy`XAF_aq)k?D;QsO_I!m{c2OW|uSg5Pl9;dI zu;NIFLnY(4vIV}K+PWbEA88u)y0}}Cufa@$>%I(C&uN9`m7BgawGGJSGo9U!R(!Xn zH+_cL0hIUYCze&Fp3jfLq2z}@HZ-}fO(xaHtB=*PG}ajmR#G++#$+_S|z zy=tK6ktt&IqvTk(Y}Uk2Xp)oaW!H7ST$5@#ruyMUk%G!Q@hs@qz4J((dj& z@cUyXTQ5N;4HMqvl$6u+^ZlP=_(!2f1anH7XpBt*g-~qb$6Y_%UkehR8k}4~A|oq$ zIUD}WT|eXZf5;u3QR2U zE-r(g(j9GKEw8X`Jvf*Rf`={=TiALtMSg;Oh(zm|FZ+V#5B|2IbUo4jmEg^=H^MxQ zpHTy$MRGcc)!iEF*_*>C1jX2j&n=@(wZS`iY0eQXc-y4A`8y^uvlI>nBqh6B$Z4>C z;AU z!eMKy6EMKW#C=AM{B#IpLdWl_7qplXhF{4k%@@(Wh>(WSdT2Pm*a!W<+#t`3j>p$E z;uIU|$=tqZIj2I_AbXxMi^@YOqM7@4-ywu-`Hg^ZKp%)hIkZMEiGcSbf#B zE!7WXzP5U*)6-91oY8@wE5Bq_moUNo(9q~>T#c4YSQe((G+G$_K3q4Wdmw(IU!Uml zS(hPF<{p;*p4?GD-FY-0D6nw*Xn2H=Veim?!#Ik)`g^@lo;&1`zaW_c{!vGe$Rk!gti)g;nP6LsU+jWk#fx$B z*9Y-AgrrQ*g}U~MEP?L3RCgYW#w51KsM*144FT{9!#82SJ1wgcgRrxZ=h)!@7=mT< z=5g@zL|yGxN5S=>A~j%HjhWhRfPaba-EsHcGdqaLzWVbl=gr$#Nv(wL!RuS@7qZM( z^2@W(1v;0Z)gO12B&(^0D~lM~`(YG^vZ;xS2OJ#_!+4~~5Cm1d{Dy9>ncR!gE0Csvlq3uOr{kt>%&Xfi5Ht|a~Qh=XOl)8hZtBl8%w3_U4w1N z#`$I@E zEP=-u97#WtB1>6aQ=O{#$uH;{yLup_i8@?_8Ao)64FQUUCm0w;?~zG2_)G>rtRyJq z@H(&OBiFMV!tV_J&*Ff9L;8Bgcj&?#i3!-si)!TyX;sAxtfoWZyS?;(vGmkF*l-r{ zWzffmNchifcw=*SA>44yQL5AqvYSdZnuJ%z1`be&f2HDAqFBMoqh^p)`sRB={-f;o zy|6O##0wxExYfo5UqFs(`mb(te<4`S4%PwVx5hswhqMHK4Q zLs!I_Yz9h>!OG^DQ5E zafMVo%y=G6v3K3|(&!WIDdQdMvR%i7-|}jK|7cte%ca3Qu?X=N9Pq9baglAP=i7`$ zPlMUkSd8uAF!igi_9v*Ykl)kUj~A+4FAd@Z=y5(l1^CS-s_u_xjo1wk$k-{dVATXo zv_Bw7#V`77yaMlGzA212vQa-SzD zbST#Ucmc+Y0yFf$4hw{Zg)>|UuQ z`_sIBJQ-%+Lg?#JU#p~npA;2H-f9tVpfn^87nBg75`a+{1c2&)Fts^K4-RZ7LNVGc z~Es?iqO#wRfcD`TGrJRB_#qa2BFN zWO#WG$)ktTl^W>AsC%0bUU6(ZDcA$B-geSJA^XafK8*Y0=ZGr9cgt{6{)z|6ICv&H zyy-jVg1l;fH;>b`gHJ2R7;2vBIB^1&%zw1(%s#5?s4y45GVl-i&EY+3C1N0!MXQ>{ z{MP+}fviOYW$R%GqXn92y~1u2$zHS=y9-gvXf_X;XVMff;k-E3*&yIvM=}j?fk+s zNA_{q$(+Ea6LM$sVJ4VE7X)Sle_I9a#)BKu$z+mM>}Y4`KHR>~8+I9gzRqv<>a9-4 zSbQJsd8Em0wA4fyQlD0*H%Eq-tu|qezka?rw(>dqW~`f^5Iapu2`lBgs{iTFE_n#W zrlqC^9Do@ky1q)0QW`@_vLVWiBgUGWdiXk!FSsRWt6?K*NH{+)+5YLt_!mZCE` zmU-E)_f|W;uY4zqA^DE}*&PB}eNEVjn`Zcrf%AYZn9~x^^T?Kp*fXV|5NA@aRxBqQ>htp)tkTTgdJSQX)Btg)f(=aaNMCP!n5wGUP4g&#NJR&G zKr%>nc1H^3tvAxkzIUv4BEBO`)<;g>QkR|MN?#(cHTgPcw+Ty1)m{Hg$r8DM&pHxjYKB{Ho!0uq zh?GFSqB_1YZyGI>>5c$F39+Y2JxPsGtl^Pi8d_RP6oks7kT0GWThOXYr764~jDE2& zq9`!Vbh29}0_Jy0IL1LM#Lf+gx;X7OD<;D>*&_%}kfndFI5;JefTYB!(un6}A2#Ya zP%Hl-iy-Zc0mS$Dheya3@eS4MnRWNMURWs!ANXMxv!k$UYwV(BK0^=sf)&p)qHDk> zSm_44_#D#$^5R-|mv!c|7CaNKo{i-1J}|m2aP9W`*V&Ed7a05nSTmdPU+dan zTU5Hvn3Yz{MdyOmzLCPhyBoynkDoa2pU#bEED2m)gOij00RpP3OLAoo9DXhv3Pn{k zo(T;aY`|JgYJiUpMQsQ^_-WNg-6@f)?D(R0>X?=MtC94xp zh*jsjPPcGxzJW`#Yhrpi1}D*MocJZbm8j|eyrpZ<<3%9bUav#*+6-KU%xEbA_y!%4L^mz{6W1Hkp=HkXz@$u`sUHVtxmMg(<$ebPY{_cIz34N?0b3Y^rU zh3uk*s5VeH6J?qW(T6iXW1Lwa{aFTZqfBfM?_|D@x3p{$>5O|CQ6)<!nHdQec-i6F5H@ zw8s8s4;S7R-hE6g8lTX4-aA=~HwzksYv&$Nd47hUM3a*gCbswB4N}*NRMw5L{-okH z0r5~I+qY?-OFfKt4*Kl73eZNuZA9W9fstX zL^6=NCMSCTAY2~9FjXUy7%Ee0&L$nP*?9`d6*Z5mBx+FR&v{Kf9lUg<_mF2@kJnET zMQ&koz%1V)b7ZhLQWBR^kb)WzW&dCVny^EsXsjRwQt0PAr%}1Ia)?O6JN<+n5K6b@ zZeKQkvw!3D1&AmPtbBPjWiIwcYIb^P6RHx7LMVV(jm<{uCW(nUcUAmh>y9|v5=A)F zMTy5BjPz9_x4JKIWrIQCERGl7_xz}xc-9*jnSbB|5F`kvhWoJDSaQkh6}gS#V|tLB zFOTW)To32ih+MfMo`SceN+lT0jL!L2J{BGFyln0BCACettT~^?U?pX-`%w{9u{tz! z8mucQI9@Ct)0BPXy|QBd;jEI#cXEwbaon{`j83+z?@N>5o*crC_^VVd@rQGTN-XgS zYk4Enx^C8}n~9jfCeL|UQYI}j1aL4alE>MUyt(u}qPmi!b(1&m^XW|gcLk%1ou@$u zWo3fR#DvU@`r5){hmvF4_s?H5eB@;U`7$!f;?wfBEl*pb4I9!Y*3BS=vqY2;10vyOjNL~)-_xcTfKp8RyN4}<(Tbe1KcuAr%@&Z;>bk}>rxQ^gH%%zk92gX9`aRBU z#L^{DL}N0ieBrMwo6E!%f#h=$=Jc6b@WD*`d_#$koG9 zhKztY!#?b*%k#STt>>dJjh>9ERtId&P;f7H{KNpOir~i88#ARlwHDtc-7V=D;_?ST z*`y+-=#0n;@|h9FbkIUISWc(M>C=0B+0C8>NJb4}EPr+>L%KyO8R%hvf;U_e0mcH2 z6mqN~5${f0!+#M>T*8fA-wObM*k6)^*!|tw+M1|ieK znd&$$&=w>HzufreitNN0ea~oZ+FV~B^c4xd+)F=pYa2eFxWDykqSm`_OJ0i+B3W0v zvvk5L0>#w`*V{|%r;z{{G`O2ty z9^Hgb<^s-JucqlrG91KN?PDenxNBMo>{23J)`{DNTJ>kdqu;~A)RR9v$*z_ER%(3t zC6e_bgGs5f8)QF}%a}xPl-H-PcZ~(FRw}M$9Gmg~_&VqBI{U8Mr;Tkiwi~0dZ8U7u zu(6HCw#~+Ej7B>~W81c!?3}Cj{k+e4&o5_;`~?~Nd#$!fVWBd8mvo)yttAe#ew*%}p4ZJ!yUrQof~bMZ3P%jgoBEDWjY>k) zufIWC!W?hp_ACo(WtbWd%c=GPCUXTs;td2cRQ0!#q#ZoNlzEHw| zAzSnK(`~5r){Ib2iE2AsinYG+z2WnYSiR6%Oh!tK$2B!VRSTimR*mvKRsSA!)a|VW ze2t%15H+EH?WO5X$YtwG}*X?~~NHgJdZ_p$B0%4JuX6A&|u z9S*&K#fWkPIwfOx5Q{HxY@Ccnbr7Gkz2t`P%On@{(azFc#sP(K(Am1*;a@NvJDkFzBer6Aq2xXP(A(o1~Xtly|cBg6@E;#~u*nfOrL zqYvCKWMvd&&AKp+d{MxmQtjrYvJK=vuXYx2a57qGsH&>!IUa3n^t-O4NvV$>Pc`%z z85HMyICYAOu5qU>KJ$=wYZcK`@bS+!cB#MjyDCMJ3p?~Tb71S5PxnsIr}s~1C4rWJ z{&|oZq}h+=!_F3>8EWw@T(Mh0;Z#@pSCm5*m4rXpP|uwuX0CS*0G>(BaoRok5LwMp zDeJM{@alVJ{F&9P+}eP&(yIHFrv#Yc%jcC}d~DwNJsE%0u)5)qR#Hm`x#?CNzuosx zg3re;>H^El?SH?%gKu3G2Ydi!3q$Ut5XnnCIa0J6ML9Xd=@KQ}t7^lh{k*xrX0PQ{ zyqklTk=iKJ6_tk)720G&^NDo9ww;Y0ce}^uLcOf)2(!9;YAM(1!~hYKD%|rGfl|?>{xQD#2SP}eupj##f8_o3#&VbEIZ~ezxs$AFQ z$wf?F(Ca(junaukLELJ-#VFe{nGTT5UIOIEiUT+1xE6k@&wF?Ck%BXzc=K&qB%L-q z4AZDxZdJ(h??OS$?3iSX^W?(s=Y-pGRNwyaD==`S;&EHUsUgbzh4~ZJwJ>w~g1H0s z<8LS##P1;NYnpj9`d9dnQ-g_)8%!h@1{NPDnwG8ryCF=ZEjuVF^&5 z=6loBHLSH#d|^jx@zLzim5YxVAEIuNH(wVK;2AxzWs>c4LGRBAgJ-aV-D3rD=nh2W zn7R(sFO||Iw+2WG6rQmCr+V^k5eZ>mQ2I8L20 z^o8E33w15x7W`0>aJ44iG#DUna(S7Xs!?qq3Vey0sa zF7iC`T2-=}vNPzmb5HMTniYo!p;5iYm~J*PBYm7457`YF>^Bvgja|K#R3?P^#|r<~ z7z+@oRa5g7kp=~zn=b@hporS@CkFC;Kn2o>!P=;yJmn15_(!Viv}B>gmn3ftdHBJp z!9kz@vCG`NtbpohI#1YQt4!C8mJ;NJ9z@ni`QmM9r#kJmB6E%^$W3KiFhwRmM#M_s zQk%#-6=0JeGfx(w+EZ&UVi^Zzdh!Ei8Aw}*DUfX;T|?o44mu%NDuak>6W?;dss9Vo z@IaWzM?6*}wxrbOG`?jyopRX(g&vcs8chcEB?a%+sfZGrgL`I~0A0HUVl_frORlRI zxy|}HE0ZQp9K7h7)v52+Ciu!gN5*v=deQZR0No96!0=vICZh zK4#twWZIQn)z#^eW5iLx$GiboUIf`beekGO|17aibLIG~2!9qkhqq74Q+Dpq= z($bPtoQx>`?FP7R7rs+?y1Z}J4c^OjDs~@tx5QAZvu0R2 zJnbrlmlI6Kv)0JDLf?SX>v3hv@^^#2J0f4Cf_|(TDxzfc$zOrip@b2F2j5=p7M}iq z2A@HhaqlNVbz36K0l_<~o@(>Yl>@{^JyLHJNjd&CruJpo?J9n^b~1jK+Q8F;NNchc zv9%ijI`tG6t2mDAf(j;B1qp=Gzj?WiqEI9uU2XPuZZz`F{@$c6ijyJOj_jcSX$fQE z^GhUH8W4FCs>3X{+95kjA&-R&5OMFBSX@iMA#7}mclWq(rn?C@kFj_wt2P(4B`^Z4 zsH@g6;lzH3$a*#8Wg>7K1q29jNWTv>AmOWWVr=Dw1@HYzJ=FYn(=^sX&EEnoc)WhW7LRNJAZR;_#oY`Bbq9=L_;|MhUk03jnZxsUA$NF9l&*N5CZ6aIf!Z&W5 zSbnzox%-iJ<)Ka4rELQDc#^Lw+)#$*SZ9^3_9TI&oBp9- ze69}$F`0b$j86gD#mH%EcdVH$nD#W|JZiCW%8oY;k;X)?@^Iz zUhp$OHB;Mh7|jyAc$%L>V5iCAjW0xT0~RTLluyTcCe)m#ZF?4B8wVvx>iL*t4=!4E zF7mqb=mAaelkxxVu<)Ih_AV~wLRqXP@9%c$hJXKhxVH$);oF9nsVRW{+T?QI4+Q>0 zBGV^#!!4YEIF$yUJ+*Zm zifcaE`OPVCd55lr2>s3qYEqOKT_g}YeX|gHgk(vJ%hV{`V}e@zj&)VIeDzIeS51Ch z5Kae;w}*lfQfFupi+?4`@_OPbF5}uN@GVL7BB2-5owbx70W)x%v9mz2wMv$Kc$1k)}+?_oYAvAm1CbljSv_I8Pt({ z;$FH` z_}?;h(|LYxT(<~}oxU!2(Az;q@ZEf50(hQa z>mSwYyoWQgTjG@^Ze&UJjB2 zgs6fG3|C2aO*G4COFHGQ=#6Gu#g5O=Rvn{Cg z%{l9D#D5>~Ro~N7{i>yBZay$Dz;qew5`39+iKKo!Gr4*SV z|F_UrD%A0`z37^q&KjM9@v`C7dsg*+TB%C)gRYAi_76ZZw9&gw?#Hanh!1-3z{Jg( zAK_;BS-EbJUo-T*SX4Gb(p4jDk-c3$YeVX+aA7F$WCaT__<$N^*On~`D9`#b{n|Rw zdM{IN!Sv|NkymQ{zcIV?|83%Q;|=e>M!2!X+IV19m_=vYOHAQ@5!jqBo%+RtpFo;% zp8^{HfveX&QpT=T=X+{_Yd#bI>g%j#BB00Z=KP{QYyYRXrWIVyfY3ro7A*N|yJ6=( zf603FnFDVE8`IJ21xhAx+CO7vl_``mU;8KC%CBEOcjDZ1&M3%VV0`sBE!miy}`DSfu?Npz;N97B+By`BpchM zb^9(uTZ}thWeyZ++VkEUx=#71*zoBpmiCyK;-)oO`j6=QKB|X%tpHUL@aj+ND(cG~ zzm04^jy2=d;F6yn2-9w;U%@9WgP5gHH81xGXZQV3ZBn49{4=?cw^mkSzXH~1=_h1% z;-d8&ajI7o$tTVZLe|sYL5Fc{T;Lqhr&SLCH)F8|7H5QOFxZ^7BkTNi{D5JMkDeA1 zx#Lo@j%+`fG^03y#NF`WCiP}{xjN!i2K0N8r@lq!^2u`$S@a3}gc?a3ZA}D*n2ra} zRS0-dfbs*Jl3`*ACmBU)GqE1Yx%r>wkHx5TvJ6|DL$EQf=-aY3l{=eBHHmk;rC3H` zAK|T5tG1KL+ggqP1}9Q~I)OJc|2H!!f~`&;P*hc~82`SSACwps9X3wgETX6%`34dtHCFGrgqY24s&EC7BI?XC`w<%&B^xrAa6JcAo}&^ssiMA~G|% zGJ&@0YyE$J*JPm}8orv5t~98vBF9YMc?%ATg#`E_H)67ZBIaFfTsR{HSr!}i`0o3w0*|({q8ou^$v^vyHm;eiUzurv z|2<#0%kdnm&yzFoL33rGexSMN-J_A#NG#m*$$bz=O$B3s2w%U*v-n;pA?LO6HFKpX zWOA|o6MaLbG+5bxri)~h zFf7ulz!PI8*A~x)Fvi>qgz$35Gewh!vS$(ceI(Sh?_7{^c5n-x%hil&)uiVRYf<|P zdAiz{BBF%O{wQ_T=_`v|U#1LB^!f1lgv(t6Isp^Rir5TE`q`azcQOSJG7M88^)m0Q zyLSosA);1nI=1ldw&@OPq2CfphUx?rGojec*Mx0Oz1tWx3as7Jl@FDwp#`b7AKqtV zH5BFi4k~VVlsxrY z$6E-jG<*6*s$y^brCKHP3%YwRkaN#?M36eEG7-wM*p`08K(9<6r!UX`0)Te(}9d%H*+uRE^Y|* z>z|-$l2DeTia4PDppRn{drPc!KyMPWRoh0f3dA`7=^};N1S^|R@W?D`Md8rvmTP@( z&#)}X=4`N1L82BtItXtFALUwN+v1xN)~g6m+%e_nqYD$6Q)wW(o5On_m=F{#Q0&61 zWVz!-29Fwx6)CHt!;(d4ji{1@^Iwa?ZEc`X>4hvjWDJmaqJhh3zUN58-Ls0&cJ|Jy zfnH*cGJKygY;A0)C7)?iw~9GL_H-U`YBbt%ZdxbH$V{fOEshIb zFSFp0BR{_4cr>4n;rn{HyenV2$9=jGD>!CXdiiK9yyc*@<{^|`H*R5cb}|^c{7SV( zO;sk4YXG@%i}L2x?wU;{N(_@GILlpd#Uh-%iuEr)!U^yrdp8F+ho377r(Zk^z8N-U z(lQ_8I3rvI;vsp0azi_mIUlA47As%Ix=DOBl{EGyjumv9(mghRsO$SNB%f3=7R%#z z$IATMxf%yJFo}Qr9~PiZm{`fyHy}z`a;EJT{`gU1v9ErZ{Km>{r+xR_>1k@(HS=ck zsP$Y5;f$pq1O;=9FY#voO>y|pT=g>6l+yc+=+tYxr`CfVqCW-4(e91nbF84umDd|k z0VJOFy;NMgSsgy+*0$pel$k60%)erNaYJ52U6b40_8Tw|{IIy)@3OGDv*zN}yuSfa zy$7T1?uA^I=xyySNC6-vmrXSGIqqzn!#Ol$uTC0+G>Nkv!HMH7aojnrkxN`cG1oC< zr@X;cI*1mstATPi+6#!j5f$Ctk4SNC2r@@4yj&u_z-ejdo<)XcRz`xn<$Ca0(%VMogoubEkE4wBA$PQm)9LrN|W z_=h9+`@xbyeiI^MF(&;Htn~|=1K!d7*M!DCcq}k0qo#SsPZhU*sHM9R@vGB7P_OW2 zE<^kaQ^MOT4zlK|{4FygE73J!$07Tmcl$dT1*+?G)8<&-#PUqkF7;E&G_Oz6X0l4W zFmy99J1YT2&?1M%H$;IS&L^4kt-X*P6Ds71-d_933 zf*8I%!$|s1(ZG#NvttM~-+@o6q~A}<15(b$TjPA)P=o%P>@HB@;R0YtYPg8fA$Ql; zu3bkJz15FDdolhoGxVS^nyU4YjNg6pJFDiOwBMt}bJ=YoyFr%)a;gU+BgeS_?d{{a@#+uZ}@|Y>yk(5Rv z-Ve7`_+KM>7(h)|z0-%@PaYVSQB`&tW?@#ovz@F`jgs<02N2xmxs%<~G<|i+V6~R(fkAwEO@VhCQ|9{wAPFGKI4PZB#%b5 z3>ESKmU@+y1+MyYWi%2=K0lOk1DPB5VP;xvo|MHhU8%x%_ejD z_o8n*D?WUmfeHUwp)aY5uk%(~AUzRU1_Bx6eD!5kE>xx;^+Ku!1|gNJEud)&(At76^zv5>sA<5FO?ydx_Wjn!CH11XF1(8&Z<6*;A%12@#| zOg7lj0z>^rTC6N3`}G01N1X|Up~2{N3U2TDV~?3i9*Z(lsFEyE`zaapYsSoTXubC` zqM07FdGLo#fnAh;t&C;sbQxL`(v8To6#@XIa3wly0u`-y1g#5ygZNn0`c6jskzt3X zU&B7g&_uh%xhyX9FK_dYh8$K*_LWk3IHe?}0|E49k?XT-hVIsK8Wma;j;BNHd^)dZ zY*kZEW#OL10R;8a6?^)xG}j0-S5(;!C~=Nqi@v{DVtrXrxfuI zKAo1j$#5Qcq|BxVR~OZ4LBW*#CRl-r8K3_*XV*X>@JZT1C(dN}z%PaG+h5j>pfw@j z^namt{X(=vdXMK=;u^IT%>)H#mk;|}W_AJ#(6OPsu#p+P&} z-0_SC9N+unr!bGyw}SBdw@i5#g%c}qFNRPVUHp7B3AYwZHt))i`CHxQ-5}*+3!*jG z;f@LHqCRdb62Q+2f`a;1d_<(BCxE|@WZ{(+jMq{!P8ajRp2>mqgaSt}&*;jV{ajw7 zOMe;44v}J4CS=Waybv z-=!`KJJpR8f5e#sTjV!1+@p{&rACHRVV0FvhRHqt74Y>AyxH<}nIj<|3ozRa=czs> z^O2mb<@p%426(fV%LKyTsNj84Xfs5yM!YQAp95qxgGd>t!%atyA zZTMcX$_v@_r+Ce5$it`=~6FLT{w2+y@?aEqEml1uaMg80^Zr>6N8 zFJmCqU@e0ENxUmzWmi0Fk!gXw5 zU>6;bUD1I8;>{1Iek7%)A_AS4_luwqdF=wIx(zD1nbT7+A_3fC$C zJC>%SC+$1}pwup=?Ak1>tSG2>v*c5qB+sO{z^41w4xxQi*T*_KwvbvnaE2@q1ZrCik{wg_BF&f~huOltM{QSf&;( zTmG_&hTcC!on^ZdFpB{22m#Sm0g3Ge%zZ1(=MA#^4RkFAas(HyIUZ!$0WYNH*=w(S zU0)|39z8}^oUNP-kcG|6Xf2mge!iA0-AR&?UiPInmO||&YzbFgv3#HYM#)X%=)QhZ ziI)6X45ZnM@!1XQhg85H{hgKTajUJ!s-J*^=pekDE-*c;T_OSAn|5*Ed-V6A2Dn#X z5>D`W{ksMU7WT5dx;5s#%U@MK)Z%iSCg{@we63m;Wh^oLR=UhxWr&2-^cKW0d6N)wk zPmnEsQGD{C`}uhNI4(q>oJdo*(FysmH7ld{Ji{4&=Sg8E#~`T|cZUycI;!^f7tXhX zzSKw(Sb6j2Ev)oMINOC#wYotLVh(}2P`fyfKn;$_flkMjtR?3=Qzm?t4e4z1I2ERD=Mv88)B=+XUsy=J{+%)g+Z7}0T7k9_map1D%n+-xX6ei|5(1lWS} zDeF^LDp}$jwnc76j|GdU4q50xign1sCN=_-=C?8YU(Lnet3Zdkq&YmR!xX3sta#+H zo73Yq)(a*dw0OQsk5EZ;;mO4y6QaN_rfdH*CIFzN4&No}E(Yg9(f zvMkkZX_MqxG!ErS^c^pZ+L~ToCz-}djknXa+jY5pL0q)KthvRD86ZrG$Ka%V|2^jN8ML*$eLuKnR#fj@ zJpP;bjR7^zWfnnwyu%Q=sw8<_${3nU(D-PD``fon(SwU0csn*h*3am)i@CKc=Gv>i zg#I4v?=uV~!}FQSEp>*?znfEnoU%(y!%wT{HRI@P`C#^G1-H-?!&kNX`MpW%@qW3$Q6*O1$a5u$XVgwCwy z!^U3;x$pvF45Na^*|75Hh)n8t++$eq{ za5pa@qB8ponQ3$4thyK^b`h>hur!hu!2+BAckj!-eG;e8T<#r6UwTk|cG`|d^ABw19yCmOXm;et+ zu!yq?^GeQSh`H8h4ViMr8wQ9`tpt*D#3OWdFKF(Q6sbleX~>MZ$ONF{;_lW7h72Oj znEEKI3Yt$81o?_m3@-$V48BO_IWSu!!V}tK$j%i8)&8XXVb{ZRPx_t^222g?jLgu!$_kSNF5FSSo?&g` zS~Q|C?z&Y{6s>1Raw&+Jc}LsQ;NkD??s~sm4nX`xMM$c~<&Kp5DF2a^{dlKqu5456 zTaE1wWUnaO+Ae-mRcOA@0W}JC;a%0&y&GK#FM1JZA<%`2l~6`-C2*NaGn+K=!^3^N zvqAQMx2kjtD) zp)y;SyCER*cJ}xG9hy0Zv8Y2i_WUWw+jaL-D@G`#u|-vw{IKYCvWWST(2eG&!h8bA z4SC&ew8v{#Ep3zu10#0pxn18FG#+ET8oVl5Nj)@J=DIYK4s}cEtXJTzL}SI}5f?C9 zWXgewM2(I_IklB0u7Ae;iQxXd^NuiAOG;2-L)=n}z~G=3CQfLw2Ia7;YC^?A?QZEi zl5NAH^{QEknPckOAG|1TzHArQpZZmOjpmd8_Wa2EZ6f4(Z?6mJ47tM9e09LLhRbek zWIxvrUTSdnSBH)+AUy-!TLRfleEkc3&YgtPGvv=`HSdYqf zvl$0FYh8v_tecJ>q|f5VIJ}Cv_iAfQmPT%rqo`m3#O8)8GV&=U6r^h!Eqk2JH9OD? z|Bk*9`80=vp`W!%SIC*piv{38(XXl(i=0MXpjX_?ktKpRos8o0+eVZ;(m~@kkKSza zFM_#mzG)n#Y!>+Z*P_k@U0Of>)2aVE7tvg6yUJUvl*^O==praKHaGRPE{y$zQV+q! zfj(2*x~WD-ELmzi8BxxP?UwexQOu#7lJVZmht?$FN(O{u&`V4$W=y~OXP#!4Q5?~- zGTPh8@y-yr)pPLoj0DlHhIu6S?3^jP`TBst{X`vCqh2q8Yi=mq6FIML364|E5N_t+ zSMF80lt-_%M!^7~VMz%m%;^~2E-8}Spvl>>4s&qytksy5!no0HY^wc)Kd3L`>j12L z<`WyS8#+S+^bQllR$*rLi_}{X)fEp%>09A%L(aR{s)6It&PBGstZviFRespIp8%AcFO(1|1C!RNz8#tvAE&*LwEgn;`9&7`8!?sNLxaqUAkZDsNzJ=!S+o z)XI2f(Whj}BWjb&t3?|7&f0O>B~{d*9|p75hT9#c9Ew9QpQZGck=Ez@dASHMCH_Z%BqAWqB7rsEg@rth2`gOu|nr7d~$aJaY0b;jS%5V zH{R2`RJ0ZV4YG!fji0Pd!{-W{pFible)d^@Ua6Qnwfb^A)#6_uVXC5`4M_%17Uz@g zbN2emx=5WEXOl2=<(t)Gw716RCg_$h;&^VQ&&@EcAlU+|fav{}EYKyPUZj{PaKTel zo|tzYq=@h3)w3$odfMz@D^Km0*TDV*cEoxCYe>cEz0&p5tDIHy{DVAn@Ntq;a^#udLZWQq;n{4br-YKCt9$lAN{f`6gPXU`0eej zN$hxWbt%h=7`iANnK&N;f?Lu{j+12o0Z)5Gs)51-wpGD=h>^+HPfKkc?1;Ebgesex zV2do!_oMT-xXbx3i&eMI_)iL%QRt>UUVGy&^L#KTM8|JoXW@Io zJ?JO77j*ky91&;*k1S~}E+atGSckh26@o@9Ic#T{eDTZaVcK;Ln|0=fuDlPFj)-2a z-nlcZ2AAy;k*vaT4&QP^?^Y)yy6WGvh_axxSC@%vAsi8ehTKni!E#uE%Ci;U& ze*pytn`!*kFVbz)U+|UKSwa*f8kX~CXed7~kJK!?lFu@Pw&e+ZC_aaulYOD2N1&`sbZ`Q`la-b`M|_<9f%<1nR#vaC z&7ovZq`)cc-T7(4j?Y+r&F4W=`Ylk?Ha*Ms1mPO|T)#s7dMHEI80H zSMR>?kPSCHXRrDF2;Gx3)X+e<$-70=jc7I4fv~oWShLXLz|K;-l zn>uTF#PSlIN&d}3*{dO^gPsX~ZLE@!JF`jB{i)yh%KkSJr;v#W5-X)3;9r&Tb0((u6br z%|rd=#Ih|M9!uzwf1B8s7zy&Z&A5z@8n>qs-C;s;>1e@jwcM_2PNcmqR(_R%_KW5n z^$R4T&r1Fi=x}Y=k5_7ck>Erw4xtF0#d}_&81#hici?7*P$U&N47*IfsjN0HM7sKY z-mN><99nT+URfRX7&Tz}_^ruPXyn5*K5@$5cfkUPd=+J7VP9Y0&YMY>Byl*h-csXV z9NUVYUg+o~)^D43o93UEj+P@Qs+Nzb$1q?cf_#I~^2zcyCaRN{Eo859HAWIoyS^;= z$mQWJ70)a6ZPn%BA#lY;JGtg6i0MJvRh-{_^U;G2^6$KV|B;6pnc5mQ#)`Wt@;eJu zXi#ebf$~~jJUYpOEf3e+aL%8OYy@8x3+ljLT9UHKHP_KDK{m`46KZ#z%)rnH-V#{} zF(+O7pXmwsZ@X8Leu)?UyvVtN;`A}F=|Mrk2RZ{Aw4J+=RuAAU{MyT$~BF3y+ zG+bEyF``%?NMB{GeSboQq$@{RI^=I?7+4P_A8 zx@sFvEzL~nZY-iID?uWZ?Yn~lEmh_xF#_6pNG!8j18sh>H ztSZrrT21lU%lHrHX^GA5Jta}h45r3A&Vp%v80K~_Sy>t6Yy6MS)#+)VSF0=yg4|q| z*g8Qy5m6P+^W*tCI}N6N+w$(n?uwG^VAE$V!LdQ=Wosj$3#ZP4@)>iJ8a|3Z_&J26 zRHlL-^F2To`1x~i&t~U7BDhk|ikN`oCp}v=7G>UU)7abj*v_@^XG3d_qNu_PEAHF@ zmxne&t9Nz%Qj+u|*>D=zC|n}i6lpfqWxs5+Ghx&c^V%Mr9&&U(IU+?x2O#hji3cn~ zC8NB(=J22^8=7N_r*EFfT&xR#Z@CfSUVmK}+#Rw{xcUXw4y+ed;@E|vwEk|NlrmE9 z``UgRkvAY2X3v71IWZj~`5_EX3lWErl!hkshg>SmXyQfnK@)XrHfxy=UwZ(WXpowo zk3jl1TaQ3gH6BL(`dN(F9mVma-a%7q=Xp{V-3fghL^WPZd3nWPItSfK58f>$7Nhui zmiE1#;^UpkR3UrXb~dt<|Du(oNS6s4E5%nBM7ONoW%d>nR5u*75Jl1MkLDN?8E2oH}q>7}61rO>SA_yi8#zCwsD z_=?y^g%cq+0%$5)`bz`1PrQCPOKqGi{74t8)A&z>#ADfKC(fQ4#hJ|W&h2B=t>Mpa z@qYyTXc5x{ok9Yi&pz(XgX9Jd`CpuD&Nyh^v>HhodcNv5NnG&kzHt2y3vjs4DzN+= zjrNFx|K!j_rnG!2Ln(qG2<N@7lzHf>GU0P0A1@e=# zCRnevrEAxjAzQjP8z0~bkHhf`E(+c(cc;2PoP--)okLzK3S#^aytt0b&tM@pmVRkL za>|B;@G>L6s}$ejJ{?#&=*Bg*u|fPbP9*oz|0<5F4q^DyqUh#DoATFcXaPYpCWXwa z32w$}bUrO!gy>d_j~2rV74DyAJaV>z!H)u+IIGbEET2ZT@mY!~?Jih{-R;H&liRp% zImRBHq1j!}p-7LF(PQ;oq0Orvn5SL2FV_>5zIt~NGe#>EX-8~)%C0sw`{P`1=j$6iu87p>A}KnpKZwi6{tPG;Be3;(hI`TG#F zz4Bg4rc1)k{SMrHQNQ_Wxyc1hEA!jNz@!xJ4adiaUc&i88(;&>C%^CWg*_z_*-c=} za=+a3!$teNNfK~&DhvrucgNmFb$KVJ)5{y~e2>)gOa8hgi=bnEE+66waTrUXz!T1& zUkF&Qq&dTO-JZ8Z8@K1eb9LDKpeJnf-=TI%jc+XoE-r#ces9Z%-s|1L?##ba!+twG zUmpOnI@iR+L|IvR;*cL66%qI*_6+8Q_&zUfEDubC*S{c;g&@E~qbj7RGRWT>xSBT? zc>slZ+LM}^I}M2_aeU^kv5N&zlTlD_?*fS%;4+u=Y#&`%mR{E-BJH2QU(`v_Cq-YL zPk;_W;mMxcd6h}pTB$z%x<*r@)lv^+t?@V77=e1*O~PYdl(8*f6e|(Q8!J;)HNNA9 z<+eZ@ZOL7%GYj>?D?qh84(RDwEh|Mrf;+eB_@chz zBK%-4sQ+P9$xr^d@VQjvG2~tXIAF4G>~sEG^YXqPEL^RwdWO(tdH~s<}if@50f|k7Ml8IjwNk z1$LbUzdTMFr4p4+oEs{8^THoTmI=DPADh8Lij4S`QLVuR!#F>6qf3Y@GJCnGPLjIX zh+_EbH_Yl{=Rou~Z;-dxG5>IRLz~wW-3gBajA8|Jm6@62XLuS8+q|X3AiZeA1SeF8 z7VhR~&HD!-p@uA>;%n2TVoq_%_%B)ktvr<3>IP6PB9Qp{C9pj#7rX)%#3U}gMtRC& zZ1}`xRg2x3xca@%CElqYj$Py1eS~(4wHRwO2yqbSDaY>pLM-R&b`^*t`zi})Bm9~w z-q&1Glixs{{IV#(ToOE(J)(!Tah=mur@s}<`Z=<4c3oAny8p+=mw+Cm(=0XK1+96rDBQ!fw{kvv0ANaj0*p4*#gya9zC&y}w? z6fvE*6|rGyPEfKk@RFAFW22ch`rfRPI{1?E9Albih;2fti0atZr(;YeP1Dn;9UX|w zy|)X-3yS>cKeSwr;K^V#_4SD%fU8~EW2t~(77arm{bCj}1Rl;YK}8o2G9|=#N(KZM z`3rAIKs1U{4F&?SU{;x8K^V$Ci#SP{Aml8>32Y}fPWAV3|FRuDGv6C-!Jlh^o8M4g z>QUj`tkDJKh4BtlBCCJ1sOw^vRx*7G%EBS=X2~nrvIZm)KX`A$f;k-?{QV+r?|2)7 z|CQ&PnDp;9gx!xeT@7Y`2-M$hb=avmasC`}v^^<*IGrFTGa`f0*WBDJr~j!(yRfoE z{6*dRP%ZD?zR@<)a9p1uk-CwScwpeM`Re&I|C5Pq)m(DM)^2?wpOC=W!^l}rT?-2L zN>&%*8zXr|&y^YtpNFLf>vII7^($8ZP&E$lvSk*T%toCJxnMzVTu2YEdf%*9xtgE# zff-orWc)HZ8`w%J{uTEB>A)?%uVKNH^^z|CznzAI?db0nJ#SoDn%tAOjqkVv(E+Baa^yoOBk<|WDT<~RP5oTc~tfrLjXZz6LDJ{l~15!&ze(6wyG zTHJDqnA4(3Q(P8Kgw7-0tk=ssJSo6ST$gS-4~|L%J&=@m-=I_Hj`5l2MvtHNt#0%l z-)yj_J7~Cpp~rvCWI)E^8i&w3)%xkG&_<+>Ez4eaU-n%jw&PpI-PjvcAulR%g zv5b3oVS>P?tV?%(E`EIin|N~&Oe`>sB79CRT%iF=Lco>Wbb4?F7DSbYIp9q(c!BQQ ze0yK{t#A70usisM=4P?3Mn4g^n%H@Xb zKJu1Es7qfbg4Gn^%yf8y*bC`LQLkU?m1B|}sL!qcLmHQzBpvgB>rvT;O;dZwJ3*2d zm*dW_?{ZO>e|H<)8pD z8`_tQ<%XcPli8W*iPN)Mo<#bf$qFDR4oWTXGx1vuwBXP+rZD(DrKc}0W~NAy?7=Cx zEaxPVUm>1}-(S;hw7^C=7(OVUEVDq2n)DYoBEHm*uMihYG*IMk}QUd4_s(xv6nD* z`qbPn?+~5tX@0INAVmNVAB%*HjBH{SRaoTg*BnajX*8~HHBk@z>=Vbc_)8UjS9PF| z+i;U0q}^>ZR6JUkGD3R=3@jus+wp}Jy9i$7gqSl_aQxCv=mX`@e?3Xtm@kLlUX{mN ze{I3XSNDA$;Lz~Km@a%qZrH+*6L$Z^H7DhrRi$Jz4LDRmXo0&)Eo#k87If4Bpz1rv ztKk=(ZDu39WIXv(NRa0flp%?vI$H;8mdCS!uMrM)8muH5#3gt*q-Rk>xM>fi*n7fwfu53 z&~)JE7S}R6@h3K6D=Q!s;?8BIrjpRiL(%l*x>(XwBh$xFsS8 z*0c*oC3>HW>hlL{X78d}(5cu@I}~#NPjcFM8>Y)F{hR03R;Oifza&;JDzKXIqNaAS zb6aE)L_$uXLeG#t2?A;5vcpo)!8g<=g{`dU+Z5hMFkI+4qc=)KDkJP7W{QS&rKYAz ziEtZyiMyzVgHK(SP&c7e5O^?)MiWJNXyvrJ)~u9naai_X1Cge{x-E}f3bX@x;qO6spg`0%`bm15=cI; zm5k}=h??gQ&w$n=%}afwAdj(_dqdXhYSj-su`G7^`V=Fsj^^>u!OUFzzG z!L94>T>Mt^Qc?-79uDEXS;k%^@NQ&UEo{15am_kc`;63MD5Z)&nbKG{z4(O*qoQ2d zIa?upk#c6P)@O->`fO3`n=HMno`@U0`aoYDs~1=L^Pe>ED2kw-J^5HM?T9V&@}6S< zu8PA+y#ph93~i{~*RMwl9Hu zmOevX_Xm_bvVJ1N+FIhfWiG#y3^sNmFUicY7C63mc^ofgW-?!Yz29!V5M7BC=zm+&4|!TNe;DIMynnsNWObo; z=Vg|H>wEN^K^5wC=|Ofs`wcsNG<%>{ywSSxo^jp)_51PqTgZ`RrKSP0f`S%!{jKM9 zLQKmRM1%!>Z}1keJEz-q+*fagd`6RVG49lQsqchbY}X+|_p#4=fT(%R6Y)F*IStqn zn9BxD!GL(%e$V3b{P9o9$7b-OQhg{%NU!+H{Yv0&iY_mSvp7^oqLS?z1h&uF7iFxZ zKv&{3Ij_iqynYn6t&Iov6fbJqIsw-Z<`v{tN zE?y6LfXTunf`|&o6T9mTw_(Q)i;NVTRsVwCIQK0SyF0}I4(U~PLlcfw)ny(92?GvC zV7h~BF7Y&;YfEIRL!jA5_>-~1byon&yUn>{v-jh9hTk`*A@8X(t^W^KZyguq*8PFf z-8qsH64KH+(jh4#C=CWE4blwVrJ{5QND7hyQbQvpUD6=U&>b^(bI$v|_jm7~=X{Qy znc2@;>sxC-Ncv>n_ZO6ns^+b@9LR1Ut>!m(YBmm|E`BNwP zaa0FiX3_7mC^ndm>C}@7S;_l(l@teweDSj03z4UQ^wgo_G3<2n=5-!XqJ=j$2kAGD zy5B{u8dCmZSjWdBHRi=pk2Je~-^U&AOa1eedin>FOXn)z>vK}A<82jW`}@ERv0dxm za=nnNSnfLvjosgQI`6fXH9bpl5L5Rw!edd%$nbF&@<(1fkt#;Cr;dt*ho2%bzcKkv zL{dBRoSRM{Hq?M zI+f>JS}Mrm{g>kvRq~?p^2Byhi=>2Ctl9IE6Er)+OE*n|0>m=Tj^YZ7>ml~R*CXbw^Ljtr3YMqsvCDH>kuY2|D?EU^1gj?Ur zF86#^H8jm(k?Rx2dhiPzIyznVy;om!CawQeVuKe{E?(U19n5-hYB&o`C`SvHg8HfS zhidrE?0q}!<>7kw&eO3DUD2Ro){SzD-Vx2>V!(0VVK!pD02=yBZ7d$z<-6B}yn5C^ zvwi3F;?I+(jguz9l|JG%7e{&;8ffJiKKz-+4y{K8(CjBqt$yxGjSWKg-1=2~WilJ~ zPRl$7nS7&ZmW-?MM!_&+_9fG|WNGe?$C==$GYJ?~-1JDZzh6B8Oom~T4gSF^S4BCv8t2ULk=oRgyXcnaDR)+qlVv{`pssj<@z>gqW6mDybFF8HxG4&fPcLhYN zYz~yZU#Z`NHb2;}Y7LF9x?+gZjyMytFHY!pb{OgQcK(@Nq@Gv*^yN_^Ueu$u$p^D3 zdzsG%G0#5ZXc{Ax2uPtEufJ_*&nqXrM|FK$VhRH?;#lZ9pVdr_{fHcI*w>=CBAME& zXI6d{@<+`P7eV(DU}44|bf2l_vK&j#Snm&b$YqP|-m!c4+PS~@NMZhXhGHW_LN0A; z%1F#%dW`N8QK#8bO%?((ev*Q@keiem9M4jV;~rkvjsr7J`o*LtfJ5A%UH``u;B%)k7(8He*lGm%ca&x-pSW;1S``yU~-)e;lLX@D`F2G;(|8 zg3d|vV)=;9;;|t2fJYvervbKN;6cU8RYOse759%eH_(9DBZscFMe8(0>NS;&6-Oza zZ0mA=6V`uPc8g-3WoSHW`gu_a{JA?>GFss=w|HiH9wnG)j@lx_Kd{GzQ!e{mpZDHp z@{+m7e)d7~x0XU<{D3j(g7?)T8~4}v6Q|wjck)M-oOL~!PUk~veoeiDu$0I-hn#w; zbGJ!+d_U^l-m!8w# z?K1CsR*o+2hZV+N`z{Npm^jrn4DC6QUb{~o63UWZPkf`CegWy&B6;O=>ZGs|HsO`+ za5)Fw!=cLTCnB`QRlF74O+j@jiW>%#CcF;1HE0wfocj9u*!~r%Pi?&LNu%F8Nt!B6 zv3~V3ijWs91OxIcz|mh3jySH}taZ^;-hO$t9v9%H6^kT20Y&RAs?8FDSDT;Dv20~6 zZO@b_SPm(&TdkQ`vm`IM$3SF?6*2>dzQxCTi^#7f#jAyWx2O&cW)ZwQE5tBs7Ba2k z{Q~2s?a!}D7wtwX^i{g9PuyBQy=Gx4qvmi254W z#2$vZn3x&rFvrOqyzo(&u<`ryyZ_VJZuj;9H$%x}q0N}Y*cUxe(K&i~jqRJeJPEJeQ3>phkB1r=$))SuM}A0X#%Vi9o~tPK zIdUn&!$%D^CTDsc@M~oczinS0J@A~B_?G7V&OD>$TE%_tu%Te2SLn#)r>oz-JBcX8 zCAC7tkg&aYYsC^%DBh31e_s#~5Iip{$j`^=kB^MRuj9WZ%n)`()?;ai793GcdgD%W zj%|DU=Q7_gVHM^1oO{eB6jRem^AwRg z|4b(%*WqDXdo}@~$CC*LrthxBpT?4lY=*cT$GD0Pa6|g&MSJN*G~Nzu93IPB09K;G z$MqSUPWJ!NRO68sWlH>JPZX^hUYQw)dhTRXz}&4lwwrfN1B^zAeoHsRy)7$ZbxlY8 zs4pn3ttW|xX7s1N)8oCcy+;`5NQBqo{=|K#|4888{$m)cgU3wJ8z*;2xa+a+MaPn$ zo>{gK#}B?RA+xr2*-FhX_FO%Oh>WR*qp~ktI zxofWVZjr)POK?Z)P}zb-2+U{na3&*h$ngh7yk!6`@!Z!6PM25P4>Ck=P8(Kh@wv{N z+hf?7u4_Evb#&A>3;{FW$ckG6m=aA@r3TS0bMZGp&){=go5I>a+GOs@qgzl_FI1Sl z@STL@9qk6A0v}u<2Ftx6<7>yFBZ`pxK4Wl8X_9oK8v{R)9lHohV7-Vo*N6)oU6kAp zT+C`2A{GbIT~Y%f%h8grN_p>Tl9)sma-I)Sp&alNtXRcZ6V)EEA_Y~y z+{dI1h$@aE@%nZ$;27JvE4FlSaxhT8L5+_e?bOo`QB~hW0&sWy*fgV;(WBsCsPYC~ zeh$df17I~v={K#($f0MUJ&A}q!6)G;)e&hWWw5wmU_*&dC+Pp!_qM{ zVITnsd*$Qg@9E35l|j72yAW!4hBXi$8_~X0vvPnv__plpE2!w{^Tx}TEbqCDC4y&n zn|=?!Thu(x2np%b9T^%zy%Hps)=16ab z6Jid0!n4PgdMrnAne@AspoRVVPYVNc0e#$b)G?;7ZRH|KaQF@bjcoG9+79?loOKTppndYdw;PrZ_YuFHI@y&aFq-=b|FHx{DTC;~m zWqZC$5qOPBCP6~>bWaR(o3Hru8Ks}U-tK0O-#Z?aHxTkeN^V6_SEIVhyo==TlHpQc@v9n{flKZYO3?P>}YzWXA7+?Nj%%m$`5E zvdOHBHu(R4+N8J)ujtcR{A_6F4>GI2c(3t{@P=I(6*IDlyu&og+FAww&IDiO4v%;2 z9?r>}bm|+8EgooTrsK8DZ#9LR#?P#0503}*N$(dhdE`q)vU<1dsk-SXv;oCv|F3XQ z-5h~9s*>S{qIy{|9fNdPr1iS!$(szhthO}A?t@<|!Dq@Z4MZi7Q!UODW5ra|q)lhI zm__v}&2^)O{}t5#jkHC)p9X^Z(fT0inP3Om*t11i3`Kah%|)zJn&)-1ZT}QArAXQR ziFQ(0Q}9g>rt8id!RIi`jZj#)^&;&b1vp1L^N!xEL*Y?2!f2+ZA5HA$JI;d#50Yhl zPRsF0ef&>_`*q~-gQ=KQ41~Jk@>a)0e^c|6XL!HKdYZ@V#op{XsO)pBr>54je^MqW zKlrP~r;{2`T6ftKDsYwJ*5wIWT^5Y)<$~Op0DNcC`|7Cf^by8vj13_dAqGx4gB{fh+9MT@@j~*v`YBW)1 zKIpU8g!|B|d%ddtR!m@J$N2%W^39vI?Job!<)v(EJjkD*777d+tH1cFLshCv781Tb zw^)@a2+?}8B1lTYG)m4D22AYHX7b9sUZM?zI=WCmQAh$^8gQ-RY^Jq3UBR zihFri?XpzEq=QY#9W{*Pvwo^~o~8Jqax@fkBWvg5);kR;xcKkPPVPht6yD?JF5mQ= zo76+}#R1e9p;uH>lUS6HuXeSMH*DG`5W;axPw=X&%^H>5Hf!42x^$_=Y&hSTAZr`< z#cPS=#=F5Z|BR*kON)RmwdA!iEPGE2ZW;>n3#i#}pi*VY?_EvKy3;sF4Gb*aXO$rU z;{%9~i-6%qku#GH4ZLxZpkPoScFHgfy^Dy)%^F-V+p(1se*S`8MFC?&N<$f2 zMS}pGsfIn@8uS{ybE)N5zfzVcAy9i(hgkf}CHP75N=gvO?zoeM*Vb%Y1i)xZ9vE68 zQrUVWAn$4$7xeAFSpd%|H67KW?_CiQ`|)$Dhw)lxxQ7+bZ>&c}oFsIMz0W)r-qH}N zSmpT7Y8UwPh6R2|3=^`YSiAQ~xA~HQO_tGmR-zw{lI^X3hn!JSweIM=XrFMG*08sq zaZesVW+{dv@Vre-`GFAdDV1*H^^B{}JWrXDq#It}k4cO#vNs}ej&Nn@fzlYzy^JPm zEzngSQ`A_;*=DSHU%Zs5oeetK`gW6z08f<9DmAL!W4FV#o!EvH8UsGa`sqwXrZY~Q z)$}xXhs~tvdF{%bU2jU{0KnsNa+#}rNoTfp6ihT$pXi;l7f3){@m7Lj3FENE*fq<` zjY=1iyk&sF{KfaZA1Y=xk>DyCKdk%aRF1x3KMA;UAj=$+%yT1+QbESlk96v+Kdr_=c%=jG##F*9xsv*L)GYoXn!j-Mu#t{q{kR1Ed-iY#syX7- zYQeDY;WHxlhN3I_P$Q7tFuyKgwYiMa`KoSyY@($_T-3u25*Hy5=NkJN6$gj!A>r+I z5}~lGV!sW;Bkt?d57P`)_av^jYCOFT>PeGR+#*t9vq^7AZ2AN!E{P3B_jG^wUbrOk zK5GlYCJa->bf)zMt@>&yT&VOpc16X8@GFa}-yXWBJFTu~a~2hg(o0yHY2vv8Mgg{~ z8YPA%=mAHgIzlB+HKpAx{{FQ{9x&RiCmgMRC(#UEoz#A)+lDGr zB&hsy0JNlVCb!FSWltf0js{m?=a&DBk()E2d~G03YHhph;xe^V`$N|jkTmO8d%54A zhr(u^x$^SPwI$H|h{eA&owI_&{!L7;tMN#Wgt5)z`XG6)iS`JSl&C-0ree{giB5!g zv@7;pTM~OTU&~0Kk!+6?7C=rO=y70GT_c%ZRx#^@xdlftR%!{`&qbYG zZp$0owAw49f1|!11U3A|W0;fa_P9la?H)FeanQ>%U{ZB|PMNt7spX$5AJ`GnREM>P zlCkMrwK)2>!EY)oS}|N)T#V}7Y_ld=0C5N_k|(|)sb~Sv2FRY}z*tk)c?2dym@GaT zAq&oP^Po&w@W46wlutN#Ulo*+AX+I%c2g?zgEa?}nRYF)0521yO$Fg5OZDd=p=9kT z-MRa{Z}GvKv@s|->ymvwWgLqLSa*A?X&;UZeR;g_<+1*^$902kHH>1XyFZpk8_drh zrihLADE6HuB$Igxy7(8RoI#_AM+-Zgo|rvr9qVbmN(&{ks=Kv;|D9T4rNcA;>1E}c zD;r9nE?iTZxjp?qPwuRazdbBc7vQLGMRB<3D!^YAK8TMS+Or|L4*Qd@m1b1uv{X(^ zO0TY72RzH|yrdl1F?q74Cs3>nVRAJ;UF9ba7(E!sRT;6}rJG%Ux85uUqj|y(2#4OW z#z~VfkQ`$ZIyIj$G3spQ$R6TlW+AEiw8Sqs8N6OhuG|qP+52p0C4HczNiX)$O(gDQ zTd&?GM>Hq5g3({bv&j>AuG(m59(%eReXb2<+;O)fqz#&h6%Zgj8_7!sb5VrU1UED5 zhR9bAbu*2CY;H=_I4DCeZTipV!aaH@`cdb&`R}%M(f58#S~a6!pfXmP_vAEro?0|r zzCnp;rAO?Yub}VGd$Q%XDU{Hfpz+gQjulD3uPKh^JaD1k16KdM6|$da7_rwk{I2AK z^h*EsG@C&p;6qBJ*Ytxifo43jsdY?XYq4Ph1HhV{<93{`z3jU_nh_6wLzlU5jdPTs zb6K`+Is5Ex2!smcM1w&zx);3uft!nKV^WG;hF2k{$Kkc+*8as^i1t7620Q_sdR%+e znLhLXWZ)!NS;A`K&@JAR?dw{3OsmJK<%|fm6ckWc;cfG7OjD5U>bp8!c_C(kXBf-4 zW%K!B^plymmlnw%wzV~}frLVbTCGRc=ccQYVDGG|S5i~WqhZ~nH*r5fRyxV-aUTH3 zxwe5>twfl+$fGHyQq>5WQ035mX>SLRvJN4`%=vdp#uT3}?JB^5#ccT^6y`&Dj?gd! z0*La)WPmHmk7N{{LgOZ#)uW2Mcd?^AjeR0t75IVv@^j+C(#w;ragbapf6?<%E( z9@C*zZX{?wyOH%}+a?|wx1MNx_dWsIXdGi{woYCl9xE%_eugW_R`2IUr}HG^Cc4$3 zY-B8_i&dnq=>&Sx^| zD$}9`y{SodizOlWxTN_UuPJTythwJ3ARAfQ9$~a8xRrf%gI2vB0GXH$Jm*p3Rn4@m z7l?YUn!W1B<&zqU!5aDrk#!Qx_y=+>1=1;gA;D~~BP+Q05Je;5_J5E2nE0 z2J&UN_aZI(v2^O{`g+xi9*V=m!%IdrI=5F<(Dz#o(pL=pNpSgz<%QaBV`J3=qwi3M zXgxi;hO~9fYj>UDU6`eT7HGxaq|Iq`(|_0S$eC|XH5!_Rt^*M2hxF3K#s+SK{R$Hr zfIUy1RHs=y)FM_PJrvmT*|RJyY;j$QMV22;RTzOR)=7qk;Ku~L9rvL>Id9e)_Ec>B z%`yAuX5ZT(Z}x6h{1BqPz8Dy{qGjo^Ym6b<0p&YPVoB*)wKmS4SXCx6~1 zHzVo#2K|}Nt8P#4BRD<4cOND3BhKnU^{Q0M+h6>v8yplv7=eqqsiMnm3MPXg==VTjm)5Z8Zc}%YJDwuC$de=^g`bJ-Gq3 zmi}Y5U82dtH>`>8%gJs=hlU=$>XOjV2&Q)l*@y))+EHAM>sAkOy0?o{dA>ALd|Osh z?9%FW2s$JKLcF!zP$&MxsN z7$`?)A)NtNj9^L#2(sgag1gr$oR$=5c#T@N#=o`8rZefA@Ph#C{bD{m2If7|Z(^d1 z$eM7Hi?pDb=vai+k~=zSJKh^Ku~g$YXVE0%XQe|M(0Ln8LI=*hxb;k*auYw%EnH?a zWa5kO^~ICho7|(nGaw0^wOYCcG1VfUmYH@$o=|CSPgpixyP)}UW=3phctmJwc2s)^ z^qwMs=OSn^ckT;W=_0ndTOax%Eqb%*?2ne#M5fr_n?fc3t$OSH(^N@WW#mPz2i!?q#b?711Fk^C zUofg}V#oW=<-Jn%ic9GC(&ue(t1n}c+iLMTV5)~~RK&Gfd=X`swSOy!C5G!U=92y^ zV8r?!gN%uY1f5!hCgkxz`|l^5dNCzkU5NpL0YzUBl|T?Dv)bUgzdJ)~NQC*+pL)R0 zU+1MqplC-fMXvh)L53f|x^s$@t;WNv@(|b!4%@Lb86O;R!U?E|IP7EZo*W(t3Fd60 z4OC~KY-iY;{g?->gjjV1LcOauL@3r~s%+$RF; z(z$6Lqh@yYOE-1P$!}>J|10`85g0CLfAn>hfLm9s%6x*`wX!UjudVEN?Tqqk-pAN_ zos}(nfQ6Qs=FoOLZdeF#;fK_yvo3m}(r1`qf!m)Ahvq#MgW9d89>~57`qm~(Fl_uN zk@t4V=|$Nf=)f$ZmTgM22p#lRv@lq>(QT{Z>2O+9KP8h_0^=_1LtLx*`+XpDx#its z@SU;{tZw2I|IsktK4F1Y`_sN)Ls*jI_?xhC*`tR>$Dd1QRrDX94@wL%kFWv_uHDdC zeQ&;fho^GCrx?iv@|2ZWZ2et)ObRsTHzw;M+A{`v6F8lxH~OOeAQx9i72fnhrJm33tU8ESfLY93~3@8o#{0keDoypROfE z42bJRMFl15-{;YTo}+cI4H!B6#6CHh97di9q-XiZJ$@W?`CB?!%nr>!xu~$kd-Zc2 zfbOet(z@=u9oOB^<)*(M&FsIehS57gFW7-0st4G|;ZfEKY>Qi_FUi___orFuH_ov^ zIYpm+c@sxC!av4O4semcN*|BfTG54fv>*cKgT$1K5M^t}$ljS*2=dmAY_L0&Do zU#;K#<>b=RvZ%$C{eDTVdY+c6sOEF+9P{^u3F;!=f2RLcH7?UbzbpHe1x-6Ds%kls zL~|s?VCBoYmE{&eUDOdXFZ_ZS?NU!QdoUyVtg;Vdm(2=DVMpsL4kUMTivhkHK}ndo z-^nj)CfF3iXHkgZB$gUdhsYuja61IW8kH6 zn=F+Oftww%13r!-sd4bkps>_+8LrtLnBdn-i_2L%gb?FD-FK1+uO=oq+j#ii@IF(2 zR>Hm8{KM*tSEcNyjHd(-ClV;zq?6m<(*XLBD5=_yW3iHGR)d2-EdS!`?+VwnWRc;{ zsR}tOYu{v1R2o~EPImEgAQ;5ThCUUukNomooA@ZAQ!PPOF0Ck`U?17d9OAx84#>tq zUuJ(1R0Rr?I#+uPckeOvJG%S_l!=eRx{|Pxc%M-mei?cHLd=?-^J*q2P0}6FR`~*d ztD8C8*+LDOMOv zapI70E*wUEy%Z3a6@PmiWI0KI_Xmj}3D9*n3t3-lYJ&n+36R4DPWVZ+Xq}=&ouDiQ zXxzM|tyYEmFMQgV)RJz0zwrOD`wl#C6XW^cDu~<#F9)!&bD#VleK#z*x%ygRLjj&$ zSvuTF6rMI~!!tvNsbdU<0Nncy_)&-lP5&52h^b>~2240v>X0K>`nq&{_guUO9Rtk7 z$0VpdXW>|+=_(Yb=U+C(0@hyernyJLS*_c!7ytl4%)08G?sj_Y{v>0JwY5KgL>dCo zGU3@{UoL#qE=$A`mY$x@K#-a?tf=1BZb=rExL|gtB;ULfRrXyQ>~P`n$ArU&PwgYK)^xG7v0@1zyulRX9s)m2Vr0u8(k5m>ik>g1Dc(d*E4hjUZ zr^+O#M01E#_JXd&w8w+NpP7o=>~9V}o>GV#JCL*&hCn2Myv@PJ7Cc?`I(}on9B}xF z&S+=oK3doL0cbHT?)^esE^E)h|JL#r7|YAI2Bc#HW2{M#7ocLh3-BB|dIT=~?O;c{ z|LtBKYY4<_heTRWPj9Rz98OMoO>HGo(XcZoz^+pA9w*pm7(#?eOSDV)x;TL=r`;W; zz@Yu;A%vZsw?mDZl1-}uplLQyN#(Y7g^&-o(>7;Q{Lj{_m_)Vgc5pM{hVehh)dZZl zQ#y>Htj?@8O4Me4W^2ae^-q$F>`@4hQX#ly;ybEFW-&GZ~cG}vQhwc z)wH!=T^z1rRwDJtnV81F{=koGv2EUC9$-}A4U2jNeY*+`OWDPMmyWWZgNL|XrCV1} zaIw|Gh7gxFUlpS|EV%s+5e=JpLRDmSVZ|p=Y=3t~n@l^DytPLd_+nM>yv_fVWqp~QH-9&(@QWAE7`4gECIZKYoIl9e`oNG;RSp1-TL|Pn_-em;dMv?Z zUzqO9ic&JO|5_Ti5(taZUHfnx!gkpx3r0maBPN{UlvtplTifahg-ECmy8?q5_%0I0 z44+9PuiBl4R&<@ZA3Am0-q;c0glWEYGN1ZK*{v~iyiFbaZJ$+$c?DJ-XHX>X#thPa zU;!kRVQXV^SJ;~2U$yu4Aw7QVk!_BDecJyJ`1PazeipEM!Tnbo`jOMaz(Wc;`*qc0 zqj%iZYw(20S;fie`q5~T$*U$JTDG!Am54Yo`#&9Rp@h%MEzrR;N^<7ZA()t&`p5ex z=sz)R1`-gP z@AOL`baV{F>`DMsc-0A@FY$ZHADjob|p{f#9=MYCYgMh}&kQh+SM5Jjp-dt>n*9f3DWSHB139 zt8=nEZ)>L^Jl%Tp$?r;6hKWcyu)7)Mlb}C$(!mpRTQGTpl*l^S)>3TSGPSX*|A4Sr4QgA;s$XyPO z{1X>I_giGr1}0W-IyySaUk_%&VxE9BTqfuP`ntM;i)FQ?OH0E{|Abz0*>0P8uErCm zeZxUC+17{gX9eZ|)JBdnT%i?Fa8k()Q864R#wL8<0}RPj3uTh2>401IkOk`pPBA)c<}N@{3x%V=gT%9E+t|M z_DJ6ooWMg$pHCd~MVCa|Jh`kh2h8cs|HKN4L;-WA8s{khtGT)M%_Czvn%ua*uV-;u z{bm?Ckt@}|xprlBaZM{LJlA&g*|UOeu=JaT*o0TLV+Rnjv8gi%hgGx1p^-47(Xf81 z?$A!14S^_wGAb-7VTVHfTlOAZEs>UO&G7+5_&L!WeEgds;6k`DpN|*(Fm=z^Rr&UY zXJN7w$D3$_1|Kh4jCfaNuDZU5g2%E{L>V~2_o!q9x8h6KiUfaNVRydQ zw=T0KzTI-%b(MgS(39=PtrLl_k^bG&!y9h;Hy+8wJ;%J8efxu9Dk#8VH^d&9^>zRIwrLmrO7I#&@6;*tMCQ$>RKXa{ zm>0YG#AJYuxCua^S+}Og;UUhwsWH9=M#Q)wNXrqW;y8#mSN(1~N?Wk#=*;$%v5A+9 zI_($!!sS`kNO3F9P1$h~|0DgM`lG`4LMX2X+Etljtr5>->Lk+X#jRwwd4WYa@<+z5 zqhqn@;#DK9NdN}d)#k#bZz6LY53)GH1Z1gB|xd`_rGTIl#zfV=}zFNPTwm8 z%k=Ts*pu0c3I?nkfx3WHKp=kgvu{NU{4%Nk#Fc=rW5?S$X|A(Et{O0)a-FZGY0}K# z>L(kPujhTx`3cBTa%sff`C8Zhr@O*}-y1ZKQD^C!xn_LN5`nB`FdMy0vqH5@r3Unp zdn}FZjU>jK}=d6O#xzey9+|*sX5&QzLHnFKbWb_>9eE zzvNlxROQz@&psNctX?!muBQtNLt}Hq)};rjkUOs-vkqHCIGV47pMIkru(CW`8~6%J z?q}}xovj1UOH+4=Hh)q|1x=!plBh&4TY);VmE6Wg28%XWGo6nPOqF#Q@R9HR#|>e1Yj;_(+XQ#iBtF(vDe5Qyntk-=&&;pEzWCDzpawM=B;7yd zv|T*#@=SfdA?~tIm>Ulh_20m{3Q>Y{*a#2AYt*N-0?uItNQE5tD_X-AS!E)dN(IkKJAnx6}kk1U31Nh&!2y3K>du0 z)7G`g@k_6fgqI{9;8HE@>b{J0N&!gWB~_zvvVw1QC2ePnnYXbtX51 zmuHUtkJ>q*J+s}+1@f9x_pUI!)-eu}iC=fY3 zP=-@x_suA~Yq(b@v2d`IEj&t>qzTuVch}T(;4h1QVoXrF`=P0G^~sPpUYMm)YkLL- z5nEi)OO5@%Ynq!Z*eNnH&tlwyoEoKKj6A6HL)avl@r<|ajYz_q6JL&iOgQKk5n}i- zMHT5)S`PDLY13fy;XV30XQ&SI{#U+PWMJzqrtKuC_3_-lrdwyQG zx-xeE$3Mq82tqu$%w#+Se-2mAVTY7s8PctL-Tn)H5TM)7RdKpSv!NLz|l+P;CoFtSr% zWcMr{Q4d0bXyxFZDG)E40v2D$eA&TSJX9{*g9{YGb$|6OI_ek`PKQ7)v05<~h+kTe z5e<3ZAq0ag-g9|MMc76YN9)~q!BRA20#)enNTabpc!9gHc}e6EO?WsqfcMlHC9>+% zQJ;s+x<0WFJO1)ifd{h0-|;%8r@6+kKTQGG@#jB1mY&df^ynTFjiud`=foB7+iFqE ztNKs;4wbVVLMKL4PdPgNzFTZT7qgpc0k?%tRake2%$2QQtn2*_FJWYa_+J@o!jYnA z-Y~h|>8hJJL%=r(3H7$ND`s6uk<2%E=Dsp--idapGI#Fx^00SxjT9GuEhqrDP8I0s zC42Cr?WT%GlQd+EC`T9m>b1)5QL@WI^HkL#-Q;(Fq~%3bs1^~^ ziM12I=V|?1AwO;N?(RH(OXi>Fz7Iiw$#i>irEZ1fSormqD$1s6s=WHt;^O-zl9D10 z3)+ti45kpcLGn^yu}GE^?AJ^NgtR9lt`?&l$7(Hm&4h}#=|>4vn{cdMxIFQzCyAZE zl8p|A5z`kI6{QSixZN^3Oqs<4$Sa&dG`s1EqZNLA8v3KZ|3Ia{;sY$SDwD8PI|z?eo6dc!{hM%hR3ym zp`rfs=X8jd5$atbkx*~cugk^DazB#J*4RY)q9;7LrsNV8 zwVW9p9kq3r8m6RF*U{nR=RclZ+B|j>q)UNYpfgD0fK?7TMQPXdv>9I=B5}U%B{yvjBlm zei9M;DdzCkEgdUI2Ld6PZy|+0e@fb=*YZzpqNtC~#PF>J(brs$%^JfG>Bumd# zYBXP9CTB&beU2kJuCA7!EMSrjTgndKZ$4+8c-hyMvtyI$(7NLkqx^*4=FVKS#r27g zO0_J-o-st*q}M{8AMjg;pm;cuL7j`f&&*O}eDS+v zfbWGv1I4>tu^W$M8CxFPJS*q`h zH#aveXMW?hpw)z6xuYKu5|ooX7??CO=#0GDwbphP!l|X7vsfIe1<0S zrwKYaA|mf^jz`n$kF+uHZ~P~9MTkxH9vZY;ErtLhE_bO%akh*71z294EAo==MCL9J z0v`sPp1R+qLc8*ndrn91JUKCvoESDT9_n&Ak_nBV>c<)F_q4LoMJ*L1zfpigaU6^y zvpWM!JkE8T9sre54RXw<*nCXf4#OK zMSlHhq@CXCaKW3wDTOC@B83l!Msh0$O=s7rvbL6xv3@)}ba`%UoJ&Cx+|h0oxJD@4mvMz=JpP})XLe1RuQQ!29Z6#S3N#3Bw+luDN~Aw z-ad2_l6F4*a;3_M`Hj4W9+yEl=&q5Kg%C~2z(je=c)~7A*c4Z(jSGF*L!&zooOoX+ zL9|wj_jMDV7)<_fK;9{66f}wL5%z!AS5QWxwvF@e3Esrq0}{l;qfzkwN<8bOrf9gg?`vgSB8S` z2nOqP{kyktKfe|8hB+qpIW=@A^X466A54V?6w}lfi>esOM;{(%-tQlh4?Qi z$%xt0sNp;82fFB)vlnCYKjNyGuc&G+wM`_|3+0FxN(2^rYjRSooOw}9^%xMX9oVtX zR~auX9T<5tmh^xj3jLjc2<#mRBX&}*6ozLaJH?r|@CiLCgi}X3T0I+)m~?@nB4LoGb@((a=mb{8u+c1jRf7dvCKihgMaig_j58SXQNt^{Nal>^8oxcbm7k zmE75T>D7URk;;1Ta=zEo={Fvzw&%^i30y6lW4aE#!;X9*z466M3crS_+uTsKACAc0 zp7a>jABsBB!hZ!^3tn)WcS35a)E4c0Ojrj<{Bm1LP{QPcZW)SjdkbU=Lfh9kCwl%z zpwZL-4)H83YH>P%)a}8;g%~9s6A@8hMOVCZD1WG4Z7AfG9v^I(jRnEzomq830bEM@+$XeE1uOTr3*?w&flTVt#1~x zKc{>}8ABi)ILKc?>GLC6e6WdR;7*p-!mt)C{R-8nDYWFO_h#nYONb4>%utI-D6Rmnh)(Ckbq@8&Z z=CB=oHC&2QpC+?0E-mzjNTeq0_aJ*?ZqB{5hX#=z=eiBSb?AsMQJcf-8?$h@hkd?y z;FR$<^&qNrG$?M-CyQmAS;~eK{2uAZ)M%M$?gIHr|ylf2Qe(B&wY;TBpN?| zwyt$&>G+zxYNN=^4z_o^B(brvWsZjw^-RNWkJVW?eNp`J4j~1&IfMf@yezywTGN%< zs`^r;#mVx%V2s-XCpM1p81p?>A3y8GB~5H5CzG!b$P20Ru9#RkI#M{5DmWpo69j{7A*Vk$pwk<0&%D1(tBFk zV**(Y-7F#lJKYuskN%-v5BR4&vD>UAWg+}nZ9`CsW}CafW*SXzU%D&(mgI!EAh(H% zr9*@ap$?yOfMUA~i+)#g#F7?T7pX0*tcXPq#7C;lBmFzw zUhjw~oL_u0bI6J|dPHP8AKmmUE;+IhCg8kg#L%qQh-gT5xeRMzOT{5l3~%Ye>o#qB zVX?uCmBp8;ik9KGb_(lOBje5I!4Da{Q?S`8SP|%C?MivC^PV-V;h#l*O1?kCdrHX> z8{&`q32$;2DhO^nME?~EYAV(XNQrL z^C8xS7huvx5!`PIH$0?p;6u<$1pPI~M0fcEzLYNEB}a2#pp&97rN*sIHFtTHuCY)s5WKx;$wG||LN{*1HUu}716 zZd_xR-Po9Zn*{JWS`&i%fz!?{m?*MId0w3)WPJv!iy6dbhG%=T) z)9(_|vM%*7;7Mm_KNxvEJT*&&$oogfi+axuXUWYtBwUhrED_3d6U`iTKz-?M$y0`Z z$iF6uffc;nC#1L`U{Mm8qiT#)^^N~>>JudK7aEJ|A=QLNv=w(KrIe$2#?%Gz?-Nal zwW9Cas6Pa?qYwh7n@+tGgq?}Tx*y@3kSy`bb5>mmR7=N0S+j!MBMorQ!Xl!DwKsht zJ7*mYSW>`~nYC@9?D-!;rR-496#xB+=`p0Cr+tMSFTNYgGMO$Auw>2GpeUbJda45! z-tp<~EniatzR)o}D862c!aK6QnBrPbrXc9=|Hht`| zR>((d-{3%3m1uUvlbI5+NM>N!&)fJ1P2Nfz9bfXae$>ljV`vt++C?AU*u3{aRS-lM@|l%h|EY6X zBkC&1Y&&abK8;Qao-|S1pD?bVrqPhN?dwWlMi&(oCAee20p@Na5=9v1mB|-SM~! zTz$96KAm8Lu+1Cb9@Wc5d}Lb;JP;s)qJ@1>Zc)_42y0bbETTgvWCqZ)I56Q^9 zj=2m3W<4#lv4oF9G`uZ`2l4Gc2Xh}AhM%mZ4Zj}1P{zmZEGoikJ{7GVdHktfN)vj+ zt)YmC-1BEHt%EEt59#X*`Cs%|2$G$TB;kR5bRZvgbu+8ZRbU1z4v14Wo<8qS6N~Lx zamu`qUTCfIlScX@Uu(k8vC)uV`(8%ta<}0=+h=r`<|Zi2#=Ef6UXmx3467J3=-Uj_JA2Lo1?T-MyJi%sehvC}QXn z@E?GiPVfJ(OX(;QR%6TT`DGf(irFoQwTt!gt$H4)SiT$<7es3|x+WYZ4Z!V!-$mbl zQvI@z1~6%n;sB$~Ed>C5QHrFNm&5V8+L>6Us*=tas~wR;@+xfelV*x@HN-0`@suVF zG=tk^)}}uQ+Jy(n&W{W9z&grG77~ktavtnAQLW2euzSC`KhK%j;yWk{0T*Hn{#I$& zsTA_1`t2+wB)gB+tjg4SoVKutny77A+8~ZZzeXJjU_q~*#Xv9cH3TD2GYcv_TrB_% zpQ8{9c;Ah~H=!uXxfgAy&t+dY?^#|CICjBG0l-kPyC2ei_h3KfE8k?deQ%iq#sJAL zLbp&d{rBDLEUh0OCK)zIniiLI@P6D;-;pwCE%T7+oxg0lIbF}|zc)dF+(M?5zE2gAZ-jcRc^yOdiEgfqMHA#7Q3>-ukY| zDKC2eujYr~hOgL)=);<7=eoAoRDqSmPT?V`TAceeAq86W`++p^c>cQ+BD_Fj+UtgPHMw$X=u?Innzf!UM;9{t zqP5=jeoC|T-831D6f`0bBfF}Z8A{^2mBc#{Dy2p8K%uoCW(@-QY*1EtH?s}Z?j9>w z?abw?tCrW}WrD~pL+f)q6N~e0bD>70)OyrK6u(4d22pfjQWEz)sLwm$>elzkc?H%?^wnPVO|LN9R1(oYMbM!v#c|TrAFK z#4kf15rM-Py*&`85M~qwnhx}T8hOThS}Q5tx%=`nKOJFGTzC)1; zxcTo~J_N_o0W`s?7Y8401QbnJBVmf{ml-lDls9pCYK~g`pp(aHGH05tZMb^&98uiy zKHtN~9S@$h`Wedf5^L|NXk5NGns3E9Ejt>`hgh+@PeBfATU8FDSY!XsTYTSD9?#t- z+V&cIBe@f9(7=cUnj_W+#DO5&Y9(JgGd!>~IJ0%*{kMUbL}nEo%kv6;`ZtQq@Z`){$wj= zu_iv(PJ|a;1X5x79NgS_nVA8h)LyL9N@T_Oh?WVi-?|ajl}^6#I@9 zJA~X+KEc^4atBD4cMu2uSKUf!y>gM_J=e!l0DG+0tEN^)Z+1%iINGv|SrrYrzUdQJ z)z;`%>tETt(9!s$A?2+6Bqi4=_X^W{^R(h*QegVa5=*wLq#O&EKr{!sU>UOme?fTx z_#kPWhkK*1tvq(@Uoq%=*!Sp<4>o-H6lMC!ip5MI)e$9av@7FJkhI8@)3sP2XdZl? zS<7NI6St`2c=@3`pfvQF|!9xYtO@(uY}gOtPpldd|&z^2HH0RvOmL?qDXV zZbH-NlcUF0ewRL`eeS}uXDexbx-3%V?9#GwUPmNFNkc%v} zd}hg304ZRV%xj1=kUFrma zRsg`Et>*NOVE$_lM$;QDm{nC1n7j0Luj!eC?8ZiGy%#^`ml&~uC7ys`BJ$3h-FYe} z*hvTl$Sm8i@@k^$Ix;&AJkZp5=e^tNd(M*!YJd?qPVCtyfYmUUeS{jp1g|x>#Uua& zQemvUsy%-$hwbXV|9%B_#I;`7>0++^rD?ZPa&KE-FkvpqzUEjjrS+pGvCOP|M%|T{ zeBOA^xPD?`d}m-`3*F9n9r)@4sS@Tz!Nq6G$C<3Y;u8K>cbapaj~rSsBrC*{t1s++ zyqU`TsW9-hYb6st7v620#h9Hm9EG1S__A{=)M%}vFtLk~wkEmw^J>DuMTN*ur8Fg4 z(w3bwV}X=zl>rlzKM#n_6Api#8jVbkM9k-X8m*$O>wY?Gc>40ipg}bEVn+^na#~Uc z@UV!HNcjq;gPzdRUpr`G1t#iPoZYYb42pJh%wIqdx#aW8AF7Ng@aC0QIkNRWPlT{I zVRLIYMZvc+yS5nTQzT!Q5=T}L5AWKtjN|uKGf^BM-;feMv~jW_%puVfElL6j?{=$c z0sO+A!Is;%i9=AKW(#GLs$dLnTQj$&v~(`p=_b_$L`ZehjV2wbYbzLhXnjRb!nWtj))-))pZ}G(Y0R0#-n;=Uzi8A z@5jye`9Ztb2?aehin(X1kx9AO40-wULf+ce&`o8!awlkH|Y0~=Kx&s?}1Q8GUF9j{% z${oddNyT}N{Fwa4Q1Kq0s>a`UNMF3Da9-^JKJbW+848*d78Vvyd_B>XK;L`liaz+2 z$z-$Fw{(gU!QmXJU#s)NqaP0UNg4xUcz+d;2kdGN54ru_j0213QNOPE5!tWDU*Ipi z9xD^z7`hRK2+m82`H&*`&Wj#Dn^%#xv6T``ZdsMGu|bps)4pPYByf&W{moDT=KIN) z?bo9?;s}yziuC8e;T;(*mKBHNL$y=S zYZIw62#UI;x{L9}YxYsTb4|%NR0a{0usC^Afq=cJ@0gs%hg#I#GxR50)MN4O^p`hD zn9RT?el%@Y7WWx+*I!rjxeGeiG~h)JwPh6t``E8qC1;3dz-VqoMAUY&=EmMV(@rK5 zjO;y{C>OHB13_{6RQNP)UZOB|B%i!nVPJJv+oSx62eJdDUmVC?)=o910!eJ$tR~W} zUfFr@P|qD0od=R+sW(iiI(gx}$c~@DZj$xwvH`gCc+%D0(1(DDtfRQ!2)>jH z-xg`2K@Qec;`At~kHbQySpwBM$U19|!*o6`Xg2=v39M6`doFc_SGQ|Ssds<;la0_c zVzFZ>0zLu&tfSMRl2P~3B`iP=FgeRCp^X12wNRP2b)VSzvy-id_)}$IDFk`qd4gW& z*G}n1w_`5V>WQpO9^jZ0iH0C?N+@b7Kk1M8Gyh>cpFBDBOYdCKuDJoItb`7k_cE>n zD(9?*T%*D9N*vA!m0uSb7^m@{PCG||rF)z0mzzUg=?ZxxW^i0_ej{VLzS*bP7Ojqa zVMS4x#lvAwY)cZuQ$uWiuwqhX@5CmSB_)W3FF}I9mYx82?&c* zlT^Pw;be;TJzbO;vTw!&KJWNjd~ZlCtsaBaieGEr;$;I-=rxsRUrRWQ=Wt&KQRaE3 znjH61X;Rb|>WdpCW$|pZpwMiGSqcvUY&lEM%n=U>`Fmhu>f`3-_VLq~CvRAAdhh!I zpsPbbc$1RZ?@D)>R@lmoNp&+&wdhd{a6K`%p)&BKziDZuu)aQJcvv$$G%sIBEGDs$ zyIfa~vZnN<%^%s`=uxagb1g3~;kvq|xQMQimcNA;?+EDEPnMa$%O0A-?Mm^^6a8C{ zHj7C8@4Nx83(j>#oAu`I)G^t4?Gs4`O&%adBsl%Z&9fcYAHmiuW>{J zmh?aTxjOTgD=BW@uZ6v9m0WbmfbVY>;bUXaK?#fXYGbe{1eELUX{z*(pY4&w{I2~> z_Ak4{EeTBP6)TuDKZ|Do%;=sr-9f{i{#$FNVE*Q6^Xy~Xm;SM%Qq$XFsV4+aocKc1 zIfW#!Jl)$~$M8?=UoHtwKCeaf{}mf3<)ts&K_;UwcE?WKZ`iIUxA5n+2Sf4!S#feh zO4iGxi~YV((dMJG(W=p7RsU*IEN4sWjuV9mO{KM7xlk-oteyfFz8&WJl4VhN}JA5YgvlrE9={~}{Do`~G(YzQ_RMMlcvnu_@ z(-d&Aaa6D;I!6(b9vd2Gra9?%ZIC{F!>5`-pfbV3it?ZpVJh53K3v6OXj`V~!11Lj z+0n?_%D(GS=SRV}yDctFaUXzNs%FHgY{8U^pN2H69RS8dm;da^<5X`lmKoK91@ClA zqZ_|jKS2cMpm2gWEMevCj$_vx7o)>^1>)Y;`pZi%oho(3Jote#QQC_3b;HCWn!bg+ z=5n3Z5Hr|H zLHEc4^VEF2sS)RFWzDceMEBe-sthXx8`NsIRIBYq*-Ysrl~x)v8Wc+d!AYX^q6U4c zU#NiAfXuuRzNkd^Zhv%q$MHi_64cD)H=E?WXr!vT_G3mO&5p(UkDx>o&329W8uuS9 zz(UK1t|-yVc((hFI0_XN72d)pZ~|m*>OTz_i_3jNb9g83yp`_Pl1DQWxm8X}Twrg$d#JnH7}pXli2vivP+8)du4f6(`eyAG`}m^FXPMyqZX;vg z|7wPniYn>ufCln_#e(x;ckfX5{ntbmk4$_HWTF7hT@b!keYlEKeg`@b=OrGHzTV?%SnwqY%@SUk zWpDPi`YrKDDyebgP1|l9y2e?nFp52n&R%2woo=O$wJmf&J!U1*PILS)GkfK*Zc+!9 z0ir)0*JG?Awqs&Nm*;;fgzO;LYB+o8ldT_fZ~eDD9~!b#uup00J$t#U_~K7-i*401 z+I!douOFXw6pFj`uv)HI7S=qKR2&eBvqyeSwb+FkvWPuSqjtbS8T++&iH^=PqjvCT zsMf0#6?Zg{(oS3!z>(ugJ^-7Vx*lGaT=GX1egyDj-PK6w>H3i97fn^C!ls1LNpRJ1 zMS1dTkU3AqRngJ0)dUBrJkzNi)b>6vW>WulU9;H~-b#++3q78!nx8QMhz3bdv|;O1 zeNK0d0{h_)Uwgx+=j?)_;~(-&pVQ~&>Xuot|B>5 z`$gJC3RXP!=R<te-V#+KTvns%kV@BlG6#n?gv7lo2XK$NG28)!W4zfyS=X?#R?o zUmLp4n#YRN{^_%KcPB>~?+tBjNnSVz)S!-Q2-il%;5=NnCt<~1!_3@Vivh0pSRb~B zw0Lx7vcB)p0vSp=r?3*h_hWwnthMx=29I(Kk0)!vf-=P=Eu_HB-Tgyc8UZLs!0kJu zf?q7Vmzm7mz432CgGsk{76^eI5=Km0A;ry0}j_v;C4fe z^zN7ifivSm`7S8vnX<&))7*?Z(QWrjLkInHAKi)XRIas49VC#(bJKI|Sk#dqoYV9O zBH*P5mmzR?a=HYW!e4_Not*ob&@^Z)I0Fg<9*HL0%GRi7{F$skTc&W@uI^#OV=C|- z^#dql$?M54g9~vZ^hFHP*6U-&taq@SM@&bO;*vn*&B_Fc{N>~u_K1iv>()$ifaX6E zC(8QD-7xuo0hBxX2s+y4Gi-k9PF`cFx9T{DOH;PDC&7ENjmh^8q-T4Hd;1CidUIv9LF*X<24lqwh>P9lYVVw#FAYBbW0*A&>MV8jT#BO z@9Aw=53JUzPmGN?q(WhIW>hz_(=@`eSqsgeZL ziGk_+OkTzcwk;zsU7THnL{HB)QJ+E&{bK>@$SKg8*AO%n zoYo+!_Rxd`tj(I68U2zAZD3gT-K-zK`f<`^p9`U`w52bo4k}7%*cbL`it`)PE7rzK z^bm6|&G4TcX*D3~|4p+^dz-*W7#Gc*IETft_r6t}+Ym?i!)n>m%t8>g(3x)fUAXwZ z|3`U2UdNdWpj3?zBj#r#>#$|`lZq2?n>G)xLcF`Xcqp!K`yqk?-D#{LUlCIIl{REd zHs04|r_o!9ITodQzKe~UKhdZo_2(1TYkM1dJ-)XMN??S=4j(0Q1B@pyPb=X{^*Ktb zTvDm-&m@q=mX1VE?BIyFKOtqmq#9f#`C)zR&DP2-f6OsdO6q_e8q^U<@*D_U?|YN& zKMM2nGpnjTS5!Pn78mViW4#_eQ?kdJC;wMpboBkw9_TIK|IiX~-=^i@hy)q(Lwr2{ zH#1JK&m$AAXra%RO(58y11=DUb&sIF0R+{dw^HY^L&9ow%4W(5;d`1=V4I&+mq%7R z7|p$Iwef|CGo{J#*UY0YkyfF-ndA_%C?Qeo)A2nDz7Jxhy>rncBK4(K+8PjwKBTI} zI!DiapoB1WM8eU4zGo`?NHJ7%*r0tCb;|Q+YlB1yBJCY1y0M* zFqc##Kk%}ib}$Ok&oj~Xf%QfV$$B_(CX#6juS8v6O!G}gxUd?;x3O?p&QhZ`P@InJ z+QQb&=2mu=HaPPkT@TbL&1mzbiuzk9!YxUs>Q)u{x6bgbVmg*0DJw7_FMl*X)_lWO zRi8IRlKChy@L8KNM2ufRP(xE6|32{NW_}GcN}6PY8Kff=ydbDHBgIimV1otG@X8LA zqD?E40EHs?b=$9@QY4ru`^NfuW`4f>GB`scO8p--K|4GyDX?wOS7PmZi-E~iAX43g zGj}P4VQgCuXmwRv^d`)+7Bx2d^vJ!u7nvq*5Z<@Sc|Q%Kd0qeNLZjyK^sKg{M! zPhY~5<^03Easp$5?PLDbh3y@Gr1;5fWy8EV=JL`%KQw;u3zIG=O`j2s|G?5!EX>5-yG$#bp0_KyuGQ`K$k?pOLj`*$@KrL()tAJ^j(5$!%kvfCZXqVk9wKq*9>D z74`Rgun@DePK|@5)RwoK)>9R1Zy!S;#v5Ho=rRdWV-9hk_-R?;B&~|66ot+OL77+M zdp>0G=ae)!7Wsy+VfuVeOs%qZciCa>TlUIv^zI!PmrmL+e+7;~c>1qC;4D~I3S3lO zAp^ZC9z-8V8jtE{Q13A)4YaS5byan$@4&ipgDk(&u?45U{g z|8O6Yz>TuX*nzNOs@x1U0I4195Oe&|(msHKUj8ps-2Mh&!uURRW)4VXA+L6$({B}W zVTwnaH)_)zuT0C5cg)-~#0*)ezN0`gm+@MTN9G5<_!q}QZ8yCug zm`r?+&V^II4>=fRhx?h`l;VyaLkV5%y{ekwS{R{lu!55h3)2=hK8zO_OlB8pV$asSNLf=Ak4zp zTJ3AhASoNp9z(ya(J?|@;#`svg=3MnCZjPNoN65FkNA!>k6sE`v2oM*Fm02jc6T0b zTNL-b>`uQFYxEX94%)k~Ny|TGExdDXC<;$@L+I_C@@WvsNM95FHNbZ)()q&}vF557 zy_I%%;U=XeG(M@1+O(0pGgH+zlqS!n1#9bl+rkl5!UIxC2)V|fiWJ&-y404lq$Cbi zX;25DoawR@=EafJK^ck_`Zm(=GQOc79;J-vX`sCcUTH z<&LWdj|kJl42J7HfpEX8xOJVd0{D_+ndgBin2^7ho4qIXh>ni_y}Bv`ilhK;)aJgR zTU3T!?_bBXv1BxondkW2mDVd$vx#9zq`XgO^joGzkyDwHvOAWoH4 z={=bD1%5MIe;fxmvK5?52zit)W`a^Zjh&>GN?zgvFB02`l%J4Urs+5 zp7$rI`gN|~Vce;yEjBlRaq zJ&)mM1A6Oo1_-1T6%eB{NO49ZR!I}pnS-C3N!#9AU*MQ-?lJMol@SKo)+&5M&GhLZ z!3X-g+l+ML=_NFJP`68y#u(;fR|(Vvsb|BA*HdS|iW}s0Oy8QkVUGRy%r`W{;w89c zDXH&OWzP~J#+@*?z_$1rOGIW z`ZuGM*^}eaOg*nxlWw*oTWbab5nomTRO~-pnb|mfuj)ym%>XR@;yA+jJ7;5{st3tl znx{k?i`nt!^wv|y+z2L@1kHrXK>oKyfP5t};vo!A#bhS7;##h;sJ-Xw|D+QOiML0m zuV9@2a>a^k4eK|DoAWH;$e!n*)5(789qHI^pSmA1VR%-C8z)x_e`acmAKkAqWEg=P zC!6zEyD$Pd5567R^F)D3?&U0$ryOp%9^*!(DkWy$ao{pt#@`#u=Fg7|ghWL5kR}O_ zot>SPiwhiBs0^Ypel4o~8cTBqxT5022A!Y%FDlBw zR)YR}U7Cg!m|AEm_Ve-TPoP&OUbBd@Tb&Telir|y3gr1Y| z4*j`H@n=>XXv8e;u+Hu82sn)kA!nYv2rosXSzZu%VPjw+XzgvJB&O9ZBQ*(In9+n{P%rkDZO*V0YKq=%?A! z!7Ufln9yeZ?b{rTI9xQ(^IS151RnacMX!CVaUEX4^r?0tskQ8*^Ozd*u|9Rmy&-Iu zerbZv1o@Uk$V>BOy1R?SFY3Z3m@~a8?1dbMDvTi8%SM8FL83a21HIH(V_ZrgK|g57 z_#WV6M!b6(?()O-Hh#2b;^XT*f72iEvF`8F=;A_kalLCLDwawd0vL?wxoAp`1>;* z0XWL}54+3qE;UH7a;lb$|8*ADYXSQ|{;9VfgfE!hC&}aE0>R|ubDHN%yP#ol$j;5p z!p|T7Z)02V?@)-)kEW4{y$URv#IzIRU#@>#FW$O(^QJTqtb~^0&m_nWYYQG0^tt(H zriG5rhnQ9dVW&%otL(R<71t)1&3lUJ3>t=t93Z7z-4S4jk@8X5NirN&q28stuvkUE z&%H}QfY%|jzGp_FkUaB#v|ZYAGh<|Sb1g=yL~Po}EooMQ%y>77ZGA#!)RKQ1)gi3(AfNj@#zbL2iA%H0 zh`i}q_ zv7)spT76x965FoTRYC9l6nP_fw(*=9dz=c1HWOK$KIUcf53~L*&zt=P4Wi(Sjo{zR zYmT{FoXr6^phZ(q^PJMIfR399$6&%6z7;^csO8NSyXW&jW#Xq&{|aw!uZ@S>BF?2k zS%(?_l+c)aL`hf8!EHCrBcz8UMtw|&D2WR`$`?dZ$|&*i@x}UePo{f8gh68% z31tZ_3eq_e+1ulhm8ZD1zGgT}-HUB2e2+U+_V&mUjDs-I5(9E(cOVp=D(Db%s@WM2 z#CUyAZ&WRla|gPg&<#+KUO(Wp-GXuLMR9B=9mV;a4$`*L5MkE97TY=wA1uX(i~|Z@y)}P22n0Fvt1=gB9J@l3DS!C{mF1o09Xh zZ7Dk&*}ctOi31%}AM#f&9Jg}~zouW=$RDg2If-ANeEsq^mDm3bqi?q?zH`LEx7S}TmY*+ZLqU_ zxNC0L^#c1TPMnMF<3XL~pKX1}tgNJ34&r{mGX;rMla?kuXrK^%~MB5oV z?^?V1PNP$auBqKhAg}11{jDEW81Alv3K|A$t3jn@&BkK&-@k4=k3y_<~^cs`T6UrWo)Z91C{{=L1-_ z#WSYPtn|eNF?dOg`A9b$t4DUoe%o1pis0>9-aoNBZ4RURh`%wWvg6x~ILlGCs;siy}td}Zz%zJCkhm@KSTtk(zjt@lFGqmZ>J zAS9(ec*7fvJ2D1loEiU`+;>YwA*W-U)#<1s7@8o8qy>AK*k%tc>&b!9jDx^9K-N<($*H6QN`2!w}r zVC`-jZf=dCWsvF$3Vt;*>rxZe0;fOKRLDE`4Z4wbh3@~curkC zDffCk*{p+E>e#UAetmvFE7_U2HuuYsdPS9?)Boe!fS_arlSGhA@{S}tMl0F>%;fN= z*hm=t7Q~{1jz+ya_AY2GWoxSe(0*NF$>YNcy$sAZ=zc`)iOZFK`zupfN}R4&rhk!x z-UHCz(VUsTYp)1w1K|Zoc>pQ7;T*et8jMSy0`^%koZq z0$AFq1GK;`QI~b}2m6>gqlmrPP3VyLXa#VvA{y*r_JR_YAA`PHmJ#Bw6}L~si2}=8 z-#T)SPB>t)CSG)dyZ$kG?h+lz-zyQ4uqAl#ijRLmpzc(a4M9ms3Gc4KZ=lCnX#=#5*`@#XoVV-DTi><22_2GN z502*FrX5ay@9qg&v{AX$)P4n18M#4gNyzjJ{006)+=Tx3@q~ z)IPq(u|f5zoa$<$HWgR(eKmFPa6bOcuE06+lWZg8AftdG2e#{eGb3nItJd+&>=E~J zEbKyqhLbO-RNiqRq%0E-VN!z__4sOzd3GYWMvqW45f`2 zrq$U)p;50#YfTHS$0z<>ue7K+2v>0YHsPegyPTJPI`;j`+b%To6D|{l^7MhHx!3`F z^Z9+|T`jHgZmzX%(*7IsBDNtdP-uMY&>piaY&Cnf<~ku84E9cf>WG>-s}LWvXTd1W zJpwJjgW!%GGT7D@xH%}Tr8q0DFD&;hJ1I(K`2*vf$2LYi$-eu@4Bmr8Z`>ghQ2I_MhwPtRW#GwofQgNO1_Xkz}%rGWTm1=3ZZN5#A8vT|bEO zLr(WCQz?fVI1ljOvKksS-%n#umm&}ws7>bqcf#5Oz>I8>`{Jm^_c zKkEKr8&!#%22%EdN|awOYPJzQ{WMPL1V+Q$KtCM4JH{Vz=i%a9M91$`2{P>G{41v> zZd9MKm&p#uDC1(f2MqBI+w_zjT2snk-#DRKX*H&$<>e4v&V-aGSXfxTXLfcrDFp?5 zd;4{N^PaJ&a!%GK8Q8^lh-K4viGAB0h)H=(_Uv_K{YtLfOh9nW5iLJS$ukBx->=F6G)T0*S z)wFD{qThvw+4fIQv&WqLgz4(q24^iO;`qI58*=!*NTM!&sm*?lOnUR=l8c)<7FE^i zKmrm1Hbn_CAtabdNCzkGTKzckr zw)!;lhh@+y8!66GSe@P$L|*!W-Z-;SYH>B*;`r>uMi2q-W5|zHkGK>)Kg7>qa_K>D zr}vNpm?lEVUU)@<9=zx%1P)`Uq7Dv|$Fr}caBrYe&8sY|!66|)NPK>cK}dqYd&@MP zy0Kw{iH*HHTJU^Uyts_G09h?u&4iYpR-}PxwhexQvl8Mc9n>9`Kdh{xVq$BHzOu4{ z85SPK%AMF7JTNejf)k3^3D3cY&}Fqw1~}5|53g}49H(;spO#aVK1hxW{(H;p=*B*dmGX zv67ZO<~!kbJps^}>IcE+;`@jE;T-{_@70fl@WV5+n;!OZ=xeA#U*uhB|3?e3scARj zaJ`PmX#aiJK`5B#vMCQg%gFxXn=`>9B;(4dA8(Vw3L_@Ag6HgYe2(^2fwA?V2Y5vI zBcilG7Z6J=8`}NvZN)ppr z3|&LzCw9O)Z#>6SX5-9LDPwwi{(Pbvb|y~dp*K&K6Oty6%)oPp4sm~U2WQ9)jla0P z!@|cS;t<)Mt9Xv^h3f7>JjK1a6smyX`k7Fo%us57wp*rKc&Gn|G#T7haFSM=%$y7s zGeeeb1rcs+babm}IS(-deWAvG!vN<3iMffWeh@X$%7+(>v~Hy-TwcB0WoE}5i`Yod zLbblXN*vDRDyyTEIBup+7SWMy%_l%lien?DI5lPSkcT!lfDECCgAzNtq&hw| zG`vv#>$*mPHz4AGi=;Ui;v3nT=|;Uv#V3Y+{&r_ zz$G^W{yBz1DqNlnT+=c$l+?Rw$|noeG6NfPd39A6ERNF&CtB9fXkI!af?1b1G zIxFb!0@)FasRP7!PC%6Bw`^*bKIV89i2VSBTXwtd8liy0sn=5Rbf3a9n+hI+i?zcK z-KTFccy3Gh-krF)(mc&NA%(i?)Hz&e2M+7`iEIh;AQ-cKerwpn1(S?fpLoPcu_ptI zC%;b};fid8=&ehREh|g02FzK*lQvh}v?PHVT6j_(Ha+gUT7v&s#>ISR8+}_CH;>@D7tS5%`gqrjt z{A{314j`3OlZ(B4h*w~oht+}^5FQo*U-yW^PxXt8_9Mvc_m}8;5pfrjW;=g~K^Wsl zc8!mRryZL1*Yzj$5E^MJD=XLcfShSBF^!1e-WszMd3kw*T3erW!oBy0+T{-Be|uZh z=6z@@P4>eY+{_p=W~VPCS{q0U>RoL+KNlKE6UjRffOAH{1`phQw9H(q(&GV z9E6*e8~gdCBl6&leFotd;V41viy~29>`9t{#?ex-D?6LLCLC zw3boFgj|2CAP$HA8k&E%8owMUon^X;?)R>5y_P)4h?e(KoBkXb9Yg_SSb*?Qsit8B z^ODeP)!G&BB~z9&=y4UFJc9Du|=BrwPbYO z@vTkCMbmV!L}zdwK%vl7#Dj5n#l+r@pHX49hMV$=TX?4(|9FAkYGk{oP%O!oN?C3& ztO3mr@g#de5nlyrV*j~o1PWcHpU0o@Lef-c6TC(Lgiws|045O<#!gv#ZC@C|1>^af zyh~rSmf{a*FC?+OziKD-X|C(DBfY`b2tM!>1vu(e>@%$)P=xkAy+tnMKsfbk0*7fi zHq3#&glcJmQ*gk;w--Fm;}H`pIT5nhdPCs=uRDMG=!3uCtv}f<$!+^N3%Rlkw8{o# z@#oKT-Nx~a}If^2UgIYQ>Cwq>z+%|(-*Ratj@u< zB0CwZ1^DS`QMA5<1+*=3)5iMO9VCX?k^z?(!@Wu9O)z32oIY+yT%0%$5o{5Xz{wu0 zy+aHS<0Jl`azvhB>VR9l4sl-<{CJDF@AqTQ9uo)0P7DR_BXdm+4lnhd{9AH*l$pBEjrhM6B|$>JKDI~q5P~T^EVE2Dp=cl5Y4X7Q`dSM z6z?M;!om@t7VR4tIDB(Pt?es1o22+mnb9SkKSvX{LrB$p?snxD8B!_@62hpUJ~VB^ zg%E^U}o8j*Ktt@-60_@mswWWAS-;ZqkKD~F4 zS@ACmlbxi^tbTa1q!w0cr0Ff5b3%;rAlgDd&wynAkCP(-Q+pI`D_ae%tS0OmX8v1o zsp|i5e5bc^_H}z@2@!%#M;-)m+mkqqk>^_>htF|8s(m=A+kc(qD(sRzQ(M8qEgnL% ztl{a1sXHs|%fLAvXU%{2C;bn%PMaG-spi?!ws0P7G7c7JTKYmJ@2O)9Ex+TU&+?3c zG46gt89heEzEpE^F`x|AW+lA&gYJhY3#;R~)RwK2gF&H;wf~I=GRQ5fly?s>19}y{ z_YVUf2UWtVVVV~|b359o^sQ4n@1@m#bNv||GKx4<%kQ65f(#Z^X*KvnzQ`2QGMs&4 zT+r)Z3(P%?_Z7X)?Xalg{BAj$z&+MYg8EQ$>v8%P$$|G%hqJ5sN4j^7n-5F@WO*rx znVFX@w*@h`bsFKu8!~k4-D747G|F^5F4Ee+PbDtM_cgKY@1qMI9-d4Py`WGFCY_v@ z1%GX@1>uLLXOrRNj(bTLE&Xu&@iCvQtn3fp^Y5sdIEysx{*t^Y7FKH~YX?ai5XO&J zc_;*U@sam8VCp}P`djE|jS-v5RzkJ9|0x9^A|iU)4yn~zrw5L{E(EHU9q@~v{;aQ- zDnlAzw+zj7D`r=|4$!S`gXm{A?eD{w%?R4U%YcdDy(z*Nr<=z|MPL;9#KW2RXO6D+ z=0&W!(ED8m;O5V?s!4C`mlGBa+tzhNKFTA3qYT9})V4Ij!cIF@4q7%`ZN*UH!%b`c zt=3AgK-mw6!@*xdbI39VyLR9Rs`4!RRp)$tpL|v)U>mnsu_@Ftn1>mRlF*!*CZtNW zMKohX&(RB3Lyx%|4A{ zkEiJ&-Fv>IsQenI-tAjoJR_){5`}Q8Fdmj1-Xj#g)Zj2{miigt5;^sbe=v7hRaN^N zI6Lc=C#gC&sp^^Z7gkRdO#Dqn9wmM}0($Z&tXWZIXv)vp4V?)N$uNiX4Q`BI3w_tL z>|msK5@|gVY28JXcuYWpaAofF)xfq`jlxr~1=huS(^( zN71&yL)-->78b}&O-+9-EbKp&$qV&+K;45DP`P3hfXEYH8yt*GDdZ>#%8M|*qr+Zq zxNWtqm~1xyX-R}ECh@;vXHQMAaZ;%}16yKE!txJ0mLZMThrOwKVKX9l=)t&=yt}!> z8n#8-er7M3q+SM;a}o*M+oR|8K^K2|PCbYfl|+W46FfNh?^mn&_UOWgl$7)rKoIoo3^=0uk}shxAd!{1AoQIl7ADW^bnfq$fuN6P zV+kN#P*9MN?3jN@m6en-})f@Y1j+1 zhXEHev*a7rA9voYCDvNpqW51pHFn6Us5&MmNiD6cAP~sc6Cv$V5cS;<1l`{nh+p_U zQgl!Gb-}BKu;+>Exu<49?Q^OZu%Xg2au^l_0K0`8Yz+T;_eGWnVi3z+1Kd$4%46P# z<@R_y!&G{*rKEo5$4ifgg35v;eof&;Cpvf|2MtPg3jdSz)WbguUur7~r9<`7s3RM~ zLY0VaoO?^1!TaDUe^s)7;d8(9Re#x(yysgG)_#C)?_q7nBa|Reviw_} z!ZX5y1;!P`Ra7#WpyjFLIjQ`3aoHLcrbvs63BEHcn+V=;y@^0-S8T7i!m>cLFnt+P z0j<(`oQRQ@mIf}{tx*de|fa>p}fM6Pe9`vYt=^WboRmx z&toz?3EJJu%Thg9%*3o0*6}B5v1N_pFgeJlv57Y!9ko0T^)XwyTR#jvsE$sKe%RN? zq`C=y#KlLydn|7UqB7ME6?iKR>IFj%5cdebEvAR{uTl<-*Hg9u%Q4MHc=P0(spm75 zGpM;L)LD^2;fS$a*(a<-9Qfhpuc_zR5C#A~1@F-I;BSQ&6&jvz`Q{CcxZ5USZeCtB zwH&`&K0L9V+k}swT||#${NTli-qP4xU`}D|GS#o+4Z4I47mmCd4SmD}&GGSe;Qx(( z?_JggY{XPm*seU!(F5{|Qz2b$e-3*%r91<3^cIX+TaHI&=`Le!n}`F1AVGOnf* zZt8vFgk(~c<)#*E6!V^6lD*YIPC3l_i2&V~M@4t$P@+urV+@{aE*5}R`!M@jBz8iX z?7O|^EOlptsLN3Ut_dt7J7xOD2YUpF2ge5K3L^{8MQ984tEq47r}lCeP)4(576KE^ zlHUOya@naDFc5*Qw9_*)b$~VrLqO0eHS8EG(y68n3JVL92kZ|Da4l^LoUN~2Ywd$e zd4j()8lq_fJyPbwX*T?FTFs$j(jG5S=OAy-vfNl3ZiHspQ+I%@HeGdf#P={r3os#CDl=2?U^r#gng&Kvo)hHd|MZIPf?eAKteOxIA<4k zyy{D*$>tae{tiuiZRUi|Hv7GysjlRF_wLV#VGPEBud13YTCnuG_;3lRA6azvG0bIQ z@zmE3f`L_`!1O*(9#cq@TH0|eZ$YNqfa31SB@??92M5Rc&d%6&>i|VQz|3ni%F!T5>a%xtR^c>fA&~Dj&wkjlr7uLn^kbu0;bL$! zJz9lYJ-|YqpX@S)_#B-J?o)8XXuK3k*ExmPjl=c8HxE8#w~)xfDOKabsh>X2?>;5fLI1!S&9UhC`+!wOYRMz z7Z4`TJNCm@Hy}W*Qvz)wM9Dot@&U~HQpQK;&H&Iz^z1Zx2dV$S_Jo84(sn#N3o;N4 zfBnKmSOjOzgMEW^!aX+N$bMB)r~%RlmP!y6w}0~ZBbGLRiHPWRj(Zmqt7^1r-ygkM zJIJjTjQ@RMpJcyy=Isw-1h>JmM9`f@v)Xmj$)gvV!D}MKZBl z<>pI~ME4}d=Rf~fJ4WpP2aZ8=(Ep*!LD_Hnir=2*wlw@M!bssZV*3>9^`b=bEkXK- zL|&^FfEG63npf}aTtFI0DnngKYOxY&I^q1vy7&QRpEd^x?tvm-(XD8Xm@G`IgnsA| zIBSh(2%_=HQz$obDe43>(CaOa!dTEhEsAgI_e%?_A`FKbSHD_1y0~X~trz~MsKUi# z>)CNP^YqmHn{{6KR(oy3w>OY~2~&gQ_0AOXB7GI{Y(3R!Zj^ z_-Z7mPY_ut?@8)c6O+Hf3dYx*;I0qFOk)cNPrAhXF&*GU+8IHokHs#rY6Y@d=}r25 z_V%EFV>dod#mF|Y*tYB~b^0T)nb4LW%d~3%2X7GEZSO4t*a2V%Pe}gSL7ngYTdRIe z^ z-&{sxW4B>0j`t}KoiWj~lN=o#{nrJN9w559x?0~uQT9ed?rrz`M=pFD-|Tx%5(f*5 z?T|<~+GgmCU3}iD7Vinx($fw=s8(c64Hh>S*U~{3&4d?aPtbv*@LRPwIulNDPdeJa zNyfQ`D?#z=I*IYQQVwxY7edsVW=aWKVz&jBnT&RaSw9KPPltO_{-ehXKC_2t9W=F{ z3hw#YPx4>0TOS$k9h4;imY+6Re#bLfvz7Y;+06^veT>fnAUOlH>ETgpIS5`E6q*d! zTa(JEDiAH@`MJ2bUd4jKzD{vo{M!0Z<4a^l5W>X-`(56W|ME&_tQ`*#o`ywgQc?@Z z5S+vq0KHuMNz^*xYiN_x(4Zpd*Sm&0to2Z?EWO@BAV>V^P5d5z>yW}m=YKHEcCX=m zCy!f$38T0)d(9dL!MOVe@VA9lwbCYqp*3CJ;w6t5e_XU@S6DTQtY_;wXn?EDCpfmA z$(Mfq1U=Jrh#NSa3X?3rldiFYYw(tqfcq+nt?fUE25iNwy&%|%FRCoHI0PE~MeRHA z*w>NE%MN7z_=Glr*r>S0Hrj;+gXUC)55S&_QVX#3pLZpfn$7dYPF=q28#n4uUWq+0 zU5PEX*4H|&bJye;a;Uk1!VKykbB6r(myPm^f6fZ}6naSudvZob8TZeOuy{69F8-STQ*ngVADW0}PG=SMuBseOxU)wwPMLzMGEdMox{5y42D4X;tKoI-63p+C&VSX#o zkfeUg;`tt5Bl;}OB0YXOKgrpXlaJO&Dk>_Eic1+zTGUqd)HqiJn=25d6-$>ti)^8j z4iWJzvsk|3wKsaB&}J9DXzPLL5}N&Enks0|kx)=XCdd84QWvnz2p^Pl+#6-fxnP~D zEuMQPO-Qh_>ZGz_HRGpWcRG>p-3omDKeE08s;ce#`qCYjEJBy0a29h5b0Eq z4(SF-1q3dFNP~1Y2uMhG2`G)EA=mXa*C3G7@kpANsuO=+BCE{#H;vXVxn>Ff)pqM0l_og5&=L}V3uIG7HSs& zm;hjN?kBI9SWl&jn$NC%gn)R~kQ*uk;_X9;ouMfn#m%{(;R>YB1t`=-j>w%+Hu^7j zayGoEH-n0;hcojAgUxTE!>Z8csT*Ll9}+sVYvFl{3q5w4O&R5PaCPn4O3;Y+Yq{KU zL>ez*Z@UB<8@=KYOuy9Th@7!(Dbe{> zeENQ{Lf>G2Y1Kr2&3^v{b>wW^gYuF<3iYY6;#cNaIH|9TCmRCW{lYZYbl-f8&E-Ft zDJuA>LC2Rqo8u=*(I0%>Lix-{6w+i_-mS&!9g_V)jg#xaf@nm1edPm1Ldy8OxGy}6{ zyDKv?)#LQ?67F`|=zCOPdZP^4frWP+^#zg#we+4FagD80#?YK^q!`%qVkiXs%86np zCqv6N9NSc64W zI$lc{_~}`hDA^Me=LGT}5z;q(wzg~`h@GpD1+}Aq6(HoQO=|{(AXGy@H9%ulI|>Q* zGw#lA_%UvzVyCH@MnImZ&7BBRBl6@*KuDazgG1zTehuzGGCH0HTSu$K`-lQeBR#Ky z;BV>Ux@#f1VHD(p!{fpBw-5)ca%Ct&z+IAj8Y|PA{Z>9p4kqpGhmp`e8*X*y?Sv`M zJYl$tE0=&|{clV7Ol;BI!OPRF+CcB~ud6rjWo=G9efURx4xC2C=U?*59;xdj#0akh z{T0`%4671w@)ZFB{7S_M8l+<9e$L$%J)C*EjQAb(L=6=2UQS zT$_1S1uw0#iPFze3L%($X0+hL9fz!12z0e|A>0Z zbS!1t8ioHtR0Ao0ai<1;G*=k3q%48HCD`QE>3>SL=3rf3IPcMZhj4JIS)P%$E{1X_ z7#&Lkzhhp4qBVZhRQDI|LRKX2iz!A;+i(rN{o0zEZks|?IDknfCnr##o6o7crQfId z+Y6ws&fhZ21!N&0_Cb8r>Tlyk>=bBW6<2$@*xNt(vT7&C*ud^ZTBKC})VYF{a}hqo zm_)t;G5BC-Mo%0E;35HaAH|sAX`8yBwQzFvLR}y)kQ2XC0F|*e!t3>0cRxGquQX$~ zGO?_KlUa73;FiSOH+M#j2E>FjN0Tf~4Q?wC@4Q)}(*LvAC!;?d-LieTrg*$xk~X=# z{lZS)_R;+EC~AXg|Jh}o?cJu305{wQU4p5%SQVzkTa9`IpBj<45T$eCCJNXt^Xe$H zRU@!@>5hr_#pr1Rcxm&kLSXN5R66lH1p0*f(odouwo}L~MPC1LN z;oc*f4 z&tVLQ3nIa6lTHXN%4`f`Uk(+O;1ST|bjs=>zg~RTf4U^{aVLWOwb!h{Y!8y}H`v%JZ$uEsV*=KWexNe)b<}iWSsxKcdge-yYyNki{@H z6IOhY5~sX)OBq?q+auYi#7>O0A-@(Eyc^OPQhycEt~twstW8BN0(;m%s9YSL~Jw<;;4aiblMMhEQT^C%%i`*rb4(|+S@Qef@ zS-?7r9KMj4|Y?YH^JwG&(*gp% z@xfp4i?Wg!ZZi=Yhy+PGN$=l(cVYNW1ZYbSEOJ>Y5{qy6p%W8zP_Xcb?7mJe@J(!` zi$GKgKZp37jP#7%q8=wYsv^^nA;9m^{hKK;K(8*AIg)qg8Wy5w%ubrby&5-Tb1px* zKP-PbSTwm9yi~fy&%MN--Y+hoxboJ9W7e$!Zh^}9IVOB6R(>(i-b9R9c~09yuPQQP z16zx!L=zW4JkcBhn#N-R+ z&cEPv818sT?Y*Z-_FA8L+&VlG(D9CPVj?k%`wU)~j(^n9{9Hw|t-sTYDrC=#)KS}} z0L$ujC8}hVSwCp8t%O>~Dif?DhYOv=QA>%jjhwZfDAX=Rzv_=` zF4l7;L_jlxMS=mnDL5%7kdG=m6{K}2!zr-R2!deqy<#ntem#5FH0 zuZ)Tc_ds|D(+rbt3)4i!qThF!lxXF25FB2grIyCfNgJMhqCKEc!ZRlH>(ZB|A(92} zL*UJ#)(mGMwnhmHAkHRw2a~ z|71m)$2Wq&D91SF5Rr)}esjs%SEwT@iVJABYN7IYLm=54WL0BTnh2VH70){xVJP#C z^Z(J(-X$mdeS2|**4?Tl8<-h#)hvOI7V*Pw{)nhCac{$VM$2P%#}(*}kWl5ux#3t% z0Vh`D1CZk4!YjX^0F37w0K`8ht{Lspp%F=+ztl3=(L=UB*t!fRQP0zXTp@qyKO{_* zX9;3oIX6!xH8}$d3%NPDxx4!s@-Df7m-Wqq)#fznOWm*VyxI4~fvW+lyLDTx6BF=X zUCyd?q+|pNexfmVkUS6FOwf{;1e6t69Eey_bL$h908603X3m^91*H4@BJ$zvR?@Ug-~zW^j^efYh%KhkO${Q zNs5`b`Pp5M?j5%F4`BeHK0XmPzTYM{!YD!206HOHbV-fof6Q-%u^~LythZq>&H@rT z|Ab8K2(OXx-#9;_yk6g#tIMwXDFOs(ux|I-Au4TiukkcqG;<(B|66E=?_b?n;_ z3pAc3Gp`jhUJ(({nU+%>nLXcn-3kJF(;1@bDibanU_UScflPU6NWJo4z5v@>(_L2W zE*%H&GM;+j178X^ka~)|4)S)-!M2nz3L;{)=xc9ev$gQcA>K_a5rSurjQ49FhWymn zgDCRNf9FUv+5hr>~cl6?zjgZ4zz9A3P^nt3XM{uHIOpk4iIZnwD8=R4Dh zH3UZsk`o=qa0Xkf%K1T8d#%^+jQA|r|061l+(d8s_%S}76gWUY10EiO0Eg>9X$)Kn z*4HfJG&1P1T}sENrL;aueDBE}i$GA`;)a0J7KsU;qHiukl*5`$UX2gUeE5MJbiQ^@8r*a<;Mmdl3%$@kZz{)Q3b0d?#WKg6ITDi z!a^b?IZG@|BwZ5jMFwu}=a)&*8JdPKq5a{ks{Evj#@vnrK3le8wP!MQ8P!bZuvnD1b>&S~9)sq3~stGlA zW5eQn==h+`yQvj)~Lqur~r7b$x7hHmWD*gUbv&QI|q_zU|- zukpqL*2krHx21A~Ar0#FYf!;9pMh|>-3~IO;ZybhYKRQ?{AK9@igppFg-j7oA02j{ z%gL2hdmisBv_dhm6TstPG5)QvKLpt!^i_O3W|?lTXFRKCfUb$&VL( z12G0()nc7Lm9l1|KKUqFrue&ZMj_{}-fXexbyX)`sqn66*9~~Q+KRV;E~TZUiVh$i zX#T_Da2u~ojcY#?{B!qJy?zN=Tq+6I-VSu&KW*9Hf7QH>@yzeIaq;qA@~unlg`-z< zt=@v?4}u9tDB?lu{z-#Pn^$9+3S$g%m1$C0lS@_ju)_WnJ@Y^)>f-B69U+9lx5_jA z6QKC1SvfesB_t$36V~*Fnr3@@O<0v}L*zu(MEDmEYH-|MTu$rQtbNS{FBa{c|r0$C132`f>E|Ax}u&&m>kB`2Wa#VK-<-38m8g7OT=M0eNP z8hcG`t!d?USxFV`L2-6IMKrns85y-vZ*7T-m44d1AE;*GykBmR^<#g*#6BxQi~t2R zvk3Bdc6TUWCFD4bD`WSS^1+_^k3X7W#Pre~h=0P5l$94tI%%gIPK)oA8UoFy_3fEe zs?_K?g`Ge>9zFfX!yEufTr1(9(%>;Pen#x%LevDS*DlQOevpF#GKvh(>{Cw+Ai)-6 z0C%Oi_WumiYu!?leU!_EU|nnid)evf&5RuIwSnA9ndnf>*3UuW;*^4?82RNUlZ^DwlbwG~7_gCf;UeNylk^qA9+Ugl+LuVU1xg)e|RmJ0!wjn7JkSwa_ zP4(JeEQ$H-=M@auhMei^Icvb8(7|N{3>VJ`7-_Zr^xDG9Kfwa$LkyVjY(?U zq`P%FTEkGQ^N@im0#RK}85R}>S{6bI{#BH#Yo0FZm)0Fx#P1CiCk9v!n%|cq9}Uw{O@gnqx#@%@9wh*ZiV4Yz%2)B(?Q+LMuQRer!)7w@NPrcfS{uPWBE03=s{ zHyDdV7pJJh`j_f9&VpZ|M#kMGBLmt#FfXdT`--`=vS*{YOGx`RwFnEUpB<(%%i+bx zObbi^=&=jL9IC6U4~&mv0)kDwYn`{)qKdV zq}gu9^QigNawvZ*ST_|jPwsQExLsLQ75w1??J@?#_i>vAVcT`Po)%*y-%?4 z?uXOCnp(kwn+WX1|Ky7ISH!~vKpZt53fz`ouN+T7QNou>xuCzOy=+`+jsPN$irlX4 zQ0?yB8G-o^ zybw@UM`+HFCvE;jbS{CW#NC^OPtL0$SorlhzlFq`#ar?_I9|sGUS|RqTF$l!y`?to zIy`iVk#~L4yLBIYWE5q%(QIz1>P&VQw=!S~z=tWFuu5Ta1M)%>ly>iFO&i1@)VMwK zYJ}XQ|J!;5vBLi5A2~bj9&lQ;O9fzuOol|4e@8r|P@Uv7$ z?k|nqs1t9_^C#d_OmR2NUUaruSy^dnYa=%$CB-#sCRxTbQ`Iok^2N*3zq@b?sepi+ z)jg0H?%qWaAs~)f+5eK9l{v3rCcr*It3u)c4*1P4EVPtR&%%cu#3@6~0rk zd_s5*fYl(i`_g{K2%Nc$4o6TJP2-2rwcIV;6Eb>4M*68ymkaFUsuo)!23Py^j|mhk zAjKZ(6DfzQ*x+2b;vnVX)fgSq1*X|sv*(qH(L2dbjUg-tk1avd7amhVK^*(N;sPIR z#%bHxqNu0{H5UUuzo1xLFL^`G2Ov&f89@Ii82FG+VMNqO!N;fmK`T(v0AMd8aA*^0 z)vYI3b&y=@#bk_BcwjmeTJVa$3o&ynOi*$Se>8Q0u?KYyv=jM&79nnQO-&ri+{5mT8%*zu4Xh@V3@eGOhDIWLl%5g{7Y3GB<@UKpyuZABJaccpvn2{nh@9K2DlbSC&~6OU*VvCg zA;EF~)@n54_jO)@evg^RiosH9&lZ?c>OLP=Q5J>9l@(rK<&1iF%w9q={L zr}%>DGUe6IliDd9oU?AO`biJ4*+y1CPGUg(CdCeb=yA@ie;qat?Iv7sE*LJzZzqED zRTp@6RF)nf!Twp(0!0j%8v$XTp0if>Hj#*HTrS_JNKLH8PTomy!s41ixGuHa0evM}#YY zTxgw_mv;?BCNqVM@cME3mt1G|O0VcL(4zlb(HpfFxp!w)US3uG?%R9nsvB481tmzi zAb5~`>CE6No0?i$GIn-FkZ}bLAEf=ybmDtU)l9rd%-eiR?DYMG6-5zs5Gvc!;a`B} z$B*Zq?=t}bhV2hxct3|CI;b5+K~5e`i-9tZ@Bi(EfKTrwT_uB&PX=#{_K&$1d7xbe zmZBKW>!YUJfT3hfAk%+IqOSW5E01>_wT^DD)f(wuR2Exu?fX^CO?wKDg781d3h|ydg{tG(;xltuK<|@J>=qLrHHP1M zdwaXK-18V(?F@W)a;maoX!#Q=oW-?OE+SESTNPg0znqCNP^KA_J_>y{q0$h zfhwW<59eAwaq;}CK&+K=lKMcDCi`WWQ>-?<(I-vloKr5?bz4e8BBC{j04(N=2F5+O z$~#t)#+9(JO6z+azba&PZVKF)eG3jDe(Ii-v0i*B>{$9cKjd|;bgpi$~_w;25@-mumdiFlwCb@Nu2_oNZGSzk)?QNxi0wAxfo zjomZT&aJnWNnkzU_d1)_`(<1!ct z6u(fqzGNnW`yb)qAMZQ%Z4i4z7 z`KN%Af^#Z?zn}f?gm-_)Aw;KE);vX{_9)G+v{m*gb?f+iQTo)bKPCk6#tFTmY^iMz zQ&5F}2+R@LenkL10&sa55)~+WYX2LqY~BCYwz2kIsu3&@<*NC}Ee?*1)PHzkHwsv; z9bY|Ko~%O;D_D!LJ8lxS0Omd$@CJ#o551ix zE)1sydBy+s@hiz*td~Jyb_Xau!M9aSzLEhnCxFgj3H{3zw4ltA(K27l#SdL5O z!o-1WAL}g#5>gkyxrdH{0r^*Xu`{V=D$eh{VUH~{RiXp>hL17`HwifK) z5d0e(TSk|Ndx3}>$!&hv^Al8C0A`^uYE$`@1DK{-=^|*Ly&ue<)Wyj16J@>8X7#Kn zJ~f2UL9r_SrB#W>>OIsLnkad>a-a_V?dZXV#~6##5~L`*+RMuAUyj%AHL>S{{bTyy zRqK#}llNqi{ZV=8ElHTnIZLa`E85VW2iOy-VMR!AL`Cr^%or8py_r1k~cl^oo` zZ>Uuf2o)2;g;EOXyYjLLwS6gbbaf%qz29c+R+z=pE(U+}rU)2p@mDkVdzj@+o*tFT z$@!_F^Y4U%9zr3V?f58zwmsrpE?;Am#e>HAuc39}1z~#kyWuu+FKlOiVb>)(EiGzg z<;538dWKLPAZs}~Is)8;Ds|@GQk{##QQT6zjd{C;kbU-aUA3f@w!+FG*<8Rs^yuO} zc;Dv5>l+);F`u;r#Dmcq1_n`JA8F`-Aix#yw1vlas*W6J3g~RcN9pg_hn|xNvVZ-f zJ2vE5m7R^Q{7Hb#iU`y?_~1b24(~eUnI&}m=~k@AO-q_{B#EqUtL{o zZet@FUxAKjZoBPG85d+m*u-SPp zH*mp7g9A(O!C5T0;Gxn#%C`H>V(i}C3<|WF`Pt!d>fw>^kuq$;tzSo>q3eJKwm={E zy`FuD7U(fHof$<$#y0p_11MnG8GYbC#l(_RgF?&)db+ygUGNCRkDvY_GFVi+TRe`< z(b2_6UrYMhG-`5!5Q$+Lq3g za&jn$h6Y+--7q}@_x%bLb?a~@!gW%-RhZ60w8x8V_SvlB*AhK$afc z@bCjX7z!>D@xf0pY+has6Q)n7e!GZwb$1)D8c~rzMt7qY|2W!Kg3Ax~g=;O?`MlP2 z^baUx+uglW*~v6d@W@cy?{FRAksf)}-?R1|t^CFZf7iF{X!QHX*B6O0a&fP~W~$&A zN5NVkP9O~p4#I!G2AbY41?hSGxf?ln!&DU(1NIr`vYgKnvo?;EKM|Lgm*;%`3^s&N zns9(ZIN03W&?U*7u7$e^Jm;spys%1=Y?<~==ggcOOwhW|rfGasW>laVR<3FFQ=5ic zQ(QeVfGOZoOF%ZViR3mK7t16(>;RQk<>^!8#2!;; zHaWS6BNG!LzkfRl3Jbs211+xZg6lzto`R%Y>f|yw427J!!|7*Lmoxmsvou9lJaFX{ z7T#A=BNYRU3vj7u;u6Gu22+yHa+vi?4~1%=ER5n<5_MVxhRcfzFwJwQv-#u4k0df$ zd=}mRjCV9KuP**$Ej@M3r7i6`E$cvh3DfecP#B(_?F%CbF;7$ZCz`-u&u%yd2e+Jf zUt9*|ooi5cFx~R9IA!`!Aue&#X?SELBRw4kj>rZR_MhAO1#&7B%d@k#&TJ^m2{7L1 z26{thBxYnFx9~Y{XnyHQ7aX3P3~gzV{nB$YRNLMCG~MId$-*3Qx0;@&FKOWBLd|tR zJz`{0sVZ#OcPV*fjWbbx%(2YzDuct+3BHK~HaiUm-AZS$HxvD*tSo3#Fz5ve8oJdG z2!ILq%i740-gak>&~XZHlzJz6IRmMn^VcgxMMc64aAARql`}9Xgou}<1||S)>2T+N z!rfCHe6R5MlUrf3&RidEvC!+h_>|8rw&C!aYxb6~jBIwkFqqp42LGLO&%k>FOYh(7 zffCi&hn*6j<5?Lv?fm87#k5hqi4VtQW=00m$jHdwFRPJ)HrsR75ceuDvWTNP{m#xj zz}Xtf(5#rg4hd8+xKAXH7q_%^Im0rfA8OfvcjG?a>|7!N=Ggr#xNX%lb@D;O1+X68 z_4jk|J{c53`udc?;oO-eC4(DJgM-oK9z4JRdk#;4QuV#>>*Uv}vDbE8bMP6fYI5(= zi?9BcSV?kzmvDNKEDI*Dm)ywtg^DR9vuY)MqDJQG^M4b zDBn;LZ$wqyLnxQV01me+&yKvyrUQMI8Bzl0Ht zTUIh~TgJu3fz2%5K~MR#ys|PA90IUl#4u_0Z}L;ozO61s7Ue?c%hZ-OMfXKK&|u2T zMpmsEsNa@WRw`<0?f4KL1oONJWIia>fy_q;LvJ8JI=W6YDkoswVOL)tNU;0>e97wT zf0!^ORKa#xh^V#Nb-7K8%wSp`u&zCAQ0x+0ilx)8j!G!6r3e1WI2y2KqU-BdzN<_E z4Js%tpo$^N_?{()e5!xkieGCqwYRoc)$2@o>myb?rI4UtIs)+qJOp&{gDiqR?T%`Wm;giIA{72$p#M)4OoFY`pJ-}!^|d}EEVL>?!4FT!yz9)x zJ=PQB8y+`8%B{H(L^l^~hnr!XXm8{} z*P_?XY<&#aGRC@^nQ)ag*LwXQD=Ucd@)0nhSRc8}hvZuAKKJBj?)h5Zy!ccrl;&Lx zx1YM^k^j4LqTUYc)5fw_xaC2~t()gJ!BNPx6Z})fHd!@9tCRf!bY8^lICi^>?Ny7R98dlo_~Ebx zBL&3`WRUCR1b6-kmhsgCXD;AeHd+xV7q!krIEz*{Ad6b#9Z)(aa8 zJNQYG%9a8&MJ+wyagYH1 zN!Iay#Sc1^a+%C$YMfX(I7|TkM4zU(jjkL;ocV*bwW2?+-#+(T^%X-sPm1%M)SQBX zdygLBr6_-zScZ5$T!jjnr@A@H%}bq8bjPy6!EZUGr0Bq%gFI@H4HRBiS63*dp27em zll=>lNf@kTswSWZgemSzTuNz22KvZfrKHyx9M3zUnfaxZQr`unBs@>|x%R+dbJqXP z$()lDH)!Wd2&CnlFJC}=R(5=K2((#mcT0ILg=K^I=HG2RHZb6`wq~iSrdEQ&2i+>1 z4q8d_8F6m4&YQ9h4kb{)X0=_ztnM9N z_~x^<^>sd{HC2$$5uQ!Fw{dw~44R&MmKse7m*7b`o?(J~Ma-@kKJ-h@#)b=E;H%fv z+8Rd-geb?CFRx%m~_FR|6*F_aTQh^DDe#SM2Gao zjhF^`_VYnOy%Fv7#flI5p230dgM+@^-3m~KiTf(Y{NX?{taZN?cgi_5HK%0EFm_yU zCxGc8P}f140nr3y#mUa=K|}>U#jgH-k$*!0mtZIzEC*FlRrSx#X8xj>A=89oH?0?@ z`23-QRamW6iDr~?b7A{kU$7AL$JY*S6*;-PGGIp*P|`pq>Dy|RD|@U}X?p|g6bm3H zBCfbOu(LkOq(*Y4*rswk;@QThbQQ|!wEDHRwI@%W_`H8l1vZ!X(gOwzT(JP0T4dDM z-^jcl!4HxE$O8XX3-~(*-Lb_5M^Ob+i!Q@m&D&(^p!uZnv9Nur-PxKbSvD}NGHes1 zk+(&)wbV>ZOkfevi^R7H%-tbX-@Q!-#;w+@G;_IyJ~K>e(B#ks2lxianDFHBEIA!G z#j;bS+!1pv!GUkOgTYo&S0^hy-Fef5e0P5P#rn5#dS~3{A#t}_m+hxF8gH9#FfKE4 zmU8lcy1AA}sy@9{D`B3mV$mj%;Lgw|p(;f}j?Rrs<$m82eLH9SR(Xec&Xe8fBl?u| zRKxMn2;1Ju{!VSvO`oxNYyf=!mpqu$wSyT4U1+~Rom5uF7bAGqy-8NP8*+@AHcx!F zn1Z*`YS;WWRpv72SC0hRNFEQ|dOu$7LP&Yr@m6c=Icqdp)lGYuf$`UiVu3+y%TPp* z&5A5i2L_pxIV|0eOGqdM+Ue%YlXXdtIIp;c)gCF%OG6iz=x({}g+Dae_$Dr*c%Pr( z^^Z6@xvDNK5NR1FO{ELY-@vtY(e!V~~x z8O;rTRo(1Fdg6Bgub}IU7q){mM99AN$L-5F?hUtYOU6ua$a`j0)j0StxL8B}6P)z2 zSNuYgP}6XHC5X;!qQ8ZDjhb0CK^q*v3DSl1|K!|37?h@iSswxn^?Pq`aC+L>nJq35 zs9+#w2PY>j0Y88X2?+rzgauMBNdm?Pi45J508&k(aoWOvU`s?aBkw)sW)dZ&vUvy( zdUG}05Bhn9UIh06tw5BOkt{DSZ%Eb=Od4!O^`InTM0kGm@FyQ8SITAej7VH^Fq&^k zFL@pRxm$WCe;}Qh%-jC!HS8oB-k@m-Efld$rUI3%B(vSTqYE`?)!(AdG z(wHo48(JG;Ru!`UE1sqM`@jI4Y1nRi?RdbOYDV$AYGv>kr(-tzBJwIQWCE)9e3&By<3h;)MU3 zWAaSghbRzWu!w%d1yj4wVOR4Z@7CijO(0 z?Eg+?6->W!s}edd55@*8PyqjdhYW~eOMnS2EZD$)><|Gsy!{`*b@OGYGxpZO4E68E z!R?Z1zedeVV_CHo2pd9dz{;uwoL2HzrbHkCq@5K3YF#*$P&X6_i=)%i;Uy-WpxkBg z6^(^WPwRsFf+#IKOCGSNt4i|dm$r3)Q`(j`ukSCGF+ z;?vBfni;kkay&0HZ!{705S?`#QWNJY5d1~cb8}_&^iux@E}_?zL=GUSKY#vQmp2B4 zKcFFh#f{)cmxawrs}djS3{KpMk}A0bL+@&D1uGoDP%!8!g1P8x$?S-d$IF3ahi5%q z1qb92442&LN2m4CjQsp?faF8XvxSKj>l6(GMv6DV!QRK!o2${$Ah0E=sHmQ(s5D>sdV zBRtLvV5Xdnao1)>4cRuKSh1e>-gYx*neF9dU?cnH?gTva~> z`m4x!+qLQZ1;h#-rJkN1AS*^LNvwGO>)N;*zi6gKRHyfxN;m_NnXdQ}u0K9GkYFBK zQwTm6@cL;u{3>>_nd6&#KHmw0!XU^NDIN zL2u_PPq*$gDKu>S?*!OxHvnjh;rg=RgJN4X$UHf~`F_{;HIOe^6MZU0w1>QBALm8F{3|v(fYW7OCd|B9qgz8Wo4d7eMURz-=dt$D z!uby`Q7th_77LaPRi1WGS1G%sMQV1-e+x;fO16cqg}FTQ6!@v@73_t{+%+$z$*GaR zvM;*atxNNXE@-KIN#(PKu~aqP@8`6tIpb{32ra=(<>Kn=%l; zM1E;s<|T+fLeLJ#t`Mt8BcOAu7EMGE?R;X*?BnErPd;^~!D*u&~`}p2F&emI=M1fz8y6y{~?PNYG%TOy@ zBwi-2E2@h!UE{Zg>o62f(P7XWmmDsom)ICnU*w&Mm~X(&VZB2uMuCzjKo>BKqd`OR zoiP@fRiEvkJQU#7OPh5+3goZvwa-V{M?tvdOFjWd5y+o=6SF;mCRF5T)cq{|5a0Q+>7no zIRGeuqU-|Dkyu+~mDMk+Dw@dHvRK~7$w62rs3hI8&u^mW{cIWQ9?N;Qwo`W^uAa+* zi*@2Jl~9QA5;N{Mc^8iR9T%r&9{}i#Oby z`z>KvYv0p79iQX(4fHh;l+!H&QVYHU6LW*8cBkN&Y@2<1k@SER%vP3zFDGC|C($KE zy*p7N=|bM%ISTS`b1u1or+_l6I@cDv77L!1c{6D@>Eq*;=HK(_B_rLIKvT}tH;EL+ z5FUTi;cUz@t1|a6CsM6DH)qbw)J!Dm7iJ zA$zdsiveEV-JEeIUCpBW$8N_~qxo9nb*=)n1ly)Hk~fOn^$Dm>!wz_=2Hi~Bs@YX( z3T{OFne<5cnCdV7j(n&@Y%nCKfMChFXVaXl#K7Y# z_tE){PK(Zax;-caTVG~_s0&0|aO`@^H@+d`aAWHFp z9NIGRq=BXAV5R4aA{TRpMutYZQf8GQHdS+uQnux@mg5y&wV0nQJ~8Pokyda(GHLV_ z{vbg!cnVP=d-jf=UA_WpY1n1S8HRVs8JYo`LA$PoFJ}|_YkT{Hdk6PYETo8GKqa*g z+a^oNPo3Vb{-wCAsN|#+FtpyrH_690HZXSk@a0a*iEhifzp*dcm-30EqHmovHu(3u z;C$caxSW>^61*3-6B;|6Wcq&j4($eS$E24SOn3#HavmX#6Bjr1ye0=ZAhJrGyv9E9 zfP31wo@r~IqnJhR{7X~+4#p)N!tD~YM#4F)HKfH^6`jryUA?ln~pqM>Yp0Kwkb*zbIA%iCx!pf`?fRF)68VFChJFmH%n@Uz)w6R{aQse-Q z*X7H2uTJ;-4a{>)&I9gm6Ur<+K)u&1(OI)UpTvVGW4EwEi z*)P>Z0ZGN#z!?ZAtcnzqQEnpICZfruquQH}EsxzbIf`HA81pv2l9%!Ix~UY%Dx{rqs#pDMywD?Cx02QA>p zSdA5j??Ey#zj%rzWmgk>e{R*Pj$tz(@WZH<_95qQKL*-*r(ePzyQa0s-{#-<0e& zR4O+qH`z@Qx#%s0M8DGsWP`qtHn&rc;0q`m@8PqVo+hllfTlMG^G zf7}w^@}%L(Q{5C3*bj4hCH&o!=Cpo=a6Dj+dh;H%Jm8Cj!9w zARLTmv|YvvhSahDcg`q&I}!#rzHT^Z3Z~eIQQPI&b=Irb?6yWJzcThl4GLP1ck3%q z&Q_Fc{Ond(aqk!0X9u4jYS{sb(C?BKa>u2na$?eYda0hJa7q1_n#< zQAmzotNUrpA>;HyE#r#o>DTj}(4+X^%fKf$?r{~*)6PkV-VJnTM=Qo-r9%^k9o)e0%x^f%a zQ}|e{@(9Ft5#{d`0*%q}>F6nlAn_GX&b6l1SueynYULjUj@A|z3Z={Fsdd}Dea_2h zJmKl>TDsHA*WTe2aGj$SRe%Wff7kf~i3=-W;_;|*;LuW={cZ6KH#gcT%{Q$QU_zVK z^{1;Qbcnx>6lO7o)i-jFjJOGXIF!T_+u)-UQPKOkwwXP*gt-}<tv&V#3g}zo)>?TX+NV%uM;;TD+ zjz8pqdjTHo_{|_dk>>cKfe{@gJo}-~&%wM7acC}M_;+PU8w?Sh+e|!5S zU@6~=AIUD_9pG`QB^t+mAb@32Z$(A-}OCH6%NgONeXRZOsQj zo4FH!n+N6(=B+oaR|msLW+1Z6$qpf>CQ+PcddW)`HF9BO&wb(^?zQO3hWN zz+0G)##f3awl8(&CqpHp=&M{s?P~^#k7fpySYHss&El>~Oj5T1qp24qlmwczO;4TJ zDp+;qeKD%}$>ZIaR;>0Ml;>$QjRKI-j{a=5PAM3tVqg9^CFaJ}HK%yp8sV*T5g{@x z0^KfGlQ{8o8l$e}JF#dz2tY92d|3f@-dTIYD==93JBJlLS+TwZl89_HiDc{J~O z;0kM!yA9VkDZ06pCuwGqZL!?u8&Fsqo@CBdDKh2jl zSp>cu_~W~`TefUbmsdx9;IIw+AerTvcuRAkcDp{yNOkEAK7gB7Ep&J}NJSph2aanLrM=$M!7w9w3AE!xn*ulhNlf_8XwUN(z$ivjh#iKDJ7@eddi zY#@ybq6P@Wgm@oc_|i>z(;V=ztjCtL)!zE?X9HqlC7jI|-57usVTf%|e2Tgoq3)N4 z<~4e%wa9wTs=M7N+2`$K3@D)=tpElM2yBL2m|d06jeYyyDt&Uc;kU_?Ktg_!_WwR z2@1>PWB;LbxrE-9kV9hd(Y}pR^Z?*ERn^cy86S$cZa4+v$Gm&T_Ko|Exg7?LJ*?qm zjRR7ELUkTK#DX;~^B+Z##(e-Xa!g`kP*LN>BLle=WwBQm-0ap(GnF~1IoK>#_D!eI-r zYM16cWHK!>qZm^arAh@U0efcKqdD83-0rmp&eMkV^tnRH!^&-6X3hLM1kLM_vVpR& zBQVv!6Y%?9qZOE-F3qRN_rI#hEakrfC(_dC+C?4l z7aSmQ*uUE>^*VaAyjQ8M6|qFqc`u(F7C9K%9NWOMTfA(<`IOu!wUj&86&bnQS9^M~ zwtZmpjCuXh@t1>sl>z}E1~APs$(XoH;akNCX`1U$R1^YPNPN{3-<6-o{EX{>Yk1rW zk((*}B+T9Oh^m8Ji)>-6!XOhz@4Qb!UJ5hHm9F*H?ayUbdoOS| zaX8UFYqL9;J`I2b5MF|;(FCv~ovlu_iaZ8dDL6=6+?5=xtYZP(XTulI>OMD69^3)1 zVHn+#Pc1F<<;JT2%=X)5&Ur^>f; z-wTxK?RvVU<>T~S(lu-Vib5upkjSDcsa(42eq`xc${o) zb>{!I^%YQ6ZQs{dF-Z{xBn?mm1S#oIL?jdtq`M@fyHQj`N)aTak?!tLgeypQhe%#R zN$GE$i~9V1{HG2l4ghZ7i?X^7ucDLm;)Slplmzl zcDa9hcfyOPw?C^E=iTuwxBWgHG+?1y_5?ArVLn75M50Z&Ng^L9qq*_P=Uk-nqOx?!Vi-#l6$BHJGz>Sivg)qxi^|T#Hqoebk+Nb05Z#@an)OAfDs?$b9b>#e7i^GME1yo=YZImn^E+Hv< z=tf6seDkEFYor~ry5$$t=TEa_$oJ59HCr$kpYaciWaEAOGEP`VIlAVU z0gmQ+1(humX65koxJ-|5-SCBiEAy*>MyB|t?#%D0W_L~CZ=ZAQTrq4jTTEXwkq&yB zqq$1^Ztkb)em23!af{E~JS|r03USYFw7&rR9wT156qekKp>7Q+Eot;Po0Y3UV&#AP zA*TBRe`S_}lI|0?n_V!+luq$#dQM{%Za+K!@-v~Q(Zbv6wy%yv3%fn&%TWsi#e?h= zgYV|M?$f7znSFC^_Ir{Eu+|(BUn=rFOg3)OQ~mL{mbB^mj1!e&3X^5o?&{0wNU#yB zcMHrFb8cJ=v7A!xp9A)T4uQ_}qw_f2+ZH$cgiV~zROjp-K0WRt{G%V0^zj zE;x$zEkVd(JL>&JaQYc^c`oM{g#8+;jXUS9o6twTG6XES6@Xgi4QBCN=0)n5#O7P2 zngMs{SEKMR&N_KGyt*H0B77DisLlqhv;&!PdWKkd0`pYX_UY3^Dm0&t`=@GbXHN$)S8gS#VBg7t;v*mims0Mi*`zeR6?ei?~oN4^@lI&xOtd;i? zVeKzmyQ3{dG1NcRx87}$PW4agq&`Z$a96O6u!pFAa__5GJsllOp2o9eW*MmT^tn4kz|@OX@A}-KQ1~cY8%fn^QZx6 z{7;-O_T6JDGvs<=l}QssNKt(&91amTGK;-j85k9s+8!P8cgu36`N^?CIA8PR-0}ME ztBxRdqFkWNZ7RpVH2G!ZXXoMMac9h$mD`An65!p;G3s&MNn1WSH8tP=kp#rk$z5E! z#hHUuF*adD#6WmL=zVGVeu2!_=4Ss2C?wiX^&pZ772oNuY0JP#8pwW!ru$ky+M;de zLrZC2vA?=L%tnp;1d$#>>dBB*s-ahxJNo4`bQ1s$00{;i^F!vVqc6oP1HTEjx)?2* z-+5bpa>;3=Hep2EDq;VQ`l%8W{C^B@=x<&Kj581I3z2<22DHwQNhO!j;}29m&@+=r z$%@jwVzN*ucU-fV!PMEpbW~JCyT}m#-3FI5VJ-a=si*ZjKPEW0joIutKxM%`Xz=3o zbmdel9%+dfu${`r($NATtiil* z>K)BPp^e+^gce%?C`|Xa_-^Swcj$J2u8wM3*x{obh2g~0Ed)(mw)n#UhD-*#(h!elI=+$tfOjyiqY;ieA-he{w3C$5kYwbyQR%gOYaii@75toHy(LD1)Ml4}>!;RCI2=vTe3Wo`WRmN56 zIPQ=L7JEQ{NSry4uApAlE@o0lv_`1irVZ$PXpOuwZh=nAi`*3VcQ1I34;z*ejQT9; z^6d#<+m~ke6`cZ&zNuqR`6tau29XBCgz6G0=Gu=M5>8T!6CR)v^HAO=?u_JWq=RKA{mi+xbnimB>SVJdY@t2w!i~+3B+r-eEj^y$#hx|IJ^5 z(GOyt9=m2V&#;?P((79fCG(41_&=p*7kS%Swenn`_4Jm*?mgIXkUrv=CB;aem2X96U=$L-=tWK{ib zj@|7^F~!$=({dB|w+egLwyUDyFW4}RpeRp=W-vY7?b0X z?PPW_u|072xFA7R2K{Zl6BlTcXi0B88!qMmAx6f7<5M=_L_!&gipTxwt%c&^lA!?) zdQmuafDlf|F9~h7a#Va3NJ%Uv@56?I9MssQ|jm^?^am-y$@fp3+Q zI_2Xqelr$pRqHXWX>lLskB)8vlKLlsa3U^Gr8jv-_2jBGZjv_cmj3N=FCvJB?}P7I zo+MNM)V;lSCzma5Fd{jBL3bN$XMeTQ&WRbwD}RiY3Gp=};%i^tj(XhrD)wvi9yITv z@oL%D7up!Aoc)>1{s^dzxuMUEH`k?{nOKzHYwK2~^ElVQN;0rN1}OO;v+}+GYggJ7 z#_kCZY7dYavDnrLSb%Ss+g>6Guhe^Eo-HKyUKi%JP_IRm)T&B#C%%4t>J(e^HdHLN zeNuB$R^4qAf|G)^%7vQ#tii0ORf~n=Mz)K$Eb4q3ec|JNz#hKbmg}Um zybFVNo6YZB7lO+(;)!z-~rwum1c4mfzivdrA?Pes^fUfR!7^6jjaDKf$m}K2^z^KAm_&( zbI=3XD+4q0ZF%{(SfNqVaatjxJroer%B4DqI@>3B57Xz-F@RoU4Wx?i&g?PP9UF|E zFs2V9(7PUYui)IRIzcUqvud5+h_((No|tq*G>N#Chc8_}47~yT(Av0F8=MTuO7@v; zATf{JR;Rv<3E3){JLY+#-~!R8w~Tj#j?RWK5QwMBc5ZLdElzB}Moh@M($dhdqD7ws z1!eU!Dkxy;Etf^?iZSUHWOK@&w|1UiIxl-s%JQ}QsmqwRY=eDlDs=DO~5M8vpK)*)Meu#v;{Q!8H*^&PKcjo{2V>AZS0#@cm3U$x|44* z6cj0*z6ECfn@#KVuh2;?$C_nS#OJYH0gdx`ma*>V3A>1H3oWzV3J@X9(+-I%kA2s` zUaK6?bkncY8dU>S1DtT`yF&N?H#pWtme3j=2gr~uf+^bbL?^b~k9;~VQ0ucnMRy@r zZT?Qx&fbPjE%9D_22cUDedtEC6*X-i$+x95QD5HmTV)dy9nvY0_axKgWb{9oS+2tN zVnNE_s?hDnpi{sS$pojoXz+;j@{Ot__ z(rj79RrksV8a_TxmT>m+3sf%D)^-*ce-Zf+#k+0K640&8TePtwc={5gSn;B!#f@rH zXuq7?(iG8#Hj;*}(k;8TwvNB5={Pw0vwY-0;3M^05ts9yG?}-j?mh`UkA7iCiYn=w15Glz;mEbm2K{Ec&Hsca_-iRyaBTJ41j@#o zJ3ULta^Yv`FDmiIOP7`+Z*PCyWqS~SPk}i_&BJYJ{<(Dg)~`4g$CqmYQ_s1x%-2!3 zS};qIc=Mb6Mf1b ztk2NQcCKE^_OeR(2~bk+8l_m?iRq&)wTRl_gUl-@cP;SZa**h`Wna0j{+~SUd_Ac4 zqOhtxgPq!=#O>N0Sk)fMwjKw8*&j*xy(M8%l0zbJPts-SFm2?VpG5cYus?|PO4Qqr z2SG8H(D%}RuKx8PRxoQeql~bKNuhOT4gKC7C55Ji>*a|hWr{$2{V~3MyI;@u$#Oov zE3o5ubFOzGoTN0-CL=09^tprkhussx9qwlw2zDDpX$Icx{IDF2B|*7fsq#(7*s$Y& zUnwqrtUuvAx>mwzc{Sq%_1G(KQNA& zU(t2(8YTCg+xU4XR)zBlr!Y<2$Q6kEmc>hphjQp6t1r%G7-#z9VG7g@Qgh>BQL^ z_v&~-tc;K8xzh7cFj5_V=+RT-Y;_8IbkGSLJ*@MhOkl*gNSyCLZznaGf7= zYUaOFmjt))iR4w6H#-u(!r2?Sw1R?y^Q^3`SXubG3id2V?oY-3)GmY__;W}YD}#jt z6$gh1#qIp=>B=wTEulq6yl)-z=D&S>L}BDJ(tl9hqyWGMT?5+$N=-+C?fuS;)|=<7 zzud8HmEgncHs}rP-)p!2J80Aj_zT3yk+Rn0n&WH9G z+7wN6yMc{~l~o*WdHG@%$9G9hU$>e)pwPu8Nm@h6p2IetglvH2v)jAvA9(w$vI*U{ z&#qHKBz#qKwuHfwIIB>@_xLp;LXpBd)j#(y>s$5_36Cg_)&tE9o&;$N#E|39$%bcc z%+wJrDAr4bJqsyA}hUTvDh`)Uw<8;Zrn< zN-xxtuL$6y^4IzuaYwzqlQEqH!)PUjdc4!yHswp}uVYf7;DEA!M`@F_>Os{fAP<1& zF)tZ^g3j58HlCH{SVc;pRM$bCL}`0s`zl7S56WvXD6jkBy0#a72M1>na+ToRpVMJ} znwpMqURL0KfY+9X@%JaVL@_B*FL?(dW7!BO%yUPc@?UeP?=oOff7D{zgF8V@w`aJk zCVe5$$V{$?&g~wm@43c{+_F9#%RgEGV)8dZdWi|3lAubbrsO0QL2;{Cd~)mA)}6DD z@M{@2Jkf3J%;PuwQja+8y%i5w#oaHlHaB5a`-}2P(k=ySeEJn36N0dp(Ypcw*sqJm zJP99=mhMfSIKLY^Vq?z`{^fI26+bjDKQ3if)8;rI(ypKi)Y|kgAm1;Z94#4f7A*2z zkjqZIDP?FZ+F|^p6Q5cd8hu1P!ed%J9&vaYa@kzUtv44wIZl7P?NtI0aUwz`m0;t= zmV;}GYgo{RWttEPooEXB!T{db7RlTul@U`&2oKrxG5_YCM;kA^^9_o|FM7(3kDqPC zRrg_Xsa~SwA+$SGGdMRW*R7nW6n8_GlJoKfD}+G z{^kqhtRKj|;Vh+*1@~SasQrx?kOOu)I&mP57t5@yjLKHINMZf&No!)UIb_3Xp+o{< zE!Ash76Nq>^6iiXC4}2)GM#LEQr_*r{v21QAc2~x>$|tNeBwiLoHnnu&6jBUJt=%W z;o@DYKouHar%YS7A-D|*&IWET2v9N3a7hM8&V=Q*Y}5wAG0e7wMencU%86OH{h6*g zv!|%x%ugLOIy?pUi$K`f)MGe7zDq9MapifW1K;nn{B-3@`mP-?PPpX&&SeY56>fK4 zRK?dj_k~;`=48-?u9a}F$WtzNSjncUi$)bkZ>WD~2Ra*JR8@4wW*Y;C9|Ap znJ?=9o|^xoA%E2|RzVf@LI5u92bOeU2ab`d*w}Ei8k~98ixD$t@wg!4h1|f%&dz>u z>F#aLmoQr`7JHcHG!PVU@DHKs*zqGCgMmSoq2^oRo12LQ{GE>n0{t}xDJ=Y0bLY&!cKEfmGLo8LGiu%4z zpzEbG58hA`m@M)UD5XiA@xUO1PDPN<{l(M_jtG`XAmQxcaDcCBaQ>ko2O?=Wp|9&ks{8{kg1D&%VhxYN zJ+5yrzA-as>TZkPylHWOGbbeH(v_*jYj#g#q~AO z2Ix~3>!}7Rbt_Gj)mc?FiThAR9{N}{PJ{}}Y$nWow6*-n7y7qP>yJFU(01cY$X9F8 z6wJf5?vfq~CN$wd?7b-6io#XmEn=%|Zj~6S-fMFh1wCr?4EnPMT6_8V@==x|4L>F` zC5j?YmS4~!Y+5?QoI`#qbpPQ#<%ZZ*IHZ77?u@-(2{dkL$!YnRX2Kz25XQq#Yu0wp z9YGz(J_tXMRBOb)*7-Vz&*0gX@0{W$TZxSwnMF1ep>?+b=BZ~dlTE)%_qK8+ zW^OTl+w$S<{)eGwi+X8Y#BOd7hvM;shMz4Em^rVkefOMnlGp5Y{Q+sCfgPi_Hv2U# z9TFZN%sMQBs-gqYJ8YwGZCYFgzH@S{v`m*wYFdACzTj+~xEY<Qpkm z+%Wggo>i_6-L0&Mzn$pV_%k>_4NaC|*RO$L6b%27voc;$INU#cEa-8Du27(ZfkP(u zeTnC{E^O}Zi4{{@Q#}}Z#j1>HSj%wgn0VNq-cvB@j^3*%lusU0EVt-(m6G9$R?jhP zcu-vVtIJ3tqHx()XH9i*_}0LDQ3bo{=T{lC%7Zq8c13RM5$o4N{MemL?TSjv#iCL< zR(jIbC<-FcRDqLjzlRR4b$q$!e$*>92B~)= z(Qez$m(JGdij73|N0}54l1a}O8?bJvhdG!y{R$eQxBe3M)q0awL@n#tj-+p8vI=Hx zJAPiw`fFv9+aU=G8X83&sva05ILm-6A+CrMxxrPMKq!4PcSKMOHtj~i4YjDW`qk9} zNd5QFD9`wa@bEXSO5txU?x|#iO%?Rot1VJanJZgR={@duZrjuz*+Lr%8=h|-5FB$n zZ?W*Il*u+JO6zg@W#5ovrV9B6Dc=boJ_P45l1im}le$?SJ9beQ`z^xTwBGtv3;&$}Z7shxCM#**?*rlwIM<;p7g z5m^g$JE~_zbF*%~%gC!fcI}FJ-OA{R+=(WKk|>b_i!_z7|Qo6FhNMEORCZ%{#^u z`z(ZKbDOkWEcZozr2tJeTHNdDovG{^zC3XCy_#cqd*p%?(bwn#irEP*MDDgzK2d>AnCb1GC=5p zP77SgnlESEvmbHj8hTS~FSd@W5n0|R5>e>%W%KnNs!Mo1L)I9naMp8@1#F})G%=z4 z7TxGllf|^W(!?$6(>|Yr2I0qA{0^C#?_CzsT7Fg=?)OGWO;7ZcEZU5O7VmL~SIcFZ z^x8H_7AW_dc0{Nz|72BRoxEpemfvgd@V-uyBs*6te{Q0JZ^LBw=MZi7RneSsRZiHT_;lw&$jwD}k2c&6;pB<+o1vuyB`K zytsRFoe1JWPMFtmqQ>c!)Z*e^TR4h=LVb+|P%Ls%EJ3cjJG`9Wa-$Ysl%mwvsfb%R zC=}zMO^=O}LE+xx{j|#%v;5-O^zdv_{(%=RUw+DtTuY?3p5dQe`tm5-Bi=4__~G)m z57*R+yGDYF-C<*PdrS9KJ8a&sMoyGg6goT_&AeRxBQV0!Lrz7~sNM$pOUx0bhe zea*KMCqkXSY_>fGbKknTb==7yDN&unp}8!EmAiK&lH08W43X8Ksz5t!LY3z`L!+rR zFMLdvsfRaJ8J&y7h;tthSL=r;@r3Rq zP^@J(6_ZBES`5fxj5ME=TEr`*xD)#7F%f9)!%9|z8{ml>pHS!XVW`7P-@!i zw!_z*+PSE{VI^s%n7?(u*&`Z2FbCPYXHb zIaUjsdT|+BB4hZqHj)>6XV+&FUnwhm)Rv_Q6o)&1ea)-e?Gl0{S(Gsa{Ds1WTIKoW zq0CFshA~O3kE$}%IEtfPn{-JY;{AL!anh}F3gd)<2$f#m;gC6pgS$e}okG;&CL5SY z(+Od_IMnyEuW4-rl3t!wv9Cr`2eSThtDIX)?U%_+ zwcOp0+-J2|cpq*-x+-8%sJ6zM>d{VVZK1s8#QpS|nha00a!!w7@vO|F{jR&wq5-0O zy3{H;MRgV3X7D7$7eiWNlMR7k=3^H#XN^5O(cYi1>GaaQ96BpR(uHH%)(>~e% z)t5N`yLo2mLpi20?aZ%>9f2Lf57LLrzU}Sy@8#{h?$>=jqNKU>h$}sY-=k`7f_a@I z;q~d|igV2~#M7TPtN;TL&3ed2DbkqaHjgA7?;x6?+KznMdh(1eOmcqv_U+u#5;yfx zFrJ#z3`7Z!6CYe{yo&Nn3zbal>M1H3Y&?9K?yZEK{k#2wODJW3IJy-=`|PNBcB!Dn zg0R8<+eMk-Z0^aCf*GN~d9$tg`A1yA6dgBQ-hT*9HWZq5%=@4swV;B|FKf4h8Msr5 z4Kh<#FeD9SjdbY_pGbTw({z3s|;voqgj!Qz*pxCMLT%lxFBx~&sT`ATym ztCdou=PQepxLZduydMzFGH)|Wu*y6ZoZ(UK$f$dLm+sw={TIFu!VZ(8G<(w9(gaDz z*QA%v4F{EqxlFCkfZwh?%J)cGN~}(nW&Z$an@6R@z3*qvqWwtalwXX!n{)fcZP=VO z>A7>m0xm0gow^YG9+oQ23b*b)a^v3BppNFvsQ$VWr5WY27QvBO|K7%;XQN|Op66VT zS@_`U`ut$GA?xmjpf{DX)Z(==ez%SI$*DmT3$>q-4&6f`#rB=^_nbM`QiQm-c>xGi zW`&nuUg}*}-!omMHQi&gSg06sa^_jf+0$DWW>L+s$W^ng9U^ePxb|$z+U-g&t(`!b z?z;cF+w{gtj}ZU1ieRL(vIp0;QknT;nOL=AVuWgCU+=b?%~GdKhj2T_CR@vvHfEu7 znj@ySI&trw+WfVk4_8ekZ;I#8o#Sr2R#^O9LmXZa{9~@ADauz!YuFky-0xt@!<7O1 zC+S>Dw^uMRYtZ_zakiFs($;^Q!e4CyujiV|07tpF41G+8$NOE2E$VHDcLH}ZP1Xj6 zOzn1u*2=iuvTrrK7UI|rr}sD(njm5NASPw^_Q)1^UfYwdLzNbbZoc;!HU{0@uB~wG z+HA$hj5v*7Ma$E-s-=iW1~Mde1r2&r*Gd}A#uTnZ+Y3Y~Ww|HHp;H1>#g#(LayK~1 zrdfLSy7t~?2g;k}7Du|qaPL!mWlY!Nb1zM^!TAdJ?}N-OQ3M|xAUM^3llFu*K~Mu- zvDIRmUm$Q4*Egfgo zYW3ng(l)OQUw7~-v%yOaTc6x2U@erX&UH^9M!!6*c%!H6w8ORlqNOp^1jPU zm}ggN&_-;_juiC5Cu8E~k@(gAHsA`E**y%vjVQgCw;Peg2AIpe_sTB1JhxA&u=q-a z`~3UH_E~%uP4*q<=HBkd+?du!D^j1q)63i!w2N|Gh0@#|_RB-Wj5=RM--OALI{bkQUBF4)HF3k#8%NOzk%Bj%nKU z+0$Q?p_6D;Yc*}6=sbye2J6K#n3zAGZyW745=6^ff_4gAw4NgKlCg_f5fWT*RLyRv zH2k;~Fce^LC3n$kp*=;<_TxZ8fVf@pih1Rg?dYQzp~2*(7Otj|HFZ2CgudCbQn$$Zx`dO2WZd`ufeVTE~ z!qGM^o8Iq}{o%u@-uXnx6Uql9-`DioDH6^;Vez%cKZ|nhNhwi^ny(CL_K|Z2oMRMi zyR+LXmpiK*7Au{XhFsP%CRBC@whEItvF`*5#1YJNQN*A^_Etr2Et9{WpV9XE!rbgE zFRxEY*hR(LyNm8eI}X|PQR5Za4Mc4X%}=kE_P5R+#T=#14KV762)?G4JeZ8JjmomI zna(o4WmQ_5KEs}-&DuVWhLL*OS%ebsZ1h3)s0MFZlF(tdmW z0neIj27)V}A$2E7z?Cz_-ivX--sLVIsS-+iKbnH zgX!brI-OSFV5o}2NaZQX{N`>-W#zCfesHQXb5cM+KnU%LU>_Li9i5Lt83eb7EHV{> z=RE3r^xaH&P)P03qgG98549p8wQZGQ6`N$1ubPUDDU?(1xkkHIdRDgXOi}vYr?C4H zw@|t;khL83Wjkd;u5x(S-i;M%*ISvZgQ;2T>8p&}507=6)p{VYV87H;wOS>H7pY+% zT9&6FwHPCRKgQPW!M^%RD_FnS)dW(p>*NYDGOc-mo9_pz+rf6Kqjyc6=08c5hz4A! z9Nl#n%S@r@dR@Hx?EV?ojIgtvlXjsPrts{UU7IDXRkq~*pY)fXjh0a*)`qLlDS{285me196u_t8vqrE*+>y&NTlL6*w~L-@!nd>+RqZq zcj<{r>`UUxJhb8I9=s=~d9zy~dU$cz`TB0`{d}3PgNucg%Z8N)Z(-?nOW1Nx1j-JP zs|n^Wy#l=E95yhpXHK-bZ$2nZYi25$&R+c{Y`u3k#@bC%tHsr+&IT#^#GI6ao(9C) z_bhZp&GN7H45^X1H7UBJ7Y(RMS?^irq6@{%OUWwV0g4$hVcjcyqZysz7P8IgucDXe zS7NeFy&cL-wB)eJy2I0A&{&(!(;@&nHn!)vp1hv^wZ&s853rJh{%Gzzn|XTaJ*|}8 zr&Yn59cisZ%#Q$xs1=)c2T=1f5J8=RGPt}iq$hIDs+4h`WF2+N|4ulwuR&s`anb?~ zO1o|6vrbGlXEA-Y;svG;QgbZrdI4y~LanY>bKtUDg9Fvq!-k~h+uF9LEnVVTj8L0-eE&wPf zHMr*%>@0eHdwhcmjAobUF^LZ+BYO(6Y&4P`%11Mksb#WFM&+ps1Lk@L)Yd`#nSkL_Y$NVUHWkjK<@ZqkU`u%^Invy6ICg)0i#FX^c*Sqx+=BH|2P;)IgHBnY zN?PB0*;};%pQPSMQC~^V0J@-`B1i(Ap;uP0*zvH^o$ji6-5PPP_^PnRzRkVqqqxK; zj?hW$?(V*Li^K^>`pW=C>n5zs`t#~+@lgz~4hkA5OFQLI+8R*PvZKP=THd?wklfuX#n#8nyA3#NI6# zE!DDOsv7$#L9ZmRL5#Vpxvs_Q{?Kw=ez$LP;%H*vx#o;n9@r6+K+{0;tV$IqN9>H( z9{|7L*q$1+!rsX6{lqLW`qIGkP_kQqTSU&~9@{v;c&S2bgLg?S_g6{Z#?nbNiD^qk^wMZ{rWWQ~neSS3>BdZ1 zDW>Z^=3(>2{l^gx6$9bM3=J-a*})bIR)$*(P|xD^;Nj5-n>J@TF1|k7xXmYEET{rc zKCEF=Jh0$Vz0#bTohi#eS3R1oeZ6Gf3erh$c~&pYLc2l#SKBPNEWUX{r^kT+E4(vn zDeUoCRUHNFJ}m}wB^Gp;ZmkH6xrzwe?J1BMuyz2(E#xS+X&=m}?)bo!3f5#?tyjIy zzk%_b5c&B0)7r1}f$EOtLT-#*Y40o$X3p}9_nh?>{Ra#!-qM>k?828ojo7ZyQoi~& zA|_*VfJ5irj9ymYto&AROKVhiw0dAmQLAFYaLOI7DM9xxwzBWJNf}o)7OGVDUvD3G zvt3UZ2p_&0NE&n7?Tgjj{ck&D!xm9~ZzYddn*GkOX>xtJaY2|mzr|mJY&IlP0T5*ip zlB#XPv?_b4$5rX%?l#v9&@N6|qqii7E{N}O%@~_5Jm015+R^^Fx?33BU#qCRWLquo z5w9M#w5Hd_3y6o*oRUE)HhCc&o{fzC-HrE1KfYuke{2vrnbA_^uyQ@00lS}>7 zTn;mXT%$ew`Ac0{^DG(>l?v{I)${J)Zh#Wkc{gTnqP?8!e@cIx7Fe6EVT!quZuiBC zVQJIqi&NjTM>phhiN1_%gD4T)CD8w&K^~?<+r-!3cLl$Z}5J zj@sItU&36np>0>ovyh8g_Ezo7Tl+8}F+5Qr?$9%oI??m zRX0LOiav=|lEw)T5E7cSMhng@EEpVS14ov3lK|A9FqfBtmR5=GG#iwquj;2)8Zc`n`+K`d2?_H<{g!nQq=YoXVb09+{#+=S|7Y0=rSyBxZr(% z<{8-T^UR#~Z@ap43RkpRk~7y8xl$##(%K7>xD4*iI$<`S;ua(W|ztgyp zAz`A&iaL)lWVpAS!tr~1zz|_!zge16r6FemSq53!6h(n56c1(dEWo*?-XuUCex4_z zwnt|&SgkiVyL5_zn#VHs!_jYbk8_JthTS)(jo%M&CiC7imPBVx;Hr(MZG}5CO1-Nn zQlhr^ZYgN(ikz~AGC|JNwp)HKm%Vss;LTv1eYpmWQ?Q~cl7?Q}8EMcPXlKIop6=e> zWMm*}QUVg1Prda%gz7uhp#Oj-(0lnhDVLyNW>HZQAUN3VDR^L<0GuSf;HZo|_}UZ z$c9*hA@yLJ%{x4`B0@FR&}unnha;C9#cFK5ee!V9kt*&iL6;;ErV&Q!mB)LRP0=x zE?Xxt^25icvD8=c40;!UQd7u+BRmTDn14e^~%6~>pDt%0wzBKKPz|s82k6bZK0gkzq8`G9 zsnVL+y+{%*Jy`dnrbrDWx=3KkH^QH{)Ha&9&tkC~W3nfaAED97c1ZhD#jkI^a7`UM zH4f@V6!43iu0m_;>k$Emk;hgIMhxJ5s)8h3jF_YsD-Dbh7hFCL-^m;ON5vK{?vBoy2 z)CUFzq|va!@_630FnM-)(-qgdHfaJS(s0D<=Gy8ibJ>DffAK8*V|<5$Z%iN-*g#B< zo${3ol01X-I`ej5u-v(~%jcTc(i97wkg!WsE|ei*n%CuV2BlmK6M;2gycG1)YLZA! z9D%LQe)8lHM8Ajt1iwD!J6NQDxg>xRTosukPa2u93$kxIj z8O$!1eO+6KupnD2LCKoH{H1{^xAIwXRL<3-hY!IGmub+O!FC0-<>R0$P;<=ZP6FKK z$3cx_z#MfyJuwlWS?u{YcW=WbfUpuG?aym<;PPs)J`_C}{;|oQj`#QWjM1HCjcy@T z@+;KP+tB)9#ojnG9T0;7oSR-;r6laIQ*p-XQ0#}PD})=XtK|0&quzIpjm5eO#X#t} zcd*(1u-Pb7pY(&&V7R3Itp6SOxu>1f<+pI{uEOs;VPa@_M<_;S+_DcInIRQx>gF(f z2+B#BNMYokH*`P%&Fl$ z*3)4BJ#B5Tp^T-IsI9Gi(FrS#>JD7K-l)kK@&GQ&E3Q9=QmFLtISE31m}D0YE>e@! zJ1`*WL@v^ehwW$J9`kYuT5Ah8sBsvS1!$D?^b)WiHg2g5V*!v|Y=A|h$J*z6cpC#9 z_ivV9e&ckg949afi3c7Y)$kuEl!zS?j>ry7EFMflS{|L(Fl9|66-kGyY6685FRL{X^){+VB$$Ptkn~8_&A0OjkPH!!lhrR>EfhN{E058 znliDA#7H2~N4jKirzx2D;}d~sJ>;_ql8A6boOpm}_}5(0PEYD6JX2t-Q{acqxX#8F z2U7qc13aZicx-zJR46fSUfxu=9vE5P?@vF*Lih)*4`Nk$A7KTrTfnBkI6t_VHQ|66 zL?IvfKU=~8c~HTBcGh_D)S+0$|16*KBG$v+!?ze9TMgIDAn#fW>E|q=cOjr22x!o$ zNfUK~*N*l3tjkt9Y>qr0lsgA;6h+U*!Eq_36$$cx-!%lz>t1&wM>UF^Kh^gA`v;gs zcMuBGaFJ(o6kvgY5bzhyh;dRFMDV=}xu4wK(V>e(g!dy|UBMNa+1NdRq~mk@7W7*n zos0DMl{>I@dLN3FhMCd-Z0%aCfZwY(4f-YYH$2ncKqmmEFTf{dsL`F4b91XiKIk-9 zSkfg_&5MJs9b!2uI*_u017SQI1dj*Ul=bS_@^vtkaEZhRaC0apVsz}`3XdKo|F6+O z^WpX8Y%R)j+49HO&41I4f&iEWd9JdbS_zm17ImNz-Ut>RW*>yZDx>I{o0`5%uOPoi z!VbLzyd0E~B2M8E5gl0?``@HZ_nQovsL{kIncZw+!I zZTXr%yTMnYC>hV-h6ez<@kn3)8N98mA#}iDgc8^F>)L=C06*nI2PR&h{TvsJZGhLo zkow=Dmw+@2uT!%Hj*yg!lcIXys*uu<9YnlU;sM-83qC2U8772}n!IxA#ND8+?QMc9 zNTy^YK`1wT*np%;}E=F zurhP~wIQ&5efFz}A0BJ$!cyaN$U38f{xs=Po&?0W&!r*#FH+Gyu%Px)pfZ2TLBL2mz}?phPXqM?zk59_vhCkx^ai$OwcGa1#wV~r;*@LaR5IR@4y;g`9Id!^C_4n zR0-(__Cr(z8S;N5E5#s}k+sK~<1Ao|h&Af7o4{@I@I5`(DE!&) zQGb<8?ldtrW;+NIoRHBZ4gbQ|zUw}>KiM8ZF{nW_KwhgJLMp(G+t~D>e6Y$=e^wdw zO4rp@9qyq<7Po;DK_%dTm;Z~+#!DlWkUn*hkd>=M`qBl^1{!ggMkJno0KN&P3qXDV z*nE)Q4`K}j`aj|3Fm|V4+*3+<`5*#1q{IWLupzK?^RShc7A>TA6l&}&Y}Q3cJ-@@1 z7%{M!0{F2ew=WV)Jb*|DjtgJ%;`T)yB&A(L%-bLqn{~b?0P2GGgsOSSychxwYOMGl z_aeb|XAoGB2d8%vIa&n}TS0kC`DmKhji@}~9=#-G>$9{QI08%piE)yRAw@MOV z1Ha)L9LE2`ljKDz!t}Vf zkFe@}vOgUo!6x`idP|VoIY4SMx=g0F^T}nJwS+HdXTBQ zySnrdP?CZr7cJno!I^K~5L5G7-&WFeN<`M~A?|-2RnL1~$m21SPLM95((bT_e<#gR z?)aN66b=4w<70&QhXfw&b1oZ;58-^Gv$HdTbuv1}#?Bu+9|iJ!3?zVLu(e05^q+X| z`OxP!j9EZogY$3869r@iZdHRDK*byXI}s`4;C=?b>tjYTF8q0^ItyY+Mq$jpA=j;F zLoWYU%KD_HUWJi0$l{6Kla{vZr9vrx9I14n_d%ji92QS#b0CN*^luf0)aG2&hYVPv z?!ON}Wt?2G)Q0#_kRJlnXPRw@rb>V-BN(bZipS~}LQgV(?eHPFf|S_=Haowp zVAFY{?o$i94*^@mpoR{hmRD1I50lY>)0pK!d2#_w*&F^SIu(zlM5I(bzyosxux_0m zcIz(x-MU<4--xk>nU>*~AAJ;vagKuB)fV5b^lRN|z0+ zf5w8VAG&w{J{IbWh(S4+27|)@@@V)!19F58$pL9~u1_2f_-8Ka z<6xx9XJOeW!lmnxWE64GL_+*L1+*P7I|@mjK_|RxgXo~z0OH0F%u4Y?&?e2Osy1Tty2U#BlQ`2;)v~$LxuoR#n zLJ$<{cl?I0h*dr?+tYG1ce)`f9S|z0R~NAx0894?-Vltl0pkAki*N4!xFC*VXq%Zy zDJv^O5cU~4NOK3A1VS(#kU$q3YvEqg108PO{9C)SyupDW3{(2_%`Tj*{%7yyu#$as#GSB~mR~y08OOlh(;DI8< z*fc7VXxY=#<6dujB32nFQvJaqAPFE-iuOuk%qukc}5y1iCmKTxk z0ZXVn6lt(#tMmD-5dq+ssP8)PM)#2_1EE2NK7T&anF>in^xt}_<^|s0n0I(#xLoO= zeD`GJ1f}IcVatvU&;~y6VUoYKRzk>3>%>v&mwhNqr$~E+W%X<^VIeAg&kDy+P4|bJougI*$|t@W}vzQ zgQ5b1dgz0mur5_cTuknEf?QIno*0Z2gt9gLA3|Fn3Lcm`0iF#>)sx`gl6mrvUzWnV zO2i{D&ol2PnEaKu4cCW{h;;vjcm^iAx=)|-GLpXSKBQ27Pzcq8{pUUSNWz^ug>-ds zaBvQ~x(Ap-@elu`TzHobirrMWkN^s^SpC1y7Io>b=V+frYKQlt|3Eu(KxGfFkou-# z`A2|Lf9p`F(59woAZ;>WaoJ7a?7<8XCpz#_R0{b&e%SSU*<=A0#`*yyf(qt+z!Ua& zl8L{FoD@EQ90iWHV#!P{4i1EGA_v6%n`Ko92Al_14kMtt4~4C1w2|6B>Tm6jqSSSE z9ET`E)!&{9aDx^(FhpY`{bSryBY2sK2hT_sZSsFeoGxZ}VE z+dp&|N@$hXJS8 ohk7C+0#*+PLa2L46RV3qtFeDQ+a{bzPhtqkoPbzc}jj*gBTCYENl`nuKz z99A!kB9=sGAm}3W_}*hdpZt_ykbm2(_$@TnouYlZMK(v|OS6%ClKC)wk>>faoE~+x zVAs-yHEM{<%8yO?QP9q@qo-sEAuN?|eRr{*mp`4bsWSy+z3648&GOiJzV>M}{YUge z$am4-uShB=T4eP~%}2^OcHwbj;y`mH|>ocPHcdnM+1chY2Xq0xG{pRFA(G!pZ4YH zij#&ngV@(E!wu2_AE~5dz%f8j744-#K2bvGMmYVc)U2#_uzIKpN($#!`OYTTfJ~rS zZS#KG62UeVlGuP;L8YzxSA`Q|4c(WB7T$Q%0wRAG*vH8qqy zn_0P(Z)F+wHR#k^A8!K4$zQ@=0`1)v!9WCQG(W$Y_z?0W&bc9FbgUiW+!APk-8-%$ z&&$g@$ELl{-=zkTj)8%u9$kpbyry*BbaW{5 z-sRf@ry#EQZX&%2U8lB_M|co6o$wa$AGw>6ceH%Mdo%R>5LD{6ws{OYd*bjKD2dg* z393ZC=|U25EYqIhPSlVmIyp79^VxL+=Tne%UG9x_vQy#kYR!_<+MD0#L^BfHNEGH9 z$+Q!)a6WZ|P;X?<`W?d73mIhFqHcN#qi1Gf$qk1w)tF~~>oXDbofH3bRuug7=(Nn# zo~a`dAQTX#`o%LpmcM7uaYI!F)>nhVCRf4kbNu}LJ~32>Me2=cT*{iF!|sSqg}g;v zLZNz6i;8-|ma;Q0jHUa{d%)}EtexDCWcR(Qj(rj(XyN?+!eMCH^|ZELS`6+C zyv)J}_P&`}n!{p0h!M0*4@V%!$x>pdI6fy?yXY;P3CiCKdAYfD;V55wKG+0up#jc? z*SFW#*YUaF;w%DL=b9RHMOsA!g!f|b(U>`jxP}f73#5V|k7s4hejF{U^%o%t_cN!7 zpm&W}{xehy3sfsyA}Xp%jr=`u7(5Yqhxz5MF`_}B!*Li`9?=;KjgI8h`RnC|{Wl-i zB7@4p!!nQ(pLzc;Q!s zhX!OI6%O=ArmLrYR|PBuy^!SGoDj5J)YGH9IFL68!ZyY>SZI#=@k37js0sv8xJXEg zoB}@@3^nI=i*xC~VaSNf6yv0Qg>XNDluzfjin{^|YZe^PlgKGSVu?Ak(fm)h(g>?A zUjfG*{0e=vcAsdU|3Kr^Tkr9brgxGCx#mkpAn2L&O9_dZD>ZQS_kR2ER$(q5-7vj< zHsLxWch=}#twzBadm*p&_3+INKMNuIo!|!#9$INU{7w=Z-d~szJ;DIWt}5Po$C(To zV}}op6>)HMLhl5=e&OAE62HJFJUKVUe5e-5RJ5Au*RVd^P#IA)NmQk0YGNsWJ>(`p zf*bGt***!JQwoaj3Ak6dAgKMM;xRk-StQ7Poe{l`@Z8940?2S|yQ6Y7Cq(7)jQvSO z!ngMb0%!^3z3G}@L^naKVu95_`tzG6a7Gd17bZO5Chf;Y1A~nd^?^Py;b)`({MQhq zeWJhc=BM}Y<8S}ek#lo%i)Q$UZuoY)C4zDLE#d@XSiK@?|{Pr~ge>hd)J==sD%>5h_?9$(Qa|nWw`dXFVaM8nv_!c2`{{~H0Utc&} z%(p%~y2t!vRp?0UT0vpqFC_L1dH?`w`QxuZIw>nDh14ssf?xxf^#*Y?pSFk72u_?T zaq~fCS*rl>u!~uLku^9!)Bg#)PK*ZG+cF^`k`3NK04b?3q||-|-wc25e~ru3`XpVC zom2}=IC%LIG1|@wFK`&ZG!*NU&r`%w7x5EpDjVKuYDx<0Y=$ocO*J39K9+CM-1Ca` z@Sr^}qxt-aJnx+KzZWc-WUGbYn<>ZMcbuOaNwOUY2}wKd6+b@Qe21`(gnl^z3<=sQSs|dffTtGGSbp8#zL_y z0(HoeJ6f!ph9ji|Ld36c58Gm-C`ATs`wKM{UvhDC$_@Pn9{8AB_uDybPh&GQv}`?B&M#HF5MnrS`1s#O%;VZlYcwik|4 zQu-VjY3JsV6sXcfj}`h=!Yrp-TU(v?e3+#HL_(gI^L2-v3#=?vE`RvZv812aKmf&F zq!WAbY%yZ+T8hpg^j=jBP59{qV~l4oT9 zbIYb-_birh`CDp;jAT+5T(Pq2Ya8JV1kh?~L4i`)#!o&_N5PSWeio8f$%)TBAb{kK zXI91~y4jZP9NQt8AmxL>2rMipG$6bv`0hvvT$>itA(j=NHt!dWW-=bkK8${Y%qYr# z6ci+Tt{nPa`HUwqCx;s(o+q=~XZ2vo1bAx*RE0@iP$Qg0u~X)Qxk`8M-USs44b|Eb zO`s3@DFCac=Ef_0x)C7^SH#o|1s29)y^;Q6AA}X4u~O|u@_InPVO4u(F#;P_drz!BY!g>ppBpoR7c9^&oql}#xZm9fUcZ+M~%Di zumC|_geZb2MjdtEu3&}q^hKzsZMkI2oR+cpGahKDSK5LyCA56c=UYth->-8zz9ZS+k&z!hn3gJowowNILzuQ9IlCpd718;{MPBffDJ22Ao)hkd z1Q1D~?(h!ncy{B{Od?3G1;ClCm0L3=#Us|ELt7TsVu6ZEN(niNO)#h10TO3*Y+0aK zm8?ZRxs-LU#kW)M*z5U)1?*b5xxumQaODhh1+We94hWiwb?Y*`_7UE+#AD+>>Z^(n zUi<)mkyK}VMJ72}%`KD?>T_f`tO_B|th3mehhlmFFUDw^bL||KBVnv8_$M0=sm|p* zl#m9JKR|3F8P3L83y_UI_r85+?ID0zcpsJpq}bg5GQd}OmJA>Ul<pSGE5SLXRE$KQptZb0}UBFC4!|yxBSWD?;)M z^RtRFGJbeQVF8pM36z@gU}%Of<(YHv9;&DT<^ay~4X2XGIsWjnWI|UoBmbG>#!k=s zu#<#Ut^eJ*bj{_h97IuBI-us~@BbNK!+t3u6qu%LqWuK(7LW9QP8`BtZ z`}e>>xA2>a-oaF4YHFIl8Rv%Q3H}X6kyucB_V#u&i><=&mSTAn5zz@`oC@|2cT+-mV=0@aV)}Jc@2OER9-Zp3ONR{i(Lkv3@AaBwKnT+OF}pg3$GK%a0P zuMkAVEf2{R-9QWg*x(=9j0Vb8wehOe2BGKn{QuU%)(BuxQy|2FzINUjfHm=Q#sW8n zy|wi^n|6F@>D&qjcb0H15-#Dr%hadlyFVTB3{ky@>N2}(<}FP9|G{n zoNr-{8&r*?rj)I(LP{_|rHhgok%?UpbE%A4RJ5N>6lWfAWHI_2FN2hEBX*U$>S z+czYyG5}nDetm}B9-p>^#TWice$ZdG2VB6PN_zka#Ghws@Ue3)AG|@QdfwEGS4hYd zmb*i0-lH}UWSI$?cL0TXes4e>zKp17T2yT}TbQ?7$VgkC>Zq}0XsXgJrvh0G>5{lW5j#o69X~O z`;8Cvl~~-AayLzebK+z&T8mivch_F|-v_6~0Z`q$OIfQ?6DE&0=IRB!1v@sY%(k>= zU^wZKQ;7*9tu}vt40K82gN5q_MA|UhIRQ~Hvlm4O>69Kqm)UL`JzS2#$#p|*>hsYe z&d)eK8k_Cr*Gx!B$)=IR=6>fvTPLroltPks#6zN@1o7d+yGhL}OoDaDC*pRtv{*uD zhT{-4VMgO3eCauN7TS7**QPQs;&@%BJH0@neGm`R3Jb6$fQsV+i_tmTp*rmy(bm-3 z-|n%zHEBB7m&m!Fwu?akoiRm#Ul{pv9AK#dUOvr2`sp8-`0 z-lkLi4;MRS0+ys?B&ebT&~p95BVzyq@D{b38!r6VA5ndrP{y-zsDu;&CN1<@1C14r z*H|l>mzo<$-q-q`g4;+)jvBN`@MeCb+)9!O0AKN>i@XC;ofn+c-_(!2m?O~PvTdBP zH=w!*IvKd(1ftkJf42{bkrg>beFt8Tdv zHp1!Q^XO{)Ip*zcX3x$pfSeB*UAp0rE&~Nm?(-jnZ zu}{wWP=)me&(Ax8RYG2WI{UFJaIZNf(wMPC73zu%I0besmSAVe9B1 z0$bDSp!Jz8IJM^C>9j-H4j)M5(p?dauP5j38}#QIq-JI+3n=W-o_w}_dP^2=4EwSP z;rNAn%dvcYPB!=x{Qji;Uq^-I*`aLt+-rCzmLeyr*To!7+#>i7T{`8IAZ~wB4XFz5bxNE|*gkS?I3nA=K>OW<_tZ>F?KudDmKS$7C^ND_dY(8$Rn zgfufPWRUe;z6f66F2=mQuTMiudka?9P;}B?Ier@kuX~quo!{U85Rmuf9JW)3Kq5!* zP!0+=)cEpBizy?ekb$7JgN2*T<#XT(;IkzK+oB#5Ao$=D%CM!R#+sL9|;sbrq zv(SXR*Jv1`GSk)izv6vl_^rzct`=x^C17Z+e|KbvT6X|74aMfuAG!-D@gL$AM8G_w zto_H_t|0%d=p?GMZ%FME5dn-FBLeNTzCLg#0C)S`yDVfA6iy^zVq#%|$`maFP2-kA zjuo2y9*`p@&Ocnx^p3M*{HN!4#rIxbg)w69=PyYu zI@$ziJ1V+6!c|tFLkjXJ!nS!mZDA`JY>Q|QcLd5T)dyt^xEJ? z!#5t;D-|#?_u;)zC|vWdrkfUD(lJ5;(tuMgaJvsd5;oQYwI{-X-ypeE2;A_QkRc1S z{X0ZLXMfuu$U>lpz==b#Re*<_1~zoz72`kQuVL_%g{J_A`4H(tBH`on;ET|R+t3;{ z%T2&vLUl;;+gTCeDmROwiWFg-ZjMT7Z z04ChO>Gs$5iazOGBXnEm*%}B3IVc=pXa$umB5RReoWCAD1-Bl~3+nE&z`unRwa3Z+ zLMA3AI3s{fJpSlj%5PuNlN|0Vf*!Y>`at%CJ8Q~PIBQg2t8v&tD=A#%@@$>#|0)ZJ z_{N7v$rk#wAWIT+Qx&KT5e=8Yx{>GcSZ@x53(N68M!u^Ks);E9K?FQw=+uk6s9uo7 z$DN1q%a#xSjrQ=djr}?{a?q{rHNwWXk2F5Sw9dHDDY!GnJh$BEAXAAZ@seUsp! zE{E&p7m&{I)}X4(FHXYS>MV%e zB$i3L`ndWnZbFNnJFC_~D^?NsP|p{@V#4|Hi4*(%IRZ-wKZwNZj^xHw*kZ{n0H$e( zF_gHqVF%-;VWb}ZG(gqZ{y!F!#D_~DXSNh#g<`RH(Rin3jP19H z4EnEX9l4~oNZ3y)Rt8>~d>bJFMLG-s2F>hJRQ2^Qv@nLkS)i28t`V|`tT;txfJ~`6 zKcQP}_<#D`u{r=({?IE6Hz@9uIR*({)+OEy4bIg=m=I~+pdeEnf392~%&5p0IM_%#QOoE__4mp+f89V4c z8>OE~%Xn}fBzFpL?r20NlO2rz-j@(@ISfH7uSV)9{2tgNcZ&fVRD~~qksM&B%M5SK z{`775b8G;T{>{TThpyN1Z;L$82t34R5&7gDLfDFx1XN!&?ja;r59eC899&EZDOsvyVrx%h;@ z8!|xvU!mUL9)LX8kU0!X*IsF5=>xK)Dgm@HwTC2x#C72OS|(iK(nw2Bozg4^Yw*4C zw^KO-&p-NsfdXwwa8Y;TB|bdQZs1-<^0A%}`8#iz83GYluU zmF_#dXsDzGr=(X47g8YSVIh6^BQiinhv;x6KQ#g=^yOknf7=46sUzioP#TK0yZ1$& z9wTN6lLOD;lJ3Dp74m-<)wKX1zHNa#Hb>vr&9P7yEf>WL7<@%9ut1Eua2b7P{>ATd zc7Mu7M;T=PwV76Wyg~pe2gz+6*0U>c5flD{5BK6Ia6lyul&+1&5<$?7T#1XZ;~#YK zT9=|=yA}!Hn2m;Z{j;`v#w7O%XLRK+IwZ(~CuVr?hbYtGK4n213Z^+cqATzby)#g4 z^3RKd-Bai!tbINWx0Ma4We$9%k*9CF$5 z+IVgQJe^fcGtGoh8VOtFd~S9a3Grj&y(yA@Yv1T9xYE&HzVN9e=351&E|`fH&}gt<)(u z8i+NM1>*qVv*J4|094Bazop-l7e3-y=aOQ3W$+9tkpjlj@U;vuyoftA(O}V7#f-;M zg+GH3knm^!2$n&F6n?S^7aU~GUe{g?1$+J-X$LyuliJtkSA|c>+|?`xLuYgYDd^T1 zE^O=-GZp`?3s}obq^4z{W@q841_W^(JN#)dxyJqvqyMEUZ5`pP&9?~o^uO&nfIU-K za2pB^9s_p(z{m@DwD>dM0xlj@#eb(T!^h{ahue}AAeX-$rL}Am&A8UniyAF{zlg-5 zVd{H@&!3Z0SIIkkJ|e}4Slml0#0fkVU=0KM|8la$TcY5e*7Dh35#_RaGKh$w#e%0i z4l*@c5b;H%rKM8j-aXl%XItu)qazI8b_n{T+ipDKp+T)IO~M6?1aHAN%VKx&Dxc!z zpW0*5`6X(pA`oWry@aDxtJ5T6J$m5c1Beimhlf%(3QuyXfQAA$^l5y##^80;8@TF> z@KV6_c_vs~bJ`*@Vb;0Dh4oDM26|!WNICFoUI0hy*OY%u@=r^sbGxT)l}Qz1AqE+a zKZOTp@UtYywFaciw1==2cZ7woRe!e<;FKiujU=lHwONM|aINd=|AL7TVlf24219IEG(lnyU?T8K zO}*}ypa6em$|nLSIKV%cShx+rYffT_;^UtV4v0$NP>*dH>Om|H_%lm94D)xALacN9 zAy8bNz3W@sl$O-$Cz#zfH2>Puzx79ylRpN2DRLdZ^>8H$> zQJPc!F`S6Vc}HPoOC`cA@~s$h=km8e3IX~09^yE=ii7w#7A5N+_-~#>9QZ; zMc`V8ehRmrtn`gpfy6(!;u%v1Fg{NeUmD7 zO~J_*aMpS5J^NE$zt88WBRJ`QKpBEVEWrw{$X#S{H^i9VwXk!$)7+tyP-h-L$wi9`Ff zT&{Qudt`8no(1?1f1M6+BL3rv#K)wf+Cj@|oA(f9z;nd^@~FtaQ1b|1bw|&F1Y@1G z2h!vS(C(Xm-DdDiiVxr#!nr+ZatWU~ypN4H2dYS6xuipL$UmT14TL!<|4b=8U+Job zf-9l;hF>o5cLxC?4nCfQ@X<@W)Cbt#*G2*re=-{IQ0^bZL^`P2jT#lK?Zsm0o11yJ z3LT}(k|z{nzG-ho_FfSx-FjuH>9m;jq|AI6iVBMXgAR`^ z7j}Avn>=Sv%KVm*;C-X2cvj90B!J$@0}ZheC5&H}H4)4wREK=h?%x0+2K!|vZ_g~b z@UHIcCTSXCaP#Ra%c$I&q?L26T^xB8n^E@zyg4&81oiz_&Fi0u48hZ%*111o^I)|_ zN;{LJa>uNTgT!qeZb>}jRp6T<9r7T7J+6Z!6S;Bb1F?;RzF~ZRUx(XI$Q@=c@vcT}7-1s}qVVq&-HI{a$6XD*7 z`Oo<6ds^cbjVN|C=99yx^~HyZ_N)KJ`N%!u;N@XiZ&HydOW*mfOC0Sq^yA+0>)%=z zpGtCs|1`j!CUEtKD20Ifc_0aSnG`M}`D+|ThCr7AK`%(~b0XW)#Vv~k-mMKsnKJYH z*8!kD?o0?tGjw&Ybr5}oFZSTrza2^RzsYn8#7QR*NSdZmhY>wM;L6HMb9>uZ8U}`F zo2aKhq*_Qou?YOp!$5~B;}LyNghXNm_M@uXrwM`s|4|D%M**`tojwGm-gfRRMS(#C z@L&c$tL+PHe?*K@0de%WAC;E6TicMNS(xro^@9hDMb+Sf7qonG3=VbGWAGOIkPrj~ z|3u9g(6-ajhlV@&5uFyiEdKSw@Sx}41$rvj*`P>*OEwdlMr^YB_g~NcsdAIUgGnGzKz6zRIavN=Bb~)RW zGQ>ARG$Xr%I^>nahOaCPjw&oi94n};Aq`Lo<4~G0hzOo{_Ts3BRSlb`wJS(fGnkxA zon25`@3?aE0PU{CC_LXv6dJ;6+b)%;nSYfxF?DG&lT0vYi7!EG#g}IEM`ANCZz;Kd z^3Tp|?4pj!O0xE5+gHfUwrfTe`$O1Bq7D){MmpnvMmd`3wUXH9B-{_9QP$XXRa1^z zHCL8W&{uPImqUp=E4;*r$5nk44^EunZ{DKk>{K*B6*QQY+t;suWY1_C+U+z66SZw- z2dOTfc#t$&sl+InzAA0#&ZymW-9YQ$R?`rcTr)GJW7=5y>23At{`aA$Nlp4cb>&uI zlS4gr&$5e(3uNiL%)OAwV6xH_UCe!#^ij=WNl<vf}nF z6Lxw!MO0(bbC3PB_5*qu#LeD>^L|Yu_C-uR>8Lt&D^y*5$gOCrQ2+PII}gPb#~K+~ zmf`bove63Q2GP;Xxf}Ggk@r?*Ol5bUz$A9k@cKFC{O(1Qfaa#)l3lF?k0ms3j{9p4 zUOus1tBYR}YHCu29PTw&?z5|oy4Qa6@O>JZV7J?Df?PZ;Q{OwQpjn=n?wS8Q#m-)G zdd?`{&hB3G(H$k5R9Pi3PTct(Fy!G1#9r5*QKvOKjoUCvnYa zii1unLq8Yho(z@w3Kf=pY*cAq{`E~#3-z#t`D>5+%P=2CZUAagUSkyd@?CuKDS}TJ zLuRuFZi}up95@dc*n8~T)H#T=JTBExPqM`zViYQWTnh0;5*=nj3NxD5*PBM%0^W?S84@$#qG`ldFDWs3MI2J|H!Oo{*#ROl{qy5hQWOt#ZE70 zi(tG6R$M$@N=8O7ixIKEPXm5+aV(TIE~*t)JOLHZKF9quYSUz^$o=6tP7TMdg)BF7 zHl7OIFAAIG3ZFkK%(CH92k2wM8GdpEwUl!z;k?B}7IWVOxIX&eF~Iz|sbb4A%5C%* zPl=G&WQB^kdKit0>7GB8iCwd@(#F+-iFWbid1jAU)6f-C+AKGByFDaFM$7)D!~V9R zg2GI+%eBW+?PS+?`YTnYVsP@)lasd2$ZBz?FnzknQcOtifxltLTC`*F4*yN}U3#J2 z194RC099M@Qa!qHhm`+dw8!J;m0X7X4J6~k(hW81gAA+QzBKK$l+^3qgI@M2DUT;< z2i={=yMqa359D%=i6=}4h)v9|a6kQ5PMm=029p4Q5z>)AL#F?^q!tM-(bZ0UWn%WA zxtSfcIddqnU%CP>sefhL8{FAx>8+bl@5WIvqPBKOGnd3yzS#@yHh82~kwwc*%eqHm z9s0|blrc$;Ws$3D{|NyWHTj9kQtA@+&^})-TPD`?zJCcRl_Y*}Li0rHqRUIR>e!>B z+YB;8g<5_ds}HZ2xgtga5cYEl>mIW;lEa(6wlUZxm+rjHOS}h-y9T(11B7^D?}H+9 zRLLe%Rwax*qHB?pH?w;#U_T@tw?&rfF?NN-<)`*OZ`A&zxV;jK zj;03py>4QMjz-Fc>GRIxet3r<8k=Vv8&+TV?XQ}Jlw!`C?u{LLj=`z9AGOon^0Vq0 z8ysZ~32B|%066EoQ(dXj`Z`8o(O0JaznWPwQM;mDcsAyHjZwm* zi3UmVZuO`UHMI6i^q7h{T1HF5+yo`Jn7vBVt!13zlr357LQXw@;oO?GMenrg2usvc zL`kmWNJ8q83@l3j*vjC50xACKtEcXXXp9|tfg@h^$U+MA8|1Mak9fslfHt@bvA?dCsvq@|q?xs}P* z{+wcO=C*2pSbS471N#MfW#BYup763u$&sI2;J*$?muJMGEX_$VDD*U0qx0Hes&lHk z5_3!^pz{#%kIMZatTOD{nZB*9O(O@F{q`r)>`UC8?;);HcYg{vNKhNeRxAfhcjM{iE~Z+c}|H)F?%R1P_SspSk z8AZ6!4fL)JE|xT>!;Eg8^w{+jOFEoyKL|Y^|kPi({^TYsbE?QnaH#*O1xc=C-=h5M0PO4C=TN0; zh(+A`cdHR`v|pXAyvD+MYj?En@4h=a3)0ebqgU@OV-BTH9A?4UQ$?{dD zQoX^hC6^qNkZ9*k7yE@wSz)mUKW~wlUZ)Pe3d&u#epGi^9CsJha9Xy^T&e4Nl#rY0 zfC0e88Q1qxq-@>0j%9X$QtIuSpTsE7rfJKM9UJY<%_F)lo5XWI-`>XHV>Dvh5H4EY z^T+qrPESt@ZF+lrefQK&?cjTjKcl*sOgbX2-hI0O{L34M>32V~_RB!nltRRx7&rD2 zgHz-!5z6d#%Tk;_UzwaH6)G)U|HG>Cesf!-@|G`d!t_l7`j~;}#%x|YKXd-nH`y4g z%pjKP!E?4oe`7QyI9c2w9>c^G7fFo_D|IopqD^2-*qJ^MmL(8mL#m$FN8Rw z(s*+W7uSe_Lrlg3#FN!4ac&@;9Ne>4UqtP9iAP*GEvxy#ZCSivFJe^AVB){fDB+}4 zpA(vzh0-da>ZNpP9nW1en0hk0Zi#ngO0m(P_f~Y5@a81zPttyn=n09yAzw+4g5;$C zu}2_($;%85pncvRZc}eD^hI3xkli_FWVek-A~%GcLuhYa@@i@qBW_BjW_%fqQ!Nk{ zi%a0&ChqI3woR3egsV^yVB@@kTY0?}mW`%=Bf{2sD7QJx0Jp0`vHcCL=(hE+v%9<1 zO2AI*yzHj&cAQn}l9gE8hu+HDudQ5m^AXIGW;}Zln`txEvaO4+D||Xe`x4WnvfLt6 zKkfM_@AV&3a@%VB#J@LAMzOORmT6&n&|KNmy*ehF#m3pY9N}Tqwz9nS#t*!D=R%l@ z`1ak5y{g^(bX-e*Guw`{Qb#Y_t{E=Vu7T5d%)|AO%B$NT6+-4+>xRUi1xPEYn2izP zG_S{0^xMxZXVc)O0t}C|PWPvS2s1B~1+Z@Px6ihCGybS0>3tmZz+m4S(@%CE`4s8-p{Sew1&htsK zDJ%OP$@5R;c)DhM)(XK^OW0;U+Lg`9$7tN(U}D|kxrH9HwceuZrRZCNjO_;2lK(f&} z30p5T%Q^N|&CU;(HLT?1I+i~J2rFG?K38I^w(eh)I-jz1p@=ggQVtgX!Y<0F27gKI z;I(nG;VlnUhn%gp(|9XdA_e?QsgCh0-bR&|fSSII@bLy$qVR*5ks&bF(|pu2=q%+M zB)eH$Ar2B+&a|z3x4d+34`Y;=*u7kd3%iWVw`yxpby$it6Zi4-7 zta^ZGDoT65NEO!>o#m=`XPt33IW$V}i!H_tm%re?`c5TfCeH)ooQU?luis>tXIruV zeF4*3Te{xGp?=fhc5CJS1Em82?uGrZ(_|@gWFx7!$o3c$JPIf4r&TV?!}bxZuxuGe zq}mTeIq8M6sP>ku%=&K(%BO+b)L2Y~sw`$CtvRR9uQ}_;YZ}*vGSn8c2hYM?<%6xS z%D7H9eo~XDV9k>FzD!wo`B8{5ob;flNUlLdJT9AgGlJn%@c|v>aM?q6=~(PCuq1F8 zjGZ723M@3n0o7-A(44+vUAm7p)aco&-fZ8&9BikS2AI_0w$5E?*M@#i$b3a0iX>y6 zrWsx6+7)u2S=gZ02L~>oMg#t}wh}ySnwj`*eLxgnfWhPkXzLb77Gn7+_M~@An(OJ8 zQ+JA@IdB_A6ktI$o0W6*24M>eA^mGF*gdua7bZC_&~`O#R@k4==I?-^cb;&_reSC0A2OIN|MT*H`bxyx+7r0F4$H0UxnpKCy~ zkJ65?LF{XbaiKk}0X=27j+UYFFt%OaTDC#EZ||o4_}$WO`b|!^Ptn_-HfY15v@37N zB{H!KFVYpw)S%v-^h1tUKB=@em6XA_H$;9LUpNqVab#e8tcoVv!*-)ob|i&9J!i5V z<+}BLj9~Uv72(Lq%de7~Wi^LU=T&<2?Hy6}HmLh5n{q?;qVn?h>TH#iMXF!lr8W%r zE&2GVF=}lXrL?|xF#CilN-U_N^YIMUz5Gt6tdeMZk#Go8*LHW2mq8rb4Re2I$>l@T z#z5niRM!2eTQRR_e0fu+QrD3a+~6Fl3ck8OA!dy|SswLfD+onvJ*f zojrTDqyOicL$F16*pd6Aqd8bSYPUWiF+ z^`@QcxUC;Y&ZFHZ?d#wjB_t4~nv+xiBID7>5=U(n@)KJa+yy4Bz0OxFYdy9*|Jox+mi|I~kRW2o7;exP!X_;|DF zZC+Hz8}Bh8*W;hoX%p)e2HVpRV!Eow-4-I07}1EI9q~DHydhfB7qupGvJBilv|ipC z#^}tl7b&`#i|U1G%JWd}v=y1oU!>XT8D=LVb2->zxyMJ6vhY+tWpVKAUbQ2-Jk*D( z@~d(BKAUzXqGD{b()*?3p2clP^wc(0{tXej9fx(aVBqd{I0M5`&%SAuHYulP;{9Y_ zF!ydh5-<3&fsQa-K3I`2Ci|InP~5=4ev-_H&per$A-Z2zY_N>nzgIY^4GYp^`UoKb zouI>4l))LW(I^z3<vC zn_ZMjilP?Q*%y<|GPN|Z8cXG}cl;iti9Hc_qmjIMqG2J5#`ab9yN2+z-l~mV-yZ%a zbXm@B5YV^{SO$hC7K8G+{%XaWi(WQ+)GbN{9=Q2yH%R7ZS<(%f6YE=0W;5ldO{gDP z3~F&D#{Bel!9;&XE0Wt3Z(#23MA|0R2MM=lAu60%QYZ%8_ZL3U8s`2D%eGu|2lutnJ3`1MGTGtwH+W3AA##E?H;6<@<%Z7^k>03|eIFG*&w&Xv0 zFf%+`vPk3^%!|71*U>TZ(#OX~IqWuwlAUrtQukc_wk6%Y{3GUr&PzXq;j~~sGvHY1 zXq9Gm5noqo!9i&8a^n_k?If1`8(YKaBZ2+dCq9wV>hA7ayINQexCXvcdx86;t1Ema z8DX(m!E7d`?Dv4=TTNlRiVd#2WYD)>#KoZ(SplNaZJeLEt4%6Q@xY<(-7D_>H5212 zHN5R}BY9=xisi@iHZ7NpI$DE9lSa{*~t|+l7At3SXNOqhW^w{TfjQ4 zPEqTD>qpHIb?ZTs>TUVQ8R*9;zD$vYP3^iB#~7>n*eqG7X)8B`z7|XHs^@gj+IA>0)N3*cw{Min@T%?iUX$FzL`J3?H%-l1xCx8*@o}$`Amt#S$yQ{>l z8U?AwEt+?sEG=atDkiNpy?Zg6cfRslWSVizz33hCQq1@w75FIWXD zcr0OqIBxt$%Z^{&>(6gyLsZ%kryCZC^S^~jr$72?&3sAc7~zkZZL*;yBKv6cvC|a) zc@tb5EPK&5KK?V;Al#`#>TLPW_IL9kMHP032r@Z}Dx3MwN%HwV1JO0XieL{bPS+VG zaVXAl7!>RmNb0*H_`cw-6y1HyG!D>x%Y7GeCEI7nyy8vOG6`Zp(gm9Nvl-)>5^!vi zZNR^WdgE8C~Ky+luI^jA;BH1{QhU2>Q+Ak}U@apWc9G+D1(beMpwq-a>{RZ^lW{FMwfSuR9h zn>AHPpHiIn*OhpjM0-m+D)?S}AyJy^0U;#7r@Xf)Y`sRJ{qkviSLx*XW%tH}x7sgE zG7FtfjXY%Z!iQE=!mBigPnE-pId5@4wB-s?6Ux2D!E z+s!;II3DIxWar=#JB#|xdR9SEF9)HjUOF_pyTyFgVO|tf)GB)|5?=+dfzgnmY8P9kcjqPEfV3uHo4J zDx9Q@BcgojR9MV*avxu*VE{sHw(5b)9SmzVv9Py;j@HzGLclgJ ztmqj#CBx*@LH?zl>0Ld5A$k$oOYSSSXUbRSzuji-I6w(^ta!EGp{0+)Y9tWG`o5&$ zTv|4FSs?KfvcOUaDNS}vte20J&e)kEar*otiWJW%5`EfaamQde7X19h(np`qlE%pj z=m%R7+TNRS;ykYG<&|0Ewrz<^*smEG#?pT0V*)0tkz8_p?@&bppdHSm5>hxQA&1}|uwX2(o4z9U+ zZ0(CEA@jHQ-6M^w@!AbUPX7L)=O@;RXAv-fni+&UvJMo-t(LuaaCDS)YhC7oGw7_m zU$@W1ayGrOJKDQL1*h84mn%Euzad9?UL?MpS0fC(IWu zoQfVipz)_7{K8*eXe}+dHsVY&z_4YH>JlUwbG?4v5cTHGnPLnxdvfB+yl8tAIly|X zO((FZ)OmXLJIF5W`IV(=4Q}M!YBSgHCabpJIx|q|z@Keevk-A`wiq8MhPGRw=$Cy>>0(=%6WtN-jh|HFs)oR)e&8O^Shf=kYTyI1JA;DX}Mi6$JagmDWq?7qXyidF<{ZvBkYt+`ZLA z$4B?qKlc<037ZKmrC+-S3gW+ol-I_%rm#!)^f}F$Ro@pz->xOL5|<6UgdS*Njb?WO zWDAp@UA}BuU@h=||JdpL(o=ZEP!^!8Un+M|(>w~K!|hX8zP7cCR;;4RbB?Azv#)C} zQ|G?J8EOO(j7|8W3o#-(PT{E&SmzJi+sf3S81CJJ#`@QtI-Z&CB4jjg6lt1u#?bTAg*$5)_o=X$vh?&%F5;EF`0Kh{erEd*;tUMK!jt^#< zw5=twqZso_wy1HOOIa5CwnYSYy6w!bARNTyc|u+5Z>h^Ywrx4(r_2VvXG=j`R^mYK z_Q)In&pXb3^ZW;Ge3;?M1*|G^)lEQ`<7r~kud$p2ys+^Ni z#Xc~>t(1n@>*u!+``x?eTL&X&dM)uHKvW*?mO+7#Z^-FaNQr4KOyp~%k&n+w%o=Dp zekHw#?9W$RGLLG)X`0j316oSgt?9+OgLyN^t>nMNh$(ex_!wy_S_!gGj_h6?>m#nN zuO*iC=FvFAtFatjJlpRX&y!o*L`S>Cyh&mAA@mJNBS|#DD5JZ|zMX~p*S0jVVoPt| zcIFIX^vCS@Z_V2CJE5QIgZC0(%#Fmpan*(5{=3 zmkBm2+#bc)E_H`@%{<(b<#>rR+EfzNUfbq0e~z%7a9bOHwY>bCzTiLaFDiSiU&m8- z1R9>Yip9ObKAsn<&q5$j4KfPkKJnZx59CJB*zqZiS7{30Hg`w$K+|@enxSNS{n<*i zV-JYT&6Pc>c+k71?-VPbOF$pjw8S~QG*L|xAr+vhy^Hk=lBV?QkF##YvJ(${KmPuT z_lN%Mm6q5u*{^RKUva$@`gYcw;`kBksb}j{RQRJmdzM!%fy=7oB4-sBMtU)4l`3(I zx#`$rw=c}^>U$g<<69SW10CPkWEA@}*c!l%y5q0iqUx2-Il}~|26c)@UBH< zG$rV(#>H_YTORHnnQSX`27H!x)>heQG)L0!jFwS>>Gjjw4U;}p$m8@eyH?b0b(}wg zuh`RH$=bz!HkFgo7&gyTSF!g*tSM!^M4e4ZISR??*Qw+Ujt|tt#bJh?QZV>yt&8N3 zt}8h?h$>@|Bz1jk+Fl!3Zp8EVrqi~Q^6u)s2Nur#$vBrvrHya}tWi&T1orbsJrxZf z(7_sw=A25X-PR46{p{BBk=*pg$ozH60{@NE($dn0cmp=B_8e~Kv=8RPu(_cIsy}!h zxV=pl0>Ja&N)7U($ZJ2Gx*qEyy=U)gYqQ#VGQ|u#)fDk{Zv-1LqTON7?-eXf-zJ~7 zsN6meVDHB40gF97Gq7c|ch)_Q+NbXgHh13+--XC`)9=A22 z7TAyWs7ft5n2sd+QIq9yr9~;tEVX);Q!Iu_YgzBVN*k(+(~&cetoq-@@mCfkt|!e4 zI2SvO_(hmSx9=|BT^8Gu(={@>e|xk++=n--guvOW$l)`IF!g^y(s!Qc*|$Dz-ytfh zIM+OibF>vR9HYm)TI6(n*&^V4WaJ?Ohs*nsUKJk7@_EGUPP@lzu3NTh{DZ@OPdzp( z1bbC;{i_LBe2&nKexl;LMaxfkr)672(>UGVzf|amIz2sCFNKysJSkc0_U;`RuJh&c zi;5;2%Vi4z{>PUtj{JXIeFaoi&HDGDySuxjLApagx<$H6y1Tnox*O^44hd;VX{5Wm zzKy=`z4!l}wQwm*Hv7yx^Q&j}oYtbdNNw2c23IPYT&NI$`Myz&XweNKjOZo1vYNm9 zuu>pTL}cy^2lXHM9~!T59lmG}WJmNk#>2y9I-z-bO&Ij6*VwoNF=Ot$e7HTkrMl4* zH^;#%dW1{t_wvFg2VxC3BM9Q^k}%LKSHzc(8;4-+hY`Ajog1~z&fz+=@otDjdXI!5 z&%YU=HXv+$Vd}a?AbsvPA_io128I>|fBr-s$;f(Epv-hP5V=|J`##=Z-04Z;A$ZyS z5u$H{*%vBg^)`v4@&vFoVOH46b45S^;;Mf+;~N5K5$=Pt;-j7QKHnuU3tWyl5C~Z7 zb=_bZI%c{{vPaw~;gL)sCygkxZ_REbZF)afE+bhq750}&(ZsCWIhWloy7oK_im8pK z063dh>A}%o*^GRk=fzPs*{@5e7#*I}hIqfHvimqv^ajQ}xN9P9H6k3RBi~$Qr|7x; zcXdT?Xha9|Y>f%-ZJKNDLvQ1#W?r);N6hNk$N4K4I2XdEn-j6~M})Cyw7tIhVLks- z0oOS$S9)0gA|EG`0HIq!-s4B|sJxl>?`^7T=|1BRq-IWd=K$wPsJ{o8Yw*>yMN4SC zGB|L2gT>;kBP%E8Y~5WnE6xZDGd8s)XNWsNpux(vw6k@2lfYz0&88c}e01G_ngfB| zb%?te!ucDq@4iJD3$uF9mc%AE-W+ppSO1xB&Flbw5PG2NmBslY90q0@s#LhorI zz~1o+pYVCR9d`8s=`~PmLQZ@R&EIgLaDSdc^L|D^ZGDvH*0ue<_UU$UwQr5lmKm48 z_t&sN=;Gv6cx(b9{bDz1e`Pyzuk9@Yw=OeC*tmA$;US{s0~0lo-YtoEr3W$F!E6?u zs_G@s7?CtXC^?@J1;6LMDIO#yh z<62T>5%f872F!7oNuw`dMO?6ml5{2`yBn7Rb}#g}In-sIq{;oe6kZx>HF!_2UAwfK z(LcYmKrBd|MSA}-8D_apO=ETGm5Z~i_*Bcu3oli)t?#i$BhG^QP50(3jBuiwG z*$4T=D0VH#K;O!Wu-dI`jeGTkI0!$|fEr-yiKq2NyZxsZRTi6fy!MBkLMShlzTu~H z$3ZvMLZZp0L#g?NWVJpJU&h-|C+RCiEf-?~A|W-qxqYlkrY=tjUeNcffx)V5>~-EP z&h=(L;L=~4btSVutBq{9^R*Xxjk__a29_>z204VAA>pM z5EhpwB-}e+TfdDn5J;RF$y+~ro9UPTgO4^Uz$H^B-Xw-edT^^^z`o&CJvP{*UjTPH zc7c;3;k?cbKuj=z<2-%29B7ummW)m8G#6HiYg^mH^}1kuha&(xEP9)^YVNW83N64( z)!cpD0TCq$Wf)D#+7j+U9sV2~@nWox#rA0*?jn(W-&X!2YqnlAg#g-JEAU?)ga+^= zwtIhH6bP%aqJRaz8(rBCe1&jwgXShF6eT4{2?-j6!Vb^3fN%+hc0YX%9@v$J+xiS` z-0BJ6ZLPZffjmnL($rXQ%tlY7tBxN?0vogILFI(M8w#I;ak2p zHiR!H%w5+Ct!$dGQJs%ixSiWur-$y~{bxpszu`1K%jY-RymPsW2yhP&x(A!CR*D*P z1onUPzHEGzvKB%qc5K9oDr(3AV6OuK_!+yCRTyU{OnEH=pkB$^x6%VpOIKDy#}uCU z?q9a_N_B z$x1l}wdnc~SO!~BS@~uEl;t#ROf=SsJ5F7WNYu*Z!k1PJond|FnHR(4FVZ#VN1To zs16K`=M~qSlZ_W>TIp`iVhgE^MvUSMmqY>Gc~0O;f^`D7X*FQ0&9jr3_KM^UX9)CQ ztliAz59rQtJznlB?H+wQR8bGdtX1PyJdl5CjTduE?wAP%14KjdyfnO1XWGoG-gcwI zeKw?kC3M0_7Bd$)9g`uYW-mLiBNRFK^7vuO60ilqm8G?{#kL7@ucNvJJRjqAbleI! z$Bbay?Q)Xdw$TB=DX79q!Qd1%%7#6%%0^Sxuy3d@a!R-9^S?684ZtkmVN$K;x-0sVS*XC+14zXd)kTzIx5YhEBSV_U%E+`0i#ZO-Prez!1 z5%eBFSzBVR2BPRc)iaA6)(oSz9x8lpIyKZFBEpIVj#7jNVshcN=Z7`-!&pbn0q0ZD zZ2S2ZuJ11n07oT&gowGd5=i*LUmnDQI`5p#DJWDnG6zTktBwM^-*NICEG%?^z;B-N z?V>3{cT`>JI$(Su=2T#cZ0OH4W*nQ4NqSP#^a9V4+AuMgedvH52s0i!R?1r-*Fjq7 zyf<+p@iw+x^49mA^j0>iog<@+h)MI&+m;R=n7B|lkvt7u9hkqW6o33V9Ld)X?iYW0 z_$zusU{&}OW;N~p*`l}iyE7rr+np=#PH)tMN_Vt=-McrhFj}*0qKg=he(dcDbf|7n zff`Z#GE^*Qjq(gV+YPaMc-S{Fff~=l@52s+2>xoe&yE@yI#SlF{v-EDRlIy?yB}kM ztb5;%20ZPY1AFM7F6qkL#`z}iihU(7gPA3Mr{Iv+dk>U>sahLDX6nRt12(hgW(|S` zXc^rLas={nMyT1kQve+5Uwxn#ya}bij3C7Nf!lDx1sEvV%SD++9B&*-x zH|DewclpRgScy~9Hy+8UasN(xd_}?NqJU%Dt-M)tU;;ONu1e^w5UTv>w=FDNq zaAjY2;7lj7)SsoyGP39e7&GYJHt~8iE!Rv6EgeWkV!=wB97WhC8o)welINCK@$G0I z`Zy^3iB^BKc(ELuPEs&d1npBpvVEHEi4oVYmt3p60}Th@$BGF#qxVQE6m6VOTZk-HQ5?O?V_N8Y?+2kFsL4{_tl>$osA`;bSzZF;TiXvpu_eENO z(*@W8IDg2%SwcUw2elB+S|4;A2m=qEGWzA{=$+{k^n5pJeuY@R@&pXDLq_!geJA6! zNs=Ir(90GxzUKI~W8?Z}u?j98QHu8tkHeBp@~638_)vpT(Kuoh@qWOP2@~K4*dGp- z>2#%8{0?UB2JDA6%k0zVMbu}BGc5yNAfe&1mS`~J$zOz`!VVPV25p??6fVJ()*|eU zYB}r-Y+j5`kOIM^2m!v;t%n)ZyLSymFhHJH1p&tG<7>m63GiJPVD2PV;e^i%+Dw0? zoM^wyW5hN#p_AwC^Pl`E1@wE!s?cModXlKPY637t>*?h?YkaGEnkO;h;%2d>Oyf|h zz8=08;HHxYc`Utmk)bzW9VCt28)t8=+f5CU8(9Io5DalY_yAZrmJyk{xT=f4*%iK) z0Ycgb~290fA3u;}yWFb*z+28Zk)iohTkJKcAZ^fCLGbP_wP`=Cx7H zsQy_BvNdylW}4&D;7Qi4$sf44DAOQ!yiLYeWr({?mFs{@Tv+0^L~Q)iOGfrjI`Wzn zXufu4xb8$rUcbYe=lPLKLNe`Tj8|NI6dgIVx>W?HFbV0xMF1R+jSPZF7_o|Z0r}If zef9y?5iI~Ew@d$8S(Xt#44{PH>iuhB$#bE`53UT2o&M=CGjjV2gCt{!ES&LP7lq6Z zZQcvs(uVGqd&b}mte&=dNO$((Ea=h$u4V!;zXWcWUo%=InMG>qGg?OZe=h#- z?E}B%6O+NpmklK33;BgTR|9TTVVBy{Z63`WAV<^wBU$hP^%85KOP+i8Z>S6eOtP+X zY?SE#ba{dMLD2T}txh#h#hJdfHf@a3!LEW8OfygN3;7l;9cYLc52DX~zB|wg28)?mP3N{rWJ8yw`XyEDYQ4FR$qD1-TQL zRAjh|0q33TJFn7#Mh`|xJ^JIW(?^zZVWI@Y!o+1@ba5d5xJjV(ZV4F@`kJHu?+ZT+ zh!B!LCA$`yx^7>2j=_M$uLU%3v>j)IY=wH;qPu~yLSvNpw~_WQ%}ut!2aC?XsNPLr zD&+y`D{g(zYvAMGALPEH<=I5^aDDRWwvD~FjV9mFuQw z(6`GmH=%I1Gr|p4?h_C$8F*H{v7F?uXJWZIgm&(4V8e$16A~8op9#r@8hqI8 zJr%sSdj(LSX39!yF@O`RUgzeUWg3@N&+V;S>9EErAhGlcUSmgF3Wj)~1YRqO!GP0g ztj0js40XTwd1;OYj0!uXt|7C7Fd@lW9YZ*gk&{Ug~v(2Zy@ z4I(fcv)Hn$?vJ$otYP7V-VKExpOY5R&2C_+te**Rc>ioztt9+#g)tG}U$R36TqHI8 zKkwk5OKPhAQ*}W5WZMWppf|zp2{|1VYzt(-9r zpH32*dzqK+l-GZnevnIUbabW(0cm`w)K7MW4slP51!_t|%3!5df=}O+t-Rtj155;3 z)Bm^l5|e|MQs(xqAwV_98q1CxTI@Y-i09ab$&Ee<0c{|l_^`vps}90-fZVa+0|Zk_ zQo-wWAU{6O4J=)UF$fTs*vV#};-X;3(CVJ8F= z0%vl+YBJ59w!c?rXB}yMeP;X+h}8aUTwye?4{`JVA+l2J4Zamy)C^qi-yg37GEvH} zLx0=K0N@}3H>V_%%$4ud9hTA06M8R0+{C8Cvuu=lgL(|a zjSya}&HfC6`MQNf@{JY3Ie26q`^o+w6}Q_aDSu!QKJSSazy>~u7e5W_tq+=U2?##D zu7^6v!GtdPBoz-M$zzpDL5ggGxZP>#P?t~!|C4=b2>SejnE!8n-}L;|_KCpnxFFcp z8TmgLV?n3+r(=-7{F9VC_xpOGm!0bkgO0mrYh-WBPHD4|0wg`jA~CRe*9KY!1Q!yz zBUW)xWA2RSZ1kT|`7=1?Xn>J>C9jI+Aom1kt?EznNI?w>(d;8yVE|47G?2FRHV@+D zQuu^ws^x_Em{#!GYo-|YcLrmZ)^KMS`d7y}JBCTo|HA1Xh*3fUs&V)aDw+WW(Tr_q zwi13#On9L7Nw5R!m4TqvMZ0+QMW%3X$a4Er@Rl+xT4i#5-`yQ)slpV=1bNV8z=AJM z|NNAGnIu@a)EU8qunz$g2)cx?CrRDvsE6R@85R_O`|^Lu zD7WyRL1hA;)g#W;aXxVV8Ey9=cDsRfL*212V^sN72Zb zpxkLm!LU~E)*!n$gj?xslIHQRjg4hag&iRf>FVc;=l*L*8O_-z6Pry5t8@LTpxgY+ zmjy6rnt=-ugJtMA#-*2uDDT2K_HZ!W{~t1PYa##efvqD4#fWDE0QSwH?vV`~JR_yn z^N>{b$aPsuS~uFjoz=ZPY?`Danun_L2u;7&96hPr6oT|iIB*z{kC7XhuK?FrIS`I? z5dkADp9!m9Rjbkg;bzz)7A~uU(xE|ch;q;l7wg)~bZy?|Y;}Bhtc+5KFm7I&9}Kwf zhG=?wEuZtW1NA>{ecpjrn(1P)u=K8WADD`v0QG)>69QzBE2A^T#A zipGKZZ@29)<+xu3xer^YC(pqJk=5GFxBQB~`=s_q?=8aqZ|S`*o03>ZqrJr1slc{D z*WYS|(Q-abrcUb_clE7v{t@hQHZo9dX`N%ik-!Qn&d($zE(S!{We1n;V+o!r)74NDC*Q$X6(1*mT>?i@L^=`S6O%ir=HCccs>Q0HH-_k)H^6q5iZO<2`lkHEtH(mMPzpC-i@=agKJ@7 z{~UV15)t99x3#EulHH%t6BB|LQSAs}o`439JEn0h9VNzlH-3128<+^GZbg_JT6m{r zXhy*!{6(d4nr3v=1igNMT>shI^tzH?bsKB2JI)(`c`E-^7OvEPc-x$e4rh~b-c0hY zDzmoY^33Jr@IwC0%#*qZlOwP9!{*$tM;C$uK8PZ-k)jc9pL=}TYQ5r$4)&oS=oGd! z4pA0Kwm3K?r14dTWib|FkIgcBx5Qy|4w zAe$=eddn_F$-b+I7!@-xiFPf9a4gRIwX1Ieq-{e)`~jLtM^p)G*V1WhhY^ht`9F;J z+S;(*iqP#dtOjVaj#l+=w5*ob)3!VYo&ON3AGM`v#5&>$xYfTZa}sZ{Av3bN8uSo{6hs7zL0b7F249uo@=!`N&gZ3{;oD-oD?oBMf)S66g1T zss!yK16bHSkX=NlzjD{0DMoS)Ddn3Zr>=)4=DPZo);K$wbm-o#rl zxwD>w+3W*o(Hs`^Gq|Q@rrp$-vXqQ_c{)*%Hwo$R25E`GWhP|!wWL8v1NMb2lrl{$ zoIg?Mj9`O2(1?Vf7mtOf<;A8L>Rhb?jH0_ItY{7EdQwEiBcXiLvP+r}anOfe4a(mY zR4c`TDop+vAb0?(5YT}ssn+1TXfXn7l8EhMe>*?zjPDPKI(>i*!*&@O(YrF$ag-KD zfW~@En+(}VtE#N&M;R9sCU!v`vqQo<5^XTGdNgF0uFHkf0|QDU&U8+kwD)Mvo(GsUlrl$?EJdO$&*u8?CV^ z#0vY}FV}eOoLf;GdoL>JD1U7pJ#i$sDmYhI2~&9Cv`MW=8$1rWO_wO-xa&yyvn(YT z+-@q^JA1LIc5?*huAOu84Q|*VE(*czf$yh=WN_4-YWpJHFeG_N5dKgn4 znJ{y*|0ATniTvZSeRgqwTp z`+SOkSDQp7sdpgL1HnUL_DW3Pgv5gj!+&ItbaOzAITD72D%ltsCv}JpD+n@4wL4rI zPlyBW$c84W&<@ks7L*GKg@FlOzo1;daWOLFhs$C{NZJlX#kLv{;m-^LhdQ&O{_t=~ z@*xF5L?IIj9J~ek6}LoZRNeTQXe0W5s12`OxPO*6Lybdj6GRC~C&lE8F*|BQtv1JO z*zTSb6AGO0)@ZQ8`aM)cw#I`vkZC^g>z(+;|8Yv1HNeCmzA{T9%gNe3(JsQFuwI)} za*)A_=wH(&ka)u|aB8=;8fjMYXY)hGLMFu7It;A+869uhePk2pWaWk?tU&2UQFNov&j+TaP zOSDFG-i}(O1{8#9X9d$xm)%7579#Frxayl=Rfb?$>S!n4=pe%2V;FFMF_s{h)RG>h z+^Q+`7Re#!Rj4>w!~Fw)e-X;BXI^Zs4%)(D?A?~EM-Wtk3ciZet&pV_SWL?ZV(i(? zpv7vm*a3q@7oV5#CGYQb`jvs~Q_GaS=xWMj2)6h!nZ% z|Mj2v)N3~zw`UuG-8O$;9Z1G4NOJl0shlbJ8(Avaw!q>a<9K1f>a@MQjYR&d&_FdA zDWg#da14M>_-@EVrZt_{qdZ!K^#SzLX7^IuksK^t=*-JX$ej$c zk-+=|nJQFjj+kpRsWpNDTF3{iFf*9X)f*FQjH!~e;G(p5po$<1Q!{fB`B&9frCekILnPeQ;h*fSk!Mo|~WBuZlU? zkIQdtq9E)$aYzn{80|S?ROYiyF`t+?0`C7PTZDw%wark$fK7M4>c=Nvl$WQMx%~)p zIKa2PW(t2@Txm6KPa6Ue5bM>UIx&|%F3F0&RjFV0q~W_xR92{(Q+F6xkT>e>7I#!? zR&c(Mg*N?A)M)guVrImE+RJK$LP(d>0veqF8xWys$u7qJY3Q{-KQv!nXkmxPs~rM1 zTocDp>&HY^5L96S3kj}>31yQ+APTbC3p8zAJIA||t?V1z#l2S`>K&X%{k=!qk3q4k zy%-YHjcokY!cD-YNt>w&kphR`W(qWb1lBc@Z0^Xr#vXvnDlaxeWoQJP7G(d838b8O z$j>kEs71)ggc(b-c5$EWDc+IikU}BeQG2=x@%E`Z^*MWM?gMEyJeIC2Y{)`P<`tS0 zUT9$<@QnyXkmP0yY%dbGUxu85+<}W{oO}Uj&yai583|U4X+x&OP@t(dj z#A0$R-lg{C&03i;a0En2g<(WKRGa?SubcbhKVNhTKmPIs2kk!0(@Z{JRpuUSynq|j zj!r1||C6-+O-CHnY?D9m*+N`mh}lKUr~m3FWkzEJ2R_cHoXI~7KVQ45QS}>+xo%Zb zSP4609&hQ^hE}!FO9Ad!3_1RLQVM0e8qPK*<~8nJ^kqdX3_MmP7BlJ$iKVyeAIpWO zK)qCxQ!8*fb89Z1AW*YuS1xJWL4x(^VAr%Y0^U45Wo8s{XkMD)l!ZoO^ahPXr^2ll zF)Zi@9TZq6iC`s)D6AX5joY#ftYjdCY*3Xqu;G?8M1zUQ+}pkZ6kZjIRwzkcvt`eR0jo(=+OdJM*i|$wWS&gIgxdk zI4>y?91pG-Z56bQ9%d>V^7lr(pq?(``+u>W!AuW9V)?#SW@OXbfzVM0F8*8Jzf^4ABDWW+eg zR+Yi@pgsM=(7Tx)&StTz!K-{Sf$j2t)T*%^f5~0`r&U4P5s}yS%xfSVPG!We4vR0wv}2Zn%gjVbX53oNrrj zJNgtQ;40%vvLyy=aNnI)_!%u$U63T2i1_00POVyk8wbYsB>8TD8<75j+&x;LorhsK`ViqU2b$|vA z48E}_Y?I@%F9jG1e+4TDJtR?qbSKMZR2KVJe2~nI=*(#GLqRDo;;0`cHh%~~u{iwC z&$vVgT^loNYzzA4(5maf6_$!Y@M><3-9~WVl!waK!`PQ2i!y&hf#8xFiSmp%4XeqT zq7uSlNc>Z(Kaajam4blDTux!%Xg6~#3Kpk^Wl zRT(tR^~heV76GFBe*rTZ75DK#3+x@^LVVjA9`|{D>*T|6r~gj1P(yapZ0X-Els`h< zYXu>;7iOd~d>z{h7~cR90nV#1pYLgV%@d*(Z6|Q_=UwS0Df0y4+3~O<>DG*29=1KTh?DG>~^-_XtRKA%0f zw4f9}zYBguF6qQ}=;|D_aBg`y(zBmXW5*(tRLWwf9C=WKcJUyT1r5pD&o2xGBhIKU zAUeu5kPjpXk~BXV9=UW9)2b5&V&IFNDpnji(K57C(jbfKy{yqd8-vCnYuxh3 zXBpR>_^cf7k9{)nrMh-FvMt{LMW#?m;yqvuizuQJGJ(Amp#)^o*htSIudCzFt8PLn zT+R1RBE9XXH%w^fOYW%p92?<77IV&p%1cNLvyab$9+PI?q=Bx!58nkZvG;Yxw#a`Y z!&ediw>bj@h^BCm;M_eGf1W{+-uAVQAE!gyk=A>@xbN}JdY=@et#rR?g?P)vWPsLh z9O2z6Sqh@GCPg4cmw3)6;23PmYpQ8RVjb`DqR63?BACRFxbfGV$Yvcoie`K`8rzbdOP4SXL~4_47ta zNl6w?UhqBcX8G?C;A(1Ud%MCX5m+qgq#)8Xhqd!!l>{?6j0k!hbtbn7EKKTFn)kwK zQoR?0Amwq5Sk#oUlA*|qsE>v`!ve23BRCwTF*>V2{8%jfqZxQf&uo}py zX;NVFOyBsiup72gPHmrW&#I@W6r##z{3j<3@~4ylGplNeDVPPNmU4JsrXXO0$A0rs z4J%)b`Ch?&VtW|)tmgYmQ2rDGRV$*60%GbXEX6x~eR56V|4Du{{ieh1%i6X^ahva) zaUV+?v7E^gOCq|pY~Jm+73J)ZtUz$MY@@u16c}k$d~G6)!d_%rzlOW730tmo3EX`m z{2i}E$D-kfPt5a_SWHEq#N&htF0gjg^W2PMUEf? z{7FSK+EGPip&V$Mb!^O2p~?Kj$-%&Yo(;tuvxe}{Nm|$dSzn6BasI$- zia`*2+<@#;EFeg<7E$47@_M7Xms+C4;Q+Q;W+5N!gp`DU1r>-Jo}b+v8sh>rfE*>v z1<7fx6a5(u?uAFUI@TrlWjqA<8IX_0QL5BW*#4^o#xDXqP z&*r_)5D>fj+6bf}ZkM=Dc@Q5R^UpU##1X(>k*;pjT|gHR38ns@CKhkx4951A8Q4+g zs?l07PS-Wo3mG}^%%IfE8qRLp3u#ofvDm)Ow^Xd{=sH*Ztse==ZjaS1`&x&8-Pdc+ zq=Z7|B^7RG|93^(7!SK>*Im_#@gR==L{iw8Zas8}*#d4Wh&(UX(;8)oh}XD3y5no; zM2?H-WX;4v?XHuvh?;aIZIJLuNy1&WT}8#v>G35iXm>vXGs@Ehl^72=Qcm5tXgf+G zFDzRCCn5n|RLQin^KQbf0>hz#s7joPoBz%io@b_9qvtcaD7-LuAuqDdS=W!{9Coms zy_ZPVu_bvqbqWwdG5f=2M z-R^sc@DRQ15Pj?i8U07-r;Wf?XJ_shxSYY_v5`WH-!HYUt7py`SL*{pmXK_!g*i^BT1{4UA+JFSIBybjS= z=K-?Yj4=$1bS?$5PLVu_Ipxb%1iRQIrc(GQM$tutv~nNdwzz0M+%nAbmLYxbg9zvs*r~E3 zeCn@%gMS^jc(%_IT(xD$Bf(HA-eUULJGS(bm8ha4ZD*OzMX5+*(T!D>&%xGv#u->2b5s?zbgnZBNo6y+uRz%bRt}0VTh1zlQrb2CiK4)XK=dK~zr}>ZRr= z=Wf@bemiy;FUVwGUR+VZ(7}ZDJ?R-PnY`rI^p_Ba{B!oCdAvT0hEv#f2xy&*#*yz> zV_rS{Cg;6^oxEUSCVSLb32X?yA8uyR$2K=Gv0j~d^{|B&p3AJ1U(ljqbYI*wWHn6Q zK~=k16*7zcr<~0E`r1^utiQVZ)@Nt4+<|_aJ4VI^AusB9T&XMDa`E?TJY{ z{>8R82`Nm7`Ta1ZBi`!LTXM9VDUG#TWn?_f^KQ_2Uu3>K(8tdPiRR=U)I|0eB($I8 zdGR`{Qu1{-P3+ZmrJN1E@lCwNdHk?A?r=8uk}yj{EMzq2+#tUlt*(v=(EJjQ^y`(VJH;0V1%#{-Y&R|LA;{k~F!dys`aVuM zko|y8f~4S$Qs(9HSEobg&1^|L*Ne{kG9VAr-S2Qg4YRW~`R;3IZKRx~N`Z13UP6T4 z`**!Oi)PPU!*ajD14TYfJJ)k0q(>m-){EYO=bK3vu8wP3klwk`A@<{94rwf2e*jyn z-GGF+a=Lbz)F`#D|Nb^g7klShHMwrG+n|>8!Lk2)ohk9+>;T^I(BS`!j-T4&N3g1e9PB}B9W)^I)+hMGr)S{R|)qRCtjy9L=lU0nn z+1Ed#`Qf!{e`_n@zQk}HadAD4GSI{NnVbV-5fg1G;9Y1dF=m}I*(*dwO^&h7=HuB? z)e+tNgut!ljJVivh7QfZ#WU#&zJqJ~k*;~D!Wz8K$u0h9P!@JfD-$_P?rdk~(qu?6A_4zq-&9GOYr*OF(pHLe>SOdks#Q7{>#y!>D3&uwbAqf+G}V)DeAFawg3r(| zuYr$9zM@3fwJad6e^_}y4+B_+n~`{rn_8UKF(JZ$K5awC5s#kPQ+ z=t_9%i17;W?m$zz@2A9IcAE|1`e*Ox6LO!Z(s-&JkVY4EyYSzqUvrFePN7}gV~@OZ zKBTUDNTJh7`!llK7yW6s2pbAdqYPj7I)N2A=Ft54P<&%q`|4SOq5O>Np^889a|fB> zF>DL(jZ_HtqV@lf|yY0B*y{44#?ugAG!-B5l#|IlJd7?s6 z@-e=O9@`T6i`4PBYQwc+LiJB|TViySA-&$x2E^As_J< zXK|SWex}~{Q@8XVzyHp?eI5PGYqL>2S#)Nz7k1wNjo7(8sO=*W&TLF`hqvy#p)F5* zh#{_f%=9g08kzrMcUTR**+`ms1vwh951JQ1V_-4u17nsEKGdeh?6PqZIZ^M-Bkx>g z?(L+@F<{#fS7;3bOT>JF(6`fLtXsgDUhN3?hwr>LzIS4z+@>`?zb$-`ex&caeVYnZ zl5piAz-oAScKy?W*X+K=wEd0Rcjfwc6A!u~S+3Zo*fk}7e{I<@ZH~|x4-PCR)dWMA@h7_`jT(>7HW@;F6qp&4PWO1XE-O=pWY}8WxnoiM?s4F{X;=*I6K2*ko z7a&}xJsOob+>EASr#tGaREc$SPCX?^v&2bPs^C~^fyGM;V!zor^H=q<{_-^oDSY~R z=&E{`G(l}9N*wxZ5A<1MZ*S79bSR|liYQO=x_+_fgcYAJJj0us;7nA0kT2rp!$HPZ0k0YPql zyMpP3)fBwpe!tu=6UBgAENqFdin!ua}^Sb(j9D|ZIH#h&bz!>`qJ7NmizM4R}r63dW zL%ZY6760-{p3tnMm>j!qUv>bck#>TYpklE(SB_zR?c$O}R|%quCx&HIaetw{hn_l5!QFkZo1H4Q@MmV3E{yUiA3Uba%22vpeR;% z14oaHqf&4}exq;YDh<5v)|F1CV zV^Gyn={-F?mDLMDHN?*-PQKCpkLZw})*xe+8sSqi^I)?rPzH_y;L{;_REg3#J^M~Z-C+Pc9iL@@gdF3J{AcRypK(8d+ZlimHxxi)Rv&P|D!G#Hh%?V9!LdbQSwEFc z47;~K@iI*xaQ`M+w?BbfkmHMakNmbtL$B{-(bmKdYz60`7q4SsueQw)N_ViJ*Jw)-(675244>eQ1+ptU8(Ywv@0W-lWOYZO>0PdDtjtmqX`FTzSKkiqH6wiybO!9s zIo7KKbi>`Dr2Y#QAb?S1wxnLZiJTZ4t*9li?ki-F^HVZoN{?s}1F$((Qry-*ahhR^ z=H((pl=Va?ui`jKEjFh;oOALNHjCmLH<7u_Zuj|*pfTi4AA{6Sb^{@9r9mG4g07rd z!*}i30S5E)_>n{Pw#J4nEp=H8FZMTe4_TBf1+UL~tvA2pp5)9&OH!}}V!>?np(`Ek z?@rN7Ap?7^w12;W2NVpZylW*!gcS`-IQLB{wB&c0N-k<1FrFQJ_#4Lhvgr?$dk==n zFGF<$#aw0S#l4^gx)}Chn*i1`w?*~z!@$cVlRZ9D5c$v*(Ou>807b+P5g0B`;iu0S zL&ZOz29y$^aGgk#c_ex(aA-Vi$J~v+w<+@OLhV`*3v3H~JW2b>QE4jr@2%{S~9NDO|Iru5Eyx09Ou+Qr}hhG#rLM@jR#a z8sF9oN6yl0*W29^yo{zZ`+g2N@%jW^q4?*5QD$|xO)QX^;jn;R=|lX;H-%$oQ&Rjtk%Rri=+?)~wC+;bRJ$fVxCL`Qu$& z`*B~v{G>Y9+R+xK(^c<|>70<2h?O~>c^AvD0g%7IJ@GK(BC?ToM!YJC6j5kj+YWMTV^Z*mC(iPT7s~6Gc}C;PEkyd`=|EV;$KJNiI~gaZLp?0o zAXLL^jT$$&!1L53RI`jFT(`R7t|AQZ-d)zJpf1rcb~0hV1P`jp8r>n~_IT=||KKX~r@R&s{Fy51=a=8YarN*VY}T2{&|a1c~iQ zw&HozoK~PL!I*0+HqZ|YHB}J=y%1AHkdp)X4+Te_jv*+e;;%YpzggN;uMQ^6Vlk*9 zoUP}LUsewBr}q>W14r@MR#ljl)+d;F!1+90ChG!svAHwG%wvpI2KSku!!iRh4G79Z{w;vO#Fq?hkjx7mm=o zI}!&8R@D{8X%D1&@4f1GJsLH%=5s5JKkG`xp`u9uD79s9f<|mdlD&$!>CGUU^!nE8 z8yt$A;Vxz#H{a@DY-jTf_8wC#od^o2b3^yaT+S>Vw?-pe@d6wG-HQXEM{1c13}^M| za{s~MoPCb2WE|;-gVH9NTLeS#JFDN0z_{@r-I%@IOKwPKtuFW0_|ao(nmc6Y25T94 zqTs?^MfM9+YP|bNw(yqGi?Alz?%K#^s2Gh@h=tlYY<3LoO)R~rv-gm5@rL^0{@}67 z?_RE3j&OH`cY2N()nhOcI?MnA)&}rNE%-D)XtxkHsIVFoH;<@*Zy1lTGp?Y7mJ*>2>)VvT*i%QG{ zC8@vzj{Xv!bN|X~<_=$>l`kB1=+G>xyMMd<`ouoaTcF}h3O7_!Z2-F656goGs1w1Y zTX3C1`r1|L_JBF9N+X~~{op6w;XoiNzNgaKwl)ZC_gAx|5_0nC6J);A%okO9hedw{ z4=`C}t=@332a$70V$l1JiUv_;GoE3MqPer7+am5wq95Y3z=u$Rn*^c7Bp5N z8kKXk(~UtHD@=)d1$D)o*WcRRW5+eyL%0?j9a1_FvugHO+b>gfOH{G6%IJS(b5*^! z{k=HW=-%yVzW{EC5E<&hTk`pafK&%0!@ zh4$XJ#nkw!5XelDZ4`)XgG!E3KI~m^jsctt-|}L}LfpFBgqQm8*uU!h^AN|3h1_HwRl%rw8J)6W6KOR&ChlX^MmJL%nVm&$IM=VnDqX!ntl6!@tLy4ztAQTFiqzp&uaiw_Z>U)J z*bBebXctG^P)LsH*X4qAO>j%}UA3P+4WO z#&*C~amuvAv}1z^O(JLmd`IFT0T8b~hmYx!?okFD;(nxQnTvxbm7ermnw6VjuJIJx z=5Gu+nwmfiDl)~j`}4=g`dN*!V9>Cr`sKRAX-8VkfRN*uopDOD@sMM7oFS~JsW2>c zW~30m4Y|lVyuOZOu?MQ~l{}OW&;jxQ5&s%DsxL_d2IbV@z@#qC<=EM$*Kx&BTrM77 zO(e~7OC9fCB6%>NeuCQ!Qur zIhG7pdp;eeahoHb)8FVKCqq1DJ%~Z?nuS|ZNTjzewE|1WU!>7Hlp16ZUjQ@6%;2?^M2a0$df1uM5#x#Tz{o4u$zWOm}Y@b zfQuk-Dbm9j)h!2Cj7as(STJ6>Q(5qI*>fN8oV>tSgqOE!$6ZzAOL)rAC#|8rYA27~ z!M!{{QthQv~?nO2&Mk^P=KxQTzRe8Z3x#|O>>5cvn4yw6-NRogUArXJr}GR_T7V3 zW=7dVmigttE7W_%$FL9dO<9c=li&(E@xY{PntspO)83vPPAj7%uh;1`?1t8r*VW{@ zzACwLhh1;nEJw2oeYxMomJh2WV7Pn~VB^iExuMvMtkbv~E$C5w(@ucIzp2$PnRce6 zm3^okUKH4JbNkv67Cq~M&i%O1ofxC_i2!Q`U_;Rs(>qH%mwMw@76NsiOq4>Z}8a8NrU=t0} zh-Y|0#<#3B@`2r{qMH5_AVw{SL%MjHKOc+OMRBh zsc|OT55FpX-`et|W`JwsqS5Og`D+Y0Tl3}R5j#E$g${6Ul-H%tVr4Fe=%rlTC;vaT zzA`AzfN2tfOK{f^G`PEm;6W1H9fG^V26qVV9w4~8F77VD-GVOe+>^ZTcUO0H`)8}z zqS#_*XL`DOX699xMtw1h=j{dst4cO7)#Q@*R_HVu-#z*ih9*BXVoZO&628(dLFj3+ zV(yxq!;F+X^f1G}v}-1*Y)JZ(VJv~Q8tDC*u7I_0<7hZz8RAZ2obw^}U92=l#DKkS zvgkWeV`IwLO)@m0$9&~8&}sGKV{o<4P{Je!Ui6VknsL5kg;>WZ?p6i`q$;IKiB*D; zDE)BcKNOxh+utxQ`+*O%3?cs;IxF!R>#cX2Jqa0#E3W7!Sz&K^7j3caz4VwPp019B zDS9Kb5HS80o$@+5kzmpIcqAnf=u=X9<@b-HAOA5WZZH_*M~nT&{3h|R3qVR*IN|Yo zRO?P1Qjr>Zyr`@u!3V6Q&S}`As!keZco0}c6Qj{9HlVl)ZrF}2FZAugoxuTlZ>%It zOBF>FSJk?{f?D+Z$(rkpyBEi%y=N!(9+jJb2$0i{fV#jcHMR-#xDxg8)qO4g{C^HP z2NsV`#v)?3dl&bF2X8aUm2&A1*>yj~8b%Vl?mw|&qkVLAJd>IE)cS2-e4b5xw{!gY z*CW9|o3Zt+tNjYeg!TgNQJ&D$IDBoEr>dgR^{0h0rIoX_39&P!y$txC9HiQX<$<^J z*TDOSd=Me9_-ezb7Qt)U^855;FtF#)%4cbLh}jPR=-ShH%|x@0YhLbGQI=Hu!0*G8 zQQ&nav{Z^yS5SY{e3VX(TD3G&clYq423?3O{i3C=oD$sPrf?s#n;Q*D@Xml#@*(i0 zW7acoPXfrT%UPYQ-9;pjw*@By{Ga=$;>IMMPI;Ry9|!Xxm(%fy7|)e?HXtX--L)_5 zuBwUF)nbz%Y!z>&DYOmT$M0?9Q$Fs>$RJtj`oW+0M8~~B2-BYfWusYF&y?5P z{K4sTXEXk_PXEOQhEfkdY~EH{gV&a)g7_mJrsY000dI3=6Ug_* z{m{oq_tQum2=#Dty{AXFN#RZQYM?k~)YV2UP8cS_3LGl>o(L#%m_Tc9!EsB1JQ^h_ zdOu@nXN5dydI;fT@s?EIetc!JxmEzv84R1l|FBmMWbptyNVS*g3jmS<6Qi~2!VB@k zp*BCO3hKHOznPW>h)NK1zS|?VsZb%t8%vNYKG?_W;O;3oj7d|g&evq-6UoyW`nTuH zm@oIgDLL$e{sMR2NsQ(uu))qmlt{K6pBLs-4qDd!;A>b*DG8lk>*aX92&CE=2asGzXjio_6O zhdtFGW@dAW#FV^9 zqLnuBKf(aZBd+`+Dpr5nW}%m}Dxl-s28)E|j=*OYT`j%aNzk*q52 ziJkHGS8kv>NX~`o--o404-HteuQ_sxDKRkH>PF#C*Ig0X5;uPjfsDE$2id4@ zwvJ+;s$5o|-Mi~cq4&G1Oq>)wT$AClg>*jYu|#DH!P;KUO4r2`ToUUO z5LRul${u@f*B%f!hw$^`)bV=spCUUShM_o4S_;+4);hjgc~hEOv)5BirEJ}7t$ZjE zXls9oInlM7laQsuQ{kX}UQt@)AlbgsLt{DxlbE8x-kuxE|`60hvw_)d!y+Z8pn8`*#xW zqcOIQfzb{z`;O0fiT8ZTGjy^$E$#7c@w2{h8I<_`@ z08*B_#wt;L3;m>_aZt*os>UUT`!4e{-XE@ZDtk#GyG=d@MCDxZ-Zlc5tK^l+g{x`v zhl?%4pgc`3V`Hasm$yJQrE^PIK+_?h7)@G5!pn->PRnhZlXI1nJ4=oe$mBVXD^T%y z7vBC3O#bA?@=;$XxSdmCh9zyvqN2i+OC8P@3Y9a7S7W6o0-e>Z^V79kUW$9<HE_%r)364w=>6+$Px)zc^WA1{FH%V&PF@$4mS!BTF0 zXI8ZO{FRw*q|Sbmqq$M;Vw$F2kMQyI60@1*G!^^f62v5=UAweJ5#6O|7Z%BV?(Fx% z8WAi|&y>2e^9VF98FABYPn?AE7ahctN#p~c$(acejd5u9b)kj^h6#QZm&-9JzTAC$ zc;o#-FX#qE(R=*ACB}RLD|!}ryU`;RT7AaQAmeRozDJo+foGr~qyMeVYZ=X`z~^>l zib$alPexXFolpM0?($oU@Ldr>>jw2lo2lp1TTI>Br2FhAjxuPEP5r-FE?a&-aO2C2 zA2mFlcxdg%ppp$sAKdJ7PzKGMbmO66a%05ynnO2@dT z6;Fp7z-l{N^xYHDd}{HndVqCeM)}%0y`4mkdOoa3Dt_-h>Y-v>Pq$*8CDwUILc{*0 z&aPq?-Oe2BL(A4v&;ybAN`#B*|D`wE^UbY=0FCg?twzQTO#F-3;TJZ$rQE2#_y*`3 zMq&Y+=lSlf57SB{YxIM#org;5_>Ahtj4bt}qKv%aj95M9_rFk84UI8>oo~DEKI*9& z&T6|0s9?Sq7yEg3F#A(G@%}bLz=gN@-F`|j;%}&70(sBntE-(^*#I$Zq6wGyW%?jC zcpGu!pJ2=BSX)oGQco!KUpA<$Q$?cj_vrU7SAiAATll3o?&G3+2s|p5Dz&mgdY|x3 z9B=1-CylSTW=@On0^Fq#6&XNC1G&LGDmBt$f*K&XWe3yk*xAki{U8JM@9Cd@Y-*1B zcKsd?{Oomjcf9YAwvS`O?tINf@^Bhs@jQrtbh5?;gZ}|QW1)^|6(7J@ut1@^-+bc& zUD>EF1>oXuXWxX09-Ueay4e(HSX)3NL;l?-Kn1q?UB0?#no zvELbW)=^nIN@|uG9mjl~wik51UYEd-9bUD0l-WzhA6Q{W<@}Y$8&B;tV(KYGmv>^f zGrEL0FVOanln?wL#b%us9vI$XY0&RDLf>#B=T5`Mk>& zi+L`%g}yd0c>9WQd-pp)%$_vzt0(=13dw6G)HMXtTUbOY<|*O4I@@%s@8)fRvEC(K z$ZEENZ;XX*FrXLnhqQM7IedpW@gqy7%0Q5yL6y6Wp0V)z9Mv5KTf_ zzjjkwVJ^`?7^W$rF>2P)UPv?Fa@P3q>eRUIU_~b{GhZeo%pCZ1FXu?B7J=^sA$-`z(0Ux03u1-|`IB*Q-eAy0( zVk`dEw|HXY@OjYuS6Nlua-@Si#W;20P)@YM%q5r*@DBZ}K`ER7i=VGDs+~`7e{O*& zMZL!a17r$?zx9V#L`Co!N6yZJloWKU8O+jIW8q`8CW!Vr0OHsm(a+fwSWoj~!1>#N zN<`wqE7Bk*z0*kenpt9+9lKBw$h$nIJXSVmg_zE|?$9yf;FLjdKO+MJYw;z@RKR?N z>VPv-rS#9N1FmvjkxxdTFA6#D(^%f_$JCz~%tAlfS#YfcAbTu^QxWY?k3tSultT+w za$`oi7l|g$NA;R2E5f1&;Mh(fZ#qJ{*egcAfr1Dj}nMGZf7I!iA zu=AYQ&({+gH`fATXM$fiNgGe)#_r0M^m+ww%}fZe3B}-G4qAfamNh<)9rQmf^hL2X z4G2_e;pY+&fzJjcD2)|%;k;&t+E{O#*RD*~nAA`}76{+wggc(A;X7V(sTq~(y@l-k z6H9{iJA6O9PJG*IBJ^T+vE{zD92q!U3Qs8qR>KT1Pau3notXF;*5AAxmP+?~gC5_8 zvq9a6sAlNit1Z5;XLX8akc3Js0i*ttw#gnGLmYJJFj9(BArgb}MG=Hv)%oSP^I|$L zfSEIO)WKZk4;IZ!;tf^DI8X6+e$_Wt3=-Xh3h+yC=zc?CMW1Wh`ejhxa6tivrPK{? zDm7LiEkrhk{|bx_Xn*YmW<4frNzFs{b8a9_xx-E)lhR)BO+U}TnB8W zXl-y^D`Et>d0M#K9`3)W{{lJ`QS!M}41Il27%h(XkkR$;9Bvcx182;7Z+*BTp0Ba5 z3d<#pk~m{X87{@C2i?P6t>ESHyrvvf`UZ2o7)lk;mv-&<9G&$Y9eqF!IYF5>tZahP zZ+J&bVc8FbTB*=4nTX18qvlBO5a&A!jMBspX73e$jSL+mS zHVIWD30m8Q7-vSBr0urIT+j!`AZ<2`jC-YcYbRd#z)ODxisVE7^2=X`X}kh*sKpcn zu$4sA0AKAsZTx zS4l6T)Y++NfnC(kSqifEYE@k22)?nw{m)2OR3%M~857FORSXh|y8}G)m%r%YHh~f~i4M@# zB=}Zxv@GCoFJVz!%+{VnS&J0nJ@H8>sOmJ>w zgOF6ynfonCf2wJ>9r?O%caY)v6cD$2K;MMq{VG5M-HAN69gUo%UebK2W%5Z+R)Q2c zl>^(bhrOC2!8C ztC>Ot`V@VtZ93oEpIrZDP}}Z&qNdVw$GaV*fKquUy|I*x?cHakq&nA2_Qcg>tk`-S{9u%1mCMPR`={*{>e*6$+q$$n;*EPQ=$D=3a>28xoy=Cfxl8)e;Lb0T z)sq8&w|@{tk9AkP4y!>!o7X7XaZ(^DNwhZ^{lAL43wa8IBf$lB}|>E;=tTF%cYsr2@;D1yjMXHfu-G zYyICcH_q_4?brCHpk=JGou%TW)}~3Xk{A_6OMikyC<4iE)Va3}>jE%x@~*20)kRU; zc`}i{o_~6eU%{e9Zl^8&2m*y9b-v(m-98!ple5S5ozl_|kB2q0ITo8k-P4L-I5#D`?8v10jsfB=j^&93fp zr_cM#o6U$9T%Lxgxf|lJwnMHa25t;Kk2uPatQ@ON@A-M_f|i;fz(r)g@1;0>JI)t) zMe+x4&R$CN^667~+si$5Q_~{$%OVfJ&N-#)4%rCzt-1KFHRK_o$E??$?V_~?ZN$C3 zV)5iqbY~z?`#5``rB?iw%9GgReDmx9|TMwxme zW>y?_Ja*=ljra&59+u3>TFH5nB$v@&D*rgGeGV2{(>rxJ+ckUSvYuPOsDc6XUQBL7 zdKI{lS#~{}PUHZ?&RfP+vtvKDcwFlKuWK_;)9oR|Wk(+M*YtmijXOP(euaH0wbUqA zcLKf~0jM?0%VY00A?T=)DVRXB;}08g{oeL=wIAsWHe?Lb)uXj=_hmGp!jE|#e(wwJ zuWmYY;&omxc`o&Fd>1KEd~z1jC!#oP`*=Uc8^W;^6{w7~;L;hZNEx(&vF6cf^$fu^ z19uE{sVN$f2NxBb><^e5(O{*?=QJ!khB!snd>eK6=w_Tc<`d5d^B!fQs^ZqtE=l5a|VcQu;u z(|gjjf|v9Tsno26fFEqLP-MYXY!Xpo`AHA~_RWt+?WHTDiu#Jpf_b(1qia;w?`q)$4jp5_iOFB-4+SpP^U07e zRt&3qIBv~uiceH<3Tg4yPUI%hmV4|+UjPldOW6tTqZuM`y73;t<5+F)^+TIGfx#du z#Q2uhouHzMd7u7BmU$kZZ4|@ziL*pfA&r^Ll^jqWh;_|8eUI`&03~u;d%Q6$-XMRi zYvd%^A*k7(4%0vIm+~CR#nR%Q&|gyoYKk8cseo((AXOaSxYp`0?c3aF^8q!Y@p6WP z3_bglb*cNgzjoO(yy2W(XSweTWy1m?`(iuJr$Y{*(9}AZ!+QA*c9$yO*C><;<1TkH zx3Fj58DPwyeDC}hlh8s*0 zxn#0!coe@|CeWcx%UH_L%+^izNH#|h!bXO5Sf%UdKz$ojT>d=}1#-~a?M=};`d@QS zc|&2a1t^E5qMRFN_4T^zWC4Id+fmR!Mjk&*(#Y$dW@lwZ5 zc54gn^+&wkV|}#KlRR?)jdU1CXtwT1@74JV^tw#JJA+shZMBAn=0MP03*LBV;O*~! z%oUu`FH@v)*d=~ChEi}ygdA>!m5^GyHO8lC--Yg6=K5tAxTA`=fxt9Y*sU45)^*&I z!1k?8%Htr9skXuPQ#;;cQktZaz*p*MxZk;QfL4 z?7#A!lA1^9eM~Gd0^-r%*KghZww9v>d$shNixy!OJUg3R2JFC?1DSoJLobQpAS!+) zN9>Xr;NX!OV+$UWzF3VkENYAwGyf5=hk^e~Ri)Ijn`X3jkMGotJV$J#i8?SflYC&r`zZ^iJY&u`%p{_FQm=tkX={sSV$bOQ&43zjvD~t zO4t6Kdss)BrRvys!i^?A;oV1eQpei)nM{-wzWsM#_aD-X!#|J%ibOyD$(Fkyl>XpN z^F7}v)l}wdc^Gc=_Es&-j&I0%gH6KlI3ag2#%}^8eu2c4jO)V>y+fkB?GEFv#RN&S z4U3}l7*UeNbdaTmV-7N|NrS(?09NJY`bUt;YQOg{6!Q?odM+1_YTW@HEz z!z3h>utG23%A)Oo>%FJAb@8u_)oOQ$YNMy1`B|Kc`TcY)i?9O=AbFaW(umU1(>x#> zeyJS^GV%YHhv=_yZzaXe#|d|!N4X_`aj56-po&?mhtpn-#nk((-_`A91FPPLrh*;M zVKro55!pN-4b&u$E6Jfu+Io)dbL&z^10u4!l<3);4C!rF6`n{4=%hOqQiqj|K)c7i z z=27wZ>gALivnMa&6oU&rfKovtJl^Nh#$o>64BUXQfFR4f-ae~-p#U=Ti=x*cJGe83 zdLiMdl_zaWiE{T?W?FBLJT-8QJ9_y%QDgRMsQ~|YpquFP{J4{6eB6i*bFMTZWV~9h zxeL=FvNaM0N{e-B9j3NMrvc(~{i86wT?PFzgo{YvS|or%+(Ei?t|h5)+0HmtulF|d z>@u-eeZRaNnf~eDb)1)-BEFO&t1rK-V z-ZdhiVOnDkGf%Ack7(|h-hOB~!L>faW#+kWT=hSJ9tbniE)Y=^yxl^C+_6@0h*J>_ z$T_pIrg)R7%PMPYr>{`sVlv<)nPQe?DAM5=?OvF5(FlI&QM%(D1NJ-y=05f+%Mf8h6L{TqbZ4fF7^ zTG%`~?qv~aqW()1YWA=DhBgSS$?wy?#(|0TH0##NOZNxWU!wY7A84F9E~wAju%uFT zOG-GU2HV0eVV)%_8w^ zO?Ak*i0TtbiPBw%1uNWY5WB(b9h;=>cY)a58H!l?>gj#?^=Mjr$EVDp;>c?Mmg9{e zKYvQ<P{Ag!Iu09KqbE_V$);;-F$mfE8O^%wwyc+~ zk4z!8%Qo&wS8h&Z8fg!kQ*yGsUD}G<@B1Q=unekgjjOdJQvRxa+k3rRcz7r(41k^* zET3X5>AOAIoHHA^rLq0)F?&tQYUE8DAKM|-{>ZxM2T$ME6N!ZiGqox~Ro z37=zaq>maHFaact9=CMs+sR*k8 z$09RL(AqH?1-J_~8(0IWfg`Qw&fxOt z?H^7xj`2S7iE4Bw2<0gp=FE^gsH{@u=+D;~1eAsd+UglEtJvbBh+!dpfpGrN508)L z59|OK_ZyPmBW2hL8X9Or$_~=rq?}UO`joAyV6=8f&1UEEkLovS;o|0G2OcxYfV%i; z6&)mM|0*2)yp1n2YR9A{;=O2w_I!q}aULr|QD?P}s+0S-IrwZyl7SXrXyi~82o@jp zZP!C*vLplATRowvLAS7R-IUf(Mr zRD6{m3)On`vS_h=8Ef<4+xck<`-`)c0TI&TUCAy{8rZc^gjRK^e5tNx$AFEs!ky(u zJr~3m2y1(3T;;ZTA&k=t9GJZEHM0DszNlS4gO^9rj{X&HOnkL4opcS2+k;rMXyHQf zg#{9Miwew{n9cRVdE!P~y$6iQcg>G-{GSicR262A$`>xk)>~=o&uF)^x0KJSKV-gI ztMPtt=XXZGt?J#+V-UJ=KK)tT9JZ8}5w}24_PyWy4KICCSdfr0Fu+L2sltU_$lxS^ z4Zpt}%Yc0?1ESam~7-xHvs%aP*!Um77l$Gow81l5B{D_KKvSFqA0O9)?Wh2A^`C19|M`R40gWJTjYe&m3Ca2}> z@b8(kk6mY{Sbr zRIzV}xMM<*kB5EdiF<0Rf4W>e^GHDUL%FU*>S+;sM+h&XEFikBI&`KjRBww9b%LTl zY7OcL0%JQw8XxmaWZn28#lPBh0?v8ma`U1^)e5T~-|H}rug);Vm(U4f=FN;P1r8+lvb>+M-Z#HrN z3O^*lOT3sit7ROQ{Wv|d>U1L;(*G$Y_l*>~p%?gyz&POxFv>}q*rvcxzY@Xlor)z=O^U_y}uN0_sda|E+1|aO|Y`F1N&rtFLk?YM@C*5Xa{d@ZjSn(qJQvw)a{0$4eig9p!_I7S!9tZ zlAZR4C_xs!CsrD#;Ej70*ntVyPXCL5mj9MRNA(jYp1H#I7pz!{tuO+YYb$99Uzx+o zj6jUqsK3>T4F+&Sw1oAyQFM-Flpt@l58c$kzvug?HBL#9HQnjO#+s+UwK!7uEK&TIUIQGj@(Z#&}p$)pv;W z!tbUALa`8c!WqKpEF{Fla7=mf##a8v3&7PR(SG~jPW}T09y*)hVfrXP=RG}a;E&WH z*cxYc4xt&2885eT^ZQkiaX!_e`HG5)(~{Hs4v)7!C4Xj%^(|Y9N?V1m%iXU~%0oI6 zku+96bm11IM|neMJuT{&G@nr#9uV_+a3UHo7_WO(7W*Q^k=eo1Ht0`hqcyIC-|--V zY+mzC7sx}Oulf2ccticwPd3iv1=KKLVQ~I@0z)RPax62WBpmE7p3)<}`eQ2!QX)1h zknN8dB9^VWy=^1{-%M#BuCO9U>#Fgwxhr&UFhMk5v+qh?>#yC)a+dkETcd9Lo%;RG ztj-LRudwuQI=Vmk#7>kpRn=I^)3+6pFDM27Iw7k65SOZp>pSyn%-a4WKMNH+B}{c=A!R{j^QQ=h^PF zk@h<&2-nvxYJSIqxscFzeQIO5dVqiki+g85Fs>cUwu&&GA46`ic$1Qv1#YlL6R~;o zd}oRUNAA-D9XIqY;pRz4>FV2{mmK4Sxn|mg5na#?&QLb-6o=rfV#5#G)N{Gppx|aWkqncdBRekW6}2_Fo#qr0`~T+Fq(_(0R{2vK8yk~jV=<>W zIMVqQcz{VHp?~@d0LP6Y?#Qq~-sJ7C_omEGHwg9v{UxrN9)}}?LeKDME0<<*G2Ffx zOo14AkFya0)Tnskbsx(&8W)E;ARG8;5xytCf3DNPmPGpIrk*z@U03EOc25o2w?5Tq z#a8AA3ND z%ORZ&@qawj?isvInbz1mQU3%EdzjKOB|tqt7$HZXLS3`nf4y+rhIcX& zNwB>^AjtJd1>^G!#Fl?J{9(zKGX5U^ph+#24e>M2lqbS6HD7F;6^F^@GJ zZiXF!hM^$v@K5GCkLRm0WZI5D=5WY(qxPP}%34(TB=&$SfJQ6e#^p{Qqj&U*p55Yj zmjv50Hltz6j65J;rtYk^N^k@$7BZW!t}(K-Gpb@Q^mb`x18!hsCus-|@9^Z1I#u4t z;748j)eWk#0c?zFUH425t5TNaJ($Wn$Y^pbzij$;?j9~=O)qL5O;&SsBD<%CQPeO6 zsqSpx^pnWlFPy?}?Cfz{T_&tP{D#!hzsTSpbQqoB1)8(#N1+sQ>+#_cr=n(M1@@ZV zSpM?Ix<$%=S6pzHY8$VuN*Jx({P=Hk5V~4$=Evf2$5m;v_k0`Iem`F_g0etj_5fO& z=(v66?g8Bwqm==Jf36{iMTH*o9NCNW#*z-_l7;Z)@PJ>9hNZt+ zoCnVz^>sqd@nxqfEq^GeN_ExW*kB-7v>uy?1yN)-bkB&{tK@ih4my9jLK*wi39=tE zxj*5?e32}H*_e1^;H4rDWy=IrK}!aYKl+E2fG#HBvVgbA)5zXwc2qGTQ$ZMVyzvxL zK_M2$1N{W{RRQlwyw_N-ZwT0hZ}b|R?6cu`5Io;D)xO?0!9kERJYSh)hbq#?5)5JU zdh-7Fei5f^=0`TkvIU2#5wgL3D78AvUQ9ym;es%X%_xx?lq9E*c=O1~d|o#)@WJra z2}6S$7(}?LrA-w9HfaW$K=>J^0z0bXAdqVNVY~Cpu<2} zd^~xlG{3mPA-nO?SMh&js_UAhyX!RdWVV}yVV;Q=PN=gd3^aj|+r%%z zL5Q)F9|2CsBvS%s*%RKpJ#tqt7d9dmS+b!a}Zwj(V?GKfB@SbTrUe z;y_bh`q!&L(oY7TmgNNZdZqMn3diuf5p@21lud6h?YyU0#);!)!F+?ruE?t zw@wsFbua%6pwYRpq(m)d%Zpc$K%rzN&(bwHXIJShvw<~%`t12EA47^O<3!1(hoCzGunjE z3)p?&pmQgh@PL`>i5Mf2GCylUw6))t%n&*aAqS@_hYKyJxTQV(muw-r1^9tIv*pdu zUDzVO4-6VbyFtoThsKL~9|C1>=h|0?i^0kSsP^9s!kW$X;i)k2#GNZ8SGVrr`AK4vBsfmciPL{al%-&>RPjIF(43veWHkgar4L*AMi5QTfs z8(U8x%G8GBR{MH>EjIXG^~GfRTig(=CQF3j%`cet_5DjfsOU{`yRYkQd(iZGcP%5wJQaEWMhIk(_cL_+Rl7tsLa4 zUr90%(MaApeshIhVEV!OC?oI<)zsit`wlMNKe>3i;%1Y@J#h+>D*Z15x*gTCr#1pg za+MAHl-1?z#klu-t^ce~(mC0~-{W(=vM2(YYzw~&!JDU-_MaUPM10W60_3qIJ4N63 z{$wXce_&R~j>h2z$dQ0g!ZkUnAKZg2MsUm^eKJMx=&ge-h%y`4&jGIQst&jm#4dq% zL#E(2Y7gs7M*>lnE4)UPX1;|3m#N;MhgEwHS=i51!KZU_&EAqebAM zMGj!dH-NgP{R;IY>;8bZA?=)Mh2LWU#fZR28yYBtGQ$(_p*x7G@GD3NG6YU^V14IT zg^|b5_i=gnz_k`^Ur@iD?BRYb(tJ9lozhv=)%!yA@enDg%|oZWIU&VdK8AJ03rdQK zT~JV(JHF3}l$jq90&JRB%vX zdJwk^dRUcY4e3=QLmwX>9GudI0 z8uskIQwpvUJuYGSne2h9Qo?zudc7-rL~TUN#P2lX|RDWiDNS- zeiA<6>51uUZ2H~w5X)q`4#nc5&c&gf^;Yd?PAhQvrD_MBz&cza(|ToM3O?1r>IvY| z$$Lw+X9E~|8})d4+XVh&+X8r3#A>zx&}-vQGLMu?@;i+C?YU0MA)yogLXj7lo7X)7 z!l%d1qb}qi45R(f0Wj2yL)0y4i!F)wuSOgMbaaa^l)@EoS-`qZ_ z$Z(JkSR^>89b1r(AG#|wS9x9%9{Mgn_oe2@TJVhmkB+*IAZ+j##FembU1OGJmaM&7 z2IzD^Laaz5(4j;<^)j}9Z9nYzFiULS#D^qxio$Gl#aL3nX-0ty+pWZd5j_Cl2aM>g zjZleh@z7Ok4zcP}my{!)NRrYO`@Kb~g$IHr$?81(b072x4vo5GA>cs!1>a#$T-P1Irp5{q}b(Ex7go+#?TG?rm&*BSs3{QrbcS3B{KnJR- zk9R&kqiweVKeMk%ZraZpl@wg$YZH@_lL?7Qw}G4D_<_h2y{?M~I~&!)V^KZAkBm`8 z1~~%*wKheR5E0vCwr@bi&Di&hIP0Hndipp2PU*vzTzCfKbd!=|$p<~Z2 z3H!O9QInCqzWInA&050>wtt0Xc)^kcclDSqYW1Io9GJ84)jr)nc611@lu12^Lyst# z)Cgy7SM8WPkRtT3O8*YCU#f~RO#2xpgZDNhPa3Y0+HKEV55F-m*W1=+GpqaYN z5?oC)NwJB@y?1byiAXSJU`fUPmWSBAHQlH8u~2UdO%2oFJN6Mu)qjkbJFJo%)`@Y) zn||}am|-2-1xj>K@`SMg+fSS0EHcLqa58y1O?+0*>CmKzJCjT+01LCzUIQ)T3*W49 z^(DI82#DwloWr@Fi$9O#Jb(2dUQfd~p@mfa#>2X70G4uS1G>e{@9?3vbR>_E+cR2p z4SbdcZ&ZrFgFtzjp5F%qmnfH+df|UP&k`fHjyksK`ixm*zDGi+8Q!6bjh!$ei6u** z!)W!m*3G}&GoCdPV2x@05&ay_MuxZ$5pdMJddpWRh-R8}KrS+Bw8y5y5$RukQ4ChG zF1>TwDCh1$-Y+VjS7H zl63J*->oIqxG@cyI;9w{SmpqY$1-sCYNO3tIAq_mDJ$ZrNy69(7kR*?x-O^`#f1GE zRv2umb8w$3%uLmRT$w?kfv^uDNH}b2d&5NNIKeMDWVTBDQFsZtTMsc{^X-ZB_!vN-*I{5c0*nV4N11bhdz8aN_!TdzJ1UqJHd(g|1(q73R_IhjZ`O zjzdz}&qcLY4p>t5WJZ_CR`LF`84^f~O`aJwOtul3%sUs6FJt<#{62B1=r7FoRxxV2 zv~JH)f)1}mDNon>rW>`dO+FF0;-TD&2UiGa+*>02?d20CO( z2#X3rSE5;PWzN_(lsr1qcZa}AbaXtHPB()lLs)AgBjfmw&{0O453XM^NYw2d?elpF zjQs4udOR4+!Qem#`%G2>S%5d>+w>vn2j75W9B-Q!-q>$Jut_}55e3}?i^;uwdt4-A zs}40aY@0|c+zx|Pkxdrf28z8moZ`d3Lgh(s{Jx&L+*lu#-*B7hDRFDbg|#NH101Kh zKVDNj7g9ehd>tkrk&)bm!}%e9>KSHtYuuE zv3ppnWkiPu7K9~vR~H=orKF;*{O8@XLgtCqZ>t4SI12n(JvtC54-JcP!h}`ZxNKl! zFh9>2y>>it?KCiy;S-_jEvUU?X}B{Vi|{Jrcbo&o2)N<+^@W8~+M`Mk!^{-DW1 ziuT~7NLuel2MZP*Ef3_8V`{^(SbdFt7oUz;O*2P#5s$f;VM}%=jxyXlH!o>5pNcxl zy~Gb~;?_c8A*~YmDUE9?dcW6(+7$G$GTqKs(1fsT0X64eYWyG4=2)#ZnZ@DxItpZK z5hQPnZ)C15Pfa)k_jM}^A;VQCZbs4m&czMbIl0z1EcaSja&-3$lkwVh#_st#@Z0GO zLCMxiISfPGI>?;_wN6mT{SqaYQ<<0l^D_Z&2fB(peucwx&9^>jUd9GBo=;t|?x;E} zu<#phBZ_MMU2x@ef&0{TpZHxp-lO_&v)P})8*j*GVz{?M@v?Jx7aU(*O@6B5>mTyl z@U{_rYeTkm`xubIVKbXeragUEogN}pB56{i9k3x=4(#OKgW0^BHGu2;oBN`1U^caj zWZE7$L@^MghTm^)QEl>Y>R7c)H*t!&8?K5HP+RAj?Oju6w1t>PPupG9jP6d?>6L404^GX@plBIiQz;p$rz;^rp%&N+ z;n(#$kY=3&)AfWdj1GQ-P+XlG5H`sF;6ab+t)u<6kkIO5etp<#IxPA0NR`$NlW-b8 zNm(jt+0VBs(KRw-;5h%8`?9T_L!3vN{%WC!#6(PYZ8sdypmV z8WO-aTMLJl)ys5q58(@D_z!9IcVBuAnsBbA(d_@!(AA`N^2M8|m7&4u7_Vti%h}*X zy+vaK8D{ASbA((B2cy~op@;ha{k-=kW3*${aNS!AV1U=1Vmb2J$ zm0)FxVf|H@w5f5cCGo3YK0%Y?`}2O|jg4&}cAyl{;Mpp;vqrLS5cY9LvAgIzwh^oJ z2v*i-Pt?N^z!(x>q%*3@2HTD8)1I!=Fn>x2FM)-pCu z;~LAlm-%80Pj4QlIckhfOou(K8Nz3m3T;PDpZ#%}`OrDKJFlM%ndX%!iBz6I4f(6) zo%;rZH;Yb_`Npn~H+qc~oTsP%fJ4WA{Fs?CotnD(BvIsn$QP@cQu>UW(!-&cYR<;+ zZvnZCqZIf9muznXB)ZXR4Wf{5^)=bpP#IFfb)d2>!mG_36pZPDzNP&@65k)r#=#DH zhpM*enSe|tQi9soiG-_{B26`^1^kV{-3u_k$`8!S@&X5;P^K6U({Ri^_nvIPDnZ4oB3#es+)QLr38r8MHE19N6Hk}`Ulzgl#R z*091n0Q#A~sZN#;S=nBHYu zWWjHGeRGZrnVY=_Mrc2w#XLjfN4IajBxA^}pep94Df2&#=7Y#{j_sGk9QV+Skt(A- zVmQI?x>|KeC_aHeXzsII>Np2@jgL7EkuvIV#FA1&g94StN8xPy2wQRfla-ZnG=pvG zF$+aMF;a(x0@E@~Icxbjjl-0eCc=>CbZ~R&d)PflvpEmNa9+iI~{#5d0{_dV|z_@hC9=>dx1=Fpg~r`>vhh3YCiB+ zqMXeHFx@Wiapn3|>7;u%?>wI2NM5rF@=Z?{*zqx*J9$q*=wO+Ci$BXR>oE`3l!sqR5c(7V27FyjrxPi`KY&k!WH4zMjJO zaEoBc65*qPVjCas{H&(Umb>S?7qPD|&b!bqYtxl58iU;IyK+9F{9&kBufs~m%DuWl5OK<>^Rhwca2N<%|yPEyPz|2h}~HCnmPS#&*0$V81!Vht1K2<=Z0?vRTd~97Ko0 zI2lO@q|N-+O33y5ml1fKK-LmtCs78G=K9~M4LnW2|p(d4+jG4LlN>uw$PfXe#coXR?DLS`jfATL_}8j;;C3*>UO-5p_Dyd zFD6%2M-#gC+cYsD^xC3mFOO&Rn{5#}g5DweCsGujzEeKaew6Tt=O@u;C8)>D!H?FS zZ8AVdIm}VF2!c(yQI%`ALg@_#7Qa6e74##wE8UW%wgnmLV*~p<&147L#56Rgpmb%M zq9XE$AFX)Qaz`BQU`}Fs zpGLGPMU{l<)vd~P&>6V5lgBEX|7lM1=6y-OGeYir&l>gUKg-!Km5ExB5q&A>;NUmt zl9_4Hj_`-l=z8La?kTNvvGErH0!c27#128tqT~!p9BuuwZqT5 zJ2^kU#11xQlr+f?bHo;>_AYjds;`f{>^)?QGdcGe_YPz`@4TMl+AC^kYHaz;Cu&YL z{%#ADP)}cZG~gn+pjs3d;fz|h^mG6R{z z0nvz{j?TZ>>!HGl)Z^f_Bo?1llRrntVJ2TSIqx5QW+1V+;|kTC&2tgl2p_8vnu+@& zQws5t5-$^;5MaCNtxI8g{fgE}(XZEqk1|!+21V9CLAEXJ`*mpGIerM}M;-dLfQtjG zuKm~#XuG@6&=G62n#>3E>;w`5dZh@720G^`>8)kN(b(wF1Aq*~!G`;^^4nHqGuXc1 z4c}*>xIqoG+DQOk&BM+n=p_b4hi@^Y5Q!?fCxG86VT79xbFaLHh5r#dcokExYTeOq zcXK`#AC=MN|MB#0^)JgAMts!lLhK6`;0{3f^ZI}|RrcU_VZ>B!%iA|2A|j-lcmN3l z;&5ih90|{S?GrgY0HcXrBKOvp)LPs-P86h+{!%}EQS*Kv^3&#qn zq?~0!g^n?k)`jHt0n>rpO%`Wlqvu%GzSEHtHHFQ|Vj=H?jfEnGGtpb;*aOfB_5$yY zcqWZZa@^U32|gya{td$QbB37d9&s@e-Se=mx`07|GJ?8UCn&J`=YewbBTo~GDL#Dp z<(tuyyaPd~;|l zeC&u(_u&Ji-Jx%*eOJfV8-wCtCML*kXYOo|)+xQa!nv;HJB53nHIjN={K&^mauDa< za7uTToV9BoOolVq04dN#f4p(Evw(c`OqUx}CR1A1>D2DB^zx|yQN%V!ovsM9iRO?y z$o|&m^pf>zdDN@;w*r~8r>7EM%I{JL110CPMaWQpZ&>lPce)Z$2BUB`8%v{uIM3R8qu*+2b)D z58aTCfFYH{Tn2J&o@i{n53-wdncQ|_88Qm)l9;sXGl8R|b;`FC&sG`ZIYr9tzNNB)1z89%#di$s-k^Gbz(IksZ{Zbi`I%v`+KG=h@; ztNdZ7Tb>gud=O`WLSl6m)0q?^Bq2Jp_C1^YD|6k?3hDg8R~{ryTqCWu$pE*GZb-L% zZ;5q*&_;03=g0-+@KVbYsqqQ6KQQ|tI^~GMpFEA|U-_!E7kalXxSq^1%iweOc5t_Z zbh?4uhni>1F0SmPzAC91CTTX#d6_ef<|Ldo=5t$Yo>k0SN}k_MmaD{n^dw3=x4hwO zLtq^1TkC(fTtw=1Wfd%;yK1lQuf-;|d&rVb4!r%YU;f=mB()+YDUurB!aK{8m%3|D z4ttZTWic5@m)_q|$8U;zv(J)b_X>kMb7mS-f5xi^aJTCxDAt`k(=P*iq3t`0khZ!} ztH8@!15?HpO%Gqkmcy!9=NxI4_|QE1tDEg0h!9zrmaI8C>>bi_tN}b$f0m4qfN04? zmof~5KKw8|l0h@|k^`Qt1La{OCUDBexhBn3BrS1j3^CF|vZa$?(ZEoA0=seTMexnT z!?Awsu%#cEU0Pd|#(8n3l8=_HZcemgr$&Z0hjg^!-DA;Q(-Nxi7SzyFh+tj?&1C*` zlCPe`sn6Hb29&4JA}8T>Lh7(RhNO0dcWheU#V$|PIKuYA&sQvJ+9XuqW-kl>H+%s< zTf55Sm^p{pzlvsL`LjO$Lu5@owQjL%W3gxOlx62)VedUq77f3?n!0gh>n4e6Z}z^B zejqWKQcdn!ouKHmbXfcZ&c%2|mz$#iab$bX)yJrGb$9|LR9!#-2(c9Xgt&6jTbC>> z)EWe5&;hsh-8f12TVX)Fo>L8r*R}c$B0_8(*4`ySIfCHBI#AQnWyE?^SYCi1l%6>3 zDl*|YFUiG?i@5xZi!UoXCl7NkjE(~cXW;3(%Bp|d>6aOiQ?nuhT$twsnD5g|=94vQ zKF1^WLX*9Ce|W=!T{_vv=r*c@_+$^(dht564Y`1BhR%_%c%s)a<4J#PRp8qHwwy4yx}X_-Nm-v${+qGh?ZoN&DOQNY^>~5*%!=W zX3_BhQ*5Ih*ks35iMn6->y8do7O(&X3zG(U1P29b#U7!}Ml>jEfk5Ry?$;tJEDtN{ zAT7Yl87i1uwFFUof`BI2NqTqDi()rOUG7`#iu>+s@W`p0Z_()`KxOmHf;XIR(`cfk zHD>J&y~mY!C_dREOYh^#as~IU7i0eWG#9Sx20j~0=2u$}FKQ!2m|IR%#~U*c@@j>zQI-tS6I~ zQZ-oP%uu^t;m#zlYWa!co&vq0lt_fA%Nq?@c^`kQs|#4%=Vj2>=OEKQ=C-^~x-mE4 z{Zx^Ngmn^_tsm6J$y1LPq28SzQY6 zmtGcm?>B+*Y-j+>NkTRkCJN#t0Y{=Gi-{{{I2J@}#l$9<+@Sjm+vj6GZneqjJTfp9hKdW`8J1woqY;QfYvZUKW%{!9a zvO7j={s)a6oo}A%pVx{OqO{ z#E!0tRPrO4Wvi9{$p`e_D|CN*t7~=!BTIU-IN{t3L2JS%Zm_)3=}DS##^=BgIT=Zc zxEL;s7ZDOD&TJ-FNe?=jor$y1*<55x!7x}MpKQ>p(=gS;)4<5E9oLtvAI>W$=}Frb zl`+N%SXHW^cTA=MxA6wgreelK-3jKX*Dw*c;;(BkoX^HwTvxQVs9W1Iahc&2=IG6DfQMblDp=vY}O0}_r zzFkO8{$GD8Gma_Z;kFVxl|@(0S&!fFv#H`Q*0$U{nNeQ({qXtBx#lSfRUDXN5hQbz z-<965)Xy`}D>`kx1Q<+=K0f%iN{il4XqA@Fak>pv^Oa`Ou1+#L!bl=_J3?c`vl-)M zZ1F5NLO$~v^()S(SCdklbt!yQs5o#PKN*oGn+DW+p#zc5J?i$Xes_RbR~<8t9>!A8 zjaky0!q>r6IcyD}DQ6I|H$O$3qb-NvP*`Ry5Q)FE5~7+Ta{U6KH>`NzkL)v`rXN<4kj)ZK34Br0?IT`^y~uROGds-SA_R??0jrh&ruY z5qVr+Xfe2ZmTP^{h(e$h)ZTG6s9)w+>$%0`S>s2c*y>TBe|$xkn9Pn~KX&QI1Dewf zR`ZhU1P0lKHpHd(t~EOMd1;WARb}e}bQGPWO84pH<>5^Pv;Hf{*7xn8IGT3EU_5n= zi)-gSNlnVQB*i-aDpA@p29n9JA8zGgsh$XLi|6nu%=moXm(-jabg;l}TLXYA2&j!d z$N6#t$9^fxCBQetIkGINK5iM@-c8Zt z7C|@EXM$CS7lJGlL^n@ZzYZQU?g#t{<9lJ_l5nT}xf+L{#GLpj13=lS2q#tdZSgAV z`aE?nI(M=i=Rk(Tae*bjqat2xpCLY45l)2I3wJ!sR_rqVTpA4srbW2PO;j-$B7XBbWkHu?$z3enIE{K7=+tqfur?@?B_q>cY{CI2JoAEo5AP2-&}%;gZT9-!>lm_jo(oL0=g}` zjBDhg)zm!q$$=reQagGgt#zYd*-}zP_lp#L`9iTqmiq`}#CSFRM2Kkm)#mGuh0bRP zZ*<|0;tzfZm?WyLzi9V#8vTuaKo_Rq#u1e(Fo&K@Js@5+%s^8*`N$k*(-14KD}p4L zNYy!}8cNf+D8Oh6{Cgax@KSK6+1c(oV%_mBZCnBAXa-NfL$kry&RDdhcOM^pvz)0( zNgj5$bSR60mqnd#idBN{^wFAt^a8Sjd@5je@vnD`{bcTd?R@}ARw zP6H^w=^mf2l>fMJxtOS#^z7;sNln#uZcLQ^=>*v5#7gy{Kk4wBPQ2lGy*bIj(Wt#VePRx6SuW!hGW(DjOcS8>q`5W3q-^8)?`Wc zOBzc7s-(jbFuR3qCYeL8=PencHJ?3(o)3eFm2cA!8CJL1f2AeyehRFsv~$Y9 z>Z>4sG;1G~5MndGZFtogguK$Hs9ko7vl{gI1kx5J@ao}=&ApQD0>2cCJV zB^{-_*!J!!pR2z(i^t55N(Kb91c!{*HdEqxTT`o-2QcKbpJAV;-kDIux4O1mV~_Y@ z3YvPeHgWeXtjq9`f<8q^OfU&IW^DOz-(5)Rkn!*qON$};N4`|mwRU6@y9K!yc`nQE zVh_)!%h3L)S@g1r?t7A3#G@o(+*^u1C9{@%xolJGuF#L!2^Ck7>(_889P9G1Bov5m zQe_&lLUx6F&6GnhVkAv%b^>&M!@Ya~XF%FAQF*|~<5>^-EmTuVQ7D}WgYqcHO zDVFN;PGY2{#jDwFFEfM#Bu&Cu5c#@=O^4 z=_p?jWZ6o3ey50mM45(EMv;>ud{RWiM}W)9j)iP=7Q;}RnaxKrEvjcYYr)w*HN}#2 z!fU%-K{H!iGlxsm(+@U#hStt+jK2sort}3oOMtUH3b^hnb|<^L!g~<)AJ_-7(S4@O zrhwP0d&K&7#wYy61r_Jh3FX6r z=K&H?VO=d1`Wf_&+7#jW<)9goS#+^HAhn!ft6uGtZxVBpMCZcAJGyO1t5{h!+eUv= zv2l{XHmN3iO37f}ZY&h**<2K~q_yge+?c%r5+;`eQ_!1WX_C%H-wbd?o;E~?jcmql zx>b1nBDvwjdG9Ia!4<$&$Z7G&IeX0Nd_ps|rlyvG{k8YgABea#y=7wVg0qtQ=J(dh zES9=Y1D^rG2RwF`RtJtP{N;=|0^VMeraty&ej5*XA%X}+<*b{*M&1OS=6__9YU}ey z#hc7^Y>#JZg3l_oz()=)`4<)!pU(3fGh;SSHNeHniASSnByG8Hc89$4B;pTQSCIy( zJ>bLQEJk2!mSDJU@)9{qJ*Y9BjbxLX@b)Tg!6tf+sgTfL-`)*s#KCgncJ~ZD7cTP( za#&PY_~VwW8&9YUa)!Oa)d^aPj<+G~igi(?gUz{u9nCo4L$iPa&5hxsAp${>icj$| zDIU@|642JEjOnpQR>%Q>$7RJAjvT7hbl?8dUHlqZUKRBA27J}mF!ze_n{d`NZ)6ct zVSDhiZgg<)u>!uO?0fVTHQLiawNo7WMXguO6>Lk;Z6iBvQ2m+RgbH;8n z7%3m+mQ@_Mc+nf5sNnZyaqA3a&bSdI=P$pDs3{NRjls9#i-+B$L7COaP@wFGUd?@g zfO;+=KIGmJU4c&O=dfO}5caExp9V?S%>#~Zp4kyRk1O!8<_~3$Xt6*!%#D8njfo?^ zwK*+&PH(bji1rX?nO zjw~_n|K6n#9k~2UU$CWQID<hgk9oUY%IaQ#Mwx?=Forg znI8YlY4F(x zSuyX~uOgGew-q65WRf>1H#-$Uuhi;Taq&N;IZZ?A@;n3A*wEJkj7J{czw@cPdC`|( z?)9%_7n!qcJXzi?F1${KTH;Bn4THkYm?|#!aLZyWfjXk`-n$MYK+>&ZVq&H|&SJBq z-5W&7eT3>}JSzEvQy8p??fwTkE8iLzm^LRUdS}|8^p$a4p{Qv!wtJT_N%Hg4uVpdi zu&_SiK5xI+X!yJbiF%e+bFq0sy zwW0=iPQ6lg5ny6YJT<{vx8Ham27g%_jJxXkN-|GLGzQBkp~y-#7n0u^kW{k%D;_V+ zr{tK~@iZ|3%pAl9op7yO8@R}D`;$3?j-!UBYBilQd}(@rT>9ed{0feUjGrhxus$aJ zH5jC++hukfYH;`XXZ%}8aM`pviV@KM`?63hgkt?D z&_7zqw;qovKw+<&pK!<~WPO$rulu=csp2~-JLFGDk+#wDy(rW^;6~LI_Up$1L%LCo zMvdG+#7?ng$HDTN^02L}R*+`OJaFqeCZlj8lRu&ruf2ATAb1BX%KT-oT=jxE%zp<9ax^U&xWuYT3QFwlNb^T^`_m`G$I0V7v&5|e5+0SQkn)=L}e~;Mo zh#KhnVmYnPwL14yKqgC`vovg%S|sC2NbMYh6FhOdUh56snb!I8rqccrC*jvH z@5uEGX80u15_p{$x>!JL@>Jm(YIYY*S?YERVORKFB;dqIr z!DBX|Um2D0r__Ee+juxxBCCjCxG`-pf~x-Xs{wfb1^caW3~xCP4QjkbfFj}vi>%xv zd4&KlAtNUTGNyo?jY+JhvzgY6L<1D7*yY1wbB%rS$djdqzJ#W3uONmupyn3yA_ZG_ z4nOSqn$nrx$O2P&wOJZ2W9y`AH0&Goy?;>h&~9i>)8fc06Pv=la|CuLzeBr@bqEIZ z-$SNf{ z5*Q7a=06_S@caMM0rN!ENTHTh#JUYlY;ncrV79mG(NgdgCl^7(Xp_Kh??gFQQ8`}r ziQNXkseBu(USc(=!?-C6iMw*E;)#(O?T8=e%ZMK+MabQxX8cwUzmz10p;ohX4A~6~qq0zPZ-eQ9u6O5BSfPO=EkXH`-VwXAIv<7O%VKcFr%GVM)!Kvq zgO5Y%_8{EU%74m9ucv*J0JFGk?Eew`Zykd5r_YFX>W_?{@xkwKH2x?j)oDfB0EPX= za=gs$vhm#EDv~1sTANseSl1JvaefKBOqp8gs2R^#Mrg~>MD(j5bvP(Kse#Zo0vGz# zn>wC%gh4*cHd}b0V&u$W725dZb5BTJXHB#Qf1H+}b0HtSd9@3%1Usqf5bP$cvsvxs zAf$l;Yfw%VSYzy%PVKy1Y`>IOg#C$OZGbGvE3GSqA3%`tU&qX^3&>imF${P&qQhT2 z2pe2&VLNlMoXZ0S=aBsoNSbzJs+*{6vj3OTJnXMuw4<#4%ricZXK!=1Z+z9$^&OPk z5llT6CgdGJ4pCbS{thL$Q(D>gfPGB7F_=l?65lvse85AH|Kw;u#md2{SO*YWllGb4 z)o**f9q;t_OhdT^X3l!PpzkLqPM?v&DOfr9D*AgeeRsC?}U~yP+AVg-yhULl9 z#A#jI$WW{cRVV9Qeax)S@UuJ*QSK@)j&Gw^&l>Gg&KnIQUnJe`y!O5t=uKkwqm?jv zGKbz}04R|tVUTmY-xWYXWmA%R3|9s4c)dQ2t-g&wqP-v#&UAN(YD@p50P1-WGNc`N z-d8rvw^)iJ-D%!-K6M+mnIjwxX2wQ~KSINXPaJjnWWGxDd-)#2zud`f4Hpx)N?Nn^aUIgY8ZgvLFFx`7aO!8><=92=x z?v!UTiKURZJL4%`HvXcOa#95^9TKyj-qlSS?_Z0V&X~wpd;Tr`S?~378<}Pvi%Qnj z8lFd7w`t%HLx?v@enOZ7WxJYv8bY1lH@b>zo+}8^hsd*wHK;HhE>J5)W!t=b8GSq< zy|KSHkS%e3%0#j`nfvX8M3Uv%F}CfnyeaG3B>nhJAcv`XfOJZa<#y&$4 za*bGdgTN{+9#(6@0e|;cy{)@2AAA5A%pREi;bY|i2a9PQjo}LfDLoDh>Q4ZV;igIJ z6H3G}_j%SN@|t?K3Qe?a9-JG~H$$ElrK?I-aRXhuXFiCJxHIM3t(It+Cg)R^xsh;2u z*V_$0KF-=*MR0^-jjz&&;|t2{nqdzIJ6dn?P0S9_y(1ibIMsZbTF7Gq+(oi_rmU09r6d`n)cZ0Dq?*ZUxJrD zVz``)SINrotQh>U6WL3Nvr_F!F&6!UkG`&~9}om@ZHkOqA#OjZk1Qh4N}Smn%9`2Ne0Q75Jbu^`7=*V}qlD49f(5UU z@Jb`+6~!yrSS|vZM#JdbSV;@XfihSHNj^>C<^FLm>g-|0AIbVmonNLzYLszvxi*L| z7rqn>1>01#SVTD8b?9F zcCVy6i~aQ5O8aTvLrSQHtlZUA+k}4~9USlVn~0Pb6^;MLCAbX!RV~&r%s1HcJx9y> z<$?EnKu~9`dP|Qtb$7ibftB7R7dZDm=saTt79fb&-u3)r)5qdtH@y+O_EUjl^Vgux zW1D62P3UXLp`~)bv=^{rHJgoy_lq~jl8yvXNix>-&&*wmqwS?tSZ7XC9jj3PzC1}`<{ z-l6J6ZO{lKId%9+9cyzXw>73jvdne6y&L!;E6HT;&YK-ZPP=iLk@^z;@Lb?3)XGI2 z%9Mo|ibZ&{2HC{nEZ`;oe~3@zLN{|Gjf{Hg(7kPok_T-GdNcZ5G!exY!Y{A%;O;-9vX8kZ-(%Z_Fv%r6UCt& zic$7?OBs;i z_0vcd?==N%w0Xshj7L{=KH7se58Hk?)Y>x&Lr{g&IUpX2(Yzm^ zeB8k7K+x9?c)F7Lceb4};7v7usBrfFIiONx}w8Jg_B zFZ|_}&%9AI>i9TfYUZVr2TK<40uvPz#u>;V%S7B(LjpX{!^AQQIz)awoP zsWVi^5MVxX@K4uqwQdy2QxL8YStyRSN&$xHb}>GcOKEy8$Y`R+!$KXFY`C%%ex^c0 zxOqo-L&#rcY;SrB?vI81zW@iVcmt6T|M};SUrgq_-L7CT6Uh=kl_m_q;R;n6 zQG^^Vr;@-}1SxX~t0y z8jRf(nYDuUSrNBIxZeY@1h-`bYq<%+(R2RyCe$FlcgFCnAI7UYV(yHMh|)%MSl^B$CAUG%Cerek6ob22E}>ys$=uM$qtQIotiVykrQj{o*RH>J zIe;I$QuJR(?Js5cUhg4*>?TLH4O5YokGJ$RQT!m#nHtWal<#?ZlUwrk_4@Am(4F3f z04_cWSwh1M^4^6GkE69ZNKghV=gAzxRX(LHd|~(F{qLCLlS(n(=!85mlUMDCOkM{L ziXELFNJWTL%{#zHQtdT-K5aiZ_H7q~1S}GIFpxQSjKcI}s76?6JVP*QbfmmGvw2|s z)4BN}Ci7e8mDZuv%FmY-M3X)c+MX24>ayLLVcnFPxcp1y=-I6qDt+H)F4UC0mO}? zTXhnzXvy>2k)OZSzxEJ)*p6eB^>JZV@-!(BpGrMqWW@p_E+Ot$_p*`zqMPDJTyO*1iW+=RtJ> zLcI%N$hRkYxUcj;OCULCLM5-F!2WtUlTdcSAX;ZsDQ(n*^h>9jjLn4z8So2=0fuT@OB_3pK1iWPywG;9GqM1pIHfr>`h7#s|oX z8gUF#)C-g@LOWpj>?KTY*dL_xluTqXcYrbNZIB8?!!YY@)SF~M_Ci4#m$%_o6%$gy zn|@D;IexJ{ud!zgL1Wg`^V1#g^H9VnW0HaYuv!_j50&Z9Tg(C;8kN8sjo?2Tv-D6% z`;%G+{pkrp#i9}xJ-s1wVWZD>WFeRp6THVqs-Z_Mc22kY736z{fo1GvsU6SDw`CD3$ zqm>+f-Gz28SUJcOX=*3xhcC@qr);^-`Z-WAe+x&fNb1fF{Bcnc5dj7FP_czoJH)`6 zYTEQ^ZxdpXz{MpoapEg8lJ`np$gbGIegZ||Q3Cm!!;*?!E_krNg zMMdh(ZH4O>x0?Jf{PCvv>*c(2$c6E8m&i-x2Ts%P;_(w@;9)i9Ctvt{wGe(Prt+EN zyGM|v5WS`YaReOro%PFCdsH-Y<(tY5Fm0aaD8#7(evsZ{XZ%aLt|QL5H`S)L2Z)GVmB~)D=92dq1GA zeiezwzM4T@`*QGcL4@sVHNa6GpW28n+ek>#MC`@DEI@wl8)C0vslp@srUP7}B`fvPINCH_-jndG#$ zS$A;#BnirmPuI3vCjVE8*75fD^?m7e>S1oIOI>SM^vU~a&D6o|1=gqf6Uw)-ax*CY zkXf*r?F)YsM2uKRE@S_A93a?!0_NAezCvgu66K%oT&fca`o7j1Rl^UEU%B93e-m=s zVkxQcsF4aLOwgQN^StiaL|j;)6*Qc4rOL)q)kB^vu3Da^CuGAv;#HY$E82;3hGnjeQtl6IGy%{6C z$;co~@v=+Nh>OO&jo(G0bnXrwi@ZN5WZPf}h9u`9u0JC@qhMi0YfhV$y|W-p)b}OW zs;zU3fxit(KB(Ii!DE&yecIq~+g(qv;c*&tV)8~Tl_>r4oYx_dOJq>>A-=8=wW{M= z9EJ5-$E;|O)`!zfngjm(o)$Ho(&w*rr-yq2*0iF1}5 zg{uf!;`07t{7W^*ha+p10qEU~K9?JT)f)3;4b1oPG*&Tg-zvil3z9wO5GJwWZ8t^d zRD_{FPg23Sok4Gk?@!UVw`N~YZnW`YafG0~Mz{6DhPoL^g^d?%&)q!{_czKfo{+TYrNOf$b<>iSedKgTv#`+A`byiU z`U;jd5wLXzxo@b=q7I(s^f4aZrxrmok0X+6A@6R^z?u`~{Z8dPeAhm$2SbB<<>$Ok z?-0{gVk?zSq}~cKYVuYBS1b<66psyYtkqD}%s|NPcz5|JCoruW7iGddpy*8&qKWX~fdfrz zbol;}_`o^~DK9>tKt!OjP5{j@xwj(&i&O*EpfaF$ZQYus^=>I%uU0VFc*XccyZrWA zOOZCFBB~BkQ$XuEzKTqJoGhRtLlxwSjPn>O-G13{R@3OYtcUtJy`ShDY{vegWKDc} zIm7;`r>oCeTk4*JjL6HDfeo2pc03ii4tq8{j{ff3OXaQi1Dw2{RmC+oCgZ`=on5_O ztAW%g!_^y@!r=(ZmAyn8)Uy(!h5kigQ~s61>B^bPc=v#<)pko)j;tRB)-4ar1*=DE zmXt6o#!h?`y@m{olbwf$5IsG;ufRUcv1|XE4kM;=%T^&Qi5EDEWNkZtA$Q4@NGih# zd3lR~EV|ZqY0JB603Tx7W|2+YJz{fDQJs)ge91ylPY$CaM|Q6w!0aRnfmn#JIq0Fk znN@EcSC$Zseg!v1Fckbfy28*{XcR_1ICgDbKL&OnJ@G`|pdbVtP;IZ-4Dt|B~(nE=V|=z*oL0qfIag=z)@IOj35JX%!1KfnurboBa5F!0|pA+js7ev8r4jG-;=P)|{zAukq=9#oLYX>tsyX^{12Rb{X+7 z9d!S%VYyu3;COlU1V*~&r1uFIW?m1)QAFO9&gjc|!tY|8AjwQ^hl7F_Yh$u$5+5jE z$ekm7)J*89?afx{f0d1BQitEu58o6I3kzGDX$ij6iQEe6Ad}_lhBq$u;73|Qui6Bb z<8i;TzUDdm-=YZjw;Dnt8>Sm7_?YU4abcnLd+5i#2)5erMT_&f%&0IO`v#+a# z8$rdzT4;UR0ab0Pw_*uUG4sw|aXMCmGy1qKg+?NN~ z%^C%eG=Ba3c@I!TR=>)xoh3^yCuPmRao=;}8ZC7ULkx`DN6!4YQr;(F;06isF>tFU zM@&jwMaNYntW7yHkk6X9XRx=>N$bV|dqX?|!+C!6Dfm_uGFR7eNpWm-`;gpH1xkq}--$uLE?mth-r86{sFU{a z9E!8O`HK))VX5LnhmYBY-=!L6{m@*OlbJsa_d6SAFjL^XMnVwqW&3JHjUs4~8-q(v zG8$Z%rvhdR>n>6xAx15^2mB?ZdcQw5!ob+!u*l$9QGD$fynAqxi~? zv*0tp+?7IqdusQEF4vLI=3JwSye-Jb0jb|_`SJI%xRPTI94;HjE;FzhuoaA6tN#W+ z8p*Vu!t?2NcI?8NY8gGhRVYrFB}&Kru5GZ`W5=3jk9d&-$_1%k}q4nm?2(FZ!6U6dy=c z+or`;3J8E=mjMf;EDu2H+_}#|fmJ#=y}SB|3&Uk`&7a>ZX=z~2z`){>RJm+R z7WHOuqHZZWx{xWj=9#RZ05ZK)Y+gg6wkNamC6h02h6x@dc*Y73B`9Fxk^ZHvt|x#m zVCLumkFO#57OlCDvIC{BsHwswT_u!R?B}Wcp6T#2$;z5gXF&b{^(z6&C;$L>o8K2w zmkt1X3@&XtGCG`jy*elV-z>l=#CLoCvRKD=TYeAn4L@um6|AQ6tP`sAnnh zW%E_V;KIT;RfRU?Mz&e+mZM>f*hqK4v4C3kZR4f3yW$6JSU`sjNyoogma3nrmL7L| z70>RMvGS@|WecnS)>#E|^D?(}3r7-$g6E&BK#~@J-D(clR)5OyR46)9beuE+T9f8o z%_;mve$nigo4&8r&$}+T&@Rd^|3Hh&x9--0{Ta{(ZAcKsJvo08nS%IFa)H`f?A!dh z`zIybquLLa*hv;NM;gaHerkdhi1q7a zVPD8%V#P&7?oF1-nKsqSUwj9QAn{~0IVMX!Fk`=o_*vkk+GUdXul{$mvYE4~+IY0% z;0@%4DF5$BLaT4z+a13t5|;cx!Ux;41_HrZeMM6CC5~-H&hhMpPP@2_AF&&XbxZzo z^jTj^hrXD+gb(XDu;Qu&aED*zB*GN1BmsZ@?1{Z?rPVd6%Gio;{(FMVNBH!BqOAvL2;u0bwVt*NzTLV811<6JiOiiO6RocyAvqS{ zfj%7`{mDr^zKC(tAxrdAfH>o)dojIKxna_L#=Rr^zSs=Q-%uD&&yXtF&5J(dWnZx2 zn`iQ)zG9=wO}wwk>vJrQPh470RC$l0yQI}rr{#Hbd$+TSOJl$1**7)rL=NG{kSL(X z6TVTRp1ma0$q&Ud6Snbrnr}*J+%r;SA~H*Y(N@lhgc)E~BVeh}*(5R=hqqrBbH;WW z8jwKrKF<27+#d(ldifNKDz#Zz;9u1BSZ;fdcA?QOxaoY3rf)tPl6dZ1VxMk|UniFRfEhr(dK4V*e-s-mtUbu}2uGfdus1x|j*vZ$uW-;RqdZeQm6}RLp zdW?!_Df(W@F19tI0D^3sTo=s9B`vaFxT@LE-VmcVt{+KCa7Xp2Op~*1VYb`+-$AxH z*6%Ti%=($Z6a;QQ{)!}IV~@YFPu#5LaZT?Auijc0kx$RW;e^futL>={zb=tiQ%lWq zt&AeeKJc58v)w4{gXL?w36(NP-8UzgMlsAH5SXxW}o^VZMXa@-qV)ips(E}qP&l6BBtkWzeQWf z_F(8bqjrOgEcB-!euvhWcyHNU=h>;)S8nd~d`;u5_JOpgZ;qePG@mm31|zpQkPS86 zB~Hzkl!SdQ9ivZQpU$4`9JmZld9Lr~y1gBL7vd$+-Upp&6KZhSQ{%5^#Ys%js_52M zQg8LL4w_J@4q8V%*O4b$FptkDGYqtK<^19GnLjS=xq@)hr|0Vt(~)m9-!J~4XDrS< z3X-+P z3*z)ZsR$@S4($az#X#pcH7W!$+3a)kFJS*gC-;BTwlvKDlcA&*m#1Ac&?G}Mb13{n zpT>7iCPjkvnA2$b(IE%BfbZN&Zjl3a(MmmR%qgrHzGMqO8L0mqDC|SIM=&Mgc8Cq6 zAt{(*!DgPNqsfTmHOW`T{H(^D6cMkzL1;1=g6&a0M*eBvkl9)Iapa;)4RI<-j%7Mg z?>BJWN?BDG?5AD4ZR3fxUd`?k(~Kf;E(fmAebJ2S z_fjq*h-U9)OMG}J`0n|EQ(aYw?ELgkbSFZszU#VTmZw(Q(U%{1geUee zt<@-BsOk70c?%BMghadNW60Y#m;g&~BcpkP6-$8BKuoD1XN_2LBaA$FNG~Hi93@Os z=87({Z&&}uPN1oKemTqYYK!RX`iyefvz2H*LznLCa&PTj$-A`B7P_|2%O3la8kLb= zF&^;JvlrLge~?M4?`R20Rvw7B)XHW`zJ?GhEa+EZG{doE2>iB$LcG9t?h z3IjwghI|YR9N4Ub8%f3ki&auJBBuUifJd7BC_FGL)O#xXeot||Bwb3sO6vhskAE+Ir#NkML&}h znrF1cy3F2SKIi9j&K}`X<;1}>7UR0ZXb;TiJVeL9K{0@kto-LIBtBX=xj>hfXYu;CheZ6%pD{mb531x> za6RJYs}?%=*A?10NXc$iF{R_Xc@8C^54{VS`RO4g!j}a67FhdH$O?GLDf9dDm#lTJ z=2*X;A1f}CuU_ojyay72CL!jgtA{l%(vpkq6B6+YOW5mF<+7jjCLDl=6ltVg=Gg=G zC!LWjm+^5W%?K+d%=dFEYh_hZaHF{;!EbB0Hj#4+F&icOp}oxpo~Fq`+6uUwMwg`r zD8-n%Cj5dOg%px1-0PvFU?{)OD=~YaInNVHw?Dsn!{j3~=`koLReG-Ly7*=<@tbdc z2c4Z>+bU~0kh3X98+i^u_Fy7mCgB{U7q-yV3t6emulV!!-h^>W_JRXz>_zr8=OQ_R zft*U=*X)$;h3}`@O#1TE7Kgm_O^wD{s|US5SG&*B;HPwCSVXVI9hCVgI093muBVb7GWxNTc@!-_hCJ3{;1SiFKQ zDqEB$&p5$x;&!sq}wT`hCY`8GI z-kWw+G1{+m+ZdY)8wgX@*O3C7=C|Z`xmlEEoQN7ZUDuJP8MdD;zgPIe@CEVcEDu>p z(~HeGpHM!0Y}wwPg~%K7ROBs~yilO~8Ods`$$&6o*K}0Ub%{p$@PR{c33*WwViq>yD z=1>_P){Ol)xUr<@0SR}0v}s|}$xfPcvnsdV09UP$h#Q)9FH93NQ|a*f1-{w~<~}+?bjQ7EEz~E}ndQ{8B=xUMBv5jni-^{% z`_{K8{6O1l8}|_(JY~jI=~_FszihF`s-9I)lAw-GxIF(!O5EJJg|}avD^A;>Htz5G zh6+=g6A$abebwlg5(~JSAuZ;~z@2~181Db#r6IM$%6h+LvLM{yZzL!GE@FlC7e4+~ zojV#2{wObV;0&yq4=Z7fRdA9g+{x+zkX4$uQW_zdcGjo-kDfmAygofhw&MFL$;J)p->x=Q=_ zd#(yKV-+QKV&WgLZ%n_#}4^Ns`5*Qa-%Td;UbSh(ERUT?)Qis6cjYm zzy$bCgtjQQa`Gx}qXZE^ulE2~`a`^7Sn&frHXw(Ofw^e;#$ylCFk%Lo$T9ggSQ|$n zg)LMmv{^DW=vUeGXT2`Cxc#exs)=BZauL@CI}!gTotq`qdj*CsE}fBW{t*Mh*UMe5 z3_jMv>Z8K=?N{+1->AIbA0svrxuA2~;vV@*j=gASK;c7NR7_Fn%o~ya29;t!taq@> zef9AOIjqHeN7wt)j^XKupW{M#etz^LY=gtuh52h2EDG~AmmP8=Q>&pp76NoLBZgzk z@f8PLGqrmS@)E8X3kshJy44EjlvbvmJQYUtAfGhzA7*V?8qJ zaFXpsQj-YnoBvuMzIO(7kg9>%`<_S@f9UdkZM!(fbwfRqAuN1#-7LqKa|ORJ|H$o_ zwuCdh%5`IRrrq%4j0RWeLqI_OSIpW#dKQMvKK&3Sa~Z1Sw*|!@zP_*wgI2lTrB>Tj z4h(lqLG=}8WW77Fo;?qC%6#xJD)QX&}?2jr- zYz~b4>Ulk`x0-hx`BQyT(#u|mr9Z|YAs%-r+me-&i`(CjKL)G=pqcIiiy$wlx>WI5)D&_>fbKq5^M7J}xow z>VUtl?{OcdgJB&cZm=uQJsc3bGqq)mIp__#E8UKAA<@AUm&tV#ttK1Cos7^F2Cd1< zH$+I~NCMKFJ>hD5jd4&^^Q>VQc|oTTt?gV2QQgq`-ixwAZ7z+;7uMDtv>}UadA}ASRLZ}yBs?{h9hiwT z=}#wJV+-pwx8RgNf`%vuXV%<0(Kacu5xPm*%QwUt6DAqCaw09_g}s*y=D_ z>lNC3euSUm1!vF?viW`aWh0j%cZJStQ(0%k@{t=E#WDU?4oCB+1nFQ%{&w!B9fQOh z3%fjejIC^l{X3S#{Y1CoOTK5%?uSyGwA1X!z{utKpJM}Wg)LXMCmbVr8zm$8{%XZX z3Qk3}n4SiV9>MJ84VP1EVpLPR4|^@J?9r9<0sYZZOe1$p2_-ui`7wO`a_bqW>v)o- zIvWl_lnk(*3DY<^2_M%l|zEznCP@fbFIy2J&gE!B5k0$R67zxLZ%a+e! zm05bNAl3Br?AFS(uyu#Nla-(eZ61?;z)6DAYa}^D%=QeBEx(7uLiBN}dTO>RQTp;3 z)i{xDer-#l42)t&%PPyv;%cfoSVW1LpdQDH#@&A?K}j-4iYSff;bV3h5Vlg$ChObb z(guZPxgZZSB@F{v0{pA)Yd6ljT(I#%mQ$*&NzKh!GKeJSO4r<06MMdbgF30uY!`#( z6hOr}TQ!hq2?+%d*{|a!nthsYqdG3p0|WB>{QQ42U+u9pd!?FX35vlzAwB;lU2oGP z+7t7;I2XrTy=PlJBo{{7LLl-vp%JFy$U&ZJ#KV(x%mLW5tP|?Y$X;DT4f%HM0aLG$ zlRJK!4w+_R?5mMrj>jpjD|Slr-`8q+$mKj9hrQ%ld56Wz<(PR^5I=@iH)+yLOvKhl z3LPV7Vyx*a5jQa?ycfB_M$#OfU%BXfHl#|YB-XZ}YA2vm6aCVtE<$(|G~sr+wLi|7 zob#Vs$%Gu-ORluMBCNiotEY@cn=>xq|zt?9*MgPnMkWn6V#wM+xAT5KO~Je zU0rLDrS~W1W;ls8?0;L6{ONi*jBEGI^J~5gjN}EcaXNETydkl;v6Ad?`-)2jKi3Cg zR;1W>I7!KG!9?2`h%!-xU*`kPPE0~VB}N%zgZpBUN+KLDS7!8N(=TH*lp}R3k>{l| z&E&3?nJ@ZVkREb5#{L75!T&v@GBDn(iQ2*&vWc_1Fn0g?Ym0AJ{A%tm=ccu0tc4AR zE^|p)(|$IJ{{9-i0fMXNYBB@?v-fqd=;%(8=YJPxG3nsTL(_;MElYM;^fJFfO+x+S zjDRjM@tnZ*yCaStGa`Z*5rS{@C0w0?Z$@scS+I3GSM2Odb5azlyl)8*{ZSmyt{?c1 z@KJ*Dl@=LafD?_&C&cm*DKhrRr2V5k4r+g9zx%QkD$q7eG6Imkt7Gc~ zQ`V$UkDYhj8~Or=Z)y`u+3*6l%AYmFN<(S!|4sA&nL)basncSnrl$0)+Ozs!|EB88 z)M&d}TR=3Md~rS-rV0tkOiz;hg#>G5dj#UhYFyD@7~VV#4W?)fA&O12E*C5Fdvtu^ z^~m^C_qgk3`0-2_4hb*3aNg4yN2*9Xbq&{> zP4I%`Zl^!FK^u+jcx!dv?9}TzZI;nfuR4tg(v`W16{F}MlC|_8T&NNMYW(H{H|e)X zk?Z(&Jdv%6PqRsRxku!zNa?wqT>;7h*B6pep>>)3*Izo@AY1|U;RKFDyD!x*eR{K> zKTpiZ<<0~FS4&hn$dKHV4d-K$rz0zAE#H`g)#3Lwy{VE1MBTztlQ+&# z=Hhi4I(6`B(}rU|=F@)-`5@-_<4sej&rOs_c5zKa)E}i{EZvpkQ}SnRFKFEHBis6e zPJH64dV~u2d3wL8SClr)v>yw`l}o#ETY{|kLJA&)j+SQOWA5rry%VcAg7G$S0kF~q zjPpvRD37ZFfrQ%_bO_`p9>&A6Bi%-L_-8r=n`1*Tu|wWjw^mw83IfWxy3g+#_Np-d zH+aUQ1oAW^NAqAT7Twf_xwcbc25EfktB(cIkDDOq;>hnxwAYH;^7!+V3r>4xFO&$v z#rpNgo;#_+PtSI+jJ1$Mi*xe{<@+O=$e`&p@ddK|EQjVq{PL=msA@v;T<2WEbAB*# z1vcD?{>r2hPByogsYZg4v60Nu1Xy(C@KWTsDIKb0Qjy4gFr*AsJAqGowK&xf1jgIRH!ghKmf8YJ*7 z8@2n26wzu+GKeMbNDs@Qv(zf}04qmWkohj+G&7Xa(j5SJ;S?M|6gY5=+ zRfrCWoXlAI%Zfnx=ZP{^awvh}#97oXGIm(jyB)_y5BJ_6#7AkEh9%-7=!2m#{73Qs z+PkJc|ChtNMW78PxDe=LYg@>y+4Q1Mh$;7G!y^6 z0XyRN#9nR3M8*QYJERAx244R_O-(7r#=?>&ncw?Ue#o;50psZgfe&I&xW{yHcFsNZ zp7%0-l+0>4xz;+*J^%Pe=~IkF_UWabtZd-ni@GN>;#s)c@^jhjzeGofSDtIs3VQJ^ zEyV=GdyTRMAA1K5CmTsqF4lj(=`Q*+75yM|QlvgIm~b_J2}309y5n0jQLQ064%ru) z<`2p~=)!TVE7ODW;`ai?K0o)!)FaFHQ@Hw;lzY9;VF4$GrzJ>KGU?QHGz~%h@+E4; zs7;o~jlAVFgPPj@X!wsmCky@YkN#jvUOit;kyeiBhv?51rg`Se3dc0_8s=*3! zx4rzzhl{@EF6Wjf4SEj!sjH(v=f>?nY;W}++t~ViDi|+Wa5yPEKX$Zk1k(j-xNmnj zIGp3Z3@+Td92*P?b;$V}+R&o7#gFz_d)rI#+fna;5nEfCng$|1-0$qhujQB>&_9l%c@S&Kcj?T5@9!f3Zvty;`Z~dsCB?Z^*i0I}xS2HTC&8AQ?*s zTO?$Br6Up32=mbB5A}~0<+U^z_p=5vKfkfd5WAfws3!%Kd|K}eF-t^q>1k}s%X zq_mm26xAT0;zQGUJ*@T=M*eu6$RP%TlhBSdwt>^5Fd_26SrN4|I_ z?xip#XU30zON8${F$*ARAS8ww6vT6(sQ%V7KO^Hu)ctAs;a>!hq&vApiN#s~4hlcag zyKNjc?IvRDbd$(SH~YoMooZ#`gmAmVL0kNgUaVY92UA~CO^pnf4#_4c3Eld>+$fu@ zz+!kiO;~@J(r@O>#=4YHkPKN|;P7Ek*u27t+!h9TL#TIkny13Oe50V)HTOZsZ)Xp% zt5X-n5B!qrJtB&IL-%Zb5pDGfdy2iUTw=BsubSj@o(!Mr%vMBRbojp3p=ju9%J(9( z73}#lgMH9*q_H+|0uvM*JBFsg4lxtg=NkpgG%lDUO3>O`%jo;Bjt7G*=2BYE*2nj* zRv3=etA^(PPzkybX6>-R?#YQU7qnb-ux70gG7-~jlB%z9Z z7F&)vn^YTnnUVWmwAzk0X;GsnD6WE2hgnIN4gZV@1pFoa${tw zuefjL$FJ5o{lU99*_peo)C^80B`1$Ly33bX5&s>usC4MXpW#QH*@3Hbj~8W*Me|(d zE<$Yd`gH_6H1u`%AgjS!C;Za!uN({v4By@K42SrEEfuPp@&AW6DLqwa@f#@LB^`ml zt*XiI?G*8v7bfZ>is-$F{SJF;s5y@uJNP3BE?D%|h<;Q=F49tVz(PB?o_x+eohFBo zQ5u0J?p_V=j-n>R>*9ihL8_nU_?;7B zk@w)`y&M{qQ(bRi=Nq~|U*D~bom$V<9*2;?5oy$sS_tK0BR2Kc@9>6p9F!WYWPv7CD<@~pBXRDqlJX$kq#d^hfpJYn_5>uXG1CPvf9;@WTs;)}KkqQJfb<+@NRUR!11 z)rSSDy1Ze)pd!c3Qt4w_hrvsAr|U;>vTB@pYR9|{3xksGT%IZxIIiCf(VaFG7pi_wI_en z@d#4^+tK7V#vsKt7bG9s&SD%ApP2HDjnu%1M;b<$)2`pQlX6W07R@Qr|FSWbslc{yGa-7Sr=(5TT&wBUqdcQGSmKAx4@B=9KX;>3l6Y9N4^%~td5QICqG>#E&{N6}Q z>>EsZqx~3_6Tb8KU>YO-+uS)_sKXIdRR}^<4)9?0F?&F=X&MfUU-JLjLQh9Fo-pe3w?;DYFdL zoi=)VZX~%mFRP_CUNY%7?&=l~GToowbKCRq@_%AjEU&)=8P}T^AGG&A?ZzJdZJS<{ zm$EAQSRNZ`{H==J8m=8oEzPuHL6srI79L4P+ES&hqMK2N=io44v%5)&kSoHjegl zp4cucp1g>#5|DKhl2u7h82y1UsOz1|n&uI5J;W&<7Q8g&WbG9W616W|hz!7;WKBiv zKBk-PH2UFLU&&R$27XUvEp^qBsCl6BkL4r^V(cCE>W9)JKI6uU**}KJ#@4nsT-=ow!%@7o0ah;NCMvA+6pVoUWjoR9|c(PTY z=~(qzGV0X8eG7&)YCQ&LrY9XgtOgR+@jBza!QR_kS##Up6mj@7R)AFKuYQ_ae$$?6 zK7E~&WxF`rc=CGtn0#7-P9%UA0YQv?DAn+_!^&sI2|N$+x0Rn= z{B3yBT%N5G8D&RpiAYz}{G!Z)sk^-V{d0^kCT>(FDaQ>3*v$6rhY-`666~8U%DE?OUG2Ly+OU^^ z4)<+#+a_w;yoM!dF0x9{+rfu35KDlD9a(K>+8%~Tt%)ZKVjiyi^UmEh>_>fhoOO}* zyIo!!Oh|2|U8wI~c`~s;8)BVCvO--~PutXPk<90!XU^Wm^Pk)Sq5d<{HNGLoWFV_c z2j}s+2`h;3P(j{HPb)2`!CO;*AJ_q{*yp%fuM4HBDx2)=43suDO-vRJ9$xtyO%btb zmU0}O;2B%?n(n2!i~Elccqf|Rq#IGrsB{BmrB&TVc2Pu9dNgF{j&rjY6W{Va2OF|A za^3wXCr?ZG8EIIR^%|?sZrt>kGpXeQ_lJ$uDIY7F%(%&xJ1-xhc0ypBJUABzNK8e{w<|}Kc1HR#E{JVx9F7Ck#9XpG z>ayWv^NwxySa}`R7lsq@HYp!;(XNhn>N0Dq*sP^IEO%JJ@QuJ~@D^E!As8cyLkcb| z#v`NbTH15)S|@2;c@-G<3|0=ax}IE1Tj{QPa`|=V`8|DPeNvBDqBZ^d2HXuj^QTnR zgtqoKO&1e$m1z-#2bNo4eTOEMP&-j!y!NTiPcB3>ge6TSPr<1RejA)wWV0^uRXP2@ z{z;m3xfw2_uuRu<%XI4qV@V-&>bTqWJ$D{r$|oCZcwh^cL6U6SW73M6G^+J#lX!Wp4IaP9oW*WtlE^A9~dRGo-s$={N;@0o;&L&3Aza; zEruu_HYO1}x@W@Wy|;q*`IzT>6dQikv*~Lg&O=O{%U&*DHn(EQ|| zDfvgbh6J1wRw514?+EdyrogxnI~>&CmWC>eEqFdLq$0#%#3RgWn4Hv#pb$g^WQ4{D z;{)|s-`UA6DN)$F1tQhtwTOE6&nM2}9KS|~+cr0uUibDU*fP;5OD+f?`kK6-xinow zKK6lnHk?3_{mxBw#4TQr$FjJ)Y%lj|o#->O(8R0}9snvhPjNuVxGdMpP{;kLxcBKm z<&2B#AWM#!>EfQBwTUvCHA+Zw zjttAm?JFHGw_&qCKL?DV0xaw3He@m3BIG7}Rm7|bIfiG{`;@Ez8v z_8b{7Vg<@>v?^nP4xwO4g#5$X7Mhw5zIIi|NUVcFDvJw7k_aR)jTi}!X2F(t99DV+ zQoon7vyqHvjGc+4DzwQpG*&Zp4{pi}(~Us0{hqpi1`mzl>z+@$P_px1)avRQ4&H?p zq5ehOhTTH=V~M5G)=8stV&7C zga>b^ZTW53cM3`fuaSSv?_-Qh7PEtgMCzP9bv}kct$giJ9Sa-}oeuFmtt#8W;Z1L_ ziygI45dV;%*FQkuMEVyn;?G4$nWRO9Mgxo7dNLKZ;ZxMdHG+@8l zkLH!zTi=iQ6}$&Sxs7NWHtL5?YKKEguZFu#Bx-&k8`duq80wGXL)P?A=TS?mtZn6o z?1ZCAqxIOI7~0|_b_Tu^zHY-B`aWBF&CKUpw(fN=T#8d0xTA9}-mRgI}n&T?tsXn=yaNW>~@9J)MMevIx1 z^o^(Pp%@V#eE)4WwwU;rx6kP4Dur)lk09Gk^Oh`&x98Y^PKY@8Yqp6v+gq65k$ePy zO}z%wG?F2Ph%LI85Ypn9)Pi*&Ke`|B&; z?%9<+G5nEO8vG?OC1vGz>k}R5&yy<}WuMN@PMGJZ-R*6Qi}SGEa(eJm10xYb#30z} z=WNeAnOB`L;H^Td%v#{Shpe9x!gVRyz+fugWt5JF(H;!H)-bRdC?4{{ zzv3jTguL+k42&kFt|nNp(qu#+`S>isk+9D6Ox!m^;6l4mp?;@tj<`&zSJhYJwG(>J zyd}c@pZpNyl3kid^3PcCQS&)WU}nTZMFDFP3iRhVs`PV0Lc#~V=IrPwHgmb#rR6F1 zJuv&Tv9WZz)m8C#%`?nqB*ecI2kf9NiR9kQd<@2aJyX0-cwv9=&(8CbmwLV1)869^)7^=^Y#*d`Iz0Jm3d{h=tsGW9M)RXtun6%_nNDu# z7;4*|Yo27lBaE`(5)$f z&ZvxDP++`r|EX@dsO<*peG(4_fGmrJwtjr3kpru^Qq((PHn|gf@S_<11+Q+G+yofk zuh-HO82!j8V+5oY_gl2Ia=)0K+Rfsc*|bfR8?Pe_^SOV4Q2E=@~WEzhKx9Yi;@VJ z&*YDsX1V4fwS9LtNy3HXBs?y|sdl7c;JglV%8xAQ<1c7+@{bHAYJAz~@u~pqW^jO< z3bXB(@{E)z8;Vsw0fkN$4REu7dwYTWE6n?X{jXV>{MW3&O%mjic-VRMli!Pr=WFN| z?Ympun0Tb=*nH0N)PNK0_eg#wLq#rwX&Tyj7s6`lJ))$rSO~rDgyQy=b-ZMV?`$J3 zvLStch}~F8egELXw}zZwaT>JA&v2gI-^v<7I_zN!M@Hr*Mvrq4f-d@&3SkAFWBV7u zp!jHFM}=tG4-xaFG!3ZzO{VH3>OW^@q6jd2Y`2L;qe_ES#{km-wT~PJk0it`G(n?0 zI6&mqj}ZT|iGOP%!Rn8ybtm;7bu^_p>)Wn(oCV&pm*>j__PJ~|PKBZqO+XIp!N9G7 zy0QpEapmouPKH~}8I|_6qhZ8BJ^i?a-6>CGEK!38;CT9mNAt}%p=6EYTnd5Uhni$S zV1B-flZIMY%GE?~v??a~+Od!OWmMfa1Q2l!beIA?_mTg>TNFgPw5E9e93Wj%*c1zh ze^LwZqRzSOu9?6M|ApOeDtEB^?Ott1gFHZ^t_ITQ%gzgg2dkv}_ZvobkvluP5)xB; zE+)ijJ=Dnx*=pF9UO%2L+lcV*-Lz-JdFUTnMuxd3daH}&iw25RRvLH0f_i#EI@l$z zp-pS$nlm~`YPBZDJDy&xETtmcp@SRvE8M@A03v2YrNeB`7A=fZ)dgm`-fhAn3PSNr zdZLNO)8`^@;?K(`3juP&OiWDdRUC-X(bw;341p8_-Q?rTJG%WZgTP-iNTBXo(6CZt z9lNi)0w(jR8^xTomo1t2q|h97TeCy)Aw+(_XcMDR3hdJC)ZUmXEzJi8dilQ`uMr$0 zd+1L9(a3cIOX)_1xhJjZTbf6x?(fK6UgSHFwAwZ3*V1AH)weuL>(Ti?RQhGS+DHTB z3H0qx?=6e8vlOgK-x?-%92TJ9qsx84`U&H!07?f^<7k|OX1c1^0w~B_oW9z9q%R(ce;Yw{w06>;> z|AR-L_Q!uT#PcIF=l4NdG$%6z;;B+-t4H@~rM~6OEl)7;AoDDBq$~ZLk&JDbS~u4AOsZ zwEm?Qqht`|r}{X>9in$Ck{}AUCWGrCLa{;G4J1>nXS9i%@>l)})A-!nATX6~=NtNY zhZ#VByHS-=25W#O<5RH_8x(PB{%QOA+PShvTa20&*42Okm-wQtrDRt}1?{7+$@rr* zrcTLv5H%{23xkFbp-nB#4|UXQ=_MFCJ9BNoG<#TQ+}W0i(WI<$KX$dIi%w*U!pgr# zpz_-$QpWvfNKHikg)H`p17}ezM#S+AmAzd2dW3%wnB?0G&SvJt3jBp}_pY1*?8t(J zCN^paA(|Lm$Gi5XBHwx4B5=>kTdzzyJih=0 z)i*-DM2P;sZHfw~f-}_o6Eh!MC3RY^VtapH%+D1EOOFn}fvjE_e-ol;ko;vD=)5+z zJQ3u?=IGuG=4_o>^f>bwqYRamK6YTV=mZ7C@4lfTRdUG?k4O;Xu6q$c4!rC9uHN+s zufl+FJll9M=%ND93vz{PWJPk{(qRiWd{(SLH!7=0zl^&33l1HvidVjNd`kvjn?!5k zfpy@;A;g_TGc_~gbKgZH3Ou~b4<4z$zV<#pKfklK(pvPl*!F+O24MI5f0RdAJ2p1f z+}6_A!ae_I5DlrS13o4`KC0RNXENSHnFb0G=55MJQ2V}3T^zjnnGL$nX^;5D^{&IlM zWt`q@CnhFN{G9wgka{QrE$C4Lt(@>yzE!nuMu4-MFW92#Fb2kbL~bBu!z?~sk_6-%4*?=Q)KFqRM1=37&E&hNclNmKAvjB2x5cNOo}Zj89x zZqo~2yCVMK^|eP;2N_A0Ka!@5X-m+=5&;Wix2qGKAQd7nj*y;s$6cdp$fjyb)?gZH z=vUBXZ20d+7s4h~xn zlzO@b=H(0&+?tQ9i(*IbH9n+cUP=Rv-t7tJ@JEj-s;W4+w;I&7U*BEw7jSX&bXWAy zSYnbGlh|IG&R;C7i6kCf6(XH>UfNexTSMkW$Qq(|q3Q-!%uwWt3ZYMUP-OHd`?CAS zU~WH{%!Y$~yXhJ|4t5FKt1Qnn)@`GNfHqIuH>^G~=ze~C|LLNdzIM)ulVhT5at8+s zFANOW!%DdK{`6%&K)foHu37r-gETK!y|tv>e4>AFW&E~Cxu8{)39ERF4I0u+Vx>fu z+zt4EDiaoqGZga;HX&{vH+eS6F%E7X$NxP3|3EZ>)^cUBf=#+$JT(g2uy8+%tsn(f z;P`JVD_j$sp26ry9T?f^GpRTqklp)Ea@ z-pQkoK9jQwU$*!(Y+$RbX_I?HGM_H({8tNLcM*B1IooBEJ30?zynD1tTnJsz?US=~ zS+J?HV9ky@p-~Y+h!`=eM%vu%GFI2tCYx~!WJPENO`nzj1(z+Bo8dN0x7gB)-Nezr$u10d04Q%q-*LQBp{pB|9{q4$B3@FQdYqE&a&gmc-{h1ZLe~eT3mJbAENp zoXhh5zeTqRZJ2N9NmA%0Z4&C+?7>88<7~scoJsKCh&-V%Hc*^150$n~NJ`5!TN?nr z0<60N6Enouk-%KAW&d)H;1CKHW}snve2k|x&inka=U$AyoFwBB`j7vXaPuZgZgj~`X(s9z6YBpP^1Ry^Y{ev(F?)uANSg=^kpqL-; zRBRT6wP9VYD;R!7^w1ts)V5ANES6jBuLLs0ZEI)u&+M!oGj?cqAUh{#)?Yr!09cIj z=(Leu?mtA+#`19`Llsb@KED@4xkOTmJW=*&_JW)<1e5C+ z*IZC^YE1t=6&cq!i&$%KSyxGQOUP2qSd;FZyg<^oq&C0AbUE_3)Lf`KCT z0~arMc}0WHpSFKE@(R>upM!aM`^Ebq!NFGeA@41dn(bX@Pn;wChM6IB7*b=#4-p9y zO9qUX!d`1T>>|xic1D-xeuwYg+TP>3z#OT2oJ>`EHp?w;HqH^L5vd<2{u011TDQc) zZ_Mu@2py#Z99^lSBJ&`A#h*qCm#CRx`+bfuMyj}{t8n$CD8)L@RrU!VCd*r9n34Fd zdt>pQodXneZ**QJsP(%NIDV~dewiLh4+o#Y++cN?I>oS>X(hHVfwu-o9SY#&td7ko z3KVpLxC!7zrt_CtfKmLPKl+NEBDMiV!!JhI|4~u#%UP>p*5fN3dSFm+^H}6@+2|k4 ze#Q9c$Ek&x(EQ2Uy)G%{h&!E`8VmKp!7iVU<@$|$$zVtrrO#@EO#5G!3xr`lYxiy7-})T||F{}!>*{7V7KPWIA&{To;(kx1G59_v5K*`=cZumr zrWF>@s+bI$Fe*Yt=Idx39iV^;u(vI3d9GIO&hAWypmZ`@N6y<$>#98L6luU&Xx}8E z%gLmMbKwl|VO7bO(COKL(}XmsbPDX*6l4E$ECCXcFBwSdJi?;WO{I+!o%lqCf?POV zh3GC1tw{4#oFeJ+HS@MW4LMjK6&mXcZDp>1a~gNy6JpkM)xX%di21yX&?+xy)W8D= z(-dDPf(m>AY8*dC6{IztUNgkZ+dK8@;+WIZ8FmmZA)Y^Rc*q4}y1=P_+x7#1PjGPb zr$xiO|9k-R7!5$qQlEA;rz2@Pm=&S=)siK%U>&=W?77WK&~kh}*(h6_U)VE0Bo6m0 z;Kr;X40f#b;<4;V03b}ewIctp^9;2Uq{TM3WDX=~kuCY4c;kNkuv0vcTFQ_<zL&^z zW^T@(xO=*7Zx?;ks9Fb`u%tz8-Po%)9C0PX%+|dX`B9b~7}Vj;EsXcI+n2H1b>qUg zwmmj#)egOnNzCGLQoTbU#j%Rz-a!yKFxLMSP~oq=W=R?Gtri*`@pI z|5wXp{$_ojhXnCb-37t|M&he8GJJD#o&okjurK-l!yv%Nb66AE2?A*t4BV(ij^hty zPuY=Nw6AVgz*F9kZ5awNW8=S~M)N^!+hr4+#e3*yXbe09dRmeucAqC3Q#smv@u*We zNl|MB2$PZDqTpvlH60C+Q^cc5Y`H>Ik8W`h<3GL2`{6oL>)*Fvgy&v9Yh*4HJdXT@ z&=ZgVjt^0712wnU&5fGA#v12VM)CEtICklu_FlABvTg@z2B(wgzo?rFy44rIHoJ$! z_F0(P{rqzV9$hjx0IqVau19}q|JsqD^W*XQ!28E5nk1FuV?Nk;&CePEl)cPEpbf|k zeRz9Ee+?30#KpGSzBRh|I~i$VGwzmS+;&GAr)07#RCwA?c<@ww;fyIkS2#Y_{J41S zEgLl6O%iu7S4GcC=LR4n3Vo&-xdiTtZ9@w zl(5n5z;#b9&4rUhDf|`=F8z70m<1v_t{n%IgrRm7bJb^QhV5YRuOR#wlDtEK&pZ#} zy%+Uu7R%|0A+1djWOxjSzvHGVosERApm_Cb)Z!&3CsmZYl2yUJFPw`SCCmTZ7X~X2 zG_FwMtUbOFivnLIU$JP^#Czup;QKGaaHnMSxo-J)2Q)@NSU^;G3JxHIXs`S6wDv{| z8Tq3iV9uzEtLsfo>r2i*n5!}`EMVrph|3TDth^h@HqwT@Q-A)v(BAsWk<;hL=?7<3 zv_rRrX1&T3%?x&b*#sMgE%SrEw>7oh^zbiTKZv z1&W?>dd6rVJWmysK_>*i2Q>Xfm-SMdoE|4QS(z@><uD`hwKszTQj|;J! zc}x$=xa>XWFzHv){2<&)^pCM-*9N24m0s&jSRzprV`M2aX%Ozhq!^R(RH-Zo9Z2ON6;Yr> zy8gizCMY36Y>;>KgwZ^$*SSV7bBO<_=#N`*8nf!w#L2-&JQ)YGv&}U``GOV1*lpq7 zLw=3#7zFq~)8cBA@8KlyrAW`qziN!L7vTTtr=LrNMx(dqs?rwnTW*y0w*U3Oln&kG zGb-&-l(kaf{-|mv(MVl)9Z*>a3%mQeqh0>Y<+}2KS*hD4V&FQ_y~{f^Gu^h_{XUCS zw!0Hh?C9`iY?kH~3;w9@8-q#k4S_ubAmV2`gZnR;jlA2rfwW2cU}33)8HWH4l`R~HMM(wrrC`b4Ic0pS_uJl)ytGd5X*6n&wg;_YJCiwcygw0GtEF%&KpqNOA$mL44@1Ir z`&js?XmF-9JXx5q(pKj_v{4kNNZ{i0-~hG1;pqSP8dyje0z2D({c~11u2e9sY$Z>r zKdtaQ=;V3XtDO(5H3n*GBGjcfPmJ1Ti3(o^bq#=lSXcBO#O>Duc{Xk)hE%ETe{{E> z4BrQBYn^V{JE!kD<%l%0ZZfcB@S5KJsj#Mq_)#BbHM*!@|xQG3V}(kCrub;cAj z^Bm0nCB&&Owpqh-@WKPuzkJ=^IIQfrwe>LK&1`1n1eGdKQo+ovw|bl-hq-EtohM-MiM>M z^vQ4<^9JsKk$K<>zbT{F5hvmzvahs%f>_3cTS;A9$U!a^I&`dz{F+EYl?v|GE9O+C z+|xc15O9wLEIg-2DQVp6nj~zvf3p^rN9M(L`F-jzTvGFt(I3UD<$t2E_8c)wJLJ3g zm^8GWXrf2#JAS4_fA6m*wUuYiFFQClKG|45Hz;MKFFG)=g%bds+ZBb zkd!h@uZYt0MydoEP%B0u(Bc#pJ6!K$ds`AF( zIruHX^mAdEaKoxbCa~v2uajpN4-di6HMmLf56}K^_U^eL*EQG6`t#?&B#Sita}=$Q z*YJpb6~C~4UH==GnpBq*>g(#vyV?9Y#7F&GSsCRl^C1O==`Yl4e&7;m2rbV|H{tiLo z_k=A4ic^edh z%D#|3GLy9hB~t)gjZ9eNIz}k#5#f*VgL;Ll2Mw%w3r4P!$TpBfCj1*}N^dG=9$P+0 z{Q18*v!9~Ii1v(gW?M5<>Z2<@tW9Y)UA!g=8NzGgs#_Z4GoN85@uD2_T!<}To3}6E z9~Vt21)2LbncgyZO86Z3mH<$6C9Di+9HGM2-WISfvtSux!qH~gyNaZG=3{Xw#Ex;- zmcQ6qqEU*JBACbD3&{x{gXn3@r#1cwC(iVXy~Vqkx`zW=4PL)EVDHESg+7pq^KQO#LU}%i0*MvjRsO;GM4kC|=6) zX{+T%ISuMz+Rv`{&^Vjhq?)J{+gXV_kiAdCl1ZAOm!r6%)*pKoKATJ!v& z35YR}7hg_A+raw#4Z$j>iTE`%!VxRP)=Zg+<+P3-9vOM!@$4p5{sh~*o%FNR;Dq~@= z)8Uks>MH2F>Hnp$z)}8oBl$e{c9YSw4u_PHK(=NUTI8%f9Cd-m`GBA;4D#|N?EB|| zJ3i54-Y1DTS0G>;HkC;5SAt2`4A3-3AHSe>;)ei2%C zYE{2#!8~^iLSBZQ9`%*$o8vXTo+nz}acscxT$w?U9-Z!>C=dxO)}_n*<8E|82;xBx zi8IP2oouX)mzz7qf#F22OVX^2-yuZxaU`0>Hif~#Dx>nBTm#HpJm1A_nkHLtTmfj^c< zDs`ng6=aRd3XUGaYj>oCUB2305^)<=sP1UoOHyc5nCgA#{OE!ctJf-=_h_GPDgc4) zmc8dwWpl?{Xl^pb`qPjz(R|K^H{C7QI0|>|Binr#V_imVr^{|VFm{*pH z_>Pa+%bzGuBXOOWhoI>(Zx(i9M{S~_%7@izFN@jLK^Kj)=QYnALQ(4uZN=rauUyq# zyW#`vz7*oG*)dn`3EO`Tg-RW=ctDSlUIee7hhr6=>^I*zNAZv-OXEz5FQnd6mI-Ohsl|{_=vS1!eVm2#auiZdxBkMKQX%L= z=dVpqHw<_#o;pXJad2IbydK~TXm~e!GRAbFb?a^XW$BK68qXcc2r6vk;p80O-<%!s z*V}I5>xb;qus=VA7*Oj%9=%6jM$kNdbIcKXy9}f8K0?v%y zDHru-u+Zz~9TMV6t8ol(Jwh4%iY?U|S6uJ83Y=&_)NSAK>H6ielShK}o+wweq%;>Q zJaWDp%S^o}sZx)VMdC4phlpGLL)*w)-)rQmeGw$&&ACzO1PL7cdwP@wR$%`H1QDUB>f@##%ztQfj32xC-JUPm8dxM<&s73~Mr3F& zM#c*GvN@sw&idEu9Qyxjq+{=UZXRyz9SHVU98}t=&6ZoUgSvXZRXhr1)3KEb1@;H% zRizrxl1JvL_9l$Y?Qm945mSz8lQdhP8n6@vdiqmm3c_X8kPlf|i>61t(=QB)f6Z^k z4XN>a62NDLC(UP_`o{wmCwAV!R{Qw%ru5G4uQMXK==aP3ZB1x#Xw&q)igOMb~26;da;b< z`jz%H))?bIKa4s_voMF6qiFT12^*{T~B5rdL7{p%P4YUDO(c#-nYS`2xY#QKvdZ zJxb4;_^9~Klo*a)OBD>Y)z8Ccw<@Q#zdO#|31|t%GRJF9e>btTP*WpPTWK%wFQmwZ5Qzq@vp*DwWVF+ z99yEme>d1K6@M$;`asl`3jU}sBPs2I`G6y}p@;Sg!76a^EX`1n1ggNLyG_*g>BK>6 z8!w>P2{>L>A|ZIU7%Njq31t4LVXV$3r^;NTG+t$D^$iS^LFYXDVRwxYB|vchK8y

%rKSsEJJ zUfDsN#kt`TFu&V|+hJhlO+rGs&Ld-Ej8YnWxSYi$DA#YZVVQyu{th_aJv&ud@JLez6 z-}}h_wG=O=V$L*9CWfxG0F3*LWA0i=1OP?0*4=AQM&bKwOYuMbLx8ffr=;=KdhK9i z=o$y_FVO6@TP~IU(dOB@et1ckHZKRgI{kLL*bwiR2G$i^4+-&)9}0^Q`g_NFGbA#x z{~7NX)G?csQb`~5YXqvoKHl?ciPIuoajVMGDX4Iz^G&`7?G0TEFvzEG7h;Q$A8!Of zJl`%DdqbnH|W7mD<@?itVq&?k45i&;h?a=AdDA|VtvtDTw9>OeB4K!PL>dQ(%dN= z_y2kU%G_x#P{;KhR)|79NXqGhTJk_dC<)qh)NJ7qs}YQ%=47TEc2(B{4*1Z~5`70m zcp~yetbvADboS$`SIPgs+>mMc-!gQ~6`K@!qzmBPf*l$}-ujQNjCP;&TBj|v?@Zc2 z0O9u~U%$z-F&SSeZ7!daWTv%&A!e z2BQ3_2{!%Tsbu47Rxhph2l+Db8_2>vcFYi6!3`~`3|N(agixlp(Qf-4%Km#o%PihI zEn_Zs`3}hpcre&Vy7PC74lnnJ8#p{Ly(|SP5gc1hQuPF$_*3!oFVq^=2l9=%^{A2` zo%jvMf;}ZncjLo`zVS82`sYu}+np9VqPu1;k>jz}r=*wzyrRmPC$tcY*~^kN6=5kl zrnNCi%od7hTNOqti9*eNJwH03+!L~#p3fNFxq9v~)L7y)KSzBfx+LW}5LM}zLV zJlxpA^0m^<{t?hOlyT|XFS&4H9JilnYM%L&o_wgyteNu&)_+snY{IC#~CYpOt|M z%|k-RKrfc6*m=W}fJQ{SNSM_oYw5;E*KA9kaJftL~?iSIv1(B$Wfz#{q!d*%-l zSgGy(3mb!T$1rYAN=H3gJiaP!e(@zR1d|gdV{ehyHkPtmsqZuvv zqv`*(u>I8m)pi1F|87K%4+em>z{SO7eQQe{81wfZXUTO!_=lNu-P`|KYn3If_vf({ zqP&~yRMh=UFrHU;F&KQonkuF@luz+)f3!Y}$g^u>@j|6&_R%W!qcm%cgwv%}a6bbL zy@|Vkjq1v~V-`!E>FYMC7Y^LGGDloZu=*WrgxyLVyHsjuzbW-~9n=4V{u^c-&NLOk z67{Xx^g(;$yF@?z970ejsTX?Tu+j+B1A6@s9cmNinSPSr=;x0>izVlnN6Uc27g#9X zURk-5G|Yv#40TZ*((D!b7z;XV2(g@0d?tjZ+vhjbyha#=pAK(~1hg;3PtCsB@~tl2 z`qu5<^4FpY>$ob{+rRGNE)fMbMg)ad;Ze?ny*AXEk&tm04wJ*xWpJywQ103wy&F}542k-#-{5a5f z6i`hMzOe@$kXDz*IuR28Fw(F3pnrb4yaxFdZ%m0Jv-`4G8;dwA)YI;ZY~yV9)b|2C z+YnC{J3_`_H*E{r-8Z3bECL4=d}v;CU3qwVmDh6Wgoi6>>iFRiwSG8xL-I)LoHv%R zTqB-5?U{7qxX`163PJbBmqLm^XrN7xE|lOY>dUUZw2RxMp`1F78s$GpWrZm4U3(Lb zmBS%5)cblOE}?(+>CJiq3Ftn@A|t`Q+U9@-^C1~;&UH}ACh>SW!%5q4gaQ-jUlz&P z)~0=aPD7}F)lGfZ|7Y(_E9dw3Ie=OH8XX4$9iDT=TP=4W3S4s^X1@W}C`fFT8qhxg z`?vUSd2j=IZah@LNmnB+7%>P2D1B%5=AC=@=;SB4Yw+r|uBFe3@jM><$_H{yK$6`L z_AV=7>A-a0Kf4SjF4k7N$+Wg651v5WJQkxInL7W@~@!F<*OGsh2f zzP5EWTu@;{OmBI8f$h4~Un_7!Vyteu(!K%hI|^Vh zvlV1133BaAAGcY)@%`sVjK$paq*-Oj%qkvVgGsHGzW9$2*}RsGp&SwW^>^kDAOMvH zn~y@+#8^t{SjE(!SUXflk2i0G=I>tV&Rk7Vk43QX*9gZcg1u5$=a;vlWPl(rjui#9 zd!P70p9|N&6(p=nm~47@49hn;9P2tPO1ixkps^TSe5w6w;rE;y&Q(`3-7VO*PUuYg z-f1tT852$A1g%G(@q{@3BQGTNoVH;OB}@ffXhvDAmE0*b7*U>MUVx%CvC@1 z7|w-5h{X-iogP;R=iaUGMgj>`)l7~{ul^q^cw%k$IXVzF_-NIgd*hE*bpMpmwZXA8 z7{cDqL?9y$_*A(q3t|^l+%Bpn5V}&_TopgsUyEk^-ScUjcn5<1bW^cW2F6P2UwM_* zO9GzS|D);W{YNSNw*$Ojxvo3OqVwEcf2;rbt}u$t?J5clOk{dI_W`IO(RMdcij`)24{^*0@i}#?6vWE2ms9hEexJ<9} zEwPRni#0p71P1RIOE|(_a)1y7sHD0QQtc-3r$GT?z47N$y>O@MXD%M&W-$9iyx0=g>lNMt8q}E%H&tJQ9i=*ZN2?rG6{5Icy zKK15r4qg3EtmKE~xtDOs&|Yw;x# z2oa-~d05NwtYna6<>tg6cTncK!@|Jh%u#cmc>F(^HEm@l9Pr4yqTu~eF;L3$=o}x zx`zm`Pg>R=!}!indzkf0c;We}&Kmn@9Ko-bR*4Zp8)BMVt24F4;xR66;j&;3B$IZ! zmF?y|7!DerU`0L^jkAcnR07gIl0JK@O%B6X30jGU?B!~u zV^ts>!>!f*i=fkQ^T%fs)8#*oRvkae=bI?ySNqr3QyTZ)+UqfPhKi_#4FJ5PfC5x zf4EukImlH=s3FFAqNa|rU&zWsz+)AHt|g@>mt+Xd-_%>cUyfpXH$pky3MoOt#j|Dbf)7I2v#AVKa{Q9ldS?V`g*T?!Q%85v~7IA1MTU#>2mWm@qUm)0ZQ8m|H%^1z3`~{o=-%{(v`SqwdXk z_=4T`Xsex&_2MFX;TK0kX}=FxK1ehS49E~D@1vM6ReE9l=qZ&e4FqH(=~QYq219FH zRp!o_14hG6gkYDD>&Y?~n^zZ7KeTzcc@O8)^DBa#(%fjJ?DrhZt)_rkJ>-(;US{+F zEh2<~)FX|#VN8x6{<`)1XOBN5?M%0{$@$-_T)V-Cx;W490!9G3iBUq#20iTRlfx;K_ITW8LC_t^>XDs4qPku`NFr>us%_y3@B!p5@XU0C}u z3oecDU34aRg~y?j;m)@#J2ntFaXw7fNm$PcuNfGakoQ?)oS|{=WRJ}24QLwUv2ERi#fv<*CPhAr5@@pT1e=jh4&T(Sjhw$^cfHw zd(L~Ht>U7&*~r2HsOVw-($#q_p2tEU=VNQZLo05w`QjZnVUTy+awr6F2roD1(~7v9 ze7`Y_d0?NzHm;>=5%smp>)eMK-bgBOLRQsom30|#{BK-S1Fj|Ogs}ZO*?>4Y zWa;p6{Dqyp0>V~Qy@S>)@R_Tbq2^B*xfU| zEBy|$&4zFxwu~X6PS6xu<1If|T6tk`u)}*KD%cD(3E$4a@ephsFPV=kv-! zMXwDal-Hj)~i@6lLvse4u?=S>Q#+iPBZ$;P+&lpvaub3q?H4YcXqS|mU(X6Gkt44T>nW@ zuOYmKcP|c-SWZahRjT_Eg+l($GhWbdFp+Aa{V9Hd>l}!m-m0W?ccMhCynRZDn2tX| zh?Pm%5IncT(wPAkT32REy@7l2tX4?t-Dh957(bXeG2&>0qatVrJ8F3;R7m-+0< zz5j>qIYMD{QK>S^IlS;eSXm@)DK+bT1Enb}{7Ku>nK*^hiiJv&a;jRa+X^h$6c7ES zJs-TF@s56Iv)vka4;jbP6KB5D6Y@39uK&`gT;XZlm$z)6(#Ftxnu$N2u8C#brcZ$k z81pOflPJn@G?^j1FWUxwRqV8tbC6drX#3_%eLvi5?XcKOgf`i(eloXmBY8(?dC8hy z0S&y&YQTTtAY=qR^a?!pU6-W(vY*==6tvOVXifd|pbaW8U7kgeiy;dGH!xi3su)U~ z2?yo)?FAhhO{&{q_CLnxOSxb;ZV7qNPGJH{b}ng~xsdE?kTt6^vuo2B8>8A+g?KbdszZzIm|GKa0vS9~%L{+Rp1?+YL!P9zQ zXbBd*W1cqFzJguP?Ol2El4T^)TXsZv$Sy8>cc{E(%74I4^WOWF_rLm8g~cT?ey8`a zNa^m~;yWNbQIiH&TW_1SJ$VxAG`%5%y|?~Q!!9IoJm0@VXUEqR;lmnIKTYNyHI&hW z)MRV2I>;#NAZXxk$e2t2=_K7LwtSG&;R|n>BEhfEkeOXTzs9Q{6)4#`@i8y5nG2Vi zqgk@ISXKyx_$4^V81TPZnos8k@w(gYWoMERrd6z`nV z2f-*0?t5)9HQR0qnXEZwR3M~HTCUn%P6S@hVo`j_{Gji;lje`3Kg9rUIZib$5mLOk zM>cr?dH0Of&*A5UDyxU08O7uTE&u+g&o4vQ73AMZFsFT64*#8^R>f|dUXx*+W0izQ z?E3T%ad^hTm#jgsls79ozjX;zStYr1peoh-yyjN!_X@wzYV{~QZ1TVw#;E^%n2_i` zcs%}{=zN`XcPTQULF(cXp)UDiabaTEtSVXnL}G<~*N;uJ0DUYH2fShp%c`XPQrpDD zB#L?}7T*K`U=jg0OowAAV9m>!g|9UX!oHl6c*+F4>4#1am;Hi+A(Yhn%_{=2$1k?9 z#<+Wy{Up}b%+o0LuV?n#!SeEgfT<`%ddgvWL@cjvEk7_;*L~MFn4I;w_KCGtithng z3XU$LxKjkq+H5;5ec;v;-5=%;wFk0GLm5rnljfKq{+k!E!&D>hA`-*<41qN|ja~if z+Y)8*c9)b_^9q%m>OXW}DyfqAnc@i-D6_gGSXz;CimL1#)%e)EhzfN0k;XThI=qXk z@g>RHdL+-+YT!T-gex)!O}#865FWL0>)l~Ayvv&|m=VJjWR}~V`(PqfQ8WC{s^!v1 z_Du4wq|$u~P+5vnnQF3Xum9lTa@Mi|tTg@Sd|0(9a%X=2)JM=Ul@Z}~pK3nnm)3K> z3EyA8;e!W{*Uq#)X_v-rUVIx&F^^Rjaw`g{i~EB z31-fzO%!&a=o$3HUQzL)viV#5S&fS9MD6> zONgvG#SBP@o?-4$n9=XKg?e%lxp&AR$fOP`9%mTNzD<~1&XKE10xfO!H=$#?U}(c; zJKVkA1OEdqjc39z(U9b5=jt(^lK-Y{G~jEc9q)n*F&w&i<5x)o275XJr5YKuI)Uh}I#sv@=u`gQ+&-H*0V0$F z<KkU0`a3`AwuT5+}S?Bh_&vgUE^9Ot!Kge0LkXR!@TgFqjr%&#M z#2A{NGrvYvP)_e3`Wmx6_LBDlA?Fp%^dZ@~-iVT}iDzHB`-& z_R$elvrB?mUQzbL`tP5$DNOqXw`s(7QXS(y^DO)w^YENPGTrsEi?aKjKi*u?QDpLN0IcnEImM!)@Ne9=RiH?6vv_VDZV<5^_R< znqMb(Qbo?V`JN+MUs&t+R@Ram$j(0b7X0luPaY8N<%8IM5NqJi{*0%F^ql^k1-2Y| zBu6lX-izMpD&W=WOL9;sH_g!C@a<;%6IxiYT>t!)3zwOeiLLI-6lg(R&ThjpECTN)FY5>fv!bshFvk% zZ{sVD;Ag+gJkx8YcG905`W`dmn{`Tu6%#?AUgk~yddKY5K(6e7u7dMOfWXk>m!z`C z83Y1Dal{=hK};_Oazkf<4LDm(axYZ*ZDFr=B*GRM;LuQht*zkoHlbh7q(s~pLbgY6 zE3Y{F=RC031*OuGcyJ*QBQSTowX3-LD^dC&)R1yG>NXUgZU;%1r6G2^VHWl@4Aio(d{D#4D zfE-7_>}D+=AMdQGQ>rigChFO3E9XV3w=AuiiFr15hkbA>T?ulTwa_wPLB!^xxzOe?!-qqE5Lg)QwjpB+6c}(UJ zui%JuLqj-v_XPS|@4Hf2Nv$1A~1yX`)6POY!P_B%#${L&N3GAm#-jWKJ9eFtLc&(jUXs>^y$~Lbqu*i#d za@yi|ki6;Z+rV$ov(&M{v8vcMwnFRmXQ#>9Nc-h`i)!DiDumGTYEyJfhLaHV)Eej~ z;+yurAB``_k@};e047qJ$@xo?5*1=t$yXnj|9ER1eQc9`Oxz)+tUpo^^CcE#ti7A@ zxGLz9hroGhn*qRyZ!0;=xSi;x;&m13>fEiRA{Vg6vnPH((xR+~$`|QFdpu@^>%xn? zl+9_xvgoqRxpfB$^DWtd@U!-UvrnQ-{cxPe5lGy%(SPNc^^QO$^L2=PkG4O91)F|LtmwT=N=>SJ&f;^|CauEO*nBfNJ)(J zf`m+ZA)xWopibxmu}S{h{oOlsPb9JYe}sAl{F-$Ql&T*CQM+p-ABWc@lZ4(El|AQR z$_$}JCvM8}P-D%IyNV+H6lu`yc8}8eblkQX_?GcHrNmE9QPO$|dc9&}aBM!)Fu~f3 zr$X-1-(TG!P+@nuO*HwAQCyPP|5W5zH4GL%7&S;&-@lt`nfI8hBbnyxg@^<)5V1a~ zohaWrvz~cUdKx+Nj+)nq)rgcI~UAmqa3zrV2DXa zDzScW`n6`&jGFHF(_bHSEMsLfIV4cXo2)YZ+GGb9;Zwt$1-reKj->qbQN?8Is?GMu zZ~X(vpnTTo@56Dymw)+7^K2v!Jy?5oIjT>IUdb29ZaEW$5E4sv6brd|{h4fNgpLh8 zWD)u{#V3=}!+z!F2hK6NJsIswh)RxO1g@ij%!bR|s(TA& z&=VngF%`oE{JdXk8YQveI;RHLn690A4857F(P5sJ6r}*1_JMouscYevUN0VadP~=G zr4(dx7v&WgS)i!5Ehm+d>PYI^ls_m_YiQ`n!eHS6;4>Q6BydiCw$D5H@7!iI$N86T zhBF-#?`p&L3vBPEihY+_ZZW8k8%s|1;agsc&DL->M~0*P+*+h)Kd3^+Hl5UBb!9&| zQUkX)!cfJ)?3CssbP{1Vi?#iwcVrHK@46Rt%QkL7HGdN^WstZ+Yr>g$vGWj=#p8m(ObeN} z8>tT&`R!b@2v3{RADrlyJ)gFbxw)K)0uUK7PL3OhY;BW{^fR1Y=z?DwsW1lt+j|&| zvIr%Y>t6^3*a{qf4AKpp>zjpj#Tc^ zs9em2;upLvZ&;&@!R$RMH%|Ja&Xer2KlEx45qK7PM{#B8vlN7&KSTE?!NyrM+sVg< zAo@4$<0zIV9#t_h5`Sqo@r!bor*VFmV660~qu&m0CB2ba>=@quJ&VQy=q+W@DM)LJ zmzBEeWovk@)~_Ld?4ci_Uk1jVyrzyWJLW^fJeismd0CS`g^rdI8A03+;NO|2W})qs z$hp5|V`N1bGK`ZO^P2iG|7jTmmS5*!9U-iiw1fHTPK9fcaV78FNYw#kTd$aLMXCMp zail&-r(b01YGRb;o7uNDbLb7E4(?L)g`cZ47R=fcSfzn(W3w;cBj@{1&MpGtB~<;I zuS%c{XEg!x8V*@A>P#XeAt9lnrdHL~=0aU>2DABboy1E@P`@NUy|~_}nII$bNJQ{h zaEbJEVhHXe%!p68WuWYkvZ#4(10-Oo9NNfT#qjnPpZBtD*`FZh$ffdw%3q`&_NA7a zKxXV{LI(hsJ|rrHVz}w834?-=TBL5%MCw!c@X26;HAo-eutNbJ3Jw_gBJR1~#9zlP8YB zp+KZCJl+@sfGJi&!ikKBo~cVLz$v>Fy4bo>aXouhr9ZsC=6@bgDcJKJ4#N<}=bLw( z?3$t3oW#mF0Y9fU>14zUY&TQ7^I#&XeOihOtx^1?3vfqR_B%>- zY-WyqsyDaa6Z0Iw2tKO3wLd7;nPyeEvYN-_f7g$CMdw0J-YkzY=b3lji&B{!DVHk4 zkEz3`0U06^CT*?@MWxa}}Ek>5n|8Ae6e>>fu)InEmS^FQcQ_hVmaJ z;i`eR!XOgwq(ogK&i%V5A{AEKM3>pOsMlU|9L5Pa&)uz5)1DQTTHQY;wQve#K{^K# zyUHbP3W5_rXOAuZA{!8&4c){T_mvHMKhN59O!!OBW&!J?s^15*5F;WmPO%G!T;Bt5 zaQrSqz=Vfn}_-TnJrZQ8`Q>v4wWOm1)e)EFCa;w zSB-rNC(XwXm{Pe=V9PWKrtpBMUxxjal@CntfNQh?6phBKJ!F2x16ODbK++}Bdf%mD zohoJYo=${CCWfTaLHS$V_~&x=dCP%R+;Q^*%xL+}y6WtGUK%l{-Os@2X@K5>-+z8^ zy;kWo2Z2b<%X`e^w%0@icBcA=>?R}tWs+{N6iP(!gN(Xh@<#$<<*W}>c=_L&C=bX4 z?2|uoezY*h{hcIQ4{Q>symv3`TL5nJ%V}((yk8-KAGquucPe);7RFtcyNX&*v@2WV zt<$e(O8p6M*}N|#5mm3yyTY&EcKgF`n6-4Wd1F<(nyUqr>9hH{&(jlz5zDGJU^LIfn*xOs$U{DWZ zYscX7*>m4Ja&O$QkG-`Z&4NGyuO>~ztN~U=%cnH?fR5C zRi)#P>k9z^Bz74{6w@O=Sfv zKgXpOeNdnetpbQqL0e9YOQQhy#TJq3#Z|rh6;BrJbibX9z^8B~*}zxeWW{p}zLaC0 z7JIGrda>~GB|1%4^+zu0bYtO(#j_4Lvwfe)Y>c$ttLX_7aQuGBwE?rtL5Jo19V#V^ z5meo4RE@dth|y=BXqadVtWztgKO?hXKIc-q0yR!%8HiH#2Ej7?J>(wdlbcHlRxz&y ziibR)4O-I8gwv%%&l!MA<$a|qCDYVs|C!v3qBv5=mxA7ts2-xCDqxZOdv~>oQt|x& z-9^>qt-?zOev*TW&~dQ){jb8rWVQRq#_weCRW2jts`{h*S{(=?3~}qLj1~h=ot*f+ z^bX4M#I}W>Bh8hna{=B>3Gvj@gyd;cJK6Ap;Ev7p}0(qIeA5_BRvd$uTbvmG~p}|S{ z-4D1!cm@BIV1s9s7Z+q-*l;D}qOVdaq`7JC2Ky9JYmaM{_^s6RbSZT;eX%o87 z9mR7y`0Gp6nA=mE{>lM4I4#L1bLD}7maj;ObAz71-5u4Q^Cku7=NB2Gqm*8SbdlZ? zDZDEv+hX9LV=JD#`G#fY$Lp~doD#EL&EqF7?)4`vn70GL3FL}Hz@FmQbFzuQBI6T# zl(;NE>voCCKaqcL!d~hmOgXkXEd{3I#Ca<+A^4L!Lw>&dabGA9# z`~UIvmT^%x?fdW|D$)oD2m*qXfP{1_DQ(cPlr$2OOQWO+64C-nN()FYCEXw;-5m={ z=RUJ~dEM9V|Ki~VA9P`NzB6YW=W(1f6F#?bCvnGm@ZFP=vjMea-I2<%@^d`02cZC& zL-G_8Z`?|0;%%c5REwecRG$8xP==HdGXRfW2O}q3jzavsz@=RJI0mj+L*Q!;tgd1* zNu`%lcErZ>3)dP>dsgf2nHo--{J1dOzJ9U5H0N#aDMqzaPHK}gYEm|8wEoumKBb4) zyC&>+fosl2m#moSRa7n4CvW!5lzKEB4?TN^5Pj!i5?EU_W?AhpZ!!1fo2F&LG4EQ9 zVtS-)cf4!=HIr!yIy;3)>s!Y896kc-Fm<%5!t=wbNGoD@2Q*O_?PSV(pPUD9^0H_} zzT2B^-&16a^3N2JHtZpWYidMJ!tvxfIKTP05N18NrD(wPg_t>92}|MEBWwckxrfR& z%;6?FKeRmR0#cTx?jP%tiup%Ae@Cexvq4C#RYvLq<5`oiZB>$g9CG{(aeC))A}(z( zDB)D)`?Pm{5Dnw^OCEG`knN&5Ei956@UmE;`bOhPYIFa1=3r3XE; z=#DH+F^%R$XLw1S{82AevnD25ItpL7U7>jsxmq(b8dsRj?ug8>2HfIE6L-%96CWY2ohIxI;&_j-lt5VJM)G@gzGBOpBTGRn&t*r7 zvl#r-wB!}38cg|~l*k-!meaV{Y(HxBYjR+Wfu%lvkxr-IET~ZWI%01ba@|NHQRbJn zT=if^)=;QKJ+FESYTQ?^fxs;2%^F65y5Gj9&wj-d zALa(R!&WcswrMAOi60l)H%%GxC$6d{ennXsdN<-6O>l|U`hTGL;nYT0b}+)T`r$OB z*)94hm#iQjo?Hv}3(X{InbOa$D661xjW1lsbO=o`wF(Gd+x_ z>;S50xg)vtIt=mCSD9p&alZFr`ty4cB+gKINyX4KJ1wWV_Znujd6x!7YJ_;9n(i_C z*K)1n`v8*CSUS}w=R!IDaG!gE?NWsl1sKbPXQB@rQpDaR^v|Up%QG7aQ2VFo(&JXBx|9^AjEoFGHL7gF#Gq`Eo(Dg_P*-nxODHZ_u*FD27ROFOF#lb6 zH*f(fM3UVlG0nleXA5wHZ*ncpU!zFip1FQN?lBU3Z@X^sP8JZ;Z-ywa-p7j)g)`gu zb1S_y*=jo;OOjYoLX1_$9bK>8KUtvd#;kN5TlCvaj3R2e2E8lko!j`f;*bQ-S*dce zUu}jChu5dppLRJ$9B~#X_Qjw=iD_bR1z}U!T&-S9GXCG)Gk> zK0)1w%U#~S=NVh^9L@`qjL&-f1!bjYjWh6bkITm{EtMA|x<83-)5k>_Roow`h(jpJP%n9x~(nvK)nRFYzTy~!0OM=LWkD7x07VizuM%GG-{ zBwwA|8u^TuYNMp!V=hi#p~`~A*Wd^NcMrb2&=&%Wd%;&Q31ZHsbz67CDW17cRU+E3 zYNd+WR7Y;%(_ob)SI<7UHD9ubd)n?|HsI`cKU%WemCWNjN0CQ9ZT4C>*E1)~Cd5E`Z#vlamD z^?q05Q*K<^rs;2S_FK&TD(80wtqg@OaNd0}Vqi8}6MvslK|^{=tmEB?X%Nw8*00-4 z^p>{-y;0f6R{1QET)8!tg6ryH<_?$3VqC|q!aP+JWoJZMQ6PL9eD%7AAReqHoO9d0 zPo=^V6;meLL!T?Vicnjgk@Uio1K^i|`NV2q`FBEv#L~>!NnQ*{LNI zmJQmKo8eN+9zcFdpZpR*&cU%<8y`{8G$pGpe@#9y8r)QX3x#GOdsD{ZJJI43kM&A# z^5(DNx7F3c36DUGm1MuGuC9*m6q%fylboj7n-Dhuv|6WTx<2k8eF*E z)Ub(Q^mH>8oz&r3_cea_)YPc*<24m>L1u09p+@#I|G`gd0r}b~oneVTQi#b>8+ACR zn6{UN&9nUX+I3|J>IU_)E+{`&CRWPCngYy~3lGLsi zfx0tg8rbn!bjr~ZR$cQ7&9Q_doSr)l6p>GLUnBua45%tE9!})|8AheYNeUWFyVtAU zj=N{aickU@a#GrgNy({Y_Ya7$VWzA_MD*qVaJOiKlML1-V%rYD#i~mex^pkJ$#qy= zbMEL&$YK7fsj2CpPF!;nm_|8L89E6*AkraBC8VB zTRu-jtHb9zy!_>E+lQ<~(kz){s25h2(CbG(ZLWk4E0~%R@(*V)i8UZ>B|C%Wi$*{3e} zx|U#pKTI*>X?33L_o|7^W`jT7wVdR1p_C%UyK;`+m6rm^+L7~BTWFQ~mH)ImH4nvA z5`}8DaI^TzI|-E~v1!YhbmQ0 z)ybWDt6MAG7ye@DY5Fot-JLO$#ajxwzJm$;-p-2Rm{jnOan~#P`vWv$+j>9Pu1s`M zGH;GrI)8gupBS}o9PWH)#o}xrwAQheMZO|3@?|51YqajE&f3926oBzj-He;ByuE&u zgOcEYapOsGwtdD0i}DnbI~F86v+$nX#`u*mf;W%TX1l^B7U;yp-j;`Vh(qso+H2p4 zVKR{z_>h*wfDo4JJBy1#8aq+-m8;nlK!^Oe*08DtD~f|j%_%&-(TZs^M!6H{9$#qb z&fHDAe>K*0-U8d06+=|fM`>BrqrVr?IPl!p!x>|(lkQHR_xr*#0V6y8@Uo@5RR$g@ zu|+ma3*=ah!9*%YMuM0bo96aEi%8WC%*SV2915$$14kG0} zn&}tIKK*?u*Lf)KS<9FTB0On(Yo_Ha`q=!Tu*eW@M04fQWG=5Bj3A0H;G0ZlL4#if zQ`iu%eZZBgQPgmCO%=OSc`kev^#BXbim1{>9bumGXGWz&Tm_;Pbl@1;hf0H=ZH5&_ zZZSnB*(?R=mY&p=IQ`ffgEJ)cy&Pw8vN*SqVV&9N$>e$vqI#-|q_GOI`MMBvQ6uz| zMpD3ul(Z!3VU^{QS;<~3gv;;+jIKx4q`fuK5I4aqyOP6IWJ7WE1#FY>(TJs6Kic`>a#-=wdT!VNQ!6RYFP84mS^1v$*i(gQDc=riAH8%qWeX&g!VL$8Bw;9&UB&?^rN#v~cqLQ*W5KP@co-rNJ7w_H0CSX6Uy>~TgTP{Q6~!~zjVc)?8K6{pRG}S zItiz?Hm3!5|LRj{Co{;wOfiCt^bq5Mj^R0g0oMoE8CVTSJ zDMDv6%qPG{nW+lp4e>C+>VMoQacGYW(Y2>pWm1cMbMQVWA5nj0xqC*xduZi`CR)Iu>tCx5;d9Rjbi)CDcjDjPD?B3Cp(G{XcToA!)Doe?r;`={Z zT^3N};av`_c5g+RV`4_`8;C=@slXLMM_vSp@~0 zgoIsGRw5e!Dr)NLyQ}FRh;LkFs(s%l;7}RX#$rXtK&^qNa&5XkxMCAwE1Io%ZQZ(MkgHO`Y^XP*>Ag|@<%=X#xk4b z$%g8{?ji0f9c}Kgip7GoQqN~9xP@pKCeF%LpSb(m7c90 z9H^|h-wW)0WbgZprq!(YnXX=_OlkkdMrO~H3K#LGvI)Q?({s1VHFA~RZyZUonor^6 zF!1uK{TTZ(>R^>y>8yFhMB!J1Lt5%j)jEG+qU(?L{Bx=g?!UQ}Lm?!lB}}hXoo@Hz z`FpNLRlE7D88@Nx{l{vqH_j{x<136Z9yA&$HlAQz6I*jua}_8bwB>rd>*}yw7xcAy zPx(#EZE$*Z-=T@Mx4`PaTaHW-D1%z$yU3R^8~DZ|JgAHhT4* zPBAZsa7yejB9X1Fk7wLZhp!gMc9&gVdY3#beTf8eRrg)M_tj)kp<8WT|08kn@WqTy z)PJ;ADKE`tJ3Wq#*StYDKT+=^F;V_1y|6GmFfi~>V$te1ZmH!u02dagr<)vaP}#vF z^=n*;T@llY(A4Ip`KXg7@1Oc>@yHzg0(H5t)tCpQLIOC}~jzGc21so2wY85&rfu#zed7`bv$& zql{YIh0RrW?b}C)_O&TXjVRKcF}~h{CoMN*nUBY&Px0A%GClW12EVgYtV8NXVBeZ!E|9&n$=EtDoO?b}il1KZ>l|(%(Nl z1syEWbDeidv3EB^^v`z|qj|HewD{OYvvjJgDbK7nMLU2oJ%Wu8+ve0Ilf&W1O~5VP!djPcgZ!8 zTll4CD!gl%z9&J!dPZnku=K+ctc$xRvMn3v;Y%;@GirXq5Y;tRUOlh$w7nU7#Co*U z*-R5M8OEZ81_!$lA4HqBvqrOOdvP7GM9;U|5ulmH5i|@971boYQmk+&KVnzOd)v9G z0D4zI$IR~8y}obt2Mr$!1=8eJ@2t*Co8Mc~UfQfYUHE>OY@)gc^)5ML{$AbJGyaO$ zn0xK7&>YYw>`7_7a>TxM;Sb6feq7hu91y-%}A-3`hutk%QespxyD091FDB zstDH~E{;S<8V9?V>dt&c5~#P@GjT+cdIXe|lq{^QY31b_Xi=8Pxc})86@d4}eh8bK z--4|}t2iBKWR`ifhRMS>kVmxFar}9d;y~8F;|+9=@vGKGs(tnD{u4ZH&x2;n1fH9F z;Z=3FYs<%o!z`8bvsLk>z9>)VO~zl%63-zu5xeP zsiNqsqSq|U31K~)&!gSN!kx>`*UQ;fMHfs@o@0#$T?c%TkFx&CrMV!d7 z{jaXbmv2?=dK#%-K>Lvw+)6rJn6laOb~)kcn7z&*LK_GPYY|K#lW zhuvj3p-pw%EA`Q*pP`n}FTN8@!tlv~#@{h}zxHP%?ZjDT@>M zGo}VzNs~HWxWgxGV`}9$4cgmau2h_G~u(;g(S$e170cJ(I{)6_Ia z9dfcB*ww!eDyB>0>j47`A(lKN z2^5*7M2IMXlWMyIkBd%zwy!O`ogU!ke2?#LF1)DkMyg}Y zl((AxrF-p)dG`ZCvoVtta?nGRW$}w$1GEHc5t6)re~$Mc_gbDAAgK{ET*@R(L)dF` zb5DkBi%p(AV0kBb_f7*BetzPuB(rQHj$?D z&4LU_M$OHd+fDlYa?QbpyIM~?*f5jKq+X;u?1N;kWX=?@7QpK)aC4-o$zjJLG1sW# z*R!XeVV;?cz<#K^=V~C0*L$TBvbdgrEQ_o68Z91)ZaY{$ zd+>|BeC~`XP431T9d>X){9{dyvF`1`Qh_ge?09?JH&SvxdicoB7BDlE>t>W2I6mNn zAGd*)JH9*($MsA0Ub%CJbi*S}fr0AU_c0sZ{OM=pp?#}v6tn56m7I^+Zieg>>P~k= z*L$%JbP-81Jo=+*FqpC04I7G{4~?CW5ORVO8d_W7BoQ(nUPHCtkLp3 zZlYb@nQP)f7S{nF9q)O$mufy*sQ=Ipt%N-J2I#r+R}-yhemQ-V4fMDMFHD<$!KOn* zfZZ=n-MIH2BaS0n+n@G}+~Y-bg=iCHH z+4t=k&o(U@pG4ek49S*ZQVFCnj+dS6ijRLWexy|W%M1L1e@N$x+V1|BQv+v^V< zU;NHxXq+j|mhr+rHN3TAS{!|I8b4s2_P7_7{bdb;!&=tVs%&_HI$uolZ=(Ve{bFr= z2z+3Rm?!2>*FI3BvT2b&=99sysA*~{qJ<}NORy9+6Xp1it{8)~MehgJLe|7&;k`jo zbCa>`uY%pTy$Qse%K;YsBI4-pRGiDn137S9-ql)g3|X!sg(w6N!Q7Q z>p88`;No0deUEka5nfOa=(gwoXlv-zA*`fy$ct#94wm4Sxj~o3Hjy9$DoLo*Egoy9 z8+g&G*8{tluhwblEVEyfkm0@=r8>jci(@?~^>_mAeIoowqLqaC2+U37$=<@E#0anT z*{#rt8ID(rjv-LM?J~pz9>b0wbY^Tgzt|KH@VM)8!;^bnrm9$S8rLo^{&)XmX7KOC z4%#bQT7*20xrT>_e{U6I7yN&ktRn9o931fS^OrcT^xm$w4GC&ttf|c-&rbQVd>KN5 zt>LOFKKHug2zyFFN$S{Wb>10BR8G5IZ)j>yS@71-J2<8wMxK#^d$PxTf^ zQ&U}X(B+CSayRq0M8=KCYYP%Z#5}6Tvk93;?HRJ%rKeN2IJh{0^%Y_x{;#;mRFsF( znoT!=^Vg9EjFRh5~Y6~u?tD`X-@y1dV z^-RbiRK;`aaUuEH9Z$#EE#2+mj+3Wb`B7C?Dk3(H$tOpF%iT} z=sp~_bL@ca-g3S$^hxbyjH>knsWlR>$n5Z%B*xE8%YCfu%hqdC{X(NYDTvzB8(=#G zZXQl9=uM)}wv!-7So_ z{tb>T)$7yJoR1me|I&Jg(ws8EmbYmMe0Fc~fhZ@*P6{^Y9Rji8k1CeD5kbxbiu5U>K~2Brz!`;$=axS|5O?ddRz<4e%;f~u;#eB;7y|G)ru z8yhhw`Tx@#q&*ST+*JCqB-r)4`rM=Ly-rRpu|h5)ANt0t`VAZ86&;@0p3g&WBPDs4 zscF&Q(QW;o;zudYD>zyMrD}~@DhGA3P+`t@_T9QOZ$v)bx^$uO+6n^3mT@)&Chrnw zjSgz#8QJScV1;ANqQrK$CGt($SGOy+i5|T>W?j0U))N!XUXDvdA4c<(_|P?k>qBstcVNPm}j>2S|+>Q<7lvlQg51oR$R&1xeTqB2V0K+zr|g5gj*!Sf@5?s zHGIonki$KdM)ka&1n}b0fczNv^-D1CEW$0`VwDPP9wA3Uotiyvi_~XcX%acXm;iXZ zp)udmA5IkZd$Gb`Z9(Xt7w~x_Kq(0k{et1`vzQ>wY0`TvB_6dUPtFH(`+o10oX}4f zr$9}<0prsIu*b7#myWAB+>h}p^q5_S4?w0T-|Fh13W^Hm`@%IqRL#u?0F2c5p@H|T zVv|8dMFl2nBD=SEtwew9k+^hLoblUvvRyF=!SfRtP7vIVJuf(SB5P6i-mzP0(NW0D6u~f@v7y(~=p{uhM-zwNFmN zjBHAbhx{q_O;sqA29>Zfm;ON_Wi>PSYDZ^x;;@?_v>mtD1fBS7zo??O{6gJon*HJ5 zc7RaGT*?+z;&AuhSfhQ!RUfxW=t{xINVs`#|@10jst14@h5TxEtH<+N>sJ z5aJ2i0gQ6<^3wmbR0&OFtEuB%Zy?6N{cS2R2Iy5$VaRr7+!9Q&cvF4F$`b6E-k}4- zGLzG>$^~xgxD85+J~;^ogS5Ef)#fC$!vhWz(c%xM%Z_o-lGD<=ZlXg&L-w=2@D9}*4lr=!*T3e&F>rZtHdg+M${E~n%**>^ zQRJO8fQock>E-3IU_Y)<@}>kh!21Ek#S>Vzk&<8$FU8ryGDiMFdC2j3lR=xv5Xxkl zp67}fnLVRGRO01Y4ks|mX45Yczf|QljZ*coLGa1VRp3AGU#e#0N zP^9CY#fC*H+RgdB*83z9RvEi>!QPch(QG9DS(9F5s<8Q)?&=G4m?59Gb@|gI`n#tG zH*QpIx`jdG7))o}+omAG7y9}SK##WZKw?h204dJE&``73(WDd$Y5htb{>+6Yw_7uz7qVOKt&m}pgKh}ie?31;*RqW9k%YhHP5P12`I%~PLO;Ug zh1S!ERZ~Ex{1GzUHjC4#>o=QG-7^dpGSRy4=@5EUI52&2Hcf5J{nI9s-c$q~C;R6d z_{gdR*q4V5<5ZG_a^C`Nt|lkQrQc8qqsEGn^gmcGs!15HwQ&&egr)?v!je!h>lM6Fnk`;gwo9F9AYbI?rw zehN3k@9r3++TvbSFnPeWJ2P&t?mi;A`Zd(haiFo9^J+6jT7VygOWQ3intRQX8L-Za++V%?|xUeGZ0%pm?ht-v6i^# zQ%Z$EUY)Gx6*-+98cEk6eMl4C!}Pl+SQcY8O`wv~gPR&KssMPDSNDWcJ5}!G$1GNG zQ&^nMOdk(j(a;DhCmn*WCcffXJKN2@w9@A}AIZqblu|Ju)X_>zw?bRKS5~&4azWZE z#gJPW^~a(0{e<2-m>2V$muZ*#s;KYVXGAAgAWseGBm0}1{b|HKEf(8c)kV(>GfI6X zMSr#KQPv*v45O}fMXm%K@$sJ+d=vMS_rUU?tmDr|Vi?enK_Ek;Ry&HDxNd`8KVsKN zX0I5KhgLf*WTl8+bnf5ZNpR7Gp(Y-z5!SD{&|YRopROe6j@R!M1;bRo;ldb?ije#` zu#MVY_e05x>f8(C0u#ETm-U?!R_F&($VXmbz7;Cdvfz;U{Qh7z9 z9wF)wt30kQuDl{V3#&W>+FOC}FsFx$7pcAH)-^>Xc};UrLKvfK5wb29&%*QJXZ_l! zLh8DLXWfeJ6Q5M_k;KR=5Qw}xaxp~mOT-!vN@tXW(Np{i?*yj2*l~JPqD!nsGsW$oa@sfH=0Tg z!Pekwg4tvJ70(tGXE*RiMh&djYma~d=yi5^Dqu?NVd7sdNC;k*Gf;b81~K(r`8*;8 z?GRsfcGQ}9H(_44I83V)cc80$Ii5Qlp;__)h7F^#Fo~%ci#QUI8YQKn975f`!GCaB z8>kL#Fen+zr;ohR)dUe`OHcyKVCmoxd0_NeS-LLB{XTN*W4fUm40bY9fdOf-R8&-K zoBOtw%BfFHs422Pp5@))ymxP{r{dzV-9e^=OQRlMR9%+xAO;H1ZsD=JAxwf);ODlZqAOaQR-g7U0Q!RN3hFhS zhEea+RC#)? z!)j*L`k#7Ez5BP7t({{=ITmAp16YBdY$G*a^Dkb=NuX$xJtk_(DtutSc=F(*1gP|9 z-4l6qb`{hu@EA|^nW-WcePO}NI$7W!wBUiSaNUnlxKA9yLi3?i9Iv4?sv~22s>b{j zZ}txTOhvG#$KdH{^_#}e;I2shn=%-XStd3%w(-fyq4o9LwHFLk>@=|%oX!+CD{}i6 z&rE#|&VCl5a`p{Uu!B(tsqzLs1`6Y-Od1Ge^^>fTUF}y*t2>9p2R}GnemjE6DPDtv z9EQD!Uok`N_=U(7lMf~Oix(pq(95@o4by|!^P`(c{(?UyRa4f^CPa(8L~^2DPgQVw zu6Uew)t@U)m@DxA8^WUV;F>;5noh5*6-RjzaA(LN5XiE2Y-US~%t+7xF?gcHFi%EF zgL*A}eRUA5Iy>K?gVpIB2t5yU=AU6WZZjph>@d4f6d%!!Laslj-ZB@TmRy8i|79DwMS9x_@0kAe>XS z&|3Ou^iQZ_kt-XB$>8bNfhNkbSbOZ8tPSG1CTvS`x-?hQZWV$$NsYy>*b>US?@VspdK`|H%jSvC&&MiL;OsdTVmjKI6=iA?-fTAFSz zXmg4O7L)h>?}$+>4j##F#>JUPX%V+b5GR-<#6M4i3a25G zf~8J(7+9X$fRhFw?$EqYIHxn|UY+>vNKX^$8$Y4cw7lhP&$m-%@6%(k)AZ2wIH#?i z&kSpy5j$Pen@6=5p&4E=>Kl6_h;)$Y`vTz=q4yHkqU&;F?%=|(3b)JP6*#N-*?c?a`~fn56r2+gv)Zj<}BA+zzu z#b4b-3)NUnPe~!G@!+Zz7E+u9aZG&|(j(%ND^t5Wb5bDE`6AdKJfIG0+Su60>dOgr zqk!~3bFqd$Uyy;;@IiAsnaL2S8VoJ}YJrE5!5Gif zq0ExgsuCA!uG^nbGne4_YX2V*3^59fGU?AuAKpeIg^3gipTZ{$lA?GGgCI5<7sr#4 zlWWr+Msn62|JcX&MGz5TLe5`WTFQ5Ib%D6(^h%H&zzSc46aDf*C#7Ac&cM#jxBQ}< zAPmUm@H*>{HB-yKy#PhJQcwY5JQyc*$!n$OYoW#B@s}#?4KTej_R>Djg`4>F#xi+jxiluPuq0n}kiz{^nA@ zin>XTeoL3fcG+Z49FI{$=k)5y8+^ z!YeLr3!K|tnl@+4&&+DL{j)Tg@w;Xy?kO5JDt zi((fW!*zK<4inpD{Z*szwbJiieD=0e#|+t;Fa*|>(|T7bl$)(7`Cd6CQlS}cd$<&5 zkn%2w#OGko{m}5&tc-nhax!&56S&(G;%oA*C2fAU5(J607m&~C>|HzC&!;o**T<8Z?jk`9$m`lXx}^$V-bwB9 z3L8zR*|KRrI~vYA9eGlZthptRwtA>uYv09WU-Ic;m%ev2He{!8r7v}3q(JxoF^_A& zeQ~b8MTaxhwK97xdK%kRb(HlWGo)}ZL-*rBVGjU8zO#SNX5O_dDg~+Dy z^dCqed>dHpGu!ltqqI@#y7DgWBIS0ru{O90C(@C4ga z^5MI-1vHjz6ZJY(i+s|&e|wc4$T&_;`$HA=$Mc~oshCd64-?eb$xOT`Ak{BHj1G~0 z<4XaV#RjojjGRExJ1i*axb%JPMJ@xGldi+Xxbqf(F{9*qdI_sH*C%O zFnkLw`2Lnr@RH665&)f?Vn*3|3y~?#1FVPv)cO+1jONH%{Lv{^{XO|=mm_mV`KG8s z6>nV(FHOz1X$h!>m-cZ;M$-owET1z3fkE_H#k$A2*68c1Wt5`+-PAtoR`a~g)w(91 zRKE&^%&4@1uMZR6qwVNbj+z24E^b!eBkC~vnNq(Z1|S0rd(F56kpisAS5s4yPl)-5 z{3eJ(a6?m5nZ6XUjVgOBq_rr!{Ix+Ww-+a$J$FT5TFl1Kkk90xt}*{(%_}C;D<(~p zCvqOFo1g|h>p`kw(S!;&T(2xTmH3u-bXtUuclXQ3_Z8D`_|VNE6RAz zsZLc^y~I#Q%$N&Oa(=r5dz@?(c&w>?75h3MMc1>Dg@V;l$b6oqx+ZTM>?yJYtjzs% zKL>brn170oU_hlI?AA$ ziaBsz;JhICTv1lt=`j{DiugaaMt-fTAOLvu*6VI-fY1-QK`E>IFMd!Cg4+(WaMj($ z$q^JQAosak!N*)^L|n)wUt5q0yRu+aHXeeag!D(4YE#nE3V2fyp>(!F$-60MqG`- z`cfl#HDibSZuQnRli4F5)KOpUmO*dk0Vm$%m80>ov1fvJ_`&c5nUZ?I9n_U(u=w^P zWTc&#fBhq`H7A{7t@j||R=-CNOc72*peP;|RD^#pQU4Yz=<#XFfjpufcJ?aib45(N zraRR>G=c-(-lsX+lR_xRUc@=}#s~z0$Rl5d zW{kCu=J^##FXHZ}y?mJCakLG<1H>}~Jyu*e@$a$D+!wf6HXZwYZ1+WV7D91tJ#H!l zc4Xy2d51!+s+ZOq1LC_30weXmE1Rsh7{h_{dL|H_DIhad=^(|Kheckuy;G(i4tw=a zWoBI$Wfqm|kqZtK-n3tt~Xdkv=O zXQDJ{L*UI!XsFQR$OBiM)t~0o=W^DIqC5yBWa_Tg`ATU0Q&V6xK+wo133mTZtS2QQ zCZzvKmEOo=bH*CatfW7DYM?_Mn$24Z>{e#FX|#+MSvMr&UUu}HGw-a;4iw0xT1(eH z3GnkTYXN^f@r3g5@Zi_ik6klan+H3ItJ>qg4T*@K??`zaj)5ysV~_Jv1)T6F0TjDW z8O9pj5ifqtSB|%4p3T{;;|QdBU?qsu3 zRnQgY?5B$)7x^3imnH&AfkL%Y_r!q=v?DU&=)x~Ak#cL)VC!s;?a_CT1Oby`yL-HA z0&aR2xtz2r%QfWs>M1@0&a%LMpV`#@+nRxUUH2<)yXc$gSQk*H1%%11!AQGo8(Ui| z7nkxi1J#>ge5M^Qp97mcFoJMdfZz!R?E5HZBB6z8`5YBCj}&7 z!0<4h#gBFXBV=iR^`{Vu>O8AYv?I^*K@%;W-tnS?jqT`xM7>ciP6#QM|VHBeV|Qs7m4JA6pc?! znF2q@6Tu0@4#t3F0bmO*8=a0u&mkzE?xRz~cExt0c=`i0st^PyqxMcwKJpL@R;Z+N z!?mCgP1vkv>2YL(JKWk*bvfd0-MFd)rEz%Y`2MoH^-rbz14A&U~Izo^lORI}1Q6PJkpj_sxjhCc=9A zST#@=0&x}AX_%Ru+~4ezXl}CCt9m}LrF+#3a<`1;pO9#YMigB|U{r^NfK7s)l%mu@ zfpf66^-A;VYe@e)h0L_4EE#$nE5CRibp0F}`e@R(@!bs5M7}L@x2#4YFE4s#Wc3Io zB7e0t`SnV8Pf?^V3CK|Z@vQOq78h@=1O(V^;4 z$fF`59N#T^lPe3oXK{{}7r29RkOoE~aD=A&;>7(i8;!^({!2!Xy2yVh8H|Q&H^3@R zMLl8Q6%omk`#?jDI$uz4Zdwhly%57E#Lv-NA=Jf~eUkUPl5i4V7K=xXwxQqx$4TVV z&O{Xbd7XX)!lZsKNq|xXl%lgwOa-$fG(;VWMTETKTMxL!u&^+pYSB-9D||dW3%~Z< zulW`8h@Wlp$p1tiWVU_gy`q{sC5|PQ@gLU}3vNFm0_N6`@xQ3JgAd}#qwEt9Pl7?o zFte)B{@a?WAAoRIk1kGY{!M?xNEekVJ&n6WPsLLOyl^1jU%I+#4h{~6OH}9-uu|Y5 zcX!{rTtTP1z{2oa#9G7gpsK{HW3T$lHiYvoF~nA8(IdEhl=gpht-h&t?C<*KIwVdI zrwWihX!8$8m$mWnJIaFWCqgvkcHf-rd#J3VA?|ViW0;|9!>iz$9va#7Fv;oN@j9ln zX^XFi`E!n&#?b$twbW}aVF#D{qVvHloj1XIiSwPNg(aikJm>Z#>}*3{V1{6?yu6&0 zAV{0WCFGBD5Jz&3YqFEw`p_1mkg1e<1)~4IrIr~P9WAS?D~yS`g^tYk!hg&K5z;1# zXXc$#5i0&1jiTgL%6!{u&`M1{k+)@OZ}@ac*k=`QpI!r2(_|Y{F+gABw9AT^5zAZ4 zi!5T0m(V=_B5Ux;0420`>Rm4zDEIxvgxHZ+&mU(m?%aS#f|C7HT-Ordj#rKywapOh zoLH^2;DC)?iB!BG)T-tsl=hsEiQ~#S8VJ?t?#2Xr&O!T9CG02`Fn!4xqvczSxkrL9 z8Ug?p^%c;zVCXX~;7wPK`F>}WqdWsgYi`S)ea30^0(IwwR{TNphV&a?ynhNC@&LH3 z28@tk|8!|iqJG*VCvF&XVzjmj`Fs>wmp*PgHlT|Q6Y2X;E`&g)G;`EQaRNSeE#2{8 z>e^fux=EqHfGZy~--mhOXXQ(K!Lp9X=a0O0Qr&xX-0#&j1T>%`r>&fmWsuY+nF zG4h4OunG^XJ$A%uDRNO4F28XbNH1oKdoXbOT|BS|-`Gk%u1j!Sc5m(0DC)R2Hsu;B zL^i$i<-@GL9Wi=?hTDI^F~qk};dg^!_L5Amh3CnY#LS;3z- zYA^xbqag(ii9cfh!!UpmdIPq4ZIu<#9>KdGz_8Y5cWIJicmBhJOg3mArQV0SW?V$S zcnt!n&Cp`Eva#tNSTYi?`XMq&Op)sOp#MpZ+CwkNK9P6cA)XjVEdK+)pm2EdU(~1v zhJ#LYp!n9HkKA#-aUJrl0#NoRC$O2ICgNQ#;S9Z;)x!tIgBqHEK<8}3%>y+osQpLZ z0_h%%6BM)|@#K#jbBA*QBa1wNqYDH^Py$e&JUsC9+$YS&TqsfyaPnB(LeSN-PDMzQ zz6%BH=k9K(gx{^Oi&Z&^hhA5Fg>9#*O;4{vR&&!2i~v(+UvzNbEdTTTToi*F^0_cw zm3M4%a&ZM4RH|}lBf|w5PAU)1{|{qar_Q-3=H{jEn#-yF%cF&r6JY+?$30hDe;U0! zH@HCjL?KlbsvTFh5Iy0s?=V1O69IRcq8CQav{YM${w64vA87)spQ>^F0P??m75Mmq zq9SWk(*S@7?G*qoySbT9Bj)aOj?L^XC;C2oY+`0`r$3_8xh~@~V6FcEfw+hx(SMiF zAD)kNNgT|B7ae-D4D%DrnD6-v#tgHOPuo8r8$6JFJc=9ehYs%TTzZ|Dl;n6`h1O~w z`7Rmhbxxbtdr(lIqE$c4944XmJzBSc^zdDcH8UXK8hW&&0IvfF{VXTydHfVmr=Wy% zKi>JW<_LiVG7@7eD=85Xq&^nKlTX%O5~HXp9Pf|M0 ztJeny#b4?anbjOMVfb1$J3!!{{{^OpN`MaG<6HW*H_J)uef(vOr2p;TBnxS9Xfb}a z>!z2Z1{5(!KcBU=_381#2Q=qv@e|PT#3BAPqHd4auS3MkOG@bFJs-+bH#cz%g#ZHi zk`<9RxAAlOv8GRV*N$X6+d)6;KZUtJ+zv*+xOH>bO8wrwd#v98zyV(tQaNhRc`4PI zqPan40s6*E?bz*^`l7NjK0u2>694#^A~7(Td`9M&WLF-ur3e|BWLFW!MnJCu6PNV#RMx;T3X89XYhGt-UyfmV9t?p z-5$3A-U)|O_OsPKE30-rFSl*|<5qHj{nc6uhz9jG6Ej*i0-vJ`ya`-J<8odFrlZmD z>51p`uDR=Afo{cmotKl7TGW0Exq;K(9SA?*caDz%_CZ^}FUa3o>{&o%0A@Y70;b1_ zG#uO^%NF?rfN$TRzcwQ9rNFIn7+qv{InXZ_WDn9I%Hl?Oc?DVWT-*%$@{!|!zw-i$ z-x(PlaI58S`Ph(chi8i(FD)#-ZlB@f;eFpa3`d}1W26wn`1m;p2z+B_r>PcFMTeHY-ara>q=9g zu&O3O)>R!UXd37bT#lCE&VaS*{qI^8S@R8n2Y+<-y6V&N^70)YTTu0Y)`_a6Igp_{ zPWmfIK#<7<1Y{zJSgdY;%I)<85XHot=4|lTgFC74bLJUkCtxt07bN~P!Th9<6WWNv3G#vW3bO=>xT^Z z5Q~hzjznEwFxBpAW0RllldPFHjJi6dkokIj!oSJa<8N+*_%8gbLwbh%9i5Jj4hV#B z;*hIfZbSCJ{i~q{%bX}yuP-*iiI56Y+Do9 zq}R{uGLo&d0^|IV7aD{-`$p^71lJA|)EFN9AbcqgL); zZSZyd_#f)o*W`b=O!k{N9;DXJ%S#`uDtZRBwFg>TuMdDR#)C12gkb-eBh$a|-tts3 z{4HaGijyo4ZucJ+^jiNror0{64*6R+*U%meae7Y@iD+o>O&6fPPZo-E^~(5|!*(A% z6fTG|r#X-`pf`X39`%oG4uaqD&+TmvKxfWk{J)Fn-Z0>PUTWUA4`hJBmHqrYo-$6A z+Qxr`24Tr*=@7m(WIBByS( zRaG5r8~pkOTd~w0T21kzO#cvg73i?!2vkDv_3WXe^QuBEjW%yQ$m&N>%0@=sj0KRp zA@i6UDV8_Zu319pCG{o3s*KVH8~5|d*5)P)(QKa(hMVfYM0Ep2SBVoShGuU;KAY!* z90peCPkvz6zT%7f$M07M(&d0B3V5mX)tt8UyQsilQ`y6lY?e6Y}(A#V|et)Y-G(GQ=G@+TWl{6pQ07B6BPmN2UUax9C7iTu!i%^w!BMl-4Y;lm?<*xn-} z@*G7;#ErCdPD5Ou!BRTKZLU+l!v5RLz#ZeGAtX z9m{#zcXr`1Z|}hV-rNgmX)CU1NC@!7R<}y-QKFurd<=~meQd_!>cU*)-|K5Q8g4aC zNXl*J&f`-ZskXmT@*Olk`9G`c*mG1l4F1bDlNa&({%H%TPN7lv&=lil3r}szGT)Fy zv0O)Ld9o8WAU-QoO^%4+Vo#K@K*kc->k31AT-K#aYaKlc#j{UoQmq8?#ea)5PpS*fyqn9Z82T!lq_~gv7(lN_~P8dkzl)V5++%Qf> za0TwF4-KqBLqE!pS*gcU_oW*Q4Ks}8p(s)8Nit2VKkAlFKD#iu;oG-s7cN{NvutSR z9KH>87ac&?0@AZcTh8L6S~-D!S@o4On(D$|zruLA7*=s)T&Vf%`?>0#@n{-ac3e-h zSQ-)98_PWU3T3pobW9#RVGEeR?j@-jlB5d*9 z5tQi_gz;FS*_!{RX;1@BR&kjYOUwEiJEaDf9P6AVW0xEPdhFujg6C!()Ya7``%#j| zs$8Z<=vYeevA18hi2~$z9ZQ+|)?WGEghiB%DNQ>Sx0myom@+8)6zeSaty^{Wueu4Y z#a=#lA1Q1RHKIQIpb~8l4u1K$+Yb%;ZQ>C+ zDjFIeKKM#PorgzRb1dt4*i&Qm?;ya~;p^w7U`p+#@&KD^)$3ACu>>&`sY?+>)a3cM zss07W*1Gxo$3^c^(nVj9r)YpJ0wSx&ZJ&Jm`t0}t0kn*Q*07E-D zIYlW6wbHGr+BXf#&75?7T$JC#?$&Aq6||b(8AvkbY&nbYh;T;l&HMRpAT;Hwejr0v zra`9YPyJRWyPUsEG1MSDJ60cG4UPT*n`rJNoLbE@H}UTKbJ|OWU){53akt(mS7Je` z9beIRBdGfVK#-+IP9Z0mHOXlGdii5(<&&zXJY{tKbG)_-R6x2pnEI@I!*S0ZyS>`l zan6A3F3Ga}rE)_aNU0%Owy}J=vAkNyOv;aud5T04(+hK&QA6c(geZb`YW_R+V-3sd zru|VMUE)z%JFC1A96bx#o#-~zp4j&lr6m%ydn*r=Qp|2*E8goihWN5qC{UQ@Px_;4 z(PV84OwwsJ0k=yo-*H`nm}#e>?rk9{jhWZDYw`fuTERWx`ER6FqxbMk7wwz;Gtqn@ z{4xJqmU-rk>C+v8#3+h&`F}{1+)S6T2JE6rzyZS%kSf7p!MKB_3S{UeM)wdQ7wCwUgkLV4Q z#brf<@10HcFJGQQ(o#zKoZ5hmJ76J%r|fT=%f4=&Atm*0ij)Quq-A~`e^_dF?!vR3 zL4TJ%njfow>P+`0`Ax&S0B2MXg;$Sk+CbT&o-f5jpzVtfrvN%tYkhy*eia)D^a(2fVg;Ky^i@z$u&1qd_Ok;kapx^2S?0UC-)(r}n!Ngtu<8|b zM%p1E;f|o++nuBP{i!Xe@WagFI1QL2wrxjdsWl=pj+ECIjQ~Hy(Q1qsR0Z}fhY-_b zSBTJio=BBmDH3Sr68nQW1O&7>Mh9V#5`N&uDiw>dp4 zqiaNWn`PFiEMIL?9z38%iCjQi<%1on=&9i@118~m&XwDRS@o)9t7twlbEtc9zji_n(`ew904HgkzM9E34DPQLGs^;Ch zxzejc!vn=6cdGW5>}-wV+RMa+WW5iRn*MqoUnANU#?b~8g}B?c?c2BSf)T~M_VNGW z7DcHi*J}Sk^l8@=1_eFKnunfL3bP5o6(Czk&K2yDGpP_T6A(mNS*$qkb;M><#^E)wj9 zFm-=~n^;wF>&yJ@gC*^=*+N*-m?0tY^swkc!rS9fw+KJ|^{WYg4f)Wyv$QW;S5Gg$ zq{NfNW+g-obR&|#@~v_$pAsETYxjreOBl&koyFbI(l77+ay*HUMD@3sIi-&m_TO6A zmNWP>2kUKA_UC5lK})UfC0Z%?c#VN#K`ekJ?HRbPIoQ9mzIf-q{hqyFK0y!nUV}M_cqjTXavsp1y($M*9xuY8=VV9Vyck)4OFv z9)5YPs3;QxHKuD>=2HdutlY*SbeQzA+9TNa%u&NMbVZb3)%`nfbYy&sbwa=OQ9V&9 zv2Vned9~d+EE?R?CTvjdHUl|KZOEu|KXvAe*;!*{TJWM+t4G;-%1ExCIXcX>)?$$o z5~`&dD21crTQ%9aGJL`1CMt^Suwcbg?lvAJ#(hjVhWp}wE0F;qA)7aD+!%U<$6jZw z*yi`Jtu4KM3dP!GiKjo|C&IswhDa&B+do1R#e{ukopVql^opXoPHNB878{q`I+jc` zXVU}Dx!}20Vm=I`$>@&^y;3nahx|JVs#7mbA4K5~oG5_fI^b7P|F zL522yva+_0Ilpm!c})0$H}Y>C{Ll9<=H)ofOsHreL#NQ- zCLS9tLtlH^Hx6@Gb;1%~wQW@d#f_T%Hm_+MYxyOCl+)n{Yd6)o$7+f3P?T~wDWkcF zj@nw2;pm`SJXOkO>;R5Zml?DCOt})3#V7Ch_S@Kvt(fJjnIz}I^HN7yU?Z^zMJ3HT z!p)w#di81mAf-nO>ll*YFIW_zW+m(oGd@E+f@#M`>@|Rt6e9}}(11`5*@!{uRThNH z)|_8;Hn}LElOv493=3$VIDJ+x4?m^*VYJpO(6C1|*eg$@$Y%*2vIuHKtiCD5$_4Fp$$snXmb&@K9ckUbaZe3e^{d&-+zP+}Xt;nw9 zDQ}wx0uH8IeVL|nwwpI^1{|Z7b&V?g%Iy<%{teIxMlo9yn?@ba(<%dWbByVyvy$+}bST@$<)We=yJ?Zx2Mw*Ml1Su*i zLv(U=b@le3pp%;%3tyWkhl=nU$cX7y%Sh?g*SRm9C@A>giXtu4K|P(x*<1OhF+3hX ztp_>*j?dM~;}#kV=r{ot)8-x;3*;9Trf*%mjrdXht%vMGg+;GiAhyOB@|FXiVs4kk zw*?Wy*sK~!z+_KCuCNK2=&9*SmeI zYXg2Tg@eeo2uEn%NFQNh1vBQ+ps*0KML-pJ}lD~=;En4JTte_~&&y8`O09u5h z_7c0%XeL;yx+kU=pcgBfl2lY22{jq#HZ$us=0 zK`--Gq@%;YvT=s9(TcHSATvYZfUE%u67fHKq{^2sUt;BjRD_`6zMb-r9UeSWg?|U1 zb(1-Ew8uZeGDdaTvN;jSg$K_>{yisQ!v3U{A-akJDtiOPbU$=uXNnX%_#B)?OJc#PhL^O=>&m`e*9p)mDm6Md?a$uv~xjWogP1U3sf?Fva1 zzY|-`6feH9&Xt{ZxLR#GUy{wFxJTn|O+Kbvv*C8R^4NZovNrt<9jBvw+Iw>fJ}z|x zlm@%p=z*}AJ*EL?Mxp`7w{{@XG#|?)g*uY-4Xsde%MzVtpdNKN^~tdhCR;<#*E=@n znOr{4U(QAWm#nyH+Swn#TYLyUG8>V3aMB9+W#PS+9XA3x6H#DUz9X|(W;W+75j=~} zUd;5u`af5Y<;J~W6{6eb{+%WIO6sDhxItQT!|_LVE2*xRZ@jkov zd@#dj3ARl-4phjMHysaWGCIkM5YB#y))8<6))c&DD-n5c4iu6T7Gt$&NzN(=s2-D_ z6Vr`ld+d;~7pjrak~+ow$s4mzXi@_hVgBsvBlxsnzQ}|bVq&D|U9GyJI8jK5`1<8H zY_>&4MX3+GN-?^EyKA?OPOOdArac*2yrQU@6b>Vxw5uyycHm>RcJyBljp3!9a0D`P zi!Hua)g+=TCfadPpW@fgjje1U_)nB{QqN?h4lL^H>$|j!(Y6hO(DCEPNi1B$?gN0I zOGgyxnkA4f@FF9YjY#K!UPf<{Q27Zcs(be`z^Sw=C+z2vuAl<{ za<-z`7W%h!rt%^?`d@^8nGXwoM?}F@#8kn$5GR!4H!4nBLNj-K;5oq+aj2?8b6wB- zt=&4ll>O|a>P&hw>J;`SjS!xZM~=wPh{T_$8yr=IghB9Kh&r-_5a6*m-TePBIRc*OMLR(iJt+Y@vr<^>AZHjjks zZQwQ@_yFBrY(x{lq5a7V^bVh**u0RUB!iUZf27to(AA2_vVNOrhPMd6?K$J8UNv$B z2eT~m+0f}JpJVpQZn&WvHY}gi)Q~r0S-yC62@)&GsBEy?8IqDD`g_i7T|95yjXi^< zZw$z33WZ6`dt#>2-?D%*N;l6WfmShWp8GJ&GI?6WqA!H^R5|Y)FcZ7)%O!!1VB}Sc z;Q)Tw902k{V8?)-C=_H=7QU7WTt!!T0y1jnI9m<0%4`0TA(o$?pUQcstu4btHFK@3 zBgx5iG|?K$NpewKn<;yL1fV2Px*Cox^sbV#rhK?de@>*zpmWoPy=o6tgaicw6og1<7B3kRXSL^yEcQSMH-*^QE;+utY-ixSEXS`gp4|NP89m1Gk22NoBZi@e^ znbWO00m$sT75dZ#PfyR2nhfd&xYihqd5jDkiw-Q_@PiJo1_nwYO_6L{z!9W|VlY}- z>se2apI%~BrxWAEKliuFuB&x>3V5p7G730(yYU%ca3WbX#Pjfz=V3EVFW!#N;bV_) z*>Q5FATv#1;>6_x4*^`L2rC9`@DHD(JP!xZrQZYSgf3tP_B!Eg#p6q9%#N?*3{02* zd=;u$Ef>X5_8QIaUG%huR*~}nea&S?#8WjPIG0V9dGo?8jGkgNh8*+*?ig^Eyl~iF z%elvENmGGychEWn{aaV8nqYVqhN^M_3M)m~PXZ9*y#<~Ce6$SBY#$TMo%T$H5m+^f z=WXGD5;qmP24t8i%vpzqT3Z~vTz1{z!-o$nq%TDW5XIbR`Gkjgcnn~T9>|^tZAVQa zy=Cq~qYD&b zq2sBZYhW}GM@JL%26;IGAU+RTeqbPK5o@sNwPeTKIIr>Iwt9L_4gyym#2DH8&G4K& zd)%Wx&TOc;m~*pWalzZ|GqYYXrtjq)zxf}Yl<5~P{%No3wCz#`e6kEpdff5D z9XFLj;o)8drwe)5zq0B(3QI~hBrtrse*W66qw}h%Nlpom^7?R#gTkAR`kd@tT$I^b z6Omf?d_2oPE=7&Han7ladY*GpGqXMiO4QfaUtB^(-Rkb%xz%b~iS5E&*bVCvL^G`& zG41gFO7Ov{S8a2e-@ZN9b6sjPwMlu@3gvH#R6+Zgv%hYiAM?U{m=G zv}p{IimbErlg4+gR6V`nJr7g%ZnH1`lk%mvSIjDIO-{W*0$9n1V^E@y;j5o}6&!Q6 zy12wO&+1HKVx0OEcF6j<$J_kWVU5>~K59q8!$E#;&!H-s+uP@nqY+ssWNXlg2hTtH z50p<;n^4rKq_l7$Tv8n2tj5&JmOtc{Z+&qIQ^-qY#+sDcwF!))w*xhzFr&xG^_<{s zo!gK>-cCkl+bIfdoW90HC(E2f4y#(RoKfMTo}i0shJC86G&qCB4oy+^W>3}AZT>~W z&*YMK5=T$h(A2yOPS6uv0*g^BDKv`Am<7}LpN1bw`7_7`um&zv|)NL z9d_AT#}eBLVBvcK*rmT;A|N0Dm!_C2FT=!_%rn)NFJDJLj;*cj+xPDkcJXOnyw>2k z)yn++!xtXY($dmWAMy0sM(WPq#ic!YGznsF+D{5ftSB#E{T}L0@>WFhKlSw%Nx{7T z@faMk&qQR+RqL#$(^=z|&4_f&d!bX%upxn~>k|?~=WjsJoR05(!ot3L_9PX8F3BH< z!=4|x^_QPIZF1;Pi59_4J|FbIOp1quXGH~$<lGpxIS^GZUzCZsBl3KQG*+mQh znK7197fcVG8xA=9PB-Nk2|fJIJTq3EJ6REj|rW8U8)IrPVuJ4lX| zZND97A34sxDi^099xC}9jN6V7JULEO+ZoS?Bi;`k=wE)S%7wV72QC^7-C~5Uf^)w0 z9c+BPN158KnpE99Pgv9n-+f~39%uf&CIN5VHoOz>bXVC363)m;- zDSjA*dj;bTGVG01Pe&TOXVt1{X&EI@#u-?2iNDT?n{SK7*_)5(rabpht^Me~F^!UK zCein`?^k$u+t*+kvAmsu5?08+9Xn#wxhZB+Rcp7}iWSIo;|z`J6x*D%N7VDo(KBTW zaert60KaN%w3^9>2EZxkgnn>X*sexFwZOx7WZd(uX@^(%7eyl05|*E?3dN>E@~YC^ zzux2SQt-?e{A~jMQXgu)3J#O3nNE2-3Ja>ah>D7)Rx2KovCcAY-^nPg8?7QU6Y%B& zzT(0!Ow2y|w<6_J--Cl3Y7fvCG*?|lE z>goG6HtHvmsINYB&gac|wFx5tDIp-*uvg*a`nk2hSyxK76|vUWJ{Hb;mm)x(x#u5( z+(9Dk+6xbx1a2z*GHr=Es^4CJkny_qcWy#R*2|8L?I@ARqrl^L9EJ0(7ryq86(U7AvDFv5esqMMgwX@Xjn?s#^G~sIUyd>Zoxh3g!3zM) zvC0yHPDABWgejEL)LF6P`jLYN4-!PxMyYsu_Z;fw+7j^EwfI+(9jURDn2=QhBs>62=7y%Spnkbo7du#I%!XUn#SXS zJLfUpA~awcUJ9Ez3zmI7YS}!(v>3@Ec=Ki;j87uM*cMY{WiBeaIQX(m4VL%kj53nQTqx z_t`RU2L?2KvGWtE0ZvkUP9BObq2cUKI$!BXiPsFsw~p1E!p;H<1wnbx`=#YDct`}I z6rzE>xVb=3x@FL#&bclD!94IWeUg5bNc(r2K#JFwXsjx z-P0p7WMZ}?D(@FUUC*2Wz~MO_4wnWWWgCxi8L-xxA@6WNtRL@#fQ@LL=TIzs>J;s5 zWksQ#lTg98T;m?4Sji&UZd?`aqcrkx+4jBqKiboh;0Ut^;G#xJnmB&%<^NdwFOmnY zq>$rGZw}4%xkTW3iA82Cfev5~YMXx%YFh>!ez!p(-%e&mXEt@}jZj*(-Ejw(|54QV z$aw`@{)2xJQikf626_*LP5m8ziuqnVy23XsECF<4b;wu_z)ZpG@B55J);x93M^vQ} zu*0(~8m2g`n?AXc>8D2g>`eNEiAF|7z5xNQMB@H-4@Ivy<&NWwJ*k~Xf=8GTk7s0%X%4Z*(8KYz|30YO+$t|f=l8=pESPr_e`PCOuSdtTUnt}!P_ z9pZ-*zz=ET=n z%sVGh#EaVR;qZ z>wkbKwfbutS2{T6zsKgYa*(r@IrY9FA*a=Onc=WUu8mSN5|^~161?PL>fEQw$;sg+ zRBvp2yeLY4%2hh`9=8VjG0bXR@*>a>gOQWxv9Ys5VPLz$Q%Xuoig;IEdpy#`_z zeSjR?^x;l$NfgAA$E}ZAcSb8QAB+?|vj?OX#OK;1uL9sM7`hm@HrGhi_{VXC`99`g z6A1*mOUI9~Eo`Lu(i0IL_pUtTS_I;}x5Yv50XWqOaH>B+iZbg^F@}gCut@dv8lB!o z9tGEY>+67d61Qg6_R8U4yO`4vw8sERZ7q^b{{M3;;|$VgkEc=_ND+Hs>(bZAlkqMs zY4?``1(tX3&###PwyE8fT%Q{o6G$1R`R>fURW8jj>ON-BDTaFLMnCmP|Dr8FZOTq- zPmLTycg-H)LuNn$Zy^5`abO=ZFR6h(KE%jlu+0MPs-7^bHiNXI{Vf4`*yhj_XD^t0 ze4U?q0*S%ymP%1nc!hKT$*2+{h}R(mA3;VjD&iXFJ(5rvVDmQ_dUDm>oZh`X@9;VK zu(_Ep=fAi^c{V`*pvL|ZVmr~oF!u{ zD5h&7dL@!}@kXsdOTx=9A!*>lTJ)e>Lq_I`;`}gwIxX~*_`8S*LTf2a%2Lr=5HXj> zP|iWT(kS@oHJ6> zSn}{&vOxMde5A+y`W@8ngNTK??{tqzw;fFmz%qO@(ErCW1yOMA*w&z@9bX@}-gqf! zMkvilt!p7z9EMm(OiYxiyn-(1;!dalJBWs~Y9vjlu5lg(4fn2G>bVX=A!SR&stmWP z>9R0fMrSuK2 z7#!%J15NP=pJ7|jPq4p|V3Z|r=A36!2_8erK zj~I&Ms0xt07*Tz6B&q}RkSeR>eEdcf5|%A}EJd`tMWd)eKg#bM(Re%#<;EcnfH5S4 zI>X+Z;~5%vgcdUOK|zFt5r+MOFp1znIu-}<1eXC`8|A3t7sCQrvRU4XhnsdWz5m4t zuGG1=fSY&rw*2fOEq@^oQ|m3viFqW+%%lGxeohTq@!R#~} zyyc8HY5nTiI7IE1N<}y0Q@tQ$v811Neh1sUMG#CH+gyUr>T~S2bnsB=>7WgCpUk+t zjP5boszSY!y=JLsBgGd* z0vvDa02e|Q4Rx6S!ymTyLx_ z5TzPXd;7oU?1|j-t9}nuD&veYd|cJ%G_7Cr&|tn7VLnFUS!S7kPQs6+KKk_}X+Q+B zCTNR60>AMA|02mf_}-CbEqv4}WGS=9sM7u2T7x_L@o_)_{S9TmHUrHEm_I_L_VhJ0 zy~X=@1K$eDeuPNCHsv5?P@%j@%iZWjS{;iKJLva)X)ze8bK*nd4su5nQQu3bVU2%L zLbU_8oi&J-F%;f)(8HJ3$cBP|U31iBMGSmGgIyp*7i%#B7bu)6m@Ijn+~ zmAP1;Onk>$gCI>1sfHOqFv5J8rcwQZLM2S6Yji0td8nzS)l_N2Tuj=NJ)}=nhAe_! zUrI`fh;ppgq%W9YsW?qZh+EGUh0a7I+m%ai`!Hb*)r>{}z-9k9ph=;{0^@B+28nD4 z!j&zLN$}}agS2^$k~T^+oh0*+JSk-dSQ(=#a(-NifMF;P(l0P4Cr7h&f<*C1)7UgPn$Is$^=1=fRWl~gqUMiwEm;N?(gxrDOo+VrrTPvqP7s@3 zuJkLlZkWc+2H3PjRydJNK0z`$3jLXI z^I!g#{~dh&o7EB7KmL#Z>p%ZLfBakb|K9lD)?Y>4<$wH%e*WJ26M?F6-Tp+mKM{oQ z@^o9q0c?W({g~B7oo9a^Lm&kCZxHq0AjE@^KT!suzz2l?10%5L@9}Y&5C1X|{tpOD z@Lzv0{3ptSEv+8*3w&P`@lOK#-@q0#Ob^0&E zC$JFf-@B=I0+a`xdP5AJ>931*@sR&B zt>U4qhw`6O6|a9?1Lesd9JTl+gJoukqYtY`n`5p>TEAuymeHgMFAu~CD%VUz%4_ZZJzWr69zmw&OhofSJm>B$J@Q1>ylU(s zB?n5a%e7cwMOe7OzyhE0P)FnOP6o|Gx}bjLu+~J_D>05JzV_C1W6ncoV1SUEs%k<3 z4bE17GuXpc4t*B;O%OTi6}kDaBbisIfX`4vRf!IUWWl2&dk@4z;8`G*Yz4L~@SQ&M zVk&1^eN7RSDEQ7He2eG>XNc_8~BUBsSpJM-zx zo?W%x!YOgU4wT*^T$0EyxX3)qecb3H#wl|dH+g&p;4av2a^V=lVjFlQwtz{ZA^Yzk z&Wi)i>5X?an{08}t21tOjgExY^EM`zi}bEBCgvKSie1$f6yx>eeGoRW;_OTm0ecQ( z1*a<EseaRn6!xE&y3G8El8*x1C>eXBn zl5))z12ZIy1?rtW^4q@yzF-3xeA@NYu8HBxhac;RfgB*s z(HxDMrcE^xZv4U<26bc_nlRecpcGOj&Zux_%Dd ztAsY9Ny}n^i(&J6I2DN~AGYqDTrEr3Rt;tmEIM0$*B~fT;Z)-3KPVL#a1oyCo*&N9 z`dywl47dPl?Miq}2A{KY0#nx-fLS%^0b;>YP2>G4!BCfx%h}!x&S_^nTw$8#6j4e( zi^DN&^kH8aDjA5p-WhAh8dYwOiCYq^j*AG7=?*9=RyTyx_Da10&b3qE!O;Hx6cWo> zsv~KGC=>~}=t+gn!?-d3>qXiR94_-{qBX=-_P`l-1toU+!vy1@{6yNI(Xqa@S~!eZ zxd}ArK&|N7*uy@kVtvK@%8H!;8>S=C?8dXrB%?Vp0!zz!Vt?a=KIK^Uc)F?Iq{0*z z-JbOXfA;2%-}U`;V_hrI>a@gH2w>ahzNA)1GwLPSGO|AjNtE+py~=Ua*c85@9tcxJ zt@^{&9`ULY)-O^<5I(OsJl`PtXNFNRfuavTNkBS;>ikfnpQqQiX|48)2MZsXT*%sD0+d$cdI48~v$PadQQVPl z`CwmZ2rHU)Rgt|Z#;CPg$36-A6HF#`35HXYkaS=*jUju8A{FFaUt6Y0Q3qLv^&e8tO-V>4|YxP3BV~!Mhlt}7F;L9V13GD&-1ftQ<_P_ z4~9J=0M&4j)3~bL_=?(;&}YA^#sjPAx(vI&+H0oUkB~Q?Gk*0xqN(P3-I{LmEmMVB z{Uvybf;fiw>O2s+3Z>}%7)Jg4nf|L0O1ZAWtWX7NcSqpFz;&xL{KI}R=3|u~x&(HW z(QmZSSO{}cTT?JeILE0odVO@9Tz1dXSieqeYQKAi$TX_@%A=v4NI{|zSaQ=YyjxIE zKcjMCRa;&C%)U%~Z&EE)|1qVOevQ zAhZ13v0_s4A*r&~{%U|!gq7>82Db3w%;{>+mc%s0~5)9f+5&XM2#s4r{(}wXybMNktSYB)F$!f zub0^Bid}G>%~E!?o*zg!Nf4;8_=kyFB!QbAPWo%kHaPIf@)&00XZJ!trpAzWkHrRY znAOrr0fSYs@Qs6W1ySwQ&>vMN_FBN10q zvNbuxV(0|rZiP$e$B90O6mB+TDx+g~DqqfWBPdBxGz>GJ`F%=(Iw;5nd2aaJ3eL>k z9PiHltFFhC>ji4c3l`e>Z0gQmBUV+gO|0;k*A8BR(B*6_3^I%Uz&`%jLPfc@`8j?$ zZ;p7~88bTN6oM?{i$F0r^qGvx`*S!MmF$T@jb(6StdE<6n=g*TdLaTFuTeO^4$p*M z3{Ny$^ucywe~}baI;5P1l}Tzia(wZ;uzi$3O1w?$PH&9yEzmX(RiRPU6*ZJb!;aEamC~J7MKfzm$nmO`$-YG0Nr|FEW2p0d z%68h&=;AI_6OoWbL+myq>X&3++%V7Rvp*Qoy|VM|VqLH#G!~;-@6SsJs8B8-f$4gt zF^aE_^m*C-#7b?6*$%!6r6Y(jV=i z%th-zM;StEEo`C|Zt)BADI5fmXS9xa)><&wv0{O(pZUZ;JmFVh#{>KI&+_MiPVTgi z;bp`?+$?C2fREUu9FmLWuXh$r2>G#LM~++WbtejhF$b)I!2ft@C$g#r23!~g=Gh$O zdDL!+XlAg}P;ud`A^jvjKYdbBBckz6xr!c$w8)vb;0Q+bBU(@U*~@a>1Q&y-2(1I- z!r5MxYnt5hI+)_Syst+53RslrLQRJw{nc4V7@qJvhC5R+^5W+l4a;24!}$VFmKTMD z_nnFcyoKM+wo+jT;=KBOt)jV6^cfJwu^HuFgNRyF=x^_JdS2cN0^9-1{ZeKb_640D z#&AXub>Z}U1w^%Co>+6RW+MC>pSUaK9wmc&Eee^^CISo2K0kzh=kR5UDh`|a^ayTV zxEw(1o>3Ry7$4gs%8XNN3E*I%jZ+mEYJlC zb%$*h>j2ZW=!#PaYq8wET#8w3>{W4zl1Ghc(z-3iut_Y`35%nKAgcCctuoHc&&9Z*{p+Xoh@It2=&o!LeJS)8Yz&IVgE_e#v9BlO z=OX~cMkj7p8OSJHEq*iOW4@&t(N9@Cg`ZHlNuX_=4ekhq6X z8uc4P3O78&YiM?kMy$m;;mn+NG5yRKm`8v?i1NX9nE7I-T^DF_l1E9OHYe_UB*j3x zB~9D(moybM;@H z4lER_(~A10*dY5B4`JWff=^H?9gOJy-B7|MW&Os{Y5;UZrx^XlpTHIF!51eaAzY8M z{M~0{h6^yKhZ<-6DMVlJzPIb+c7<;*b>2#xPTxzkrN<}tK%1N$RDM3oN( zQ+|f=hopg*loI4CdUu*UUaPmmjv!Fud$RsUE*eE=+1wGgvc_iQeRX9Q9m?^uzCoSNwNEvkA_Hv zX=0uvKNu>~VMgzldOv+yT!?Hk&edW*zIONctwgx?NJ<#!^3i~A8c^DPFL87$t8sTj zt{|3Xm9d7-HbSs2W!mecu&GMt_x{q4U4NANshj$fuj8*AWRn&Y03hs2EPQI*cRvB# z*7`HjuHYzIW9{~~IG8Om_E1SJ!1}F}K112SFWeK#6lx7-;~5uc$d}f0=MDT-#fxkNOb)b;Fo=SZ4qceMIi?o*j`LArgvdU zF~3+Z6+XaN*F^fCEBVm9lzz(X0+7C z`F&k*Fp>$v!+V9bmKfBp$k-h&Q>0#UGAZMw#={uFCjw4>TBMJsYriYav1(a8JoJ_m zgi@83@}TbgEvqvUPLt;*h$?>XYw^S+S?sMGlxtE;u@xWr`%@Rlw8C(3X+0U#;5-ar z^c8aH4M*Z|>IMi%IB270&P;=ornui5T~l=r#Geok*=Rnq{nW3C7jT9&_3^YD9dbH2 zGU8uA1GFVb&rt@(bN*r)6b7C`5# zKbA)^GW!Kob%AZM9{$bx#oUC7jIvmR!>h6k*(khZ ziCio=UXG=I&RTa0Ma>|zTxZKekF-@Z_h;~M&^Mieh5-d|%c9_IYCYDpe}Rdqm9!Nv z5yUDi31SQQGsqZR)fTTYa>AJ*LDj*H<%PemhNesGB-U#MDP4{;`~YeO1C-C->+8ePWKo|at%d|Q|~&<*9xi6q(! zXk7;LlQ-r`UQOjLqzP?rjkqpcu_{KZJBw2Fbv0AY6jCFf!`5+ zcp(`083fm{oa4vi_FP*L9%{yL{q3X(w&qk=kh8G-uadBxr z{ENmAUxJ}Ft#r4r=KSOOD%LAH6ohIHr_-p_qpzkr2w0_X`40XvEa$mvc(fV93uq z=8)-mGp6i6`QQi#Um}7L-hu~kb#PF>{=fQq!S!P~@0U3TnF~5lG!}5% z;ImPK6~$@iBAD{YNa)uCiy+`-P>+rE(J_E7Ivg{U^1Lj=B-7Hq!Ho&7%YQfG8}W$N zrSV~dnZBc8?safCN&y51*akk#$ZkUOD{377Zc_!X90`x&(S<9-6xc6_Q4y>`#-Dat zfc4w=8_G^CpIP@zte-JX$6=^bi?j?rwGRiqzDlbNKp`8|FgtOI)%bFZ_-l@@-88%j z7%JE0vcc8h^?l~VPIwv${0|THTmZfWZ*6e~AmIwi`Tb#zU;2ZBQd)qf%1F%YAR=VG}ns*6|aJ|v<|h>}Rz+E2VW-Dxzoc``;@ zj-AvaRJS?Azx1p5?oXOK#y4GPSaID})NU)JY~XEM8i8Ym$gj2-ns$7_<4IT&#@e$- zsiuRU>i20ZU`yG)#4`NEI+4rp{`UF=?#JDKlK2*Cw3fZW(Vd+E1SGVh zTQ14*8`!6ViArWeb92@eEyIn^sTO{XbX1DQYTsaMhE~R6e~VKSS+qb58lHxhl6czj ztfwdekvKEN-NqFHTP%{y4}=dkVXowF-S#$xzm2S%tKA9_rxdaa7|BV1$39?ptn2I@ z@GZpUXXdKvejj6#MT@e7k!Elw-!~m1TnKq))CTq1UV9VdQnv;BI+i{SxOX zjCx?|Csw~(&HA@U9ps_0fyE36>CfrpeSjGhWKoFQX671}1j?RY^7OsqD}JICL$FtB zM%F8O)h6^vC^BkSBoRsiH_(L4gFJH!M|kLq*I|r}@adV0{9?TMu56Xk6Aj?>+PKC? zDK0|wfGrWsKy%e;`o1ytVk^l5((csZKFO&`xxuI_7do(81_w$N6q`91MbV96cE{4gd3PLM- ze}Fri&Mdm&YQux6sd8P0yZ(5S=O(J40Iz#irc_a8-5{_8K0Q#n67D602|9iEPnFg}QG*N5|#Zm*eSB2SKLbJ#TpmYi1xjYBy316;~-g z4YljOmP(2=UAnI>cGm+k28@Hr-wRqSg>UU%cUuH~MsEgBgr`nDqZEkghWXfiU>w+W zm+kqML*Fb!Np3+LW&i^#3}^2;?A8Nc3-IYwRT+=x0Kd%2m`f?f9ksY-oe==Gr$)Zi zhL;b3c4X?;7VPmR*)Ib~HX@!Pn~#%I1@T%)WO<#!&3cO$-;f*XQP<8&?=E`7JqmD% z49|h;2vgoc)XygF?U8-vWC=D&;a?ex&ny8zA4h zuf)KM3a+}leFdnr(Pw)4>MN`_uy)j8vI&${cJ+_hK-BM4ZA2{B6A>OHc+*@JwzW1m zU)a1|+xjQE$G+09OM|UsfM(6`0WHEqWAO*{M%nS8)W#3-2J4W=CqY$kHrI3&!lziUOHnuY!9Z^j70AM{8PlOHtpwY95m$spY~@y z>zUbpj6(y<4BzVgQ8TJ6BV;xWw#%P@k5%$_foOa(Bv#31x~U0>TJ4-qq+!pOU^aIg zA5>#M8n-1-r;z}Gb)n zy7hG%wHn;okczPf>KWLz{|%$+yaBysb?{GE({-%1*5Bu`KE*zc?xN}I&ARkf*@*^7 zozO3xB$B(0rk(v0Yd;h-b-p3J!pX(^+~HU&hsrP}!*U;+){6Pw4#9CD>j@u8%CJXr zk&3xyvP{NBz`PA7dQpn)+GN||F0k(hnq{I4#7AU&Z3LJHcE|O{_t6bIH!v4K8DK_SQ|w*=m0h zxH~o%)GesbF^m=mANj*5`NfEB{Mu-5)Ac2MxJmMe_8Rkx6$s=wY!nS!x`y+U_U1yg z>w1Ig6%}_7$q6NkGDCZRS1i`A>G>7JxRIyrRU=D=dm7v)3=;3^c}2-8JVr@iyIKx_ zISqbUKfx>ousl2TiijEY6D`k)>;A8oKH^H4t%ZousyW~tH>Nzc-_y1Hb}J&%EffsV zL2@Yq^d!dtuIw^nO#!c|Vdp3v#l_ zOW#a=Nabc6#q-+?>xJ4n1rR%X^+1+^9Vw12NTX99-dW@{RdQ5IoDrrE zPU=WUMeKW|Qp=&%dd0NFeKl<&C5|xFL}#?7tJ0eiFpH4kFAWoqKRn`vPojRO=yfCj zzJ>rh;C5*>v&tbKb60tE4Qv~v6je$yl9OevU@K}lc=7ZC4T(6;4+xh#==Yj&oC0J7 z;_vLK6${;LbDlx|UzL7HfbSD|lYKBMXc9^|s4VGAsTfbQ45?M*@{_c`G4OEpV;)P6 z5M|B?x^;EL6}e{RZMhNlzWstEo=4!0q92~)R`PH`F%RDrNsx}4p@S- z;q8udq(4@eE^^x}ro1H*R|3R5E}ZU{l8TQ4q!`S2qIQ$rxYVwVU$Y95 zBp)39bqmY(3e$3GPBxeDqh#p~emVsJ8dekEE1vg|omqF5=}1uC3F-oedoC-RTBmKf zLn=_JQVaRlK80E~ow|x6PDvU1?oWoi35hsOL#a$?sGKleeeK_8O0wd+O$t$)=d*H+ z9Fy8|+Y&EDYoeX9X*qzGo$_5EbpnE4@Wv+r6H-aql;mPKFf35^75hM?Nf(oLgFk^; z5#WzIzf^%S!5+tng?pY|?^0a?!dBHG$0L4N3q=imjf9~N`lEyzJS_ANAH1Kj(hpePSD zYmU(=xYcjST4mwZbPW_)Y1M@=m@yX;hQ?|Tg)J~#!uQU}pb4JRU*0*!cj9~XejF8v z0W>DVj7ck6%PDSVh|0ypnE_4~s2QuVi28~x*YW#rTb~S21iopTQX}JgT`gC$0Ug6J ziE-}Fzy*6BQFBX0sT<2KIDhvrOBQyOYz7MgHNxCtSqdnx^09js`RPm38*$Cu6#n#I z5%Lk#J>oJ{7b-#SFDIO}g36xXH9*4+4fIr>O)#!z9z7qoP;K`+dj0Iul-KZ{(~$39 zYK>hXTsY!~0AVtFEci!%$ifqm5q;w!POw%2jaoiHJrJB?^Y48;b1vk~n_1;m`etBG z&ftO-0qd3g`2b;cvtK}5eKGY^mlD}Qx#XGGYy%{u<^fO!0rBF7^f7AjSX;C^XLK-S*Nqn8B_x;L-{wuQx#s$(5i z0IviCKSj@Oz6Wa-9sK$ZocrE@@;DrB^hoVfV4)0X89e)}Je`14Nz0c~LW~8a>z9j_;ow*-Fy=L^;P(>q*oXtBYqnFb z!_SMF9Z-cXTLJc(V8DR9Z;b>M8{lg|d>odj?`v2)%RSm;%!)$EzlDf_g#mQfJ(S({ zPLKHL@h*ABSjELmrQ*g6RDQ&FHU3FO=ahg|V_ ze^t|lrsZ5hJZarw*A1D1R4iOtU_-*)t`bRWRNPcm}2HdiJsW7K4i9&4nXUH zWc6zxL)~P9fgvmu8?*hGNOF&L!1(eFb3Ip{peRAuT}T!6Um@Bmk^Rw_a68 z``Ht!Gwa;xz%mKefsU_YmS0clD2d+E6yd3WfOHXm^-!b3pKx~gSk_J?_Bpeps{K&L zeu`JlTer7|`r(JbXt0m-%IAB-2W+Ip`ws8UI)A+S>^t>z;pdDb{h?Lr1A>8xSWxyA z42ePH#T9gr^^>9v;g;wT_)KGl z9@8@xL1pDvKSYGFWPz|X%b z`{l2O7N>;N*ViV2wjr?pLw}3Ptz@QkLAmPr(OG_>NJ|1MCBQc}41jxK)HH#AMihhj z*z_B|fvmZB+j|RjMa|%6guL$yKjH12lxt~VPFU{;IJ@s%QC8LqFLxkV@j-(u9aOaD zL8ucj_AFgK@o`pq0(qn4AMf*@Vk_$ua~RsMeWxQe@&O}x?HcJlcpMr?iD25p**Os{!8%B(ABvoXh1H6Q*+)2Os@Az*LMJ#3Vz-cY44xx z*L*~f*VUc67blH=Tl|E4i6KZajh>O4QYG21f~6HG0vBkGeq96nnjn)7(sx1&13#R* zR!yCFO(u+(EiZsfacB$tYs0nk6~crUnN%b6T)8z52n&=Kf$lA+7xA7@>F{hWtWY z;TOfz%w+T0pObmJAJO-k|JpYB|LLLp|Lc&<|CxXa5uqWYq5W%S#b`F9^Bh}3rENK=>QK%$JpDBwZdi3|j@JfI1RIUC5503bIg%Qiv0 zJrN4<6NKfbVA=FlkzZMCHr!$my2XKvv)c7bfr`iLMAAgT8GB!+)`WT;7$_PGTqI(< zWMr`w)+=$E?m2t)17sdd^^N*l!LXXKI4$=`69NOC?b$w(hP)2Jrh8Oe6TP7qn9dwc zj2fJYV`-b<+@e97&^H@!6di?Dh_?__n1b57vw1adxWH5w^m%=4p(22q6FlTENe2lj z`qB#o{U%iO?iXK0A_x!x;7AV4lrSF2tZ8wWG&5+R#BTTN{l2gSOzs8bP9RyXG}|SP z2rZf`Jk>&*V?bC%e<1iRa~A$e66aa>8WNF3D~tjQ_CjqFy>_kMFr>qz@|U0TQWHFd z)gSr%fHYC5fCfb{?0cLRGQ^8f;7_YYwTL8a3U+s zrRG_N4%UyL{?U=@3m z8X#@J+6rGPq|dUrWYh-PG00v&piOsp;?%alWvx!WZGn~NQagXod@N%jsgTONlR9(> zg7XE$-~%WLpP|M2 zECNlN;Ba7}b9uW3w>x$M(`krOcR_&|uaVp zJe2}X5NIBB9Ec_gXWBROk{|>zaVlI7Fr%OxqX03|H_tipvs$m&Y<>z1=LV#YOlsTt z^Ne5NWaa!J3BZwmy66_Vhmp5;@oWP$XgVk=2ZIU=L-1Jxn&>W-a(bztM`XbKQZ3Yt zDL}SV4i2#f6~X*Ir+^sbjVbCGP~PA@kMbKrmE$Js96bs(aFDRMX(RZ)?~x$7gH;wC z@vv{e{l<&Ux;_^r?G@580rjS#O4HD|8-e&ypD)l7_A}NE{0Nf4&AU=_siA$=mTNM_ z{cvsd5pi9tY_#3-`QU$Ef~J(V16a&V4$_;N4)C{UpF#9$d%b_&0Rk`{ZkjnABEW8=i2 z&q{cR`1_q+6IIG;jkcc=bU7e|hieTgG3Wg5@Lu_J0rTL&IKiu!)JjEZ|c_4Fg^kJpJ6 z-RAKgaZmB!yy^#>I9;5jKp;Pv*xfn}+w6WjjE^Y+l&Rm24}B%hMhYJ`O-8dPw@r*Z zj<@m2;M6_65X!EeU&UDeB)&NP!~kfsEgESxsa)R9ux!s8$t8qjInuC&n%pv*uq zsw>~2#GA9!GVPFOiee?Cm7R4Si*QV^KH@UL#eyz~2h5vLzK+OfcIEk|fNBR##s?tr zh2W(3!sEIr4H<0&#m(3|u46vr=0nGpo{}y(L)sHeDv!gBnW_2}LA5PT@bl($a}D~W zlnNfBI)CEp1gQMF25b=NG#MdKQYQWq{g;7~23&RG zi^n>T#_WJ4!lETSzXLi!KJd>YFP~3Mfy|4LGG&_VX|nad`4mj#ijP2zggsL)YLV9M zHi468$2M(!KHeZC)sy3l9JQX6LYqO$bSkD4Xbt8TIX`C;)WncKekb4C7M2F_RW{{d zv@AdHNBH&wmRaH<>%bGSprnIj1QYfI;G5Y7cR0XMrn^UiVvxkho>C#y1~m8DBlPW) zjD$(wtBWz3V^w#7!R_ZUX}4!SL3V|r@xv~@ys^|E%azSRr7_+bJN)Z!s@*q|u~n-q z!{q(TT#*GwDj@gBTzN2*ZJ;86rW)v2FG~z?dYjHjcBoRb1F-_T+X}RIEhtcCVhX@H_87{vf(Dxt_IMwhXNeOI z`s%_r0A0YJ?Q;q&6>*nxd(>svp2{x%mee^8l5jMsA(#7_JYv?TY=D|f42xe6I>C>% zMhN5tIf}{9QK@&?2{bL>aQ9oYc z2i|0U_EP(tQ2GgN4pI~UfO zg-5OK_AC|*w>Pr(9sQIlLG*m!6GX-cN>8w?p?YY(tshYPsgl;Y zvyn131_m(wb6&G{kWM(3T3u;=_q;BTLskeWFSY%zW|r*`81Op`R9Q z(;E;5cp%}cU#v8Wro-wYZB!tIU(?{9(DXVA=Op+)4=j|`s~Is2M_vH8GkyPD->_(s z>yfRE5GtYzXxrN#-0GeUxI_^Bvhwn@#0&Zr@ZTrCUyzCNT7Nbh{Jo;n*f-LNt$MYM z%TzEojONUFA2J0;Ss3(_c>ja3t5|jw%+{}j%McPQxCF_h3x@=Ec=}%KbL)<~>d4*^ zLg1GrpIGf_f0Mtai}#HyYhCnv2@WcC&zM(xU&94P+6Hw?;`<%sQrEk;v8x)T0D{$-43Pt4uf7C6+Q3__&O6J1W0a3aTRmS8I?v^GiJ$CxFo`rjcAyrT zbM_<=rXGN&6XeYJ&EAMvAr_Pt2~$8wxX*BeFy+w)&j5nF{QM!c3klVwx=ElT1z^}9 zUMCrP&edD7`Meucgz{z|{koGig-T*BEBj#&%rj;*`}r;|>sDZDI4E3venT?%5#;f| zH}z1)r`x0Y>zgWq_N`{ktrZ8qRIOsi;w#Yf(1vmit(A$x&rluU>#;fnK8?;n`Y5_7 z#lIW?f;Y=(4~MOP-Rl{UnmGyj~qTKu-et zO-G+SXy+x=&qE2gZ4+95%G!8;T1xiUSbD(%1*^Y!=e$sj9A_AB>lRILD|CQe$iJgP zG<{pts;`~3hV=+qTBI)O!8iIIIbpVQ&QcA+6~G^M|Bdd$OJS-cl7E@n-9516>D@MZ$rH`S9z@dZ0&T>@EHo4n#?3X?GlLVM$Yvy zfJG`|KqG-HpMDHTo3jX9v#*7ZEuwrWC4pUF<>#aXKyc^J1KyOPFASNGfYRCwL1NUO z?_{_~ZOtD<+=)hLGI-^5*3QL4yTHXi{fH=MJ{a6H1;`gQ*W{imgAuGpp$W5|1lrjL zRUU7gSOZi>${Q%u(xpM#Zvj$0Wc9y@Yl6hi`O64We&hp66(7PcV8TN(_1j`QQ|zw7 zCH2X^8$?B=ztV}7=}OYw!#X{BL%$=zuX6(F3%ME=&`Pgfs+8jq_3(3lpsx_R5OU^* z{gZ}*M^UAQ<@5XpKdqWw-sBukdNR>|NCAVZ0|1a1wHBu%gY%0y!Ftv1ThKyauPq6M zJ=vy3&0*u-#Mu2N$<|CR`TXw4l2Wvz(FbqMpcnp(t{;F@y*Q%SBqRx85tIwoGbn-J z@OTkE_8kdAfh_9f)!9g-)IouNRpceH``xzSA&L+Kwn?8gVbc##-C_`jVm6!DL5hl_ zCefBaFUN-&&Hq{lc&e7syoUt~ZCZ5Wb|hZpSu$DrcYRiSFRJsc{M7ONGG16q%v}fV zI2m87{@WB^8}~t}?!;G8eK(!_svKqaDRalQd1TG=ZJ9r9wn2dd`Lv}_tHyQ5gUww< zA;K=x7ZM3<$jH#R?U(a2Q#^)Ee7WPV7}QDq1W({O6a2kM`NYzARZixJ z1DnB}|JNELgaC4c;(E){C?$3MGx)0FaS(G1+0Yo&bo_NV4WtF@d@7msBkW~2i`2a} zciEP)G3V5q^tOSY@Ds5P??J@y!jo4lm8?aWpK}2i3FQzYv=HZ@)E%@aW{9q0`;LqaUt;OX@-12{6yb!@mgR#w2=E!ZUiyQcAD}dI zk6Qj!&4Q5Ra*&^;w*qk~d!NuxVL-M_n1FQkct1g7QF;DQ4betrRUv#(q5J|w02a&Q z=YRxC_7_alDO9mB~_6K&M;-U>FgHwuUXc>w_U z=DCxR1-XD|Ysw~FHIf4g4NCaSEf*=y_y@EN5?gFRG~@Gfo=yL>5Hj#%Nr+-IYtjvH zSgA#$CrBbZ+q>wf5;;Kks+B~gFL2eUHFlr;|BdIfxpLUBNf1FuQxJ6la$9hRU;2j% z7QTrIXNERN@;Ggl7^KN@6ud~_*S{N`K@zKlo?JpEnP z$xlQohU^QTZ_xt?6a!Ux8z4UpSOAX_gdKuT1crn`z5tfNC~U*YcfP$byXPY%U?wsW z@}vlsQZWvdVfxk*bSyejrFRJQem*pE>j(b8fn>CkDOOXLKmC-*t}`;hAZ*fhdZ@>! zbYLIk&rDL4m3SeRS4RUpkS~lF78}bK!(L^;F4lj7uC2)Wth5zsVjXYE`y$lo{EkV| z{a)|4DWt#{6SX66Pf_rva&&%xsk*=5s1ira;GCuUKm*qgfOoci$SmHw<#ESvl9@ce z-cp6BmO^=^Dy<7tEUrDIJ;OO<&6*o+F783Wc!1Rl<%Nj7yZ^j4wXOXwUy;xkCEm^6V6CB|=l^XG!$YQHY7S z)?_zYsCor?0%y-~9Y82~KXU4$!5$=JbwK*rrI&#`C9Mze$UCWLjM!<;euLOhKI`iz1JEvLp_s8=-PI?e|2&9MC)%=<9U6)iLn)+y%z6)RT}xMA z|1}GL@6@0e@*Rtuj%Z=Y1eci}hzFkWwYQNH6RL6DqjHeHKXv6?m&)~=m+D^;)%mH!FYM*u1o6lnb z;=l922qF9E(^&Z8TEBV>HzJvX@_OJwc?mSvB0n!*G`31{dUN{P zDvp@G`7!+bj+}buobWZrj4J?rV8K@4YfT(frLwlcwQC3{zKoawAxSTAgfE=eJ<&~)LL%=b< z#Us~}puo2I8AgSr>c-dWG`EL+ep)gy&~5X7;CgDRnI>d59oQQ)$pJ3atpF9W|jJQO43)<3IxW zAv|r}hqOebNt0?{pqQl!eWTmobzAsVA-`6-QVl-fmeEaFeeAd7Cb+DseahVog`H!(2wfz*3%<_GM1_VH9Pbc4c z=7rIZmd|hkIXjSYngA)wa1Ccuz(T**TljPC56`lV&KExvN(BKmq?jFzPQM7-nwxE% zi0SK@`yc@@kEG9w8n%94CVga|&m(PCNVuTa`VfWQjiDVjeunir>pXr4Xp%R1(LFm< zDFYUpDjT4pl{<*A%E9Eze|ofBSPxWs)!~{t{B-4W_qC{c;S(G*X*G=eDAMu%<`b2< zUiYHboFl3)A0kZB+ikWu;N2-InDDI7{($M&-A`02qb zsl1Zx#!0~JctH^J=D#NsGj0YrV;1`rcPEn{L0Gqp6`Nyss1E=3a1BRy^ZE4qC1uQ! zl?0`h9B6R1I#3^Aio`&*{~jD77%@(|A{yhpJfn+EN@e{%K$ePH9@A<-=*~A!3)3t+ zaP{+T)`8ZPvrRA!mwj`-hK{jV3yye)c^M8GDVA9q^Yu&n==i;#OF2i^9sdK(57t!6 z=|Dt-uF?>)NSHt0d4GxFH2v~YkXt-ZP?((JAx$e)h=_g3zm2tx_2nWfotI9d60$FD zl+FAgSC`kaO}olK&_dK$+>D?IKRI+Lc+-v88P(u=$BKa3CC2wn>K!cckj}ISE@~_|;IYaVcx|+O6p)EpG#$->)UC4Z!-Xte3Q#1Ruv4PMhnV3KWx%=rj6qZz%9VAOCxoedo|wF zZ|e)^6~MIsDfAhG#g~u*A$2#~seh+dI==F0>rVmk4BCMNP>-mC#8oc{hxrlyh7Htt zQHzOxaQecZ3RG)n)eLNAVLy|>xl}aLUH#sY(=ibWiLnL?QO2t6&vJx1nsfzURBZJE zL`*hxQAq#_DGR%kUcv`!l~DdniN4TzLYD^hZdSEGS44WA7T27KigBTN!Vn`uFMewNk31R8h}H=hxD!^_B~9? z02JUxd=~Y!b3@;7qB;fv+uW(4W%4Fd`Dhx{E^#c0(UvZWmAIl|b|CN%E-e6f9Tolf z!!3;1(tP!O^1m-!tTdkGkZzF7g45un<(b(!#4*v2-i!*F#khF!f4M8AM1X0~UYd7z zJNQK=<$=PcX*(-KkrgaZo-p|U$o?yoD=UB{CtFTwWwUU4}mkR$47{TqYG ziXK}2f%_$Y#Lc@a^ueqeXIo%eKMF5>HJjk$)Q{sz3A6OwDiJuk0|?Ab1Ca>%(L>tI zU&XH0$vWWQpRlohbAP{nmeV5Vu&+7G>^yt#JZRiKLSu1&VmQkv_%u8YGRUwyyNA*gigxS_ z7zvnkcYHmP@DIWkLRw_L2HUC~w}QcGpG$WB}QN^dTC4>thz+#F2NiV z-MVb?UiJNoh^UW0{7+Zvp;`jV2>2;%378U3_ zFJ;qf)2r9~TCQLD1&OnHcU7H7_l9~etMv4-UGN(qcOeC=PCDKK4DLq&fK0t$W9dl^ zt^*Vgl}Y4X26*A&tUk|qFm=dhst~kcFS*I6EGFw-!kTq?>B@&dP4bz9{r6t%cBf1_ z@5BJc3aWo9ZOGa}CoY_4clKlbbVu9D#vR24$#4@?BYmeIAH!=+2Epi z(wY94${&;fHmEe z4&RU0Rv^y1+YWa58qUyAh-^Y?A}8n{uP(aFRz22>@@7L#@+yNC!#i zodNNg{1yi_XZN|x9*(9PEp*sN1A@)6c!JnAI6b_}3L9G(C96q)c)J}eN$G?-h7E{U zuFk92@JF{b&MjXnANn8C^*>s8pN23#>c@SX<+$%3hxQXa_d2tga$n!d-j}ROMSjWw z*_b^6Q}a43^}1_SphoV`pCkdA%JEXWoorPiUa*qSUyET zq`2p=uzb<(l-__57}TH1Q%ACJ_R2aUf4}EvN870i2ZrP}g{r4_u6hrbe!Net ztEd%c6FVldaX|L~GfIX<>*!7bP=I?&@BZ*I+5+z;0BvJ zuVz6Gz7^ZO{3JY0;3#YaB4%EK1wzL~4^q#!vIs9Mp|P5UhTj9{D`AYBBu}WL{Hghr zKErGu4|$UA(UM6r<2djKj3-|7=49QsWX{n7Itp+g5=?clYrJQVy+DPEZIbI`-6tsTReD8SB1a9RoeJ7G=g3`kMB;}&zeL1(Oz&}QRFCgeL{lsf` z;BI%-=rg&UKBv1HV9AmEUhfU+KHvLFg(^aa4C8B84KNE{7Fj@>{ZzpKsmid29YnGLTl4Fc^f%yhD1@yIL`0(*MB~L8;2~xEPLk0lZr-77cO&-tALosz> z#-tQd&~!!KX`~u9N@t4o8IRBi{O{Myi=faix?j9#zxPRjEDbh4vAgb} zGnUDRKp|Qj2FUPd#_YEkph(C3R+k9Q5Na?A`)5;%!O@V3EnmbiF4hYOUQq3sb{x4r z&>!Qzhgnb;kWLAJXg4ADs9pG^&oo=(hS8vJ1qFnmvn-{696eMfdgHCtIZ{ARn`-A5 zM^JrH2_QqT%kY3vf`51MaStveQ7@th?nvlG7FNeF-uZ+9BSQ7(e%_Nb^0*kaW|-05 z*cOt5A}Zu?&oz%UVGbV}o?uX$JvWLK5E?)F0Fko@-m3T}DOf9YU(*LMnRijVCGTfm zcOgs^GngYh08R^mgTv=V2@fvt571cqwl6Li$)ad~H=4|4@J+Jh<(8xqVY_CGLI}uy zV9F;BQeiU473>GAdc{sNzgxcKc&c!P{yZ%pND^PeUQ&+&!HIaf@78miHm~ni(#qz^ zqIZx)`n#F%*;d82D7<9;!$bJ$r=uA(&GDMHpE5%T5U<( zp1;0m#9#Xitp#}1J1;v%;2w3!?Oy#rHGTDudH`Ycq1nq#{M9Mmv6*SiD+L@eM}__O(%4kTOn2{eJ> zUuf&(_hf8kliSb+0}W&i{JXI5k-(!n{QdVQxn~2MAb{o90{Cn2TL=NOSU7NLAX%f& z1=#ciEA3Ru2%X1%$q)*I8b!d<)(-pkLp#~~f_|zm)1s;XqF1bGt z2WvKmc|5ESlu3_hwSF>FK$>8!+EPj1j^yAj^N`~94vQt-aolf}z>>jZoEX+>K8|QK zyt4bIqu2odo_X;lpUQpzEsT<~dtwZb;oyt|1?SD)I=Y_10*F=cgtmW~ExPdF9rmxo zXCo*;4_@~x?vr+kdq%w3bxBKT{fYF%be|3O=lcE};uR|0v8XbBCFxnjf2&J^Zj*RV z(c6JgbkqtYqz>^OAoF1%kMNHE3D7Hs|E%S#4Yq@o8PiLP=$T8CncXc0G20qwG%|lY z&njm`(=4(_3@%sfM*dE72bjiLj3H4L+b4luF8Bk$2kcXm3j&%<@RoGfKFuBz_hxF zxYY1RO9uJb6_mm>h-KD$I`c5h_|QsskR`mY2}qaR=S{`=CSgE6l-s;G`{j+o@!*dI zS$A@uOvmB(L(J17n+VPxNFOj34n_1j%N6DA)De!wYKA4MF zI3VO5Cw~X-(+E@)IC5uNaBe(yvLgF4G(~x`-%lK*`s9%wNQyf5g4n9}HYLg^Pkb5v z2|wT8f~|V?NsktqmxAG8rboM#EECMKU>zVleib z6^j*V;bO7cFH{S@^1T!o_vZ-Lr=$3xuQ;J_r)c>h+xfL%AREMe1M0uT!?y47$KB0~ zKbyA;*`aUYX={i<%m^k^?5PXN{3}Rqf;9nJ43Egk)UXvh?wTG`{X~?$Q z!JNyf)RXDz-M;S`{DB%c2$t@iC*w5u7d-Ea%)FxC7@{MRy%m>%QN|O+6-MeccbiH` zG`s}U&8nPMoI1bvnM~7|K8XbiLf09ZIIQ*e;N(wA75oJJ@AAK`Ps(Er`BEIfKIHpL zdi-Dl%hIqyS5;z=?+rl0No(Lci@WDM9&)-xP**|cl%~9M`BTIMjU7g0$tT=-o`3{P zW$?7aE=7@5-#k@?R>goSO}JqWLJAuFRpwaXK#Z(y()CV(u|=cwHbmS2X2tIue!`OIGAdl}K)$JYpJ0q4PC32=TyM~o-8Qg7mcZ#dL` zGRrpxcZ~9}eiu{+;9ny`yLlF$6k z>f*||jcI8{l}f5FP?Xk0O_}{~2mSAkdu}nPs|(aN&SkPhQp@**v|zzkqKVRZY%yRb zkP8?QAMhUiO`-DyU09JviicLbvmA`rlf zN|ynsEHC%6EPyTmrr@q7QP8gr%jbEif_)EKsb9jr`bGOe-L5I zzvAA*y{8EjVt7#qqHWUS@&3tHIOjx6XiwbCf*VcthN!=8~sASg|Bvl#a!k+`0 z%*pYfX6EZOQ~*~58o%ZwH^;p|_CWEJn3B0B6^7XNoeT8$!kD&U#R{a=zj077?0cAW ztyZye8&(I&Po6nv5dT7Jd}dQr#gD{DFsO+i^?BdB^)LKr<|dRGfavBs@&NxHRza!W z&#vs3aBm4-rYLIQ_Fzi}KSx_7R6fRls2ahq!D8INNmEBW)uQ1nTOi@#?$&IpLr3s( zcqm8)z{zI1xK#GktW^5TQ)-k?%F&ey0a)sFIX?I~*ngrb^hhQKRy-3B)5qzjeoD(X zD*O&ZX*}H#P`}mP&0*x#d`Sxs0EXuGHu4ReZ?KOFu#Ew7ISZ7lXzs@nF$;x{m{-w2 z(Yf9Ny=EB^@1ch4Xs?!A8cd*g=q~U`JdWUyF@B1!Al1pL8Xttg@Gs}81wOBFb^W?r z!~R^=K*|$nb?{JE81KV$XIBi=`Wb?YF6)d&3%;C!Kj z@9=X5s66<{5}RdE;c5d4dV}}`?w!RsccKZ>oKMAZhUF#bHi2SI*31t=Z21LDR+Z&P zhASl0c$D42BQfBx$ng1b$HwCQ1+Enqj)~6<2-27jr~(5uQ{_sQp5x_masrnoMi*;#L5}>i5;G25KG75T`0&a(kM`fhiyG< zke-mbA9F9j)1Qe*dS-JxtOjU7Z58-7(h7CuR~(3z9aaw0aYxl-BVE~3tsAH3~n|V+I7@IKch(qZv`cZY~cKknX;!fMT-y*NBV-j-ExUYL>#NnKXFES znwEQg9zo9)!W-J`bHU$BX>TYHUh2;{jXpZ=BmnfE-3J(p>4dNf=_Dm!kr@S@#f@rdj@&I*P>L$t2Jr)|JIyC>jWJLF%WKtBq(R}J=n%!P zr!{`&mw!+$^)7~Y1_jXgQ=cy$#@z#yoLdMz?+mBJ(sw90aFl1!sHoe^J>|JrzEW;7 zuY&by@f8d?5O7qPCwIzTLl1=77JY)XA?FK#<_7_ehnmdlYEDn)F6w+E6rh$HsV_@< zfc$22uO>iM0#!zG`@LxGI>Gni9jU-O@?!bW1eb>H@^eV}xoIEjX8=&w-1Mg?F;%XS zE=&z=Q4oJr1y}+hG7v#Ip_=T8aTGCr@VpLlA@&!n{y08q0&GXSI<%X++ z#g-kj&#{jo2-;zR3<4kP-k(MR&spymvu|gN6Rt1#4+5?xUOR}S+O^1Ci_-_OI|nQ* zV1an&HNH$@R$N^>@K4aV1!Q5mgFQeQEXZSws&82Zuz|_HDih`R^P+7YiMF$4u#Pm7 zYv?}UvC@6UQcSS7{WI1wD{Y^9;xNpGaT)-Fy#woG>s9WA%Z9*)BqBnNm%o+!Q-e}~ zEQEkHh|?u>yuKlQ2D~4Fg8M1xqm?O(x4*scA9Y%b9RrXJRs-bx+KAF-{L+kMYviZdB`)m7-cc3F|!|5G#VB4$m*n{goiVZnHYUH;-hMN0$3q zk311Rh8eEd!ApN4z#TusU1u%?@m21)3la~DwtpJ@ut!*NPQr+%d7^2edpUH|QF&xK zZx@OXz{!Q?V(Tf2`;#Bx7&#wkz^ym~x1|1pBsQ>&G_V2{%@UjMDE6Y4em*?_8h@o# zRN^-IN?sR&4C{2qpZP&YTzV&*eE0A(C$NlG83c&iYI&H|w13%djQcm1V8K& zEq0^}S>HCmfN@qXyc_q@+nE3gBI*1v?ki|$HJ?U`852JJxbA4{2mO8KC&9p5d$hNhHJzJVYG z$CHKs`HO^t2NaD9c-G4;D>}G$j*aWZ25W zbR-c(*@N1|?c+X}G6$2tfn?oZ$=U~B;OrK|1SP?q20O+bf9BmW65DxsUo-t4y8wV+ ze{0Vv7Go?KV4}jS*<~K;N6c^$eoFu{2$EUz?R*XRQC7VBmL7b)9K>HXyIM@aF>!cGY1)Ypzk=R*5S9xbtRFOt&nu+Ckyx{05`4b%oa!-3 zb*xnKs4LTUz`nw%yy3p`@)7(NFV^@}JBfX!NlqpAO$U z#s&P4fkT~1{~jS&lj~J4M9T~U(m4g5R*a=0p9JX7eBeJSRKJVfF^GQ!4+4`ura}<( zkQHB0`%=cZ)6MS-!-2FBnp)&U&;lGhb^~#jJSsLoca8CxO6-W9z-#$yivu65&p+&eq|1Y67zWbk|2aZ_xCQ_M`Wfa}Vu0vIv{e z$A>}H-w;zwSPaCEEPN^B;vg_-UaW_L-FjjAcV0NV@&suzp`hj>a3n|}Y5PY6oSyPw z>l`)551?9P`H~YN`n@FV5cpI1YdMi1uFiR3UjzX3?ZwCTk{hT-`(R7Y`__cJY&_>b4- zt7bi}HliV;rso|LI-(Mj<0sG*mR1l&a9sNDEVcv_})LF*K`^oxE=z}z2syHgwu{O zW`!rdRg$T{o^Dom2~?$x*i<2vfJ$Fv1K|W*hXB4^RrHfQ9@6o62B3@gyKL~07vao! zWerr12Vve`_sM&Oo+r@n%%X!p>QjED@>duo3G{n3h*F{3xi+nyVLtqP6xRVfHPbZ^ zKL&)V^lI;IFt4BS4&{Q_jLhfbVF^QMcE*G>h&9wG`yUMnDhnQ`1JgOgI7jkIZHqzi3rXgtcB(?a@YjI#q&YQTET2me4k zdRm@4eF0%9tW7scx zMWtqwAnJ>r<>I2U6>pk!+xyMS>s`lCs0=v%UP_`Lfu&fqUxSA#spCdL_K2L)qAmJn{Sw?Zs3=Xhz%9=2>nEu>snF3kLNY}8cUt` zu!WaS-%;~M42tu9fZ2fAA4|Oht?S>B*d%~s?j+{}W^V5-LGD8rXx!VZr1Sf>Iat(y z{3u;F;7J9qQ#@$_Ru;64d0~~c7k56q2Md}#u*w1;jb4$c)M1aA#knNXjRF=0KHok#K{MZ2;RL|61oTc(8q6nI2K7@4MyePS z_yXUS{n6wdX{pNcaVsty1-{x8QLrpYa9@}EP(twVv0(iW%N7vFAEQlqzRYCm=U*W- z)L~S>+JB3%^1YwJYAmWS%pp?y0a1{gpZWKvxSI&kVfwPhdvWJmH-ak1R5{nIz};cu zozoiqnSkWFngJEh{!{7l@L1#o zsLQ#Bp5I|C7#QkV!J+VNJSx9?@&=mNZSk7J5h|@_4%TelC~RjeO!w=B4Uzf-yy(hR zdj&>n7|i*cjCIOBgS}l1FM8#@3ca4XpJ9pl9<}F2_kBiAKVExm&Ws@~1 z&8F|)!ZFeJ{`k0llh3HV*0@n-zcf*(D*L!+GZL-;B{g6N=EG5Ad{>`>=w zuXdg$@%4z>Z={{|kKDnLQ2;+y`25;*Y6({#*nMk%Y&x{$^gbPXNy*PSBS59ixArix zbb&2v0Cu-_bS&`h2Xu|nUvT<60?L5x1hmBOnSgFvM(eGnI2MN!f?;B^l8=&Do zNsymJJ%iKaBR@(Yq=KG1@sm*&P>k?yXhMbr0h*-Jy?PIA<>>8}ZQ#c>VXg>(;5&Wc zIkg$L7>!p2h8pWZ-pK^C0i@)bG6(7B{HM z{=jk<)9=~lVLI5#jBK1UiI3$1;^gtYmIJBWZq;fjdnk1^DX`~p(8B$En6F{Y%S57^ zX#}i!&n2{h4GT&hU)1+-1h}09rDnPNyN=3!hu!A{!yC$l`TZ1qMWh!|n%=vzgGQOf za;y!FXBXr=!Ni7*{`3Ve?&~_Q-B-Wj*n}Q-ra}=Pi-`~@pW3+_e{K0S%z~@@-g$p7 z+lgG8Nzy$5MFvy5lBy8e(tkSgq|@i-d#p}%dfGU)E!%_Aayx)xe*@uN9-1{8pxfB+0{kYFNxXnEF9q~M80pjh}nd$uudkS%RXfdhRcfMOLE{xf zA|%wC`F@?irjVLe#Z|4<1+))jzp!+I7W0X&{iBe^c#ID|*NXH7f@|921q^W}{^oey zelYLeE8c8QSfx*XC*=Y9#_X1`gtwY|b}yY$l@(}PrGUIot2KTn`MuYd7Grk36MxMqdlv6I0ywuF^&C(zVl4~ zMy)c)J(>9fv=P#a-J{(x=}gK&kT>Qi@2d>d@7^ARYkL4liUdeY5V|aSLhbu$f(?y* zabe7RTTjeVt2{@w#}NU4ExTSaiFS+aiJ?7gpm6&`V$ARHv*-5tPTmoX|(k~~nWkhDqA7*L(#e?<{#9;U8^v-2LRDlzgIvfDTNhMe{VWNuKdNTJZ=OTfwpkkV}FYmH`#(nyVx>-$b zn8~VO68B%`u47$QZOy(CK~hshBq>3X^dy5K8HJ~>!P?chood`(oo}7Bmx_omnez`L zc<_QMTF^*43$GD0D_y+x0RG$P~PbvWhKJd!Bt1NVtxG zI`Y+8^P{J3cMK~roF(r*L^jjJB8gN_Jr*bJ85AI}^76GI;dW#kDVk2e0JFqnq3tWm zC50Hn=QmoL!yAnD2KV?4uHoHHxkuRx$KL`J&N8hws@GD_M78PID@W|&yYg86gak&S z#_{xngC7$|?-gPPuw=j#a{4?|K_w1T|3@L2V|$Nlry9$=EHW$`hz4)QKD|C0NgX;X zvabEdFQX1mV>Xi1+ZH&5UA3g$c&$N7K2Z2oh&4L%E>c^)VGU5_6!CyPY ze;tXj^EDNmay5d??Otn{RbEU?^Kkk6Y)?Di2$4MY;wFB79aw`DTJ|E)jx*&vKh_b6y!wmnLq7RnIztKfW>_I|B3F^T}vdVLlPYBglz zz@ku`3(U=Kq4k6vkg)oBFN<)sy{P{Pj?taH(yGdP^0KazHsZUW)$vc=P$5JzK9K zYA*%tbE%ed0L?dS$7IXQ*XG3ktpZS(_V&0eL5Z7)eXa|hFfR3eWUvc644>K-6VBm4LP%~Qm{|C38cY;JGv6+Akxb|u*9K;HZCoN zzIpu6&}HAVJW_$}@)N#-Je4Sn1!h+1Z?onIf1L~#ml<4F7`nOAyf47hpMvR~P2N_{ z^|$GX6B9TJ{Z!5iumi7sdwM5E^a8FZ=S$N*v2aS{a2H{b4|MoM^uO0=Z*0k zZ|);M4E7%byEJoJ&4t|gGi3T-a>$ZipOONIt)@CTJc>s9?Qb(!OywAQAJcz7W5`ely- zCmrA+wP4Rd%HPw)?stp@$?2Ub?Tu!eTR< zFr$=_H^zl1GVsKV$-lKikqEfv4P5>w zT$qLELkTi`C$SN+5Wl5M{j38+oA4kfaw?booH=i}RD+kYIC1k52BQ6J9IZS1&LQBm zuc|MAg{%R3B8~;iUOYcOyT2473vRilnD#!Q_Kz69*XLZH{xVscKxiey)~0~T&>PTg zt6T(&7TBHh1Xlrz8+YWUs6o4e-4C$c-@l{6WlGt{6h})nHWkk|n7jy>M$(Z2Pu z4u4EXD#g08(E0Xwfxg+}^$wUYMXL5qkH>RnfXIcK*ZG9U?S8qiGgJ8$3+4ZAM6fP2 zo*O$B^#}aHQgQmr@B5W{Z2N8DdHI9~_&IUD{-%O`tC=XlX}}-k(6IiWlhl&O`=7sfW;j024^8L+MoE>stoqaSc zWLW$)quuZ6f=ew*CMG3$N%nioO7?7F|G>ML7nGoYbF`nc>+uY|< zF&__O%xILfyKCVD>^~ZB9VqNTX+R{Mc@`K4NT=Zis6^toD(Jt5BQdgI{2ngO)}N&j zqk&2w;%vy>hiCSK0HPD$=$11V>1{D8;&Zy#l0Neh$CW0f1lnoT+B0Hh{FQ8wiP zhiz=uKC0qYFW^V!>_WRAPdU)^v=5#45oc3`x+Q)CleDJzmk@V+B!YhzPOITI+Gm)f zzsJG_Z|BU^C_v!V{nOKox7cHazxIRR*E7^fw;@+6*7K7xL)X$%lObY~JY(O&&k0PqxpQE5Vx{pVC?)%y_Vu(}#+b zlm-0l!f7|Z;AyKmkdF`30{4jYP5vP@XWvq5x5^A{ryznG_1R&xz&M%oi~51J=50^; zR7A-G>S|}z3MruA9u7kUHh5Llx!vJnsc{|*Q$D4l5F&5?QyIUzZak=5wvR%ngTu)+Og(@M#uiWj z+-o5D3AGc49m~hZdmv{Aa$6UZ0aL2|$){w!akk?K$!DLdPIvl<4!ATzqAMqKTTtHA zTy_&@Px@1vos-&8>_O|{ycOK4n`JffUg?I7=>AEj_3pRY#*GM3y^ftCT=ez3I_Kc} zrq8FZdQJ{M(v1><^RwcVWBtUtSTkzhh8jgE= zG-x#0xSDRML*R9v{0rzvGD#R;zTxM0k_|obZ-uBGeCr?A2_m`bmw7L@v=y)RkBU!< zb9_+LIA&jub@$)`w$g85Rfjl?(sL|=CE>t$;4(+|VLueqRpHZ+5Z?5o*i&yy6EMA_ z<@EdzoBI?W_c%UlhM0w)+)otB0QR69Ja!i}9G#L*x5<MEdD#95qvNuindl};KfK9g zBAT)FVyL^1`KRa*-A)=bh<}Uqk#cJpeyQo#J=A^I;jpg*I$a9yp~S8)Z?)2^tL+{; zX4nG?HtJ#Q+{N$tGbiuJws&wZG(f`7-|V$VA2k%ufTY)8r?;QRbLRG|7uggBkldB? zFimbxTUnYF9+pWs+BW;-0~V8tuPBP@_b-Qzz}{6+)#zX^!a87j1J6pE&q}6k$^3ZL z?RHpk0maJ|DiHyMqb;*Ho@%pT|7(vI>iwIjw{u$ZfkGF7mw4suvQ7~6-m&K1+i2*3p3umg_JG~(+o?x2k6jv>h(zDwD!&-g@)oKn9~ zFJMo)UOofs&+zC1Ud-XJ7jnQ4F_kHzNg!woAzE9M9v2gV)W=UQ3p5|t=;t4AWq7+> zuLqL34zIfx*jFZ`Eb%P^_OXQ|SY8=9luzb{#s~_K;(pGA*5X1S%h~*06nRi-*==IT zy}~G(lG_W!{^^5dr&Xdd+3b53fXT#Iylanm|5WM#$E&9>_5CD+Q(m`E4-=;NfB__Z z1>IsZ4DWu0Bx}vMA3Ayp5!sQ&vxWLSZMAb`v?Z_)DtztPxny$zJcLUKF<-bnqTQFRB(&j#S-nyXaJp$bydOcFFz2dz zD=r_?iUKr4BVCertF8%i(sHfw8ee?Ot-M^qI!1;6f7r3;;^beXd{J z$cFsIL@FY-5^JbAr*W~I^ z%~3B2rW|;~{hh{pU{q$VJYRolD%8r5oBHrqRd8#K!Ge_qzK_fJ?u*n3>1BR4Esa78G=K|@(05NqO2-gp&WV!cmP1E%_d}Lv z!~*wGhwaacIUG#qO}g*9U{J7|@J(Y3Lho(!i0wc0dhPElav&;n+GCf1ZSKN z6Y0%O<#0e>X${}-H3w~KUwo_!eZvat8b?n&YzH82Va)?qV1ff*Zl*r%!Gv?!_l|Yi z9-xYNJDdKa8kev7$Lx_jh=H#qik*^xD9dRPo~P-RMQ7|To*4w1LGjkL&-l_NSpS`P zI8NM}_L<2=_U?VkeQdz`#;O3Zr_dhcpkAh9`ZooF8-_ln<~x5;?J z`|A?h);G7A_m8Xk6dL+JiF!<$d$)8d>Ws4+7y~r{Znwz|n{)DRB*==_jCbGeq?~Lg(MU#b&n4e?Cofo)cy4?Hqw9uQzRLo zU^a!9g!NgN$QVZS~q`TQ*F@8i&&Pal$l85^*Y&ob#SAD-yL zyf0pgwmk{ee;X~e-$6E`alQBD6&Oqk)$8{8QMnS|zEY&2DWOo5-$hH=$aASZVS}lh z&vO#)Yoa)Sq`FUe2I4jKzNfM7r@j#rR~PpQn7OcX@;6>j>&w%guZLGX$`^f)B5rF~ zD}Cnv66Zplo+Pk%jB{^g78mAn=v)*2Kc%nvpSigqP9W@*=+I+&L^@?Lv2 zZw@J|mW+t*+zm;$*N{#I`(RySvKp2kJ;>P{M@X>j{M?>eB&+vY_+@|AU)(7>G&8|DWvOTvB{<>;gbNXo92!;`D zIdcaOB74I{Q2k9UEr^uzQoE`ybR()^`GB{jrYEDa$73-3yS1=ajST-ShvK%r z-!r-r!X>XA0VSprd`0fBJN8K@`w2dC?g`=rQ-Sjy-=O|^Z&SdGlI{0_a0PWa!+7Vp z*Fa#9jg>??nPKY8?h?|x8Wbn~q>kIH0%$Y@kaxWdzpfo#(d+SQ4XRf7wcY1$MxZ;Y znv_STKdf^O@j`|>Y+s@wF1|oPjkLMbDaSY`#T^WLVvCl1Sxs34Sm0Dcn~kxOU0tpQZIS5y43Aj*aj2?Wc0ytsrXlsr`8>GuL1+7#DDV{YX-NEKu?&-y3|#ulJ{B|0yp zcH(YjBQqqYM-V&z(~O-8Iz5~=POsp6@a2C+nDocoxxDq2jknLB^H(%AtJXVbLH}xnD0)qhUz*5m~U@TOmmG*gC#GUhVkY z5~n?oqX&ofM=dNjf)SIf_&rXaGUfw^k7o&*M`pS(w6u@AOUI6X6Dg=6+{>#EK~NrP zC#7lFNT$>?dT8Z2T=o>uke?s4CQI=&-=M7pg%H@@w%@&)RquAp3&k^LaWhs`gC4=* zx6j9|)~rZzM99VxIXKK7nLDTqG4Hu~bBgbT4;D(bd-V4iukBWw61cvX^ZE7AD)FHj zTAY{gG3~aJizWC$O>g?owP#jO>fyB^SES1AVFQlD(gd@KkqH#4MPtZ1c25p0z9#&67786T!B5yB$)I5;?1y1!vR4SHMbIkpckal z{GIwbmY8N5u>#6%7j3?1#x!Y!c-4!v+|XpR{q6FI))XqbJ0w>8DRuO4ie{Vl^8a|~ znn^5csC2l{YVugdR~(jv@y{i}YIR%g8^m3sgM)WEw%w;c8OUwTdlor+WNAvWh@U*3yerpRoV(F` z*+v+P$8}qwCBrC^CIs#8{I-(fJ))gjH3hpcRs>owYBqkb)lwNneGQZb4(*DP&9pE5 zKUoMnl2-<$dp-5<*wiNR^zGI?s7_45H-^oQZWUBAdTp>g^`N3tOy=3$$}x?m>QF~u zk}k6aRo|{9Wa)g1hN=!gQ)m+{v1N!z@3SMz6mMmDU1bnRO*Cw6YFNnG@N%28$-~bQ zChPu&C8u)d+Nx}C!L8WuM7z?LuYVU#Aj0CP;ZT4$=O?)IJd(8FD|F+w7xWQkMs6(< zx0djV$KTNhu32?^t(cdaNq}Dyom%HJ_L5gJG{S;adwQo;t=XQvXZrDZ2;5yePF`Jv z4sxoYHz*!THMm`>IXPU;bu$eEp+E2bzI6L*ym5xB+_$?4w1wltJAmqy#qiIsJyiyN zN*~>0`2ay)fd`Mut(@f$zPT+0@SpBBhTo7J8MrXc&BIT~Ei@ah9*FVmqY*}NS*itZ zsb8D@)2Q-Ao4R@9jo8D(mp1|NUa9Q+#MX4Wxtqywi+&H+>~LDTrqMHMInn-O6+IvX zV}>t(4M^ha{R??IB5Mq!4z+FjR$7l5&p?xxG|FJ9G=(@$%Db?NBW1!1{ls|f^c9o> zF17)P0Le#sZiX&(#tYqb2OiV-rdl{;zAKy@T0Dw!xR|N&BscnxMt$WdPC7^FZFRuo zen^60gN(Io6#|`h;iSl#B%(oYgpdRS5-e{5?;goo{E{>5U08xVr`Xs=yhEL2XYk7nwPwBJ3dntqI{*p zzBdNyx4xg+SU>Z9V*Ww!NWsk1vd^uGeefx3+@F9#5 zhz$#2zo7M?8SDRSM1>ctG0DV=vlarL{P4LK2N>{*{xA=L0`P1hVO=FS=U#)`p-t`| z_4a*^_sI7_o21S9V7^?A`nj2`(+F210XQ3GEG;EG6DVl390V8sJWYoH4mHBig-veJ z@TFE}WeuAjU^7`8z*Ow2EZS^7>2NTi-}kaBr|Yy#D-PN>q%HOryj*w}UlaKw( zX)Pq&p{$%9$Z}tp1>yu*)1Ey40LRk5m8n^$KG}?W6G*6XIkE2DbQJ8*qh_+#ArtT4 zi_GySqGr@Z`ZxroD{&<+i2GkI?7Z*V^x#$V`}H^ZedkQU1{(c|D&Q{|!gL$9RCd>= z^qOwhIJt%LY6355> z==kk2FJCAwBPwdz`Sc^`IFmk#@^OFV!uW%NHUizKgaCF`TZK!7+PQEij$sj zw&pqd|@_kbnu4|ug{OQRb$ zbW@K%z4cvgeFfr6Ba+D-xbYy<5GT4FXE}O)h&O6jqLv!RF-v?wN5W+sgl-v(FEfze zR5>Kwr-Igc#m-nY#El>scLM7h#?*L751Gn|^L?kE{9d(N+}=xH$0yHQyWBK@D3@81{hn`-^qgtyDRX;$bN$U50TYh; ztxp-{s9kdULgP~T9-Dea-^ux`zCOd{fjZPkt;I)7^A7<8AwnbS)@n)Go8F&Ksw+lY zJc+gk{I;C3!(ls>RGBzPC(mQ=X7}I#Ch>4d)A(4g8w2X-lY{!BWj#OPa;YH)B7WR` z)an!SAc1YMwX7-OQ(VLO&#M?mRy`GJw|w$46o(kL-}eI-*6WjnG!gm`D%=U(8oE`X zmfisQAJ4z8?u0EE*i*JwCErdt4IR-Yc>(RnQ}Kck=Opeye^PretT&SDac1*ztjYSm|C^><#z+Ho1!|mRmU@zt=1Q{l-5mS%Eda(liUwZ9n znU_R8Y4gaOn8<H5)rFbf81(`qHY!t-wWxSn7rO+=}8RO{w+MzEnSP`n}yV zh=?p`x}hZF8nnp`vLh+`j#B4U1*CZZc!Sa*9~&p%#Oit}Iq~PH(@hR~SjgaD^bn%K zxxOzQ?CG_dKuzX!w8nkmkshH*KGdQ!7O*l}D?VgaS|+umdNjOE{Amkt(_CnReRjWio6N*sT_Y!H<_ zkBsK^@3y<`VbLa!6xP4%>fTmrFgb)o+yx+ip;Y$nhF{&~YOprqunzzz7V6+O#Jm*E zr}w~uUxeoBJKU)Sv?i$e%)idga((uHo&%|TI7*Ni^FM&n4Ng#VAa1hgfRQ=8vCRGB ziFa+(!pAWPh?xD*d7<{T+=7G(CkY^Vk9VJWsyI)G=ACpxWUN!M3RkTzKJ{?CLT6A1 zku|NNjy(8^TO_KpsSPhg&dHpe@-2kM1d2>~RzAZd0@8ppmX{>wm3MgE%Op3`zLSw;1*x2iFBrTu# zMUEeHcjd0y!r2feSzXG{1ZD=QlS=JTxvPCIC@?M>zqMMyg+ZgP&h%>GQ;F_9yGi21 z5Bu*1l_;~If1Z1pW9hfXXdA8m$NiF1F+t6q{_(D@HYizJmYjt#uhTX0+4?|m((|C%R`;qJNIo}wb)5as{oT3a z{j2lk#kFVC`+ST7@~x;1ai2#>%@`o|%beVA3G;v~$<^y;IlkLlqy#q8^OE)U zo+b?&f;X`w27pU#sOPpQ-WKY5ZuDAxEV+Doz3Vf<7AlM5N#%&SOav%$FwVn@FG>kP zF0vI@LWA5ATks8y;No7d@)vh7q>7!D4QsrxUuExf*KDU0^Yh=_#o5cn`i6{UD0&#= z*FO7#eMjUJ)?W-)8T|~*!uvb%<8Hw?Z3P>JybLij>!Z-5-xmLNEvM5*2{$1ZzSJOX zryOw9V97t-ePIck#M>Y7KHr!~$nn65_So-<9Rn-JHGNgMkEx4prJUFD&|IMal$yyCVxPnSZ12KI~TQ+x;X43uWanvA8SbeIwXAjm`R*gShiOjq({947Zs(EX3=TG7(aC z+9Ll1k$3UleZ-z7mrVBHsf-{#(F)8SUC8?^%|+h6v)xN+mz)q4VGdh%Ka^aSP(^f` z1HPx@sbytYRGJtCH6%l97 z-CA1AQA7eubJIz0mO4X*F05lTZ71gM{>R5uuP}F3V`>>0-d`1*PaJUZ)#>uz?cb)y z5(qE3Wvn0ie!Z|~$u*Zudt#051YD2qkk>yZ8C)_NiLBVL~Oy~27Y z@J+-|YfCLBxMlbi_HdJ>t8vfJ%xZZ z9o;PdCdCiGQ#+URWf>s0h)GS%@9iBPXC7LNmseiH8jnoJ+~)wsC>3&-^%j+vKwS7o zn5#iG@x3gaPWdm}lNxJ3T{#!oxjepwlBXjqc;oweSPDnOC)QobQuvpAq67z~2WUV) z-dL{l@deF`XS%NomLu&0(o^WSwMU6#F>_E8Q|4%mmX z9KtC?$$@`<_M0+XqVL8nq@_q5rYUg?%oOrhm~8fI1}Duw;07=P`?iS!buNoP9RyH_ zRQ~Dy+lqkzFg6Be5|1A>jtcMHe}1Wbzzg_`+z(9-$A8Zc6m1OTjvVGOZHN}_s1NVK z@8^tj=lz|<6UG(zmtzw4hV=li(BTeVmy;O3evn$lQ~PNU^B%84e?6J=S=djSWpb3X z+YBJj#4l{;{~^%tcmS8@HQEmdr5F6>Zx>k0EXuNvAqyMYZOzU!<PE)!k#{pN~<-LC{S8 zxNsVq(@eIXN^FXsl+UAhzqhaKzb71Nu0q=1*M*+O-LmYrqXF~I{c;+=ebZv#7|tI4 zAN{{D=zpwQepB7^xF;-0*A+!8BCr(CT6$KoCZ5gxEO5Y0Rz?o{?EcMt+MKcsHOKR0 zY&1*7Ty0j#?iEIy*d>*2TTJqGXqH>|ZRRZdI|&a(fb}@_{xlHJFJg?bBQ@`KQq`DKxL5E&od-G)1UOyK5G?ke2_>a(J68d{j1u?((M5s zCYKpdq5^NV#-qR8jLD9Qi#pE@7yPD|vn=|I zw`s1aqXky{Dl>WAaA)iv@)~Qi%jd1y`6DujV|@Nrm}vf$fgfFtx7PGwO3>Ske|vPt z8MXDWFQSEk68s5D@G6wxQz*g1_fXwnA8-k_t~GOW{+w?ZGvf4CC!q)+D6JYK6QJm` zPguT6M0*jCf4MBYtihu@!f>4HBPT!lg4_e0LnZ;_1$}?Nz|Zph&Mb*SGx=L~MkxmW zV5@Wh>GrD{xZKPIcNbiHERNczV1GrK+^CAr+^m$ZyXcvC?+-HMD`1fQ;+xtwW+oFu ziuss-Dz;5Sbk1n`b}1*vFi+;DDqzSB-C~d?)f*&EdU5ns-}!{lu}UgJMBKl^FcZzq z>Yo}sJ|j2wJ3=%y$Tzo9#BH)gMpN&X@swQo6>|PvT(+f4o=pD$(NX!Re?QAR&k}CG zi&2ZZYgwI0!t7zn7rkt>_WQ$Q-tO}F^M?|H%<#$Yzst0Aw`?ONqK`P z{EbCvQHxyiOkKT?1r%VEcfYq)Iul8gu%c^>aP7V#d*|X8v?zbdBaI&$bGkCICbBII zQSs3~0#)%yelp%v7I~$@dSQd!f~EZK;vGtTm^wxNtP4@Iowkc!;;*Jxw4a5l?=9mUzEB)^AX%%bNv7S@`{^Tb?<# zbbY}~$FD@e;+%6Ds84br;2BSWLG)BgNVY(J`8YjJ%CHw@Iv9CQ(sGTWdnxB{@o6^2JjR+;q_+@k!+{qoYtki=(A0FO-YHGFh)baaq z-Gfde>bli(dFp|H(m8 zB&TI8);%p0Z_pT^QKn6~&1*^J>9{?tPrp<7Q_T6Pb;wGvRZ3+B^p^(w3GMqyR7jl? zu3=VdkNH}U_6slc#;CT(lX48v{oLP^HorGCQg0CUe(ZEo_;z>Pq_$RpN*-JV4pDp$ z;h{@h%h%EL%1<=1w|~0u-RIP{#{HTwCEJLqU8Y5N|k$LHqfeCrPId#_Rp55+motMjwK)+k%d;Z;X7{sV4KF^BuQ6sCh{ z^_#Ux=Xn659ZCr-9Lf`8>&&$jN+yVhFY_#XVWZF}_LJ{a{k}QSP*7oSbKx+FmdNNw z5c@D19&WFq63MQSs$4mzV!m1GOJDygH5Y*4>$loYVO9Cs`Er_;=((?3`g9Dy;qioY zhXmmIec4yU81q1)qj%IJIJnGg=6}=Xm0OY>NzP}FpVRBo9Uc5(iKKVW>OGW9?D?d7 zYTPue4ut!l-B70=r(wt;8S-^p?ys z9Tax{a7j-n%&d~)9XQZO=}0|iG%7(kloi~>{w^^mg}!266kFxWO= z<(fQRvhiGiVVH5pz6KJcLpMaHnX#>Y)OQ~1;syQPy0XBz=vlupH}ZK{u8F=~p{HV< zNvL}9Yi~h&r{xWmg(&(^X3Bgc-)sxKu$ZlYyXUYY89@io``I5~Fzuz$!jrve3c&u4 zGWDPaO7D=n7_NLqV``Xjd!9Gq=2GMQ{T9tiMm4J8r#CnOt~6lE!MmKI|)+dcxu?%ZqC;|Fgt0~1MvU= zqV<PouM%!(A1*@)53AEoPpB_&evySTKMLokvd!p+(+$7 zL4WsEmBDN$_Ye};f~m;VW9)dpmy%y=B_G@{Kc#VN9!A?GVCAXaJZNNxZ~kGfP4e!q zlktC){kuH69w)nLjPzE=0xS?WQ} z=K4|6(J3*n0Mv#=*_%QdB6H{CXxq~Fc^k9BGVG+;Z}fi5q6>gHpY>cg8Q@K9x;fuH_0U_~ z0Pqv~*Pj}8TOV|_%bNkxKgmTO5NeF73eCAq++BvJS?M8loMG9Qn;Gb-V@7U2VBn6a zR>jp>=z?}=X#dZ<>U6w4v&&{yt*fTY$vr-qiFRk`2GG@^I%!Dy!(KWHmnyTeuxj2U zr$`~ftjq1$F_(v7eB0&zOc8lKG16u4&Q+KB{xM8C5Nsg*%xewSr`e{t2(#_$@acF$ z7)G~YxLmm$?XlN~T4P(Izhvg)ewW&*R0=69wRH46pntwJB%MZl#`$b7U;s%z9bwpMuvO=Yxnmm(`DABU7?x0U%M4cF~O9~%73 zpnNun8`WkFOgE6*dzh;3UIPR2Tl#&kNhLa;?HJSXQj56~6yV#cd{)9A25ChV?9pnJ z9Ag-p>8zHI=}iJ?>8-6OV21Z_ChpVv;2z6H=aI~R(|D7`=M!)n|3rU3yZ!;^zveZ> zNjZ1napbWilF^IPi!FX*->DcnrCDziCaFZ6AoeL^`mL#Vao^71p%v~NIK~lP&43Tl z&`yQ)ARWeAK>U&E<%9dqKj|MyF@cWu=rCnBaBFF+0K!Yn?9bo!1J}RLUioMU*$bKU z4b`t3;U3?_x)6umT-WDW_1lfXnyths?}@@I5v|I(a5ceA?Y0r^Jmek7)yYU|6N z0eH6^-uG#CZ2uH33QfBmbzXeE^N?x7L@%yms4h?}erf63wSZOnEiX*Po&B8JPS6zg zem`ipy{=~v<{G0+uU^(0{2x9A&lA4;(a6?*ECRH%ev+6lBrB=PDYC*nX-?nd1In|9 zNpGsqy|8!x70)h|VGrTYk?!Z#&xaQhO1V$YLQcfcDYWy1+$VciNh$MzZfUE8U`%7s zR52mFkSq_aF0xmpm>BL$CzK|Vju+SxbWCq;1yq-2&TAP(q3vWTmW(c zhyiK7Kw6+27Bg_T4=RkIEh*#`0m$vVvWJ#HAJ>2noie8zR7zmeb)?|v2?5oryvF0R zPXo@*1@>Tsp+lc29yXbpUz}|z8~#aa-ze6{Cz2EYuJx||p5TN0C;_rx)+37;{ywe-4m(V_Sa;L!TnsNIc99;zM;&kM1v%$W4 zO!xjhBfO0RA#YW#9$~>hZ?XFPTK%dgp>NMhK+v4og9prkr_9xdEX}7HXSbKDW{Ywr zJ9-$gtk^MZ+5{Oq)4q;zgmE+SPIqdAky4c!odc|@F0$a^(0?l0g#-mB8g!>qS2j7U z-^2O%aI@?D`n++80g~Q?B$3%uDIdwGw6*sI>onMM^RKS3o?N-n3NOJa<*S{wA|-9` z*kkdLAdXf66*mfwEwTJ0V4f6ww0L1xWm}STco|E-zI?Q^Ulw`Op3rKmQ`YXGEdO)( zeePO+6L*eI4TakZ$f&N|*E^0!@4JuorFP)}&GP-DBM+v^fuXW#)g-b`fmHv`_pBXE z7o2VT*(tegPI_-z(ms-{up+spl1!c4uuK2`9(-I)DEgY_iJj=x8)!k_yB7BMd%M6B>UMrjVV6Od!#%=7bqLf@bA7Q8 zrOeas_G!h!D0t|vBw8-}Js58T9{3n?Di4}FQ!mhS9I$>xm%l8Na zKyN?%sJTY>9~=>v#ihAKhe7U0hs@Hn-}jX0ukYdGsus+JRppZ#npznwO&^%JoVSZX zor{N%`oG09xzDZs%9R8GMq}W%NctZ4-8U-ba(f{dBq~I!7GmMrl8N8*qxlC>7DNF~ z%!2N?<*uMEO4s0T(No@Xq4Rr@Aq(MwVpg|qeNm^Es+KYMM&%v^5b1r|TF5;R@_V-w zLy=7?7{C~VP8FQ-(s`HUTDzU<*RO*GB@kNw^0hvu6u55 z(4TK%n4QtN7Y~YCkhz@wp*IPNYhOHqQ(USlKiAha>zF+V_y-ciKCNk;#(sjQ zJ_^buOs}WXxsbkU-yilRxE+d9Xvi>@F=1oyzL(uW0>lLFyqQXoRWBaY^wE7nToSSV zG*Jkt?AQy#HuSh!b&{Sg)DlbrJuZYDx>wUZ--dv?;I8Q zy4S|IqwORNARGdHd6GPhjhpj{+M)(}Tha;kfPHYjLg_w|_NdDt zO~IPw&AX1!bzXl|#HGXzMiJkyN#DR6Mf&t6Lz3o!^&_EtO-dDGbm5`$L%&Em31~Jj zuP$E+f&{&%V0{%2$#nRrQIPO)K+d0JQ2|5>Yb+|FJ-*^jyS|Um?F0jGfJ7nAB|LRJ zt5`{E1|M-aTR!_s=OPAC6W&Vw+gK47QPkZ!ne`GE_QQnGpLQ>P?H?I)LoBpXa$fyxKbpcZVMK z6(<(KEXbELYb}pZG$1aY6$@h$&`wd^~J`d%OF{P<|FY;SIiCOPm&cM*^7rN4%E1l}# zhS!IS|AGl!lYnZ|Ot;&2xqaVz;9(YL;VPj|ud+t+l!yA#{j%z#)8?-F4w3JQ{YA-P1eYr z#bbNo{xipHGu+>t-*Ne7(! zL`NISwD?p{^&r?n!Z%USaj;v~bn6vK;}_bJ>vbdlho&>zQdUW#@Y9@oWad&35Sa%- zx#=ayAR?2DK7DWMbgxzaP*sWwNoHikj&J`FbT$QaD~hxY>$yDacU8olec{fSNKRS) ze&3sT^{&OJrnd?O!fWrk5q7Jn8+_a88=RM0+Ps{NUIBAO-0jsL`|1mDUZA@;f7~ph zCz?cMJEiXBtyne$@g8yeWbSG`%;+gj+f@aXQeV2HDN+MwdO2^bzpSDgDWaH<~WM`MZ4%>0>}I zbK>1RskCT2>DjX%2k+Yl-VNA~1lcm}iI2MW;YZ3+aq&LVj$ddoq6(5=Hi2v;?&!4r zO`=ipVBA6KCS{m<^*cp?Moa^CR~$Y~SqhiBWFSl^PnImhwEQS+9JBdCFQPH<`hYo< zP}VCC6MDCwQATszBWcXSYb2ZDsvTcvn}D)HCm!|d@!I3vMgmV&2R1c}4_U0w1^Gcy zKzV#NKV0^V#v9zp`pX1M_vk~)+_pWUI|LV6KcZy6C-a+`iOECyPA684MS7*5+l6*% zQMIY-UU<74vsd}Ks$nWP&Jlep@|oa>(gk=uE7H+~Sc0eBvQ#F>nKv}*%nfpRj2yr7 zM_Z-HtBdZMj;nLIRzHW_m*+R&bw#kk|L0PmR0)s{coFJPmxmYSNsNX5IH;KO$Tv-Vm{Ha_o^ub%|8{9|G0Ro2k6HBxCJ@&U7%18AQZpxSQyjJ+y=5xPx zVp0BXw^tdIqiUcj=Y|GcBsWh1s#}`f$3($zKa+*^E_|1a*Q4&bL05^C+FX4-LxgOML2;~a_C+`fT? z1&${c!a%??mdBZUy&l21@p$p-JU;d`VA_VzT8vTI=Fd9n=bg#U%VL|=%T+(G@qE9+ z2AC@6%c(LHg(;Hj>Xs5GTxcjjU`|IV+F~7lPbBliCmR@tFJb@H)d~pGS)VUD)N1vZ zIEU)(yWv4J(92Lydp0Rk9j3DKP9`DX1%xzk>xSC2`1pkHCaDS(o3R}JM&-fYAvM3+ z$i+T%_sEsi!|Lt^wnpFSz(Q_zuJM^b#3LqL4xkfG+tNBTMgin3Kt8b(`(r8ndw#%! zB1t`^=lf>GGe+h71W$%-)PA^+$+^kS*@GArUaTqYpik;a##K>XG6@5>1b7_Xf|Vm8 zHd)h@^^#5(QHewz^o5P3-)oQ;44K^^=E7`dy7_~P`I|K5E&@fo56F$ zhJpa9iTTm%x5%JEzl0-iWm|vG1;NFOy0g(|fI>*G!}dhy&15aiU(b}rIhG`p=As?4 z$V)HSyArc`J4A{yG|xS$J)JT2e0;R|tq@+6s-_m+833Ikyu#7AxWC^bfFNrevrI&L zit^P@qt;X}ko3~W9u&-{>TQp?$j$R>B??FV5=_QA3M`%E0JZcui31L*Z(C={;_fTU z)HcTeUBRKP1V`d^Pxb<|pj11aw30FZ8(^6GmvyH_Z(Y zpX)Gjd{KWM;ruG7d=uf>aDJ_0w;qPKB?EYz^7E_wLo%sQLaW6uY^E$^GXyDTQIvOc z8h}SD(6dd3a3s->6OKN#8yINFjMk%YWG2<##Y>=#GY!i3pioWQ!$#3DJ z1xoxn2g2bC6o^*Na0VwkOpoNu0tKk18Q5aB0oY$#eH~vmjHT`Pazk9d}kN2N@Ic2cIONAWA)D3Far?j+44+pd*SL%8vAJME`jG$Yo`14xKHy?Lz z`+Nx^d2~97oPKoXx>7{LH&Nh0D+u2uC&02#OZMc<&_An18>f9wU15zXyL6SR-U_KMtI(g$1MVlZPHJ5=ST zCGEAO*vRPEHk?->eDlIZk_8ThVJ18GRCP-Ify{P7f=KpUm|t2*NQ4?j)Gy(Q-ISt; ztm1#2_1irqbRg_M$~x#FJTwjI2JEgr)or|f>IZYf9FbqAsMSp5;7A|!!PpEKCOewz z&qs7}{~OLj;99wY*3t6qFM@>~7JRYW)5nP9gIHgkR~oC|$RRE&dkdadGIfjM>ATR@ z1V>gnVMFEu6O^i)6KHyfOSlwnlI*9LiTfT3M`ufDxYNPzC{~E@gYir5 zLEfL4FpY|SK4oA2EllDKKRr16v_6Yl3U``=4cS-o$(cF9z&3~-C#@`w07vqrU0Jg~XTh4o_(|2dDE7iYEmGed_cNh452(B8Eq%>mLd~lK%e<2@9b^L-kqx#Qaxl6*#+E8M&HhoZrXhHh*&Yl_ALglh=m1RJQxaOa6?n4vhhg7{0|qRr8Q>qfO00Yzd>_3%^j%$BO_QU zwJ7d>=OyNFhi^(!@zXOlol`@>d;xNReKlpcE9an}`B3fiQC`j23@A=@+pos=59od% zu-8$TNV{gI9K~zrLCo12jyNl54##j%&;X6U=hTFH5&zi(Rpbcw_kR{1`Pq&sQuz4f7GPp2|tG--;a1G_K})oe`k^c(C9FzleyGKAwu6eB<(@K z?Y9lv?H>sb^eBn^FrIVd zVwOQ(+z#E`Oe*n*R@=)yON55aU5Am>DhTKC2$bOsN^=&5m)YPzD%KOjp_6tsdWd5!^*aYvkw1QbJs2N09 z=rFH$3*x(BUJqUAsN}mLQLna#+iL%MD>60x61mr{Oq;LVDwe-r28xj{u3M{ki7y2; zd>V_An>UQY8K5#a@mX#8mM1;Z?oeI-#7@>Inpna=`VPemfBz(MF_xFpBM`CCwd{x} zL`l(jvy9nI>w4@E^iX?WIOe7zT7VR%2=%ybUq*aG5$KD$gC(mP@yR$D8s<(ccsBc5it$GI86&8Ee16M)(j9@%xdplRk}>v`q|oc&7wcTs@CvACTzzyNzvL0D@#L#zo3OANsS9VqDZyu$-MAiMcrVH~F1dz>Q3f#*f~FbPqVC$9@ueLaoY<~zqsZ^L}CCi(2Q*ttBRt;QXB)HwWdUlrdG?-i#~XA9uM zM5Pgv1Abb@^ggS5{dc_65IjG!Z?&(}{=NXC2?OlJ&!b8-5XpY+-9H-H2W{C2j^@H$ zyka4zb$wdva-+aZ4kF`CmG5c;lN>8tGIc2`-y4a%Mhra&irPH6s*K`xK>)W!F zD`+?iz^J#!UZ-5I?b0u&-T?F>eQU6x(yjTCajWUIh@$Iizi0Qr?ENvC7R}4p#=L~` zMj-Ph+C=vaJO_3J{nt<9lq7z?1?FQl>OWtCJlz zd;3PE75-E;0+NS77R!XBthIc-j)v~`)D;C046BNt(wOKNt7c5^%#S-|$I~Hb2lc3=8o?A`4Ax z0LG9oCQKx7a5k?fzD%m{nC7!-BH)m-; zs@L~Il8}H}3Bx5xCY_DL9wFh&_NJCWw}#rm=Dws3cVd*G)Qt|`y`5itJNrx)R-@p( zzr;N~0kqeg&Rz`hc)CSH(_r_Z_s=toP|5pPP9`iBMM7h!2lbvlc6>aXugvuWYg`~N zZiv6FLzhe$-yfWcz2`YQ1mE%--hXU4>Tmvn;iy0!zApNiXsTas+z7mlE-Abt#eitd z>N>ek0FUpnn|R*?`4a52y}4T?p9iE#gMRd6!yLR>PP32Xea!M_u^Jzqq_mC2!#-@A z?CZ}?nQR3uVI((!Ycn3iyHOs8A_Pusu`l*U4~$fSBYdM!+pLk16Hm09$boYF}vs zAeWu>X?0Nt^J#Y;q9<%YpW>nT6Efi$mn?s+Kj!(U&ni`s`fQ+FM44{fp}>#ddzGPs zOC5}lN2ERF4bDi`#;(3gzn*e7&n;UHMC{O7)BQvuhSijCdt9dG#&m?QzCF(?aw8gB2wnS`e`i z^7s_~D5twW0`>ujZAONv?o*C--qbuyPe0GPQQ9s%nhV>x*+<0^hU;%xf+HnAmmiuj zDlYHHsj7qxl~T8nfutu54^AeR!QfA*u&fUhUm5RtH}@nc?gf#4S^5Bv0eqVU?N?3S zRUaGntyS0c{(-98EsUvc$%i+vO;vQa3`t<@L3~9`FPSn(82J~EmR6*5M+4Vi{HD2k zg``0ECQXibT@5=4i)Z_u?2ml0iwEJE5yyED{f5jl z{ayDRPF&umL))h+1?#S-ap3li-2VRE9PX#}z7Qz@I!fERp6qy3jKI+WKsiGIVI+sj z0*hzcr($P21#knnnm*jBCv5whfX1r%n%5^#P9Vg(KkVbLw5C4m&^c_8EJ`5w-tyLi zC{JfVQ~xbz`(a{_BHuf8+l)4(_aM%{Irn`vDt>=(@>Uv?msmk%{}4#^E?Bp=A0HW! z#h*LI{rla2FDay>m%J&bpgTWc!K*4NJY_)c?O&}WTfy0oPPI8q-3iGEk?&J>@z7uG z=n3-*G~CepsRq|rQ|xED!lZ=Vi%WNUZlqO0vN=};@{_+>|J7K0%jvcDe1N%84Zq_R zC^s2xMspCp(mpcY3>N}GebIAFkb6LU^S+12iI!pV@R#1eCnWhL)KKr-YUZI*+SQ$+ zM!IdSuRmQ2zn2yD!(NU|Q2apc&?--~6Y|&JIX#TO<9cU|Ae3U{D((d;H7ZBTGiqb> z<@;fJJUyV#3GtojQli|C(16G2!w4nWqx&}0Z`gN=;Y9?8h>qdOR#zPSPE@<^G(!LU z2K<))nn32=R{%$KGeY*Anp7toPwUew$>W~fg5UShlh?Z=H~hI5AJF%HtnuJ%=VfAq zIpa9(TZnL{_!M8Seh8)QwK@~l=O_ev7$wfgPM;jl8E13>-ojx!rX1KxIB;U@$pHYS zdKDrsUu%L#NiIKc-=zVc7bz(FzxS)NXZj%0&vm)grz_m2*=Hh@6Y>xkuvmQNLkUw1-9T+=VTqalGFLG-fAHz_SRrt*J-V>cl-3 z_Xn-bM{XGHnB_=_WejDTanCBLwH@)#S(=y|`;>9?T|^Uieth^MhCptH5UyZZ>+@%g6+cW8_;yEMuNrsd`sNL(z?M)8@&~yT3fN zbqyP9btI@Ku$|Rc<`%%Tz|k0=IqbPQ>9!BC)#fpGf27Cb$EZJA3As}VoR$_>`gl4e z@6)jon>3Q^1qc&GexJh-^%6_1KMff`vp8%lp{t0vSqKK8Mfi z=L*xo>SXwTdo+gXZf2+jZSBS2&fVW8E&Y{QICsHOCi(M*N~3k0YYOGW>PX77;--@t znthP-O)2Lmi*87ab46e0%U_y82?iHyZ@?p#H=@NrdF#zu)HyB=x*v4X*D>Ems4Gef zKmqK((f4(J#@jLM`Jk-n?}WG&3EJ!T1POpGKERbFx2q-$W=SwW+a4%E0@WNp?#9Sd?~+IX*;JFRCA zKGsMU#jcmM=L>}Wh8m_@{DxD_7@;Kng>4m`*a)|kyZH=Ec5b?Tr(gZudvDGKuSs07 zWmiC&Uh49OUAQj(E=Y2Ap(GSv77c9l6mJzBztb^)8-M^BJLF-x0`sN5zLAdQ7 z!~;oezvLdNX0ZX-e8c4c?dtHT{KpH_ORIYRlpRhZk|%XgB>j!%hXpt(YL&jwhTYfe z>XQlSGX!i6`w8x0cmp9Gf7{SIor(OyMvqJ5F@~zKzq5E71&j5*QC%21UH&-Ywb~Qk zy1iSNXa!`vY5bn46DrKlE@AKc70u>$o$T)|hL6uu%X4&yXiaY1`=j%`+h4Pzh$17o zGvdwX>);4hTLFg;ReI%;np(H$RuMr7VGw4wPr*hD?KPl_xq zo;B*?O*Rg`pqkPb$_XYz_=bT=X5W1gx(=82Lc!Wzu&J7OpRTht7CAX(d8R!3 z!G{;ZqMMn&$KA*Cor}m+3;dUJUd$uencr(qb0#1LStv)Csn>qdgRThnhvRE-&~;!- z67#}Ve8I27S$)fR3Lu4%^=JEf^-pIvK%t6 z1*^QH^HhK8pgv>MXMYz?>vwQ9AseOYs$&)qZHXw&LFlFgg(CZ05rF~P>hXACuXXTc z?nFk+1$eUL6zQJVD9vf{UM5->orkCB_wk8-WQqHBb3w@j zcX+qjBOBA#njEYTdc|uYv0!%O3D*6F)`2^nM#J^-68osNz7&ccL)G~H?;^MFkbNc4 z#M`bij_qlYh-OaruzVLcFmV7JB8%+n-faG*RghX_L91+5Z<^RsG~ zWds*dlStlaCG_KZ&QMRc6C8u5^s)2uDL36lK$wqi&Y8^zVrc--Orxn zHI;pnSEpydpl{IJFAL)Bd+L4E1<7^8IuAeNMWA~tJWJ;lSS3bzC*p;=jDI%L*u*GT zz7e6O{pqKVLR4=G{j?&3Oml@sJVSmN5PcjTVgMzXvd>$?u&g>p`N!q8eI?DsbDC&C zBsHfRTY7{dwRqK}7uWsXJw*MU*8t42-|VY#8LXwcj~MpflM=!l2~I+B!|XXLeC^Q% zTUZ~V<*WUb1XQ&6Y3=o^-n^Oqajrhgn>lEj#WMagM?uU^N2BWOSWX&34bbzEeJ~X( zpa2Qz-1#lW@cFCdqIrbG0rN-0=$UpC_&vFyfi#~5-dLE6g*>3S)Y1`W)=#jbD z!BIB(`R)8rRfLfEe6_dZSM^*~HtQh=YA%J2EP zy2`tIs(GXo0BC?)!r_v@xb}V8^B(uRKb@d*HN4NOuD^XL?Gs#GsWP8Vf1|dKb�x zR)u>j^c2ko7d=@wFq{goKUV2}Dwn|;?{h0(b<(&WroN5dZ~*vr`#wA1?Ca}CwLa|- zPzDL91PnX@6I2pPV~ffTVv*Cc|E>2R<@lCrG%v>5Tgzkz`=N}5I!D=O0)CM}eYT|K z_q)l*>w+H{{+@A~K0*r7T#2b}DF%il1*V+VTYM#Q*2nMP6^nLWx3Cmgr#OFvDk^|? z3sWm+Ek9KbEu!%sptV8$iD11}-cxLB?xHdJo=P|$&i-G7JjSsc`ft*fGMfss9waFI zdib8qS~vZdJnz#BfjGy^SS%!A`Ptv@Qtjt6n<_p`T%{#J$P3d8x_Tt9 zW@m&7VpIpPO$4OubbpHDndG@lJNWVeZdU4u7L`Lcb*_HqovES8$xxu&`3ySuSC=L8>|PapA@X63%MH=E}@EsumZ!-3Hl*SBYIS7x7qkO61y zL7qw_gW#6<4#tg_PJgX?FrJz2sOu#HeBnG)>kqBuwA{jv8!+5I^imK<`M`YWu-x~# zpt|gT&!QT$Q{8N9mRzX}&ahQFQpJ11FFE_YF9PpC#9e^U)|8Lp@k+of1L-Mc0|*(` zpx^pHz@NeJ48Pr4Mx(JEGT(g|6YfM9KL5QL=@go;EYk5Le02_ba@!lW;(SZzM6k=6 zlp9A~r)BiXv!3VAWA-fSe!;eTGS3$z9{lN68)W$qzL(tax-fa!)W-Zde?D>{xj8@0 zkp)PrQ)A>3tA%}bkWtKnGJ%}9?C1)5TDIGl zi@o*>le1@Um*ZJ&+%K}YofIS}rRMG+vm<_i0~Qhfg1OH}3JB-baFlR@Q^*08FXNKl ze;eCQi0QG9M*~#^1&8R$ofq`?yjiJ0>A@kv5cre(6#=%6L zeHxdXAhj!v?DN7S0NR%>2Ax&U&t-oGzFV{F`SbP>yTUgcKp%7td+|wUMPI0ncg>x& zV!oq;QF_LYqvY^I;aS&%ifLru3aw{QX-o(&A6CIf6P)EQ-wg17E&MpkPz}4wuvnj7 zw8|}+X(CIdG$fHZ$du&tBYD`J`tV-Vm=7IttNV%VI3p#G-xI=yHCX%Bm-J?1!`HZeG^ zU3<#`32w|L3h67)f&Z!dagiPE3lIT~ZGr@t(XkBDgr9qiLy3sz!j z4g6HuFNp}=UKKAlf-$|k<8Y0{sbEi!#=0mw6H}b**uJCX18}w7hDK!W?T@$|**Y0| zG_M^apDjul623W8w`W6eaQv%tkYiiEScN-1$O$rFS=>Wf8rA1KpmmtSNTs1a4=WpSIf%KbUXEW@nQIL!VUP8udtp z9g21Co5N45fp5d%@HoFiWOBjwO3a-q`Bu+%;gCZ|qoyy(4^87JxNm8f2>I=f+0P3s z?9cn!t^Ste~r+r}JYyX1<;5qJN*GgwRaQyY0 z@9eK!{4bso1rqC;!jqF8pZ1%JN^Z6JNBR)j!|FcwgJoAvY$YIHuD1(_Sm)mTZjU?N z*FOEq;&vlQzOxuaL{&0&BbBg!@!%l;i1Y9U4(k z>4T#^`8SLXx?iYW(4iQ=S+kAwFC+}f>>nkBX((HKxl8(E#^757NWfzk-{oQ}#&0VUWzr+hw;;XNLdHQ+T zc}9zJ`|G?9d{T3?ET_(=a1RXMXZb+PIuL_Z!}XXtUM~IUwi+-%Mta z16exhaHjX^>vlcrdp-p&3uAU$;fonjxv2O8x+Z&-5S)I6#SDLcERGasH2)pNcldBo z^uT85IV7@#n@`0g{c-nsL-ayNyL(jAKv9Km+3R`qpHECnN^LZ%jxes+s2%OBJhVmC zIaT%yxrH5h1+xPTWO!Y)4`hD$9s=_>H@13odh^XpX71sJUmxpJjvD72055&17jN~^ zSC1IbzTQr}HXcICKO5lnoZymWrnN880Lb0)Jev>$Fd9R*;rlm-B@@Kmej71wmmU#p zT#9=ax7b3^_4F6N13Jw$MiF|%6mnYh5 zX3{&~tL)Wbhb5+Ym~SZ;`eAazR`ZP@ZD)Uz+p0%&lo^o!8(-CWK~ z|9dvK&^YOd*MvD{JdwR74P!J`ZJ>#|5^iui8%TzW9mYDkILf(wxk8_Fl2qz9U?-oN z7C8rKCz54N`}27Djr@_>t!Kn`inXw@<9%W8ZweAG`>d#LR{H(@nQzp=KlLYt2l!ShjZM*pAC5Ws#!Yo zH*bWgSaCWrAR#o3`6*;6I}|R@&Ad^TRez2|B_X&4L(R>^qk=q}+b8Php@mYf?Ai?R z22UlGbSX|7(anZ+>oKA$J8!?X2Y`kggs z&<_t1{$-AH((>eLNRDKA#MWB2 z2fc?>wfVZukg5Y)NyriilHHwEqj znM*ol(EjERJ1*v}<163GceiE{ z8@|)uiM;(}Ca|h+G(*QrR>4mDM@vVbX2ZZwHd-ar+r6Ks(^eE(XgZfa(Ys^2-$bmY zsXVFki5Sv74<;KL-jh;(liw7+GCE+;_eOp0>*;Fq>5cFXuR~-sD_88fAo!vXw!((G z{oB6->;XI{Ef`uw+&|fPYxm$#-#@YV``Mw?=ulPz_)3r|s$7x&dg?EV6U;oOKHthj zE($uGmI2U9Wno+S3%Jz|l(YQeTC0#Y|%buRJ zAwzI3urA*Tbl9K2fyKjW?&7H}lv&C1^y?votZRW>$h+9tvv*YEUo4Ds8%m$>$z&%o zX@?^-t5nit_ESSWs10QO?3fqXIGxp;Q9$^jTo$O1O%i_MIam2Kb3U1YvQSfM`VwVm zbzLs}3?B5<6o))HoSItT$Zdim4{;9G4v`xZ>{LEP{k+ZE(eX5_A@1pue*=1iWzKR@ zOg@rtdQN>BxJtTeBaQ$X#=ikC&0E?Far&N3~Q@xN4&?MwOJ(W%yW-4oPO6r~*WiXEBXct|7 z#1hsM0YtcQ@o4FYwI#zG~C!OVa}gNAPArQTA#j`r*Kdk$B?(cyo$meaY0McpmL;q zzrA2e-s_w`H8hlrm*d=gq0G98@;jbq@%GZ8I+%gGyYly;bGRvoH*$o{HVO(`eJ+wD zzV7)a#yuwfwp#B9paFq`g^foxG2yM*9*~MH9Cq=KGze1RRm<$u6kYFY#md7L(3qYN zq5HnE!5SU|j%L*D766=iMD0m}WAZe`Je<|hCSkvS-W0U=!9nTb!3-{Q`#MEjEA3it z$|;|fRl8^IP5xdlQE~TX9!hpAOJ9pI)c!8|~DKNW&bnd? zuyb8JNL#3ft3SeP`x!Y#7VlADXm}EE?l95x-tgvRwc-GAKX$=VF8B6+l(eF;QNclO zc6VkjO2)y86%K6YYbT>BUK}g6Bll#iNJe>KUVe+Co{D|@{@kFT+P>zJ9Y2dbvmMEx zzwdV6a_-JKYn?svJuDIG@A00%jrerT*25=|JAV(Z-TkCa?~g5ipX4adI$BuCijBW+ zSEfbD{-}xHQ%J$S{A@v^n(XOzmt*&M?rLN_VIbWi0|np2Vx@s82GT4-qPp+ zeoKCd6aHaP8D#g>;k9qMRWFg<_a4qi!8=zWHdBqZ4;9b2{>pa?r z%ssQ0MlnUOe4d4(3NKN4sS5Nccip<|g*N4EO83Zm(nkP7n^omF%Yy&A{2+raS<+ue zXetbAWQ3{_Tt40RtY2fzi+$a3X5n$Zo#y@*_R^c`-tW^Jn#9vx`C32na`~}5nHQxG zGfoyIMeDGne~G!_nv+LI#Dun1`Qdu|c`wM+v#%Dg>8sK6;~1kSHeYCAKP5B~%hBT= zmk;T%crX;?k>X9>XafeR))kUIZC~j-MH=+=`HItgO?Rd=xD%QF!qa9NBu$G|M*66UBb|6Dgr(0dvOMZ(*VtiQeBJ~UJh zF&wsHTjk}m^C!9FQaHCevenK65uO+r1yB1MBYXaMvr+!qGJwkZ*NLN<@a8_qVfT&^ zH)x~qPao+@vz)5TV#dmFnf+&It-^c#zA=cEMWLzyaDU?a} zlgw@0*sy>fZ`?VS-16GI5>nfgJu|3+zRX|#EI07o64i0$L>z&>uF<@-L$R0-lkKjA zf|fews9xxpb@#k$ulHwc8G1M+pXkPOybD`)JZ^mX2_?mJq}1>vJ{M&H`HW*RJMB9? z>hZWn>+>Fa6sCYH1m*Z4PDr8HeHnp?uvWm}R-+X)>mS(zNzO?9@6JEh#3A+U^(4S%Vj?bWfu#t*Jw&^fchGnSy~bi{y$hBjKCeIO9v;`#=!6&mGj{N<<7P?g z0^^ZblOnzDmjk2)WsdN`>+G@ko^OVT|DdF}k7=5?$2V2`#)6Cnefz9o16O2MI$GxqtC?|G<13v%VXbvd{mL~L#Mj1IqAsA}Q#-Opms z7XWR?YdlUDe*Fy#M^8Phjo~DhERSk*FEjIDs5tBrCwnpc{#tN=q4Mu`61>8CZ82?g zG{TEIcyF|h!JtSq{))101X1PZPT#f%J!Q8S6roSEpBbVVGt1;ivXMwG4*dP#j}^=T zj4E1Mynw=VuUq7ZuhaN>kR|U}$zdAz-K_#w0Q?QB1HEsd3%dLce})P9omu6^@O7J4 z;e+NJ#}@-ziLWaj9L3=-m9Jx^5Le5|2nH7AzrzmNE#5q)TWChm7{epRi0pR$2SQ)*j!OHv&L3VqmL143*{-G~-ggG#ed=dCZ zMTz7yt@ta7RL2k-5XsR8=TB0^a`;>8Y~_98na=pHcmIYVotGWf^?VPs4Q~$>NG8wvyLUaZRs9nRgclhi2n9k!s}P-U8>MbaK1}NP{V`ppzlo{H z#rLY4l}D(ZlELisX=FU5wXai2)U)@%vw!)~$v#$GepyLAs_<7UXrr$fGnHuXrN*XJ zF7?Cms-e8#UG@6y%lCSeh)Dz&Rk+Fp=%vleagTn;S6_X!^~^?21Pk5XdWp08O&T3> zD$7vQ&u`<`cMq4f5%ucvl+)-&+b;H{ovpa&i}Oc#wy(5A*&DBwJ>tB9n8Dc7FXZ`N zW@xOg%$f#XmAorQzQsP}40iBEYTcS39T|6UWTmI1K87jj+~-O+;B#;%_wxxuJhj-z z)4O$q;xy&92T## zsL9bmskHc(bBf-<=e`|I1sZh>#cM~`b+X7Bd^Eq>I)?;HbOw%TTl&*^@6c2I3N3T5V_+soE2E4uLld48_PLny;8=<;gAb{d?V-sdPB#O=oGb~T(|>ievECkbzY zKj2N)juajs)`Ssd&_|j=ui6p`K5)*ZN&{)?=da94m$%jm8Hv5H}37D**TmF>`8z@TP-4F?pW)M&r|-k zz5*k|^QSs@`Fw$0^TvYRQ<45HKltjI_T$llL1zNy$oguP;KfhpmFC$5s_*A^JGYG2 zbm0;Bk!d@9f>e%DC(D}i7ic}w?k)4>}Q(^h{ z>G+kgm#qHWKd*x&^RP0|cBzSS&TcwUP8g`TDs3#R`{w_bUQ~aUYIF~V5{Dx9&oBh- z^w8Q{wujxK8TgrgDCP&U?egOjDby5u^M*+N02|is1$K$w9*)%AxxU)p<8iy%gF2zf zQ~hM&k@*474QQ1A92okc17!dbiq(G6P&iD~>8nEe1ZmuoUpKtN-EL7letrPirwN)( zx{p&%ewQymaq0>AX)ZyXRIgwLoZ1GXecs8XOGxw!Q4lOziPCc0Hqcmh~LauIdCR+C!A*kZN|>Orr+ z-IVf?{n%lbo%xyoo61kG_wnpEtXo7#stK@^(J6L$d2^fS;ZI6rSnkQ{J{v&Gl~h46 zU7$DUE|~u>pR;b>U59JQLOWfYp=e52E!APF?x7aD{s6*QTpg>JvalQV8fy4*BUh?F zHN~7A)!dBVqtaj-vNjApj~MzkR5XSyy%rVIpyDUoe8dR(YaZiDxVO5QvyE^=+LvMa z^-`@wp08=~G6LWfXRcmLE6$SSG(JSUJgD6SKZ~mP48e%0dfCP4P;f%g) z!%7mg_gp*+Z94~98oW`yg0Qv^gpxYSRpPG>;;(mj6eZ^DR%^mB6Mjgg`?g$Ro*Jj+ zoLN6FS3cW(%__O>uaK@!FW+G*-+GXSd%rKUOOACPgx9H!dqhDW)X<@1fRsT~?`sui!uQCrw6_bl$Qrb{%WPGz&f{B0^X5NS zQHj-e%E@6hV1kv=H65P602?&MQ0FEhvzq_Xn@04jPC90D{4(02*J4Ii2<- zIyrGS+QNJk$sP4l4+>QOf$}CMAlhjUc^DO%!Ux3#Z2MeSJO^77SxehiCvJNqPk=f& z2E_xw;+4EL`|fozIU#SDzDn(Xf6tv`C;Geku6Q3f2%@2yo4(jfR(cQn^{GFNjA)$6 zLA2NRG}7>ktNwipHj(H?VIQB@`FF^Ykn^TDOvk?3>lAt0a7~X;RlFPw@mBEhMEi9) zeJNXPU#0t6AxSN+$GLWCxDSr#T&{(qulvA&BlJlD25WG-z1%xLKj!a%W*A?-tZv!k z*#q)oNB`~zd;(CgfNU3O9QP3S1Badi+1#|Pldd!Ek2TWaIM9;#6MF7Nq!facj*Cx8 z5_)&OS8^ zM=w0Cr_ztKYCbD!E4xzxu#qbee4|#Z@VPzT=$LX4*B+TeS<091pud{?9>$iBee`%Q zLlIccA5{Jl0+EB8Av%JBLE*d^4*p8-FPe5s?rPOOFndZ8+L(P3OVp^!G#~iO?3@9b zzJ0z0&0TuP`aOp`U%6~we_JA1&c{bfJZd5}%^hIiJ11p^tKCs@`J78=6cPhJj$e z76PO<+6tcxm-dzhlh|CXy$DZ3PpLbDv0TmQqo-0N|IpybL%|7rhG=gF9UDth0Duq_ zv3v0|+PzzC-ub_Q7WukiE`Z?u)WEGS>K>^NIIC4{s&O@$e$dAG|gw1NJ#eHP62jbJSp`lcl?>TucG7mV~A3;Irb(p9~ z@7MH|1NjQd{yyvY7eKTDXj$760j1w8HSyxN+b2FI;Rix9kEZ(aJ@T`U6Dhhw*i&A0 z<8ENp6>^JNDFnkj%37xMtGhBrwrBUL!Ocp_3b z=$-(A2@*CzZE=LO7LwM9Rxa_Is|>`sax)X8db!_|L2iG9-{hdlVfXm5U?CWJM`Dnd zA3O#nbZ%5A^A5jmFm?Y!tVDJrE*;+}++ zIM5J+Gg4j`C}I!hxrHuph>6q|IER|1KZ-HK0NeK(ky(w@3HDy;>-&9&kw}!%CNVka7`;R z=O7rOOzK(Z(8Gf>Ry@{5EWFQPR>Ci(yIZ$Uf+=@{F2;&AdGk z9UTdaXjuQ=g!Zs{h-t3I_Z9{$pU8J@V?)4+fa#8s7Lo}R;a>e%es<)_K$h)T&-Tagqq_bXBERr&lL1? zP}4h_&3Cv5smi350oo> zhL0zWj*{Pv!T^dhh{)1V+V7QtGvnVRxrKRyHxE0`WEBfvFU#CX?32{yRjLKwP*SXQ zD&_qK_KR2x08Air?n$T)Ys4Y%!1 zG-|PwnZ0w!YCBdFK z7eDTC^Ne*{4t}AC&-jff_ioXXyX*Pg6_JR;c zr1Za>Uo@bBmP1*VPh_S&AoZ}C*bwLdS}V4oH;|Nw+=U1_T30- z-!#Bz`#BZj-FbV(0Uu@U>BvK50E3v<%`ezr%Ttfc&Gn(+MWNt}$=R3P-^$Ey{?iY+ zw*Pi04+2;|_>0JJx^vq<3K1D#X%}`s0y4k}$#W@z47aZ%LIY?ba&s2V)uuY6AFPR@ z^peQiZ6-gHfW=Ep&eM}VlzT)iqFw=ISte+`4uO{(i<0oihr-YF(O6qP?GB7|;2DKE ze104tnfuwuBhF5Am;-NOd63UNi{sbF#mUl=-T$rv0sAL7F0=cVkZw65ZxdgbXx1^? zEgwW{L?|JSalz4GH?g1{BUFY?#IyW53?dJ${{0w*IQFP`j>Re@^DkkFPpVq*e{9+G z>l~^*7&$zz%l>%%_w}%vRxoS()na;*>t6dqfVS&C+AM8992Ba46Moxwh_7FX~5y!MOmP1uuB$m&j%k~in#W_#&FpZtBZ^2Otn z#6tm^*pMvk&suI7=kS+IRFJ3aRSmJ+3t&=l`eWp~TH85`k!tk`_-jc4mY zpkEU`@An9@xCZV0ii!}dhabJ2%BU-wZLFJi)d^qlzNaA;!G{^Dx_tUWP?XtiA+voMnJ(!Pq4avuI zWIYR$t9-QKTN&t&b-yA%hP&mDdyWMOCaV~>ase;bXub1{$+xgMvMo-?_n2z7ju)JZ zc)#vdDp4JOQ^`w`;}@KS;UNmfuOI1MBUWr1P~P@Ue>|ZThiSirYOo$&MSgitxR#;{ z*6|boUjjqsr^L9Vt+8^d>QB6a9+XUsX7(gX3x%3yw8_ z)SUF37l}Lw5d<2DK+uX{zcpOJ85LMiKaK}i@}uk%TwD7bu9BFtmodQaSXB0hP>BMs z{g9l`-nf)E8;-xaARx0w_#?Y+amPxC+`C{oAje^IXI^Wr*e~2Z$Nt{?bvL)NhQJ8! ztqi&_@;v;|{7vESyx-2#esR#Ip8kSsr^i|Q-2g@b^ZOMI~*C*Z1-jVH>!jRyb(#gcx6 zM8)$*f4B_T$fEf3{%F8uSrQ&remXu=wjIhSp6jzGI#8Ye?!61u=|6%+ z%(Q3$geUcSc~zXO8o;i8rTn(uOCk!{4}82vNao9a9`dPbnjh7k21*!a_x>e?Z~uP1 zn4~GJw_oDAQorpquwlVW(p_grAUKzdqXsKu@$4Yx^THzcub9pD$v8=zk4JdJ=dPY8 z`lDsgc&%fHx_D(RTOY^DO#UOVomj zOf75Rj4QM5vETi4*FCI5CE9iQ;jW9DZI)^%R|SMM=5zcg$NKF=`U9gy1k{A$Bz=vO zxDwDTe>g8MGcFr96t02xJ)h2}XLdx+{z=>Z+LhNnog{-=6Jno+xc9{*jl=k}PUG96 z3AQ*iUvKXx+E(?;sw*@R-;ERQ5*V);o@;*z+&nne27Ctgf7<{1&|H+q>+9UUd}uK= zEF$ZI50wk8hc5fJ2?4s|z$iYx#xGt7udA8OV0*>&em4SiH`Vi8u(x0>#<+U zI=zy)q+NfeniIqNZ&x5;g#phTL{J>tmKR?lRS2d28xg;(h$Ro(lmVO)}qJ5bo{)VDp2zp)rTY$AvN!}e#{w%eS!{>`ypM$QKKF08MQJ7O+GEKPC3`#X3&ZmRM5uR0 zn6DrK)a{k(GhMkt82@@44Ad)SbH7c%`vg>VSmO<@7h_+-v8MZ;^mI-vABL%eEwI2W zZUA+kLAaILZYBK{vcQlveQ~E1eqZyQj$mx1e3K@4z8OLPK77dEyhMon2nq$4+!YGe zq5I?2w&(LVGFt&g_px?Q!p9ljd#5Cv6une^{dl_cf&7k{Sa`-9ydSUr8H>DppM%}A zP`>-noaOzM1vZMDK6?dAyd_`!-%o9tt^{sHVtC3&zVSfa^ zM|~2_3t6~s*kRX%7cJTC9CXk9t|hMa-iOhT%F|dVJ{K7pnAl+YnS|F*m0E+oU`qe4o*53)an^3fe{ISxfl@bICtWNc^p}w}_@Zh)AKn3w0gS1p_ zJbOKI=e4wL)6NLN%uW5bfc3(}2tLZnms2+QW&+xg?5C+rat z;hYM0qmwSdEQ{xg_wbI56FMZMHmKB|h8$;Z<*l2Ld=9MsJ`fPIWM&VPFZS%a!@Y)( z-?#KO%U!ZTOxGg%_EdIX_3K^kX6?tLr6Tdxi(YXzjX*QtB;#C z8)5X=CL8jT_^aD0H+62KNBD+&7aKc;y$c}g*tsuJjyHOv4{zJ}3NoImcv`J7Qs)u;H9GY|g=>I~vNk&ve3q$>BrnOtD3aC$`z z+OG;3$;bYtHpGdHi$9<+Aq>q{iCA@{W}kCF8Az1Bb3oNWg1^B>}Z73HCJviOdnP7T1MtJt&HUX zL+9o{qTz-hii*p44Z%;U1_7+&@bIDOJ5;#CI%aZ1h9dq<1sB;{rgR5$L^I%7sCu?6?#TS|Of>9Cb*g9kKigC&o<0jhI{B9_?9 z>g>vEA2|{8KVuJ!{e=Gc+4l;W+4Z=Mwma&S?LeFadrfi%wyfYPn@-Q3FX(o8Zsj>l zxnFSgaLK>cUY7F+;d1XTJ+1|8Nr#(tO&u&c&G%WM==X<883!81gT@+4Jp0n7;k%D6 z4eeEplbQ;;urooqa;`HQvvJcNBy}<@l_oPpWw7kjTuLW%U&4cX)M(TL^#;*Z?&aET z9}Vb4gSfwzw>LaHpefF9j2x%}I`l_SIQl|XPOjk)QYZSo5p!e`hEkAtF+kCWOtJN2wpcdr288yjx!`GA?an3_u%#T zVlHBNE+Nn#KdaWE7vr{;(^}4e^hf?syqj%<*aX==#2gAmghFOZ9}SG%zycaOxrp6u zzMW3S&FX~fXt57gz$&-UB>p(Xr>p5qC1UhvW&RL6i!`P%@H|3oc}vPk>-`@B$-IIA zhAaymfW^fDbE zFto!ViG2!zfdl-yMwCxPII}Z%%9C`pl+TASUz{RdyYKT#8q9(rAzt3Z;WnJtHQb;G za$HI%-o6A#%u(v3ejMnG4_GgM7q>k98)9tI`ufi4CroPjkXgltt~D(eWANGJp?8rs zN3Uxn^Ey7pjchS0q+Nq9T_bg!2z15ONQA+nt^*9w$6PRDSBypp&II zlI5z&UWKFq%9MB1H|mh}>I9DlVGFIBqfdVyY7c-tv%Egyc85g`@ICWktokr4QdM=_ z1SG*}yNTv&ko`I*O}|FPabqTvp&P|Hq`yneHcNm0X$ z1n=7}-gLG>Odvj{a{_tWCN%cDzYW&>(x7y71#5;XD=v2udKy7`V8mBnrT~V05tYgI zMUk#fP>W7Ct^OrAWvCF7ha~vcVC2uUbY!mAWm2r}lfR8Dtq}-{6s4^);s|lF)Mp3j zOWH&4MwLS8NWMjOrJTF*(a$u2NM$*Xas1Pb>nzw{{4JPrA&tk@4AkiurOEd2>+7CO z!UvMzm7Bn^yW=FRoVyTQ3wd-?rt@sbTelogZGgfNDP`yvM|-gK^~iX1+2dHxCawvo z!Aw$6N4wR*9v5kEdvDoi7b1-^J=b8Ucgq@(muc#_=_2t8=n)m{-?8RGj=7=DZ@cDn z@FI1ZmvrTB^-9U~Hi0h*Anx$^SNu66tLDF6~Vk zr|a1teT|ENZ&gi>7^;;m8@KFB<%SYcci@xO?1I;TQ#AXta`P>22`y>`scV10(;fnN z!S%^ELAln4Q}0-NMWs2TwgJUUVv~AiI`P+&)X6JiV#v95%ycnWyKNwqa$p52hPBw~ z;bh8NyG56*NvY})U6stvlLw}8k$79_W7+cL28P4t!V^)0mow>p@9NvGEDB0si!v>b zYI{sp#eA&ae*M9CqG~RI^rL;Y*F5Gob@1d~d?#b@+-KQ2m&uz^|GHQDPWRQ#mgDGJ z7nAb1P2VA;o{WDbA;ngE%}2N-aSIbj2q=SW_a`X&T`xljAyzSiy=9xN^7TNR9`&DE zf;kAbcw_LPBZONX({0z1{nPT~;G$zO#KgL{<)|>0cy8v=^!r&6?#x?Z#&_~;E_>i% zOg|#zupkW&`|uoED!awAS;>_QI3GN#(AEJzusY1JFBL*e1Bz#{??P3ZP(#CLkJYE; zX%unt69GB=XybnR22Dkoty-0ch_jcyX zE_aY<)qvX12d0rP8*{)>?UT3dx<}^O^vVf?wc-1dG-d%LPXk`xzEu`8p49)&b)G@= z75i79){ikG%E3Xkc$Zv}xI}nePrQP}&DkpZ4$j^|9N?3h z&-9U#g+3*>9-z|p(POJaJe|*Q>Nbrzys)urpkc5X z#25q~aj{$z5EYl#_g=)7w#%cG8h5?Gjo5>q_1yevuBzX4YZ5#) z-DRqL|I4jHIvdj0>$x>Qn_KedBRp#6fm&S`4i2Excux)w)zV~69NYVF|Dcs<7Uy9E zGH|=M-yX6NnF1jeO+|~6$!NtRzk1ec)pAOp3S2{c=K2EoKeEss->(&X)$Ab{qQAM; zwNRZ(v#gjPA;49Ho#HbqPZl=X_a8zJ)l5nL(C*{KBbs1Y+(NRZQ>tW@yNO8fX7g-XB-E%c@L@_RK*l1*D3fi) zh4X_)9xl8(k&z=o@a=b6h(4?oD0$)(2D{w_ti|&~{y1=l_OjG%GODxqb?HebdH1uS z!G{HlWLCeRWi2TZ3K^eowu#y8c|B{ew0Ezj?Ho>}hB$VB>Oz$#teTGg?~l|y4lK>V zloiXaVMDYKsTrL5;8gQG{uMIfX8?bf8K~xaJ&8{hShdMU74H|~xGJ58U*;~hD)&78 z+t%4_24-xqvWobm&b;#wJNbcXd-{~Jy`3t3U%lN~@?tPyKN%(Y?{Dtii16t+=@yaE z2{MUatJ2tss7IJEo}UpY{3S{rKHw+$nP>BJyH9=!;NaV}?7!lkKE%B87iXV7Uae9N ze^34j!EL#Iw{}3ax$j;cbYp;^bAc;7QLly!DtS1!+F^7C3f7>vzbvT(0&ib}b;JCn zY!@WZ$BH-%B9T;n7V@IIk(BI~ne)#;FG>5R3GB*q@G-}y;Z_4AiL2+DkwM@=Aqr#b z$3EoVA6zV*sl#7%ybn>jj_HetTMUsZ>tB3uO^GY>g621@@?ae-+l{;}t|L~G$;G92w z@Hrnpk)z^cZ`mBosaydx!%L?hgB~`d%3Cb9BGlKChm0ARy6$ zZUDF2)zQcG;2d6+DqTL-V{?Ab)a+jL=h-`kod43+5f47?ba}AXDEy}8(q6GOTfGqFZ#6k`vwWy1fML8t3 zJBXu@oVccD1M+b{w1jskeEBA1UBc!NG?R;GuOy}(TP4fB^AK-tOp3^&w49oaVzqFMGX0l76 zZ|@+u6z719{HJu=hT_Za2OtaY>#CFML?|)if(1dsLuDXued$VYsg9wcKuIMDM+3Y& zJQ`i3k=&yJ)$dc1ch7a6QD|H_GgVr~uX^_IUV(8hfjixY-IY9W z*WpFqE1Uz#?Gu-5nVh4=qsRZ zS&~o9Ru0dM7JasQV$X+xlZT|BvR-cIcuRgi2Nn04)(Es7)sWa>OZ{nPZ>??FM0Gj5D3@mrl-lN;A%MUSMp|r^~Cy_kY z7U{mV_1=0gKi<z3y&3X~(;pL>d}$&&@OI*0LFr@IFMWSQd^k^9)=Mxy)T2RCX2bC-LcyG~YZOTP#m9Jtk-F{qBmRr>h(=VG9hZ zpAx)Iiud_s#jh~&UW!M*2)BN2VOt4E4+A1gf$)QUU=T0(I^LlaT zvg<{#(aVb9j^FTJKnKNwq=k!5ZAbP*RcL~}@5g;FTdkR_QbGC(5V9FZw(2l_fQD3r zGU@RHWizs=%*)r}&*^7<`&cg4$a2ZXy0F%rcRo)32xb6ov}s_gYR_4i@$ z5a%=W!;aod{$4e7-%a&<3pCWm=-S;1;iCua?R=n^D$BPoJtg~zJSi)(>i+3(LNs%S zpZxZYp4vOXWZ%-;mBV2@GwIAVY+tB*LFwa25#Cqw_d}-K|4_UU8dn0d&nq!Q z+1iWb8{7Z=L8e8jlKX|{(>j3zQp48J-P;Omo)uF5!-;m+*L|hNoADIDYYC@yubaUO zgVU0Ob~v148dfo0wLr2XzTIb=}M6_Bs{^}Frf=1@dkKAPTR)PH>3Z+K|_;; z^MOk3YN8RCSOEcxFdW{@UsrHn_)bmY_$tB>Oli)zFrYk73|y#jBgH+!_j$c~5MSl} zeOEw8$!F24$>*vUYeX4$VG0xWX8X~e{A3n@T?1r5=QRNN%QP#a+o$Rxy25uiJGh6I z5uW+c8=G!8(9S60PF2GI@&><8Kiqn~?_uUL_1^p@0`F*N#k)JIZ|k*XrFC4($IWWu4Z>08&lCYqPQo%brq~8*Te6(MvddH zvd82FBI4-Vd!3{n8s|7wP7WQ8;a)C4){l|Jq!8O5E-v4uy}VK1-0U1G`{}R?it=}t zBx^?i!F%K{9$d^;xOyk;qrSp|?QNj@?t%K203t9BnU-~NM&0*f+_z{ZDeOu@MR#;? zuXm%!!>sajeN_D4wLxzwI8QJ-g4#lLC?Qt7oGB>$*I;oo4W4e;?!6EIypr1*ytXIg z#{V#+IFhlBR@tHNP=@?4903L)EHHd;CFqMdFrXP*AG?2L3Fxw22NT7@H0W37igF)hORSy>zLB^* zfi1iEX8}Q)9S@ehkK|E0_B5#uK~Atr`$AL=abtCzdR@Fd%4%s-<{5BcYJz5}~EcB~l?msFVTse%bBfzSBd$G$5b4Vd(|KeJRc zpU-|%n!%f{lj{wwYaWf@OJ>!9{l2Dk0X~{rkKM-e!r(F>NX6%EL$_|Ue>t>lJKGh) zoKa%YuRdEMYp?28Bma`88gjJk@|b`Em&KxA5Rn<$Mfhc}!x>88ElHV&UXP(EnBnXo z-yfycg}R1gXH?IxU6$%59F9l5oxV?L2V3FmY}{f0a{oE+>G3Ac7yqDGS&QTTLRP_# zhKsFtCaGvrLms6#xtlI*on1dmS)gzZvjrBfZNix?bPIn5Z4e)syGz)TU7|#26&QXhL~CvSHQ|-@f%5#Vq{&sFH;C;iV^0$@kwe z{EJbglTI=P*X={Q=xTDhwuc=zFP0WaGXq&}z)kD>lEE1_y`X4&RiSU_*1(uZ`x=G! zrP@BUX<<+FFOzV;^S7!$K+Lb@O1kT+J?}f&dssn31{cE!f>XeK!u6SM-oLd!;p62- zxiCHdj898T#ibBNP@d{JI>A^(X$->@+AF>AKcR9=~iP5g}`pG#!{P_c)gDBfq z1y@krepCkU5N{?tRXf7$(apRMdJw=r{Dp6eE_IeK2)_7}+}vH+0iLF-X9 zw-@Tjavvau=Oh3ZC5UadxD_%TE^rSlUS!YQNdJTSPs;JSS8U@nlj-|3w@U4NT;ViP zmzkd7&0&kGf=|pJKX3k9+8@Gx(eKcpPX>eqBD^oRA4J|P3I<45pHGNrACCgv?PF30 za3vKUb7;KU!?6Ic986uWS@>WkC2+C0UZy`uK}Y0?*n^C9e6PmVU~QCd4KzIW+nliu z_hXHVN^$$0eoya{(+lbaB`7#A-+9;d53qx&ipnsp)q>1${XP~9Aymb_JsIp1K*{V` zdY_ezvv#5?r1!<)AAeGqIEfVwYpHPLb-|xP-dOgskw_L-ux^FZN#)7B09-HRm1V#G zEg#PK7F^3WrSj3sQ0LbH(XZILdq_mXx>0sd&Abtpm=;>O2(a}D4u79v9|z|@Rn0^5 zGdNO9X*Q(hY8(r|eDLNH4aFPTu^f`!Hb-ew@Iu^Z5s>|Zkpid)RYi3DZjWS|IMTY) zT|&az;W1rC5)|A-{rAy}$Wqk}L(A zOm4Uj`;Y0-2-oC-kM?W3Uy{ZsyL*DiQyxCAixgaVaa)WJ4Y=xdrGcus-b4BvKfQ{K z!=sF0*hYh4e^0+<__(Jddluird7|Be5_+#+G$+u8pn*srqT*g#vzuiH51<9Ge+u#N zMc}710{zF8IF@s%i)?t|g#HA2y$K(i2mDWyP8tIX67Srl14^Jwmhf8-Uo>tz!$qw$ zxhoW!sth?sf1Xq4KevKue#7;s}u?E5S*T+{nC$2~< z`>bUL(&tVjibS1D!T4He6$@&fW6+70?d!7Z9rol{59_Ry;kpYYoI~7Fi@7G#LDbzt zqFt<5{oM?8+ou9Yn>r76D&%c!JHtOwiR7?`&vM@rDQI|_@nFW0#Dr^bJp*`9rA+jx zD7d_``I|O|>Si)l{{7nCbkUzaNinRD{}f(;8<^3sY8dzRaUDI^{s7*Q<_D4A zY@)H`JM=kEQ!gA(85}ci#Zx}*^I=WZM{5$&+kKDl$x|1_dkCdm* z(J*&KfQDkaU%T`S*F=gdV|`$we1cn7AUCP%Z@Bk1@JFxxVVYbz$Qir4^Ze(b-*^{FUi*kX zsT0IjRf?7Dv#W@3F1Z}YbAEwJB<`_@?oyaix5-TQ^YOjNj&5HyHx7_{Nrl@cxed08 zvuE^CZ-@#Ra`!LRpA*-4=U>l)8fI|&hZTSM$HXs{_Rp!2XI8s^EOh8TPQwhF_1s4Q3Q zPdMJ2_ZZSL7oBVtBE<(Sr*y0kQ7ixB|K-|yR_ z8IRHuP$TB539m22SecLV#LRugf%wKzh@N}V2RH}681F84$;dkaAp!K8(vzeXUe`06 zq4(-d{v6%6*?HCa==|B+#|y;VhQ&akm~KF+7d9;S;t>qdoVh*1#67t0hs2nWoQ7l| zmE!S-G1%jhR>ixlg=gK9lwl%AeAeCsn9LqF%wlE(H;lm`jxtpeEuHq%#UvG&v>$k zvz5D#sXi8(T1yw$(&^iHzBS(pYnUvWlHD)a_v58ZaEqi)(CX()+5=MqC3`nIHReGT zg7DLsw;hrsDu&^r3r{yw4KZDm0JEow2LIzB`00L`5B@RkE%nOXsnbc%0dmw<(l}A- z#c6fvHx~XG-l8h_zOMO-3s0bQfp%vVxgM1*2J)YOmwH-{*1U zldCNT-sSXep|2c2VG97shoeEA;@JP*`s}L=inNhL8=3Vb zT-5IDQ}As+6^4`k;Mm6rS3q69D#4O*0;MEe2{EV9M7{ZdU>%}&pd4iR4n=^-ioyCM zYH;b{pOYgB5wn=0PLBwSA)MRgQ?D;URTj4uz$!ZKuB;DO(RXjIeW)XQnC%1e>haJN9>*oA#^^b1@$Wn?} zT0#AlkC)n>O{(Wep%;RKD|Rs7z*Fz`X>s8u`8EaybDfgZ3Xda9Ov^G&i~-Q)9Qmev zzK_B=&FvJ^rdWJ)NJ~)nKxw%zem}ZJoudsiOF6)f<*+~a)a8t7Eo7g8+cFKib9lrw z4N*KOxNm%rM2hx)u`lE;zIz*5)#On_aX9Z|Kgm-)x`1o3$$QEVOnkH*udlQITMhP) z{}z}z_2lIF#vMkPR$x3uWBAAl1;YvhE-jTeYuPI9)yVE%3}!(?4>$3ShV=bG9KUtU zpHl?ia)1<#=iKCpeBWAMxIM))M=8z4@;*<~8ra}_%rao-3^^^9B!f5MP#re__B_wk z{xDcM+*Gh<_raV5(MI`9_*!LR5WlH6gnK+C2G`s(-=7ED6tuUhDBhRCkaT+MwTIf3jhGe-GEEA*bpb zU!i!QIr94kfPlSWRmQX_U-=IDk5o}zl_?*dQc)^yJC>KLIJiFet6=tdYjORGX#nNs zK{$^SFqwHY0;F(Nn$r{GRUB3j?XwA*PO!mv3B9t(m3S!}zkO*n%@-PtMy~*&hcoSa zaNjR7e`T#AUn0zr$-HH6&Z@&0TnVz;Vshl z_5@&U*Z_QO++VT5nRjPXEkf=k$Qv5rcy(@f_+Qn3P$AUt;i`dz_qu|r6jv?HlwGq? z+^O;XAsrv|`1o{Q8Lrw!{lf36*_oC|@3zBp4;7wB@~3_QT_qug&@boLD>?M1#7_rUObh z57>6IAjdA%I+qk1n|Z~?`UP*EHg0)DS*Lwq^L21B&B$72YLiuORb&PNdw)v(SV4sd zyKTG9pr1)44tq`3(oK=6x9dSD95Q@G5XOC1aKzOgMh%UsIaRznX+ucN^*(0he7&Jb zncv&0x%MXBoS1z>+-#ZE{d|t@7)}1=)ufLoS)xIYVqcNYIA+q=n05@D8Lg>GJ?TKF zJRY}(C_8Tt@01haMB?|CaryDW3fJ7WOKA{QnNzd+&zsTn?vMgLT_*7qH|W0?9-~Q5 z=@eIc9M!;1(IfSI*&5wPwVnt{Ncybe)3?lf<2u4mJ&6zG;qtTyrq1DNU(U7ED0C+B<7NaXkGGwno(5Y8I!=pQESE?pO9DIJn@%UOveHmC^8-!_QY z*FX*{ZHd{yvqy`$xiDry>)0)5bQkWpt3?}v4=TcXa1mVu8L=KCstiyTJK_#6a7yvOZiW;Jrs+_2FG(^+&*MZY35;J6W;=5Hq zpL$09hd_Ds9bdV4Yzm zdpbg_b(8IeVe%zz>yYH%7qq~i>Y-{vY^9m!p~ZUXanJPUo9Y=0xVZR4g8K8(`oRbJ z&9RpN%nWL7;v%9GtJ8v0*xw)!riRCaIvjy~?F!T2R@Ma_xYp;)wQGxLPUit>)}=Dp z#E8!Ni|?1N?^|nf`KZIbtCPnV%GO@KQv~_6eKmEd2E$jYsN<*EIpHFEwV!!sI-&Ni zJrldNp_~oMDge;Pd#mae4qaRBRAsvUhBe z48fe_@XF5vRFlyqTF}?LbO@5;_u+UqU>y)Z3RB1|*rW%&%z7=5yjSzogE7VhO%y)C zRJHP76}T@J^zlFM#NQc1H?D?-cxYuOeIDcC5{$+VPn!m0c^ypo^A;aKVYxd5;V z7QQv(=NiFke@!CFRc3pO1xb~+0Lbk5dI4r=5B!xUTm9aT6EFsu%~8%nX><6>9hfG7 z>U>o(v}WrU{n2>Pls}~x_bqZik8<5i=7y8S$xL|FGDFI3=`2mnaqltI`mkS{cvg<( zlvUL4s|Eh)Nj_tRMLPNDMb&z}m+LmcTYK|uzrM%S@2DkmDSeb_<3A^+WU78qUEuP6 z>aXE+{&z{~Nu39t4-L@dU+lFywCVGl!6C+~Y-PwG7WQ7|gn*rI5IXARZ7^|lPlTOF z6!$B)hqn3Qv}ewhJOWr9=gom|{2bA<&*^Ub?yaPYoBk1V-q;pK-W&^=xO06TJ*U*E zKQHncC2%YEYL1$qXO_Ih!(UaEgsI>!w;s2ri=03N+#pnG<+(uFzn6dlsh9+_GU$3X z`PvB6`*`hivx=pxfeZxoq<-?J6AW^A>AgQR$ss2;NFT~<@A8PUZ5P-m8xtiJ=D)W+ zQR)?Kv+N>h@8uXrnY5%ZxW?QOiNfiAh zq~}pYkVd2zc%w&9ltu);z7~0JeL>Y2dGchYib%6}?1&X}Regad5WPz+_p(E*F~saR z>e=u}YR7%lkw%Eyg+3jws*cOJcw@l9r{N}Jnj#etX*HM^7ZeEzrwVG>wioaLR9~jtdBbD ziGwLsCy$qgGx{HkpJIEj-=+4Ejh3Z;H9zagqpkK;s@mzQshhmdEM)Y2J!5#sAK5GV zoQLA{A-oYy)_Q~hrg`i!n5R~Yn^!R79mX%$Y?oj4F=+i+UvT;^YHHnY9R){^8T}*R z{RSxSiPVAe48MHFZx;U{yZmB`y=z{M z&zG5NjJdCau5^Pkwxd80j&|$)Vt>=F8DJ_Gtp<0nyhj9y+LWmqdHxm5>Jy2zi*vpd zp4Q#HJ;DXwdXFX32;>(79xw`1z_D2e3k<6}c~!aUky~_NuGZ)5U|1B>@lmn+zzD1Z zIpPne0Gw+!vayK$NJ}={y2buG>A|erPr@rt$UbzMQ~$KvUjSt&TIEN84*OJBQl@Rp zjVt^kh*X?P$#&FvRC!_ z!*9jHPm7Asdm#F+5`>i9>1QovF0eO)P_05ko(@XR{UX-;Z~4_ee;tEspevpOmhxtF zT+7rQSjtKDb#O}MMms#Z=R!*`rP|ZG?!b7Aerdzhvjsj_!*vN2{_NqYlIj@u-a0>r zC@G5CHm~7ouJ^C_P+bd@e|R8Vk;l{RXjS4l5+vn3N@4xOi4>Lf2CKn8*ioJG@mjn; z%(DF=L%$8K`ay($d3hC+!m%J=;8=OnSZ6wN#*J^dC<(l{riU0BUUQWsc+lw*Lm(~d zq?$7gb^Q)B>$I=uV`o29YY+G-FvCmomJc>DNeq`!>PB2~0sZ6p!e&GFGq|^T)M-_J zenakviaX@h;TVyeyoZYT!nv38g5%rdY{hJZ{0s?6i0UdGI{`B;^_J+$D{$tUHTvqoRCkGu!zapzV-Fc9b ztGG$FF0epY!l~PW(~@)bT?xWEo%6i~MNHC^18}(Q!nWaq-}Hp(#ODII@@#4FC{gy% zz|XEX%0ksu$b&=jJqBU0YQCLc-k(%Hd=5<(80Ux?4t;>gS9FgDb9sd?FVLPB5s(>< zET&`xqT0zj$+3chxj8YEK2ASo5N*$o%L(2O)`2(C5s@rG)nAo*^}e_7r_&<-M(vBV zN(EXlI3~IY7}s2~ELoF3DA(uTC-jb&OTZ4fW>UR*K6LxaMQd--RXCsZbNEf{7eO>TWZxtxTKZo1z_&%yH z7?#*rH)QkYuCuaFD9GL_{@cbjGBotAk3F1FFP}^nj-usU7gGIsng<)T>hl)t*p1<$ zLF>Z#WaLhOjvr0743?vqGZU1ggOt{*Jw8vLcp#@cOgo7^!Ainp+di+pf=5uOIxAwZ9f$2;pU3Ks$Zj(rfoHFB{t(yrkz2b@;5EzPV zR-G^#ysnxHK6k|zFjT9KQvUr?6MZ1($OShnrQvg6Q%q1FxES*L+Y<>u0T}z`CHANL91O28b%8b+H$*kmopDu9{ZtF-4sheExr zeEBS+cAsTK6efVD3pMs~-X+{JZxa{f75~tGsjKCjM4#gymhhyR|^$MoKlh7_|0M~swxd$zwb zb#7z=vQ3WsdjY$1U`F+{9z$O8ppA4YKj zRCIZP*}5y0PLQGG3RfV7O`34mV(~Yl{();mUry^_N7c^s5x0-a5jpn&*I3c({bt3D zIGnC9a9X{5c)?pG_6VqFF9RMsjM-Z2Vz{w?;1c(7_+!)gr=oivd2)`2VUy7BQr=*o zh&LoKM2MHZJoA>Ovu$9*#`Bg=9L#<~m*2;Goi~!UYgHnyrv7RE^3zC|*#;-ebzSJm zAYLgDWHNgVR@+ZXG)_ojTfhS0J-WxPShlkXYD|#cp|%(HQ4~vKX1aZUX=;PE1Gk`s zz2qZIfvd`Oukyao9f1`??XmAYXnB*K7BBTcqwUBa#gWS|qa@z0gTQX*^{?EJ$T#|G z=tz{x4_r4;g7*96M`~$?eiSi(p5s0H1E>e5C*{L}IH#m&lQbWMuzX2tzqC( z8Ys{Ru%VlA*-z4dMz_7*DldQVCsF=QzjBMm+x?M-FC$OXVww&|fi}RD^gNrdF80p? z6{)$Z*o-*pIIUto0Xe=0HezSWq@&vpm4_%vfIK6HO_g9D?Q?le6j;pRIau(^mshx6 z4!l8NL1|OFN5}mIR>gvcqvc9OrvIxN=|@WybeH8`6+T!tTK@N|ynCKQ!4*e_P5cf@ z`R84;P5bfPl;#-Jl=*6~YL{bozUO25<6Rs#(K-ja2;^6k`pG(7LNW6r3C;sLmxB@< zJdf(qQ5;-9J{xNB&{z=L_yw9yhHEp)XGEJgg;t(F=9kA(@+>X~u@ObRmN_>jyOa;yb)j2Bz#G@YL@3Kw3UGsej5SMjl*_=fTNf{nOOCo zwg|6h?4|wb4zuA&fH>hdk6!NrNW9+JR}(lW;!mlp5kp1WH>2NgzK5TJ{ef{#em{!u z_3~w+R?dJ^&Mx0@Td8|o*9SG;2niN%CqB6Jp&EE2HbjByo5IQ0h#6eTZx|yT#-UWK zw7;K8dJmPu_Pm?|#bB@C<^?=*KS%#**0A<0;@Emo9gI|8k}DxN@b+cKewV*a_OgGD z0i7+F>;RfQkt7SB%Kcsyz0bfafpD|01jEQw)%ct1Nn>H*R+Y)B1is0Mx^@#3ZW@}^ zslrFR3}9I)8q*B@j#5HM+^rm{IL;R`|LXZV^JDD6II8~DYnlkn4{fLV?tq3~`|49K zu66Mkf>^*DEzaNj|QGL{JfXf9> zW_%rfC$Bxs@o=fjFWxvnXb}qdNJceJ-TD6WtzY^frM!JuB^Qry3Gq!_C#W{Zn98-D z$TAEeV*21531nA8-E0tv{?t^gt%r)eSHg^Bsuf*7UpKCMbUh>i%$ZPBwRBdvD=Szg4W6Lap`nl z$+GO0vl{kUZu@)EAI4)h{?IQZf_9(JAEnR|{rCjV-4|vI`C{@6)=Vo7S;*0m+ zi;HK=Z#X%0ldj=!1$c3iCA^f!K4yId@a|HFYYvO?qDc~4d>Dw zcI9GIGKOryjTV2}O8>TJ4FZ$>12y2;`?ak?oegI2ep5N+o@&7tI4mWHc~!pfTe#2J zakF1(S7zVNPO6p5=9bS3YK}C1d8K^0nT5r?EW7}my7&+23g6uQ={&ySi~2uoX)FJB zX8zlmzarKv!du^pdFd>Q-nx`eHxv7dUBO%acke@9rY~be4^Dn$_5~@9%jSeDh8OwY zlV?jNRqk`+dW9GJ{-LHE+LHXq%^Sf#@*DRQ*5WfCEN?i79(Sqk57d|k{T<;Bahkm? zHDRvPKDEs5vye$><2`|C3zS5q@TXBiA@0`z=@%BwW?PvOG#oe_ipuumX}t^!OX+al zK5tzJtwjhVi&_aPJg#QZDV}NmsQu`B!$f!AnOK+!W>W_~2i>Qd32T`5LHvh)k(vs0 zp5s6GmBAbO$@|q^XCa;Ohv&s_|ST# zQu$co$r&GFqQt?M#e>(y!hV&O^tK;l!>Fr%TKO9W2aSVX%xBIfdbQI0OYNzUo`)oN zzXps0DjIm*3wcs;=+t?Gu3Mh}WSVH9`jT0BFm_X7x&Pd$@vx6A{ysg5*(bnvVsc9O zf@0ixgAm~ghrL%-rpQ8M{|*eeMR*pzzG4n1BYK0>O(bvS`UJ@>jLUaUlAKDi)P57J zArT?mk&jmgen}26@<+9~O8Y0YHi=zH)(y$2vn^hx?9I&m{0&zw;W4rYi9(y~c|MdB zgHIyQ&y@N@refiMUyTg@bA?qtXR(}k|F2ZP$4Hb{@-CdaR~*R$5)>sn?IUB9STw{gyqet@H2I!4kLUW1-z{&5y7#1f*%hFR0 ziFKQhv+&nT5?cH0t3!`KUfvS#l#l&W<4e7{^JF!GpY0!He(#6%{0DB9YVHq>t}LK6 z%4P=uF)lt}_(h48e(wHa_Q~!45%UTa4SE;6JuxY}WQ!hYWG>TsJ<+v;DGlAYutK1J z&CH8-iQj#`?d_SlMQ0$t_C4FjtYDhw3;N4C0LozQaKtn?RQ*1@h5mjFqXQ+LR7xlV z97J&>DHKXlr^4unv<6!8;p~Y2oq9(#%kDe~QX#;t6u)5n{dZ7A+xLj;9-nky0`GSK z$H_kR+#jCsn-uS-uT(L_i(7eU>x)iAO=0p@=|>Lp3FWR5HT9OJU_kHI{kuv{P&!0!Y$1L07&j`dSz&SkC#43_R5Zt zqb#`H{dIXAg4_Dh8z5+nOJ^5%fKx!9q;BI}kmzoI6Uo9K7MhR*Mfn=cLH)IGI$K65 z?_AmUTvF+yO}RmC;0~Qtp@HX>IuWY^xxaj`Ki9s$TLziZCszrNU-BDRI=I>m`pvyz zOa4raKs{2+G$?OiXMQDg(p?`Bs&6YDLQw&} z0Ns!k-!!UpsAC#W*QAAu%*XbWq`Lvt)-$`sd0j_1TW-RD6O#g(zNU%=Q&%JO<*+H} zaH|@dD@7sM_)(Lv?6PLgOg(spoc_|duex|8uTFg-=Q%8Qs1?9-^Y4E8!|7jlOR!xTjPpA{C$Qp?v&& zqE+t|L<8E(^{SUqeD?`x%^fryd*h3B)l~U5-i)F2FW)-!jj;n8Q0dk6b(n#exHB+L zwymoi;m`ApKC2PN2{BQwQ9bIxSFbq3ul6o6vHLOjF1+1vzboixJ6tVIhF$=-0D+(T z*Wvl{!K)47(P!7ghb+-Spa&Vq_wOxw6v2BD9%_Dl)s^$C8*n^^rn?l=<*xi_$2y`3 z0!_)^Bk^l61!~x#YYeOFzwt2&MfIfdss^|Y3>*7>C(qjv#oy^rC-&EVvIi~+;Q$<> z(Kv|uz|34Reg?v1e0DB z$o>7LwMNzDIzMh+kt(tu<{ifk>~`Sd7pLI{NZ`Vw#)!rM()N`!;W_l=2U34BnAJrh zSS2;s4OJHe-XJNR&$fuXT^>Ms^#HAUEYYZ{b2Tj-iEk{!DSe_m@>Wl1Cs7lUJ52X_ zgIg|b4pF@y`?P&OVP zsv(ZM=5Bcfpfu1aevz6ElJ16g9a8P0*Lk1)#i#KarW2a%ggq#tZ4uvB9cC55PiA3> zgI`}?LVcKLW^n3Z+!8lJcXugmx5-YxNQQ?)|9e!3uyUP2ZxReXJxg!=FN#c;YQF`j znq8ao0ZZ^8WXL|@enPN0IykIOc6@mVmRc8(zX~EhfuD@uHdyXTzY#-)ETuS1QD2r- z;hs8s;T{+h<*HqLWjvt-P5vH2@fW0(VoFP;Xzvr@BT}}5b;m@Ff*VZd9Z9!d<|MxM zx!MpJSQ{iv9=f?tds76*hnQ#c7~qNg=`h2Uzw`IR;-d$d>l??FE@ITRNyW4OJa_yE z5%IeGHi{l>C3MXbTfy?x8V}LW&`;!8H9`QJjKO89hh#lJ1WA6aLjotH{GR5Pn|||S z5O{~~x#s3INJ!rk4;3_Z`z>-68C*KD&>}4`eXXhe05~0ACrYMVR}(9krW8af zAeMygz7O%@$z8}G78rdGEqc>apZCe`d7(=~%+y0tZ$GR!U@zT}8~XVk>Rl-!?qwR&C07*LqZnfC_K?5+oEjdEF; z<|C4GrXoM;a^9!nxU<%w(bdu82h!ir3*hPW0w-SX06P)4t@Hz$vvu6l(dC0ka*xr0 zeG8mLbJ}?GZV-_XwhqTt>;=P;ic!a8ZtNd+I&Zd>P5R}EAPUI9)r>e~7Z1;*hO}Vs zp+WswaqvF{og=JLE`KKe=2m{5AILig?Oe&g@JvQ~F5C#nf_ z@rqg#h!e|MIKq#UMU!eU_JJxw!~%M!Uhg;c`&UJS|Cfh5V4OcE7vkNA>9fbVIhxkT zazy5b=T-drIWvnmo1-{~s!|AXc)3c6De|{16t67+Wp%z}dV9Y3D~&SrK9DmlW+ho; zo~YOR%2jaXWi^lI4>s7}$M6Wd8>*U!rRrGsVmrfmx3v^MA4~QxTzxu>&BQeOBmulb zLTjFSyIwl3OLVVDPQmY>*WSe<@8OoA7sWOoTm@>wB>CdS8P`#A zhmd~e>HLn#-l0&D8X$)iz~W2Ff=$o+$HZ60bWP7B_yw1n(~@c`UMKw#q;pugHaP!O(WZ3kHs9H zvTS>pkYe1E01d@N!1xhN9EJ}^2y~6&)IKsn688Dkxe7fq%RCVTT1uw+0Rrgl%JU?=--hp=qb~PM< z8`SY|u!`mfyJ`k*gq_M;s^IU99pd=zu>{agC5W}1^GCXZ6(D(8KhN@BK&ufEbE+LA-q za4mc8RQ%YtZQ1Wb$@Cq?MA#>?>+3}@p2~1J>Y3}Kq0wX*oCIUV6(`?+JnE6gr#WIJ zD%ugc>hsSG)%(LBBi&4g_W=UB1uK zDV_lr<%+S{{n4Jmz7A@Ah)`)(FEj_id$$~N`8!JO%Mif*Ig5Q}ZGl%O;Mfg~AGs*8 zqNE#SQE+|Qf#c3bRf6@2Ol1qvHaAb)PHbb(FMdtTm zDfib2p5}`ACzbrLaG)dg{eUn}PD52&uZ^1FcFLxFA-9$h!-oB#*L#1)LD%T>x?Qi) zjFIq8t;*lr3^gz9?&A@$VgcuE`?$ws_hG5n_v4B|1!ly-5G3bh0j5q`OL{+y&T+Nx zb`X&H!4O(~5|YOI@Y6vi^F_ad&GmPi=a~;d`RMUNTtta&O`{r7$Tc;#4G8sV0e%tF1qNG8pc?6`M?LaxaALnM|QhnZj)D!uMJr{#e4~j~hs?JcCl0G`c>Cr?B6A@2-5prK9-n2WUC$ zmmM`oKHcw=vwnd+MpyXb-Q<7x%(4g2I*_aU@)$OvRwRLmQ%(=&?>xb4{CQwtdy@jN zI>JwdxWi0Mj+aMdXhcUorshM@xF_51i+{kb=cWNIr;Yy#>OrDSfft4?R8) zy?>n6;pO(aJiF$LMO2%@-$y^$wC{XR54Y+6D*V;wv~B<`!-m{ak8l*=Q@p*mJ~HOz z@OsorQ-5aR*^M=8#EVXM@w$|L9w^wQWvA;){yY!y+x0;-VR7~Bqi*=x15SUub`5=G z6wDCvukocyrgxtZ@d6(wm_r-Wra^v+`^tSe(OJ7@x6Ar=Voo_W?Io3{>=Q=8^y^Oh z)Q>Ot+DNqNwDcZxZOa?FTEZ{yGOyAH_1@fk#_npjX%Bv12=A`TTI1z(9YH{bF+f<| zIH2UqxQ0Vdkk;?#u@6xtFubSYwlw>tX~jSNt=!D>!?JhY+ciy`R^+Vf0e70QjT-1mU^%d z3OpMj{kXb^ig=jceWU_-`0>M~DCW@!3riO4DW&bSN4cFyiZ!Nzh^n$Ub+l!KJyrZJF2~a?LvO`%9TmX% zt<%pX&L8e|wMo7zPC#SHqAOKNH0!y1{1w~MpU|XX2EDW3kfNqKn0+6>A8@vYnjzu+ zILE=}qotp8;VR0$z;k{$eNQ;&_tlkWvK-9eaxR^j9T}Kefg*)f_Pr|(&cpS~QxKVE8H!!-_&rGvrbqcs9!4tP zJy-W73v#xzRK@7b%{mGFsv9a0k)g$a-U@5fXi9%DicV*A1voeBPINXHs^lo$SE?FN ztl!rkUm{c{Vbz?3%+$+ow&@$|a&YHG=01KJ$>~`GCs%a!7zH?eU*ZzMH32%Y@Y$l< zVUOvqcl)MN4ZPxl6xT`ISo_rTl`vb#sI`uV_xP7JQRr{|JR|B}C-5uW!XTTp*MBWc zOp@Lm$9Vm+>rgIydpg2SmtZDp=1NKRL+0^5NJh9X=9#xnsGj!$5mMp^5)SG{AAC*l zC;-s*p>smRt4{eEWeJvq*F%n+%p~EOQM$|_|@4} zbj#z@(na(M!G0T8da8o6IVUtN4()S#a zysNKnavK;TYa+LrjDv%!zu#qF9g1JPrB$ z>xsn2+bYX+v(Y}-&G z?R}RTQ|vvwyai|Y^m{D$tmBb5X;W-zs_ydUqoTgu9>yT*W54i!{(QHdzTTU0y5VjG z;&4b+<`ij5SdJ8N-dt6;pZnki>o&9$jW>ccVJQ*>(Ul42S}l;#d672=z@RUX$0Gc; z8>#?h35wY5`b@m>bMZj^ox@cj_ZWfBvdhOm@pHW1qW+LdR#7YNw{1ziJv~u@_`Lp- zW!Ir?oe_RHZ4*lQ5AcagWWw=WJKFC8oM6Z#ZYQ>!&r+^6o(OvSw6S9T_^$oFyN4T_ z-R3F)CWiL@{FlE+81IEcZM=eaCd#UO(~LAauqEOt?%|+47a-%0buL1;f4jnsn@-(} zc#aF~iq9PAOPRxd4mfm><-ctKsF(NbArKL%oWs;FysP+18i_Uq;*TVkQ3h2)|LvoJ z@Vm)(ekrca7iO1x+2A(TM=m>Aj}=qL7mUJ(oeRd)7GwytaBsh6BW3)a1!4olfj9)H zj76+9X2Y5O9;f_pqf1!9KQDp@`Fp!?<9teD-7L9l*y{~?yqWL)Cper&-J|!}x|7Zg zMTzaD8T;_FuYyk@n%s}YGpld>2l;gnB6Fq?Z~PTa{n^F6@PEZY_d##8j2j79(}B(= zo7+h8EhNFny1|3S?(f@+KF0#XEz&}BY6asn`%8Go-aT`=eH~e_Kew#-ZC`i8?WzS3 zer=AYQzT<1!Q(4x2S;eK&7R4#;S?L9QA2ZwKCR$&KkZA!AUU|*1SF4DUOumH0OPic z*S002NR7MmP-J+CSl4IU%+E6;fVgirVPO9;O|f=6T_hnf+WMCKZo z@oBV?aZ3sXWf#=i{~WamykShn3PJS?YH1ECszaz~YZ~(k1dSH9Fpr1VY24~5e2v*} zdp}3PVd0zMocq%k5OISILYM(K@WNUr*-P*13thNq{zz*5{Fq9u_}1@NfmAmOgE(i5 z9+vuz^AO$Tf9`Lzc#7d5Xg+>@VKp2C-f!lqe@l zvfp3l-=_OB41z1z0(^;Iuzo}*e$ENV;COgV2Eopvg{)<_ug~IuE&WJfzVBlT`QU`YRQ`MGOId|xedH0GA!xHWVN0@n|eL4 zhtK&sV%_MLsE4=k)jBb61~LvuDATOG+|bEM?Xpx6t1Eezmxw3>=-@U{XtLv$ub;lU z2Qt)GD}v-D^|SM;CZEk3O|kklpyQQClhhqP7$bO{fBg$3*^KA1XoNDNu+914{7z~b z4sUha9dtFNz3Y#nue5Uv-o*(!NE2zvxZz{Rrr zy7)<|?>DBL?jvN7fDsxfoL9ZKAMQ+!Bn}#F$;rv}sk^uHb1RMybZ#G9xuN5Eg;8Mi z4CuG~ykF{h_?iw-a&BMV_%FmC;p&})FSpe$I`(A&$k5sV;sh3X6oqL#r_gCKJewRE zPy6`C-3E|ESuV8rp3TNGed$1d>Km~v@lR>5oqnHT>O8>h$-R$X4;A>5%HFE{N; z2KgyoBAri~eN{G2%cYLzvYtXd=@CuDCe$ z)2QW>kYQRhbS5x+^d9hp_hm)vr3{~nNkqwG6Sh4&<_9f{ zL@#CgU@*YSr?@{6%P8r&Qm&`*LZET|1f>qIRat*Q_C`3VE^?;#mN+@hr`Fr;rwYkr zPJ=~to`Y~nxbK=5@e}u#mb+|=?%q`)pNe#Sxv2#N1m#5BQnx?-FgZS?vys1FbQGiF zRu&UtWnWg?mHS9_x^~^YXNrQit6DErZ)z{D{=G7M+COVyg}37yzzhImlb^rvRyp;3wjt)cJ+)XDAyge%WbC}iRG%@VD`;gkvSh)lgy~nDg zvaiQ>D?v2F94MEf%Kc~ZJgujO*!OWj_7eb%Kh)h**qmG*1D@Vb{TmN#_w*C4oWjwM z{W#S;#IAh8ko+&gGxiu}Q*lMg`%klqZ$IXWRfccyzkTB7Q6mh_wxS(%7{!Z4G?fbj$3XBFFG@R)s zex}n6PempV6#BQ>?q+vl>|feF5)Dlp)SBnA%Q-TDAm%9RH$F-qf<3*Zsczsg|*!5`gUsPO=Z(GPWmsPRcv`cDd=h=kV$uE5mvAZG>-7o{i`xXpw-~2Oz5#aYyVvXWZ`C8Jy{m?L}mdyO% ziOqgzJ@^e5PKCja`a^9u+8du1=os@a4`%Ku5mSi0nZO`+KG!AZ*4lo}W`FM^Io%(; z`!Ve&N>2CFbfe}mpLZdGyiY_miys8I~65ypRoVxIze$|h&EfQ?N z6^vEiHDtTBe7tUq-CLZ>CmaEf`E%%h)v|rpC-`rlqU+z??#AS*vWVhuDUx$;DgsOmM$G?NSOU_Ji40$06wWPfkA0s*rc4@aCRv3It6u1z?d zuu^+n!|E}jq+#@)fCjL)8!g?n-8_lqTT*%z!owUtR3g3(Ks?@_DV_KzW+7!DTbcO1 zn*JT61$u0ebT%<79(`X$w&uRI;yW6t=U~U1?9b+;o(I!1>J!AY!UqwBt9=%pVQ**a zR?1r>*9|r5gCAB?b3{3}?3Rb9aAhLtjE6V7kUzIS^uC*EuMXB6P7)~lFdZo6lan|g z$)>pvD08}BJpxm&5{~$MX5i6;*_>-KTMqJB`zefHJx`KVX4lj}kwBGHv;=nb*QLAQ zRO0+XgaN1rN_by*Pc6_1N=5$mp3Mtl%(p2D^LQ@$!|x@@Hb=Z>@0NX!SgF9c)BhgU zV^0%!Ukd(;8bjWjoZEwWsXXm7bbr2TANaK-lY8GwNxu#KgaSTLvM1(c485z@x6#D$!QFey!Gj*g>Bz<~NQmb$gBO7x&dqhd zt-}XTqSH9eVxW5#T0^Q&KF>%HWdl=8 z^CpoBI!w#>ddZZ12DJFu6$rdgBGLx6j+tHonM>E7zMdy2 z2KC)x@dzxrixXqcxZ`Bv8U_ABkev0 zMhZ_+*Yv!}F>~?#>Fy^yJD!Ut3=dk0q~+8vGVEHaGQDQ$!30&|V$$9#eFRL$#u7e+ z+|znnGpV{yg;u<0K>-#>*xzpFu%9D*)e4eU*ZrJ+XvedXLn7zG)!ZK3@4>bR$wcaX z`3&j--BJQik*4~d&(%8R-y``GBT5IYMmTHt+mwy7N9)S~dQtPx1Nbp(8`u%E5q6_@txLn~JSIvSYN*Oq2V*;H2!g`#up< zp70%7aB+l>K)~|&9!{yQo74Bepu^=2lFJM3C`=`nuBXK=fct55Pb3QG9^pK;2c9nH z+@ay74$E8BgNFUPm~Xan-uQ=qG~h_Tz;`1XUPZ4@W>(((UjtJvZ^g^S&k+owyHhq- z^2V!{TT9F+z4oT4Ic8s9DDNe^2sjssI-mfu!Mz#MJ~*UI2=b1(F){((e3f$1b?n$m zwb4f`-i?BIoilq46>_}Bxcgo`9z+f8ewo3jQHrkGN0bUc_@~)K^9hb>5x^Mfv5}`y z7cU(ctankBexpBsh<8?=nXeMOz0M>j-HdKv8wqFfd?TJucqGJUHB%8i>Bn7|_vfDw zx_+D?T>!H(*1w>K;Jz+HpTT<9zq!SrFqhx^@apnaweX|d24E4|X9W8ihYwlP58b1e*md{_P1o5{X+=1rP z3ryn&@2io~08BNJZs)vqAX0@s4@0{T9|)(0jJ$A$;w-;&t*$|lVi^~PGMVb>i)eE& z4NK}W8vQ4F@1N?7s*45OCp|ZMB+H?J^Rb%HN8(H2q(H%A9~zY2Kj8s0Ct0!tbg>c5&0`lDdosx^2n$UwMwY}S_UlSQfd*FRBB24GGEc#wQ0Nj z>ZSN9bFR~F|1fYNeEeMfeeB+|lw)yWwj>t~h`Li));^-eZt39si$Sw7kA0Xa6dUyB z%QZNJ%-VD@#tZ0t*iiIQozvdFCT60-JidQc+oI(zsr6x<1L+ip&&E5MW?5?Gcwzp? zP@@b9!H=#`J|9@@-!Cd@8uu_;AO7Jjn|X9PpR@~f4dd|*p{(efC@6*v_xxbo`g-K? zeyKM=DvIC@2l*4%!eMc>>&;KhrV=X`un%6m-7&k<+i3ZQrd7stCtmk;-)a0az3gYZ zr&_xb>oI(V)ood*3P{-Coyyr~-On9tm0J9lr=TB7WFth3mb}0g*e6Y=?n$oA4ll6* zZjQ1v za-RW71Obu=uFulEg;yzGasu)`CP#q}5Co-P;B&8ZVb}BMVUE+vPp@;~y4sWp?9aPB zKFjASZG8)SaJ#`ZdX57_JrP~IhU!& z^kbJUN<8b+-ZZ2=z&#-RE1`@1Gm%mltXf;dI$l7)&hf7vRu(To;?^Y^N}vr1$)D{8 z5dAAshd4-n4g&6kCIQ+wu=2ZBthLHV^8Gmh3O@wiVw_Oj1@NAm61PSEw%Zxr9 zN{oCl!tT_`Qk-p>g{NSaoNSzJK($H$mmi1JHn~VIu(#WA&W7v^BH8p}Et}NUDEwp& zeZJK&@n!!SOClfz)w`dW0j=Cg%NVx4@?7u!9((otmQ5v=(rGk@;w*Rmlh{Ly%tDdj z@aOFZZ7K{5_`$fu1X!)uBRsxx(xiG4ytx84^c---(Y17<@rX?*?vv54oqXoxASuJM z`8T!64>i2^JJUeieoJKG5X+?&m#Tg|G8SE{-4|U)-wgUD-`R)jemK2Q{)yCAU*&N< zeO`6Ejix@w{m#lxNhproeNyH#WT+oxcph_9^X+{PJ?BM|y#B z=9*%Z-TOra5TtLKv_2@I&>U%DSCl zKTtpHSbKJF6>w(ZZ$R1BIu{g;C;H#$e>y1wIR)mukT+eg#wl%G7tIADQ z@hTj{^?W+GXFqHm;;&;?e=>22>F*(B1d@#j$1-eKx|_-y)lsPKlnO1eSM+lCJ6h8zF& zVV4dZEt-5_wR4jfK)DkVf!Lkd)aX83rR$&?I!tX(mmeQ|Wb2l|j-H+k`Ug>0;AjVI z>j)nB;(L6XTplP)B9;|r)lTlz@0CypxEke1(Cna95^HPRo?G}z+<3oSD4tl*_QjjG zcgac)m%IlwAt5N7%UAE#GR?tHg9^rr{^qznt1^k8qTPmfJ#+eaqP~sjDz&A-kox0Q z7YN0a5k951!k}4M5^F@KGORipWu)(9YuNz47BD5k0TS#!c)stw3P1H$Q+Y=rFBb2o z)P9@{e?QS2w6^^61_qPuc7&W{WoDNRaz|ICD6)eOr91$ zQz25tp2#uv7&;zjN;wn3=>8 zo7*;eAYO#n=}o2a@Zgi{uK(5ZB2{m5sh$LJo_@;WEjP-Z=s?AKF+N^QCiO}={vM&R zEZ;$L`8csx#RAf??fv+kmJOIMlKr!0GcVK`*(1<3bc9z;1m8Bk*;hJV%d~m8r5trCa%q0c z!a-bHf^I)FL&u+qC~mZT41~u2nTGYfIMwC+T~qB7P_wYc8=5DZ0Jkx)DmN-2?%N=L z8lP28r+~ZIKu;KMGJJ8_>+`KY_4=}h8HyK+S$<(Gs~_7Q4L#7=GM`yJf9qFne zO2&+HO~tDls#X=O91aTFn{J=8|JrAFRd{2;-dzc}oHfHD(ec%Qp9~&(y`^Uja*XF` z0L|FVuLW76g_@J~fm1!&T0PM$vKnZ>$r^;glk_X!`Z;T;mvnqV?1_%#%ZIm_pZpQ( zhFL0uYWFp{_J$|1ILH=OkN;_Qe0Sj&k6 zmNE)VOi$dn;CVCCw3@9>h8Y_=Aw2kL6((BIz88}2&{YbS2P*ZiuS*RF18zO-tbk32 zB0?wq-VgRtuEy;@tesi2s!9@t{}M9FBgj09BFLK{2r9@t{rX<)+uiRS(GmOJbGAnj zv8c+*T=}h6{AJDIRiWb@@3C1Gy0C}$qnPWM~zIhzW0 zUpl5v@m}7fs`(9Nh9*r??kn-uk?&euGO`-QKaZf16t{&Ile3vaNklyAxXI}jG{C3qKqv5w!w3{Gf)OAha=bb|iiMpxJS zsd`{n0XHd8Iq}2_s`CNFY$a&Db6g*xL$&Qo-R&3GI-tX`QIa^d8aS!~0G-dsl=Luy z%{ho2jQOzcU!Le|IyEv>Td4eI*?RA%dsdA`R0JfaE#3uKoZ|0zE?U1|>Ts^@c|Xab zsB(7+YvXWK0M(yZTcHmvqEphF!^v39JG!x*D*?YRK=U-h==42hLl@|;jXaj9z}1Z> zFF@`_R4+*QF5{5CH@m-O7YZ7`jYW;9n zm2U=yo>!wPy>E6KvR~I<(w(fc@w7hB0e$G->r2Ll^c7?f%OZZOssQB}BIyeX@=05` z%#W|;YKoxtA`tL%?rm}?olu{#;|wo17CVW8G#{v4i8xeP+C&N@SMm5M6ZeW)M5!pEhRv z@o7oCrr+z(n$~swXd9TcKqwgup6@RF_ubQ1XT&duBZM|5Sy2KfD8&7uXyp+%M)|r? zuiImf+LZD1T(1z}Ys=>bvhyW&%qp|t{kM$XrGHSrit_Qof$-{yRX0}U)8mc&y`xeM znJf;vXx95!Pf6A!&HTNdy3LY&;<*{xP3GXJ zz9dhj;c1^IgUTofDJ#AV zoGmKv{*2UGdt25q!pJZkA@i0)1#r#0@t@H#+w z33?roJj{LMizyhmdzxLL;&u&c4$!nNZw(WV=Tt(+XNj#`0ajr&HP*Y6wQex7+NwM?GX5h zCrf6SR)ZveE|m@Eqr1t?667)<^z#U)!7MZ%r{MK)MYKt?*A+#-=c3v6xePk8$iCyg zfPWVVQ1K^jBK{~bYsoLYKP%V?o?hE;{wi{iE_Rj1VB{+ydFT1@Gzq0C6IY}oVZ{RP z8twcZW$g*5%pl%LJ^PgE^)LWi`QzP-Rv>SvFe}~+DR6hpp@8-)+MjV{_8F7G```I_IUy%!I1p%)Hcu4QCbZ4 zMi5#I7jnYJfsiQHpJq98U!l}U|72iBS1zX(x0v{C#Kml0W4}7xc}p!&DEF0X`w7$a z#lPxYK_UPSd*Qd@R|h8RIPq*cpJXFxt2iA|E!?-(0-#~gn?-Y+%|Wo^nnW_iBMsbp zr$Ns`-*Gu^j^apnj``w$-{|5$^~kUr;j6x7g+%Dl=B&|9az^gwPsHFS#6K+OHydB= zw2-WiXwB>$-s;L>A6W2nq8kauq44YLNjE)x!1yao(EWMt6BEu{{~Eh^?CV>d2uMuWX=u4xV zv&~=kD50EQV{P*L1wpRxg}xyLu^%#H@*!b-;5|@1Fz$raX!k_uQR3Gm~$6I(ktkox#Zk=*m z-^xk!ewB2$Q!Fu+J9a6HVkD0|=Pv=2ZtYG#n*0SL9NCcn%^U3LJ4s3;H?)i@>e+V^ zEDV72U=;YML!M6n#17hYeOPP+%|J2vuqVvE@LD)7O1Vc$qP$XIH(p0r+9P7g*8m;m?7m>Y9iiT7BT~evx8J3m3Df@Nn3r=ixUqE&V{H%@WVw>1g|qLyrB$Z- zn0?dI@~4cc6i%1HyQmOP?mNo1^EH(X?+35_b*In^d^-B(H*0RPj;K8YTeL^B&Z6MG zUa%UP7#f-7u88fPg@7Lihy$PKWN zFhmhGT|aZIj5LpO4a$guxT;=||@%HlOk^&`sUVv&1S4-T5o{Cv+vWUp2DQH3(}9|I(<|`it_C zI*Ff&!voR5RJAX6AgR8DLRQ?Xi`XD27a@M`aYOfLXjj=2%!M+&;9>1PErQ*K(EPdU z>Xr|b1p2G65cTgEF4Xr?8qnhnXF2}$sH;IU>p#;Q);{r2r9lrK`OrRfN<$81$(v~# z&;h_Wz@(s$n{|B-4dW$@oHT1n0s5Iw?-bUTV|Akl``|FZL%~_#l<(JNF(~s%LUOT^ zB}dHFSHq&c^0M8$kj`L)J@BlXC|Q0cs7qh63NqCY4|0jb24`oj%kic4vAFb*Wuf}2 zMTJJx!Ombx#rbEA{c*2yqd387g-G#5d*g!>>79Az;UdwsynQ4GDo?=$R}v+xtOOG4 z%J{ia#L}rE=F8 z=KO?t(>VSt?v~)wZ+{H{!8=)OGzvc321Q_2@&+&Q0Y11zI3PasJTFrYEOwILuC1vsZgIg>-ZA?2Hv=^TrJ$RLXoiBVab1nzX-Jm?t zGWfON&}FZ!`ETD9Q%@9*O!$0o+2a|1nHTrg;6(ZqkWl-*mp!l;Y~mOl>rFcCNdy)+ ze!V08!|ddzasGN5xFF@jW}G5pn9Xkj7j0eVOab zthFI(DLtlkgVUs3ZZcUEvMjsQ1M(9 zH=k%4YZ{vW>Z5uoYjjdJi6*vInmTS_50L=I3d#~v{Bs02@WBW2|KMpH zI+jFmH2|5)9(k_gLE{74n3tk*$(p^nNBc932U=ASnn*2s#tj|(JeonstVp;`m2>q{ zCEzu_o~>S?ce=l(h2CQjxXE_C4g6=YpYn7XlLnUZW6bYR_f4ST6qEZ*N+2sJWq&BK zEa4{q$90D{2JF+L&flR!t@V%bG%7hv1qF|%Jyz8qDd*#3Zw>Ev9AD@Z3zRMOb2`{bA6kFk(<0sDv zRnfldrwDDANnIS+7zY@vQep1dwN%c|VQ?fuf!B{u*q3d!q2$(2CxKpj!9U#v*hC8HqQ4Y!;@w>Nk4(yVFbf#$a_{$#gC#hhW83f%j5kvIT7m7)+~H{S6IizpFpZenS8GO#25u!TaJsKNrx~tNm4aZWst=#n&r!pi4g=^Q2$B>fV zyQTAfHND3MkS}53dl$vaF`HD*9RZKVuZF%HHRC+fd@&sGJHN<)*QgO*6`Mxl48(o~ z4q1-vak>B1+E7u3Ex5-$*Zj*e;_7C3M|Hn?M}#W<@ZxH2WOSzK$*<}T9K{P2bP!u)@I&Z|XPGF`RQiiE_}ww>`ywc(Tbuy~CT7y5rZ+iUb8>LY<>m z=C#tNdfSbsM6Ro)r{;Ae2HAc@{Me~}uB?5Iie1cRIz1J~rs>&uQ|}n43W;8c>#4q< z*1g*sfxt5&;TMDLCypnu$v%LWWCraW-zW|!CN?grQpW+l#_cmo(}-W6>6<)ct5iRW zh`gU3m;H%XAdg|QE)ICY*l!@lqkSOhj98w?mDW&%`A!DAN6%;^ojzwPwD!B2EBk2) z_oGs1E8*K;z9+eoW&9TC9^0RdZydG#F=635OOZ*pfStZy*Ccuzs7W58@ALYdxBVnm zJj`U%8{Vr6af35znir!mO-!MQCNf{*6~drtc=N|U7-e$ZFE2V`Kk45E7(J|G$|eW# zfh4dVlE=QJ>fO=B8#NmH?^}=K0iFAr>S%_d?!)l%g4X{15awe}|3*6g z{v9!Ll|B>-6`MEzzK_E^odi61W06zi`Llc1lKoZP-7g+R z_p~_JznT|vnzUgrh;tAg`y}_ibI3%w%Qd>~mmiikdsdJHVm(Mk@>|;EAJ0#v#omlDfWH3^XDnRHl56=)f zd;KY@8OZ|2-8tu1Z@)w8678fJpE>*F6uluS+TS#@6ddujv=n+2BEI-dnpftGWK2!M zW%^%vdB1}DFvd81;^|NyKxpJ&4rYM;ysu`?OZOk@KeW!{p$_u| zuyP56viPk<+YA1fsu};6w)Kq`?;PY8`o6C z9dnE_$07EE?IT~AHVtw$RKNFWiy1BAa@#Lk^jXHK`aFqK6#Wsg`G$4H6(9uwoL;?) zf}t?inPF}lF?7q@^N*g!dawNwp!1f|Kls+rig`6}=BR^B%#9K8>#o5EeUKGpt(vN* z0ukC=e(sNJOeI^r%q4aM2Jsl+@p}}iMZ%Y#DJLyy>%L52PbmB1H_J>^YH)Byrh#*( zxvBV2aW&ZK^}QLL#0PWn;grbS`lM0v=(Q=9JA8|)sw5?;x;4?$q^rli>%{SJtSvuo z4t!(nXZ}J{tmjBZYYOizX5v6RoB0EtY4^E?%}ThlDD7;xANlh0-m2R@I`Y6BgYRvc zAy%k;7SHPVynqVK3cdqvN_$EN^%7)^Z<2EE1PU}+)cCvrZS5qg70$EmZ6YEQar*(p zfVg}V$@ZA+!)%YC?E`{aO^io)3)dF_5+tEKRI$3*13jZQVa4gfH|m7_sk}d*0O`k4 z+}nLSJuw8JvxlX%H7>j|jCQy7xa}(bwd}VCez4sY9`IQsVr$?>sc&fr-DSjXHIJB==Dc=O>_2cmDux4HnGl=vv~m|b3gv4JIi%1^zXpPBu{&aZq`$kVr8gO}VH z$IK_EmdN+;T|d`d`s$QkVV<@?b!fS7;Z56h3QC>+cMl{a^AbPbu^Z#>lf1s}*+BKO z*y~Y=@gcxUPkZ0pnzyS1N7+01PL-#HMbB%hEs*nUoc665HD?PXG(dMLQ`w%^FoXne zSYC_(A%EH3HQD_ zqK#UUg7)w|$YCUR9$>bG3T?UBYF7x1;P?=~&*(z`sfz0yHF|tIox*JK8!7pI;TV8Y zhaq{%`}WdC`sLPvm0Zs%>I(AwW}Kyn?JJJ z`5-c+`-asU(sp=I+rIb7IgML3zk$JrB>wPKJrJE)zHo=(d^`HuRbH*iH81k_gLn@f zRu;k~uuPeUzaOCu&p~@ntTpC8)cda`pQTanw_%Mq?H7}-KDQrqZfG!nB#`uCNfj%A zBrf{-+8ab^l+}&V`(ylu$QKKrn4AFJvp+N6tML21*3~x`x%WjSFZW9YWGWS26XNjI zBI|u<4-KR^aj*wULq#wbPeRxCaWtoHkk$l_5R^1~c@9-W6F16tP#@U(51pfGNcm(|4+Y&MxW=*&sWc`)o=2)VZaOljVEN@Q>(ZB1T z-^`HI`;>WnRj(fA-z^s;qlD;6!FiFX`G<&8jng+am;*rORcuRifW>Bik=5?wwl*K% zX6NQAHz-c*b*VofArJ>MaCD@(Jh&+&mtm3^n7+WK^bwsI!B(GpxK+${;e9@_yhjwm z`(5$|#8B2q%D=(8sE?OUnV{O96I6=SZ9a%`dq=4Au5%CR9cH_*FLMU#*KjZb8eUvP z`Q5v1$W`R#$8yXZ8sEijN|oZYh-}uBCb@dOL3JtuR-Pmk2JxP^6pRp)ZX{D@k~D_vTu06DT>0` zdcE13i7P8!VTp;?l0WP7W%a=flLvfj50ZcKUhMIK(0prqvvYt zpJ`BSOtsA#@xlOz2dkD3DfsB-+JT)8(<|@axw)ysK(u>DRB*(8DeBZt98;XtI=E zKwm4xPN4Z*wQYAA6G#hIupO0vhZRJfbtlCdW}Y~`!p`^|&F`<}j;`M#=aa0hl^B!1qK;ADpchzB9P!ps08So{ zXW}}=NiWDXM=iknTnc?bOLnhdn^~nO;IsSoOV(|ed1#Nl|0FSI)~n%ir#czfxYli}{5V&X7HNFM%{2${H4 z=zE6Doo(Ku+gQQxD^BnI`~nbVy-N(SDY{VH6J$@<*Cf82^bI@l@94&v&{f@j6oSd# zB&tP#Fn%U96@a~$eIRM&nM{Hi4D2k~8xTMQTj2&GcfS{n1Pg*ESU3AU-ApV~CP zf_3`bKOS*k?OS@;vqndU-S<3dvssFsxJXqUTHb7`<1rKu3-yQ3)3!-{;8vt!C zC(8bl_kDDRecHNAt&Yfz<$T_+Sn;K2PU+j>`>bRIoTByo8J?glmeK1dxS+!Ol)Za5 zh!Jjc6O9k9>SZpOrMJ2t>AQ!{iNAJY(6@nwj6(9#1nRr$9Wpwg!OSTF0e;AnFp>UTDx(+^LWT<04k#oSeSne1COdru@}l8OH#!sdK5 zfeojbQqaR`oaN$(u;V9WLxQy*(eY=nG7aXOLZ3Y};oU>ZM zro#<+fF!MERWcaPqBC&MK^&XgBzU3vc8H?15Wk7`R>Qx|U!{=vN$scBp9&g@S(7)4 zGgqf$oT$gMw90Q^jEfXqf8Wz#P5?*G&9Pvr1@Pd9O-rP#v1lgjW**8nUzMTbg4U_Y z$IFoyQL&|-RmcANlzJ}mBRXlU%%0~XS_UucR^Em2W1UW-rF7|=6ACVF*dFpRieqF1 z^2%H2XT~`Uait5dRKV&dVt=z`&$n1r^DNle_|xW)S>F)XIB6U1*C8)z3O1L2tZ-${ zWyDqVwkM*_l;vD#-sJ-$0DQ>)usXKlO8FfNxTf)`KV7c6Grvgg#~+b}|lA3J%fP8T5#$i(nN~Xpbk+y~&o&(>(_^KD~oo&})NX znp6A!nqWS(YeJ0?T$jyniq-z<)SmxHcJ%Nm^v{Q@?Ohv@16eHjltLs6nqOvApU>@h zr%=vPPn98XZE3%(Il3Ag>3!mb-dO=)?(Yc-5NkCIh0w5ri+li_&%4af(XRcoeUTDt;y6uTd?6Bl$fR+tZ4wQ zpk}nCu@%ByJE-2q25;2kuTCxr8O0Sdj(;h|K!*ITmP>HsG4iw3zWkN>h7#N5iZFkV z2rM%On(B9#^KgDIGbtIXO=8A$4Q z-PF~JQ+pQ_+_}l0qL-%KvHpbn#25+0rsuFPamw)pGNRBSd-P>GhvStqHnKznO--fR zy=o3HEGq%HaEA;w&-?Nf$SiI6AoqU+^5F~HmZQRkfN@S}>^%&T1e3}eWb_Sys{snKOi1NJG z^&8_%mjl~wKD}?(V&U8-Og#6MLBv0o)h>JAqR770C4x5xgGSetWzn z)9kMc>-_vt`Ki#w9q(jxNt4LMHe>lrUlOfW(OxQyxF=y-HW1p=4He8-} zRSB7v#1?b?Jz?-Y!G;lTxM#U9UE+lXUon7*{bJBm`SJa{LLUY9c+cDNxb%rw#wcc6 zrv(!W^}dxaP+dBW=(g$|!tMAHF{jhWLiam6*x|YU&q2>KT-pP)?G1%q4iV#|gG34? zDj9RZCm*5#n{y2 zgQoi}2O<`1X9r`@*??`mc(SEeTC(b^7jfC8ObS2o|7l zzE(=hhGkQeHd=4?nTVj#GjSztpFgi$JW_1NJeR||)3B`VD8(x(c>6+YT%5PRUiftc zog%OMYG#b*Gi8EqHBOCM_uau}fhc+}OK!^CR2f*)E7lZWl_ZX{B(HhHDff>S(!OL9F-l>25UWUt{T~Ur|e*AW0<70bGY3U~P zSy{nb z;J>sxSATZ3^Pir#x`K;+d{E-T_%DgUj_TN>MausfEnE$LxBV^jfY`qWFC4IlDHabdAV3H!eoySFw;U!#`3PAuf)uEBG;eYsx$!FBzeK~J+3T!+PvQh`%JGD` z=rNruHtrM3o`&@r=#Tj7KA@%dQsE-6j1{0c%`iJ%P2QC~_Yb@DBMCEZ>S4sME ze*5INuWHYFnqQy817asl+oQYs*VX$z%SbYrRRuGM_sxra)(>SIWBSZZuDaR_(k?vM zP#>6?cefW5G#P=XdC8^oD6^1A`-&}HwV{?qjPR1VEpY2;om(I@q+@+^mqJ$caeLVN zY4NpkKGEEE1e@T4g1LSDL7K)L!xb=D$GK6nk_JkaJcNBdJ_sdq!=J15Zs{Za9;_$L z44%i(p|?yg=W=Pc7se8B&-Otl+pXcvGz1}|RQbZuu z@lU2bo6uTt4#Y6nEw=JAeu!_55XRere8k|;J$%h;hMsQocUPN;tjGs97sV*ezhYmF znd+gJ&*TYE(*4dI;8RYZ-4@uMfM<3)c#-c3=1#oi@xlDQ%ldn?nnOshyEAp&z@J(6 ze1yxOv%ax&6wTG%(|+y)ceAnx-MzOs4MoV1rqE+ZGs;0GI1hz^X!n_ct=jX6+}dTI zrhyjOqf#gVkWIK4wddjsV*X0di=w?xU|0WTSJL5hiEm_!5ujv!1?I3Ewz&lXCG=%6 zjGRi!3YBQGDI?bCgy{PFRP%!q(*^tAtT7_n%kv;4fa z9F5RlCBaMGX=3l7g1g2I*GPF{JBis0Z8Nj%Ywf9$f2Z;re7xh>gzMz+YZKX&!2G~4CKt;`?9NR{gE({ zD)O*u?Gu#p`3RMEoSXWIRn>1erw^-#LLA0><7fTRmXi~T1B5B7Q?q5`t==L`Fy*i? zAK&!thcHyVYpoy9swEL%l+97C$6;=p$>tA&LBaNkgrv4!qBk{1YhEgoP0Ic&4g3E6 zgRe&Kq`GJ)Q&ky$h%o}JLmXmhC%&sEQm#|al*iiw{|oP_TEMNw!iY8{;$WFzUgzi~ ze29~EfLHba7p0_kd9*qtc5o^wB~)_T4`NFr_Ipx?of7-h_E<+zzxS7s9z=b%8;!aA zQJRaH;(m#)J-W?#&)x0&5r&dzPKMP6=LQUY?wmdUl(+)Jvbg*7rwk?LdgIK?COI+P zD@IJ)gjT(~c4(6Qn>g6kgg-*G?t240v;=V3_?`MR9=D#TlJ6LS^&9Pq3P$fBJ0M!j z__)u8%*?B*T`{yky}DgE!Gb4}`Hjvm>Z5BR6W1n#bi7-VP7J{IE4^K4pZXHG>E5xe zyGgZbjNlAuq&bJ2d6Q`McQ&2AFiw|n&evsmuC#<=Zn@-e ztc*PesG+3|ScvazT-W?;-nWfeNOewzLAn84wVjS9 zfbR(NLYLe!cBTM(M|$p(J()H$S=&eO@E&a#9R#K-BuDFm?U6)3V1tHEvt<>8l1?NW z9@Xd^ps>L{_U51*Ug{TcH3nDls$N?&%x#mnFDyWh_iw;OuE^h2+DDi20zg`(ta9~z zOr{gC?8IG&B|JrUHdo}Esb95HOR9}K4+1Z^U3TGK#Y5&!6S9hZ`^rZwiMBuaedv=P zgQV{K4UPHd2R;R|+joXM6KsM24X2{xGi7iP70!#+*~HwP&k5aTdIR^j7lXcE#6se} z)_Cqvlp)JetM*%HanApU`bf@f9``w@KVzd}s~+Zu@Y1$Vm>^Ym|J1>6K`1%m)0?dgG0OAVWtif9? zRHc*&HaipRiyFWvbn$&VX?ktPLs2|h?+V{}MZDKEj-wo7x{iV()anN{+hIVXMS-;L zS_*3=Nnee;k?Grhg1^&RZt-BvkLw8?PFJ{Yy$)~Zgm|`ja#Fr83O8A)_T|$ugBXRsWv{&@o&SoW%el$C{*k>c%?r+ zZrahGr!NNIBj@lhM=77oJLIX~1i$gfs6LQo%TK}^E;N`$(bx3;3(9o2^f>uXwR&Pp z9w`S{HsgPEg4PZE={3az)9myw{WX zn=$U!Oa7XbqM-|tyYTx5`b@YcEqrE6T;x2$Bh>_N?5l<-PPyH2Apszk_O#mm4(2V-^09)uE_CbJ-~?99Vc-@NnUt^T0yE5r4XOVsTTHgO|C z^8abm>M?h6dRwmNc}=g~o1O9i5%nL&hotur(xtEvWx$uIxh#?MII!q6+b3o2eT^yR zVNnbiLGpRI#yBVG*4pEd*AR)vM5G=jPD zem60H%$WQM*DMO%fHJPD^0Eaasbt#Uzt?|$ir@a^?_>SbkGmzDCa&W(H_H7I0ZEK^ z;bV%H@DF$(snXR-_e1@28qwX@_I<$iY-}$^{afP??tXp|WE&hGy^^Kd(C_qOykjV( z$y}5D{GK@D=EFVvk3^1*&YJ>kdNmN^;Btxe{>k?2LUC^2q<37E-I-3g<@?xdQ!KbF zI&0aHhGF+e+S4Y1C84MK0y5MC;xBn z<{cgHPrqDV;(cpIY=Eu3kFUpLp7>A!;TI2{Egtib*x;}Iq~Ca-sxhtsZEU~xeDK(( zTVj(Zo(pu83D|*B7Uk#9Ryj#7?qcBtIlyU~+djV^Gw7SHeJ{ZbsXG+HLlBdZ7-94^ z^)ruRNT0a!8}?}ahp*}5{ULqj@R%J}o%dB}8(DZ|JdWOqcO%TjyaORDiR{=qFDZDo zdPQTJ6A!J*osHdW>K^$vt=`t^^=2M|GG2&n=<5^>+H^v0-*kFBM}519a5MQGE>?b5 zCa1XwM<4msUkCxxcqW>IoDSsqROt_0C`2%&TKYcRTInc{M?Gs>;+yr)uiJmQALbYk zX)a(l2WR$|OnuU%>pVN~i+LbH8uga(VFccmkA$nw9p6un4tKcu3mCS!aSjO zuJnTus%D&VN@^z`>+eEc#;e7{jo|XRX&cyN9^L0I3-1&IlEOGjp z=$|zXFW@uk_7Y;PRyqSB<<~yGf^7BnK%HPZYdSw0IOm|#%K^^x8t*$Im^dL|qpa&` zkH9~$ad2jG9d?hS`qTq_%H{e8DrJd8`_kLsi+yg?DhbX>vOlva6ZG8JE2a`O8@|c*d5B~$(yS=IdTFO zC@|-FmTQ=^s6~-5(kA}vdg4`ujI+;(^g7o!eXx#a0?pz{d~V~H$zLyNm7Z_n<3Q3Z zpK&S`Zq~DqzOQM_(HIfIhL&pLOaA3yT^&5XN|7&59Q=mcMTBSOoGE8taISPL9e6WM zE&nEYv8iTD0n)rf`3ZSk?<@=C*~gT;aXo9IQt4jy(u6#FieM>5Q%|1Wzv(W-vUi0+ zhHnqYV_Bqhd?F);5ae-R-OlOh$Z)*K^RIXl!y&h8cHutR6-Ws&D~R)3BdJ`fJ5|3H z#@YG&EtIdmunxKKa66sv!9>Z3>3(^@OyjJW#>+mxXx!8|`ZM`%${6X(WhoT>A;;#8 z^;;o^83OF4nbsx;#MR2;tG|ZJxlvW9cTh}iQH!uqe6FA4TjtrbSd>4CKvpow4E4<@ z%U!tVP27tKT-G02Hww4YZ9#v+m2mH_EwaUO-dtfkdxwc|jul;P-RIP7QsM2nUHFRu zZ~9w5Bh%>7F&hq1=@?6XhvnRt2(gzxVK28dZ{m0u8TMjuY}ZgS5yYR7AF@Ebsp0UP zMD{REz2V=Dk$xWO7bht1OS_X}>?m3Sw zGa(Jes)nqP#T^eCc1CbVlDR7{rZ7~Y=LtLR`2>!i-Cs`r(=93J-f%Yt+=E^hfr z9OufG$PfYOVR9h(eCO5|1@O$hwYVxY{=s?ok5xwl`DI?NW$0X|*cZ3g={zzwxHusf zuumBoVV^3&y+aM@G8DU?6h~q@o~Os62VB9zfM{gy&l;nQgU3ZDYEaq@tTF8|1{zl% z`b$tgXifS)!n?Rh-?STFbG>}P{uFER_K8B)i7(ahl9Vb_IMJDM4)?xPVRP@F_3qxP zZ|pK7w0lnFYD`!I73(aD^fl~2Fyikt8+q3k7kP#3cM)Y(XGax2^LH*ad;sMvbTsg| z!~w3_^)#gGmTo8E*bZe^8P`j2QKc^~@XtD*S0_l+cYS`cA=n3gs2X|EUhnsDkx9ej zM2b6r7_`J_9+!C>nyWQmTnX;7fyUMid!#uPm7_cGf#5kK^6Me zq=xXQnN^{87B2C8UTP8}SE73wg7LxGt8|V@M+BGfLR}ta00ycaABKht7)ify;Jb?8 zM7z3@B+t!8nNuCCfmPpYG|b3)pa)6xU98n2DS;AQx)HdCYXeB2L^^7CJz-C@2bE`{ zJ%fZBC=_;Rib;I$^mcwfMY=8{t3^1Y_|;d@(eEJ|Uq2|;!-_xb60AFo9J~I|y zg&6oAV>vW;Lt_TbfVQ|Sn)lSYW8S-uL{GLOfAh^mt7c&1dquFh0PglA^I-B0{nqgk zF3)#zeu(Qi7T38+dl&1Pcz!rg_^^e+1CN~Fh+p40=dF;s1qDf6GFAI|kHkIasf<{E-nZXve!(SH{v zG6V0aqZ2Mxmvw>9+wCCV2(pC~W4^522qCIN93p9K?6-S4o?iE~`-%Daw)KiXbPz-} z%2w#WgmwekozG~aR4<>mX3*Rx*cBcbwCEIs_Kg3-`Qq)H*{Ce@*Vgq}e|MgISD)N< zpCLZ6y$Y{AOL^Y6E1>@zkIE${#~Vn|m*9h5!!iK>Z6`%bwpcX~#muwiLMWWE-)B4? zPLULu%pSVGGTQ{3fYC_~E%N=ly8d)&E zF4CfZ0M6tF+7Ibht)p5{d|<(YC%jCF-$%RY0UtBIQ0aWyhkC1L90oLY`&M?LxAah?Zfg<7Sv{#skwVEaHx0VZla2vrX|(uug`I|Pj)cmD<9J9Sg3c=nPnv*Gv2e~a;bhzI0}bI}=u0V*nhAs<#rpi?=C3b-_Q}MpbYMy>yA?hF`V<2l0~eX0oVx?vs|3ZeMy2C)zN-wGn<)`1|$o!!y|-g$z_w@uz^HD2;F z6%+U76q5*(*8&Yp1BrYECIo1V2}!df^%F99AWMt24#lhDZDtPyJU#p_kB9jAv}+U( z{gm{#=PFg-BHV~A7#ZV6&jI^TPa}L*n3Fpn7@xV^#T2xji)+XaqWXw)bUR$aM4syF zVcu2GJX4>>((X&|-CgtUXYPU!(1pO|dmPrNC)^)q3QE~8e;Iy%DOs}$JBM(^WsRBK zZ@Z`=zk-Ik?tsDp+#g3Hf0{bwUX-amG`DM1HR1+a7lMyY`~4(6Uc>FKVX^sq^_1@; z?AU6n`P{1g%8D_v_2~X^+9UVd)GhAOGZ}o$aj=Ux;q(Wfaj><%^?Gx2x9=+Zep;k= z`*j_@5SC|9`1Qw&`yui*n79f}b!;8o^brvS)-r4P_N#ZMHHtOg^nK1&qK&Ec1Z+7_ zWb_Nxr}hj}1wO9s`%V}Y0r(3p_w=_fE#sqapRFzEwYN59p54!Q@Co)FV`QlW;|e3% zQ%_DC$cOOqx-i!fQe?ya7jHZ~Z@Dc<>kwR*?lUfv%QsLKUW5$k%jJ-3@ z&AH0wnQMLObRtrWF?#Q89lT^;HaK_BE zqG?IH=z7wm_qeBwK1z74rZjA(=XM@McfpouTBiVPJ=|z zN;pP#j2P%8o?<5vqpyt+41PV-FwZ)Wd_CI0-m(AyGm2v6e3LUT}O`_Y~fA%4Jucu#YDS{i?}RnCOmTKR&Oj4vX|f(KC-FnYLxEIM&} z1xzJf@fztVVqTR()-{QNykw`{yiQ`}0~~;>(tR5~mXR9_9PYRDAl)yE7iok;n!sx8 z=gK24P4`SMY=1{y0}cjfRT#m>oD`!x3*iMF6;|LSY5wq%i89-srv$=xBs+Otl4S5P z3QOE*44{?_SLVF$v(ROhC=wFyu@~kH(^zs}r=wpSN^&k+;p*w?heH8S64VJU z`myZJoAyl|ZUezqvr-YFd1xxt0+?-Pe zZ+p&K^Bc?tKhEJe>rIYTSH7>z1aW+Mmh-v39=DODGax4Fj_j(u{tTIFA|TEsqVo6b z0eaiIUjYXB<9;@W+&J;V3nQP3tQ=L$LO8?T%TcR^#CmI z7+LAD4x=pUzd@r1vDa!U*FZr5HnB-u!DW?O%{}qC>2ibl(fnt?onKYf!V`j}Sfja; zIm0k#t3L~K+&@2e^nA2v8LM6UaciaaHVhb^Gv+OcA-Cashwh$>d|Y&xUcW%J&ESLs zgKYv$lE3D7e|mKB`-+ixdQlqV>C%XI-_p-%AFpR0I*xLtpU4bdiGkOfQ+y~41>G#s zhckdt-ug9*LqRr@yX`(E>%_Ihl;07u48))sACTw6q<0{x$L2uqJoV~|+`#vbhk=(y zGOw5ChkOV!mpFMF}@N{03+B z2>r9)4dG{HQZJc3Shk#HsvN$3gJ_7$y}~@AM`w@zt z_IdW9c~O;dP{f0d48rCZn(`)p*s|34xbL5exoQ1HiwN;8I3)sS!Y=bSb$(@+`{c`K zxcrI$YDy3iUIB$3SX4NGG|^wVRKhXkbX3Ol_BnSnLxrvP8h$}dMuEj=5;`CV*Tz(X zb_WOT9OQ7v3SW{Z`wqzE#gL-lTEZOe-ejC;!0!Ha6I^{CmvS!ecxh=7P2RI@3vVIa zn}~fe_iIm3*1c_Ro|N0#C4&{o1qnacr-&zmfAI~W@=TU#U4ak{b7KVcgMA;5G{NR4e9>%d-o3VFw>6bmBx1X7}^1F!X zdbtSd$rT?Drt=E-g(3tW$m_2?UXTEMKZ}d>n5aGLs+^aQRiFFC@A!UeDKy zqJRozMzniL04s5s%rak91w3)m0>Oa zy_$FAe`QWxP9OF;ddXT|uF4~pWPQBlXEM|(iN@MlMXUPqjpUKlQ=jBzn7Sb>+qXq| z5;2*it9%}5l@;IXPkv@pm1XN5jfz`I5&hKnQH4fw_KZd5J)RR3;)LQ#)AM)A5iyEH z-)f%-(EF5rY<2H@>!yYG&HtgR&7ry!&36a?x~fFLHdfU1ss4J~+;b-0*Z3vV)7TRX zDkp2cud8}6x?3S*u43~nL7t8w1CXnr<|%7)5mu8q?V+lFeA%GAs2bAc^nukU^j>c%ojcuQINIG2IdSZ~$)UF+ldqA^0G zO<#dH&cb7e_T-GjT{;z78znzEK*OpR2+kd7__BNZX0N}YK)`n5P-{EUg8ZU#j*qcqER zB;VRY3rGh|Iir-QT=_n#?e+-B+)z31#_>Ll!k3_^#{E>(2iGMFg+D*w7qQ)b3GO{? zX5qwsDX!!+%u=>D`e|*VFT*=!Sx_PGEnoXeeq!N z@F5vP`4$1jZuQPostZxXocIs-D|&bv`r6L9rF5=h3nXc%DI% zfZGk}qv?>u`}EOh9`Qg@_$9ujQ18z&@DIkzoRw?l%Gwq@d1Fe7a^0Cks`Wc-&@$09 zolD z=2Wx#o_Eqj{{6M%`tWVb*W+%VNMYa}>IOVki5)!FuFG8R@clu-Tk;pf0H7ryP#=wi z#4^07>%L~jNM2%2KW%-O!#uYt&wZ4s-Zc2?Ofqx&N>d;c&;Cum&FW~WgExVV``Cw> z`45GrRuls2*YUBuP%~kyIQyD~rim;%VL$K?M{^U+G%%sagBrd#(bIHaj`w@P2Cub$ z^ReKX^Gr*G{eZ_VBayETn?~mQdbD4jK~B=(ywmzK$M}BbgHMw)%yA8@x$STB;zB+B z`7+?BZ@&J#9bpAC$D9Dsp~T>!?-V@^cO5xrmAB_ocpR8qWw0hz-m7NS9g$4 zbbQv17M<63tE0RdlF1xJkW2Cd`1bJfGodhUA$er#rvd0I7xj|BJi24?@<5?u0nR5Z zvOj+O&qsbuL1(g>j}EHMqyQy+-LAwF8Bju46`>9l$pjHcSiXy`~r!XA$F?~Ig6(Kkkc z7GUIz>)&C%_V@Z1!B&sX>Cds$PaSzL!j{0tL<+$;u*3pn4Qd@!CEq6j(=is~1Hc9m z>w*M6AnkYGMEMOFr<4MYRh4%YmB{l&4V<7dZKY{>VG}=Ktu_%HKedlrJu?OXRVe}tI<|Nx_7w8UOprZG8R?knfph2h7&(?8`ZsbYl&gl(&xT~&93?uA=53EcP zZK$v{;m41|c0^n!UWg?29)qNB;ln)yvATWlb3I1asJgYr>GH}a)Ez*BqgmIk?Z2Sq2>&@7N+CJ68a7EJ<@iB3jfvKYQXPLZ&{5cuO#FTLw_)RQ-G_Rdsf^% zEdUQd+$5#vDOJnSNMF~lSiOc(?vL^|XUJ=B^dtExodV}`Y(qV~G;^p0prUak)vL;v zli)nA-&TCUg6=v}H-=zlt0Nur3pzz94T_h<*0_OUpusnh;*qjtO_3~60g;UPi>8Xc zkn7TBoRooime;ulYvj!bG#3!bwiAO*e2x6FY7;dR1MGK}@ZgHgWWJ=_$39j4^|O;@ zRANMr$s^yQX=7RjZdl67n+@Qz9Lyrf4oYBBtHsIX zLtB47Q-i@w1jTxdp0U9#?{&6W@YIZjBE)PheN|nko`(R1k+vmGCdY@y##Zu(Z zy}Mr^8~FY&yUlfy!zWWCd|rH}qE#=CJssmz2bPLq zz}G#Ncafir$D(RLqd#9EJXpcKPX3k;jeH@l823~(X8g@+q<#7Rk`x8k*Cpt!S{l(0 zWsZ#2ioeX{b@6LA{ZuA54k8vFhOGFa5zX98hi}x}*;8;8nQmzpc}Pn}V{%>-j_B|$#S@JECfsJ_d%AjSOMeCgI z%hDc_y$bXU2!+Da*g?KP+*HxoTvB`5Wwn9JHyf(M&_v#5Tk-JU@#Aw`PItQySa{gt zN0EW0=BgMI0LM&@59n8OAv=@yrM!IiZ+`E)fymZ{bmex4&&0gGs}u$XivUB`F&>Bq zjz_syWu|*%A}s2k#vKNE7X?Mo?aJ6hp4jqw_+9()vr|^~3mcofAWNrx`iCI##t0?A zUj9^HZ&pM)e|&+D<;{+q-jdtwgC1nausN4{4aR7{p&fnh1qMoSdW7C{+NZYnk$;sZ z>ZDNqbb-T^!wTVkWvO)mt3D`DCH-(=A|zj~eUl0Ovt9?%w)!6Gv`0G_V-0v`^i>i9 z1|!=4nH(J*6}ap0=?7Mogh2D42v0;KP`Q5B6x~FIvnGqQKPm%kJjzKd|~Nl~S(z(Y-2ni-labWd^xy=U4>SQSc4}Oun1SWT??>R}?Pi z)-TU=D}XsP1r*M4JSO{he|#+NWad7xuZzdif%$OT%Reqcm*hg@PXdGrK4F0(Mv61X znfk$cH!8=xMRqv@=v!s}=>=SNcl}Y~sG{<{70e~LyeEb*^yCNK+CCFbuyf?uyZ-K4 z4O(m|AS}T*&H-$ruZIVaV;F4rtj&|rnfNSw$}Sg*MF55lcdK-)+CIZPML~W3Xp@)PW}dfBaNqmr z0*kGK!YRVzaLo2O@?-1^K)>A=>JR5w{`7s=NAu_ZpDox-ck2j@DeINE{50Tf9&gidrHopYSNibJpFa~K51C6;Pw5B+t|@#hI>x+jQ##*O50U! zqWlmJ7Q^0^6pRiccf1R~gfHRC9uIw*->FfVJYGb3#NanSEDt0dbJ~7elz^`4ANsGk zV6qqwDL=ewVhaRML5VI>!pSLNkb+k!!CRs|b40)qia9_q+bvD!Fq&O%@N%%5&wM`E z^p`jA=Pj}V5}L%n!l01x{r;h$Le3mS;Sx4`S`}{Ru z`1dS#G=C`f+X0MFuwj38m_Nd;RKehSO=NeQ_p4dz;5}9P-=6x8k9}Q0L&wI<$7`@3 z?leboi$^GJibjt@L_#aAiE{zOXK8h!VpUOaJHRMp+f zi}<;oAvn{a0^xRrZq86>Q9_FfJNK>gT6 zd%(7&mmFLL?oIRihiouGTg!|_lgJij0+Lz*X?3!7<*~3-Kl@u|{<<9A4brFIgDmJc zb z*n4AfhIh^`n(vlgTVt2%=gkzWT<*uHPupW;3 z1+E`>5A075V8{+z^^S~lL+I8NXmu}}b6H=NePLhf9NNE={rlN#Von!(VNY#7EglS# ztwpBQ%6t0z`9>XD-Ov9^-JcjCWUWSpAay^i`<;nj4F3R7l=^4N$hcK6HK`+;l+=S=NE#vzII?PD9 zuz!>BW%Yxhck|}${jCWt<3>m^96j)1uY`TlGu>SuwVz{s_axH_G4VdUDE12!qNj40 z?;+Y&dX(?m<9#H8#_xpng3(EO*Cc)aPujEmAGGHp_$7~57joZ^e4Kv#RrT&6SjqzWuGUpftkC#S;4Lq-{s^fc${Nb{ckY~eIBv%a0 zi8jusvtX3ij*(c`k%pJxIqq$W1MhS(e#Yx}LqG6sG0C)ZzqhK1Utl#}SL3p+CptPO z=-3wM(0CQ5F^lU243t5FtBtM^&HD~j>cW&@kFQivuZ1nA&*>A~(cZLq16x!`^R?4G87 zf~z_*Y}lV9fgV6Kt|HAY8{eFFJ%#(ZUsjWvPzuqP5e&z0p(*#-Lk=GgnnzdSTklHo zOOLmT_@V+)JwxDbZXjpA`~4W9K2uy-XM}coLMy2UHM4co2JyTczdBr$eN`N&JSpkU zInE>ERxsE^JAzx+FLFNEz^OOZdWIT)EH2w}ATH}%I-+o^n>yLoSV|lpYI&bS06u$O z1;?`d>2z*IEIupF#|Wi{hj;u$l=4ykn(evwmx}DM7!Jj|&ArUWua(rHT+kt^!5i6Q`U=+q~ zlMr~Ktz(b^ma*;g4gWh)q(ISRn(MF9zb`-Rk6977+kO8f8N4#GX%)C8qCJP-*Ln!B z^eHi(4v>|PhB0*c3IKBZzSlv{-oP<-OvAkppAL+U+)I&*1l#TcD6)Om2vFZ{87|jv z>SOgQTanl)`p{Q=o!t|gDbC{pCA- z4dCmQ^7Na~Yv4T>|KvSy{{P@T``|sB$$#>m=^gneDYJM#IP8D&o^4OtFUdRiawuKn zIpG}=H?TrNe+}PYD~6{m>&{DR-c{8;>)9dAZk_%#y1Lz$&xy>0Ejx7|>Zc^F02ADG zjM`s$p9D-i68y`^j)T9@Rkw|~dPS$doZx$SKQ8L;6qt(pxNOWJl>UrCgk94mZMAi| zn`bll?JMhtw=rdR&xNp&kM`GmL+n7blc$E-)v}tdsy3{&UT3Vi%ix>J}!rI{w0l3^UDfWZ74m4I(h#*!c%&U5j|^y0=g{Pr3JG0^FXezUFyIme^F;Zf&^R&>;WQ15h@;p^_Af^GYO3Wm$p(eXn5pX20~uaKJ}i-UsqqZdF##s0WOBrgc!ao18iPt4v}T9FX=CW zQRMZ@pZqTUVsetFi9hbsxOSGF>#Th(iMR;Q=KL%xF&9e8JsjcsEm=BJQQiA^K^%Q0 zPtJ{&GQzr1;mfG_gat%DRKjv!$yCR2U(r>{iCa%N`chY~<~bgPn#@S3XpDeKUuXC> zFeDLPhwO@MXqp|5y|!}&jVKz&VN+6zomKJO7{8djWQX6`x-v=qZ9wYk15tp+T@Jz2 zi-8z=E{EwMOM2_nbCc}_BIzd+51OxQgE`-i!rk1G!)2eIpY{zwpg`Vu`539(CKGG7 z4~#2;d`*vbf-7(IYMF1Lc5PXn4offT$~_x zH*Kb0CdPaDYtb(!I~m;PIM@&QG&wepwzu?w!smPYtUOXuIl)ro?-OD&Ot(m^FPrv~ zf9z1LXc(N^S#~{~>G-27dfVPR+9|qX4p$~KFCO30 zfa7X+`(rPZExTJfeQ@jem=PqT(BrRT-mT;kqi^yVy?%}{@EekD83=y_nUuiHE5%>< zFe=ejq)4kON8cHOJ5X4y`2&6HC*C$Lsjf+)!iY^9?$2^UcbNQ1ULlNL(z=l?Gd@I+)p11+{M6}gH++ECvhJgAv+vv1#TtYdOl7w`y@B!mO95iccxCVH%gc9 z>$MgYN}$$?E0%(or|}N&+xhTG|MCXH3%R`#RdTK*(M!u9p^L+C!P2s3%3d-OJz{K%X5b=M~oh6I z+50!!d8vz|7$3BCsITZ5J4o6kQV*d1RNJ?#G*5p}7l_w|56HoVM`Zk}ZMKLj?z>^W zl0?s@n3FER%b5**Cpld6XEuXp3i_pT9fmsCgFFVU6-;L{Nn{LQRGif=fI{;?>(0Y) zi5-TbW+$hIH1%~hXjvAo=bnygRl3T%dPY@M`XTFn07nHN+hh@)*rd2JtYt3^qXISbnh)_vdTKo5>2CG?8v#FrP2i^Gk;LIzs~&eNPRegfDU5O z#_jsWj)>cbuZU#R6ZyFhn=pFkkoej78d8ZLUMtBu0wz6S!@(l+Ps%E^3 za%@fdC)HU7)w#&t=^xekaANM}$!6ZK%!dm{MkdaOk#jOh7T_zr>K-j!fO^$S0s6=7iZ=|eGTc^LhfAdvzlRjvCtx1>ZO>s7aJV_5(*!S$@KX)2gX#V%1x-0 zr;qL&!zYv5lu`6Iq0tyCS5foVvqk4BS4vJBxEf|J%37d zgU+$9tL6G&ZR=NgUVN{P6B+@zYsNZXMs8>Fis22h(2v*N2lPQz8U52D4Mxi;bz*;g z&<)$WUSGcg(GK81V6EW@T}K4R%~SMPAY;+*Khrnt`lJgouEF@I*Iy=H9q!~0 zz1*nZlQ+{j=vcqu)1VpB(OUfF#cuc z{PF_ep*@Lz5@<~`-V!0O(Tk^_)A=>+Lu~LHf^uJlJNS>nE2;pUMG_pIjivn@J_1#`2NH!Y@Ge(O|#*eN4IH*=HJ1Ek{)2q z$u^&A(oBqlBPbl+Rb{ZEA#cw88Ee#EfObayGQGEe@ouHJPdOMwr~2C}o(o;ibZM5j6+0vPfXF;SZ*)p?dGh&16_rLu+P8Z_v<^C1 zs4$9D{s7C#a{hz{t4TdF-!~O1aRKdy%u`&l{@yosA)vVCUkpT>KaRXiOK2z%!qcDo zAxh4|e&T@c#`pgx(b@hN(b@YK(HU=YccwFpq5qi95b-3YBa3l=oP)FUeQw=DfCkAW z*~h@Cifc#ENqS(eOAo2r2N`}~P%4BNMRgQE6$gm(<6OsPvwE14;OX=T zbHn;Ee@NXkNzXR^f;yL+_g_S3dM7$V?EG({^XY|3u?KJiYoyl7}et9KJ?m|3+$+Zm50F^Uc3M$KvEJTGPIlm>7VN2708-aDVv0_$7& z7Rrf@q^{%-W=R>NXB)lSC7=#a%ny^RJ%VRglmgclhx9G}xtIq(kil2X~JTxYHZP^G{AI zvRgl=hUA=y-;<38VV-Z2XL+zc%HLkVpbm?-SHJpXCew4jg>=0uG9Ioq<$@jm?7^Br zRrXZ2Af}0Mb3vnS@LOK)siT0zf8PbM@fdibB4$+YVS@e&_8v0csR|ATjh5D76+n%- zfzRW6Wzl_%8Ge?)abEXR&!4?tw}CP!-J<=Lm6ikh5yzGHaeH_TRxRpH<|-ePb9Vi_ zyvx1Hu<&qK_IL)W3Np44`GIyHX*Tr)u^P7df@^HOaIU5F;<+#QWyMpH5uvxj;>>UR zX|@4(hWzmJFSxUuzWl!oH>6YX9_)E2pTJGORC=-Zx7858HdP647 z9Em#&L!-N0z4pb~Q~%sE4xXanI?-C?&Wa0)4gQb}ro${BgQtqNgUxsjZ=R`4_?TzD zf$69G>af~K?nLu)aWEw~at**egB3C*8T!M~=$ax$YQsF^6GlLO(C_!}yTGqvWK#rb z)G2-3p2o>}{DB@5@M-lkJ@%hhdp85yy%<*6lBD-y(@RCHaS$pi zgEwXTcaWX!GdFd4?iR#&JVu_h(A6 zSU_YQxgKE`*e`Bo)1opN^YN$hH>L9Z$ok4*8AeSV!9O#q*$5R9sH0r^PJ8!^`LvSU z>?^W?nv|UUk@kzzQ72JLHCXmR-HR37AOKv*;&1jQo(B&SxS)%Nzv1ufYM$|_iTfKF zqyZ9-0rIG>z0{D>JoduHvoX^jp?mjziMpSjQQl5Hb$s?*vzGMz5m}Z#g_ss4+^Zky z93O=J<4;f2Wk&BQ8GmWOaQYY8UJIFaY&-3fM;kp;9(Dom&?r* zU}H!^p-F-qn|+7{z^#iV8|c*HJ&;r=bL8 zHHQY|o$?paZo8ZGok5$6_)Du`(vXT4+U-dRuCjX6zl*=`yxWGXuHl!-r#eU@P@ZBL zlXfI(1^?^WX!l-M^_tF}vDKoh-Hd$z#t=FxKqKQ;ja{{6KxiREgOce2{wwv`vrk2r}J0Ad3@Ad+AXu zFVu>qSs-uik8)bpar6x7ug%*dVW5^b(Jqu0J^-#(yT9&!tH8rwnPJsn+|^dzdU$>6 z>y#f_$af(4Avf~;o+PJ>Ud9S;zV=2J944N#_=?t5na$yhSHZf2OSmYmYRLYu#!9- z0~BDtn&(mol!MS-VuNn0M2Y})jx%*WHN4H<&ye%tRrV&{P*!TCxyNouEXyW8`+6Ll zJeJUpLKY>$1r9Qe?Kqu`;&J!dOJI>(1>dCQ=%9iA_Q9l+)hKWeYZF-Wz)`_T|GK>G zFlV?39!dTz_q#nBAwLZ+|H$)^th}*bzv|=Hi}U)W#-CD7{b~^(gW_#8(|u!^D3x>? zT42~st01v&xX8hCvlKK2!0nc7^(=UwO#wL)pGl9utgX<3p7R)?$I(R!1BITGb~I!* zu|KfyOYrAednRSerd%|M9;>q?u)62y?ePf;z4_OX{~`2nq^HW2?8R{fF>XMEMWbRZ zTt{$q50udla(wU5cqo}U6}FE0m32lFK6}{K$&Y4))6py1V|kU zH%xIH_6@OuS$Lx^l3jx+kdov%fY5#tWZ(hB%h`M&?We+vc{Lsp2mkc+#);qzQ>iPQ zp5L($jbC+T&;xsW*yTNf)SRKY4$&o!ljxUNiYc!{oB5xg;-BB`&Ry6mnd|%<08=zk z^V-kH$v%XLLGdu~8@4&@bY69wdnVoI(hX&J>6MvBR5naihz|GTlB2khS^TxTKZ*DSD} zjMSP+Omyomc$18eR+I0(1DU$9d}SjBQvf+qdhps53z@#eRFs551BH-o@_W|!$CaITKU)+&M~BflDp?$RJrpAfB(V<^XKm| zb#F)?JeSC8BJ6*;9~Or>9rio_X51T~22H!t+|T~m)^>yIMYGU-$CI?yY6K;hl>bM8 zKI|0ebGF}=`!!LV(1ieU@WKiKo<6It-W}cXD>diJ{i_duY+ocd@OV$pzSt^1UJ-m> zZ~GfN_=fFD>isV?jlR*mu+P><^Wxxys>i~nc*ORK5F+T@FT_hxLLdI8c;=tC^K)TP zJ2syA7(g`~ZLduR>FTdVeS1PSz2nrdV+pK2MTOgU8C<_xxryCvq09HEFja{c7owG+ z-`PJJU3J0`b%RU+SH%A@otpe3T(kWu!CUeFC>HnYFnZfR)He6yYwh1n+JE=q%Kr1+ zFGdEs{%^iNYK=~a(PiEq_wPjN?_F%B3X^|=5^+~DO5L&DS0aOPJ!{0e9}JfMkk}ox zOT5kSukUrIJ8Pgj3)BBobm!{7=+4a_-Ps^WT&Cky-CH2`!-?xzB0l8-`V)GUgnmED zP40cD9qJ|}40l0dUa9V*beA?LiVYqikaKzb)Hrim_3J^b2o&e?bc&y`R_Db<3RaQc zKrU}CA8|KqMZR_yI2xw967lK4Jk2iN*Y--4B${S}e}*UT8uGfl;Mf1gcy8oB#xuh9 zKgRRnpM>YvzX{K9vc6aUAB5+jaQf$d_kFKrdaNX79igT8G>CN|v_j4}3S|9Ve~>QS z?~=gn>-7-6(bmr zF5?9%PGPPe^)0kKPJv1Gb%1Oz^XQEkgOCL9$8}~c@k1A1*s##c9p2#UAwU=}9vb$O zSXj|~t$I8#DcVl-%82Exzj4h)dyPl+H3ZPc$7){=MX4;WRpa0J=YDRI ze*Og)03?Z1!9Gtfg3y_7b@(^u+47pb_JEAIPlRaHu#|mt`R|3BT~_P;xjZ=+6nB0mxbK zl65Phln@9?MfE33dFUFvZPUZ6_$TA}&LI)H{G0I{{e$sLegLMK&w4eve0D$`zDb8f z9aoQyF9Xj+8tZrPt+@WpM}WkotE|lPP@LvJIG!0fUrTm=z64Vy`_L;38-a#x^~u%r zyt}M|!gi?dLTk+KwYcEA6d z&!rexS^6d2;c*g3I2F{F{`2sw-gm^f#ywHMlz_J21?Zn0cLhoufaeqN$qy+B9P{mo zY`?D%#`}Tz$XS7h(|ucy5|8Hi$D>1s`Ut2WK|clVcByxofl47=8WilYf~Qd`0;rw{ zNR*?REJyya2mbrQwSX6bH{L*|Dz%v;ROLXwQ8r;-+c1hBPit&u%@cI@BD%jEyt}(F zhXes5oG`Ep$XLu5GF*>`b$T5!tH=3W>`);LEeJ$64_!s&Mleq<7@^LG7eMBAq8f7A0IZFn!y21 zYB3AKU$mhZu3xUw%G4YIXl&8~rn4`R`=UH~uhNPB!Ft~P9i;!FJyY3!X)Ojb?oDY@ zwJ%5hh|fQQ2JxBZZwQJ@*+ADr|GEo@7ACXd`|=(};D7MmspFo3eYM8Uul`MZ7Ju@8 z5TCh!5uacGL3~~Y$N&7B_*@v-m1^k@PH(`@dMT0H&n1P?lSZSRmG>I0Nb?DYl|MuliEZ;A&b6>g@asK1Q`pPxF^`QL-scIBXdZ|$oI8wLTX2mpzHP-p-j+Wma9+zW{zkKndGxTNb zT^151JH-L7sn(&G%a?*%NOHHLARQEMB<}fIU07MgkZ#*DFSqTw>$p@q@Vz3cCglDr z2xc5l|H)BjPxD-`m#3QrsdxiXSv^n1cIOwWH~pH{rC28u$^|b8nDot3*tl#^ zrfK7TK||gCAutoW9f*fKm(QQo>Ii5g9e$Gdr{;V9YAD%*8|qxj&HM|GL48x22h`9v z0x^~P){$uV6ra9}KJr@cOWx;md091io8F@B`l+s;%PyL4k9RSW4Q+TZHPwhv?)r_( z@L{TEy_Zs~961u)e^8(4$GJ^J7g=>9FaO|eg$_%uNUuP2180E-uToa759y0qi@0SE zETCdlQwL?q_YrTT<9euvm+;A*aa%oUfJWfRFHe*{MOjt6w<0Ksv!Nj|{tH{Y+#^EHdNr%q}ym+QA^Rrkwo zVES=ElTk&7d+sP6!~pWBCzpEtN!?y!GGEb$tITzP7|noa{V@7Xf!zo5fboXbeGWGX zJuR9gIY7NE3(FdFj(YOO5)GHTGj!=E4Du?}2d^~n2y}XM4SeYU6Q(99I26EDNtf)z z&M+JX_hV9!J_3T0ih;p{W8U-Vh6p0by>>!HJ?gf;nO6Vx zRBd&HwBpVn_}q4~>-J-fFWx#?j^6#)pRRUY>{4heg?${~0o;*h-8)qpmQn8jk6e74 zy5531y+P~tVP19eKL6D8yIx?+f?bfP@iDgL_|_snJx=fBLIDtJY#S^y{}*d-wymnR zY-_)gk_cQ1h#-k5Id_stB1kUq^rzCtTKoL_@-O9-GH36jn;??37A>O2SJTXT4z-a& zxTY`Z@gOHdeAmMIa$nev-jC6B6pR0oq#cl? z6VKGzVSV`Zs4me27mWT@K)JORae-+LEk{+p%}dqyj+&;Vx;)q^Yd)}GmyqW>m0wUh zAK3vp$)%{=eIgP}vHo`I>o9$bB+TK$g;EM=tv20l#bu1HWAiM&*&%nzo8JwJigu*o zdn2y1iu~Uhbz%vEk4u@>?0XW3$$D&oWk3@t95}@$>xXjML*h+I_!)WYC0azLkhL4l zWaRG-8dK3(KfyDItzu@N#ZrJ%iG*Y0+q3gS*9{u-+xd zPanj?#VS)cjl~#y`ET!fFewaBtdPa9cygT+CVC+dCTg`kUO>%yI0o~yDK8H8nB#a8 z`W_lWZ$cgSd8_iT5eboRLmro39AELT;#cuj`wFMV%NdaRc^@G#Ld{Xc#`oD-3}vDS zj)oT~69V6<^GkM~r~C+qmd>(~Z^uF2OU8oB_h^q73Rck$+`i7&M`*3P>mEcs_r<4M z`@TuI=Odtm7Hp38yC}b4bdadSas%7q_xcpwboRilNxR$GNZP8^l&aoem??+9M2o~O zV9W~-?{~7pT3GJPpLd3H%XkrMFgcYGm(lkuGnksmv*vWW6f^>^*CEmCP@+U7@OmZD zd)-!lsvsaMd4vnb9n7)QVc0S%^8&T65Q~FT7@3-DM}geDU6Vx{{G!{ddO%r$Ns(PG zja2%sUvXIjCI%2A8~4EG#6|DV?Rt`K^bvnczsiWXJ4mf}m~g;pONGsW%z2O@9g


5{kNK&AAq^kxrh{`HNZA;)xybHwcuCV)$mrRad;6f^9I<6FuFhzk0yXGjUA2$Z z>PJ{r^u^)^@X@@%lyKZ9VTKCt@l;Q^%@0)h(vH3w;#%5g(kVFjV41C#DJv*G?_lE ziI;C)V)OcQ75+HV@9jnnp;qtL*&j#x?Vd{REo#yBk0b3^J4c#@{WjjV{U8(j4@LR} zinQ)*^z+3^qGY{14|XA?RHHV^{2oheZ@~rmMjnxz`ALYY;gK)mRgO`U*!5+pp2rsc zV$7%e0tE+rx2Ha`*hqoI4B0yyKY2jrdZcX7c@+*O4=SkEh( z+_PH~NI;+4-_3>lDAa=jWR=&C`xPmbK+;5-9-1MfJBJ?e)$?6C=W^g)%T^;`1w^njK@yTM(pz%-MpE7bYT`^*yp`rmsdWQGm8Rg zJoOFBz={1XKUV|v;KmA*@)=D_RVQ{AP#3^qd1M*;TWx}sAEv-Kxi)d{Pb(x)rJ2ED z#f2tR32V|NhTD>BL)e^4!(d(?I}pjU$4px+v?XolqZ@mfBLG!8*;OJ{;XI(A{ACUtK6GaPU&}itBo$j7kngtdnvCYlKW(zGyLM5xzp+QT{_dZfx9=3 zOloT>P8pARm(Qc04y6>fqh1eeR7V!vWqh%oU#z1xe6?73$|opA63O*dePdr2gpqQ6myp~Qy-0r@MJp3M62JEid#o`%wu(PKb-*9_CfmXf> z_x$OO4hWko6eOe~XqT#If79H+z-Uj(I-Rk*DxwacKprIwH8O(32y=ojQb)(e*BRpm zl@F~^$6pzBaaq&R7gc&ehN(wN6;@E7Jv?Kov%3dxMY*jwaW^YQ*+mp!bt2;f@AvRduhw3#9v)I(VAAyI3{$o|shQN8uok+PQC5^WQr za^5%v#ZQ?-fz*Ia;L)$-g;;@M9*WU;d$;@F6>(U02n@Qjqwb(brJ355|9q~L*SBW5 z1?4$=)WaKLI!x&mC6BW02``4GV>xT20<3{gaOzr3=-;rIOHWr1lp5u8w}@_zVdR(S zZrQO4OE!j^HwbNiUqw>@3krWQ3C2FcwE;irv4j`=6P5E&-=23+t_9}-XeLEH(9_Y} zhWAiC(2+`b;{>v*>JPX%ctRV#Jo0w(<#j<7v^pO)!Z9~aB}{lysCE?o0C9zL)Q9BFmChXf_a(CgYEDkHLXDbK8e>NoU>!g2x>D-o*xhA)i;tCT%c2D=N3bF`9J zYr=o>PNI>n+`st%Df1<6H`l6;F`D?Cu|F`l)g*5zM_8i++;c**F*LcL^4cyMUSTpW zugi4@X-bT{j|Z+1a1cGn`*rQ+-ok%Z`CVS_17A05I%Cd~!n-~G(sBE}FJWKUjbmsP zC#8%ehjaBki&=SA#*#!HQR;3MqJ`hGM^Op9XuikTnlC zA3$0V_-WWUe>&qX?M0VGX_x~jPr}`d;d_{K1TEw9hz5QU;l^q9D(#cm8yB4=#CyHcUr zE%dP9J_H#p3VDb@lBzfJ9G19>v`%-p4)2}KFdQ6ja0xi|pqvy~U)V$hb0-AM@1l#Z zi|~_~&Xv)7^BS_dPhe7)t^T~qC-gFOCi6nN1n*(!&v-2h6V0*PjF!fun(MqU}?<5!kdO%;jqXJz?tKZO*R<@y-&OinEH( zn51U^0iWU0fZ3DXdStJ4*Lz&;=En#jte{Rs4VRN`SdNuUR(kSFia@u%3^(7&Id@$p zRNk=J{T{Z5?s2>c-17^>gL8hw91Q|qkcF4<%601iP}u9gJS=UaG%n4CD&FMAiTB~>8>9VRlW*Hj={cqz zT?0cOIeR_OLVSYMb@5SEzrkquiP~Hs)N^18)|h{=*3f~Rn4)TO_{;AbllP>soKXK+ zak0GhEnSemwBA5HgPs;Cr`A8|`%tPLsjUM1!(R94;H_FyZz=S;Xpmdr0R_wXqW|@K zoEO`NKEQRGf&TlRQTP)V?`O!8L^5_&3#M@jmn_%1B?VkMs|Mk3zb!>VSy z?x$OI9}{R*@6<%k@-=M%g%e5N&M|EAX_P%FfMj`ZKym{Q^ro7`0#~Ah*UN=)_{*_j zzf2w4N9(f`C~clf`WQ#TOnu*3&K1J1apL%s6SHNDt8~3kTXqF`;a1Ph~x-lcn|S7(i6Fd*k>v^nBDo{s29xJQo8Q>V2&PgY2eevnd)DQlqF#zZ z82g0&EkPMY(I1NWI^-j_tW&%E%Dh-tabL*tDaEOeggY~`x)Som;|kc+x`#JQ4^v$0 zZ!FH>n?OYN@$0i?S~@pN@|+`!bx5%d<{sy%&qqg`?00rV7*i(7;5D4(=AztvSq;&z z^of4$?)m<1)qb~5`SIuT3S|&3gkC1mX^_v2V~eoxQgH5l6YyzxS2i z;^&)nC}5Gwn_8S*m3@aoDB~iOC?%KAGMCxk(tEyAoA$F4us-Be7^`9+mj0~dzCs*r zeV-H^OxF^?_wFN7Y^UvuXQ*B-vJ`0Fw2;uPImGcp`hbHTzxGNN5Y(|*9V?D-zwCzN z&hxj`t9Kt=e!d+;=kp97x`LLIfIxG@FZ8eFWo-%Q4+cJY3Ge*z9mmu_(--o72WaX{ zGK$_VN@)*r3RK#di1aZ2UAnVA;T$DsskTbzF(&JMnonqj0ib_^}a7q*K;VgjGLhF-THSn zkFP+L*-gQjXm5PH#P3)-#l-UEMUVNvYf+~CB77;)d^qbBa7uPWikI%CGSO?p9(3?# z5B+_#y2iz2@WUBJ*1rKyWNVz6*9jUvBLz#K+-v}<$k^MKqq?0>IVE%+d6lVvJsb}^ z271pF_T1Z^0=QwgNyX`AyBO*{H=55&I-w3pWmOTUW;irr;2Mo@a(d4OmF!sRYtf74 z`eo*$GCk&TU!lUduR8yAtH9m|7--hsPyqK;1LC{&#hs|L%LVk9z*}~=-j-4f^0c6% zm@(Pp<&9fFib}>8W;y0=YbG=(ZO*C#KbF-3z~7P3@N*)JJdArF0b)2cod((Chn|P$ z!yXXNkL!;p?t^r@3gLC%BM)DZLJuFgG#o0#j|lyE`5{*bffKXK7WX1!S4%m340kua z#Hs*#9VaPHciRo5Pm2IkT32g4%JTMgv=lXV`pTc!Mih^*mz><@`Ry+VgU#g?~T zz2}=FgLMr|mMO22n7(#z_5RPAu;4or2{dOfT=fP4VcB6HMAUFnN`H^XQUGp@s*YEV6G(zyWbAe0aL)-u{;}Z!3X*y|d%W1Dq2J5B}nz{`T&EuIr zKiTc;f5AGbU#XM6G9~tza%JG05?g7OTR|wlK`_u~Tk2{w08@5#7d%wnn(cP-?<=Qm z*|%W2cQW5KyJ9rBI4>)p=eIQ^0^xISyJK7kJSw+b)L%EYcz9^#{4gFWA!mwPjNilc z%~(i_)}H{exj8reMsE-T1#u|a`}lf2?Wb9DXmD-`*G+x+FWpQSiEL?`J{i7wP}DL7 z=u~hWZXfSqMx?99?qV>;Cre!zM~QKGo8P)^q{27pm#CiRh+^4$A>66R%DZx3XSFx_ zNSKKfqovyw73BM9E#8KD9=Rkyy1G};Y5Av z$@l9R96slPi$gN}EeDON5n2p9-{*@ka%h+NM70J(bQ8tpGNFJ$_D{fx#CPJD4xW)n z@9bpBLBhaaJTsD&`a;%AF6Rd8MuV8NMn|6Q>eCYIObX-rLuE34wI{bavm-}tBx zA+5RTagnR?I7Y0^Yac@45S|`c%iR-2jrjwbm8L#6EGxn06XrIS_rv!?lqGfRdIR8Q zzd-LK5ImnG?JoSu4h&0qYtKd=5_*I~cfoDisp>w|!n5eKoaN8A7;cQNXEicxEQ+1N zZ<>y9st)v^(gyo@IX#rm_x;-Rg_z>Bv~OdGMp`WaPq^_*Akgow<;Nno=CCHK!u$2x z`8pQBpPE}@xUOP&x`DQ#a+4-3-H{Vrd3tc6ZPSw&#NA026*hf-hMSPBj9C}LS;36& zj=&oMU}s#PcJATW1A>+HW9}cQh@08N$~+fY|Cr)MO^V+qE=hd#?uDgbgVG)TjsM=R zZ@s^;+P$&0jDwWbDzdLXnXfIa84l*AC{bX|sp!sfXLBB44*~h2K7d&en?xSelIK%7o_a2NccYe31LMl{&cS${UzZX*02~X&+Vt|trrghQYui574DYpoTz^$it5?XY)W?JN@`3)dYe{)c@Um& zpM1Vtw>d7I{-Yd=j*FCAqsyo1t+AYjve_Q)6FDr9s4x129$3|Wf^l7xpQ7(~_x|0f zmkKfd3Pl@f7Nm?LFOhPx>^XdVJqgo1gTu{lruK5n{Y_*}U4-`@<^MITy)PKEV*4>K zKSEUYdqDT7eF_@K`JL6Sl5ND)VH%YJ69=3BZZfmq&eNU^uYjJ}KM8&(+v_CW`<9r4 zc>vDtSf2MdgPOkcCekMBKTVX8=T#G|{b~p^%-E7{?Mt5@M$!d+xhC7}`gh)L_U&ui z4L_T|0`10HK7(g&B8SJSc8@7m6vuD~;k&`kf7Sz8y}!*|ZW&CmP5krUf9CN2aI5=u zZ8iI@qvVgD6}=y+73w_v#fN{v&R;bLj}{O7fLJEmzt{e%S=m_qPn7QH^=(s{!+Res zo|Sohzb@oHwf*4lqT=@+@;1*aJZJESxVh}DK@9^B;?F-y^k_T#Yc}(O(>}n5^t_FR zl!*82xwQLiE#g_(ebnTdmM0dzx| zz6~rM@RQ?Uusd?(c@HB**&`|HbO&zgbXULseZw1clIv#FXg3_EaU%wQPH4o5`>95! z&qS~!N5O9RVm^>_k*d9bgx~4UzV2sSqcZ$;qUp^<^V&=!Nr>oc>A|90E{8^KwW|KJBVm%q;8 z;~X6duEe5+(Qf<6;TY8hvNr#-#==|i(8885YuvYU9G-X$KTr6fsXf4(y*d7oX;heT zP;AS)V;&j{-ZbB34HPdgYl}3_0C4tz4a?-?begpkaU))09wKb#0ktC?<|9?>B1;1)&?D0CQCzJGNWDuX~~~P zVg-O~hMH(U;H$q}KT$Ro|77)poL_Z3T&j`)iW6wPI61tQ;b=)B1VUXVaySzBYYY7( z=?OdwzyXuEoS9_V0=Wbp!PE3t+xPV!GWqo9MmMGi4E;H(Z{5~5T^XW^1NGD;XEHiyM$YoAudHrWG1jy%e98wHB zJjq$7d$|uQY9^lW%jIv$W10Vwk^6~K-+RE$liPPiSd9mC%dnk|3cW4oQg=u|HN5I}6;ka>jyw7GSY1KJPzf}&X zIdi|c)Eb|%AC+bw7vLPiUiU)Aei?W)<>I;1il5SbJ>h2N&lj9msikoXKy(clMl{dd z+s%67Y{-jtiqMu^m`tme+)Z~sin$d(kqa&wL)UmOUut_-B!5G3dp_=` zYJUqJ7>>DBTV_9V3dV3go2q>mHaRu_xV){;od^hamy|WBNuJ{ywjzZFhIF2@Hg+NI zx5vc0&t#v}pmBg4*h|5TFb+SXb1xTR-Q&-Qm6N>1Os zGo%k52<&h!^Bi z@PbMgQi4KCesP#c0&i)He#-t4mGTXam+`(#Fln>pI&$L(EI}Qr#UW1abYP6|@h*|* z*rJJ()kGZ-!^g&tc@%qtniL8OMrrsR+wL#8?6VO1-Mqm-=c9gXpFNNb)0rIq{7D-A zc_HZKg75zbSrTzK)6)CH!uNUkf6 z;r|wVF3S(hWIs^d{uEz1JW$I%a0NmLVhu4BeENba>yt0ibuoLvlB;kd-}*#5D|(JU z6Fl1Ray3MK?KO=0^94nLEH1Ba4m9|uVN^emeV8Kp%uqfe{7Ws_;lE62u6Z6lDCOuV zyX7_gVN_Jyu(BSr4KO08r&R!%bTl@h)O<-8o#_IQk(LAcQt490H#MmP*Y-{@92Zf z_Dtjz*vEJK70d428P`Y^{|s(tBBlXJlDvAM=AOI7_V1Kh<#l<}3sT>?CIJ~t61Hd0 zrF#I*LHNOmtchK!{u!O@o%C+io^MYX<8(gFFU{&;scSW?*+rryJn+G#4I~!xmW_&XFIINm$y6*ud3>=z;_n0@x*240}Pd<;wwpUZoAJR(rrEStf}cm+0;C^FiU5s@J@SZpm$D22Gl#J1ejf{S39~+#owquj8kBNAs4=+eATKv<@&KV1f_i5Uxy%V3=fk-e@_!yh4=@YD@M)) zR#3$N76X7`4P~GS5#v}NjE7(L4eup+LRytKoS2jLq5OD&0+q~zgEbYG%D;rp;R)dI zP@V=!0d&p(oWgyewjA~G(pD@8rE2oOcq_~v&_9#s#;Im6m%4k9?>E5Do|H_?%-E6y zpE$+ZFW`sOI{g*C3RZTAA7u&@n~R3x#?&ObxezDADnA2P)?IGs#rDxvB$vCIEc@F; zC)bXfN3;Mbd%8f{V^l39I*rp6i+C7`WoA~N-FC-&X&6@|w<@wchwAIk7UPJ+!;c`! zp0u?4+{feDxyNntgM!DySJ?xY{iZyGM~(=s1F;l94cf`|5R*RO;bOlpAkepGu|K~Y z(t|~wGn~@{^RsrK^ikS_767I7p$Rno!@OIsei7m;IRnt_18ij}>k3}U1fcZMYFX}~ zcc~|MUs?S!1U}ttf2K71(CI!*m=#d{W8WY;)r)u=G*p|D=|&ig?9)>W$HoTi(%Q-o_WDhOW}KX8G=$qLI35QxY{qwhBLCWExw*a3+;uf z+&_MD;8CL_vBwB%H5kACgMJ>s_~&T^e%JTAXm8>=?q_@82pd^(a>Z&z`Gt1E!aP-B zq+F{p)widooaDLWGRf5b*!w<-f97@vN%OVv_?%7;SYSh%a=SO{rGI|7SUT!un^vzn zQQ;vM!c%&C9k()WA8hl^pIi{zsx=NCwuGV<$t}-JtPtnOB7J$EBu;pKEc181PYP4b zxZ9YAZB?{}aHdNzP)jfI`F0G{Xv^C8w2$wdNOv|qf6Px9m?g71_bQaK{4})t&EHaS zY2CH65|c)D`_>@;VNm@b{f{U68xx>fuUd245!o@m2tB6!2j))LM@e|C@I!~!-eq@wHLcdT z?>$`5x~!AspZ>mMTar=HJPil#CLg->`R3j|x(ztT{+RUDRUw4sLoGXG zHD&cSJwIDO_hdq7R~EcaxNkmDVN`wQay(nj30-CJ7j<}Gf9>n)1WF5!v)@TQ)plm& z_IT;&1@{*k{!fDueQW&;qpqwozqCj`PBo1dh!;Z~=R%`@s(N`eIxl?ZxAlH@ORyBT z{3^z;R`A@~J7GDME{9 zkh7ft>=nSQ_E2qJJd9(Kg&j)2(`f7Q&L-rH(Z{|sMimjDJsR%yj5Bb&Psa9DT$;c8+S#Y-W=>u`U zaK9-)5z!#EVXEc@BC7u{Q@Y)oZmR06!K(_R*%a51g;#T-*Lnp&c8+fwj_ z$5Z*a5YOYKQ7*oHvOtvXp56ZtrSDG=rQw0{zlhRmc|iasN!MW~N*~kp1xz@)V?7Uw z%a|&v{~=0)*#{%ASMZAa;(rmPX|oainR+|xTsf6_a8})ot#u+|4v7|r{yZw=j`z{k zczypDQyQyv{U2gd)*(SNT?po$MX}lyA`I_=Ib8k7fLSh|)#BczG8yUS~k6L4qia z&^O`xK@RmMD#N=X#uTatO??=cqknwlA}&YMfd2FL!sma9-c_z9L*}T>(lJbWDPoyR z-jOIC%XAQ+yGRu$6^U zQX<53cHIYm*3>?!c=SGhr=0k16>6*JTeqOhRnW8gdy~Gj{?3<)`l{Y-Euku$4dlH%I+T7 zTwD$g!Ofn^bpYig(eD%~m&edtAj&X*j@vFpplOH5tH<)jfm7AhQ%;q0uFU(;V9Yw2 zI}?GWx59s&e)n@#_9h68XHC`p@=byF+dg&qjzVe%vdObwn>!jfUTo_-s{BYl@qPK` zfY)JnKO{9t(o%vUkvB1Woqmrz29i&9&kM(QKuSB< zz_eE9_@QLi$HLjEyU6j)&F z7gsTI)tas0xcD+7_hfVX9uCVhfB!zm12$>z^7wYxOmL zSMp77mzB7Kv?TSVu~x)MTFYN*RoR6@Ad?C1)z*shg{QxZSr#U{z3NVa-^dq=>8Fmw z5c}pB$)u?j6-lW5_WocA2TAhd!EBz&E9K5|=9hin7&q=RmwY^7UKYFLl8BhwEj%_JC7_*v81e zPJTSi_@}65&=n8<`x(FFsdNhMvY3C8L5{r-*##(%e| z>nH~pY%h$VPM1TmIH3~Z7Q-se*rP=e8^EhM6I_v>T&|E=MWLAxfa{)c6=X? z2GD$j`K&|p=G<8dsAMA0g6FNjt*-w`*!Q`P=Ua-VGUGeEZ*rF}xBaMW2wm{&kU@cG z?D6hGCLlxFVr-8OT@nE5SHu@Z;!g4!+Esuqi@a0buYzHg%#DXfNZ_NK=Z{gYzj*yl zW<}b}{-+BB@u1Zu6Rq4$+9O^#PBZkpF+*-%Gu^iwSTmHYgyx)|NPmbnde=>j&dWVN z`H1a&Lzrnq8qB)i;tOzT>-&JES|`M@J`nqmzqQUdA^OjLNRxksnH7VB(l!w#XcZpg{KE~jG67#((_3G>0F4KIssznaE%6M*hc^eb7>0G;2M7g}2zikBxJJ%t7%U+$)@1z(B%h zezix=PmSyy^eleCyrc2@fI8Ik`+ZA~w>g0CRJ;n)MlM=ZNssAJ9&UFC4d6|xBFkp=9zFR2d^v9M9>9|U*PYTma^X5UC_FLAuA?Z~Q(X(*lr{X})M{gNS z#Q6v7PS&AKe@Ohzmn!__y3Vhl2?N}a_PYEQ^|c{cSk@;6TXUsF49uP{(i;jE6R^BA zUyBlRobq}w4$3bvoT{Vs0*O{m1A}|+~)m45IXzX3*yplLhn>C5sc$Jb$I5z zx2Nwb>F(_s8Uj`dP}%X;M{N%p+|3B360)Kq4)w5Y7Aq>CDZ(;BIx2p^b*Gngr5j22 z6GVVobc5>uek%R02|w2TGk|bZ5{BP?8Rtr`STKect9~Pg%0F(=YM9e{=*3}MR2J<; z{$&^J8tVf&j-39_>mM|wG zniyXwvs$T|a4aR)hFih$)VR8jbVBcR=A!<^8b~(?!NPoaF1b}s5>)7Q!#;z#>-Kf> zy0`ITpM1Xc_jmj;bjv5dE~)&h%ZiJ9b*PX@&tt!7K1KX42;e`r>^Z6SJ`7byUyg8% z&1gh#KW5%Pz4`HCDlGjjUr@6GcaoIOxM2LNVkq;r#}K~*Hd@a$A#d;WGcc5J5oB+x zkstrbGR>V~73L_2CZ(Geaqsdq#pV58T5x?}*q3-|z*PH^C@vmkvDrjl@TLLC$=l<~ z#vVb!jLazZTPY}gjL6nPm}oo$$=&wbw!Ja0b<{ski0NqgGC&vh+2;^>AHwWnt>g_3 z=yY~l#-&y6vDD0-uMXW8tp|8n@;(^Ho=|Vi9moN4(w64)dwwW~W0c2zK9|AJL!|sM z9IBGDl|6}(Hd6@Ty%}OMUm#9?X&eE9QZIvg zeS#F&{^rI3O=QWuFFw>gUi?(Ex+1G3D9UI)h-D8ZYyQ5Uu-0cxSfL;*AKpF7QaAvm zKZ4_-vjFb~Kz$_FQy6_bdbAESEiX?Q7LJfZC=|Kr*3;~?6X8E(B7$`h-B8>+JzHaq zB0K}L-&Q=Xwlk^z4ol~mgoh_w!Vlz?OwWSU`gqj=n)5(&oN5k-n3jeQYf@#I+-Zw%*f6K0Qs1=1cot zQs@qygv_z8hWP9C(-`Z*@pgQ!o37fTdm$i zjr0Tg^6F{gl2@*|V^eD9zHd;v35C4?n-yKqF~~isdLOSposD9C{&E*5U)8{Q4*?#v z*=cpMAYc<`o&>K5zXGRStO^iD$MjzBf%RU(#>1bG827EL#f4Utj0V$0K`Q|Ow!$#d}l9XYmae6d4 zeGZGD<^h$i(_Don?0szLvc5gXbov5iF9u=oW|?|m%2MGG)1?hp$W5-eC76ui}Q@)~Z?-ho#+&S(VZ9mg~&dMX99t znCjsyDZHdjsi=(l!Xup$;j@n@uqoip{_$cj5vneZjAm$7b%x;wi3HuNK|74okR{iC zhAGxr^FS{DIiK7TPuYM`06o<9_qAWl4=TSN{0f=Z2Bge|6{Hr+w!003R(6Zl9Jnn~ zbL&@rK~MV|8801(D(~{{r}6l@9O>D(%k^Ckq!Z|g)*P}oIF(a<6ui6+WrV5osVzguB^(fpK|`%DW~Xc>T$+ogS`!Xf2A0p0hx z;Wp#5eY(RE8@+Y&cP^Q`_;Udh#WPD=LF;yGK|yvNSQ8E6cOSc*F~rZAQ7L~-t~*;g z`D07-7g|UyK`<#e!yRzJNkPThrpoN|Ms8LKPA0jF1DV{mK=5_Ha57e;xRhmqTgRd z{K?{C(xUgZOVAqZ6lJGc+y8nV>gaH#Hu!3OXLd+CZI|C2{j9+XlyfuNpKd0s*0C9S z*_}GjoU!lxcq+z{yM3{??gX1Asq0<8*(d4u7vN#T-uW_n?a#+QYkoAdj+Hax9?W0- zc3%BqKHNpPilFChpLv9QA1&n?7XiQ6Rsc!V5&yj4L5KQBp?)6rPuB)igJ}_@06&c` z=%m#sYDXwbgjXXwNBQ&m$F4ehxIFm>eaZJH)59$GFI&MDAc!>&k7N&bhUY1>?Au9V zgMMRsG`!+Ln@b<$pYt&ISNjpl#?NCv!&&kC6NmdT_%?5SK^bb_8vgfnQ}nByj4fpj zweK_ez#@Kf&|G6H5fc^Oeo^SwuCd!o^e7nJwljVo5-^+V{~o1}nf0-J@eixmWo&=_ zZn??*Q4Q31j7<8Z?nabSHv@vsYQc!a6bbG~#vuQ?UzGdBvyV~uC3NOK7_4u1DMacI zAuZXwdj*Sc|9luIBU#|$U!`ex`#~SoH&(OR@sbDowFZ9${CpnvdlunT+-wBuC*zuB z(SE&7+l@xyy+iIv zHv7pU?CzrjPj`X^sZA@tuW&re_QdQl8c@YYHRnH3{499YcJmO1GINonzu{ED#beDc z3d|CvH{1+3`TN`*CsM8j6F7TW{xi<>7G7>!se9>jv6p%=6D`o7uz^CF#P;D*rC`+<1HWFdS@eERFXoheotRMCB02OdU(XoD}; zgIKHwKD{6uqe2>vnG@KYN6I%vHT+wKfQ@zIV<6oNqeUMSsPNi+Mt=7h6%vTvMAMuD zB>?{+$exIo+LArZ?dy|*f=}M1BkiQ?eBBOAug!r?IWlMEyrFG|?e>4<=p)ul|H#p7 zYbeBN)M*!GSeQIqh{+@GDgZH{Dl}-X+=myr7FEx_JgHNxln%RemX(u*zK6JAN54O> z@sKld1a>qnfdu@I9nJk?M_UEh(bh?I|FNU{Cs7bPI~s>9`8eS#+3C^wn&lKbRG)bU z{PFqT$0GtnfA<_*(MAs=C-&meDE1r$>wp;;_$3EsfC68XxQ#j&JP#9n9Gb zgYiirbjBg*sXI;5_*W*4GWtMRdTlHfZft#7h5e9;;7gA{Mk|!!+ z;s8b_2vT44I5yYdrj2#Wl?My45x?q&NNY?HZ6wMG!Ej*(v21@Lm?F8-g5x!P{VR|xY`pladLxc|^jGzYZ5~6I&f|}@K2wi2;j|gH zH^no6aG1D=vJi>6nc;dsgMG%FTk8`)0Yu|$kL=H>^7K?DS1S?E2jw0KD$}u|=wBWG zDhNlK8eM6tb9Wk246jnlNq>aueQ^AZ<*W@{bykr9jat@Tq zuAfiH@yi(se*#r)TT(%>clpr^(|nF6W5eYFrUH{)6=Kmr zLE<9p#I^BJ$>lZWbbW@0;b#|Dm2oy6rX>4C0{4_jXq5>T=Ic&tl8ZYn)O{6s+_x>U z=B1wxr4QO`{}_dyL?6F&@L>t*j=a8_IBCcN|YUAUOJHhw*$Kt??tMO5OkGvJ}oJP|4dU89! zB|suyn+6aOjhReRJ{-TtBm|JYO8njMHg@FXNAcv3Xw(l*FAl*mbQ&&K6D`C%PrLm9 z+bgoH4$=VL$ua|VLw%6?0N5**Z!c#`_7UfAWk6&h)m?lS9T9C_^z*AT*EeB($5%L` zqP#pLz1s{l4e`o;jXnDblAbFJ$9g;J0XRO8qrx#z|3UYAy~wAi3AX!fI%uo&0rXyuTm61ay4s|1fuEy9#n!7Jiy@PbbYKt)NIJtv4qqB1$K%z|+@Y|5cSr>bjCj zc6Q@NM1-~Gnsdx=v@6m-r&Ke-K%35JCg6z=#B6SpiEZ<7xi6wc&7bY`WgfQkI;h9G zC{tkE7Fa^U=EWVLHKGgR@g5WNb;x&kV*^0Oet3|aWWZ zO0R==d8%MSUO=Rc|MWUc*DntyQ-KI5-1eIwTuozuNUxe-K$r${%E__$Tx_ggrMxU& z4}i-q%cT$8-6RIJ5g}rI<7_7_J1yiSiznMgRy&*kx6Z$gF1mYIzYpzuP`XSNqhC_z zm>B3PO<3yqAuB?i*X560UGH#rCjgPa#J*2(uPkS5aym&mCayn^`6CE)Jvqo}k#Sw4I zF0{y~8}v5}P~9%m_s;vFWoBIQDr{;+@0F<2bSt_WR~ib8&|IcHHOS>mhKiXl8m9<7+Jar~DWX>-zic zCm}Js4S3e^X^$#J@?9-7VyVBcVPA@ndO(Bwam4uc{CIeVuZHv+xgRUME4STOj7&JQ zo>-kC>&CQj2jb+g5Vy6@{)t&kYn9~XeXBWZqnDcRpKWbV$=Msfh_XP%3Vxy+?H9}6 zU4x(Y`Q=>n=k&D%tBayLF~tY+mP4dp)BBuP1V`~I`_S)4&>YkqHpV&bSl1xKV4dC8o9;%l)9@MFFuoAD+a84&Hz;xv&->yrP zY<<80eH3I9*5~I&g~4gypsr5Mui=*mSLsq z_rVqoStC7pRf+bfocnbTVx$%}y*%(UNp&~PO9MsLVg3ytou+b;j7p~TXy-%3w#qJN zV~^`@;mZ$l^#QUnY$Cuorww%CKd&Jl9li!VZjX}z&=8wIFZNk{^>OHy+K`2Bx7D_iY_+Ql;v5B232b@I17qFUa*3IX1*oD1V>Ifk;g4V!d z)^S7u-C@AA>n{LaN~u@b=hg6Mw|Xyk>s#MN3O2>5vXj5iH`vz>P-k&YGgO<^6F?JO4p;-`yvN~Awq>0 zoRptuw*VgD)goD_&5U%<(d1U`m#<{Pqm;Q1f&z<}k9fA>JWF{h!{o+E3M$Gb!)2aiCiTV;xhmpY2td`jtJ-Z-%!=e&j&RLs_jSPPk z#ouSpq;sSCsbYHkna9RW0-N6NrnGlwcqsg_1?Tuy$VWnQ9+)p?r(?pm-NOT}fe+4{ zqyZ`hzwNcN88x&Z$lSMp4(klK?V6jaciSfI3Q@&8H!6P~4hxgiO7lmWc6#`fPDp9B z7vKA{65-y@2@z0j+`4pms`f@tH0y0>qIR@EpJ ze_5L0spvH+VqxyaJzzHNS4Tlq=LZQ5lJSuh@ItJk zOI}~UVm^X4TQ1;TidW#^4IBfj+7vWsUATZuGD4LbpT*~vCm|HX?X3(uAXXf256``C z`U5vx|D6}|%fZ@!xv@Z{)uHm~iCb_!+^3ZvxUlh^60l&}1KaO}C=YxdWL7nNt-_yP z1kG877it#rR)?$kDM&3m-e>wH#fZ5+*}f3}roKnUJg=nC&q8L>7SmO(EA~a}5fHR= zHr*=v)@^|UbwRcBrUUBF)6ge@hK29#&pWd5>(ZD)E854?q0K7(C?6DA`|&-ervLD! zC-QTM%6)E1u8w;;>&cxqUerD}Mi};_#}aylymCnl>hwb1lu?*(r4-|5XQY?uL zBbvq%boLw%;1A(mgbyiXnymvXIk2W9u%^p5coA88m-3?M;iO!9aK_?lWjW*BaEnH% zU)_4w@F>IIj6?|C=cksh_t+bAPl#P}XA4l_mFmj-$2}w$4hhY{5B8y{Ke4dS8SFX0yD5r5f~7e8}jvm>*d_dy>DynRHEdgS69#}G`vuET?U74_Cn zlg=p%Pkf;p@+3DP+NQ<#qM`lxdPq-A;UmO0&61s;44R0b4>1ol^$5f(2XrL$lJCZ$84qNc z3~;B|ZYowK?!Gd`nbY3Q5zUk0vxGx673|A_V>U!$Q9t4cV8ZybFP*^fbI4|*HxC_0 zcJ0k=y5Aijq`uMH$Z2lvqxUM5%^pf1>{y(Zf)mS)8>utn*KNB&+50qdXD6IVQ>5Px zW?7wJVe}Rsd#6fiABX4gzF?=nIlU0*7X~qA?^AWl?@d@+*G){`IXv}`tHiBjo=7%2 zqBHVy=(zg3-zX1{jVFknL-ea1uGF^DoOB8AaNmSVFL!8#0Ny7Lmk=a2=j0=u*(+nj zbdm!iztJXDz zK$*XXdfxJ>$Ah0dp6|$D0_kv z77U>y{W7a8LF#)T7Ql;}`W~I_25rQ(rc!m_ndGVX(PL!j`IbeW?f6JzykvWv2ehKW z1-(#mV?__VUB%E1V=vcY4}fp=@moL+Z!F8Jd-~6?p`%xW<_lW(HF)EkTiuA%whZKp zZ6vc1oC-O+S_Ao}ioOl|C8-h(K161b8nJd>c<{%sxnCGPH(x5Z0mONt`@{V+%Sj!g zrJM-y+8UH^V5vVJaQGZ3-;=$EGksi(IemyXmuj&9i-Ao*Z7_Sn`6fJ&47^bra0TjF zHImxX8%7Ra)s_AV@44-%Vv!DWO~PFK0U_Q#!@NxxF=q(qwLtsbgcHz#SFIo+d=(#Y zn(gxiFnLsX$v+ADbTr3dP%K^T^wVU zBxrFbyGpOEe;BXt{b8uWXM-@~_7H~ob&igY+h$$%43K2}r8sVVkqXzg6`^tb@Ocr{ zxYuA!A0ni!BsdM3{e55K&c&q}n-#i z7L(Xz_?_5b8k(xKb^3h2>&rvex+?kEmT(s&J6nhvL7Nr_`uzwktgLTi$h&x^x;rGr=_K40Dbp8h zS?R5Wg(~fCVp|p^NKn6g>Sb!tBhMc9=?Xiz@?|7E~rWi{v3jB;zPyA{JrmOZ<{)~Uw%xzpX>ee zy*n>$_EqYOU;c630B0*T8OiRNQRy+XBDgHo#x7teP&V2|OE{>Ia#M^p`P z_0smcnHDRh?JcfXbIu^+YZ^GdCxJ=AIERFniOZ;dNy9ZVxgeT@*v0Ghe8Y7kowo^P zcd5B4r12HI=dyj=-vdPWcQ=#23H>FMk*6nmKO|58?2}`FB{Ek}!9H+FMEeEsB=X9* zxK*SSuu)&XYcJIffx7K;TlNsq?xf{aKVhbpB5xFkfN38XpztTcUaIAjOr#8xJw;_m z+J$sc{hxVr9Jx>zeR;1l|3s$ecrE{$wdx1goRbxe#{8rz>^*t*bSl<)mFD+=bWzA( zI4P*IXmGdcy)!x`H0;vqs2xUgA7X9=0Ry-w${B5K$1~hk7LTyzw+nK-mq3PkeJAO9 zeQ{R>%{a?=ac62f<>xNn!v^$*y(9UeOSQGj&)bBLqm{N;K#J#CFW_ zBcs*6CdSgj>;~jV7^Z56nN)(HWWThNc7Ur#G$wFHepaq5oW$-J2g3!I(5CC5G^<(H zoWGy*mj;fyf2E%%J1PPgr7(r$Uy3H@_dfA0?rBkYE~apWo#)}=%w79x}^cbXt*E+<$-#xOIB_w-HByyynkZe;jL{n z`fQ#Cz0%Nd{|pG1@SX#FG2X(Xy#)<9?B@}*R*so6w(FjsP2!$9gkSNMZ}~88-I!;2 zS`YTS=otPqMmw`R@&n}_tAARQ@a)*kC$Zkzo^VlHy#0Tmaj$cIgvq0PtWDiOaLL~H zf_qddp4@-11cojrj=^vdKHYX(l1)^)3Fdd)sP6&21QA*COs^g8VyyJPjUq7h$#BDp@6`F0-Ew7S18d&B{@OfCuGYQoojrEU-# zfAoTCo3H;;6BY!s_Ny>(GkryY^AJ=?x_?einHddp8ueB&{L2C8{n#+B$N^oP+vA5?3Ep8jPS>2zJ(TbzeFytn1*PZ}B? zER-Y&5>{|`6HgA_#GDhxAm}u3%l8b4J zF&PecXlmN$(W{X!zMowRfFse9Rxzt9c-v2&-XDe5b^ zdMjtV3bUQdKN{(1&lDG%Cw0O+wO$x1r)x_YI9L_?n7&nII!KDXJ_?Y#xJo`1uea5| z9=A3lPHg!&FF9NT7czbZCHZ8FTTalbD+1w$&LguVnU_ z)N!=)Md^^H`EuC01xI1?WA~~?ub9Kp*avRef{TCM|JxWJHjrfj8s~kwie%x3Vp8%% z5>F~E#SO_SHXjo@fPi>EYg({hKCg4b*^)DPXh`n3b_p)3;T(^XNP!i>0msT2*#e|q z}73Lio?HaPgt${rNmcN^Lyyyg|gfkwO@z%jr-KOe$pdk zpX8@>=T&Slb*k3IMVm=$6!F(Id$iyLCj0B8kx%|`Om=5>j+%1p-vIa{hXFm- z^ZM4I%J52yVr$3TzL;_~%+r$f4U<2IL0v$xEC8d|+NT$h^3PzQRwilit11lo^F}j^ zq|W=?o@vvMjM#(RpW@e`-IM8or!*$F@#f)H(ynHJW+Zqh)`A1!^k-_~drxRsV+O4j zU4_kwaE|8~_T(4m`FNzQ-hzi99G`k4e5W|lSp>u9e7{yw>$IQJtMgIG#W2D1kk)Ly z1UaG7B2?|c%Vl$=j|kXxu(9)lyVM|Blg&AmU@lAN0Yz=>XBO|%swTMl4p__d=T-O^ zdsBpDolN8Vj<#83hEjR9HP}3T^pF(Sc@N$=MAWAUb;We#|2O5412A-a@Ay#TfnCm*?PIC%o|HRXZ?{{YNo??N`+ zwW19waR_41E7IuMs%vMp$l~GC>bu3UKyx5jdnjA?Y4OUw!*suA_jg;c!a_p>8wgJi zt9JFoNyoAFb=bW8>3It&4`)@bor8n1VnrtIxP%5HxV>~WTpy=efQuLfk3BU?mJqXh*Jo!NG(s-fzbNL;k}% z(&ZTEN>RgBsT!67gL(eq1vK?aN;MW^$%S5O$<1+4+f;QJilf|~ePV(D;9^vs@SQdB z!T;n>lAYoo9-g@F2rjk4ui5z0;%j5LU{d1)t8w>ghsW<#q~gWCLG|(W?jW=YxU!t@ z#{nV(TQMyE+1#LD&O&Aq5g;bhdks!d{2NpU+Vu2}@`Nt!e2xyBeUq@<(vr>msCNNX zvGdX+N$2RFn2x7kAirnuSp%kjl#Eze%KifM$1~@t6wpq3gW^fOWOV5pl6wXWt*?e( zc!+;jnMuUcogI#|_JKji=h#HW9t+j`8@~f~+O1v+1>L=BT+FyUd}SkghDzYkKBqOc z(e;$Q(N`Gg3vUb)RP@sTZRUZy$zB6%`KQZ_T#^Ew7))V2Ua@Pi6!MV4i)b8u&)3uA z(_E|N;6C=%bz!KF#yP zw_z}tXv3_$2IUPZhOw_2$yP_%SL9;awjz^ zcG#Zb@a>J;C+9HTJ5S3Qt!`@b5$(JC=;D6&#V^*GVB9r4;%l%r#cF?Mzx2E>I;y@0 zYCPTM@SkzS#`(Z)9gl4M|HXGq+S)&)YW|N`{r~6to_~DJ+e0C>s|lgsJO9nd%Hc#o zxMGQfIn&tU%>x3spB)l5!cUWK7|(hCxvXgOg*)dtJh%?~_3tjvEYUYx`lRW#;o1p1 zdWZOqbxA(G$Pt}27C*nobRYOO6!y2NTTp?=cI!T;f`=^k%eT4O55QVZ$N7CY*HP2$ z?{}n$@(x=?j5h5z-1qH#_Z{FBumC=7!k&=Ua#X7K3kOw>e7PUg;Ghej-tcCbye6C! zsjEXLq6=$}kMZ@#a9&ccXHx z0!{GQIgxz|eHbt6%Xzi$$JG5rbNw68ABrHQBb{gZAE*NTr3XwJXbmAiDB`lu`+&kZ zY`w5UJItR1XR`QJ&XEdBd8CM4{AKQof`8tNWLfdz9H8{>g?%c;e{cIo)(F;aY%dAZ z#-VEC#{vGMe73E|gShv#!~O65TOs+lxx{jNVswx$<9slR7YWg}F-aUFs5s&v4nGJv%s_T`yiL`jr@4U`GfNB_?$JSNr+>U|NPL$ zi2}hN-|#hK0i>KUxgm)VY5PPjO@IXAZ;3s*oG7@O)91m-^W!bIZ`%DEWZ$M)hsZ;%^!=K!_g;c>y;se$F@ z&SX$x$5K-ccv0jEdo)LK+nr2&#o^*~Hk|W!Ka;dm<>se8=A`qKi~Zx0E4(|+_ydA` z@DkE|uJ-eBp+8JcSS+*WIdm46DD0p6lT8WGug83rI)r{J?&PvqrsfFkAK6xu$NlEC zRfYSm`AK&{N8Ii&A66n) z>{I0M6n>#HSRA#BjIqsozqZ(qCmZ`ER0aE~qazNsavv7!NO2Z)xP8(5CUmO9-*o{S zNX)z9OFw6ys)W=5Anq<5&HE+iNIA{Yzx`s`Ka=&ePX%%l>kpF1-F!c4Ki}y6v#O>2 zdTes%hadQQ!v@u3&%E)O(UVsxDo1Aow%v1Z-)s8v2YKJe^?c$er#E}$&o0?& zzE1B`SH_&m`!x@cBRQ88QaA3Myi*MlD9=)eva!qiMzzG~Tq~bj=!GNWm74lAmSlI~ zZ1h!8n9nvW>pG*p^{<`V733$VYeR zsf;+xY5Hum7-v(u9a?#?&bmH4VZq9shQ|-EC8!Dh#>}r))2Z{G&PUyw?kv%k3}agv zLT1-l07c2#u2v7lZ(qW;mVNjN_7ZO6*_5A?(HsPlBdqis1(y%J4gg_Y_sTh%^HuE( zSlf|hlCP)JYLkTYF@Y5~J=0yJNCkHw6Y9A8FG&YIqxkw|b0bW`PqfP%o#$97FrY!?m$QQLKw?wRX4*N6 zj>p^6vH+Px7kf0`pZ1z>**2FDy523cx+>#^VY-u>k^|~4>FKNef<-~o6vdp}luD9hQ##Li;J&E*NuL2hK8V>XvVVRH za?#nc%(gwjAX|KcVAK_8>I>utm#sr4$xfbJ(Ec=4(q604?t(Y}H7LtyPyHIO9VNGQ zKEb-zT&~U~OmLPYcPwzjw(m_^jhL^L;hQ}cW5121rlH``I_t#cbPNQ)Qxjo~0{=3y zz1iG6crPmOFLMDVa6eYIfO7esg5||`3knJEyX-N=-Cd0L>&HC*QZ-5gHy;NOt0pZ- zpoQRnrlZ4jl;>4oY>yTINqF-YrLCn`BwrViV_o%F>SorYEWLUbdLRu5^1j4qkhIb1h}m8oZKt8i{j5MVcX*AVI9jYX9`7L$4lQ zq**Pc1n2R0;C}fqXAJdwTKe0kf7yr*^E$M1l@N53ch$nkr)haD;kQ_b+*lphV(@@Lq6+p)%IDUEO5 zby;__=+OleS0#(z&0ZBic&=^;bosTVPx8&sJY zd!jx#K=Tj`0(Ocl5c)%dM)?6FPs=$A9NW(*&OK*fn55qOz2MB`e3Xk#2yqPiiGC6QXZ0vd|YPa8%9(gN~gqp zJ7lcyz@Ra&Vysuw`y)LUA2qvd28;o}2I{Op_Y%oDLJDIzt=nu}AMH2TC*t^Raz;W= z+H&4AHfJCnn||J>)N@yoomjWfM=yJES(`s=IJ|V?Eat;$7=?Ej(#Dg}KPUcZ7PuMA z=@J>R3`H>oHn?Q~g6=$;kdTN!<06L?;up;U88-U6G`u2u!y@gXcZi|8-O6p2vL4^uh z{_A|b{khv+WO~Ub^OggTmz6h`(GAFhe;aJx){`(K2Ie&&dB~iD$H}D=4A`ih?B%NV z(bazrXBk?i?(se&?51VGb-8>zo|}v)7{+?G1f*(+&OA(N4&{ZfXH2*cbGe<@QVU)C>Gw=Y zmDfG&3#!}vum{pj>iZG=S;`R)YFRY3eU?$+Q*5JG%^QM7jf4|7^~3ZT>autF#M$w% zZM?64Rj7#zi@6+Ojgy(#VNbeC<@`Hs;YF!emrzTd;1)Q)BUHvFS&GJNt576 z(1!F!a-Hr1cYrzPWA$|+Bt} z>)i4#TMtcSqqX~ixJnJoE*?|)3a6R{X5v$B^XU}5TK`*fFY-mncBIcUN1pdENb`Ld zvVBB}cqC|RkSCA~dD`=9FVnwz`#`L53WX!yi0(&x_qmH0g#moHSHEH6L5pY41QZ8e zsr#!@@9Tylk(hA}(NO-Ao6l}yJ}WddIy*0p%`~LBut{RF*id*UHLc8xXhq&QW}?ANn|!F8Wy-xR8aN;XmNL z{s9HH7T9-oTjx*_AKTa57Z0j=LWdq1ErI$h=uHG#%<8(08bEO}fsi=~+ao27-<#p6bcDK9pN)4=W8mk7pwM0!d z()R^PL_X*5iT*sWDsLHmrgse6jGf|M`6C8v)hK-OW1c1!w9h%>kyj0 zYe6O=!8_|`UIk_^U?`E5t)S4$Z=~Mp*OPv0Dcj#qx<{v>E&SZGn|F%YW#|_}SRN}x zD*Y+_ZZ~ERdLQysl-ee`Kz6XL#{6RD!QYA(&>8_*-YRNeZ+`59DE`Ky)_&O@g(C_~ zp@PrIJnQHiyV^98Hj?aZ{axr^hB7Ac`eg2XF768ZeGzD*bZLEq&*eKDf6;V3-v3;3 z=CH${dEj2@*SkNjCReq5byD{Ah;je=9`C_s)qAlZEuzw72}^fs_J7`WQ=~5P z-#s#%y))1Vko>+@%g|J9+-fDR+##r&@r#(Nf>vZ2xwju#{WQa7%>sCw)5Gyl3I17Y{_u&%jn?HMHUolSn8gGv1d*RQx zf%6wP47|jXr>~LG?O=hTmQEKGMm}QzbB}e(w%>}uO8Wv>c6d!m2FrDg-524d=oHm; zs$f%buynaod~j=0NkaQo`&nswJsGECD$YNEej#dMiHo0Z-l4NZc5V%!E&*f*O2<+} z(oQ2tsru7tGGKI#eKWFmgzYGWwXNo9ype%Ca60)I>Nl0s3I6WlA93S;ud8u=Qa&)~ zqkBpQ006ehE?Cryv6t?8BuN#S49Pz|A13j7n?G*874{?cZ4rfKW{$no(4wUSa3002 zBFyUxFlx@?mU+e>5B2Z;6dRwG+Ful|^r;gPEhAQ7y~`#phB~~z9!GO?yB{(0borG7 zffB+l0@oUAw2@1pKS0yH8sEogGKD{VL;b1?Vob?+^w4Hp*3KB7RX@Emmp)96j@}eu zRe+#vR*bF8o8Ztd{NN>)4A?t&eVoooI~Q-6Di0zHAWt)^&Cp#g*`2y)4~a-`Fjtul zUf7_(cJM1k6i7@7ukSk&@ zTQ6Lm+oJb}(=j~RIPFNGOibEo7v`IB6L}H#!PEe~>4X9aVzu#plQFI7Yj_mtAnxeP zDf!*<%e_sJB9vGxPwa|&K%Ree*c=W`xR&6-4c*a;%1Ll$~pG(zWZ$Y zIxe^1!n1TH=DR-Vx5as)&38?FW$gSG za?_L_5QZ(Ms;t*?$jd{`m#1b~-Usmioq{mC=dbX;G7AmXgromr)xpxVu`BA~gnnBZ zQS9J9cDj8f)fJ@cd0UB#V%I!>bJp`)IUM#Rr7IE3DU*W-Kf8@+Ie6&10q@y<8v1dd z2%hgC@i+-bh`aDVUnD-;uR0VC?$bLLQ^YY0=hauJ3m1b4%CJNU&5AkwG89uXO{-1sYQM~s8NPN3W34459O5me)eBZle-pR@o)j{V`J6C!gH+bKM68bxoV2xCY-#wV~Hnr*$k%(BUn zzTV0d4#flqw>z^tzt(!(PdqwHu!fX|?eg#weLU*Hv0Mz%G=GwD1th?}lFNkZfpdZhUL2_l_#>*-{pXqL(GyibFbXB?a0dvm}cgVjC8Dj!X9r@H$qqi znE9^X1ylo;wZ@|Pa3Po0;!BVZ16Ai9q3w5uLZ1C0+8rgqVXrSkb_Ho6kDm%INTAK7 z=M9xNDhb%%br7zi{MO&O%*v-MTB%kwM7A0yXm>SRP8;VaTVQLXf?I7ETO@=*+qca; zPb}Pz5ZU&Y2#c~6Vm>{ZuKa|L+a5RBZNol)5?ST7N*uz(W@xN3d*waL>2b(u?VMai zPS@&l=gcV#58Ao+%B+Ll#w+KvxV?=B?1_GV^EqAxErK&z zBlhLcD6fZ-rG-$jRl9*=MV7~S3)JKw@oI69uDFLc(#n6 zE2H*JFm!6$G0rY~&P>fFxS`8gHt%`z`mg*bO@|2a8~*N|_v2>>?}d+x{WlBNVn!@D z+7-QXw3Ynkb+EXV!O>o^(*Sm?EpB+K=FZyd1J_>5U}WZ??iYRFJ$pYP4FPH+PB;+L zr|rkE3myS)IDx9^K>o*hOXH+3M3)idLD7OXL5h2GkwY6eYHMn z=#IHb9J1w+?U~tI-Zr)gYPfY-RP$nGSj$OkD2r-|Mz0b)aM07`%3xKVGi#%rBr1OkZei=!wat%7Q-V#HD9=YE^9mvVplFl;=`XGYaPnk zhXAIt8AZ?Ft_*w5I%afJLH@g=q8dxzg}q}3FCB=BVlOK}m8zg=DfM{$xITqHz<1iZ zj{_-=C*8WfCj*bN#}5+8_MC+indIxYa@m+}S%F2;)I>`-5_->*D|^2pqEx(q)JIbsjN)jA<7vV{0TK>TA3?=$xd>@;)CyNAv45)!l0y&i^lqi|(3!R>ebr>XJc z=Af~#OrwG#Z29aEYN$MMBt+j)ZMLcoSNSO!-b4?VY$Pp_wu-f{l(S~fLiBs}@|MR= z|KL%>SC$L=agm#NC-Kq$$Wx7DefTN?BZVdHJfe3S52LPjwff(ye3CQX4_w^N$`!Nv z<w1+^KyKzf_l;(2wWZOGXO)wu{}730*v%DU1rnW0BmQxo3E;* z+f)8DpZ1_>bG9#woz~o_iID47-njekxIMo1`Fq_1r&}N3_J*?!K;-;A{&eR;@ztZq zNqeE7f;@}!T~fG6afQwS+g0=I2N2cc(J_a~na(OtS#UBU^S?f zi1j#%W%>5-+uGo8+p3NTIb@Yc5pZr9^iD8v3is@1wjoII$=EUi8Oq~)c>PR;xrUMD>xF@q@y!9CZWz(7`CgkhS18sG_@v$kQc{|cs*x-Mz zpxK&;#`y_8V_ZG`p>xgHO8M*gkd2ixv&HX{HGRLY14LgqKaUo8K#QKkQ28>S*t-Da z{}6>*F|K9z*h}jD&B-(iteJVa+~Wd0BN-Q zj{4?ftxv6N#@XlF#k_E^$|#i|iEG?U*g*)b-U{A&#{goa|8ca-y*#ERZp#PG2l=!8 zl8DdGOVYwnR=x8}e?tD;OG3=ZL9>TWR+0^ueE|zPuFbP3I>U<|l)5A{70flq5~baZ z5n0;017rscYIKhSDLy31x#8bSFZs8L{q1rE=K9*v!_c}Pa`MEr1UQ(e zIljAVKU|qF{Y||~Xi>DCHIl#Eb|cZ>ZFvrA8~U0V^HQH+Nbm@uZ@}%N5hcsL)06dF zqqawC{tmwpz+pt?8NntrUeOJQUAU{5?>EMo3W~&wF6#u3s4wjMpt8nH>j`3aVpUq}jkQ1AYL6!N=EJ+qCt4?a_!Q>K9L^utU; z^KtKQ81inlr_{+{0+Uy$GOf)2ek#(KIt9ikrj8>y~~TX%mG%Qyc% zL_6K?3*5-Q$(Y5F$lJ#8f)>agOD8ipW%}`9?iZw?ENHSIES>%fd{5m^zHJ9094+H3 zol}1-`JgL$PCO21$G`IKPxlK&2nDlG0aGVPQAigz5G4)QmlQEaR?oTpraSWUnhgHidr||9=~Uac6_b>WHL1QoyW|{^<_I@AC->Y0^p`Jpif@}9b=3_Xi9F^* zX%T=SAwrnc*_D$KP`YSX&QO@A~nMknQ7NQ@8c!eFM-Fpr+sv4ZAOV9Xwp4KZLN?lDPJl(xf#njzPOzkNN9YuJx%V+ZXXdE0z^j?(O=$VB4(vVCn-GkUsPoNdBc$PIjvtqO`qB z=5p^!>B|bC=%CmxppU03g|L8}o1m^&`e96`;=9OZYbZr-`}LQb;bl4d+JA{sjCA=G5V z$M2ZPyoCEFkuTCyoU)&^i3n0(_;Gugdo+J&4E^tau5tlpdJ^$hEzTmw(OUe#6%Z)3 z|Mi@gfrwN-z%fqypRdD#e)iwbv7^WYwy7K7OFs?uo?5vNpYiynH4&dXKwAon&lE1Y z^WmoLy_Xs|X*{b1&OVH^wLe+=DZv-s^yBU)NgJ&moX%w#Ln1s0&=DP-ETjU+x#bR?j$F}LjJP?vpKMLt)D`xDs$rxSoFHADxZ8?2l z*!t`DE$4inim^WUtko-u0cJ_46(6NQb6aipM{Q$hCyK2({uU>znS?iM?iYS?vgFaa z&!E=cQfu`4>Us_pvb#&!5llb3Ia!N^dPkJN8tIU{QYyu5Bn>i8CTATf9vaODRks2- zvoekIb~JSV2G*6tBqq_wD`=#DQTXn=ob6k7=s!af(dr&{{bKPZKN9bKJ8^FEK&b;k zt%kUW+mpWFGrs=>nt(bv>!d?f%!$h(hHGNSoJdaLe}q4MjcLs(KIaw)r=#lOE;2ziD4SvwzRe;{B))UsM00 z2=p%fZTkzmUkr`WrDl!GTvB!DUg3~eh#a(;`!WZwMBYZeJ~8I=F#68Hc4AnWGRuZ$+<|S|e1jv2BZJA| zdo#K5Jnvn-sY32rQ#LYz?m&RIb)95;NAG`0kx%el3)y-_vT^(5J_I6xdG&K44D@pLoy6=92cg{I)wbM==Wij2EF6 z@_jZx&K=z3b8xd8*=OtOM`q)|#Sej+!@-^RyjfLc@*k?i$06^dM(4@m{H}hv>5Sq- z`t8^85>vL3SC!3Qh5a}V78V)*Y%ak;Tb1to$V3?D8}c}j+h0Lxx7wZd+vaePMI4M2 z!--R<8_IcUFbF*tG4>=K_6xEwUKJNTqt|+?-}?!8JcYzo^uumhvcEpcHuN@!(YCMP z({|rmu|K=X{)41*?N*HqqwrrMa`;Hd`H&Fbata{|(XZdr+GD(9ziU;igLt0%Fz;*j zN75!x>{X6`rPMLr*F*WI?G-ZvtJ3d7flp3^%d!_pLD@c))J?`AE#7Y`*Ib|0-14mL1|(+_-wThs!jF zl0hSge_Djgt&ja3*5_bfwub`>5MSJ&Y_L_v{|>~j(EbcWRLnkAd{${p#QDW_yDvZ6 zlNj>Lf6gOtIR|MxZYsJa)Cw8#;M(I?B7{r*QW*FBZrWi@U7M5Hr9)=@1Xq>W-lGiZ z?MIX`>Zr17nUyINArB{rw-uxeyuAE1Ql5Z&H37DmcB7fYa>+oAjqsNJCi|L0;v01I z{h1{+=7`Lo2SXLs^tWHB%=!fQ3+rnuo@u!d=v2%e;BPcXIqWgy(7yuxSP9^4)?6>@ zZhQa~bny(8UmGcB@v-XHafXEzUaYY+f)JmSc|r5i#@M#ox{2aY0&Q9AdvhPXVw0Kg z#5dxWzh5*{y00HhG4g2;&SBD}O>Z~(=O~#4&z{C7&~!jegOQ41NL&ASdGxHbpbdru zPAQLss)pR5f8;l=;P-0|Q%?eoT#L12x<*Yv=! zniomeZ>fInPkm6laW%*~Smi!b2p@xs`_<64WZNaCuE z{q^&pKOU3|n(H1;7f(1a&ZMdAAnoU3)$An@uK;PMayk|yn$pGL5lT1Fys<*d*&;P61(~gxwx95bc71&YFkooRG+x#$xHF?2MAxJB z-7gmtcARk}9L9rAB<);o>jNEamw2~fSllbi^hbWiSDp82U3i>-?bYgdBx>`D8=XHJ zZOkshy(hXxUt<2l+huSK_(`e?)SszoU;aNzS=OopV_K#J;v@?OQA2X3tn4Enu?`;M*DQK3u*-Y zNM2ISeU}Py_<<(ATYv@)D_m4KzRn@+{@l*J?HN}Z%Ssmb=(o40<8?3;Dv>>?U$TiG zonVyaCC{bs!_L!UX${sK(c+ojy+v>A?806@RS+fM-$iz_3>@$mr*GSJ>Ut;M7o2Xk z-`zGeGF6#j5Z78qI3eqWC z`pow}`aPyS?}a=&FK^-=;05HlRP~Q??Nrdkl2hBCe26W$$=WBXl@H?-{o%}F-hsNN za);i?=W{*7AokZ>=j#tW6ZR;c9Kowqr!XJa-EIgoYUVWI*Pf3IWT zIL7x0hS~FR(@Jq-%x_a)ZqBEW66WS4AyQ+ zST%<`eS^@yH%J-PA8&1IA$PL#C0pI2Hqhc806_D2)bCq*>~BV05&HW_9rqn|`?GJV z?-;M#k?=!OH!HAq{waj5@96Lsc=%2~b60LC&NW=<6LILYK(imvLsdVS4;>2IF zeVdoJeY8iU=+J#En0{74`@$Z?%pvuI4FP?Nzf03Bj%kVw_w)9M*2VnI-$;YrDn|PA z%gbtttP0sj;-IM|z-Mgs_N&0r2m4!(wYo`Cj! zpL_P~`!VxgA3!FaP;lD;Pa>s6F?pg0!;ptKI!(XCyp(d2>KHziB(@J-~i83bW z$*A;2`j=KYpXJ3$8#z}jH{LkuW*q}Rd#xm67X9`3)wE-bnTk=eKfDW1d*;A; zfYdPc%X8V6!8vz@T(l!hZrECs34kQNWJx!Zp=!snt7Vbz_hl4DDkaugQEAWR$6DIr zkf2og4q+1hv1eu94-YYVBYeR)o_)rG$TabLC|q}GtRJ+0tbDS@4|TYGCGl!3+#+tI z+Rho(Ty1et9cm^dLZ2Yw?*Qd~NUO_9IjlqR+7QQG5}^jEnmQnO!&t(JhY=0!XCI~S z>I0G^iD%IL2k7;{Uy9?B@lSJ_udCIVk3HDGA(uNJp8c2E1PLr*OsENT_fsc4J9iBF zhhq+=Y?M}!m!J+7gdC=hS9}PgKF`bZJn7AGd)jl~!g7Vzt|p$-K5#r7iNI7g2Ik~H z<0ZynlNYV(R5iLBN*6;Gw@1~Mhv?4n?56*g;0m^huuy_@Bh=2q&QyUG%Wzn4{M02q z>%IY%uD}K8DNLCf*DujcZooA8AN5Avd1rX|Z25yOwAhQ1;YkNmxPr9WeYrP?@I9|p z%e{a>!3za~NX&d;q9ePQ`H3nHD3#?Sf}g;;DQDvS(>1TpdM^~3@A|mJ$UAeM(-a5n zruspq+mHJN+vgnK`1x?h9O*A*AE49t`wB;#6#@e`x{&3vl*cBWTgb^#mcRVbbZ`B) zP7VWP2lDpQhZ-(yBER9{_FbiI<`WWV7n6|tzFZpk9#i2BF- zC+@&(*hs1bOl-fVW2+nbCZ48E$F>J);1-S8^xT~ z^V%duL^8<=XXfkTtM$19PDU)t@S#c$3wS(4ii?4@gf42%P8;JYX)qDsC`ZS?ecKVr^gOJDdk=n;|6Zu`m;hec(u-VtN zY&>@RVxEQXZ~yps#uwEFa62_tdka@#=;@Ee?5p0mz}@>UOTS}Cm*6?S!Y7Owlh656 zW6pj1A{YGHuzaT zT3l+IJ~iyg@H;&5SI{4oW?!@6mJ`?x;U_NPFr1`E20t>`oZNEScne5+#N`BR5BGxZ zJUvu^9$qs9QwlmSrY<}-_Y|DU9I(Z+9?^(=l~RRm#D!6$j(VNGuj@-nsC&JhZS;g)+DAulG1>wJbeDt86-doMSoD8M94lQQsjg+0;n(Z5E{TS1Bc zFdj@rfHA?0mEu;fflz#lv&*$gZoB|K>i*{%KO6k?8G|l**ygf1G01h>(}7onyE3%z zfvDErYOjc^>lFnX@z2=tXanrP>veBmqz8xo+@nx+Bw5NrCHKt7ngIvtW_d52kW zvkPCL8J0)k{*Af6A$AN#m`Q4YI}%2ZzVWrP3%5bD`psv~*M$bu_P#?g*Gm1p=f>gI z$(;J_vzK$wwRku!y^^hwLHE+SXM@UzGg}_P$oR!HQd3M`n|ngfIY5RA#Gth$N6%HQ z9*XLk{e;8ChazV@V1VJX&PRUQuBJ~5?>z|?sNc|=CDEHMb3|z*@RB_f> zuH(`&z6ilyglLPeg-Fe+CEKho?Rj5j6j6-((gr8a5J=c{Yno8G&(TAz%}t{pKu<67 zX4u%)MPe7JfQ>f0-&a4!DX{FWk#1-nmLTh5)^gq6CM*aJw@`p8@}!T@`T+E;93J^v z8tXxttt6$?>*y8}T;x~yKwLC>d7=9}QR&TW`6jR) zBH4YHi>9ktm>IoH5zA0_od{8{S>{EQex5W!Urrlnh{r$pe*G;;SSQ8GXkPsUhi;=Z zppm+-TWhBfATK|rf9sz(0;Luvf60=X&;7IXp`$*#_2agc8Ur0`$*i`h4ents8&DH4 zzX7M;Zf`{0*iQL9mtVcQysrEnRI#J9`RCZI$?|OZ5YW>YgRw#rNu+p(`Re=Y#JK@7 z8Z|z*Q2*VUUuoH^a9Ir^X+lnz&zy(hrfa7dI!;y?-QLazKIUq8M-Uvc*|M(7^jf+ z`0}s%R6j%d@a6FVP0|7H6#resYv_qxG}3huwPDLkGMCK-U$he2ho$wa0fJS>MOAHN*gd^y;nH9QB{|F%Z7*jEZNCFB4STB!#nq#hHGT#gZ65J zNCS>N*vh&z-aM73=5n61cLmV+)+%369^3%1z${%>nX#B8s^@rQVDWIX*bFFU>SI4q z0|?tcop?>Xr}vuA)}Pf`nzAF_%ni$KWI^OJDQcG4+JpV>r^v_RvV&Qz&c1&OWIzP@ zXCz@^k*Wdg-g=)FJ2Is_tRfaE!Pl`ZxoJ`Jp8!mvH z<=F}b&0)+w!Ml!8_wP3qS#1*P>^dzc@PNs3zP26Ug>fJ2&|BdVw=*BW3-_)(&JVV> zn=8xZdo0Sf`@-{-9hZ)fKdwWT3LyA4MXRsba!06VGS2lG!x2jZO8VUYf;Wj;f$+>R zX4t-i1?tAOzP|?RQOTG#yNoCkjR*dBnuFjm@=}ta>K|(fM;Ccx2KV%++YkGVGgb9V z9mX#%0A>84exvgDJu^5$@Ho1pfmqn_&sARcqTQB+LBgx(d->{Oi01rPWT%CTwCM-q zwb=K^*svoxy+4@AWkGpm5RZVqarL5``?{^cQ7ErnvX=t-{MY)lMSqk#Nby?+P!j_FWV*-M0L<;$4h@)wNaH^*DXxB{G0 zcqYR1m|*;ZyPt4W_A6H>2TNhTAVXxH)(hnVxP|@vm!&c3y@SN*@GQ^KzP1^3&^b81@AUA!L!B`*~^;WF>SgVymo;No@-(YB{1(s* zUv99{6eXVuwz`n!gJ>LCE6J-!-2%sYRV5T>sh6G@HuVcQk=;JW*BpC8bv|ZZD_U*C z+V*;aR8%?}Yl{V{gAV00hf6f3kUv6xZ|_)sRPTCm3KMd-n7qZj+K6vRGx#5C^5=ML zG5Aj8tBTO1bTb$Q5y1hyaMA3b&+t_C1HuKzl*^i(_8k1ISGQH=!VTkviQwMy$?rKP27yf-=jtjYBO|)W){kEL_Fz zyLA*v;Hh36Tg-~0scX<-@q6Tr+a~Ra^9A4wbQ0o+3J?xq#_SCk(6v0YbxfyRH!v)t}PwlZ4Q)TwnC52m#_@nPfX#k_~5Cb91$w$)E&~>{Pl+vY6-jt_y%j z7H~Dz&$!?jD`bha4&hKmp43$|CH?ixl2qVXBuxtG@Nbbk-k?uR_A2AX36A9d*k?U_ z8ZH(gZ^dH!Jf*BPM;umQWBr}w_{SA%vp!W3AyWQ=<13Rjx-$}DTD;{u&9XxmT`r0& zKORKyG~!IDcyhN+$G&`#nEPzlR!QEsS~kYoW>kmwsk$g((7E>4i;elc-Qin2z;4=# z&8lz!qIiFwMkxxPi_O9HBFco~CcR~iT9ZodE{6~48e#X%Ac}tI7@*c+0(As&2d_Ks zDFB>b7Y$STn6u8loi7jJf0=Gyg0QjOk433KHcHq@+fz!x;yo zJ%V=AV!1GfO!;LY>@1VLjARayzE}Se?5~jF96S+ZHXAFv$Uj+3k8F41>d*C!F|7oa z5%*~NG;n|Md2kMTjE+piJtVfc?!VZnR}yA8LSAG@5$um49!TWJ&6LL0m&%`Om$(Kr z3*2TrkCc#GYO=+vXQtX-I63|@Hm>h@E9>(Z%sP0r0h;XBq+LG26QePD`GNgaB)$igPgIxT(jw4UQqz6pC4@A|UxKDn3p6@6|sMvuF z7!^IN=P+V`z1QB-BFMtyGVN(SZ|IH=TTqmkNS{sQ`Bn_b$FpMuo1Ota?$;aQKtiJl zobe5}hG_CW|5${BujxjUwGV~F!m#-Fy0nMrlx|!TysHDPW8EYghU-?0%9`5!MTQ=* zEm}On(kG+=Xss^IwcbObDTAC0e3j5ofm}|GL1Gj6TTYC18=Gp=tm}9>s`Us3?}vyn z){!1jck9`hMzCyN8srTUF{;X)!7Ut*hBxASZz)*W-bmfYXR>4`CYjA zIMnDO9FtWpT`}zZyn?mhZ(j;NCtQqC(arJ4nAMpj zUt%JIe{El-uYfIh(O{W|Y;CP+J_}~zynZcCepvHEwBngoxWB@epqd3)0#ke0+smdS ztHgr-A86M6vORz39X%St)28Up_Q411y}D3)ZTRy84Q3DzQ!KyNvjT~MLZRD6MX-e2 z-`>46J=|8ytK*B{zBz*b1t zXqFB8{Jvml(se~NVq9{sm7d$4Tea`KUSR~E>rI~=@C4`k*SM%@PQ-tR)%~k!$U6Mw z8hyC)Puo82wTyi_nav+we*H;Jqyos@vt5wBw6@jtlKowff+-DW0Nhv(4HpJHkr^a=K3nYRewNpM7U)=?5O2pD>y}5DK{ph}&i&KrGh$|cqN18= zpMC#48M=rZ3x7str_%X?mG)L2#~=`q4&{hGggt~-tU%pfG}WvI#C5`vzf14nh*Obw zL5C!ltF4kUuW@cyq{mOee#e!%VLJ0W(5=HKf#cCxmLIfj)y~hHO7A-6#6Ps@WORfP z7r3MD8(MZO3we=9l#6-s8vq_)mUv@VtKr!Fx-q24WwB>t7UQUI)x`&rFcsdD2qs{5 z*gv|Ww-(W}MiE2@$wNs9h9U=I&(Rq`#irs?rWmMuyxyPifqd{gz~n5{zkjSrQG4WY z(qI^pN(AjGDl5U}v^h1wu3^Z9Wkf@44?x`0sVq zrvZC!dAs2G^fy%>07VcEl#4rQBkLc#^c#ER==7WPam^+j&=U zu_Cl3wzuGf*4i{w5edFL~dogzRkVXK!z|iW(3Qu*gV6;c|2scRDF2z1$9P z!31&t=FadoK-p;n#sFA5QLqBhG`zNh0$wkJIR*IRn<9) z@4`2Ds>|`X*WtDAJ4f^gY4Ls~)Ar%`9EPcseD3z@uYtx+AdHbYsh`R24N&N7)`w>b zcSz7?KX;hRaPxJK8l)9Jn`;kN;c4G>*oF*-67WBF(T4;g)HzeK7M>L2RJ(iHN0>8n zy$AX_#obAtt~uDh+QX1P`gGsbr2sScI=5||P<9`2zn~M66!$1Nyoe%(0Q3C()gU+2 zA$;I7T!$xAjW5+(+b>;Reew2B`GH)_%D@^c()rH)*^``dSdmU{RKZS}$=mt;qRf-< ztyKP2DOIFyQ&9=r=hX~9UAi z=v6{0c|4a_5%J_NX?oNI7G`$l`?aT0X3V2Vf8iVyh{XJ{lnoqm_d~aL-HKE6sIMKh zr(kayesiPSw^mmJXh06xk5W(Y-nthnxtBleGpTyiHL-S9v&dd5k*DhU&8Z<7RR-~* z;ThBfSXGth&E2a91iUU-{H6H0*9)?#tuu^j4K(5hreAic_!}9;Wg4zd4T;M+>R_n& zcm~2}8m_w50{4_U;rT+(F{fv?Lv*(_4q!n~-~u1TpZNU^WKbVQOBMUL++&RO2*0Z_ z&eM2EV8~gehdt}K#9k5pC@Ifcd-VCYBH*!#6WeET;^P>$&|Ol0^Li*B_pAGK6Ab3c z4_~ibPe^+Ed&A-;YImmpP(NgN%2Rily(Vj4?_s3D1TmoWdhcK;2@%m6U-D|y-u&5x z2=4u~ba3gPh<^7A_KDGKzOjNqOPG;d)+2d1ta>feJt@N>@eEzBSyT#d#_BbH?_cgGQOxUknMXBj zwf#DS=YVceKOf?Mmp7BQ7GqK57-UjVTmDQbItI^(|mO81Tn?&QY{FaRJesF>l#IHy2us=jE*O|uWnWtraew@EDA?KMnA7lx5|#HRk}2svBjUwB$IvjHw*V3YO1ai?X;z9d zg?-IqR;?_%ku{`@%33){zc=h;B8~4H4gdB&GJELIEcAZ90&xnI3?jZv`GfL&5;s`d zJp@Pp<0H$C;huzsV?3u?w$HxcXA@c{_{-@#1pE1q|EhFHa)YssIbU{r)M>?w<{ri6 zjG{zXF2pdD*inxPd%GjL>1XK-enw z;&)%9fPoT9BDiR-2p=8uND-fX8x!M^-XF!i+y%B@qfEc}sGPZdA?5yF+@a3pmL4e{ zwL;uz-=z;+T^WLr9D5Pb7M|OEnKI^61F{mH>J5Xnx1BzIETf{WfLm&Gs$x{c_fYS+ zW-fUk_Jy`Nl`KbFJWzJ~J@+LA9wy&US$4GW?*oDnI#A{&Kt zGxA2WREWVZ-0{~<+}|yhcn+pO@OGp4_1IfI_x+2r?ET5#&yK^v)oeJ-nc_*9?vxOK4Gb`ZM?6t)aCy&zu;$a`=od@NN(Sr z=P4+7aijV9#kdiVQrJ!haDnf?BTgFeS0rm8q%dF4ng%0m^361juGHBsYX+O%an?7C;n&1fH3PDt|pUV5s0-?t0 z;hdH7-HG?l`~N?ddJqynajpe1?0%c*vO(pplgwbTQ>MXH+;zieQoctVKxM+yahLe= z`1@)~?PGqo(wgFlf${MiZA^50j&QVLt)wWx+8i)Lg(D>X?$r_r8k-%w;~qho^EB?~ zBm9Sl`W#*-Ic-h=$6m7VK7ggK98iQ$ff4ZN7B1A=T)&g=B$(`LQBrL%2TX(djG!ki zp2Wqp$%m~@{S{C(%KFPG?hH>kmU%g*HoKs(IncX{rXatPj4`CSPP!4_9<@c!%=b0Cw%X7_7$L9_*mpq#fXOQ`^j3ddFCf|?El{?%ZCAGP`c!VJ8YDO@IH38{ zH&WV83=A?T9N}EBdQnF=YaTQ2myhLw5?m|&`GuI~6++lKw@1~6{$CEVdHi5X)y%I2 zF{hV^Y`+~&EHNsN)1P#p2eDFr*k3iB>2KKyQ3uyuaL+_fAT;-ld6;krz*$0yEla^{ zpl2r72>X;7^jEe3r$kFPJxa-pb?IjjO4g8vA3OkaD8$iUSpNY7-Tku6e(jkp2kuuu zU@*cg_+e&2qlQh=62$zti{5-ZO!e~>p#(#oC+m{1rhhsgw*54Z;ee3m@~0B4ck#-~ zwRmEd+SADN3 z4A7q(wu^T!`G2DgY4cor}RJyuzyz0Bh>A6QqHG6 z(N_pZFQ@yy!aM;a7Wq*=X-HowA9b76i0|Cxdek7*q|Kr&g8i`SADiTS!1-Fltf&*T zp61_&Le{^%1U4S(z?cgb$Vtz^A6qW3FDn|utE|_1+s-QhI8aKUYHnsmCbnNf8%a4Z zlGjPv#;79~=lhkRP^_jLKHEEiOG(48`bGThV@mY5)YsZ`%0iu*^?-IBh)WOVZMi+!6n^md@Y5uq)kE~IcUG%1iOezz|c zmpaiP&TL?*o(pO#Yk}O4Cwl{IMA|b(RHe;EIs;(xttj$y2TF`NjFH2Jda5${Q*w%j zd^Ry2ehex^#XL((6MiR_SDs#bmLD zX?ODigNR;2yJ|^ z`&Sv0=aZRt2QUxiB-pf3t919I)_?XC(=EV}P?#hRt6QE;M-TH4{9;r6V_(2=?qLE6 zL&ayNefRk7mVvbE8&=c2kPfAG8&^N0kKK;@~ZuvDU1@eKF&7&3ol? z&M(eb%OMR(`+mS=t*E=)>4D7{H?lH1;1%rjbhv)v@i4kK{sudCkd#UtYs$gxnWQ%@ zvY9%>FX9HdzF6i|hTdNnO zsB@T6gkFUCrKP`qjyIPY>g!3kM;^PMJw~No^)Z4L$a%D7QIrSM;cl#Xb?m(-oAe5(Irh>tpqyc2ym2?EtPfuZw9OzCZIcdWCLp%GhLAFCU zk(&pel(T~MCtrb!xA7rqzH3=xd>&1c^!NQuZ~V2>%G-VA9m|+=gWzr_oFoeMiWvDJ z@<25?^=ZI3({kG0ebNF=&(cdTl;$n%Cqq|YHy(E0>v}Me3fcZy<~mz2w}>}T%h7Un zStFRyoV*%N@{DV8C(l0|GtqsN7cDQBmwq2;o)Q*iLZuvP!D9$ajq>{5`$&pEt^#d~>5{Q@31gpz2V-@b^WiGnZs+J=~Pnh78aQ5tv3B?wv<7f?gnKHu|mm+(M0IC`S+?pb}1$K zJ$hYaf%*|?Gr)-W)Uwpkyy567^H~2d;xtK9L-_0 ztt`2}?Aa#05!UAJYp#KKf1lK3CUSoy;2F$KV6y(i5`v4)= zR=Ps|tGIO_zeLi+iu= z(Rf|A%vU?$q$i@e60j=_4xjtak?!!T+taYq$Gpne;!eM>zzs8dkHX_8D?NE75{zLs zuH3%P%5aji_C@3Ihg#O1hjGMV5|d|vsuryjhjSWyFc+S_T?DTb^Z?#{Iza3-?DdSs zaPxNv3^q*RJq9+}@H5}varvm8hS@C2#)xgZoih>>Bemn@6g*(SMn5#s^5~krJ(Opu z_sj~#x8JqO4Ec82o#zywwQgf7bp|9HmHHa)`q#5kV=Ko#Q%^Jb;JWl9Zim4*9)$Dn zD>; z#Gnd~Xg5d-wpepPvz{64d2x<7st7jr}1^v<_Rwbq>C^vwU>Kba6Pa=}#R@}{0% zqx$>u$6)xq(MZhMcQ8lMa(lPmbBb?CycB!gfuv8O$(+jSTCAC&5tpu8fVh0_<2_1Q z6((cD&(hvnad>HHF~cVKX7}+02+Aw`3+v}(2Rf#*?YdAK?Y{K;wc%dUO5M`lNcR15 z?*09nXb_E`Obj76wx!F*85RoOP)?Y5#@l!rF{+I1bimIB#9wj5o2SS=4R1^yH~=AL zQ5MIJ-z%@cC(_HClD@<(095@Du;hU}`Ucc^O(C%|{9s1bb`CdAr4A$C&qr4KJVb$d zfa>nIfFoF!*UG(3=Cy5cFTE>FyVe`5Ute&X8_hP^JR53~4J9R|9t}3u~W~n-X z7`x#u97*`G8iB!$K?}{mjXSLBrkp#5jHEe5yX$PFzA{Y8_2RK9^qU~S_1X0e)gNrF za-{!!c9B>hR~VKdGWZzHClF!+5WlaNw>92g`&HPdDP`<61R8$U-_E4PH(Sup;nP#W zrxDicp7xl{h<~m8MSNuRtS%i={nw%1DLI|thbmStfc&IT{c8xlr(U{}$I3rW&Fev8 z4kSLoMBVB0P=vMX#igqph_KdZXhMDx*S?6kxpD(zxWuVSV{dus-ntxrr!UMhOv%4Lq(B-hR`FvSPik&cJSZc`R?#hBI<_3eg?em zTd8P8-Hl(x{G)2nk$_MgbqDn;+x=!nnO5QXI?9Ol-PF>m-dw;41R z``=>f%V1$U#a}Zf%OLFOF5Kpz2?@jq4BE#0yG$2#B85t;a^8M+#GX^EH_UW)hiF}F)DXwSN270@=kt?yk%^`L&VmZ-r54iM?l zC^g6Xdo?4{~R)OYXvgDybtf?%S-A$f9ef`HkDK6$yL~iR!=r6rvz>a{ztO2|_ zTDp6VxwFM4te~|W{=BDTEzjB&jgc*AA_!m>_BYNCM{*1H)8IX_C41cbcm+uhDL3a1jQPPkctfbL}y~^;F z*>0R?9og^ejN|7$q+@eq=)6F;9j%Y*3Y9-|K_4r^h*Pp(CRr%v7*dvc)^3#36}8I~ z`0-PU=MO+9``S9p29o9_o1pObG3XB^(B0MjPNXQZdYLnKfOJ}AdfJC0B%GZ znqOChPd9opNY=iNg>Olt*ZPb$tooo{H(1n6EcuO$&r;c)3Ec}q@AuJDZ+J1-cd=DzA9$CBoce^ddcK; zqF~r?F8Z_`1o-qpQ2lO~M`L-0Dssm#pB#|r*e+aPq?GGrJ z{|-OQs-LqKrx;AyW1 z9zi^J1vvp`2MmMOA7)oSH`=Y`Dj*nxG=12;9Ff~G5$0kp9LQ0WTRaM->#_#LrBQq6 zxo;M?83lqL_Y(4SKNZN>x0n+U%}f8xGZSJ?wu}Xo0F)cZ<{C!NVK*>#6o$1>ooVd@`NXjI;%0Ie`)Z`H4!jL)pB z>VR4I^idM4Y~AL4%>=YEEFvOVPQgW2_D+Zic-L#2OdBGZoPl=X0h^|F;cE}TQ~Ar_ zk0fHe@K73$wt3s?%)XX-JyLLEC`}x&!*h=?A?iTwF*}~Ug$l%L-S|N2DkqvK0>O}OJ?8)a=q$4 z?jK^Jo4sOBK-oK_)R*B04Cy)L0c}rXcE>Tuh4$^8YSZ9MTve~8M(mKPck<+G)?{N)}vR_%MVP<8R~X1 z_g#uD?4<@+T(4nUoDa&mS;mhOGtwJx6kFY1Z!uDiw^_df&Qg26ttGo`XHYCTpHthz z)rh#8lRLHmdG3!Xe50IxG}|93Nr|xXDtm1LMCzd!O^{H780KYSE9vNEiDS!b%__#u zzM3AJCmH8aalL#*F1x2(&``$eeaJHmFVOlP0PMEejefTZ{}IKooWI+KjF%Z+y2?mU;L%VHTaZ4|Er!do$1 z{iX21s4G=c;*O+>iYCGVQQ6a~) zM+#b)b?ZH6gZc*!lcsf(ly8!fRLq4K6@^WjwL#u;wTq`C{tnsm_@l2d?~8=UuZVq* zi=*x3pM&iN0k`Y!XNSkVCxJVR=F2=^AGJKr_dR@LO`*etaPyzVP~w&_e4NHF))#<= zsBD^cmu=C9l{gg+9!a;4>Wurc%$TmdKI$;0?GCp3^-YL+VL!abBsWS6Kfi6T_M$2^ zQdiD78G9xY!TRiqiIj+&?>jc0`6 z^~1;W=!ey*mms8YJDb7_jz@=}bBOG(+=>NIIs8WSz3z<8AGz*+1fH(E!1#a`pMfmP zMUj4v4;do`mrMC0ssmXQFLyYg%bAvDlpWzc5lYm19CARz@pO0{%-L-z`Yv4lyf+Ch zVsY*Uo^dwKNR8OMAYVN>aa;~;;tuHa;P}7jHa35h$swtS5IH+LJzrm#0Jn{vt= z`F8B4EH9oN``4RKvNC!-3u@h$V+3cZ_IiOh1U=Uke$g!W6v;fzE5+H6bdOd}-!Fix z%5{|NU(9p~KZma^bXYG%xm=`BFQM9%yI+(x2*8yay@*`*mIU(`eR*aZ9dcE>_Q9u2D$qBC@^bcU5pYM`H{q{4c>Ns zj#%{fi@~XguBYb5^ntMs?ggx(YH8yKr;c3daBhj(&w%UIlK8HW&eOC%1lD{hsGY-h zIbvk2b-z9K@WVZ_GZ|FllHNblJLNJ#a3cpjz4*`b*F@5+V0jp5{Wh-$`-$c>lhoNK zd8bq=y~IxLPj9dlEfBPB@?*d7DZ>@1rq_~Zh5kg$5rF@pWG0EP<)uQxo6PJUW}2nX zniyaw_bcC^?lVl&o5z8r=W{kSF1(g4C@1YXB$VY!x!tQ6LA|~?J~QoGw>bd|hqch? z4iEZDYRYseW-~+?q!`A$xk|8bh`JABTc4C*)$0`M&*w}qw#zpI_>W2$9X=l~TRh4v zrK?2DAWMVYn%l>YP_+7NVnjY6Wvd^5DZGdu%oYP!U=K?g>wYL(dzl3v0~x+Z@mc=z z$*wwTHC5V|fbrFpb)LnEQ&<;^J2yLGl3+;?f3A;l4a`fRL3|5w!xOD)+W{TI0j=2V zZzsC`VKByxtvBw)ES?rR+pXq8<>Yaog1-#*HlLqv4ouW92}$Bb_LAMdvsf_;jl6E! zi*}YfOk(lp^H3ka2q!qWsK^J0>MVi?1~}7f{du9%o3~x48|9Z9jp7FV7Us9q0d|!q zdcE)WOiBf@BBD2Vhiu)%%8eTV);mW`MW6k2460LG`9}Ou-kn0z{{4p<`5Rj|Z2RC66QzaD1WAO{c&(&KLHDt2r3^11I>Py2koLa76$ zSG)3s(D?WyIdeE0H!qpP4R1#noya0o^U_jww0T#9$U56I0g=-Rvi6@-bU9u@u(9qF zs|Sq$EM~4?2IfRxP5Ect=RiUJd_~(%O{Bn-==i8s^iO=gVNX=Hm_&%1*{@(J{N^_h z0%etvid4?zLj<_>suVf|(H$1F{aeKt>mtDC+BUe)nC^RMgM95_t&9stjM(}N=R-50 zX;FPdAQ>NI^h2nYVkC7N)b;mu#^^UTy>Vs9Bo|D3A`8>dL@H9iu{#{>Q)`Bb@n zLg-K*z27y~#^!o`v_t2&=l!C`tSfbnbk%Sp#%-;U`ApJb3o%RAsQvYZ-X&RiUus_s zYRF1|O+As*hjj2e;t`lLu0KdJ@tb&Gv`Hj)!J(Em}{i{onf}ar`Ga6YsA3#T+iy5{wHsSp~xo1x9Lb00Q9$z>K zK%pwl=BsIV$#UA?hN~~UR`!U4ra2>m3&QvosCZvDNsmT$#7b^>b8{oY4~)0|BdL+> z%6-T3`y!-Dcq&kfNEZnx3*AncuW*Vaf5>ekvi$6&>cxho0Nd$+NpIifuwQtCautM& zSZ?cN_`0%nEdoic*0C?uiFuO&9su^4s^me`mG-HbC)b)i_UyK znA?mJEs1S$a9=lxY4;f}spuXDg<34O_@)Tk;#t=G&VIt0`UC;md%p{sO1x`{Efd29 zS|A#z{NS3%^dZ>5U>xg%7hi_ z(Si8GG$W8k1!$Czd%YoyRhEBZsiCB)Vsuc&YAg5pLI}s}_o;|Pvi1&bU*Oa411%E! zE{eRvZ2G)~=J;0L2!4nRr&9i~~joKE;y2^anQ;a{))_aY7-T>P(Pe4y`gxt*qeE(5>$ z5Eb)20^6T)%1-e|zJqo~TGT~29gfqyM_eUk+GlJTxfF}{pnDZC&Y{gk4qg2(tFydj zvY}mJ@8^D4Ld6abmW+&4|8{7ywifetzr%JTMv4jG6jabgkn1m^K6zsL zk4I1$GvxVsssywbvy6_8;zi4vqGxS3k2@c2!zC)p<7_A;%Wd z)i^PWDNQ44Q=$DY@$ek|SU3hxGPdpC=3X04uP4wd7GZ57g~|dMB4c~SPGtaha22Fd zHu4)iPxJOc(0{Mt>mGYi?*2+`4tzH8*l#+ze8DKfC0^7pM&!rZ`5=%8YXhsM5hVa7 z!oGe4Y=aV5z2U8S;22YY${yONRIlb`4-{Y>M80XjUm#D1@E?{zF9uQ`jN748Y=*oD z$2IgB;TJc4?nl*L(4{}anz~}Vpo5^BzxSutli`g@fnpjYGd|x>M+pN@-0_au2aaS) z@9MRbpzrvnKPDe*Q|BLHSdSuLhh<^03x`Y1&cl*~dwvw)yX1$w8p-Sx{xL5hLLlMA zBs~6YOxDxWXB;vOCn6OaNM!q9so1%S-Q58yZO2%{< z$&_`82`??ZXjZ8TCHRSWZ5k;K?s%jogRn*je+yi_4~pg@usrp_uMYma?BDDOuOcW> z5HEgp=Nu_^zw#-bT>(V@BR)aQNU;v{s57%rEWzQ=zE6W=#_2ElsKm9&cDQ~o^Fg14 zFs)7N{>SRBHHXZF#@iv04YxU9lGM%`20D`sLCq2sU+{kke68bz&k|LO31b-)RFR)L zYwkX^-`iKxqy)eO(;dG+5eM)=joO7u8l5uhy985@Dn-Ya{oFx#xkJj+C6R#f zWw{LAf;eDd)#L=H3R=ex%(Hl8`wl-|vG*?Gi2ZtdIOO?9a6ytDUd1a9^P+#+~Gg^+wl?KP>gM}oh!Fr?Y>aEJ?=8^2ft$x=?u zCi?gpEn4qoAnqoC<0uo@w)(&!Z97ZsMYS>n32&JwF^p9 zplLu#kMTY)k-%#=D9_sl2^99po@lS}EZlf1i>`?d-+{7Y?M5TPv z9`;cYa)GD}>B{ir^p)l}-#?9vIt{8~3pMLd)cR*zMYj+Q4)9_4Oo{$H31%lOC|eil zO3b!F14$Md!`jZ#!WJG)T}qge-+0F59@c-wX5wJJVG;a)XI1gPEHVDw_5$DZQ{NtM zc5gu8;}nBXlr5fRHU2&sTJg#Kp*Wpce&6IO!M-@e>nwrK zlQ1Pf%1Rxc;(nH}s7c4ESgQ5jMOcXRcjiP(u~Ti_=Z-jjj~8WPDA68DAtj39b0e?N z115(wUu(LhxH8>8Q<;27%CSOw^;N`vpPjQUk3hN7)K7}v7m;q44Wq8|utyQ*?*jR> zUA7tGes5Ol9`o1<(UQU~?>FOry%D%Z5-us`M(o|Ei3XuFZFfBD7IJq!p|3|4iIxsd zI8sD(p~6bS+=i}r6h7n2-BHrgC%OAj^T?8kkt@Zqu^ERWx;^~-Lfwwdf3=i*db?I- z3RN@xue6DzF||m%9hPeG8K3b%OCa|&+WBLj6YFG%d043mXOZQLfS)_6Id@H%OezOt?@C*WB}g5HDS)CTVTc_-ThsHJr4JDg zI$?EKm>@0*Tot+d=3{!3QjS<$>1*2!*ru7o}>VqJ7YqU2u5*GCQf?8WlSc z2`gI*E<3PJq_(E^!bu-?Dxg4|T*$ zfxkNP5d1M^tNpg7BPK_M9k9LQu6}wJzr)_9UQ{>wx6Sn5DjdO15LqhWA%hHe2HFD) zDL8Zf1fK{9)I7LHP!6kK(4~h2M&$H9A>U+t^hr16N`kk>QK}@Eo&Q(L(9W+veS7Mu zqAZ;PIgv=+26S%`-;@cxm{G6jH+zs)-dCUEb)Q4_3Up3fqH!Ph$?sEUCc~!Bd<5N!9+1yWUx|wonuK7|pSv#{NaF})3!!x7TvwmX zK97{Aw=9guG+^s+V2<%}WInTE*PK@%PJnpu~@GFc_Fv?(-}{VQLz!|CLV6Qa$K zRom<0yt;pr@;Rv?b$}X_{I#JEoFCgzm^z95sofXgI*naP+R|Fx!-qzktYR_mE(5ZF z`xi+3>x($=k^B{hzKW9I>?g{}kG>Y&!^ml{fpLaa@8#t}8*3v&*)r>n53?>>sqQ9Z zHR`lILKYnwM)Niq)P=6$S_rN)31qdgkB~9qwaQ|JThvEwJQmlz5kX@$U(YGaM38#Y zG47U*%Y7RjV##>7ruUyno?Vmn6@4m4H^Ev=xj8ira8}(7U-{GjVkrK9q7QxmByI2T z2EEoX6zi?4>N?|3)zlIP+|5${cC^k(tF)s-a0l2s)5heH{a_{je_lpIKlMspGZKaD zW%;;`DQ~s7jZX+A(w_0B3zt8Rc{+`r_}w+aq+{Uoi6b4@l&`PNot7AgFY<+d350SA z6^Eoa-lG%swk;ig;wuqjC=3q4G8sIccYlVS*5X)h;&RXE!IxFghshgnLTEJ6`{UNV z;lUhJK3;)aA>;ur7>?aLX<^^I7xDYW?~K~U_>Bz6nXI=IvpvQTR^bldHUuvy-^&N z)RG#T!r3y%^0oiA7CMI1!6H2?M+%)`vwGgwSID!sn53nZ;4MP9rO*%cvWd7)6sKkR z2`hEK3=Q_ZkNZf^ZjWVHMMK=D5a&K*)eF9*xO{*5v{oG2?z7L)L71k(ClRNIzl+i4Ll~4$OOl_vm3?+NSjUy#U;NQStzL zAxX^lU=+T%L{00%b+>yYTKhCeR~*Hi_kP4oiTN2rkYw>B$=<-}jkA|j`CIZ5vYVWu zIg#e`u)QxH@8>D?#}yS1nM~Z~JN!pVmI$e1T8mbwI_HxNSWXPEHGEwDlFnT;kzJ8TxoKF^5WWM~+%YCvjct+_I>l zfclfjTeJ77{L=OwNhsh-HJfNC-0P`FH7{;$Cko#Q8#hZzpgvSm_nG)OQyf4Sk z)Hdtz-206_c+KSNd2m!J{~icZ_(5UYu+AV$@OQu<(88qC|Mz#zNH;8%^{M(R(4Aic zi_n;-lStV6M2&sx`Z!HhFoT%VY~xEND$puwqCq$&9yElj%$@NXI)e@XoBAEgev;}Pd}P;17^91X8Vjx0Saj^Rn^^5yf5N8ZU4ej;!2 z6YLxDJlJlc!IW6Y8VtV=wd}Rnpcw{eZ*XIR)terc*W3b&QeV58@1}IGeYOFS6DR8v z6hH0P!fMJs%;6uFC5m2Kte9l{X|K#p9%I`2vC@r!^_4h5A_Ct7GQ*2x&}(ygk}2HE z#Hs_wiD1Qc3W+5pWcRBM-Of|txYKW8v>&B{Bhba`b+nOno-K3%eVyw@{_W#^0|4x} zL7jwaLI&ME9Gt!@Yl| zh*cj~=I7l@uG?0V{e7;@<)!kUc_7FO#=;A~M=(0x&RT)mn?`ZUZL^Q48ES;5fg@Pg zZ~bEL*G!lC-_ErVgF7Uj_-Sra&yLzce}DPw9n79MWm+SCYWH)Ig7(&e*12hZ>|~1} zy#(+S$L97hq%-{u?hR2G1RqW6x|8Xo1%@%c?KI1nDet)Log-sE1(|+T`!pnRdMJ>m zdt(aeWYY${5V>yOn)yzZcM6L>1puH=G<-*7^uA9M8%KqffXoFRUYWZjR!K$E7Bru& zyQsDczywz}^@;Hyt~qvxz4@C?N$pz!%fq1gn#DgH*yNvqEW4JO5z*(=H<201+kBY(<`_| z&`@BCZi@ILTy(nlaKvE75ctq|$iSwOa2g4H$?aQo# z@h#@+^`(#8NpR&?axEOUL6*7U5;^UNf)XYeZ|!Tf%TH7xYRo$I*pmQ*0o-J7b-CV2 zh{4eIv3r1g$*oam|+mM>PeR~P*}pF1pDtWX`FCFm|C7qdeD+VeZM@g z2nRkc;~^-&dxw31{U-ad)>|sHtMdRpCgF*D9M?tx%OZ5KJbv3#8MPD3zsK!T{RBl- z&U~W5+UDy%6CQ!Tiyl!>SIej$@q>B!jUtoBB^WDp<^$c~HFrX!88vg3tIdxG@iO?{ zI&dxfeH9^>9?#v*-BKb(bKkPtPW6QVnFkT42zoKEEAO7;E<-(dZ%{;m4f)j(ucey* zeQmTY3*OiHbu9KH!rmX!Sas?xIf?f$@NKHuj*s!x-&a%l!KKUdgIMLCEb3kAMjj3* z{Q%cT_!mK_tgZ$lYu?Z56KV*Ixg^s{={rkgA%fl$_pM|YNSr{)qKb08++HPjrvev9 z2a#G*?i9UmzAe)x9H0EQ|H6j@@Ln^n zX(Nt}eNBWmN)OfDw|wnnfFM1IuHDWV8DX+z`E8h8+PyZD;;uY(+lb*|$4+^5-tx<- zp8NKWJC^APZN!^xjOpz;Y!iPoI{vZk0Bq?!dAZykZ_UxTN&r{A5oKf&BQ^6YG^eRJ z=h z>JtobyA}i1Z{daAstosd`q!6t=%LP1oGDf)Ynk%D+_?&;TOSVWVc!n=j-wpd7ypfh z8WWLGN7FdBhY0+_`eFRZ=^P0#H$jvpJ4BwTb=JOZ^&J>oJh#c5dJng&muoCS?GQQx zAK?lA1ibmW9Uv9%Gz4>E&V~Li^AV{N78UZcBm0|klat3;$w359sD@y5MPGb7YP%9Y zzGO0mB%7cd^7FcV=6wN4%eRvKlOZi&m$MHlC3LUP2F4}@l%^rGv)hlY^b-i5SL@1P zVC!in9bk~W+Br95EB$x@gOO5?>hk+Zt-$xN!eO1!eZdUOcLtVmpi>>Xrc2rcL6nd2 z_HkeHqb<_gkC&W^Y&4xD>FVT^?m(CNm*MtmP;Wx5$8FktiQM}h-^o)dN%py&E>JrJ zJ*-Jz);Ax1`So@2^Lbq=kM9|K%d<&YGSI4_r3l zfg|ZXU7u$t?qOS{97=MbpOvqX!?>l>GlfPEea-Y^h+2?f1%cZw{eiu|4KaLk%EJKh zOn{18ZNu=MEeu@Du=G3LYbCC}Aes|4vvEGn$}N8w2kPW}s~_8Ch7I>@^JZS+%cqD2 z-Gg`1Hj-po1o4(}LkPy&yT|AY7aO7IP1!5Quhra{hIf>C^xt_^gJo=;^agS$_);`w zKzqcjyqZ!SSTv37S@oE&J7Y3>{hU+8pQu>N0Qa3Tm3Oo0J@`&)YGLsy?KJJwYvmuZ zO4gd*K2;tA;rAcMDix^E_tHQP-UAJ&KE2My29n`eP|XwE`05zalpDm+gCwDHh`ZDI z7HSzh1OE8xZ$E~Z9=S)bM{`gZyVQ;A`*OYnpto}T9?fR#+WDq!wM z^;(=OLDIvQaRXTR3!>R1ACr9vV|hYJyO>mzI>>S<`t3VzZZHIc8-T@@v;yMAt*V#0 z@N~Bq>fv{FH6_UpN#L|%brT!T=|u)`wmux z&~449Wrl2=UzOIrFs#At!doR*kf)a^u+cjV)fO?1oxUJ-*980(>S3XI%o$^J!5#0o zhmC%7HE$X(Zf>2xg*D1k)!96tE4d{!!+7)qu^grb9-8ovzT8dds3Xzx+4SO14BR*r z&99$d_n?8w!udzvDefbxVLKv0is&KV4j+w$*B!Uxos^egSNJ+g_u05G(^lZE%&9N0Ym9!AWWNp&WG-$TSnTI;WZKM#eEWTFp&3{}nQKK$D zlV{PhNbbWl>R4yuk`)}ha+;!*uiKp?zx9a{_5mZmOt-=n4R5)CeOid@kj2Hl2?&;0 zwH!R^_7k{PGVfJzy4iWn?P+&q$$J?h4?+u0v&b^)c8e!h7-De!?V!SL9YJ8kE2Pf= ztD@#gDk-OpXbZD`-YyR9){Cr|W|(sOohX2a8|cRU`g>2|4$i2*W*g~@oPU+hF>iD; zscm6s+So)qZ=UB^>wkR~;=F}2^VGjFdm#G<-Asvrf#;3GYQ zNQ~4%8bjR*#yhJ|=dH7@BgYg!bPY8eyI4YWBWfF}t+E>wK=ye({lTjm%<{O`FIBu^ z;nrj%9d2>WE7}XAr9zpO1o{o24^)EKm#8+SHq(4)fR72FOE;`u{Y~vLdY@QtUgG7{ z93iPcRvOv7b=xU6iQPxL$c^Dn-;|DJKDeS8o10?@MI$?Bid47_eBtZp2OL(98T+opp& zLs_Fr;*cA@n*k$k1_44DJ!sGmG-vvq04ei68B_71e1G`~AW?&a||M1kRe ztF($4IuAgy3c^y~=oOfz;TJF7c8B0t2_CEoTMQpcu;a}r!-{=GqTD=4kD>Pb!muRd z`6E~7-*t~LL$Oz<+@f4SIq^tn<;Y1Op6N(_!+A-y`e9$#XUsKBi93adx6*~-^Y7Br zB@a1=c~Q?1;$+LG@6J>HTA@egSqnTVjiJ2J`_j)lbtUlcCg|U{=E`&!=)YPO5lrlc z&;aRtNK96DrC2U@)!wa7{DFK}@iflCH!HU4^(X3UlZVH)n9FYoJkF0x>`TD_kuosw$y_bV!%(1vmHK&081j^*(1Z-UuFIM z^6yVS#lkjnqn{!tHW%FKkYc~TR^0jJObv7I&MwiC2rt~fhv5}VmQnGM&CJc=@_^~8 zj0D(IY5- zwyA$7b5p=QJzL@Hn~dwtWrjvTAn-EMFqCTwguMYAxG^wS7QTF&a9`uohTT;?CLW}m z3;WAS93o}0Zoj`MXP;o%IW5cn`(0x!-`d-3K7&|$BeBMZ?hsuP`-130M!+KB00H%< zw>1rfH=eWWgP=F2PO!(}E4T^8*T`VLKVAhr$mLI!J9jU?-+T0Mt>DA>LomGYDYSZC$RgXPHWTMEekxb^1FEV~O{aO6Lscm92pM9S!rzFsq&4pc zUEN{dK*M4~K(KOX_au|za;3mu?S9c*@9|bM9|KX6sqZw_dHP5mA_AhLy?D6EuLYW~ zFD@LoIz zI$j_^Y>Yq0XLLsPuo9J9ftq^p6`C_)OfN#(uw^v#6h4T$*uN{dz6e zYrQl~^wXD0&vQqU^C#H{ci@dRHlYwGy{!;p6JELcN}$C{%`>x3TU!R>JPt(Kwur)> z`09|bAM#t)1cYnW&C!c3yIr6VI13jS}Moxi(uny!N z&>keTc4@wo6wGxly0F>tBBZQ6EHCs}4hqb)rfDHjZTOLLB2D(Vxe-w}NGH zy(i0GA*BQn7yIb%74hwuQ-yAS09WPV_SYd~DzWk;D$C3_GS7Ar&q$UnAF5VJ)DRznax zZw^Y@I3~YE-*c>JC;iTbyl+Sme(vD+S(U)+>jGDHIdz)u74g#{>EGAwYV!BHlW#EY z#eQCQzC2_I20vsa7?`s6EDRs(y3M(dA1N3MmG?8cal@&g@gAA#u? z;P01b2S9z@hwlyx@Xk^$*}P%DPQJfM{2TYVPN|90b>-qaOTr@s&eW_AA#C#UgpYR& zv+jm!Dx)z(xXkhge5Fd+VmYXrCnP%`wvhFsQPERu=ts$eGT~lL(w=A}c*0$QGT`iE zvy_)>e}3Eb^2Ck-TIS{9Ggw6()R}VqO6~~d|AL9xafc!(PD{DRYvIc<^0wP^K)Zb^ zT}91UOi{!r|5rHx*`28||HekLCgyGwmHF2TYzrjFr1MJLcRBrS1EScjIqdzPUnZCkq1=QTY1rgA{Ek6N<1V2W%u1eK&aH))*f*3Zxh_HS%mj{Kt(u8kY$ z=F`xA=HxDKX?&ezI8IzgGN;pW8n0~p;=OO3NoE=ntoK|ydp1oLIt|Poa`i!rO6&9} z3yJ7rI5Wf&iuTMhIcNTw$LtB#t$aDJ{d4X(!h`L^&9+XrtFdqPXpk6bVA?c>u9D}8 z0cPcLQIkX>WDwkfp&8b|o5aS1I{O11YtGk_^Ib^xG;s9u8xRjtJ?XTb6;ANx>Ws2x zxe!cNUHdk-EQ3Ms_O_1->{l9RRDxlG){? ztdMNO5(pR$` z-yu4xe2LrDZL?~EBp{Hvai*D+M{rd}ejfYof_M$T#~4Fi15Xs@<-WF4!`ac=AxW)X zL&$X!66_3WFZ^@Hkf;MqPwL`c&rXJ9Gn8SHSE|*<@7I~Ib3rN6zPTo8(bXH|cYmlW zRow@VW5HlE-d=;?NkErSz^_mmhl8XrBn)xMOMm;)d>NR;0qWvfgXqbsFX~~yEv5<( z%#UF^KNjli`@D{(cHbiSW3GQ@IJdog)x1WT=P4I~{BCo?d753^s!I5n$OIx~sZ8)i z#6gc5__n=srVD;dDUarsj^E#7qk5M3{`SleaK)^@2VWIyk9&k!n{SZSV|5PHUA#bR zd8M71_WhP6-L<_z<$jGf0Yy~>t927$R?9(B`$=t+)5m7{tn59;>--9yG-(AE)bT5{ z#lvb?>2Om_>qwo}0@&pOY1Yp(*R;XafyleB;m@$X9_4iU7r->iW5pnSWw3!om{Spih zHeVF+t!CU_f;e*%ciMN6pzdmkzC53SymU&NcZP>ENva1ay{zx{=lry&q})EIlFt=% zJw%?wUjoZ>s?s_7C(9cY{M2x7jL+GT>>_S`Jql?^3#hspr^zLiv&(izwRG4m=adh{ z)VKbvMOK&ZAq+_ezXfTWPNxK4XJ``^`}>D(2Om4D?$=kNyv-B%tua(r&n-hXPsPaW zb5!tj(p<9*27e2h4Nx){((RdC9%j!-b9*qu_=|BXuYI= zUV${VPZ*(bKBiUG~Fs4!l=CFMn;)_~6q@+DY(fMLI8a0I#Ni)dJ# zVu#xqL1E9E3x1cSxXh0;xo~gl-#7C;t>W?cI)S&aHdBs3)eu1ct%c1_^f^-XJ2Z*9 z_`(_<5>6X}69BOGj5b{f=M1bv`yN{(>c;2K9x;|3ZH|0){OYq__pl|e&nQn5E_GCw zIAQD{=rbtB(F2f&2qM^LV0e7h5hDh0eVs8HQq~(nI@dGo)-RF#*^o7|5_&w+s6?okycm64`f-@eNV>Tf%|$?8+@ zUGM6wk!%GmiC%E7q%cKYqT0N{#|%ROq4ts5`&1Y!1E-xMG6(JSzZR zOJ39FANxw*9-{D2jK|1u(5dg#AM6$E*K@yxK-*9&ZWp)ofu4G36r2%a(>c6pC>O9b z9NkVfpWR$?!|9)Q;Jfr|tgL{&3dlZ#>=*sy8*rme7+mc;XJHuX!07s&i}K5q5jQ0J zEK-BJpW?leP*v+a#qa+UQLFfKHGN=<2o0bm(xB8tA~Ok zk)6Er9O=B67zr^Q0{Qe#%29?cV$wF8@9Y~rO!Bs#O{^d}`B!5~b@Ig_+N!4S!wK10 zhy|e$MQytS?<8>o>ZeHCjT?V@X=>dHopc0>5EE@%hp;XG<3!8EldA~LY7r^aS zm-6#_`Qvt%+*wF2M`MFHBxkd)KSI&_k)M*KK7XN!P36b&dftbIY97|Zn>h(b@1W0$ za7-jv@(BCHWN7~9C`jp{{@61P6AqU>qjyl}3v=oZ{;cD0^ba`v2iK#Za^4G)AlUJ* zB}FLEnHyX9r*c@r!cRPac@igLors!GH_^v$6r05ANn!ko-M{po@yrQL|9XnUiDDtA z{^_u*NV9#xD(Oie9bqI{KfnB01uA^vk2)?3yNsnzzTo=l-jI*{7g}v5_(`9Zjx*oL<1P zvXaxIf>>r^J_`okW$n1%e?()6R!H}0zN+~;+;>XXM2eYdW#fIlPrluh)Xy{}3V^PZ zvoH5sy}C}b$vp#RYB472#Y|u$3)qD~k~Jsr+Y&xS(j0vLzGsonfYT=%lw7A9Y`}i4 zZ=~uDaFpbYCMY=GSamr1R6ymAX>vbh3rKyjMaPRjr~)MYPy}ZEPyv@PxEzS75ujD> zMyWrnqkJ)MnZq$(JzDA_tS!iWh}bgpU852)1a!q7^Z;{h6XILx*?)bxd9)e))GIeMA51N;?nkk1F_W%la%klzg)=#1;?0+u`yGyFf>Vzucok?J~%Y; zv}8PUHHE!Cwy%2Lvp2_gkLWPW6WBrx9g=AP<)o=P6!r#mN7V`DpXiwD2q12wm z^@@R3>!NKd4%yk_t%fYro?&v+uv(;VFgppLTjm|7ls> zuf{b7jWW2(bmjQ#FM{`4usN;dtUZ^oO>Aw_n^GkJS5Cbm!cwo+VL5A!^vshNyT(QcTqfID~*9A8Z-#6`8&fR zREdz!1>1@2#}OgVd+b3&rjy39L0w7gu6y9u?+J1z(pa}D{}yyEw(*FndBUW`VpR@H#mjq)d8`v z&x?i@!t(2NI{wXF^%;d6DzY!(tp!Gmk|> zPlE3B2@H`wy)nlYZ9LBD7kPV&ot)XZp__9bc*0Ab{8cO1?yf?|s}_ z;^Vgc_3>a-@1_^sz`yg~`ykYslF1)7#th*2n&uhlzxE6EVOkw-hS2&OW>yA-&LEMfLEyf7*M> zp;cyIcXIvRml$ZWqdW~fVi<={4R^Z)Zq7%Mc&R@-mG7sXSz+_y$y0zHuG5cg<-f=4 z?0Ev*GCpV`5~9gamA(-J!(bI9oqTaq9O1rza4PlpMbj`(-B;~J93s3u>i|t0;h%82 zeb2^0Jy>5P#6I~)S!9si?$RtX+2=pJdXG|qS#jG*ukU{;`lnKG1*e&} z07938G#8PxzzuIJGJjy(o4=}RVj_%!S|FTFrH$nnt;?MEgm}^=Yk-f;c@rdN5O`6o z_l6=vdoqb^(Gcc(1R{yJ@z4x91>)GHtG-6Z`>~>9^Q&_n^-(U3{_wqpNKz!0n%@79~typxQF3T?1zI?9FG4utOw~J zeGa?o5DxPpI2`_QxP1=y!|QPSU_F7u;e0=6e~169tmA3|?6|g z`*aqy@XMoS`_f29sFkacoy4iaZEWz}fdRWsw6vt~>)Yg9op!eB`T3rW}<-gK|2ye|Gg%Y8X? z1fPiqE{EszF~6zw{-Y!aBlUYn`Z=4g_S=TN>c*yKyW}j5+%7#-t>7zPmJ5Od0Ue3% z(N?T|F@qQPB268r7dr|dcemSRNhfL>jQ#hl-xxxaig^r%I7q;*hx}3?>=YTpc$6749&rgJWml%I7DWxcgSs=r5IJ zUPkrj{LZP6{u_;bwGw~BPZw7IMxXHfe?FmzZ~Skx{BIO>70M5pmlXNmevlylZ(AKj zSgYaw53rpEC4L$`nfRqFni%`&f@Ue!E0Q zE`miIf=sV?<(I?h;V64lZ9eP}04egS>w9L|pud_|2;vBa+d-|Jq3@WpB>;ABwb(OC zPLTn~IdlTCOQRs1JfMKs)E%7_EPI$bp;f3m0^X#jDEBm`TV*=GCYFgMmF|m+_FYNA z%-=A3xt-NH5|Eo(HPjD0t(7 z0LJV22N^eXi+@Np3(HsK*&n?81bVz2KHpO+^O-YBn zk0|@Y>#~Sth|);=-{XxqY)&dl77XAyy4ZW(|0i^v_0u%mBZdsFHy zsJ87Du#Y_tU$7|3z00FuY4}Wq1NtH*bHx=y>1k!>124)-AWh=4Z7oq~nd1Wqb}Y+r zZjb02{{n7O!P03yuy;5WPwY8JC_3j5j;y*#ZqMD8sz#&Gph<^5LxXD;rOSaPJHc*{R| z5l{YD3$P)~nL=g-cUwOx{Pl2l2Zq1Wq1h_L`S7tAO*8j-?ff{T(AG<5re5l~zY9`t zccHM41X|TXJ^T7zU(2?6UdLb*R-`KwOG}Sm z@gnF{mc=?9T=6s9{_t|j5~6uk_`RUL_V!pAI=j-ULYU#(OP|`>94bxad2fOHE{#e7 zBxm=&q|%#U){!}X=I|$;o}=}-Ywj=krmyF(PasAc z&F7;(K9JYrs(k%4L^SZ~a_#2_ectcM04M~Eb=~Dr^rZ0F@7`I~*dJCBN^t1Xo3rHp zN#lc4U^97nd0fxt6Fgi?zLEQ~D^-E#4I_sNZ3>cP>yJ5QR$wHsK{YSY?`O;jVM}FH z!#K{3Xmt-CDB8KX4<0R`mx|VmQnnX>&wYyoe@p!GBX>~`$GVt{>mQH&w%+AG zuL1J{gOsgbn&=rSjBedN%at#iWiz6Sm6fnqa&%P$k+%O4k3-k#jl6vt=l;8Ej9`qJ zDMMcHz5qZMUpJWv?RKT!*Ve86d$BsO$LH>ppzKp5b{u z)EGFV&ry1BPnfd=7s&bDeqN{?uiA_R?(I8h5jMC&0V3?WStgS;SNDCSy9r{d!W;Q( zuo_|Eb*Y^UtyapqRtJUQqqTRq)LNJDMeR4|Q}_e5MSBN4jhJ`b_$c^rA%qIfUia`K zY(9WE$tG38h_>ojFVNZM*=_TE<{MoTUsow})@cR3xzL|Oc=HZI1%5~e| zMXatKx_FFvt?-Yc*4mBV{N@5wmbONU74D{YPiRvT%T+NRN#~MbTrA%zeR(?}Qcv;a zx=$y(9=@NLpWu%Hd0TKN47R_XByJyB_<@JK+4+gIW~+LqXhcKro?$Ph6k!u2{I_pn z^4TXz?abDBe+YEUWh@QW6}*17sP6bAI;Q3u6{lP(WEmlu)=xKpWHrAKduJLu(lFLb zkdf#YQJkJ<`fC6|$*OJUM~arxxz!)iu?{$Toc@^Dq&tpc`diA|mAsA|JKAP`aQ^}r zfYWs;@PyL$j{O8>-O{@g0dPkltk*m)CxkyB&YEj>3Q^H>eG``QkXl?0(<5>oMQKla zy{qxY!@iLF1WqBGZ`}9git+zo>$;Xz)w1Xpb(NBNl$?}WHRlKf@&tuvF=2esHC+r2kKL~i&gx!R<4&6lJ3edUU6c=}(GO#cOa#Gy zE5X^R3aG-tfNX?^i{(~-E{W<;o~kJ>f`BfG=<^HjB6Tq6O(PYoIM`(&X)TCY%JqF*No%4;l~1$ z(W|mAO&VkC>U|lfx|kZWIa>+ z%o6*r_yXnTeO0Jm;_H^yl#3c^x-_qgf8O&NU-c%FQ}SfHZlt3lca`?o7}(G&p${j) zsvYLmFW|^5riQ7+pj`bEiji?irt}_^`zrYOqCggr>vG-$Dy3+$bh~^`YP*lIH#ESG z6m`(1;ILa&fX2Fo`)aWAN;s>}rKCy9`7Q;~wQ*P^T6lm__E~2{;d*#1ZKM8}UHL~y zO4;KeD#xkA>E#mnPbzBKMY3Pam{#-BUvA$new8M$gYa5gN68eQN>}#13xGB6R7IclldW-+o>B z5R%LFc4$`qCSFde@D;7-a=Xkya7FxlF7_6|7aMz9v>EVtP|1_V6i&ykDM^EuM3BQI z^xs}{xkcHQ-)@6tEqtiZykj926ecb`bw@YQz@*b5nR%z(AHd(;*)Yz2rI?r$rpFzb zY-l-FS_y>pno=aDD$i6SgcIx8O$`@{|9+W3Y;X)CS~@iu%#xPkHXX30LR-K4oL6hK zo`<{jF!l%(wlB~{inc0MP7mFc+gC3mk;B0}MF=mb37XiWDKyLtZSzgn^?kexe%gLa z5p~daP;5;lhBUrpdM_33@8 zo&0kO;rdDLfnT1^{yjSdszi~8pE;{PM6J}@g)d*0I%x4D>qevwgKYp^%{xps4deNC z-A)g?dwF>@ey`StbWv$yLvPm@tpb12jjazBojvT{-m47T3`}QHHrFG&8R=Es_*R2F zQ8~oSU{1tjJl*6Xdh@<)3FlnY@&!96;Uk?;j_X9oL`w!Zu>)ZiIh`#MQtaNf{qk}4 zjJj!$>@4>Vm>sB}@y1>lk&p~KBnwEB+eHG!b8d=PO?F^ke1G4mDC=qxn^a*A_~+}> zaYZ)YjVH6vFJW3Q#yQB%`fAt1o|Fr}`?ijboVK`359cQ<*5jglUMFgE=*5C*$u0T; z3zFBCk4#V-pI|=7I2QtB+H;QLV1$oL1y_oTQNrX-CZ9ze=-U^~FQlJC^&nC7?Rh^W6T4v}{Kw+!HRZeC&r_93{Qq;Y_!;XyQ%xGH^&^66B_8ZR7zO{Pw!u}NT zGKbkAByVhFnxJn(uQP_4&Fx_Tjd`{qPi&OuiIelsw>VAlD+4q3ns!c=$tQ+Cpza0K z*kI<$Daz+_8roWG$`^E_+JvIeQfXiTum>uUdH`)#E*W3qE;x)|3hNwCc(N{`o!)2t z8VlV<_s{2L`qlLbQztMQzcfj}z4;c9VTz=K2N%k3+66@Ao`Yjmcd}8tHR?aw6*zq9 zjScDxQZlXnwIKoa;|h;_T}JkXZ-YTGhe+qW67$P6n8UsYapmo+%B;srvl zwH1w76QM9y(^CrnDTU`fs938B$D{t>WsmqUhU`7*>Y^9*ZSQql{3b1!qut))Ip>sd z-+BS3!En%TswX?D7@Zob6IeS|~1;Xi)5 z{;u_lJlE4{X0n6kDS?@TZ_s60CDTZKF&B3;B>LMG_l+8l^NHD=5NIJv!_VI5I3WF3 z94p5D0_wnO(ia6&H#@jr!2hL6euvHr(zi1DA0HW@P&?l)X^?e+gRqlL&hi~$2Z%&2 zIF7-vk8=`vH1o@IVOBfRtF^^%E{NU}TuzirK{TDc?G-~@eJYjwPXk{w=bp}Xi(5X*2bsTaY(dlSUaK2uvU&{7D*_ zCwnQyACsz>T_~Ss9ed4sQz^9*c)@ek%G)tO&kg=9AO_?Qt#0vZSaR=k8|$u7kDR# z8It6J*~90Z7GCbA_H|phzjfcdBw&!iwi`#jqZe$Y?p$UtRzIAuP|0`Z*;udI5L%DU95G&9~>#^(;`%wE&_$iXyx8JOj+O?rro(M*>^;GPc*@T7Y%nt>! zHmAo_ZJ$NL5Gu}|KIHc}n~taUgHlRREGoK(^7^_81Vc0^>*S4B3$+{uQ*ONa8{TKwt2v0$a)5IWy33rD+9tHg3SYLbOEyaldG(o!*~K51s{t9=OtRoZcUf;_!T4_n9$Us?+?czifYRf6X2; z(cZ}(@vmR|)vVapZ2H7U_H5tUo0Hi`l*6*59a1D~0IY}b?pc2!*bV!7|H8aY>%XLJdm8VFZ7?rJEFcpXcf9xz?@|Aq?zuH9viy+49T7b0IN66X7lklau^}zK;YGi1W(?@>afTA3Of!tA4C2SuNF^ zNd+?7f$qXR9jmw07Wf9`NZ$l2fCb?~3i9#QjwKN2(007LECrN(1P#3^pJNmJcZdDn zP7&u&sk7&iZ^Q3%gLnI{_=PR%T--Q>0wpPY{B0ho0oin{`@$RgHhUue3;1x}ZN?pr zL(9lMzWOI2a7*|{-jZiDF>-}dJ3cNMw4y|WxX5V&T)T|-FbWV`Ot1>UB6Mls({;u9 z)@#tmS$MkfCwTI7%wraWxq5%#p>+pg8i|BoH)HQqY%D8PJWPseBe^H@-Bm13UxXlT zxI04~%&XRjm%ZMHd?i%8@rMI*e{PN75sCeLs8P=!PsBVoV9RHLZ<1>FEHeTndQm0! z6!lqG_jHqFCNgk~iLOwKO3~A5*_)Xn?9(Ok1#>eaW2uLJx1jVT0~L0iL203d1_xnpzy`NB-OJc-?&zNoZq z?;c*sg}-2OuD1k+aPYQ%+$I-_l@wIvLRCXogoFz+^7F-kdk;)C-ZS9*8{m+Y;;n7;6Zt(~Ddv{x9ETiAH0wZ8KXX_U&oG*`x;E12BhfvkFG z5Hvxc4MQsFd1uR|X)ykzv+a)1Y<-jmS?()tyFCczCixM#;B}wK>=sq2Khh)zwl#+5_82?SiJ|S6Ma}!5$Dr6QD z+4H#AzzKVu3%iW9Ggt!nXbKL-)C=WO>)sDe=SVbhHdA%1#WZ;CYTowwy4bCw5ce=! z;a49liTE*|VCoq6AuWs1Rl?@*W($yW{X>m!AuX}+w)FX;olVtFl1##N{XzMB&u@|x z7K~9UdTnM`23PV{eZvt{ed3N>d z%=oyAaj-gGr^7~NJX!~Sboh*qUq;w-D)+Z`70aipo*KQrTlKr~YcSb6qZoDD^ag#y zqH}=wKqx-+>jci{(5}D&%NyjLKsUJ-=@Ft3_)3}UU;(}L$VtFf89!Myf zLWl9mFsB#4>5q$TGcWFL5iD})Z8r9mO?T3dLv0+VffuV0pHt-X1>^R`q{{fqH<&b1 ziyd(B>dUN=2NudO5U!%!*Jwp2E+kQD>j$u#nhhJj*|Mba{hFu zgzvtJxaTzmt$n+UaKUOY-lEc;?8h}c>qpDhV59&)U}GH)C%TR3TaslLgObEpgIftc z84SPo#)zo!C%goWCw>}PkG_mls_YS6V3UwAHr1ZivlYoB_VYHW6lg2vaJ$O{9l&S$ z{?$!ZKdo+b7){n zB3ECyG|m(spFd5fTU9gy4rwc5geAHEdoV4SO>DMZl=0#J&WA^!BLRav!d0#)Q8=dq z51(-~$_7O0@AWzLUZ!%o!Vecicnb01ob0@SNi@iPl<4u9I0~p@*-S(RzdRvr<+620 zxX3n*^pK-yM3%RMuN?o(zFe?`BXn-5rY9$wG+jo%dusBoxa+%&_|-f1&JBvA^z*XG z`|ezL{baMoPl++d(q{7_FAMp2f0NXk5D>#1+xEJYNL2WzM4qT5xWEWQxId`#A4%|J#Y7GLuIwyL^{1#+f85bs4?h7;=F~gLe9!Es zT6@;Ep1JY8$aM%IAjwNU2EgywfE$(r5=9n!`&_xkp3RI-4>=;Rkej*4OJ9_2X#J$m zaV%9}+X?kMovV?KC8LA%k8@{`h}NqCbk0jyIK4utF>(E98iBOe;6i)5mF`hJNe7Df zy-g+uGp-9v5h_as>5-`gQ8wO=Ff9nf36R`}XV#D7eX_elTE8_plP9itu8tJYuFqU` zf`fbTz+s=G1Y-ft*ZQn6S*+LSS6>loOv`~_Q@S3$;p#6UA}9oXiu{zvib zy(Imn8yjbgL-$dUb)>DXrl>u-&0Q(E-kzSPT9ev*3L}JS{<)3iZU(%_Y?p@7in8|Z zk=ez^xENfGI&7jUMqtXvGy*-;P{-FtE&M0p9!>T{oj5>|m>a1)w_^SMNg`ir{W=n8 zU=z+Mn$s6~3Rhjkz1QUlz;+85OYP@hT#x=-oM`)D7Y2>7@&Rir!99YZb8n#k@+DA& z!wBd{Ih2#f30%2DmfWA*W|NmlTcAiVC#T2S%;@?WfsF1lDv#*X0rh}$AH=-!WYbu0 z_8tUD5jCaP;dP4-4S(N$5M=0wxM08sfc{fZk&jF{wv?T3Z*kJt&*?5jTKxjNtnh+4 zE-xdGU#}9;W=c8z`N9_i2>|u(oTH%r)t~Rdmv&gq_g>i_=`#Ajtj0I_YlmJPf1>Rm zqv*L`$Zz%+2O3W7H8owmSo7?D!{;ua>0`ZJt4=Q}6fJtlhT^kB5mv%EnU6&W%`9kzC)gs6_%0AfI(x`{^awmNz9i5HPr8M> z-u3jS8!bPg;r09Z1E`UXbZ+SSRyl6i%(vT$f1K{1E_A~to1!S zl~FPH{xU&Le6U+{fv65d?DOa`Q_@p~3VR}svN1X|usdNnY%_6Tjvr^Uy$ctd`GXX~ z`I?#^{N6TJG~L$z_xl<3i$Jo0k-i45M)^i}+aWC-Ry<>yGi%NWLv=pO_da41UtmQ4 zgH4eI!RrU?kLlz|T=Vu&?2QlK0?MRW!DQtusMNmZXVI4N?^fH-`k0gOb^^J3`SJQos?VJO)%pT)Ma+9I8}{jysKLr{vOScBsxHa zN3pNCEd4$^U1q-Y4pO^XYkkkwM;7*~9hY7#^_AGN{_205!DfNV){O_BIJo-`2E258 z;wr^^=cUWplG8Hb!ke6^5sJu9lx3*aJhu{RRfX{GpgBvV8pLz&&}4icBogQx^yZ?4 zf){8Yzza)K{7B!zwV%}r1Gtcx0#gi_5I@xhk}!C8q7dvUsJAoifwCr(9}w6LeIBJBwvr5IR1l)LG-ndTmG_^aNxV~qe&-0) zs)Yi>VaFU!uVy7k+mj0WmD(crw{1GRB~V#bA`dn4qY0dRlM zl+E7HZ9a{c;SY51xa!rnKn|7u#(xwm?Zl?fhx$fYeTJ&yOLy0sG4c#l?3q|gzEhJw zDHJRbk5r6B500eI-+kRK${w7P zz0jdsE4U4SnS8xa>&|6HpK5)tcBKhIZBEy^9R>qegb?;ah_1%(4B8q#VH6f1nppz} z;e*1bt{cxsPMqguW=U3PpvQ!~CVR$G)ND6C+#OXFfcdq9#DJK=TOegKVejSs6 z>bC_x^J4#MU%zOswgdryGlNk|?cva~?&<4TAlG5y&h9T5SZ;*4o!{H+8+HlVG8`29NZXOhx|h!0&yZ$xtO!E* z{@^bO>c(CCZP$1sz55TZ?8D#`72=to&yIMu&ihE@M12nvAUuY5FK>tpa6Me%_<_(G z;6ix$d`$C1I1baeLDs!Lwy5>uPU*3^7 zZrBe*$!}k1y^U+7dWnMlhk*^cv~~vDcou@EK3Tc69y z8taHh&XUiMhqSj$Y+Hw;aEXBd&g)KCKPT&CU$5w-sDFWS!Ga<2NdO+%YX!>S_JXAj z<$eG5*W~qN_25tuVQ%^2pQ(dBzv9;v;Z6T+o+tA}LK<(Wj*BOv6DY*PW#3E@m3KfH z`u%sr$5|p7vGkRB7Q(5*_Iq!*6YQ|?KV*Zi2UHL^c}QllTv}diIfH9C-a6c5&r5&~=HC)klKRm`NxzTb+Xv6+y z*XfWq<*0hr@iE@A%4~-z2;ZY=V@|aGh!6{YwQyG(yJEgb0a?X&{c*Q_6u}k#dTrNz zMH}p5&6FZf+S}gM-+nLIF60ZxhWw7+tPXptyIZVMLw)W;?V+wcs~5|DW7}lk`!s=# z*>!In4o;`|=dceT08Hoo20MGdKhDpLj+zD@-A9(PUhw|i-@6BHNS4?4=#wYWvX^OZ zOCI_>(n9lGxlgR&?<+5={h1jbO6S3uh7|Vrde6{iKX&_F#aF>m&1CeL;j;$}Z>o8} zh7?9RUkAjRa(dEx2)rK{??W5JGyLhxEZkcHve!Z7VN9Tq2q$n_F2^VJtgyr?M!H`> zy=Zq2NFd=-oU5_yOZBvON%f44g~T18NwU6PrGQHjDxqYN?8m$N|E!N>!-153q@uHs z23heMQ65WYAN0R6nN*H{{e%t(VB-CYjPc3mFyrIMGu(dbk`%VDmO6J+wrCrCS}3cE zD$f@!1@O=!zxFT_HVP1YZPo+ECIbGc;`4`6QOvoVUmN}49~^Xm$)9zUj)zh>v;O`e z>9n?t`=<)I%?B213MAg~M_exa#UZSHVQP@PyYtq@KDu>pJI0$Qji0uVW2@kB;Ta_^kc#%q=J6l@ zU-t3M{VzqZd5=YpjNjOF?|<^!4nh252U=V5gyGsfAQ>mwBDIuWGB~ES4L|6;mH9p1 zXyGd7lL7Jb^V<6`KE1XZ@wFS<_iSXO85(v#IQaA`sEB@5(9+f%qUBGX*6%OJ=&uUg ze3w?1poLKGNsLz{SJnIQL{6|DjdC6Kv82Am@4nPR^!Z#L@8%ppzTsXM!!oMF5pTRv zQZ6x53IU&$P!`zE0+vK&{w*aj;x{Yz>(69m4kz-zcuK+#jW_pCs>kE$40;z;r*{3M7A=TrIzhFzvVDv`LH2;46fA`kW2od1q$s{d{5{hIcu0 zpDfsBaf>-A@%4fX8!Npt-p1TDBIJiI8+~V)6>TV7@+;iOr+FWw^l>QW<7)|i=kKNP zLUv#8zZmk0Fg<_l9Tt6M!@XfO6|!ei%%#oRI~N1>ol7;~5e{e6_+J0gwtnBP`)HzLI21U@Ow$RT|89h<;j03UgwAlsWIyWVlN3MIg=;r+Rs79^^KS6Bj7vY-BC**0PDula(5 zh*f>>dKq8_D7Vc^h_ZVtV2|u)+eHABEj)A_x{gwz*gq39ES26qv)%Uzsp4=4h5cfn zy@+9mmq4~C`6DlrTwU%xYadJdxLoH>?J^E8A!!x5SWl8kuK2ypa2bNdFCB@;RKH!( z%>pn67V8iiy-ytQ zZ_RYatM@-aJ2*Vy@pu1&|MY~~m%1aJO+SA$$W_`K2HL{;?3FK4KBV3;b{Y@}rJ7g}n#4yJi84>lR{ezemS-HY^zNWd8+w*Ru9&!G{Z)eD^2@;~92hXnjns z+W!838k>kV$o-s+`q@t3T=6?Gt2Uqztw)9SfJX6 zkAeHCkx4( zNST}2J#OD;x!;QB>u874+wZ`0SPW$Hm_xyBxPCzey=d>4)XSyIvrg~VM?c^AJ2-Q= zivTO7u0AY@+7Z75j$DYo+61 z)PH#7Xxr;pzRh-KkI1Py$EkwVMPkL&K3w+Bql5eF(4#7s6%gwCwj<#VD?tK5(GH-i5AjEE^{gbLx?? zYDH#7RIjC60G+HLeD}CmkcAKY@gn+4l{3y!dFB!5Cdu$?S;6S?cug4hBE{+|u); ze)~0Z*TSQo=U)9yzy7w2GK%HT-ifH?`oMR|b*q&RIe2OHNHr z6?H<$z(d(2EN}ReqmM7UOSA){xi!=;`$I@w#~{tuZ@bS0auqc))2n*aL;B!|NAogoUQvrx!6Y_+jiN*9D>6Vb^1Yk+ z(DWDGKbTLz4n3j!e)3X-f`;THJ#DlT+&R>*Ka;r{ynbTLjJ)mSj>JX99bkBJpH|>A zhriF=VEfa3%3HgojH=WlIgF?0NX{}cxF6uRBNXm6;@RHLX?5IO_GrqRwWt~R-##onJjeDI1-uY?)#3XJVhJqYJM~iD-wyiB&w^F(>L{Zm8~NU!Jji2lhwuutF)i)ilmbkXko{p$IV!5EqO~JqlVO~qXvY=5P*I&sl&-K- zT*ehrQjISr$NT&}YsKv%m@c)-krgIS#kX8GzzJW6glYZ$_G2mLO>W1#F}etlVzee! zl6}OIm;ThGhz`Wi^DL3_H}FdMCrlju59TCAsm&8M9_lSEq@NF^WPblFh#%$sw#WEU z)1K<}D~l(<=-E&Vm7l32E5kw4?S!oybD;xFL<^a$=F@_w=2#g>DxYfO`=q?Lm^-P~ zdi)98J1IUq4=}9f)m9p0SRZi)rH9-!67X`_@9*x5>ajvr53$@R)1!q5lHg5%m=-k^ zzfN!OdOP<3bkr*gckX=_QD2f6zGs`4y*$_htMVCeeg&aqC`fp3L3y9<7-5QVgA#f0 z9Z-*6HzokH2(LoVi2NNFLr-3}=61fkxMP<#C#zKHSNjznF^I_uK=OZOU>VtrDN%>$ z1ywK;>^0+jkYQQ-xT$v@Y(AXMwyzIk7PT^7`-5WjKvS?|^c>0$;n_3;64wL^+T?UM zTP|5OaEX~lvA>@KN=_wE!pm*GXJYlNxHFGn39#~3^Y6*>9n{FnjDl)R!#b%j5Srb^y`3pT2RvxR-8%44QS=qo{&rg1!IO49Yfv3ibZP=6dOp zxgPx|tup~v-yo6@oz3hgc2hdS+90;-&`uUA;f zBv3~0thU2@iZv@RzqC50p%KID;y90-wFiVhi`HkkgPcLa^L9Hv86K}Ld*&ylAMD1Y`M(dvvc##9=UBK_$g1okBg*uoGmSw-OkI+Cj}sx zHVYdYSe7j2y#^Ciam)8`awb31-iSTB@lL&c^#hG(lfb^6jXY0mZp!eRRj&LyrMQuQ zpOpRmoPa15@r;mRU5QkPQ_P4;|vwiv|ZXYi09M^68v{h=%2d>$MBhMo34q0n%DC zBqv6-cN>C_B(1p~y4@`AFqD}fT5~X##xj&Ey)QE#^K|wVH3aFPZ~5M|gR`?}efQW^%Ik@i0)*`B6E zMj~>5BK15cWEXdT!pU%Tj?CN1e%~N~TzymtTGQR5y*24i*!qatw32uY5wdKF*zk_* zUY;+^yTVm2Ut$%vHnT7Sor}kCzr!x{wH~!g7R=L74=~_5^&M(bhD||n)vL+#_Y(ye z(Qo^U<01NG7<>D-iGY(yTi&7%snh3if1BT&gY+)K9C!n8FhcwY7_4tSTx2 zbY)+uh-&KilaZIr1IoYRQ+oaC-;2jq@ee*a$6nexu9Du~&^^uF`j@ zOa7IO4-Y2CPbg)n53*9}l7ekJUta|4mVZhgYAi(+M)NZm34C7~|1K{g{053jh%csmWcQi-4NJbaR~B^C&7bq&FpS+iHM5j#IE4G#CVrIsf=x zqgP2)v+f_C8=UUqBp0*2yK`_RznVP=6~( zx8KLDXn2a*9d7Syrh>+nP*Dv#14SK@;v_vBvJ8K-rD_l7d{@K#hWn>%hN;xI(-W9@ z*WsyA40UtL&flwceKV5~4t0DqO=uG_Ed^HsBwY_s76)SC3&Z)}w%v}tDcrDCcA=FF zY{LvO8q^{iibZ5q(Gd1{3vokJ?c;qvG(WG9o#D`TN>6|M_quS5kQ;ZoC~~Xz8tMe= zJL2)>r7QY?C>(TJwtQC-HmLrM9$PKZfW}o&DLx&qm#57LP-7F`f_nBh^&G)>`}nZ= zTmxY12z1|Q@i%s9VRSr4|bldsknSAfw}*r)F{N{8I2KqG!?jIcAK-` z>hg3_`#`QG>X9xFb(Ix3DJe{41!ZG3?eMRaYvmk(;Y-xHV(9&ZmfA2ug} zM#|^17e0kY0(fzQq~030=SLUTP``tHE{Zqxz!D~mcM zhT=N0&@*`a{@}H8{`{C9dobuJ^bW8~=kTpS2Uz(&q(PU@_Nb0OppJV8>Z}Wku#i)u zhDFEmPJJDNpP2^+){ApYiVRkMkgE}jd)-Y5!wVl@)o;#?RJGinuH|*lj%c+nSyNNz zZPNH5`>}5x7c7}ds&d-zbW4vH!n}_&Wz8d6LOH{M&QCq{Gz-oNB6w~4 zLFeuxP+j{yUBI`S1{<@Q(nulVUt{&B6|58;CjjDk>z>msI#R6OfKheVKx@2`x66ef z%}zSUU%gG94{S0#4xDdSi5oWF)ciQhvXk9VP`wn8St{M(K)+2k4SIZ!Et~nf*bFK0q)$mcUWp6_LXkb(RgLw&!IBS0V?WC- zDP8>puEDCOEcz|_p2KSp3g(^O2u60U{Zsi2r5L_~Y82HH*(LX#Hu96fzK#EWx5n9v zYsTxaXW(;)t6T()j$Msw3Cem4Z3+ z6k$CQs5McbIe|19j|paWya%1E2jw=p4_XzyUKWpqWD=L5-ZxI7SHwsmL0jY6 z>aa~#OWNMjzIeNNa6kR?UMESozBjoNtUQ+K#T0dg*7|!C zqzZ_`-xm=oNVW+xWLHOzhn2-C2|!zwuJ6-VDu5ck%s73D1W$x~XDe(cp5McBytu`% zQ)#bt@R{QHD#OFH@G&c*6ixdc#Yh@vDxvzYqEyY1yQqq79ho%H&Z{Ir38*JZGAS-S zW?i4_X0Li&E3JbMJ0e*nABR)d0!)(g)8GZqHCSpy#q&w5mt{u+T^CiK$zxo7-9v4!r~krwk@@XW;H`@`SS~*N(LdIo>IHu%x0>emQMXKcUA+h6 z&T9`y7vY9M7K@T{)ywJ)SqK*v<=BWE=FNcd08(3g*3+z$?aQ;3V=!1qS*#l&CB3-V)~^*K!Ij&VhK4{=Ks(y@U

yM0z%{ZTmSrsdQjx1<$D=g#@7klUx9I#R@yOW-l|4Rc+Z+XFwTBa53xew~a~GNd?7$ zy=@P#=kBFH?|bYr3Filq4sw`x zd~Y5Sdc+~6yGJpIARfOlf0KbL*1Yz?=5Z>p^B3V}eCXudBQMec5a955 zc#zhUk;J0|?aFB;E4`MT;CLel9Uk06Iz3ZUJ!sbPFPV0v&eJv3RKl-5HH9EtEE_hA zAru4*7Mn5_UQ`-yft4z!L;1xnm=`jYX?)jl(Bm(J;;A6;9?@fSu1=K7iL&(Q2Eua_|w4l8O*yRbv5HQ*23dKy{(fcZ|?HE}U;q&@L@4GG- zaBx9-=%$<@E5^{bj}IsE`g~bE_hrF@-R1Lv^*i9~g$oEQ2LXWsWEgp*dVAWF04h%J zuQcrQ4S6Tw-KeDBWXmaM8zrjS!%0pXVU=#)(pPXmTx%~JRYdjFRL|rEomp6w7Dkx4 zZWkK{ic-#*`|L#$w0(Z7GA-;bHzxuyn&#aY??V>fklMWG-;C@VnAnp84Vcbs=bd%heWoqhx^a-h~5h= zXB=&4hw&%*y+(e7PPQ0OG-d!k_L~K2G5)zQC_*=bRm)Ly++*STFK zWUz{hxs*YLg69RzQ-#AGmB4)L&F)i^i?vj^FYD!7F8fp?_ZLW>|R)?B-afMuzqr({h69g;o=2 z2ZKkje73#FDFxYbK6u{655iH!+xXx83$HZc1;u>Zhq!A%!B)-rT4$zvhMset)m{1j zxNN$;ul~A8hd=B>epBYTZ~BOy|1{%9^!rm{obt)?wx=ui)u-uYKA4)-UlTSs{=ACF}E$cfiHaB#-VW3pYX^=`?O zbDg{EH(L-{Op^TwJol;F^hY8wL3d&K?WOeC>Bry9x<7y$0`qgaTra=_ z&W72qJS55PE5%Pj;r0x!(t6q`o`h#e(<|`C!7HoS6Gr)Lpw^VKb&n`dnI{j-2_AEe z@`c2Jaox<*$9o%(UidNtPcQ=kMjLe^-032oW(7U+EYYnS=6j;bGB@#ivOvU9636l} z@iD%Mt)Vh#o7lWt>yUO0Bd!k$Wc2=3pX#>J*QccJ5x@Rpi|FeaQI(Mwi@eSwxi@a0 z>N)vb{bN_Rb-d*{Q+scE(%DLR5WKYnS#Y{*5X>zTQojuAkG2b(jcmwpu)}?mymToU zRG1cfdN?|Lek#f@ZT_T+YJ?x0U0pKj14tb> z)9n6;>l~f0kSNl$>@)N?=gQ5u(JOy7FItc*W||se&TvV?;XRoiJ}(H{Up)cO1;40p zaj#brKKe6!R&P#swBI2L*ElCFG_epND-ykW8PeWNb8R(`*; z_mAXH$cFZ@mt>YQR)Z3$+3x5D8h>tqs463eNK#k8{;11iQP~-K;ZdxdO%+nO`^=~i zhjYe5e$KZ;QurLK@P6rUAh+uM+y)FFO5k*?$*+R3^yPK?QF6Km!NI-}frgKJe`fU& zw#ayjm(^apQaPeaAsY`)vOe*nUfCOJnD@acPV zd(zWh>knS90r7B7ovK~mUOag8f{81q?^>ssw?rSN)$5*N_p3jqNw8nJO;4BdprV~+ zM)At+rTcS}#kcg~Y{9Xj=7aTG#`2v=2U%=cxj(1IzHE!Ymnbat$wwaaR)tJ%sAx?e zB12EqkAnpC?jL~T@NF1OND90mUuwE7msDhWAVCPcXmpdDxYCT%?U7clf&Pyh{Ft~7 z>gAq#1FHKls#RYbpQnyqSu97qD~!<{yR0&RWh}h=ja%}cw5W0-%{dnc| z{l{jFsx~NKk}*sCXzeiowPCglXX z(}{;8avn_rDvpNrNEj($HnRy&`9%;va0W#sF3bU5yh3_r&KOg1mh|TFJ#ZeOiB;tV|wi*2K_<~_FwU2mRF}>j+QndTQWPGSU z$HF64>pY0_9zk%A-RK=HGo$xFTt9Vjmk^H_6<8`_*K=zw`^Ur-Bm)alvE*N+sc&B8 zK5~)OhdFDqjc9X4ds{qcOkkc~{>}8eTn1KWIVraR0eeiPup)v0?s*N^`mw}W|9B?|Hh z=!F(|Yrx+6s}7!eWL9A#FKU`b3Cy4w6V{$Tx2Ye#eBaldH5SoYh#TKaLirg2f3=om zY^&jrX3ZkHYq|EMKWKfGvQy(Q>y<{Fp-N|uCEopzN3C(+xbLKw(r}Bgv+|a^_Y|Lw zLUxQF5)^9THef&eY?@usvo~k~GK&7Zze0kYW`2Igb-fRJuoDi@fD`W}`ScD05AZ8| zNc$_*TjB$vmpu?QL#*{ko{wiGL8JA3Ox`dQ9#utZ4pg@8(MYY7)(MLnZnkXKMvHuH z-jnGP^Lz|dYLm6lEBtHEVug!EqH$!y3hlj6tU?9WUL?`!>#|ap7-={u`#zNEh900l zUC`OB7!Ot@$));v3_svG$9#0?dw}MqVGV(%>E1(3OET0&1&>sp-$#vq!{bs<^ycb$ zj-=4P8Lr-xGJNgNiQ&u=Kxf5YUj`mml>No&=~+zJ=b6sktf$e2<0Is61hQeM^W3xH5T(Owjsy@wi(KpFaz&q<$KXFc`5{Cg|r zzs>P^BCB}+3RmLB(KnB`A+=>NNy@REkq^uQ)O;lO1Ie{zR5C|6O48n9r;fa+?h0Mi z<3lyNLiLN<$Vs-?Y7Kfkevcu^;DB+eqC*S+-YU{f`OA06_ahw}Vl`?>0q6fUi?F=R z&qiJBryI{5{@QKo2PP#|5&JOO2RWu>#O?Sec*diPu_N-$DDHu_{7gU0{u{V=?}OpJ zM9guK_SO6EkNkvP*XhggQc5RZJf0VGZ-2Rw-~CI#Nu8S8I~3CxX2?A5AaRkZQJ|=N zSpFjZTl?Eddl=_w-(#BRvl54`h}PBH-M>77djQ@j%5ol|?guP4%DXsiVLW`qo5mu& zv$RClh8a+RSCMJEv~1kMY%7a}?I#qjIG}RVObf75SDJ>^wkVAcVEfo6YyNQK6~23( zRH**ZY$_@M>i$|;E_Vg9!dPs6A?G#-I0n%2i#@F@jT>>uO zRQO*XxlDsxmCWcvuy47mJ!(7lt{-uO@<8fPy~gk^QlEj~JmB$}Ti0uJ{A{0({j!^W zyT0a@KHGyrf2}fosD>-?w;M`Wx+Ki(xcoWDs?Zfr?tH5FY$~?<%=p4Q#uAryJbnDI zE=U%`dW2%@1~_9w0TQO(IdM|egZ>Con0i~1xm+LO9;o!_X8x8|`Hg^3qHob-#+`G! zHnRlBZn_xMC)9~a!hb(cyZiNdb$jIF%ZR}F!Bw`)X=SZr2<$3nX80SHznj?KiF+tM z7j^wxfwrhx0WB-}t2OP!Xw{5ITMF;tK6BYyYq7ziSs!REFpTHktVlUXS|9341`j~t z^q9k@8aMT(b!}8i(94dWIso&E!%IwM*WXq!9M<9mi4>7DYSI+CU151BZQAs4t64UZh2c}Zr#np z@j)ogGcI?U8pYYH8u*g#SO^Qy$=|UD;cmMR(vO$Wa(&I`$Av4M7G!QbF~oR}?nq7W z^?~(zQ>9@3irPM{dvPZ^MfnMO38Tc#7E|Fhc8((Cl+bxJ}pZ z9`nAtazuOOey(xKtnIwUpIC`HoXDh5i6sXZfaZ}sP0?>E7ZTZsXOK5%j z^l5Ux13IiaG_a$WChAi2`*fpw&+Ja@~KAp0c-xulX zW)t8SPOY%I=`BOa=P`@~im#UKMDCvp>7`sb;h+zw*Jao1TMmT1@Ho?SOszLA{aAcx zZ!q2t1d^utN9%LvgWe%Q1ziBGOFuvRsCWnSnf zit3f-I;E9y^%HUF`skik)C{%$z0| zu_+;hsIUT8S!kv(jIfrmyy@mA`P~>G_=$B!(O8#tmC)bE&6U14Rlfo_quP>Q5d*L+ zfu$-((pUJe@3(LL`#Qld0GER3H(VEK;pDHIXWOi`=-o^IWQ*iOwuQ;{H^RvLzC!q? zxrv`^Z-FysJ}oHcePw9Lg|E`vMMv{Xf%W#UC7qOKz9qA-RIx!AUyV|&Y8T}UYf|90)JiUR;~XKKd(Pum$r?7q)Dq{%Wal*I)*HS zeKY0CKZEF^03AW<%6@-6U=^2TYwk~eyB!s5WYyfA&!lW0eo|Ba)atpp(0<^4UrFVj z!E2mKYR;l7?qZ)Yx3631P!9Ch==_Mz?w94hX6E6n04}vZ`qnGGuB1BX(`Mn}v+^X= zvo;E>GrT~j3u71F&YKJ>-o64Q(0P zwSrt|N_t79NimOHbRgLdTBxShdX4^pWq4QgWV(VAvQt94g&mY?%Ejl2|4SHd9a9@_ zK)!tK`R_3SZu@+_9b(Lv=)u;}K!{G+`F!qvBQF652IG<|f(j*O=Jgh>h_sjNBoyX*%-a`M& zriY@`360*qp)D4V$IyMbNJ9oi4DA!9GnsUT%k`}NBmq^ju}>W5TiU-n+|ZSSJxlv}y$bm^VtuYREch9`^<7`Bb#%Gq&6@EOO;fOr0A#_c5)&FMf>qt4f2 zdl0Kr&$!W~woQTVmG4pH{PU-?JxaVK>=*ha>oa?+T^ipw`cQCSf>VVD3GX}0`Jv1F zUGQOwjj834F6@Zad3^`%8|cX zrEL#bI^`-JsUG5Jy_3g772*eSWpsPCu%`wxN~8h#YGDnT|MKwu+K}InAr;f}!z4lZN{MQP-cIS*Bi zK9U><=pUZ;f`od%!MQSQ7dNK*afk|->0Cf=UIwS!&LY(#iC(m=>IPf%mH1hii`5SM z$2I=x3+F?J2$Nb_IjQD73N;(iKe~0Ehxcj62diI6^Q<4Xc;AqOeN+VG`X>?Wc`M!{`KmT#8U!|;+HC00vS{PYLG7^LQPt#r>gL1^xM1}!&lh4X%oqMH#5$7+dOZg>8L=AOvVTypB#gfryj6J<79?XX3IZk27Nl3T*4N z@(Fddhl<-ltosEm;^Gg^$3kVtp8&F<&t*uW^M&A*9?n%2B*;Di^Pk^uCcvC?UH$mO zZvT1mIlO_fT!JZ0(c5-krG=HJ^u?c?&3s7rz|?}&Yomh?93s^J(gp1aQ1V5e?Frv> za|$&tL3yg`I_IM2t_9HGOD@k3*dgL0fNdi)mZE*+tirChus3tjmSGRftn$))%~E8Z zb19)WCTWq+Mk-b7mL`-(6D{xd^r$Q0L*8GmQ4$5Iq$WcEwdy$4#9PPWWD!GF(Yz)} z_q-*Bk=f{XGOK!@u{`-HUw4;O`rvM>_i`fI(}zv()d&ttquklk`AgL|@pQdKjuO!% zG7lDKB(WEL;oXNL(vw>Oz-GxGOt*1dd6A4PKb^g(_hUj4pzCZUN;ygl!|gLK3X`Cc zMzWv3(g|!>3lYkv3b}3{B^H<;&K{PUx|6;O|LqskrYZGFhEMG@n(xa_S_RHY=HtNp+uc1Y> z=40`&b1?3bY!3ay79%SM)7bJSS*CYeks(pXtH7LNH~OqqC7$if=Ja@ZJIEf$fG!!Z zz2*AtaPD5UZ#B1X3xdwxa;#1={ep)mg`2)cL&AcPR~eLK+Zq~ZM|&0zYE~Mb`B;

FZ`3H#7@*y7d?g%jQN+SJkAO((@XNG0f!zfQ~B*Ypb} z7@vK+kS-p$y+TE>8QCW3W+5nYI@l1qIHY(Gs)NYraO~BHx*ZX0$BDRJqIP!qf+-`M^dw0)Z8kwp9}XCaG4z3kZQ~MeF`@ z1;lcmXh-bI8@v^}j0ai0p!gr!?)B#Ilx7gSOx(Ua;ohx~$q#lu3CNmgOAt2TY?;_u z&c|iP+<(n}l1NeJQECP4-P0N7`B1(9uj-{I8vyp0t%;~>E^ygrt!%I*T>!YN+Fssy z#u@m|B1~R2o-VHcMrI*y^zY|thHJH}=c7VzP|#Z~3Q$%n)+dL@T$v^o2_d+%wf{%KgrfZo;yUC7}N-pQ98KUnDYIVnY=J? za+lF;CPU2bFYJU6c``v8N)>B*pe9v0TeBz$rM`MiYeTEXKZdXA&jQW=hLv zfQvrVTF7Io95QYU0g7NkGD~=eDQtYoAdg`E?dPgMDe|((eadkB<{oFJIC;v!N-OTT z_X`H-3F==OD~5I; z9+j=kye$a%X0uLaJ6no_@M#G~Yq4^>$E|x%MEDTe`p}@Z0^OQ-2E^z#j8I#XOyrxZ z?6UKMc*x>@`iKe5qQ{N-?ij`S4{mK7of<*F1p|#LlE5P-eVZ(F2*UsNd1WM0 z(sOla2RUsOme({X|Z-7YZAWd;aAdS;!>gLxC;*(wSoUGyK>B; zEWl5hBUa*O|4AMt)|UB>W0%H=l0%e8X5a6y{p77!2}i69>;rC8jK1&c`Y1~*pVz~Z z<%8>jBbFng%L0Gx>VVPRgOXh?KZV*^zt8>UC#K@w8?;H2Yyrv(Jx%Q?$n`jNo5}Od zcS*QIgQ$;oZ^gb+XNuo3(nMADU%2cveR3T*(pj3@*0E&wBh-)pGVc>NyMe55VS=6? zyb?AD%T+SuL^IgEC5rEwsd2vvm$@_=edOAV4+PL6y4ajM0mQnOh@ujOK-EUi z$CBF@$oScvSIl-Ao3mje&hRAja1m#v2yLKulZS7qjklKA(^g;Uk3MQXvJ6~RDE;-l zgCOHgP0q7lz7z_Qk1}ld-F0>|mT7jceh8@4^_eEX91~}OrL0qYCcFNfb=FUlyc%9- zFJ`>}*GLBXN#2;kQ}c3;{{ie@G`E^TlcY}F9d6ZnKIQCOO5xm;JMhUpDXPAM=6A7E z^*x+o3^xQ9&GuuQsd%~oNQTWnGzfn=dB%pE_}BoOwIbbsB*f9~G~o#^&&x6yslZb}$8WYb<=gx9TG-_83oxm=f0DJ?%`I(S*8DJi{EG zsG|AKrKP*=u=X4B7&Jv}k0BIcmcT$-g@+_c&>kteo6b!aC+Jb%MZU2x8EpAxsL%=` z7zp^88iCM9ldhn{1VH!TCcXAnb1&qm!Pii4*c4e3>x|UADaz>&4W29%QA4#+k3R(Cc4j@Q};E zDHK?GbdDGHCwHzM+B}XUrLo^&!A2F{+}RGt1z2Hhc~fQzr+)M-Yw^_FPH4`zCTF(? zpfq0XN{=SH?O4;8mKwHqIL|$FFLL3Ds7afg(6KS`N)yM^ECO`T&C2u}N+CueVE9^s zA(7*YA2tzB4t3|A!aR{-#mA082H_o$&~dt%oTP(MN0Wh4obzFng{{50P`Zl5UGVB- zR6a3O9*^b>lLB(jR6S@f?q#&95UA+VHh!guTGiztZhj8^l?YWvH43~<9&IbPj(YNJ z@R-2@8v1OzJPWW%BRl;Pazj2hSfRRp=vhgo3x{%)Xv$eKtgGMdF=1MdWrFTHLlM^!J;kewN7stp>%9+cXxgQq9xpyeqs5Js2bOKH0+%;` zTI=w$7ZveJ$-?{e~HI;Bp2e+>eP(Gl>{M6r(YC&(_b1vFylN0V+AL7YXuPzNnz$~`iQ2pHLj0>( z_Uz-+e8c=#H`P>v+q>3_BT!vbVB1-IOJlQiVdDH?=Hq|{jigb^e$~}+^wXsT@hkcE zIhKe_!wr|&^}VYp*9mttTFJ)PJ>K{t4p| z>cMUE(7o#)GobFpfqUdv8#BPZoWCzj`wqzmqiMnn>y`V1a;%{1krJ5k-=pNHs^zpT z#or1xn7kLBT2`eK_|v*|_j;U}18YLsrW{YgA;>P* zULOXrE+P~l4WW`ON53EkCOs|J?olcGv>KdHvft1I&cxT^_3`j=FuH;n$!`TVx-T)` zL#k=9dFmrrnPT7YHCK<$LOZ^b$?W|qqR>8(j_&*f9CSt$=2a%fnyi&&iDq#nPrH4? zICJ?;ESd`H7>?nj2o>Xd12>bgcSwBZDPQTtPn*rBL>cm{iSXkac37fIpry3(b4*$) zyRg^h!;+7rls!C3jGXbH8=%9VI2~6wvYW_4p#>FU^~ONvJxvB>!*uEKobnyh81Q}G z`HZTo#-BW&zUt0%F~rHQ5beh;y<3^=y3XwM`dy-VTBSqMcvjmveL|SaUY39>^1Dq7 zr}(2ZW!#Y$&q_)iVR1&_4IL<{5IgD4{Tt@W3?GAcYqF3oTWy1E8_!SWreD%@*td{v zy<*he6F>dxTX2nfnHKgMsyh5cWzL5#|7f?vSw7gNFcKj5)50K0s5W%V?dg&Yz!j%1f|Z}a+AuSv^24bazqsEm zILTN0{{-xRd$0uD7NcER^erzQEf%B?z-|c7JZ659{6B%-5bOp*Lo&v39Lcg{0&^~K zMsQn4b$@>`Bg@Ct+g#61M)#;u*VUg=ws1|M(m@feIIi`G;*Qgp$v(qYPg`?G= zg3xI!E{2DHQ0Ikv7Y@QS4(>?+>DdvjW#LR@!YM~NsKV^t6|(S1CgTPn!w2 z3vX|1dJtM_za57%Q=+Ijh`E`l2H%K*cWq(Ezcin*_NnqrXTGHJuY3xBGT^L)=g21< zcBqt)S4lU>bX?`)AOetPcfZQuNCfh)iw7ZyeXWJt;7aj`_{OxyB^0I(b$4qh<2;h+ z8*WGP3s0Xm;$wA>A4wb%IK-ugCEcVCNoAQWXa=dGw(0|0te}tTIZUADlxybhs4WXB z4C^PmBq|3YtH4RK(pZ3tcJdJpASZ&%> zGm^_V9#o19>t9#J9XqZxupkh4*ChTXtxBR7bLb!dSZrmFLNfGpFiTI28Djl~KWB-B zPcUao4;ppfNKut3lQ`5B^CPtig+m9Exbdw)#tpJ_>fRrnVTt?c#ynN<3-?*EUjw~lM_efx*EF}gvzMx)YF zl0zhv5TsL((W!(qqfv>W0s<0(bdT-<3P^W1(kU(ZTz;PC{(a;5-T!U82JDaPIL_mI z*Rkm}yU)Jg1RA=IKyB)O?N;~l4mLN>I6YZ8sQNXpNR;`kjW+;i=#N~G`I1FLdUyGN zfat=5;%xF;OV+77NjWKZP1;XS8758qXc$R;1_V0+s(D+-~Yp3%;w0_lxIewL>^a9!-tP-eYj+sw7pE`TE+QaCF`X z?&A0vr^ zN|~cdHK7!CFh&@|lVeLC^(jl3)#7DP7$W`{rif=p&lCN9kc{X{&`poJGw~356%x%`xzS!Q=9AtU5;rl;JJ5E zB1mDJsArc`U|28t^@DgVF}$=NFE6zt+ah3(p?9$wVxzF~BSb|RPs^(OsSIx)p8pV# z-*lN=hIZh*4N3&N+n8QvC}2KaI@6LXyr;UeM9Gt!9$^xI^Lsk$Af@n9mSqaj(VxG9 zDZ2Jvmhs`EBPp+{3XA?h?C5ta*?csq>h&i`VEH=U#e&S4^{jw$C~C%|aT3rE(_y6} zS5^cHc24l#pRFmorm(g08 zn=He?hYoedV(R`Bf9jU5>sbFk$>l|NPFF{`CxxKQ63&zqe%BstP|u@fKGxsiWRudS z+CjcO|53mgd?eT~4f=rF)d(~N2RT{r!Y<2P%6gGIy)&N)|1wpnPvCi+c?Yaszr7## zDe}m<4kjFAG?G1`Hg95QZN&c4awaRXjHj3YswZSIW``%xmYWa~;Q-6nLI4efqT#V7 zHPrt@5(@T!KBXdaI^CKh3{RL{fgKP9OBT^U5Ml2!f;mIA7+$Gm2!QjUC1dasEJVEM z%J3!Yr$c~^%`Ya$R(`WA2p^ADRq*Bu?Ykta5@0p+A(O9^4z~PxC*`mIVxPB1Ldn5#rs&rkX?%rY$c#f*F(C!2fK`^?*0bZ;Kd> z>oQ|!-JAt#8EQ;HzmM5sz^De50rbY2RY=Biusfg?hJ?7m*JXn$n`S0!y(%$q)fXM=G>uYXuE34!$sx{T~SsqQ(@T%uo3r)2;XW;nc=E*sWoVUcv_|E9)^$`b0*i;zp%d-xG-wN@-_(`^>GF#u*ui zPS1kvKT(W3OGXCmCcvqsJ{DXD5M-oH|J!`(?^GnXf*WAI- z7;ApJQ;DI~v<I4Iw|2o&zV_nw!;C33m0EtC( zX))@0ssd5xd=(@L*9Qcbj!Q4{{l0(22!qkA;QWXlCjh_BCMy1!K!lE7RbGsE?>UPI zkgYwCkua^JWIaV*X{f#92|4Q5xH3JuO40q#>maX5Hl#mPNez8!Qy<8;P`nvv+9Nf36GQp1fjk;wc@U4t%6{AD2%G{ zVMJwPky_nlC8L1d*B=yA|2`c-_i4kKbK@PuMoCkM^O4g|UJdHq?hsU#KrsFEi5Gev zQI|DcEG6hr_jBYxD}B($>5PZW3!Torxq_)|?zInh`fJUJ0;8=3U=75N7laJFSPYsh z$XGxf%%ix%Kb^&~hw(JQnm+KohsaY2rKxES!Xt@qwKQ5@az?wjgo-prWeGswgG#S zPFEP?g%G`q?(*$d*cyvvf2Eijxl$lem~n~~p;-4JRFV(aHF9cTY|jNBHw$&gJAZ2K zSOO!!LBvws@bR1QHeq!gxmDf!*aA+vI&&Laefpo+*gx+WxxsTcHi9>?jJe%u=-1~p zthjRG{|T<=atD2ccEyC`bJL?zk#-JnPg|&1C}sxbrG;lwSQ;iNGZN(6{U4phHIe%- z!z~MrdEf_posZOstAB@j058WOwkf)U~Q1Y!T91+dEzQhB{|{F)=Ff;<5mjP?frFJF*hK@|;WGW1$$ z0zdW|Ao89wS#msGkxwB*k$%)Lfv$ zyvO%?PcDiyia*ZfP1s5qE^}(SuI}!%^60T{C8d=)Pe!OfEEEwJ9O>o|T5qlcK8HK8Dx zSR&OyRZbxtuGK=@-5kdEaKDp;2$`Q6C>h#(2(!at3%)}t-@UJV$DcHTnnm$W3{zxh zy_lMK+1wwo4@*aY3dQ_DICPTZj>`aOs{!;;-E)?wkWt^|#Zd%Koi}7|k()I!5Ttr0 z6K=aS>nI)+GQZMWbHx8I#k3n`VaP&j z#X{081f8V+9eckXy7AyWH7IDMa&S+~Ibqkw@l(?_*AF{J!4!+wma&5U_LJy15=YE@ zQaX5QCBk>z{?pKl$5ZE0ZY7%SGd>_e@wNY(bq`7TSq8i!L)>)GP@yl8@ooB#Y~(V7 z_!y4<+P`kgAJZ{$$equ{C!P!lKA4pC`>N{kZb#!3<7c6NbtoU@%IhNjvjwByk+dqnKrlaYTm>|@5xe3v6uLkXQ%z~ z+Hu0|2)_D8a)8kqU}cnUniRZxq!0BC+C~3KGNgnUEvaDV*;jf5L5mJrJH1!JkTI%S ze}CR;@X-+~ZJ(WlBN&Mh6PCQkbGJw|0rO%LTk{>v=&fhPW5$Go(LNB`c}7B^BwPpa z!LYMXQgkJrNR86>b#U@b+)o-&D!{XP^ zFApAv4mvz)t8nFARqMPDLA)7u=;|A!x6RfOyFYM7rWhAyZO1B+pjLkDhhiOHHC}g= zYF_sQc?9C2_-yBZj%O)S>Xqce`%<5DeZb7g7x}0A1(qS zf`fU!0GnPdh!yRS$D6e!!A-U-CYQ!h`|+N-86y}hlY?6)wVXq6fTkr(wR#*9E5CLtnYl=5TWa=r z(w3!gKjDN2q!upc(_5S70wvwN`MdCE9seb&_Ag=06DwStPBEpKScj6Rn=hOt&JBb%EbPvn zH4VM`Qlj+LxGwh2ujBd2H;-ccj{R2$O{^gZ&d>xhy@CGL`Az8Y@_WIp@;bfy5x0cD z7E619WrnZ*P3-mmDWe6SL9A9>GNW#WrFET{;%*7^_R^F83+##m)R`E(@5RX3S0A1H zN9=rx!`=BRrSuYr(Ycl-ZUX;_O~+^;!BbfemML`q>P~e25sofWbHX6BLrQ~d{uRJTx9JT;Xb~Ei$;QGQ4a^@W2Uz_*3xhyQ2GA~NN6(>W!k?eR6S2Gh zT5#{bcNBtjddfGwE!1-0T;-2jzwuI`L2pykiON#wC}}2Et{FJ_5hC&F0Qi}(Iu3tA z8%~RZ=RXjHhBoDs0p2Eo$9L}W0uv(K5bk*qUmn4L*xr?=k)d=~@yB;eSGVeCauV{< z(lm>4EpPu)*=8hIz15?Yu_ZF-etaPU$Rh)Hu7BHkjQVV&YZy?e)K`exf+T~KQ2PV7 z>9p6}Aj1YaRRHHIJLC&F@0kB1Y67lid4+Uj1|d}bvS5RCz|lR&7%Dnb!`z0m2S5JxyMt39|S4k!4y4#z|4m{upfws#B7sDgYEn!IZkt!<;d&EuXGu3XSbmo#wj;! zY31X1WGq>^2|UlztDTG-B9aMu+Y+htx*N(2=27XS!E^ zuB6Vll+)W)W3Tw<4KMxOlM~m8d&e6N#@{UcT=;{3RdYKQ80~yt7F}Fc8#B;!0}E~X zgDdbC5y}wjS%bDc#my&`L1GMzD1KT`NmX#}9aaIO@u@oU!bCr$osy+!=L~k1ZGZ8c zAo9_pJCNYKKXxxjTo!otwi49OZN8=i2JR8*tUtlK?)YEmrcMpGh$e3{w2QE_#7JMW z=@yUeQtrQWWWTrt0gXgoITeu+R%X?b2g0YAsPvJP?dbfokIqUmhJi%)m~fwW_RI-| z?0nAlgf?ryOMNe1M8ExeHmCph*({z2v;*)ZRn8a3+y$pfy~+Vl*bYXD|wOa>GJ<%LaG5=Vz#g4tr5c#G6IIjL>Dyk~{M6D58}@C638) z2%6XB3ovwuCcIa_zRn@B5&qe%Z>^Kiy^tUx5VG#|Ed&k`P|9C)5Nk12df$(F_|W zmx72(X#!N0rVVkI-sQ9{fBhdp;y91R)5+Jgux)55EYIKNmU_-63XvxTBlu{gaJI&kn=V8NuVR@7@P1`0C#zn(3_wsfc{>!MZ|b8D8Oljd6ZF^c1~mYPf*FMuRqF%2xplPxoZXY);~W-byQFn zgM^ap@xR8v!jTk67Od1oDKBl=2#-Hb-(KR<$J6;b;t0aF+aw5(GF#Uv4|gZ54T3eV z+c5V*il=%XK70h%L5z&CLaLxJ&4dKKiN*Q*9kL_KOn^YA{Np&|4DRwxUy|ka7^ggT zml${?nwr&f#HpG7Czkk@i79V$6c_((PB#cIv9TdOCx1 zA0)_7ySgtYo1Y`Ry0p;-vW;J@7g{1jHK;*Ka<1V?rPPGGo%lm2ys~ay5@* z>+y8`)2x5cmK#V}>Ni2?W%EbWJ+rS4a`c`y+MO=8@lZteayyXzh3|#kmH6!+1?B3K zjf)qZ5#l$w>^-mkd3^s5P5eRngKRQ6yS|RxLjR5Hj13Gd);^yUZ7cU7YRYt*RP*GG zsofXTH_ImWz%eI_B8L@jF2M{3gOG_*2}m<9k`7<%l9Qju`mjs62l}QZ-~ZzR`p>D0 z>EqB0mkUGxY3Z8_JTa3?CVEit4bsZ3*gD|8^;94xDSU# zu#?DogxzqaGGm|H^w-+nu4|lC1-&wIQBEuv_9)~8TVcNoM%GY}pooi~BuumBiQAVL z!ipBMUVSof?6mz3hP=RNBRo%FKN&YW@f28!4FDt6F(FUA;@l^z1XXK%=lid5qrC(0 z@<(sRW3VvO&y;j2ab;MbUCcGtK1?44_qBFM*%|iRy#hNI5Wf`_A2F8Q07$;l434S`gUC2oRFHjSSp+`5%VaIG;46dMb$Tg-`#OQ7vGQ`@ z`=ruDG@%W52{!t~YkM*$q`2febL}P4NyPrmQ#qxH?ARAw0h)oz6P5eBan~e@pxkku zjku3a@u$~qZD*W@cQ;RjE2^yqj)rV2%NiSlvwv{%@>h{7F4^)vdg3Jvhou~B=75CJ z7~a-$5xwq@$Y0!mK< zx8gAWuuxuNof2|t0>Vgg(U*B{#F3sLKuF$MZ#ozOnG(XX#ru_0hIF(L{*)<3mMF*x z2Fr&2E;iMtV`(NKd&^~HPuKiga}ED>9E^~{(W`WY>5tT8f{VN{;qJ|f)%Dz)*NG`O z{o|`#3+W`<`%d2TuSYK4jBbyNi#sun^mEr7^*B3)n=*q4WguojN}aGguQhtV?3L$v z;L@!qKmba1@cOJx%X%`OyXUQV7vs#l2sNsS&dqUd2L=(td+G#ft6{Nle*KEe(9#Hr z&-%Sxb8DoFM&RZ8%OJlcDxNFtV;ZxnexiB6cB&9eypl?`lY5 zdPmE}YXV=nXk^`)!bwVmHDKwiS#d=nzk;w=X(Gvr+&W%2Bs3Zb?jxH{No2`*g^ zdA+{HqrVI#QOOYN9=~Fk6EL6URlVf7*07#RgQ5*(kKKmfxIi4kn;y)}r;*-w9Sgt| zZJyZUa!QQn8n5l+B5bxY^1+5+`D1{`d+@{aK0(rACm{1Yn^n(G-H+h8G2grR_p%1C zrhgnBK`Bq*HGx4t1fkEWj{DpekBWUn$TOUnwkmYI z?O~|Jh!I`(6W9qC$AzX&H6$B7n<2%+2TLIWZopqX_K46A!RSqOAX`Ivv}^M#e%i-D zt}-}pt9y4WAdHTF^u}feQhHxiU1SB6_Q)z;hx+E^3Xp%n*`EWE5+RJt*W1fLGjLda z#s_nd3)1b-k_y1Jl^m>OGt31Sa#Nrc38YrYy(g zY5c|RW%F)B)hxYbt6`~*?Pt7KjO+$)zrJ)48L*otgrai5P8`A)1BkA;N5(VGPV;== z;*57VpWgCH@1&3g;gho|VL3U(@C_=yn8$?s(1?#Z7$gd03Y0L__T{#g??o;rY?`0W zpRHrR_-kB*o#X|Kjr11oMfdenEH?j?Ws8*t{EFUhj}7=eur#zUO&sfZ8oyMJgV+|^*{8IgTA{Vt ztW`l>mtAt5I6`7B#Ss(EX{p|bd`AzK0mwtpFjf3 zg+EZ{x+@+%$-?t2T+X!X^!A}YR_L4T-N4ZO<_i`^%WYRJjm3U0fLOL;>H36)XsCQ< z02-b`;3senrY1IU1PxVtE`-?9rCus8gw6V9?Nhj;^v33h^Bxfo9yU(N*`4~KBr!x% zH^s%lmb(wj!YzyWo9y)-!pA2IL)Jd0pZcjv)mI{mu9Fg_J|LZMC8KWJ-HKHaEjVMB zBmWC@J^KzCb@pTSRYQWiSj6hidQ8*f|dsP3N@40t_ zE*^Dc@zYD^TV@6%Pq!zp>K> zY^39v>Wn7?AaxYZJ$$#yk1;Qcovq}^`AC8-z?q@snUfY6i_B{i)Ij6z#1{bEAOGjGlWN+92fo! zIxLjE3B`Pi|rBmIH<=CS#Ubf^4+GO{k+nb3e7=Ftl_2reSs6SUHovMD7nh8eZ3fC7U>iU;ga&C01J*f(BOVcF>bh?gwA+b&3aHi{FuU*I4v-CpncG?1^dH;{ z7mdz=O(V$k^ZL8DtpiW42ITAmSWIu)wgd5*Z+>g3uT4A*dZ3C)w%T;t4E{KRk(fd} z;h9RnR6Ae{&6tCs-RAe1yzFMfWJd0Hsn@T1znTdC8mPTdgBou2i#f|BOfM5{JAHOT zIO*}7$N@RoI_KXVescJ>9F1cr9x?3l=>b<4VCo1;ReQA>Kt46>(r=pNc=Mj@r~aB* z`oGD}{*{NvLD5whi0gemv0n1@`z;>&#HF`Mw)Ec;gx;rMo?xM;+l&klCt0FH2}H%? zqmo7%3!kPE?x&dc;7knfE39%m=DMKy7+jU3%Z}+85HxQ-yzcpD67Vvhkk}9Jp%gLT zA4a{u1Aq1+!KXY?1&)&Vbm2pu7`H9SZ$k5oOmiXdjdEu@awjZ>lY4;`2k}f+yX5aB zhItQ)aHTR^@m&meaQ(r|@f$TyAv{W!&H7wdVNXN^W}L6H)I+4vOsHH1(}8MzDYu7L zGi8ma4|2lC>B%ej55I{5WEB)a+JYXNr1_conN{OCM-se5`WHP)bg^(-9Hqdv<*`%; z*)G)8xes-@!>>i$b%8P?PGf-`aH@zHmVP^k#qY8gtbmd8eR^YV-A9OyG2X8P8xmhU zjdX){**j2zo3SgK$dHbd1{W${eFP$EvH;g4emUHTX2S`uQXDzX8T2_rK*l1fb>f&^ zxnitsPAbJ#Gy*)Ol~Zt4lN1;-rH=#Tu`9JsQQS4I{3adJ*!o5pHVG;1pw;AHhn55)JZ5VKF#yGE-O;4vM{H8k4El5 z(uV%a>xV)l2MD;QEc{eD*&_F$C1815z)tWahHYD6STj${$Bb-?DIrp-5G^Vcw3CD| z<1L}wD3L0cij%4-IX!CEL`tj2jsSn+C$gIn`?E$tE@@YcQ1`S)N0L=T zs=uRC0J8FrZyr|*k-%lgAlLK+R7{Sq>>3D4#5Cy!k%~b*89H9h9|c*%$msT%V;yB< z6Pu4p7b#tCVQDSbZ2Y3);afBLgpKD5*cqLNhm+U7=Rf7H&dTbp_@4_X?z|bq_e9ms z*=4P~{(`}JhGBNW^UF=w19y3Hz^NU4Qk~l$!TFf9ty_xwvGyrk$^tQ!EozqGOqlWu zlWAthDIzIvS>jY$k`#-}eUdQp@ia4roZ88_ZfgT3@BEl2#=wJ|&4TXgcjbP2s54lw z(FW@&*uZ_=*tOLHS-s7!t5!7U1*898`R9LSl&s-La(?Ss!1=N?@YKdG(eYa3@l|0( zQJdAjVD?2uAPqH&-lZB2N8Tg&jxXsJ_ zV3cpVqoqZVj-+J1?&Zs$T3yQtQ!w)+SZEqg*Jt&X0L$r~X~F`GA<{eec>4s1U2WHP zk5DsG{wYE$;-oxS|9urS!7^{?@wS0IZ)@&*tr3~XM(n%wt^{x~jXTqGYFOx9=Wp_5 z(gUbm8N^T7!=edXl}jG;SMs}M_%X6#j7nu9jw84T?eF+gc3L1b|LavaKItPp5!*G1 z!2^dZYRuW&V;(GYnpl@lKqTyd7{n*e@b9aB8$_X=e-T_kTD>^o!R&*o z)Wf#s7~`ezXT>tUJ=XIeE2RzDnHLSp)57~mfJt0b`O4@N)8ux>pL|)|22)++ZJop= z*QoEGnbvy`Iu60EaWYoE%<7yX^3wV)ecD6y*mmKwQKPxddsCO!p*|Y_qXl4t8IRhx z4i9;1%0NGGy$aUI4Qaaecgi@G*2gMCXpg~*a4d0Ayj3Y_S;Ek+lF}D#hus8QRrFVw zh%BcH3Qc~FM^H40epC%pP9#}A7v85n-JGRgPgLtz){Z&@C_?I#TpbI@l!c~uNqkcA zUI|PLY_gk>Ansl}1$6B^6{tm2nVl}`<}Fyu3H=#V$EA?rmZoDX($RcT0K4vvOlJ-m;G_Mn&e zz=C39>`Wk^f!6If@9v(;gCblLO=D&x zFKYB-Y?tO>+4n`;(S9J#vjra#2j6XFJuMvb9!ycH-%2mKXg#wd*JJU z5>^$g77D1Um?7~*!&=-8SC(TBc-b&I-e#;k!oT6@vqgkPgzEm5^ct?s2)Xs7>`uWm z6u4$URlDaTlm#mU;gR$YaB6o^5`%KJ!CZhOmhkCcC zs1V!Su;qo%zW!$ah6ny1;NYVgj5GkpdpB{d+Ro4L9px8ICCrgg5))aw9O#%{20x=@GVg7 zM~oPJ6#L_M_cAMk%_wZQx3;$K`3=ZZ?_(KKrrEZ$Lc;ku29VC*L|_dITWs$ri2ccF zQ#kt|sJ^%3+b@`WG3HY(a8GHNYDT(PSBKDW6igl;+YV${tI3Ak#?A|cwovRSBIn>$ zPvNQT_^4vc(W7(Ocx-xTmrv5#mGvK+AuqUIP;a(Q5|~sqyB{Amlb$0+hJ%PWoqe*u zk%i>zb1B8uIVA!zJ>xM8;sA#ysX`A)B{n|`hr8I_L2-tBc-%17vD@&btfeKEw+~eq zlz$G&m{>Ov<#NbL!?9C7&5c_bTtXJHzUuLaqSqnCLPQAP70sGuyLRz`AU@tn2W+{O3OOv;o~>9wt5oQfn%tm$I+lERR(%g_5yx@II@WFt6weNQqR3_v^aH+cj#U| zF31K?sc|ZU&{!4mIL|6(uLg<1?-q`9SO@S>>h9^8X2BxQjpUV40#&_mw7Z(BC`fgi zlGgae5&7u1Y6Jz50S@BrY+Rc%XHjPPESz?9F;bHSS34e1_$>^TX}~ zoIH~7Ymfmq35<=VKsiv=3vclcMe7H+z-*h$A1=>TDcc@Wa;Zzng4Q8lFA8;^`4a5_ zMt=tBvW2KSwElC=(tH^{qjcw5mq%JN_ggf=N0DmzirL55F^TtT@51n@cfn}Y#k{-b zKuR01RlpW}lJm%k^uV?Rp8An;@uYV#Ynh2%VLb=%TD)^#t^T z6|5MK*wZNEqzC{tNWSMiIlb8BCfn0r+hwn>gwaj{t-xOA*7gUG0P)JTnxHbqDM9{aj=1#-cHkUmH2xn zLSTEPV4bD06_h0U;^qfgshs^ha@>eu;i~R(vcM0yo6YC0XLP>No#M6oyL9n%dfV|s zs>h-0p9jy7NN)(j7uxj{t4j<&na|vac$ffd^5_sr$)lanezm%o{^A1pWbr|Yg$;A+ zSITe8vo&7MWHRKdAxAHdnnfJLQ@in`99G^5jZqsG=gDn3x?JHrzDEGKtb=x>R-FWubq_uX$*CFau8|FgYN z3jhvL!VpLB_pQs;SP2HU^r*$qK`!lTg7`EaZi!_WF=-29j&^PE{ z1pHKFWv%`%XUM7ouibXNH_%QjP8QB=0zoXnXu!gwm= zQk#5Jt|tcaJjgV*_ug3nfgvG>%yTb$&Q6K5*oUGHT6pg7cPlDCU@~=iE}O+Jbhl;r z0&%0m!1f(*7`a1H>EF0mSGk^4UL! z6zdVz?9X=G1XLhUqQ=aC>2@%WPIg2K(&I6Oe_f3%dX+-*7@Y+x`qR)jb`v8d(#jq3 z{-gXH7&bG8alwYlUan;J@Nr63MoEn*!yFu7 z9_Sy65PB-A{`!0BohGv=o~=z~^pBkKhd6_+cWcTx$V;<@$_0zV9PGZ}p-k)VPy-}s z2(Nq%R3k#3sj!D3Plw+13+V3a<3Xh&HbmEjrE}kmcLE!*I7=3K~x$C~<97&1Xaxc?C!X0a`K5d2*$< ztdjB$m%(+~x4`h9zl1AhZzDSWcD9zTEdgU^=WVEiem`ZG9*`SQ;n-$(D=IN`E7o(* zB;j9F;s2C-koGfpogC6}v!`=9X7#PMJL%C&yKTsb0dnCrG^2W_!5@ER(l6J3A2Iv72xPN;9367ms za;^K5r3*p?s&7g3&X*9jlrY$^wf1yM zE5wmyLuznO-dnhf9xle9178gr#W9ovqzQId0c4L>ak{EpGr&7062hZM-YLZWpb#Zd z1x`)Z)mI?H5nIKX5#XmRbilf+PdM%rjK=)p_|Ih{fPX_Vr}DKPpLanAucptWUj|l4 z;LZ=0f(8~7W#!U;)Fmj^qXcSNv0_RDXR7h@z(+vDS4;1^^9nSTwKO@5Jn1Y1y;eS5 z0OtX!`jqwhz*J`%sfGq0mI>FQ?KTf9mPk&)1k9;0Y+C|SWyF*iPJ{-3LrquTQ^ck? z7H>sE^O;TXP|>;!Z?{-`w13@ufDCl*kPpd06mtoR(OjJIs*-o!&D408N8?c8apy;5 z13p@0LXfU1I;wosY>TvY2*;@Jh2D@9ADbpVXrI9Af@Q zr9tu8J$Uy$$i~tmp)!@Ig4$TY5!$WOT!MQ&Uyp?< zhJNMAkNcJjzPND}4lxdj2-5p7seYpE9D)xS<84IS?m<4vcI-PKl&-%8{* zG@ex7-5(ZKU1G^zI8ZZZ221B!<<739nzywCmHha#-bRbN19-E(!;I`R#6f?-g2)VF z*nJTmUuJ5D4^1~WM_#|ACSF-xN{Y=g81#v2?u%4vc_xI#XjQ&&;ctrGmp+l&Sbgz> z-K8;jwU1QPb@vU@+_+UV*G`$Afa;flLgjC^(-&73UaILoR-4u}-%p5QSv}@4+{U+zoaT^hP<@4VPu<(qB%&E;(N2WQ^Y7dz!XkU_DLVQh!iI_=V0g1k>a zh9NecJ_Q(I!)D?TZenD7b8Qg@kI+5C`;BTzn4qITw=C45x619p9pF$G9u@i#PBNsO zY*9t!>Gdf69i8X2nIYWh9*a@rwD7qwku8wn_1TZQ z@zwu-LNQQdyU@ce0XEXx>pF4vw6@)`#4=s{twbEAQ110f*faE(eP@Moo9K9|YfnQs4>m z)%R?4P&taqs07mKmzpWk;%rpUXimxAdyQKn_)9V2K8Ib5CwE7`8Sb2!eQ$|3Fk{4p zBfbuQ2zh<{ROd2(To7)&Cm2)?%_Qe>XcetUz~YoXUm~EtufKFjl_xDcKHY{a02{I{ zb%A0S;7?gBHq7e^H1S_|QGyUv`sfTo;yim%N1bf{pb)pZFo#wFONH8|FnxG5 zKoAtj>!ipyMNHel%sOdMD1W?_4@Ko7S+sS4vkn^d-V4hD3 zhSUW4crcahvwE;`uswQ5>m9Ugi;6e5e|e&f&&@6Jd0Ihl_l|cas+zH@SD7!5o%E$h zh?K1l%h%2MN6+S!*`~Wx*9;yIk|e(;^__3l3t*fpR#q?ls8&2eYtrKpJ1$i}H}vOW zzUi@al7)are89J`=32YTJND`sdcy7D4Fv8J+C6rIiEyh2MLYRNPNAuHmOl+}tHRgo z;YL_pC3CgKuB$Ty(Z0tdvJyrvasaXey|@G);XTn#h|TJ zPWuZm3m1jVHxn%kEE@_tKWueVCO@8)#|MTsIIt{dtuJ&IGn7_ndFGI>x4lOpmY`>4^e61Cl0$($k)kg(}A>A+jHZ31wVdT$~4}qG@uYDf8UyJJf8f*zc3k~f;YzVH>%%0l3s4!5dzaUAK85pC^ zJrZ9!zL_`KKK#EqbH4aMUQ%s#*MQ5#&ToR(kgRr zJEG>ol@mt!8)q^^_8>T1r(qv&*QP^P(hg zp${Yg-iRBQ(R`*A_<+WXg`$)I_qO-df!?3`h97i?;82Zg7T=R*JS@_m`n%v^sNCQ zSWyn}aZLGBV+18u)TR}%0z_J0&??K6{d1JsJ7|erO3w2OBfE>1;7}I+tY$x^08K2N zZ$T!IkzUc^%reOf*Keeo;doeY0lJ*ZPhWmmaYCDarKCY@Fh!_Kav1J+y~>7#=9;%4 z&e%QIGT;98I%~yMN9N+>2L#BG#fvfxWLL1#mLF7{yim{z+v5znWN{muf*sLT&C$x* zv9Q9c0j%KCR*VnGr7$}~r}qOHH_-0siO$_uK9d)oB^IB(K=mY8+c}NpqsiIl*#mP4 z#^R1Fe59MTGQ}gC%Qx42?!KlH!$J2=iMuHrpYE~}-ls!szM@4HFAZn+0I~>$CNt$9 zrLBp fjHtdUAwS@)*QRrL%iTJ9mdgCBduA;^b$Mx^n#UaLDScYu(+?%C7biTqXmjnMNa}r1H=Jonf_i3Lv)Ct9VLtM zOdjQdhVwB;1+LOTv(Xudr}O*EWm~o*#j+$;1Z-~>d2mZIi15Bg$8kP9j6@mIm?^T6 zoR+V&yw5pf_1QE1rg4eU8f+_H>2RWuFivy(7*k|}-!+`bAAoP0-SU&Du;uTB@*%1$ zj1CC!3CJAeNwO#eUeBc;_N@d{jVSF9WV~abS$z&W;vFO)^UYi;rwZC54)XdrtCQtJ z>h;T*zyaum-!$KX<#6_-IS)GJ))uQ0q4P6jlf|ZL-9PEA(k~Y)&VL!Fcb>#DN3_t` zf8?FRgB$0P8cJq{@U6=>pN#7No(a4OY-`#M3@$VcQ*|=0%Pu=jYg^T)(sQ{h!j?f{ zxKbYM2=2%0Nse3}q6#E;UU_fOaDlJ0l^9Vyk87!la;$?7Ja}`NS~)0Gp_*{8%I9}J z%hz~)EPgP(@}jkAtR}7=pJGap*SJfG!L#+0X0QK;8WQgR4_46)hB4qSww~9+B}2=mKBWKyc*3v;kyWI}H(A2e55Kj49Mhd+MkS&D4_{vy)n>G%jk^^n zF2RcycL`RsI24MzyA>$zv_R0}h2kE97MD`o-Jxi4r}+1F?%a_(GvCjwWIv?&R`{O;wonM?s_4i!J2ejDY$NW)Ryf#C4&ntjuA0VfH7KYpb^|c zQo4cx=D!g&{`syuk>vpz2PS6}ZW$(4zj#T3j|lM8={P;8END3htGdfs6lJa&{0*I% zQgD@}S>a`-A3nswW_diw0iOvx8y3ml^bM04{Wk%biM=<$^4jrUU%Mo~DzHJ>(nDp5 zSBe-gJ#`YifTyvqz9~E~LVu&wf2^BEIUua??gtqn!-}XW`qj4FMx>{Cx2!nyjonfK z;s)LaGdMj!s&fbCQ!9xO67}{4&o(rE6mv=~jLOexm!HFx!XCQ%k`JfHq8p)%%PQgc zeM0zXZ5xVg0)cm^Kd;0 zdXzt$l7B`0syfJpsc(M-DdjErO&m&+Oln>W%Axp4o+qjN16FzgGgvJ-*n$t_w@U>C zUUP?x4Di~aEzl5Lobta_>p|HxGd?gD3&2x(P1E?3a53@YicJy<_rvjqn$XFbp@tIi|iT^I6T<8i4N zL_Yt_R`K&k#>5%j*rhqXwS4V7Fd2risq+0%+}_ijJCG%dD1;?P=bGn>$E7*m1YWLL z*iwoX`*$FR+2`qEnB#*EVVurKcz zWz=%GykW`bJEbEAbMK1y&^SCGhON!1!1$&gMp>{IF0yxbGkzv6L+=fVMvH0ZBGu!d z1p#q3DKB^&+R(LbusTUsHAt)@3SWO^lRqG`nwM(2AI}n>k4pq{rRF>qM3ayZjx2L$ z@N8y-kIFi&kZrWXQEbsm3jGz{fSZb4Y*9b_%IT)l$6#&2$RtNFehfer_=;zPiZBqe ziubz-(J>bGuF<&j(}_QNe8(-i!QGB!#c`#%rKRjwXUYZ#zT?f2gSCmE!>{e9_VK;Np-@^8O@LI%vt|@$#wA+3i>F9>4IP_5GGVJ3Picm2ytsw3qsfj_3}x+CLrJ^u&?# zR*#_rhumf@_dx!#p1zl^EeW4ZY29H8xxo-|R9tIF-AY&3pMtM@F(_j6UdcM{A_zh( zcKOL7BHOfr7j!VO^7j0;(-y_TTHY_`8~*RXmY`a$u|b#S=kTYEzX>V-ghT$xw3Jl^ z>EAiNy1{f8NP2$c@%H%Vwxp8_A1^w{1~d0h&I5_|Sy>^{9@W>&dO2#wBMd>mpuP0W zy)PSTnE5Kc0ciB> zpq#k#n^-RxpjeD?`>*l?<;LI#QWzS|7K_EU`iIzE&?8I1BFdRfTt|%2`<~f$)a_|# zLqkW z22IBZ-nWvRWll=)yOSq5#&Vv&$wHucj!-FxzL!Z8FC6&-rN4YN!r0aNJwghcjTZNx zRZ>LQv_EEH4idnlT(@Jo1bPY18oQDY1)bmFENl<4ZR~!24Vp4bcQJh&fP;}mPcQ8| ze}P+Ap%^-0C~;zGVwYQE(AXmV_A>af7z?yiZYke}4=P84IBu@CwfqFx!!L9Py+363 zC%7=#!GU|bv|Zy*UBinz_F#(Xa62ymrTr3eNKk9l7ChrsH@lH<6S(%eZ2!va@aV`M zpnYkV&887ztJ9)EQmPv2@!1Z>+u7*LQiNx9UYlA*!!2ls8ByYh3L^Efz{_&au*s$3 z;n~CaaaT;bh8;o`$Y@5fL7DjD#ujhY9F$!uBHr4npkwb2B22P}Hv7MHw#~7{<7Xo0 zOt*_YYnEWV%woX;0%aT_FBd`Nvj$poAOF0p4r(>5+$|8Xe}i5x0PI*@#G)59klRlr zZGF`tl-llMSY?yUqodJd>#TX7cNQ>d7UcAvM4c(iW7;`7A2JO|*cLX1{&2hwAFJ08s zX6gN|vaNv#KYCA7?N8K@!!pVnkeIUJs4af)dm1Ivx&!i^R6FfI5|x*imuRs>s=T*Pt}oX0 z?{To5N8#@e)n3tiMqB&vqzxb{l*{^o#5Z47fh?8>O2(#MIeL>3*!^D+Wv6nnJrYmN z&uIjPiZkJ!W}4mAA@G6wtvpyY^;Z>AXi}iN(XvE3OaGyn*>86#+Il4>$Gh*Jyw0UA z`iAl(_4Ev6d4^;Le;?oC$h?st=KQJ$6AXs|e5r(Y&!bsQ@Y$UaH{nD@h^>cK8CMEUFLf z55DkU-=EHgl;540t+>YfAju&0PsZM}huKjd@&BeOy1tp~(TdIz1|4LFiw2JBJ zp^wzxo{e@0EB%ASMEdT(Tc@~C{WTjC{X7{`mjJ(jOp508H~h^Y7pecpo}`WwNcRzI z*#uq1i#V=-{R8WsrRQM-s~RjgCB-u=rL4V4rz8j7R=dU7u29WaJ!VA=vHxc&3%ITu zl-ZDA?J7B@_j!Dt(3X^2C-wC@kEFF+7qa~!`~ zD!g7SJBA!0Ol$V)BN7u@Kbd~PEnyC*oqKw+BgO}VU_XIz!4@0ljsWu~C`Yj;sBca_pLGb?>EQ(h*(iIgHwRekNea0@BM{l03?rL+hUD!Qn;eT1;*)HVtSlu+e7yUy2#~^N4GY(A2fXCOci)}`qid*-@^%mD${Qi?^wqk= zxf?@=qao2G-=p%v(pxr(?jL;qh6c5)YUj$mw|l!jD2H)X^gFx-RSScsLe*QJU0BZK zsLpEs)6cZeNCYr7{CW7c8{1mLGX++EkjFoA8Tmc1Hnm*~ z3wPn*H;VADfsn}(q)4Qtf3dz@pLiQSB!V%-ZgSgJu6vs__O1OM5$*LOUdWy1slPF` zdHj1EI4GUfg1C%G5iMqaz;1N)W_G!8&tqX`lqDu9^DN+6&moU6%a)0Uc93RHLuz?+ z2Kfxzon-S%w3?6HRFhcy+yF?|46o2D!;RkB^h)>)U)1S>b)LlmYJjLK4R{uiae!fW z4Og{nccOaW0vwt5;NIGbF-zRHApIwz4PPm zexaA*OSl6-6~`1}TYd#pwI(?9{!{fouVUc$x?96!5W?N(H{1@*#1 zz&mJr08Rloww7d&89W0Vxroyq?LVf7l6c*o1FgF4@8?O>DS_h#h(b?AQD^XU%dF7i zY$1FmMGH9*=1Pv%;D&j1Mt@XJ^w#?OIbIXjGleQ-?GeE&B#;PPGwQf4*Qh_*O!5FG z=iG||CEg5ZE;_H1G`YoNwlcW|4MSo^=xRjhXfxOzJBk(Mc*bf%RI+92$7AK&x+O=8 zQh4TpVS}G4BOa`hr5T@Ix}a@MukUcu+ZPuYjdlO-nVb0%X9JY4>pQqWuwjijSd_Tr@G)^4{S=a>ptXEv)5S2hSS;uimx30A$&B}7qpjlCE-dXT6QI2 zc^pZ-7SZ+QQgCI+pEVKtL%<8lq5ZZ*bOW>ndf%RlWD%PtnW;DWA{&DW5JYZ6wN#~afB0s3&n~< z?9}A)8^SuT^3JjJh-egA7Ne8|UgSP$64mURNi0cG97sitZ!u@rfQEzKJl zX#-Y-6>@}&3{&gaROR*q%A`Xb?Oc&AK@t15-O5(JLGj0p;PDZDDeGv?fSPbkChuFjIt2=_M0}hP)W<-o-%pZM_ zW|SW9?u;Eqq2cWcsjE-CG6JpKl!3qh$e=906MuZ!dVNVvVb>{UH$}u*b)BkaKj(4g zRT-<&6!=Q;qgLC4Fp~=zx^BLM#xf@m7d6YK)VIbXFi0h+YRz+KJB;jZCYnt;8w5qB z5HSmBgILYmA`<_kD5udA_=*TYM(XNA>Q7Wi4cOh5!B^{2r73?5{eFM>TTzqPAseZuXN(_L1*F{T-c zAqk=lJ?Q=A_OA*_s%p{T8Z$XKOpJaE?0yWBiw}=m_5X5y|1s5!8UyOkoDMFLS|Y%_ z+iKz>;xC;dglQdV4n%GNF${j)0I~$EPDsi23bpCWVklmI2zYtri#R!uaOnj)CqfVi zIUoV^E4&nLqd0Pk@hXlKWRz!>&bfm0zI_DfLF~(N2iKKpM4a{M#NZ4RQ%p^uvy81w z;o#taNN#i|0ASzjKI`cNxTncdewG9zCf|tg8wFA&!+@vjXi@T~??(<=>r@auD2r~m zTrORg2|iB;%Xj{u8NTrA`2%I!^;{}>#%6f5HcvYpa-7}GUb`FN{37-4uP?Uni>{B* zNB)u`(n#7U^`2cD9wzt@WSB6?yAZxB1Gb-fBttn|efTn9Fvnw4nBM-}Lmb#~NYb)T zvS|~19o9Z7hDq^534i5f@Xq_V61&c~;Yi>2zO5|vTpu$oR`MrC<WUBl&_w&SMJte70Pr(lwwlIekx zg^h4y&-8FL7>1bEyS^91yGsZderUW0uc0}*zlsy7W5@2_ufi$eOnEWv3^$*ASOsMF zkWw(?&F<+ke155m2t$D*I>noo;^olZ&^9daj}n-=wQ#L+f1v^-hp3g$u8W9k(R!?z z)$z)-tU1sQ(nZ-}Xxr1-J4kCU27QqlAXKDZBoQHLG~}U8Ex_%mmu8AyfbEMko$-B-KB(aJTTG~z)E8X;yR;L+3y1R`v!r}I4P*%3Rp{e% z?2fqe6>ybhU>$h0l0r)zp2G@kM!1a6?R7sa^0G~`vg=nbbXF0*9*i)#njiSN9*x#E zJ#6q9EVM?H`^`aX+ruUP48J=)Dh{Bgu4)f?Jnczumd8?0Bb{GXdYN;3Y<)`id})2Q z><9SK!Z5}dQhd&IG}_(Iu=IaR*U-Ju6KhcTtWz8-K;`$+_^HOYD|4*FjSVt`&>J6k z=_-0Vs@a@!B6`ce+H!ql9^A;|@#T{nf+mwmEG)GrU)pGaZOLP7{?!nmVC_5CMYiVc zNj>Rya-N=Ad-4&d5z>k3m4mZLUR>UEN13+VVRl?T_=3u3J$Gs~K_c|1(UsP!0IBExDp76e^S!YajZ zCb4kK(o1XZ3k-A&(q-Pa>;EniPYF7$>MZrgaDqm3I`()XQ#3{xOed6({bG}OeYSDO zS5Z;X<&OOAm;+Le*G$ElNk(FFN^st2ihz7+Z8Ha<_ zM2y_MQ8f(yyLXjDjNKkO4P~kGg;^BNbY{{EvWL+j3Qo#05bD}*m7v(k-wE5NAuW@- zBo4>Ia9Q^GsgUayW8Wfnrl!x>N-nxR=AUG5whIViK-sH#h+ypeZdGu4h+ij_Swic3 z-n{?Ti-tGiNs8D#xn>(&*?cDyVsV5XO^z9MkDnrjx{(^Dos|uRks=h51OF$UwK0B1EhZSrj!?{C7psLu+u* zr=xW6o#qELMvltqNOMf+^t90=6BQkH{;xOl`|#yz%Iv2H=Lfib2gbu^N~(0cpslqmC`(ZWRFCF ztpmRNF(&@55KrY5-tLP@Q7!>8`Ij&>&?!;>x-UY?cw{n%76+u1q-IKnX+^HKHZsjA zTVHjZ&2ybifTp{v(ob%;lODYM)5KT;8$275pi=XKyZbL7sUvoUk()9MJunOc>ml~5 z@b{>A?}#6~c-r%~c_NGN*a2L);X(F`0Gl(9+DE7biDiIHr)BKdL%+a=ULV28$k5LZy3M zJLdC>9+=M5{O*Vre&H=1)I)3CQJuw~v>%>~AB<0DKLthr5|9b~-xNbBBfF=Qjn9^9 z5;>3S$d5*+#{|xsJFyZy|oRF=W;;fA?&TRwYp0KlgRw9+l&7ICr8y0tSt{kWiPCJ zk66_ZtT0wC0-D!fwls|a>_6x25>=ztRviZ0;#{Q?F#NV1A zY5)+e?pd6+fqR7LIMF)=MT zYTkr8l3XWpUopNB^mQ0iC^jzW>pWndg zein74QT6M0M=T-j*^~r(nfS2}CpOd+hJqxm)CsR>1PsIe@FKiS8An<8Imq`%5?c|t z^A0A#`TYI(TEt*^>bT8(d|_SNR{+y-R}jLMPX9^VR&CbdQ$?~hPQQxpSSC`V3TA&C z0u+_;-Pw|YQ^pa)l|%&H`WLzcwcptcY{^Sg^M!Fl*Wd~e!S(A}a_5xc=B0#PnF`9B z%w3(KmT;PJMo~_8N-Zo4>b4W>#Va4wm#bt!Eb#jl&M8&k)Z#raI*%4Zk7i2$Ly(9A z5n}cVp*oXXj>aR-$FVt+^3}$>v^G-d5N&La40}JeV9MmLN)kEK-!H#(DZe` z_T-%va`D9@NWI)FudHEoX0N4!bnJXc+YbNEFAWf66f$g}^$k*en$e$g-#yZKP)g#3X95}FZO3!egK3_MTGt(uU0(d-&5cQk~1Lxd_idRX+ZJ?({vnj{v}Fz5lR zn{Ln}sF4F7q^}TkRfQm?(PBqurR$AbvaEsTmC|7J{%L~~*b7Ge7-m8)Hhdn&rVYKv zA8(_9aAejO^Ys)_jbkG3sgLQy%ix1dK7FZG0`G`FRNzQd(dU3lH^ZA zgs?NV^ixF1O99+S+Wb_$C-mf--Q6;!AJ2FId26hmqxyf^#_YZh2F8b+A|D>(NBmzW zw{m?XSmA@!?MOAxqg?wRI?Fkt6fTnMd-&3EgL$k`j$i^lX?dacIw2sZ!s zP9m$bCj~Hc!kzm-UEXMfTvEk6zBw<82$T6n5x}{o{4r@|@$rCFDtAC$uj1a=!sp0?dnxHFm?ds$7DYM}=$GQ!g zj@@2!2P8pTx~7oYS92CcZ%W}#HFQzd5UDIixr>2(-zn}672~Ojh9xB*atpS8YkD$4 zk=-c7xJ6QW<3T;z<@Z$;|cM%BDRCA`wG+VT5} zUT5!+aj#zUN1Jj_heZruku;ALQt$rAxK*iPuNOLu0dMZY@B`K32SjLt2e-+Fk7k$2 zaHYZrv_$R8iu`-oH^!J-sWLN*M)v1Q5PD{fJDO03)b6t&yPnWXN--6r{-S89jGg{T z0|{fptMv#JvQaIBa5M#?JmRU3{ll)kBk&RtXc|$Rk>_RwFzi2KQSY%Lb8c*?C`2>F z(7>r5465PY+xnr{@LB1KX)*8|z9(h?d%*xc zX>A`@-}}?+{n@_LfyMyB*R3~tqJ9TH6-UNonda0GO7rA;R%P?lLiY|{CtABz8S4Xk zo2u5371cmWYEgG`X9u)pJ>n>x;JQEF0c@@%db4CMUws~V{FXFK{4f3G_aK-1g&I=Uje@IVYoT+9BK9wIoB8>j>>R4=cY z$%NwUJ214gxy^9(4`; zzDNzXMa(`DVyz=6h~d>AccYr(d)34r2@jgwxgRbvOFY`lv6?-)_C&3W#NN*LiyZK7 zofC`x4_c^T9O_1;UFczeT(>K^Zp$UwM+q51Iq;$kr~x#=jE}D-^=&HFHLyI~OJMTN zJIC0!Eo6`p7#fS}UC~VYqg!`xcc{6d=~CWFO)ZvsGD(_RPYLp*95h4YG(?zeXbvyz zibkn2cm=C&U$6?^!ZNq(yWJkp&=c*P?lB_uy+`Q>IzS3!87BDr>)b%yTlJrs-enR< zJ6{y8K406Xp;EL8H@Ev+E(TC&2N;M9KBiq?)f{m_%S%VQ%hKC*Rx(WAUd25v4Xe|# zlya+*n=y>UchlOht~mZ=BoX;C>~%PcHanaU%2tTUR7YMw6o zH+oWAYsz`wIItdqqPr$}Tk5Vn4|h`r^~f=ij=p0H`<*--8>z;?leND2Aby42x*n!; zDl|GT?0((;>{C_bqWt=AymhPi(zxT#y$1A#F+Ra^{~C*5GktJ-yC1)T15^>~E*tZ2JpB&w$cPv@ zzpz2Q)(Yf`N$l;T>k(HQf5yREV}q1-4h`aQgJE8IXEb2`x7;hmg3@ie94E1xOYne&tk`VLmI}~pGiL+&rtVHQGdizn&1wZ4l3MC z<%ZKou^J(lG))sTD~@W>w{dKXF1YoK+8a_^wU2t&I8k{sjun&*bQyq!g)v{>K_wXu z-_U!+<36VV3Gw@V+>M_r#h2K4duggl`}BLhhL;ZOWu4*^L7a z>peT`j7-8kNBZS4rI)q{tllP8+}&y=hS7WhWYA4Iedby9)w6MCxm3bOQrPY5k$-6| zI(xD@^+*Nd2OoH`v*jH94iCh@4wzAqR{^$|Kzl z49Sr=T9;*k;eksR*_sd{3*S%WI+4vksR;7K1g8$Sgnw+LA^b~Jr3r380IjE{CZSmT zhFKfG+QQ#!LhSTjq`30T*Mx&D2Fc-%Fw5f44vYK_5p`^3C-sZBbM9!T!-$(zy8RHD z7PQdsr*)3Id+_}{p_I(x1Mje`!q<(!< z+`t0}HZMgHJiOL$II0`p|3UUN$ct zQrJ0dWwBHG0E0ST&S>TUY=9#Kx%vl=DwP)k5&zXJAJQbIC zCBTi&_mS(g^Cs_I3vT>y>C>uaGuU4gA_Ny(im^{k$tt{ps|H(b=U^WCbQYo3p<}VF zjgRDw$+QztpBDhVR8-eE^9Mf z9!$A!>rZ`hIYt?r?LdF=Eb(_y0fZU-17DOzXDd^`D2T9~7|yD_K4?uBC7y0wcs5`p z!lTTSh&L?RPR7ozy-w-Wt)UBwB!pP@>{jsX{Mp|8dM|VtutB_2B_D90U*doE>A(Hi z{}s#3>Rk9M5LvJs(-$v9s*Bc!^UPE8gsc9Ta*FPdG*9x&2jfkVasH!`M-WtbH4ViF zO?YDVg=QQCuRDSf-8bIB*K~Wug;4w$;Zh#ca9p8tjQ5DFF;+d7$0LZZ6c2*jxYw89 zNY2b@_noq_9gA?8p%cBRMR7F4hiN8T7vwV-n?ofuF(@ zBzb2{xI1rOXyc79qaMafqsGqDTCWwdWhwu8LA)wad*=Wtw!0Q!iZ0QwLk9jV`g=i&s z2{D6pBDq6_ye50Qckv+gCS@C@m?i2rV{nUily5tjCIXT1%8hwW=}65}X5C(zls3TZ zhCN;0A^G3i2|p2dWYE2P!JT4D$M$$6kDxWOrlq2op@~dizA?+KrgTKFX%&~^{gUN| z&_d3Zhmn0n+vJ8c_&Ngoi}f+5bWH+teMy|GWEpF#1bw!<=9U?_BbyJ^b z9n}yd0^K5NJa2%UO$Rw}?J{+xMR4=UK>1G+qqQeo^J6P3*?}Ew0cpDS%X2Nz5%Xn+ z(E0GhtThaIvc239w#a{Cb84t>X8Szb*&dubfOZ(P6GIv(EHqI)(9HtK1o-u_bq?NS zCSm#KSd48uSnr)63^wlQn?F-pRBl)~M#jFlLW3~$e}}8E#Oc#?`CUcp6sKI&pRG(S zEt>{r_XL%p(|6q&VSS){B{1t!nV5d-%DuuNxyfTTEc_Pil|_0zD5r=BtuwTbz*e-< zRqUMs9c@_6{~m3M3osTh^<{MYO}`K95hphL8C1mK?Y~ueeW_{fh+!2`-8j4d+LhEO z5nk*p7FpjmkZb$QYc-5BE-DgpCj74bMNa$?~xxWHU%7S zHTgYMmOcjv4ZbR>pc)ONuibFpA$6x^tqVM8gtR@JFMA?OJYS#%oDu)snEYqp;(zoK z|3+f?_ea6Ce?4w%2eKOn(X-wo%;vVZcAG#Qp~x1|%t9l*=y1-_Y)(^#G}a@n1n_#? zt0-{6uqiemE2i5+iFg>WoPsMu8#faAfwWxhUGPFHp8uRmc8lmhPm@z@kn4zE-)U>2 zw{7b3+Jv;5lvPSn80Be(Z3*iWKlYcP6NNXcdL!)(==nvf>Ja@oeS-o~>Dqf)%u$aV z?fCjQtm+>9Tk#KFWb|GjSri&p`E!u?3n##m!d=cUG2XT`L0$m^>U zqS+bF-*7+p94XQqJ&k(XO(b>hvjQmGXBxNRP^4)#&~W3V$6rYn)x}POJDMR2Ik%N{ zX@8gVf6&0@fCnCk zz6LiFeJuQLmaC85qOpYjscskEj?gTUj4)?I6VL7HY7YOPQ@}5dRlj5X|Kez2YtaPgeU-U;76W%D z4=zst3xUbl;X`aqjneV6m-w(A1bKO1x|D!v1M7)2aghEm5!L%gmmCTe&+I%LRojUA zqWMYWZ7ju{{a4uz+d$mW??@+FP3~8!EiVzw3D6U`K_ZS8`P<1Cgs_yk9YadkBM;t0 z^*>GRn>O9u@93 z$N{Di2ZZ0a&z!;?PX`yMiA5zH58PQdYhOEXjFSF8qsrg%LiGV4SBRhX`-En7{$@16 zZjSW(xZ@m3h#@YSe({cLB_k2Y|0X2Q2=4u#liw^XQ z*sW(bRQ|0eJgXFfdao{@xO0PEICRd*Ccm@5ZwqbCn4qAb9J zSPhN!U$F*vx>1%OAz8CxmyR{6=>vKc5|ts50rk#3!Sxg}b))L#DqHx4i8$p69LMtM zMi4b$y$a`C9OgmEQ8Hs2Jf~cPoF>~qf`>+l4C&POT}iESmyaEs5oC}lid&RiWoj6M zZcQ5b;z#A&I`aTf%y;P{HLLp~N)&QRxI82YGPue1qQF|>DPok@hV4OS*jvKTn7bAs zvJ*?RlWhp#w30FRtxU>YI`4bYxWV8HWDCv0?+#Q~UL&u-+ZxV1Lp+GdEQnR_(duzK zQ#+T>p%ifXl@vpZHG4Z)abc|f*l|<1XX^Pu6~|W3fxyAZ;h1Cv!teyhSzm7qs!&5_ zK%CrY0@8$i^GmigF=m2Pu>^+DW1CP1V82VojO{3txM=&+$b5tu^3$Rr)g>F@)H6(o z$Oh5?XW@v5ykH(HIosK3^%E<~HYw{kJis&!j*7y4xF+gwW>H0nH1Rg2DF55dEMe)K zETcJit3QU)j=d!*Bi9}R7FNBozWzJ;O6HR-N(^ty4L6H-z=<( zdbJM4PM=|wS4pHvqrP8ux;Erb8=NOi4kE_jC?f)Mvv8y$mb1%tEj^kh~L*N zdqbmW;Mf-_t$$17C04w7~e6_OWYN#L z-d@>h`xh}4s9T0kG&hBUdmiGiziPjc(ta!G zpb*cFsdk<(D$nf5TL4m0fGUq}9aJc7@YxRM^94%bJ6FDy4chXf?T#iPrZa(A=*FbR zzSqTod4e#Q`;T{*Cc-~>1s7=Oe4bqin_x!LyPf>VkTNw?>mk!8X_s`LZor^0WCXT6N+CaX{n$65gchpv*&&CmsryoeZ{e{HN(alSa zmPW;bo~sc>T$H$fx63J$V&EkA^113qjgqs32Upo1h+ z21@?g!&yO6om4ObsaGlP@D1A{Wl%J9#1ll8TG@L5etcU*ebT;GDv`{HalHFk-*G>8 zv9#fLlBqjWjn#`za)~e77Ypc>kFudphA0bCx5B-^H=gOfeW3y2bF0q8Z&FA5L%)zz z{q^VB?n&o_5|byiU?2X8EWXab${cw>6a!M~Nna_{ z6%kqvl>tqBvhPpzi7{W zUH+IJ^-xGPTp~Uda%$p+tX6|a9^$e}K4;Zg+3oCis3@IVsSajQ?6Rk32?@38 zGb&u5s1CO-;B!^$GST*vt#{WkA+Q(!N10HT&TZPn@yPKfDmgk@(V`q^up7joZ?aDkCq=J-8JUWkXB3}c ziD+RGx$c{$2bO~p!NHYWRT5?QR=MZ-hwDkyu7 zFDw`&`B{4?W#6;qsd<&p?2f+|jC(aR@Ig;i=je@U>B#)#b*011)-!sb) zd9rdFoQfBTZX@^=iZ*;1o1g}wY+y@-+KTDF`LA@_?RY(Yn3GFAgvGEh^ z@guLAg#|F6P3}hP2?(ygK*VZZ&~>mh#Hgb1cq7^HPCldp4Q9&xBSKw}$U^Vhjkcb6 zn;9uGkx|5`NB`$9q=g_yWNw@UuTbzPb(C9yE3WNyPrpY(xW7W!NIr*KZ7?lKE*{NN zWlJvjMG;h)bEi4cL-*#%f-LJmP5XnV(nc9mvEA)aqA9ruea|H8E7`?!qDj@%X-iNV zEvZ+BN*BOJ7e^iOJzo8uqZ)BU&9}#q{OiCfb53}>`D_51$w4~nl!SFq$nZ8o?9c54 z(T!Xu(*VD(dx`V3>xW09<&Ha=<-lXEEZ;Pu0N&a*m2%?IM)~SyTe*-zDItWyt0JK)NBW>I@Z-+id-eZMXYwleKnaYza4@8QQ}mCb zB=915pup(supbSV;8*jp5C;mlO1SmM)VD}_CO#XS#}ZFyIP4U%5R$N9S>3G?IrN>3 zi>PklNj7lXYIj0U3aW z=@CRVDF*Y!;QvsktbZS7HI=*b)97sby3S4p4;fkS(<|VfbamUFNi=LEFfZ(Jx)DDj z2ttDuo`?h(BQ4}o_z8`l?|k~qrL*QOrQj*h9`Z$Th<`9bW{`rZE7hlvmRE_k+BvOy zM@#5M4EzWZD@M@PXfM&XR|r@rLi}@)dpB;M-#Case7=2Hv71YnHbY_rk5kfou%=Y- z4kFTw)#v*h#|ARA0Xc_3If(Q$RF3)!8-ykK+3-#o{j2DUoYE)GhsF!hGC$2Ly4Dby z+-7yVry~sYDTfszWnSsf^iZRg!z^NtAtwF$xw2`{CK>;iBH=zSnuD6yRTo&ognWlmiX7072 zGczw05@VCle&=@Hi4a=cjz}{qqiTG)f&JwEq`uazLtr5biTw%W7ZO<(Hq+bY5Pxe* zw(v1}MNp(v6e4YvzFP)3%IfrMHEI1gfD8$#B+T5YKma=vzgOSH&!M5B^I+46cVX%S z%f~J{3&(9`r;61LWRTw7qyea#or{!xzBQL4_hEo#I<=R7yvOUu-2M!}o7D-@XUTHt zH2_8Yg0&=qaY=+F?A~d$)E^)05;#TQb6f}{j*U-rE3OBj|B+en&i28;1vY+hmCMnB zs%q4H^dRJcSQ#?lWPG;)h zTiS11QgnA+55Rm*Ip3U((PZ4eV59IMsh{0ozo-6G^HSkDCcd&JyB&BTw#Y> zYe2q?khinXIWE@PuC2u3AExk=D1!r?r}5Iml~d1Kv5cXUFIODiMuW;NYb$aM^*<^T z|1{0HK0^n`Aj-_>uvmm%DIEQ^rPopFF)2t30dP~;GSjUzjpXVE++1%Y&R8H68R&X{ zes#$H8SF@EZdC5xcA|GWMH*gdK3VHnNaAMdv*i_XUo4$-`)`8_5B}a$uQ4d_;f&NC z@hb4D8uD=MJZ50b%JP2>I)D3;N3;@<-=pq9&OZv%IwKut`t(7PPb562h1oBv4m9Q6 zPwk5@e-)FIf@>$bH+u60-S*JpC`2?cptdoBF`RQba*5NWg?S5h8>bs|Hhh_hgTfRz z(DwG2fDTl}^5wKDL9#e#0}#w%@+y&Hioe!_ep`=!WYSUk{nq`g%Kszmt)rq~yESe> zKuRS>x*VyYK^g>65QY?x7&>O?5RmSWZib;nDIcW=>FyXpy1To(zVV#*Ip6u#`+Vp9 z4_IsdVa{ChHO;UYJ8VF0 z&J+_GB&^(o1e3go2K67^zG^9S;Vmg4PI#V@qtkT<>~S4soZKB-Ql9UeT|4EI8L{2- z9YAO1Q1aFby{PQ zh7n8gDNTuR$~nhL007i?WOuiRJj#0wz$~BWsYhYb5}N9q#Zp$5uSi_f*_mDcC`IckzZz`VN# ze368Q6nFjP`Kq9}_<3JQs5Qn>Z&oD&EYCsjv>5!AVViMh21xy^#69%)NQbvck4>TG zTbfQIt6yD1cFkpM*PUmV624dr;cu|YF{KExRD*zWye-UX^2H9p;xr5ohmD0)gX$g| z1?n*#v_KsPK4@F>X(u4SlL_BT4sQ(HffGuxFyM~Ke8BlkJix-4Lnp1tC&BpKVJxBH zrUcz|*cGkR46{#)|87KmbshOysl;c)jl;#y(8(k-mEM_8YB}8H*X@7g4)vRjH$F$1 zU#VJxnMx!vB~;ITuX$Hp4<*F2ij6~>4kK6`w)!5G*7-P7uD!XY75Ci{yXe0)Y%zRw z^&P-^wlvB>S<=w)Cy?D=^l4*CMHY3l>!{)exzIJ zurV*4wR2JTG12I?LFSr!v?@AJDvBB3^T9CmUTR!!ul>?twaj#~oOp{dIwi#9Pp`vQ zKvDQ?QT1caJrUTlu{>%Fd#sX);g>dVHFRO+bIB!J_!WEk#uga0+ zTdQ0PcC?gyT|&YjPTFkK@9|Zswv!Sy>xY-LIdDtz?ta5J&GvORM(X`=AWw$#4__3c z-rl?AcPdRYh4**2Y2qL!$KzEK`g4P*6Lt9 zSNZc}t(cTnz^G}SBA>uGULNVL^6VG}fTP_)jB|2TNS4$ z4&7B5VzK7gwFC_DUNX>ODx_iW)qF5&F#L(meW131qZQ3h*B%xOM`pqw=XRrz*3OVn zhBWPulQkx*)1Mw&w0ZcaKAqhShY2V@b2+LqMqeq%1O$$T6In;2WS z^39F{9NcY2qj0~!%gRE*=Z>mqo5{w&+pE?q>;W9(3W#s(Sd*#}(jQ)yi12KY#WS)8 z*feWqFrZ4wVBy?R?GNx;{Nn9c*Zn=RpLa@PLy8RJpiE2%6WQlN#B1nv ztQ^>oVJWJUI2jPq$d85=Iw4J0U>HYKJ1e4u5coWe(?kSIxg=!0dc7z;PUR=ak&Nm( zU*!irsm<+tlJ!_UqT}P6SXzwTA{i%Aiy~d=K*yS_$6pWgWPb6ELR_w2_R*DF2oWE@anN!$&x%Tr}xo_4_oyhJbtBMtfpZG2v8&BU}LF;do@1V;*_g)!| zwY;|1!)Kl>q2pHK=)GhR_Z{?_)}{TH@;KTS$9?_e{aJq(a}3vvdiwp#yGIU3L*5q2 zI3{JMHI^SDe|HNWjveJ+piuI+zLHrl0Iz=KKL#9TKxRZ0eCSQ8=W9oueH9SO}TgWJaH&J6bT8|ik6JI->>(L zT;IRL*G%Qkrq`dU5sPlkAccDGEtr0W1mw&k1bPSJXh^}oYy#;^8wziW5^l%VwJ#`_ zNW5Kb_jFEui*F~&vq`ZpMD!koQyIC}(gveuB&jEA}B-{C$*T`el@`P{q} zTcwU~6M;XSbzEMjkufw_=Sdun@jjMQx@j72&?A3dGu5EV~@J!w|vemQ2*W!f;{XyB1+ z^g1j$U}vo(cxD*Od` zH^NQH$;oAYe)U@y;_gP$bjnI0Vp7hi-sKiHdGA2tPt_=8R4OIo@Xe!rrkuBmbQZ#) zlUAGgK98z)e3?xw!kc(BemyU+0#f4uL(~LeB&?b0izj&X<#!JX6Q8x!(>Yr6h67Kw z9^14m3>o=h48xcN5JRvOI$a;UMt~HEV=TVv#Bzv66#?w7MsVP$Msg6UO8ZL#Ba&WA zjTJuBT+~zdfLSXlM9!KT%^t>d7h!?w!>j5hx_<GHSgPX&;bn4C=04Ww!e~k-F#Z%o+O7mWXFlfKat~lvhZSyYumSvPmg!9z0UU zgA?`$5fhJ#vHr$o!Ssr-R~U)tF8y4%0^giwleb`e8+i72JAA>sSaxX_&)D9 z*=uG;8<9saJ}1Uo;6pkq#lvSJVxhz`bux}~R+a1T*M+l66r-Y(-B5e$6wx>vXQHvk zaRM8WqQc{15z14Xxwh(G9}F9%5b46Ze|tU2YvsfCwEi%qd?hdZXhc~D>zL`p>mfx3 zZBM%&Bdlu~Uj@qqFxtQ9 zp$;vhke#c3`n3MSw90ptcZPW8bFQ2FO?8icVI1Z-QWBRFl{0 z)Ze{ntb&fSJUtAlh~PAg86(^(e%NVH>2?r>$-x!9MYaM_o(y!v`IUd{)NR!j3Zae<--gCF}Lq=hG>m~<%W!DqkoMSS} zX`n5JyIN5zKZb{GgsKVZRE@Z>?5kH4^;3F0k3>Vg$-u5gUEf<^AtK@FzNLh1g{4>R z8QW}O1=|ou@pm_o%{f-z_hxBO$oYA+^KCq1za851eOU+Hr%LX7pq)*)eN|y)WFW|s z)U(}nH1+9`lXu7S{a`nh{du;q7*DE`r=*_ke%eJXsEGkP6_kAT1Nl6ZtFqsuO z`8c?-cRU9+SmL`^kFApv>8ybYi9U$R(G;INQ(b)7`c9CB@b{*ROgb$~qq2*gycB{j zP$jbf9|;fw%_lnQQ4?_CspsIwX>hZcsAZYfFxtbRpaIob*klS8M3OAYLTB%%;#?hZ zg<7mrSc%w4VJbkrH11gL2i%FvvKFqW1bT(!pzKMH09nacDP4KeS&`0W7jODAO#+f&%U!>57(*;A4-=5Gjrl^I(gdl z<7EP%PLxS1m#d;jM`u@8qE*WICOa3_W6!!hX67@-_613OdUfhp1{~5I9b^tXJ1M+` z2pza^8NDKw(Cz=sA^ZGjg9g?lYWCw$03&M>sK+rIfV$@SNMgg9P8G$xlmiGCAqRH7 zgG1l`XwBhYOI{hFY=uiV$G zs;F}d+mG}GD3L?~lB#8eF-1_byjlsb+>$g_5lUo`HZjjL%@ zm{Zz%iAeewQO%WVpY%ipcIq)%H<%%XUEMhFF@rAw5A~;H&L=9kNM~&hVJSp6(jYeK z(XjWT?{|aQzXCX}J|V}J+g%Q2owUY(S=gwsN~!=nN?-uU}_pHSx)I^XR|8jN_L zAGjsUrf}Ay6VJPuVQtx>LCp@{4fYb0mYpxma{^uYLoQl>buHzWo<-%3*}4 zUX>Edq+ua1Rrf0+K8oX}vw`5Vp}SwVb3X$AbXV9*o#k3|VmssT!JgGeeRLIIh`B6SRxw{i{FXIrASVd*BS5NXD$E8Mf=XzKV#tEQ4(;ZlzZ``i|Om zIb}5;9y^QQ1-gq@Ia0C6N=CPyo`3VckYen6yS!CKQ*A0Wrhp{P*d!DaZuEIFpYMxp zShZf}=Dk?GTf5!aYUC~Ia2|!m5*0)6ZhncBp(AkCEy{$ zG=GU=&?@>JNMLX35e0;M*aW7F(aVlw218_DOhxPKHoD^ho&vfg5zl>rvJQ;gzAL8T zN^N@$QU`@ZhxBc@4W6d>NOi*18nVrQc~B{5DL3o)kyqUJM~cqn@&DEeEtoO$+^iaQ z92nkjr-TssEK^(DMm6#}c^Cfmf8HYHEa+RL+`Pc^@7TVC1=Ao_Ur(pyGXc4@g>|Kl zMTHJ9l{btx%rp*`(knk1$(J_c@ru~0TGcDN?wu3@lXLYgHxnQ25Go9?-jS9hR~bj7 zpAA#B&gI;*j$lAlrn7eYlolK8C9Vv6cyl;;fDuS~Y?Yo;4(_Ax3aryk9yXu(J6Bf~ z@`kA7-NkIikJ*>tI5HnUZD#PPBp!M!CKexd^hK29QgpWssHxG+>rEAP4Z24s<2AHC z&r*KmP#NLI^O~wtTVGH5yJl->{7M^*79@sLrM`D(O^?K+JMnlQs?FV@3DchEMi^%f zExylLcW2HTL*arEhnNNQrii?a^XrL;iP%$7ggra*SXj+kMRs(xMYf>5RXH~I7!Xc@ zUx0&Q@EDUAO379eXs>?eZ8ASyl<5#(%C5(CQHrY|0%fjfJ{!*uUkA%9A~{mWvf9UungyEsuKVDYKQcoAYH9?` z9eb{6S6<8C%^JnT{jNamTBc2&b|?0%4R)yytUDG8c-^`w^j4lye~2bF!+*KRP2k5b zi2kagfJX1x_swUkKD|Qe3lM&}t9NQ{6UUc*K!sN_^6RhKoH16ctuPsyy{V;w*)Koo z5(;69yA|3iUqPKtvD0q%e30QvN#{n_tsMcX0iVg<9@F*PJ)_XQp+VNd>`B8nFEZY? z@_+1_3-k;>U(R_IwS30Nl`?)v-t60s>VCN)pc&WB#TO6Wgg##EzUWJ|GHzO z>z@k=*`jYNy}Aue5DAKte2e&zP|G>68~j36Q^tnea_m{1aGf8y;Fr$x1DKcRqROH2 zZtiZ_#bF8POQehTJV(lupgKs(yq{8&cUC1-LC%>jp*3wOLmZ~@9n3v0xN5hoit?CBJ zRnn&m)kKHpq(SqVQZAJsdEYbh!TVlw7xs$f>%tfxz@lrT*gsweRVjF%8cVkAV5 ziMARKspWjuUCoM$pC$ei%=5S6s;a>H5L;j2Rqp(^g!5$ncyr+(et5C0t)uhi`!I1> zWcN3?DTrJxI#&-ZkU(YdEk^gU@q{A@O2iShI_ssEGYq@l$Csl}HSg52Ocx7shQJ&F z1aNF?U_;_)>o1bmf%CkZW8YiDS*NYQ_nl!y215jIL7i=oaHIspY2bkE+0TF-ZMoTR z%@D?z?mT97t9($2L~g=4jjqN7XTsZ*-{8t}I9~myDyG@duyh|iV7_J$H1o+8_M{(@ zgK2V+sN2YogRqoWGR8O_Zek+yKCyz$$>5ni4192X2H@4d`m3u%IVf*}HAY`;NBDFU zT&T#tO0`16BZb&DQgGaCOXn3CBbWuwBWZ=kZhJ~+Mvbif8WKlXSH3k>wO}Zy4|k72p{aGH4gGh~EG525V0-vn}JY)}hjyh`Jf#RepBu_VT8` zLDYfY^T9ry7h#MveaBmZm?gQ}E;35ZnOi(57sNJeCaW&=1+-O3Z>K(7OU$s9{fx41 z>V}!CW4&#cn$oE0cnB^QW=k7og7-cA`$6{Pe6zQkVo`pL)Fb<19yO)!#}~biF=yUS#kq?AY& zH9+Ti#X-yd=g@neI7Y~`s$vPEAx|Cv_^K#droSrq#8D{B3e5Vj+?c zAGbz8G$M}D&^Pjy60k%P5YsPKTN3)38iCC!KHu+ZC8F8c@oA1k;@Fr zo^VqsK_wJGWn7)xac|-<{Du*n#1Qz8D%WU4l1%by0^RjW8w`->a{ zgkM1wr55XqmtT9f&K6X^(hW>F+JcsYG9vQ(S=yU_hUzK>oVFDEHi~l13vtt2|I*GZ z5hYWukKNj<&*@T*O3+NfQFM=+k6t(Je+Yy1^R8B~l2Gp5)|SwH4HWe=;^2{cr1u%{6l|Jms9I8vrhzJ`1Hd|P{LRC?Y_Q%=m_g+|;Y z@0urceK_sbOQ}DFyx^7jUQ&!Z7lYQBzsbwb+Kw#tbLvK?Eu8D|P6EpOYYnqAo}e_m z62LbZGnbApv7QMRhtM zfm;{?)KZJh-aj=!T|bxDU4lc)(r}dQHqF#(;MiUAS&Ug4{R&-S=r6w!>e-ElUp5RW z9ys8}8KDO7B`PeKn@k9j^L4>+7_z`le&OAV1)1NuOLjEebTVc*ZUR>%nt?)RqocJ$ z=L@Z~nVl~NWj}TvfqMnkDwHA$adP)rR9!}DgZjm|vlNF61*x-V56k#wFYk0>w%=Jx zUYF9p-H*AmShFjaIO7d6yxsao7jQw7;rIQ>_gJ4L(w9$}?t0CCUzp$9{73S`S{6-y zSa)jbYW}UCN&Ty(8$KnCah?KKj*HjLe=G63(ZIg2nc`~YBkw8?@D8j z(p2JdM>;yUx3_`)M`@#g`DA7>1g+D#lGPc)GD&OOStHhYiH_-&d=>nJ85_d=5ZMSY z%@^tk8f8>OSPD}8aqBtkXXYcrf*vt<#fL5PrQoAqHMipXi=4XtWTRbt8}XCKl~W8jrCiv`J~5JRZX@+uD|I;lu~Nzcs)XV{j3G)mmeM9^%j z+2&ghvW$BiCOSFG08i-#0?^n4F9Tk&;?*jd1>epGY5Q~N#197j+*lQa?f7$aU;}@w zH$wmFm3;Y2AMxEvPaQ)%o9FK<6|~uuyRGw^*(s7oQ*b}a5lxfrQNId{Igtnp$vQ`& z{Tk6vwYF4JXIA6zyO&l~cld(yH@_^K!<)4@HRkOzdA zfqhMKNE_$lmIDV*s;AE+!yhf3FMZgS;^+*ifa`*}|JY_1QfIVvl->`?`?fcp>7VR$ z*v7GnDF;Q(jH==Sh>c9Y;&K*TH~YN_(qu@h>{8Z-h7^b^uXDWPWN-zS{9taigBWTt zwwk>j5#mt}TD?U;waKGs@?H-KXyGC;OlQ7Nuy$x-Px@GujA36{x?37d@aZE~`5`X& zUv;1=SUbqiuVAX;aW8Hy!k6}X8o3n*)jo2)J}IPFtOO>n6ZVQcgI2bVU31@KPpaIX z0HljKNWAx)EcTWO7GCatU^%mrKnO^qfa$rCIabdy#DIA+g z(fs8?idDqlh3ZVkue+o(ny$S&fyH6J{yaPx4JmLPF|H1J6fy%rhTm;} zL69kiBenkoL9u~fVo?9$d+9e|GuV}VBlr1?^y^-y#h2rDFMf-T10@i&=b$!so(06$=pz&rX5T@xTH# zA3jP%SP9Fq9-2y3waDYi?=H~_@v3EM-803L*U02RtxQ;D*|g#rd+8^@&J`fr^Z*R* z3S|Arr?`RS)g75>Pg#|v?z@=9yNktqeB@D_CZ)7S@+r3=CuGcbE;nDr^knRNY_Tt; zzrK{+6-5V*r9~{&S8D14!N+6P{^Am8SZ<|c|8=CgOZV~TLR^I;LdC4lztQ$T$GaFN zNUBujeZw*@&0^U8&WCs(YJPBapiyVp=&H-ub0s~IrSDTjR<0Jn*{&6l-l*7I4uG6c zk!1&eE__(=E^bUTj*Jvo$lQAMOfZEIB|Wh=`M}}3UNOLcCBb-A+l0@?&Pa{94b#j* zI_K16*KVD_fO!?WcpMckW6aZ|@VugqlGxPqtrB83Dz`!Mp+8oMElZb=Nze`PGpPAj zw^6ps1eL7o>Vdu)o8$dEeQC6!`o~!Zf8DUA11;ZYt@9UADItKnRl}@Pq5HLeELQ(} zPGUUxPh=IGU-9!_C(XzV6JV4==((QZx)c{e|E_HGj|;Lq#5i%fjcSf3pA? z7aQ1+JZrUI`AlJqp=z-?H*81xM4>ialw-4fC*Jet`AqE62Z> zJHi>LWtQ7iB+TcvJ1X~Ka+yUCrO&ggK$VE$DdtJQgY_07?qFig>=HnE z;Olr(k##LnX#L3U`W8Mk5zDZV8Oi}r)z>LD^psjqkH}!qC4)2H>cC!ccc^)+rpw3Y zCuD$X)zG#{T38d;VG`_;YTp~}FcK&$o-I|#mDwrvdhz9dNEe{g#G1^idJ}uv-S}v* zGVMoHH*^BpwGuX_sl&2={1 z8Z@aXGkv>fxIJ%xb=2vY<7*$ZbVwuk%TFO^F6zz4=dVv@DVi(aV5vOfvEM)ACax`a z+peF#&zP6GI+m0iZfY_ABDKxp>zG%g1O7KC_hUZEhSzC6E1ieM+Ty71?ReZx=e_Vh z8Ww+Bm4Akb{;3STp_373?rJ#iW?`~D&OqCkX1aQM@Dq)^g76%?PzKM917l)EAu(EF zXnt6Z#3?)g{g5TjRiOVb8E`ZV1oRL=P90h{BDNA(+zpkIpt?4Jw>dlAo;|Suqk0DR zB{n9A{9iOeOl^!HQgeOacgC*%*S}JGHenyQc|DBBSemXrO*eJd)SY*iYFuh`Y)H#g zbgvsIpTt|9R;$RK{>ap5PJEjM-@rCA%v8%#Au!O>iNA#TR)=Xri1i_w@t(7urg8Aq z^w;dSCww^xy!Bt%SM^B_l9RTRWF^oBCD$94%2qk^>q2V;*1#}yLs!Z`F&I5>*bhLN}b9j`$cus}UF z3Mf)^qqCs1GIand@yT%OzP56-ah4bwVd2t}wv#7iex0q_nME3!zvF$xuC71%lx{hR zOFtey`;&FMU8_+r{|C~bgBDe)>~n?`9@liXV;SEj3|Xw|Dd;XCW(X_oSAaXoTkQUt zubfv&vhS)vcY6SX0WAN};u+RDHLrSU|IBslbJ2Dk`CpW|5c%>4q8+`-FWui}Rp(_K zg(2&>2SBsyY;bV$odXGuF*LU@1c8BF z5<$zYjZvOUF$?~=!`gN<4OWJ?<}{=*Pnk#SA?62;>tb%~p4j9GW!ho$O;!i^IA*6F z3-jj^E(*c4{LCcAml!C{5$J^F!azD<8m06t3S7cGt;@H=?_H}yd3i{wJ16beheBtM z>p?j^Pu}6Q0w`cj4A`uLN6xeGCIdV`%$l5JN|qZi1a|dFeAe)=S;z079QQf)(vQ6QU3=TK9C8W1~eayjQvg3(@^*?cSbLUb<%eZ9U&Pl)#Q`yE16W`BtKLHo=Khk zeoic3TmK~|?nyGkHdMLCThTTbP>rl%+rI{=%DVuFKrcK79mV}e9?8Gg8H#LZ@sSPQ73?M!GFFK$=@i@8x@VR?#!_pw zY+d+TNe0{JsJjb?9`P$Eq+w6mK(etR#vuB%J4efOt8r?l@n@a66e6nDL47Z8h4Yxc zbGfwpj@>$XJIQ)@zAjz78i)CMZM{&@m=j$Qfp)KOONfGnEeYu!e3T_J;R-We!pact zm=tbNh-aXFP6$Z?BVj{_ITRmmw_HFWPPodVMT{L+%l@#gdH@u4DkX&u!Go|#vyu>G zpJP-Q*QUPy<^s1unE6Ct7cb5Gjl8|R#XIBC|EGsVW5wa4z&4eXyV~i}yzY`(;?%uc z2)enAU5$C+CPnreITk~d%#_&#>JEq>A6 zzhjB32(L#Aq}<6CD=%DTFPe~+m_@l;P-Q#qjM8suMgk*-}v^%O2%bt_Zn{x<011%8N|tfUR=@_z9Br^DwMB0 z(-hkm=5NI!(VIKWsca916fArf9{&FrZ5glchcn+@9mWiZ_pYFSy4CW5{YPuypN_$5 zE>n8Vy$_9u$A_Rn*67Z#0{r)+H8p)&FJJ?}|FAUSj|K3~%^*K{(Iu+UvFXLV``*+!wiWsXZQf6g}l^YU@ux zNK?v5ywVw!^fq*)y;iSyh@HhC{VI!rdV%)=ixJTy3?(!0xHx(6g)+rbMo%iodUD1z znAoLTFCI5t1e|DDpc(D2rkwYcwp;H=K;mik`!!>J`Bein5dJ)x^@F;6335-^2Op^y zbLW=FaJ{B$Z*1zV-*YL@=9zNuh+OqS)f99M*Y;lnu=y!n@a5D2DFT#;A0^&N_^8>) zKYyBfq}9fPdbc|7ACn>C-~Ol0GmiM(THK^$us;$kp`N4h)cbCA-M z7DD#f!(5kn!wfyY^_NBm%1XYtj@P(?l@Qs|jePMC|JMxb?;;n4I87m@5>kxoBFxMA zo;b-bFC@RTR(yZ?v#*Ikn*cp5c+&{P;@$}Bd08PFZFKyZe8qkgQgKy$OBJu;ZH4%$ zBm3{26^fLV&h0@);|z&|)~^T!d*|EUGS7(H<; zXny#Rl;z`68(y3!sM2xS)Yo*05v7K?!rYy9E5Qm0Kd~z8LI4O;1i_0XY$Jyvq*j*= zNn0+|iW(CqVL6J`Ge84T-q`CiU``U_B^48xIZW*VtcB&VbOSf0Elq^<_OOA>6Bm<3 z<$xV!$DeXV*>NM^X;8Pks!8aYGKiNXp)rmY89Aei@2k}QT1`?1IeUQ7t!e^ZDU=md zNJ>(W1dV8^3Hq(qCR;6nrzI_C8v8y-nPf7F=V#6al4HGJp%w^7#u)fy0H1%V)%{~{u=d0-OOT;(+#N@z`hU%KkW_Z;!2 z7}s}CM=7QYC%(Cm<%qrW6E-0pOWR<_#lV`s-(2kzihp~ zyL5XvRDjZ@^5yucuVI35vE(uR8l86*$9}cD)EEmY_*>!!2)$hWbj*_*p3bamP0TNT zD)F!2vw>!VErT13d-jsyrsZOT__}fdZMU(VpV&QeeTlgXedyOi4BtuKylC4z7DlQX zSsL+bX^#*@gl6`M*pqR^x_9D%;$>qiB>XKlWqDk8_~XZnwU>+7U5KE?Tz!blQ}%2H zxAJp71Et2O@dIZ){$f)AAumtHLoj?4I$`Y@c?s1n%4T?^h>w+mk$zyw=l87%JpXl4 zDD;xf_k+doS9ihJGoWkoPlQ=zIR2hKww~V0zxEPf^$gQ0kH>0WOFB#9o1#8J?m#l7 z6>O7p!r8yS=-FeQ(M2qEI)Y>S_EGOSltEq5guP}A0X8QgyaDUx2~x%9ZpEE~7`@Ga zjz+=uZw=GrPxAG3O-YI0ANuNKa~RlMR8$xy4IWGw0%5Cz6P(|GR#kj--Ov0CjGjKg{6+dfr1IFw3CNMO zA^-gIw6L+(%HRi*IFUUz`#2;07M}Hy;^&g~j`TS3Z92?=B*R~MjHt61?FC|MhZ(ZJ zbQv7;eMhm}M9|4pu7@ax=Q`A^UyJ!oK4W=}sMLG>LfAE*-=SOb6L!2RMS4M;)uB<$OvNb&3C-tFSC2KuM>ip)Y8V z=L`B5Jj$PAmghP^9G$2m${k5_SLy+=z~hU(DfT)rlO{W`*iQxjgdzmwLv_wuc;aksjLLVAj4k~zeBo`)e<`xyEzTNSx%1+i;dj|67z3^C81 zL@eE6hqE|BWAa#||6-^u9(|t=_9)QTOaGBFWq-$Pb$>TM@ImXJ>|qv6#W+~%PJ!+% z+T-fpzuPMqE&uXw0Mh?9wjN2Nqm_r4Kl=WL1%xdy6`OLT-ToL`Xe~hwIUDK;X9TNp zJ(C&>OSt(dge{L>7Eh*23{BbT=|hzisB|NW)qhjh1j%P|Y$u3U$|2#@>`O~zQi!ZV z+)QPvlX%uf#f)_rus|X3S@R&%H#MuAk}W1}aA$#BFpZ?l!q1zH1euiHO_)5lrXz=` z@d#ehOry#IR0O};W?bP{0w`x?WmxuY5(&F$x#rdGHS6^WAKU7OaeC%Z9bM*-tMgn# z2$$to4NyuQqkA{F48YyFoF%-CwI-}Aoy_s- z1)w5POAk9c<+XVNl))3ah!S{0N~9PS9(A07KK-ruC8HsCS9lQTc5jL~Tmu%Fq{MIP z|8{KYlj?$SyLxz6ORvc&MIC-9LoFQ^Mfi?~$YX6R2>6C`ocfw$vttaXa9KxDY?_C4 z?8c5g=|~vZOhiqc25jizeetHUxy6gxHM8zvXAEsKTCEj$GE2RDl?3ECZx{Hz`{|&A z+TIBLAhTLlech|w%MkZ^TWi&|Gfcvom5UeW;zmpS@)A$A3Br*xYX$AyS+Sl!WPiB! z+D_Hai>~rho{goTws}d=YNG(d0hcijTOC%Og;(q` zrUY%(GMwe1>Gm+Cho2$usxDMV_OA?yxEqQA&a=*W`+?-pO7ToNM15)iYP$hsxvx>Ca#bX)55(L-^yaMoV6=+mqn3yv+JqH>3a(|DQo z(x2y6V(Pm}tBqa%2g83pS(}}b(Rbe^UmeHx_2B=Z0Lm%^|D#I3MMp0#_k`uxf0wlJ zpa;2PK7*Nf$bHW(5C0LjRPYT2RB@#zb;XsIJO8j-Ks3qGeh{#D2C{Tl?Mhs$m z^F!sq=^JxrN15NJmf!7WV2-xkUq6y?bm|`nuskM*GiPLh)cBZSNo3o(Iu)ohNC*kj zdhDt2-MjiQ)@Z$OOMi}mAhF7y3}TjAyJX73<&M0dnLQH++gd~Jq8fm4&liK(#5RMZ zUX*9%h^|uns&*${gPq#XRWJM!L&GG<#hlHq2B>Qd*fn-UL;TrXTaOLD?gK#Bno!gs zQkBThiP4EojUOeIv%VO5{2{#0^w60Hu$i)yUl0))R@PdosL+hSti>G!{G3&Fv2dq+ znlAd8lttOd*w{d^8r`r}JI@?;3p961B-OM2oTKQ#3i#Qa@Ph@bi=bvHW)W zi7``skX8-%Qtk<)j>rpRz4v_Zsb(DCmjuZZ6aVU#ECV>n&Kola#}5l1%~lW98k^$! z-o(SISDV2(gV)4dx43KjSJZ#?%^MoX+BrobXIWqZkTa_=IIZ%2fd_;)q|2h$!>ZKFf(dm;eW`B%d&V4v;E_xD2g zX8&v%i;-;juDz5)=Q8GW9!Eb^zTKglzW-<$-{GO_pKtKge=UyrL*rP>FI<$Gy4{p^ zeq8Ayjx)V%UtuMbIZ?C{h{FLbq7{r9D8Vt?4-{ad>64HSr2Q;PY*MQqcXE-c!kEi| z>eLwg#nz=Jd~md=tyl01b<4A@rS>>;M?1_OHU(w&s#8NdL z=Oyk$S@2#jE42aQeZ3wvOITcA%H&qZ^7WuB9kCQ*No@RN>gq~6I(LN25=l)R5A9qo zuepRy1S@=w(qk()w?d2en&DsQ_@NW5up9G09jYt9Zh{_7%UDm5B_|aW0PN zRWe0H#sCN65q7i*#l1JOx_Xa#HxPFv) z6|%p`e(~lAQm5%@_Y*qt%a#QTJ<3U)DoPfjFjQYY#fGDLpV~hhHFaUvU1Em&`TCBFoDUYGa8(CZ(~I^-Ks{E#!8^djrA+?!IG&3Wo?ZsH-2IeBt7 z=zX}QZ$iQtyHlev-i;ST2zj+`&fi~e+>hD!%?zB?&POfurlf3J|2rDiwEOO>us2mk zvA3;ZtKIF0%JUg>>gz2(&A*YBe_F^^DS~Fm?2oa(wrc$s_~K8U`5?hmW!Bd>g`>KP z_04lqRd0MY*qgjxYHtoK^A%yM@525NVf~_jD-QrPqqk=r&U+o`KjSqG#C8iC2usq+ zb3)ki^}*G?+N+C8>*8l6pqY)U6HM;wz7^fG$p`?zN8txN>piague&uS2xVgecfA{m z>)0E=4bGMFg#EUQ55&&LOlmqSs7&Q_R6fBuYg2tWqReuDSgvGxw79wt3Z}9Q ziL7_y05`x9`aOm72)MrieF zpu_r`xYvva1wpBgx6P|_8Zj5bnELfsj_GBYGxRdrbP0Ow1~%s5C+!MJzqd~-_!kn4 zRkR~yta;5jb;f`W*Q*y)d*v03r-^0C`srvLo4ml=S?<1^NmUGfDnNObYBc(e1^2xV z>?eo4SMRV9g*HE_QK?2xnPLK`eJ)4-pUq=`Hh(Oi@zb&S0M1i7KbpHeMI^j+-0c{c zwW|yyA2vU{T)1ySHNVu2H+7}bg8J8ZMPrm=$IoOTAT;z}nqJhiIM|;^&_Hg8rV7`{ zyGvxRT^G6u_LKCzkGqD2$2~l`^&4S5duSL_pD(nZN}3uc9%q}m4}h+YFSsxb4A!_b z5Vxkt9o9#|o0<;j?8d%rQmjhi+5bc$tCuk>hoFjuD5ArpCAC=Z_NIcF2J+Xl++G-$ zo^vm;%h@9sGw=Af8jslj*#(|XX*v+{dDv=rJDNf)ZFmDr^}YVjt31#f4%oW(VlvU! z&3`j4AN%llUuT0$ZGN?CPs)nN9fead&M2 z%TfMzBe_>S(RPAG{el>%>k2)abqM7{*wGRUm~lXB;DZkGwx1PhcDBdD}&`$Fgr3!H+`_NrM)A)bOwZEv{IyU{-C+$V-Ey<=P7Q{#79@(Vm@61mH?0?De z44dqTCIZ3*LUN?9Vh6iNSIUAK#AufK44$UZW^O1+8N9+x}(%z)eY=*)=IC_3tYeh|~+%f%5Ipj+r#$A#KBp zNdpRe8#@msvH1ZJP*JK=nfhP0nk9Wp#^5Vqs*E-@ zM;hZVU8i%X_LmnXw~Y%?8`Hx=HA>yJ!;cOJ=Tw#l4_d2CFO7RgW8{8ptq%S_guQiC zn{C!Tj2A5wC>E?O!HQGdOR?bYZUurDN^vPr972K=r??Y}YjG)1pg2WKara{1-I;mb zci!L3eDi0LJ6S7hUDr8#pS{mHY!C#y^v2N6;^3OOXs3-ONhN!0WTC1r!BUzJl{3cZ z>gvM$JY!cu^9QrDvL^%8g}Ss~;#%%Vupd0hG`YbwG4&$o3VkA6K5Y0@{XEiY2LHov ztT4KcSLw>h_&b=h**A$&^=a@9l>wxmNp$0q)gazo3>K*hvOKa*V5`b`-ie%$yk9)w zX(7FcZpU%*!-AP$chp?x9_;qVUqo%qMuy$^vn=EUyb?|U{}-T`WHu)65e86vIT`); z6K|Ys(K4KU(R*$$Mx(RuM(>4S_orF^wRDz}0T^CtY9>DZY4U3s;78`oOg_=xUAhZ+rXU*EWtsp~G5_kn?mqp?GTh;)Lsxb~7;mcK)eTM5`YsQ76fVtHzwGv(1@b$PaF)O)>*$ z#cCqeU(E1R*3E!}Z@uc3V*R$u30KiM{jkeV*l)}ZSx4B~L*Fi*JTz%M=mBn#Cl4k6 z;)~ar1VnEkfFYq!A&gHNotHV(;D?h5nh1EPY02{C$7GxurH?e$C_smn^s~wx&yz<0 z^A2#Ix=oajx=V=r`d$8J=?+A7e@Hj-Z)<08l=!=a(VY9{b`f4&_Z76iG5kiM|H|-Z zfgw^NAc6Aye;C7-n@G$ecRvwIu%Ts;OS0@KSnMvOV@Cm#0FvtF95Kw9bMrq`khrnQ z$l|7u9;WC)f)bC>OxJ*_g$ax%DpN(2VxwJajsYL{158IzieI5lzQWg0Ln}K^9!D+D zz(EGBfPNlY+mWZYgk^2mMlQpxq*lj6X7!0E2xqXn5+`AjsZ+x#@Acq?&^}K!9}Qjy zTe9ZU^QCW|ydtUY&pL||*=5@DMboUGqSjQxdHm+s^pC5_on+>+CATqjr!LU!lk%VT zI5~L&Q>-2qTq4CcV4^~Ip*@%{K*Q`fEruy7Px|-a*w1gXzZ%(fMGgO4&)4P5h^+bw z*GtCT>DjO!-@RNe%6sT6WOmb5QKg$szw_RvosiO@Hb5otT%pTy#L3@Rzn$@N0dF=$ zitdwoq_3dl*v^VtefY!=+Sv04AHvaJ>4z0ndCeN!;Nbc$?KL;Gox2}0p``2%`ZyVp zxKbpc-S{kq^yGu_`31%fJgwQgK_I~vWN`kOM}pOc?6cy^fhur&D`OWh|53w&rN4qQ zBnPN0+X^}Sa8L?FLQ8FAq5&@W0uZ-bRA18LvtL$kzO1=mz%W^>a5#aWh^u>YNIZGL z-&N!F{Em^ovxax<2yH*)62-ss28}j)DayN*V><2b<7>77C#HTU%dfHdGlM>V#yq2e z2RxFm{2wJG`0V{Kp1f`w+D=+9U^7h0B45FLNRQ`ZLm`159kho2)$428gI;F}AG4IM z=%ApkFVu7)U$8PejxFC2g64Tlw;`A#>Jh-tS+2w9ClW0xZM9bSngk5sZ)X} z1F%mao`5BF0%*nsQ}T}uKN{e|Qe=N;Pq^Tf?@ zu!QQQP?Ty~K6|36fSfGxj@{e&tj+#pyIU*LkByXpg=uqdyYF-@Mr%yJn>j#ZWb&AG zx)3{Uzy@&`uTY5ag6Q*Sanf5C5?z{mGg*oVVGTh-kz9SC{2sThcS@J12th@uBuo0Z z-X`^?(rpc;vY4pu?P9$wp@-*jie!*7rKNoAQt(*VD@yPLOn*jIF=9x`XkAzdTN|gk zqO^B3Yap$YYu&1@7;v`bw)&|fD-gK#9(GSBRclmfobtZ*Voc6PRPB<`O+-{}`@hH{ zwb9NJs#NNY`DxCMbMlTIPvD%rwOk+RBzkm?Bp;?8sEsuL+$y{60;SX0Y9`I_GX;Nv zB`ykFQEw>ae-l;-;XQCSEeI^jhei&#i0zh4AB7+y4L)WPK07qW>ToZJXqV4FWP3*Q zDHoQKtcMkXA`*fUqAoJ4g^S)u9TpbOjdVzcs8yIYpj2w8JLHvWllJw-gXrWuEzms6 z83(GWg7_v4_l^i-uagMF!+oZM?o1M&G0iQhl8?A?n0vw{e%dW<`+~HyS46Z+hc1SU1B@zR z9t3%;$uKhlU6?sZ3w~2wq)JNu<@STX1CYzDd{Q|`)JiuLZBK7NO_60!k$#4#BOr?K zAP~>F9xp)KUA9KZsneSsGb(uZEjvY@?qblehDxW3-}QX|{Y+f#LF^MTlK*=jPDAl(+ut0{zdm_~)xdCMO9DSwDi+hW_JSBVM!~i$@OO z;oPF4Wg1p2oGL2HEZo_Zm4sqFxiBkDC7yh*0aA^~?CQ@N?7AAK6U2;~HY_D>v+^9) zk!+Z=xD)(45OHlJI|(PdVnnF{sdi_XrR_cRaXk{Q7d7y)3Bcvr!WW6_AS!tiB zPdX$%2E!DA1l1114GZR2&7WbLeZ*p$2)0WI$*0hq%40Aro&N5J+q(Pd*AMwz4{Gov z87}5eH+UE)PSeq=nOT+!0&@nK&e@64w$@AoeOhcpJ48}Bzw=Ck1w35xV&MZpcyZp0 z;E=po#_ej#lag1D!fST;&T-gT<=BM6UAc857C*XvXBzDO+56deL?Ua0hl6I?;fdw` zsHT!l%&%zop|i@j#y4K&VdxcjQ74Zb*Q%^nDktnjt@TrE(Du+OZ-!vzs55~u{Zz+3 z@Ws><_I}xGy3oVSMH5opN?HFdEWJ7cXJ2ZY+Q`r5^qR%=V*FS>7HDLq2WO$)Zo~dE zwN_oik968Iy-XF$dEe`Fb-c(PH)H9C@IVz06`#?(42(dchoW5Jcfj=rs||o2G`0iH zl8iMf3>u!7TLnZ7=^fe4k3}2~x;aj4c1I4nTs+y`im5epQs{m3BVL-ERd@LY?;1@$ zm&GJ6R~N0m^0}Ndl!zne4`uqS9vy>+ya8$RqE1_tH0HcoXe73tPUc@JIC1WAtXzzp z&uXJdTbvP<-kw&4Ey^liBIPd zstmOH+gbONS9G^y-Dml^|8KteKi4ISi9UFDHC2J&uge68H!|u4{T2E(SRer>tyShw z3EZG7UlRp*tC(27ZH>HP&IcixM-#4au(Ub?uoTF%o4F|{Xyc_R8ETIF zHh@LrB^xkLZj~8n4`7ojTdwALi_5CuG%0z!s_A#ii7J&<}ykX^kMAzzviwu4F$W!>o@{s3RC(l(p z<;2_Cj<0>IFr-Bn>0FAaBGCJ@q7%`Xuqgsc%Cx+_w7wFr`O21&SE^~!#WHc_l&oRe zxD-}qBv}2^)G2)TssSPt>jbx|JstEW@FeX<_)?EhZbV(DS#9K=lqr!Cdq;tsTvZQVNTyTO-Fk)G2?- zC5U}`j<)r}yu*|FCrh7-N~d^$INZ`$-~~!k!{#eJ4*iC_Y*A~96fXSD1*wq-8`kjl zQ48X7hAz*ektfm)MACZS(5)tNUI3}&4UkIuosO5@^Yvnf z)$CN&y`_mv%{=UIKM(4E`6UETG$6+dRZiAKD|q*|dB0~znv)qWnv{=G8fO=>c@S?K zwpwO6lEK`3+sSd$5ham_F}tH;9L@*SNK^`t`Y&3rI5uU7}MjYXjrMi|wN$i_jTk0&;a5NSwjg-BE13A^4 zKwrjB7}En9IP3P>3h8h;mJByzV?ZDbl>+)$u=3#p-Uh7Eiire|=#yGXWV8tKpA^Xw zZvKwhI9pR6FH}j$U+x#TlhPT0tIyd<_gd%LmEFfUs^jJ#QYuzCVk5`&Smd_Pw8;gr z*r$4Jv=q~ScAv2z-CCiHpORDG5>+?}zJ3z_Ccd%Yz7h!>@=e$3$X9=({7=a{0P+N$!- zn9beEe>|z0Z1q!-9%R>)U{pF`fcOl;nKKt=(+rT_0w7s}OIcC^isD1>5#~A#H%Ep( z+1<0d((@nkFzr=WrT4AlcyF@~)|_yWnc=ic&L2u`l}S`*`5zW)D+=v|S>M=~19T6%S{s=f$J#29Lv}#nw!H+hV zhN;sI@m8}B)4o6c{(~M9L!Vwg^!oWhbED!#)E9&3O98WQ^Y2?syA9mY&uuEYn#|B6 z5l?wk3}`IB`Doi!pTMs&J(V9Iv@rX0+au*X#R6@C4zXk%vEZ?r;&=1k2aq1_Ho4H= zp`3dDz}rH?)z;A)A}6ogVLgdPTCv*2ck^qZl8}7j6lNdq0~XQxHOhtdD-l5+FE4ck zq%h^wG0Frw{sS)K-i5F<0i%v0w5`Y>-=4tX4X-j@Yx;oR_rnq+H@Do5^d7x|ls`@~KN@X1%53`P3><`2bfpkV^10tyzZMSgfybFhWp+_fT)pX%`G>F4KH5 zbWqrqo2fj|d*Q{vxPeywujD$h^g9O&5nFP!3Zg=d0T%~mOFqu4zyD1dp~v80TK3(P zF1i_`1It>bi$$%*2y_-{5!XL?{1=k?U+VJLO#*1h>r7y{`*016@2{tfG|}L6EEEs% z@y$*Olp%0-(kKX4N@k{$=(Hx=Q}X=ilEj_okCjxEbBv1L=d#JD3~9V%2OAdT+ZV@o zmOwaSz|QsqY6>|CE`rkhF||rOZGl;Rcy!aal^EIolWpqkK^(rOKoAO(#+4gMvmlUV$+ZhGAa0=!OWFQ zAuQy&(UtgwS1OhwD%`Hx3WVEF(5rq84SBf_eFArL;7^urQ&S6Ovo?lQvStVvY-b@( zMWT#FS9G6!z^mhB_?03!-|={O9YJhy=08gWZ;X4jT4q6nGh-0=>ynie>A+Vjq2ZK| z(&<sy=7U&3EMB$ueR^xw$Qhc6e7rS`jYMfjecdL}9Q2g^ z0;k{^?_RRISSblA`0NdpQ-DOv*-qE(O^kqU>8dExIz0*h*XnmzoJ~dNnuW_k(T}tfrPQmi=F&% ze0CHS*vubjihrS7hz+0q?c)8kiya{qzZGu29*?UrqxB=wux~MTXQ=^IB=(@=TX(!L z)<-|rBpbn=IM;&lL_uxA&<%dk$OjeIJ}oWhEK1fKxlY3YPt#PA)|WW%%Eu#+(ulK} zw|9&ShrbP7=JA|+rrhV_-QDD`S{8Z{cySJ1EnTl>AItuAx_Go~dP97Yld%jg069Nm5})qTbw!FI(zeye`S&~mY%P?wBregdByP9%*A@G~s#6 zLobXn=;!5QCSgW!*wBVDBeZwi3WWCh^A}2DX9fpZbbRtLy+#7WvG8;CWc(Bp2uqM# zAu*@4B(R+c&+mtPrmm5D4Do_?;Lukv2P2}fmu&TqRWYahGM)Qk3y-$X-hd47ZA>qDH9sJh zL5h@9#B6l7VhFflIV)uf;L9Mj8c6rsIH|R-{USTmU2>p~>%==yHQc6maVhTK?co}- zk+XCXAM@LP?8Om;H8iT`{Lc+Z`_X2?$xOCVX1-(wO%Gw)H?Ic2c#o{vE2*;J+j>w|# zvzvMcMx#Qa_51n&o$wcJ*g0@Vx(Uw!@E317L~ zz)EptTM6c8x2EXjv^U{pv1v|y;6t!(L79Kb0O_TmuH#cvmhO@Ki>**tob_YD0WH-n2BUA8Ci3XXYQ2~8Od zKS*e9#pvov@jmM5?)rMycmLru>qg-}#QqAUj^;aWc-!?4@DtXS9pkD@FN^=qv>5>k z(HU*^KNP}ICNP*m(`vfXFg!!Vvxro$pi9Sr5Byl;GEYrGfxqj$76hvTj|s*DG``y8 zQ4gLqL=VAP%S%jj1qNeCMLjZl09gh+jMdM~hp=F-=j9eEwi=k->61|_=r$;ZLtfW9 z8sg-(^?jaE+$x8*C%mSLsD!wzE8|sA2f%xa>kG3qgI{&qdKy%axz=u$62Ept;;pNZ zffKji7_oO~?B~x6V9e>6!lS9rr1RTk$2sS1?^lb9plL5pmcPZrvb8OsN@0#r5k_~D zgxlTLD+o^YnD?%TCRE$a`GqWdH*3Pj>+pk5MjX%8)7+lp(N$`(+WVgg3p?s6R+f$W z@n#m3PUSFDN0ivpK2;DBH!b&8-#_$g89j0NcEYv#j#<`S-(iWHK1X;Uokv7-yX?;mS5v+zS8IDT3V76)vsd$$>%~Z4zQ+u z-vfAp1{aP2beelV2_%o0S7B9Kb;#HX)(?Eij+e|q7quV$)DcBuF001r;cYD{G;=O& zhqHw;jj=Ab{d>5_#za8h+`xxfpsFdWvZG2N)l);p|Z&eW@otYFo@Z!B zw_k15?t4t3PU}KbkRNa9j^8e2G_+}v{!2yapAby85Kv0x?^Bo}{>M|__%U|1AOo;x z&z{ZH_z38fo0R{Q!37q~u0iaT3n%)md6=!-<>h#ai8%?FkK&KPQ4p(`h&WOr?ckC% zBaQ+4fftM)O&AmGAqGv+uSUEEpIf8g#*=cgH1P<%f%+QdN7}0+hBx2qvfBa`SKQXJ zzTc!)A@nfQcZ_cs7GaO-6&~?&Z4N|3%U1{)D`*eX|&DSHr?s94A78EU^G%Oaro`$c zK!@Sa7yAUBHmBiiTFqLJLEoyvY%O8&(btpts7Ra@9K~i;IS&`&`FO>d$MbHSve7N zLPevmoi52T7ca3@Y)v{pdr09RlL*x&d2%hK?*kM#!ONN{ypGfZnBW1{LJ_?v>CUy1m69lX^JE^D8YR?|DI z&&;)^sWV$j(@{Y7en$P?Ol}cBWd6H{{L$$-BbC)J-YltKZvzDW1E*Cc?ziH)y<9t- zu5?Cru9vQh-?`2NTqXZ^TKli@SduA^NBPbCRJmTeznD(BK|aH9jqPZz7DtF(DJg4I z&(q^sHlAWGSHw$3^iRRxtTkn#VBWc`S-e+2il7_%#dcxAhQ^4nOC_`NfCLW7|U z`P- z&Na0&f3oIU>}U{~74O!I-w&{~fPDiIcx3jX+$@c$G)X(|H<2WoP6X1mL%En+tcek& z+8&?!%f>@#m|8~PtTgm1n)4fk$CZA!sNhws(zeZz)98=(W16e~xaISFTAvQ1Vc-G) z8RqS4X0_PJ6>%;_-~2=G!50VsNRM$HBF)X87KA?a{+?!sj% zj}+|qhZ&)^P>Uzqn4Z`4{n5Y1-5?nvm%HJ1sdd6TvqyY37515;5vw`UlI2Ma z1pihX`yYncaf9(H9wGMXACX@&oEWIieEIFMQ{}oQ3!O#EC=_ihdZBAhOt1#Qkt23 zWo=5uQUWl@okLeh!>3Q5inNNxpOEUli-K9C(wF9i(W{N;s~BkmAG2p_K=YUfPen3j z2JbX1GAv`2yV4Vw3pAZ(FDQedZ?fjW=m>F8j3Ky;RY;ql?a3S!+=<2aH#dI`v57X! z`BPiY&lsZ|q7lt*Q};p!Mg0aqiFgP3Ec{qdyh7-g)R}ow_t(4di259cuYNK(Lv58_ z$F7To4PS*;Vz#Q9IMX@B$yCE8_d+etwcRS_R8KwMJaq=OP5oV-dLTyV>`o1he09jb zYp>V@e?h4Oghda9cuY7wFl-|dU?LgHl1zhc1G$*`8Ek1tGzIwHE{loQ!90+o)iYwt zMKuh8SC2p*<;J}=1&K!<(ER40ojvjsZTzjC z&YqrGZNi#O59)|~$XZKZnrN*|tLvJaxi`NK2J11lSmH-_#7}BP0C$iaUdIgWe4|fhf*vsreZ!uI2xK0k2uVQs5`?lSMZPcf;7&dwc1Y0mBs=u^$u6_^- zC9`{;-`%58jw^7;8Ie>oF6S{r_pK$U`Al85_dB|&!m zc=*fWK;<<=ZDu2agazxkVuyxICL!%n0wv7|?7+B^t`YDHl-w*=alv=>w`e}$_O|p3OM~#bT@Lquo&unz8~s(4*d^Qj7+Yh`A8PN z-|Xy)uqihN_R{K&iq_=u=OO=p^&EGg)}V8a|5xdP1`;^VY(22DV!k_5jb5r-sl)O~ zI03QBVm)TWAKnIta_&Mu_YQyFlxT(z@dmI*W{mCO!peH3zrcWb!4L%Fwje92_Kz8| zo*?KSR|KBU4=BL(rGjlNX)pu@}0D zvf0gNCU_6+RnwfOxhIcqOu}vp=tcPWLNyx8C|tz`N77HA{H4G6IWCWFr^b%C>kI2g z-%YsZW9lFO5=A;Pb|1H8Do#2vi1!JxEY=X)iJY#x>(>){(TZzSmNMu^b$Wyo0NT3< zv@@^yWi~qY{~}bzPrRv96|d&hiV)*>7{X$d{4C}f%-6pX>z98eJNNwJHH^<11b%{+ zQ{{oCpt?lRfpaTez}a2p@>RxgMz+l{*Br0ewK)=6_s~kQBMHyPWj=!L%a@6I%Y)fg zJ+W4A+2b7}w_T%wD#%O}gZ|kGHOgfQnU(64NtZh!96|3h?oXUJmHMiGmp&?8B2X({ z`^@-LWTX&QUlF6dDl1Nq6TKvN9Tkby^VpyxVl~&#TA+d<`)XhWe~UWOcmPa+PXr}g zraN7384hY^;fW>>w5W*3nB5AvBEP&o2hYij2i)`lySx(rLv2f5CHpt1J?M9zL}o+K zcY*eZ8$f#bFZ5|hIdJ3qnDsYvyP?)row|VSZk);VvH7L;PStrkunvHb{vJ|0j!Ddf zSqa5|Utd@M$=3^2s33kPEs(hDDh4AHlXkE@W1@_z>Z4HTL;ZPKVT1-tz6nvbMrAR$ z=lg6#-Zsh;o7V0LQ;%F|3{GL}r*3@&GZjL%$w3MEJ)#;K{*(z5RU|{lgC$twTly1I zs<7>VltC)oD%QtI<0Wm*VN{kI@+`uaS4g!iM+99j&$@uN?*}{9PoRmp#Ywt+&+Bs5b$>h%FYGY^7CjW+K-80>nIFc*#F+b9ygV`o z`DVJ0oUt_659r__g;{jK-*i|@GQ#?)afV%8lSbVidWa$7L5cy6T+u-jJ8btR{%3VA z8Gq!#PZ+a*)ImX`R$4YkMHqhb3x5qmZ0w++KZFU+$E(h78y>)PDcGaWk^fmDNJTYF z8KTEDxZl=5SWg$gR3YMx0y0_1hFQI9;p68D+mOrb3Yn+v5IDc5G0}I=D^{M31!M)u zIf6uMUQI0ALV{hNTiJ!HZPnF|8N+HU2Q_@$ZLT*QI7y(U@wMNZ8gCgnzV_0AJY-!z zpAwsRW_CpVx^S5iL^9;mP8&uMj1X)dO_dBQ>DwkTEbwD$>JXzjssuXYt#&?7wBGqk z&THw{g!Av9zNjJIPNbo=%SZ zD@*=U`i+m4j32f99l=C|PsrqeBDrttk9BT(@9`g^SC~-@d3T+cMi-y z>{F8lYLX`7gS3&l-^J-R&R)|fEn zdH;#2O?5xzz^xr$ErH)IKInpCsN0wwQSWV;FyZc~>6`u_La_Su8`y5e^o2!N0s#f3 zY53$8Uy2c51XI0uY~hqx7?Z9_Xz90t8KdaL0SS zKTeTy0StZgbt*M?mZ`8U9p39O7yw?90XG9>XBzuVSLxSr`Fok}@gEk^39z1w(YqA>l zb*)d`_ayDg+HI9T?>`tZh=@0T<_%r_Qp=*FBW&FMDKvd2SsyJo8j8Ca8QdoP&fn%D zV`N}?*-Q=>8E_#G@G0zBFjQbKfrsqxM_W%F!z(aLp|INXhp^Fofk1Hx@nAu|hC+V7 z#z$ygq76^Ktve)sc%}{}&Z017tgBD~x2~lh3gMr!yl&Y-*Yxu)QGsX=Al>s~w-vsP zmp9Rsmxk&(g}f}>uT+7>&|$b6#|G^ch4^PM4Egu`G@ep_>2R7tW;PiVTfD1xmSy+e zqTD1-qSRIPLGkZEzQtH#hi6y(P)2yfW8P`)Tg#l55`A@;Hkxbe!#{?siD zy@PlZSG?DAK4fH_n7dw~3X@Z-IaVqu16mFS(OlhPuRj6qqMIL>nXvqfZ z$>#3o@Sqz?lJhrS7*G}TVqPqbL@YK!f`q!tIwK{oh?b+jflqke7(Jz(T{fo!+Pa$p^%i zA$jF|hqX`hmcfbnM5I0BtF1)Ze@^)?(K6EC2rW_bltoysHSYaTgKxwSym(pNWUfRV zLiSl(UZ4DN6UAKk=4bQUF9-K+{}P02u*(c;aeX`wdgl@zS-A^=9Zg!i)Nzu8X|#qu z1G&Go2Mz1@@9(Gv5jYiaAr@U(gz)b zmn{DqGP5l*%KkZ3DKa3J!AMM8OygW}s2T$0!}pLZnqNJcgvcnA{)DU`EMGHhVSR}{ zHU2@i<4QAFPa0l(TC&6XWcC6y|7(=3NrH7)m)M;A_S!t|U`@`5T)>O=w;189wMsk! zDDA5zXaQ#5Y~_EdgW8aO8F0{2D~X|D{k$dL)NGh2;+K9I7;^N(UpJ~s_oK{2U$oWC zmq8*=lLdkaOq1dE_pZ?+z!X-%rEJJwNC58FfLm9`htZH$O)Z7o-ZfW=cwo=tHFLct z9NvWR2Jc$r=@;tA+PRS?u0P;1xJFZ1R%n59yMEzc*2gj;+1BABP)fzx#(UA$`y)bN zQasRa%5mmLJz*)bRQsN$u!5t>y;?l7Mli;*x5jJihIWKXjzOWWIl#Jq(?BxN0?NnO zuS1Q#2F^Az)gM6K(b6pvHXlCpKD-vgn8n1HZ9=si)Cz`fn}B}d{Q&nT9W*}J&v?r? z*QK#^!+1=0=kgz__XYsn*qcl`#q1TZ+|)8gl)G0Xh1Y-{Ow<8 z0L9zeyUPEEaG7B<8Bpk#pXKlE>*J+W0|jaVoeBNL-KN3weH zH2k$fgcdkmHrM)D;|pRN1V%~TM5^ulNhU=4%n$5(T!5*s0)vSn$U&35oeVloHAbxF zr>ipH_s7d7c%=}m7-EAfiu&?bGkUme^HZZ+7`h(Il;wpFJ>k@f0|KP4&-@sDwj8%; zSU8UOVQwD3b-!OwMwGWz&P81`C(!Q*+WW#^v;1}w{aMOjGy#n^jgw;Pn%edN_q!D{ z%ofq~@Dax&s6mPclW~2iLs6fE&_sOc4o*a=Per4>Xd@H67L4|KD!~I)QMQbH0B(A% ziuNbl4=cfkWpG@5(^uJ&H7aO=#`)eBI++2WVq?s+$f8rIQR%JM+Xd7>tn ze6(Le2R;THR*a_NJ2YTvJnnGm@;_=*Z+#;H!Z+(!ddOJ0_|c!RZq7&jvv)lIL^1(` z|95I~o3lt+BF15UP5TLQuB%?WB9(=>?7REyU+qP&W;Es`!4BDQZZ#x9xAe z^SeYJu|=IL*ImUQVF`D&%r-t+0$ycX?>GP&uC3)VC=|QFO1Sp;o?8LtXp?J|@mM*~ zd7_0`o8MQAvdBkrIF)6@(+3Hy>I%OwAzVZyT>KE8O<}UU1?kzekn${MQrkFa0~KHI z8;(^zr)>EbPMvLxt#yALAa`pU!0-B2({mt1^n-M|ne) zpW`2nwrp(-o>ctb-agzsqS3>Kb=mdxy7|#OXAuKsnwpxB2CGiyIJ&7agV5XNx0Xfi zbSgijfYsdj2I_W&=E%~xk82%gT|YIo-|+0P32DaxI*7W)F2YKgy+5qD0!Z3K*+#`h z-G+nNEgJZQyR}wBu4)+TX)5e(JS#eMY&&oCaZ8G|E*q@#;n-ypuN%w5C`$bwVrqj2 zdp+JW=hP&V4*lyZXWd`iLyO5IJvbCwVG-OsM7 zA9Chbg<6^_gOXr!601G6c(G)DHATuILo8}^R`t4)ScjVaEA*Kay3YAlLQC6iS&uOq z+Ne=&4&hIN2HrS*3${m1XM!9Qed_0mMP?9U>$D$sR;`a!mmvel$0kFpC^v!R39Hu% zchrzN*Ri?@6s$D#%eP)Ynk{es1Jd4r!&y$%3Cz>$b@=i(9 ztlva=8XTWY-ond@F;pu?Pc=tFcR~m9Y0TXEKv9lcidv z6m%fX@nQs|SiI^0Zi&z;0oFfjjk=5M#wEQL@`rTRWoYabl)+cOxK_7&`xwCT=|y-$ z`8_cx!Jm8Irp!`BsB-M4y;Y!(b(T*1yfQG{M)d%!d#pRYQ}$kOak{gdszzlwhS;)} z;`vt9&e&SPQf+dgh|K~Muqwa2@hk;S zr+Lj|^eqkMwgN_il-k3F5g-p(&Da$7zohb1>o5o)Jik8ZyEsw*IZ_T7_K$qZAV7v_DfQpZ1iW{dzr%<@S zf~MdKb(ca5aD9gNUmzDFnOyR%^doClh6C47WAVNl2jbKKv|NuV$;=q#o{T3TZ_rRPqa|8w z2&O8GqX zZBQS)cr#*(y0XWN{L zA2klz0uhGbW|QEiAVn&;f7?ngGkKp1t3gg!i8vNZT>xJRotYAg6>DO)^DTpBSdeB? zei9owY73O2fnxq*J|g5)=1-xm$_V2P63UGS{K6~!3H7_#BAfXWd1@U?}!PI{zPO$WutMvR)^mV5h~H;){1#^|Yn7 z6Z&u7Qnk0}L4|}1;6jk9L?c@3yME$LEfo2-r+rp#VE3tF|lMn|%muOt-PZ)$} z1#^iA0GMFs)E{d601umQs=6?%SaI9%sor`w$Pt-Ozmq|xVrC-A<2KB>n#|A0rwX!OXqdnpn;pX z`=GDDFoyq?dGt)sVDB4Sd=u*y9TieOO4l=3K!|O|#eClFco-5h21x8I!`Hz~<#<6H zjP#wxZ&fP3I=mfuE(dm>|Gsed%T^}d5f@(emuEd&6Z;UIz~m@O0SPo$yb6FnRJ?+* zAlD)JPY}N=@P@eJ>nA9vH~V_ecD@jn!1Hj?x0D#+#;H@=*92n|t~3~JmD}6jwK%cW z3K?*V-s_52jB5kt^g6Jl$0SE&`IvrdLf}p_EpvaYs&YyGT+&Vn$pM0XCzNUIxQifm zR3*QY6o{_u>e=f+Ng#%Hnr?Tqt((N*EIcxq*s9X^wCEKkFYI*)J^amC9SfmItVPLB zomdG7eEoK-m_;cW!i<2}v$3WoA3MMwmSW6r+Ge~T+L+VS--7E(BKRs=%nVH;K5(J zhn2K+g@Qx*@F|iaXKXGHJWPGUPhH}Jq35D=-y*6!y&OsPRNM!ulH?Mm0#{HNcVzDn zD^y%1fsbmZy^-cop7Amxbdns*Pot>AswfR_(yAx@6NyzHq>-xH(k1Y7taMt+)6%K7 zgpEfWbb^}c>MrP&?yWSX-ITL!KrU=1-RLRum3_0T!&Q;>X6^^WdKvR!!IS9C3JJP2 z6Tih%m<=C71hpl?{y@*X3s%S!24gud1#eugeKg;sg#I5}Qqe^q-1OZa6YALCOsGhx z80l+$U=*Sb&v#_GB49yHpuhei+~W6KH6Dm$J>OTlA_`fqBUI^c^Etu)244aM((DS` zt9~&OC_%O55s*5!KK_;POwnGN74L6(y5pD#$n@(gP2Y8z*>N;aHj`c{DRdfb)3%A8 zHM4Ug=X*cd71=}hU}grsA&)YG zSW(JzflJL0XP`={=eA4Y)$b_N_h*}*_CzAadH)>5$UoU1CIeLR|4{?&r1S_w*Lrvf ziTAUt3D>xvd~8Jy3FEU@d+N|+L2t@!*1W=!ZFuZJ;i0`G4X)!#`U> zAImA$0(}9~4t-Yo2i}Aua@&W5Uf5+Q%i-83q&roZ*NZQ{7P3)HU^FD4uh&s?MB|p-+!PTf9xc&A-L9VoT}3hVM97WAT!o+QErRt#xTnkq;-#5vPMB zN6&(i;;KzqxszOl)GgSO0iTGjpB+&|Im9UjW)B+G*I^zrNP-c>-{87P74dFbT<1Gb`WU1;P6D%ag80bdG)*=C95n1?3G@7Jv?8uT-)~c+EHJz_9(AVP zq9GhSZ6CMdaW6hIf;VHF)-mV(7?Vjdhm2kq$E}NM6`!Q@ zfI1lwTW`Q@Hns(U?yy!CtyZ3GDS{0Et7`aBRbHvC=H2E&;E1Of?>ok^4;>50^9PY& z#-XWJwGRZ&VZ@e0wdYDnXBR#$;y*hiHlOrkV&`I9Jy+*8tv8b}3lH8^NAK+!x$)#@ zCgr+ajlz!Xc_kuwKJ8DiwRGM3$|E24FO*&q+lU73O9x5;T>!NaBYPvTg!X*t&T)KO z!#R|Av(9R0cB218P*67WVhk9~OTu}!@J8`?-TFGmnlBi$$z0-lF8^rq_Rn#|K*IL5 zn>6PCN7q-zRkdzkOP92SbVy1{N|zwr-O^psv1tUQk!}R(?(UFoHr?IbybI4c_x0ZU zzu)!;-0t7A#u{_ZF~^(_yZ=^=qxw!esU!HM{;PJ`ZyhU>Xhf#;?Qh zQco6-==KMjwC|xVTV|8&txY6pNg>y4o<#yv#@Zyx%z7eeHuhktcZJx7gFBtVmi-}I z;!ZPQALT=)K*c@gu?84FFdKDF$j77v*SjKqG=6n=tnlf>p2%fVisV_&P;EA1i@jzH z!#i_6*k3-k2}217Fuj}*3Kco;ne2~41#7{=xff4wf83$wT_J$AWG;k}%5S&24a#(e zu2wSmhKL+QPs}&48aH{qs-7?n;g@7uN@tnNbTCUCbG=6d_Eod)Oh{0+A{8ryO=eo= zInk)IyA>c0qmCP?Q-gKB`m2LVP_O(@co55Z`Fzjsbw9+LNdHJJ*XRB2dr}FpW@*w) zY+z4^X&C*=z#fCQ!5K}dUkN)!9k(f9eg@}UaxqhAvopGBzmpnzArAh z2g3`=g|k3*Ka|r}78(|o&+O!ufJ>+-%*1y(8qNT8BpCttM6s#LuSBSs2zb6aP(U%9>HF=PWbJX6ny-3X%V0gLPg;bq!GLTai?dqI>B z;m=Wiih;8A9Q#Qz#m{)|;Ki0$iqD~2WFxoqBB|27rI_%#P{qemcsiHu zU2;@CL+(v{7Os7upX;$-i3!w6U!ykvYUi`c>eT@QDt)E@^p~#bUjM=OF9%z2syaJ3_@<<%kroN7w7UDT>7Hfi1qEfs!Y; z|5NTCIebRzyHwkoZQ##N9_}!+mL9*C=*_7%N7X(m&`OkVC~Rvt)bptNZhh$FUutq{ zGJA+^px9A}-q|(mwU%wxGQGlPwjdQc^-zE;x1pe@X}mDhiH$3%T#SXTXWLQ0V3@Oa zZYWe-h_QTcV0-VibcMenm%@xccx7Mb%aU{?XfbW+sApo~UUNQGPa{xC+WUC=ldsBD zuzC`7JVBi3wwD#7NoY2I{Xx@O+u!yrsIBT2N1{M?WZ@iANgkns?&NK<92tFFf9|xo1l>jeGq7ppjpAbX4`t5)UHY6|M!jnupr)-? z7_frRXC7r`s5Xy`(|u_w2-pxU<4y}@5{&r4v1aNL`y01hlPUa)@f++HQDjBd%C$(Q-li2Dy*Gg3j%4c9(R3vCJwQMS>BirPY|B zKWEa#(P>0X_LawCdFPc&#VFTc2^-r%T>w*mz<)|4v$+1r{^1_y`r}`#aPCZG@FgM+ zstsqlMq4VYWnvbL7rl9J@R_1!zkEv*n;IZB*@}2)qJsb`=kbZgky$Ri^W>RuK$Xc! zOL7?hz~5Smqt}ZxvImP>c&o;{V~~zV9m&3x9eEkTRM>Qk$p6B9+4#H=9Qs**(pPwt z7#kJ|zTCkxxA!rP69iep#kl-&g*o{b50&q}Z>JFq>4*l9Hlx!?ZD7qD1i z5;q|l^()FU!9VfY*qlxQ&2?nZ68o~@058(jw1LL#^T*Ac4F_`ZczUtfG1!Mz)h!>` zMp{dp7;Ew7{iz?4;bDmKf*Ny(qiE3DMq zdS@?0yHNNz=ed8I04CT3;45(;e&yUpedVC6RtP%)M$*UVKsf@EHxrHoF%lFMp{J56 z6pf+?1zJPRwSG~GSxFK)$i8x!Y%eJ)^AEsIYdPbZ;#6KnirV2;W;?OI^hie9DaL^K z?`5Q~dvm4!6k05|>!?l9_wL|(Cd1QWesz`?+wHdNu4~H6{w+<{`4OE8#wK(~Burbr zdwnIorVOdiHta($KQl(*_CS5F_VpzA8fSco|RPMoc{7_uXrX+hhl4>e?;p2giX8%fwO3h^Oz6AFv0Za{u=Hh)cbQk z)b^zcs!_U}mSY&hI2Q%SOk~M_n;rEj5K707W+_3e#kTsP8TGEpbnxgiciD4xx$ob9 zci4vFG(VMO?HyAk=Svv z6b&NCA{1E7R2_!qNo(4dLJn7M`AYsM9DG|cH~qR$7%-UXr6np?{jyd+&V=eJ_xay5Bmq z@T*($7f;;|EjR}q6=1}!4svvOxE_8bdt<4P|5x_pjkfIqd5~J0$FOatzU!&NjUzr} z84lj*ULUw5nbTsdr=W>$ad64d2i%0HKK2>j{I}~=^8JPw&b!6@PY(NB9?!eUW(1*U z?@BZL1St3Ok7ePlU+4E}y$P(>@(~H5AIPH-pR=Clgf3QOIf~@2AZ>Sm=XPlS;+wd|1^%Q;4HZJ8q+2LW)v%(ud<)#MpvO%gUjy~)Y3XLN~k+ADaY=8ze8Glw(r?LSIa48kJ1&aVc=Ow z{ZQ3WVeXe6$y9)8hHq9HoBamt!SEA9=jYF#%CvNM?Fa96Vh<+vE|?bB@B|F-oB7Fs z>7deZkLJ1J^Ed7#Xle|Qhj4t}r)iHgOv8Pzz_K2YJB*%Yb@e0%zZ)HilSBR;~;*O&Ax#^|g;= z=rO_Nyk6cbx0IFzjfC9$bEOu`*oD7rUQDVrJAHc*OaTUqRB~z-O)@dF1;iy&*@AY7 z2&#x=CqN5cB{kU3ts(GixYbR{?uu$Z<67<2eN^Y%)L?Gq8)&ZZ=Rq}^p+F9(FgQ*I zIcJ}Is2KAV196E`HNk50R)QKO-@=O;ns`R1SQ5?K9+1ED*`T;wTk{sty4T^>pZ>P` z1c3%B>(d6T%gAz#f6z4rpewz>_8DCjn%!l`->OFOq!G2kn>OgLFX6nH?0^*-C$L_( zS0Ki}(3LpE<=P zLy&XY5GTBEPoIi7jc5hg9ZQhU0)}oH))!rYU5E40 zE?kI5UL1uz#IpaSTd~mqZd`WDYAm8m8mOGjN6p_~Wn@<_90n)dd-?g&eE>T#L?wfV zD#$%CA+<&IBGaBegSSsM(r(m~XDew=N*5mwY*wm4k6WD=NyWA8TX|+O{dKE|$$lzu zAiAw{x|{=R@x}>*!|HWOUIx!al40K6Kr-?81KzJiC{uM)S>N^2EO?>HJpqdO$0`i( z69BJ;Vfe&|ZiwSMd4Bd*KB6hm!1@Btq{vzp!zIaUW1#L+0Y7yF$F5`&>NA>-J8>QD zr7D$-`v@o)26qirn-bl^AnA$Yo4%=xQ8An_Fsh_u>P=34GOMiEnE(F%?K^YQ5iZC@ ztD21SsuGBV0pHM^<~!|m(7G75maNL}^^aOskTJRmwEg%X_Q~OY-}={pA?YdXou^6N z>xN5sDbMhQWDe!d2V4D2l=0M9&@pd6P7Z}K?v01}iBpg({Pc!(Ti}4ot0E%9f%9+r zZ{^wRcc@~c=rmKf!pp{o*DMbp2;M%n;L5iANFpY1g( z&FDYI&7>N}Yt=lVeo}?4B)cPKUA}MBZvhP8wS<>2JAP=jQ_wNnM9rRXfH5(R_Su*S z?D_*rKcr}*9*IDWA@SkHDjH%b~=uoyM233O*L4SD(-68!| z`DZ~qEXa^n#3h_?tGTeJJ1P+E%@7*&b=}f~)wynCd}FAwdGWEUIc#L%xEqinwVQgP zMpwB?zF9L!GfBv5mHO8fQM=NCywp08@FZVRHMemb{pr;^hCX7m6dd4zJhNpmb+u=2J-)@?JUgJ-9Y}Qp zEY|Y3x6_zM=r;|ALc2hqevTbrXfBEbMMdjrf0>0AC)wTPrkZMZ`=5t4&+Ot={TF^t zuh77DfK2h3*T;Bq-HF#91uuO-6;67pu-IvIo}zB#k$=&VBbE2F;_A)Z-MQj*D=#Ra z){6y;;-vhw#IzToIIz9OVMGd*XIi*O1!}7RU!nktel{Q&+M=>w>LdTZ2;{e7^=yeK zq8dRn1Z|6fYVFu13R*aobgzxZmdmj|G^bm@eCUR#%uU&_&QZJtOQ5LQ4T$sgrrG5F zCYiWugQ{C7$(wXrvoq4F-yMwuk=D5u{ul#ycbv(hRI53?Z=v-0VTE+hyj80LP2H;S z&B&gPV&*>+leZZz!Vu=%P!zqX;5~iw?vigQ94RE}FB@`f z{siogNDu+LnY|j{()DF|r2e*ZL}H8DQP#bjfE7?-?Ju;iHr0BggGqHd)fimP1>qd- z`W9v5ur=_U{Q{gRV>pI$pMU2#F-R-ZP_kC{tHY%WBo$@YpbrJ~Z)&u1 z@#c+kQa*WboV0%Z=3DXA4YoAj9IlaF0skEK`fqQmxFYmlH`M3mP~d)&uQfFKGk*Mj z`~qU=rtsx9%^Nv^QPaDO)%dz1HQV15FFur|1cEc)&g5v^2Ur(ix?B)V=D%4CyY)Sz z4at=B+HjK41(FxZ)QEy{fhb0y%{{P$)bb<`weT6#)CRTcp5OMyt+yIqx^`HT(CjP7 zw@KbDp4<{kx7fZuJ|Fz38=oFZi9BpaFMjy`CJ{n-xmbEbNQ!RYriVnp1j{gvt(UlR zl56%N#-f21G-YL{?Fzmwi(NU(mN#< zV9I{<$SNlFAQ8ujW`e`H{M0Kz#5bqh|5 zbJ{((Bn^NFCB%d)MRqbSNS)C?+jcqzjop>^kQG1Ot{(J8u~|lXB;En6P{3F@*I8Vft31n_=WwaF-ro8(QAhp8921S%%B(YB zY3!QbD^^K+)lv%(O?2X?sVhZ-r?LLL}Rf$na6By+z z%V1j&=8NlDUM6t~I8=$*;9^c!7H>TL;QrRwHHqQS%` zlBNMNyKe9Io<$~7)h(|ee|sugKbC3+=ioPas%^Y9VB+;}Zss$r0K+7Ow;Y5aRn(J3 z8}Uwms8aagc`tu$(gH2T3;%3ygO4^a!3im4n-k~)G;mFsAWesFj?_s(OnOT{Iv0@> zil{YsCH7NF0MEf}QoG9m&rqD~8rU}%Y_AmFv=sVq8A%1Jo_Kg?sQc5 z4?q93ILbdfN>%(Rw6$<|c&Dt)A--FHDz*>BNr$o;(VP-mKF&AB;|;liAT>$17wU!L zcL0lAk$@7sFN)fC!2mnW*;^g{lpYw|Fp@f|zi0#t0ZxI;Jn96!=8Q&89@esh35%T} zN}8!c+G;#Y+2Dm&PF^sTPIe6uHCrDzsu?3**Xa7`-}1SM{WH-WC_Zo{c>p92f<+@s~q2Gu#39j04+mTcR&By;oZ(~#Cu2K zzFESj8)DOkO%91vP-bw|ZTd;RrB~F4f(xI`s@W%{trfWZ;dAoVGevL6SLrWcs0APp z<^KLS0uR{(SuSlwuly}ylH)`65~t!0>|&!%cA^WoRWkt;Y}v~}H?daGNOYw%P*W(n z1Y(}n=rSmHK&||4y_pgslp^+EkcRk6#h%~}u2U&Ls$ZsFg)Py;;sVuT@)3^lu|sh( z&5K768M^Vq*NFNH6&G!7iZtl}1Lcpge!#D3wZxDMEiWodS62!35MW=Tv)Hy*Vg2Q1 z*Q%b2XQ;iuw6B+I;lV^RT9mP8hZQlYcZfX#M|-xl1wPj@>$K?O=yRGa7+Lw8IlkTQ zn`2~(G%Pm%rDIG8Mq7oCB#D3K$p*o&Li{BPalkl;N=U2)g8V{GaBlf}g6uv%&! zn_ias7aaaT2Jmsf9s<@7qJ@6CobIU^BWnz~@rGA9KR6D#QIvwn_~|Bd*7xm2V_t6# zo?WEqlk>Rf3}HIit{7E!0pX;k^tvf=YDxu8tPGm_S>>VxIR{Nzz#Nk(V#A*+z}#p^)g zh=n^ye80D^BZ_LaKCxX!+e9JvbJ8*Tqtw0Xw_{g{|EX{EnN6eU(pT6cx`~l5fiI-P zQ*-5VDR}Bpmn;gbF=4chZ?rHvtvfaUWu0K_$)F5IW9-TLygK>H-C(;!B1e>xT-`=Gs?Y^`3k^jXDe*vLF+ZzH5euST1zTMP- zvPrGfNpg7zMAi;cS;;}GvZh#)o5-~(#Jh^3JzuDs^dOw-Afk2ktT=F^HB6C7p)A(%|&3!(6@FweHW zz_y%`yX2}cgJ>Q#VCPM2#76vv)63D{-Ej<6ej}=cEWNMIW{mN|A_FI68cT%s_jYhQD$zo_GY;`xbGs$5BCIA*a}?WVNJ!@5 zA(rkP#I%FV@J9My_HIr)(4&HD{hE+&ZI^bNW~SL$jRaJhs<~lj%dCer=y*zBtYpdK z()9Ct)lWZkZh5_n6tHxurDY7Zr1rNcZp5g5uOY0vuAU0$d7OL24I#;09bYl1PoBm@ zxO%jB;)^Fi6J{RCc13*f6(evpfbnRrs;@$Y_+EW`Z385bn{uWpyQk0U29;wqC--EW z`S@VMj_f73Yw5=7O8+XC5u&63i5!&&+FyvmhVC|Sy6yVFMly9c_&;OK-{cZM2>G&i zXj804beeq{&*iM}Vz#qD!%Eo{aI2O^2^X0J6owS_!!9E7a&?aKuAwl48rA)=DiuMT$g$ui}L@vDyQIpP8 z{G!b!aZztD+@QE{q}5Fjm&GLlL@1S^-kV&-u@9{6ZvtNyoKcTfaTRM_bUw9g*UN#ZR2U(8+{|7SO;ZlnTdc-h zT=+zWJ_?3gHm-A6K68H;()!{9ks;sZ$tqRY&aMRt{}2N5L! z_I#nTHUw$u+ZJ|Y)cWJ}Ha|)p{wc-Y_`IB+wg9tz-U`&9xKKS3V{(H~*w+qt8c~$k z`@se~!d9kyuV~ia8SlqGV~ka+EcAQ5dFWs@S=6C`qCMYi#n-YC?J#T;zIK^cftBg) zvC+sE#@mY{UY5YpMz}TEPt=X5uMI}{Sr2Q~mf;NjjB`c=5C`4E$YwcwBi7mnX4deH z0$_qUwayIJ$#6PM`H)UrE%du)dr~x-@`2yYFUs;+u-5v#U$NuL}x{3XG zv!rG*={arg{8|tjgdOXbyAc+`t(tYzQd>a3zpZXLMs4Flx9@X%CSP$;Pss&bHsH|# zTJLL04cq8{0%g+M z_a>MTgdVjOU&4(<&mhd<`TsNt8QIK;Mr88trV{mm6x#~b+v^K@paf@SyivGaC%zw# z`TD8vBYrG_d5^fPb9x@fZp$X28Oc__vP1`e7UF=h_P9-4ilxUI@6m^&Mpu`|!Ith# z_d^ETxN+jkWAN7UR9v&=Efm#zp^w4Npw00wl(HkmgVRdl)yYb!0$CpE8cnRuGC#FT z22(Mww4J5X6x+%nJ}V@+S)C3%d8#+DKFVCVZ5;hwP??i1H!j0`eAuSSPNR($^f*fx zK_Q~^3>7!7H?bBvjn&L}Itl;Mbl!!fo%HoL7XQ5nduFe6Y#=I52_S`s%U7fea=}1wPL8ym@E&95w|UfvOIrZ8eGYMuogzI||p7Hh($B zo+vFVwT`oDIp1u|sIP3!G#>1r@_6HDgLw03@kz^K_c+!ip0y8B;GW8IP{~#2XUtMu=tZ&a%RSUBS4qMAjXB znmBrkqb~A$r_0^gOb!SlK{y#kF3g+Zbb=1nd_o^d_PfyS47{=m@!lIoc9NiQ@CFcm zwGq}GKlEkbNvs;>OBS`bB1ycwB$?uX?03qjJ6mzV*B2QQEqs9V|I{Dy=#WAjMu^FdMN}{^Ik%RG2?w^XBv9>&_M-tPhj>C#j7BpB%cr@GkjA`ZggsU^+U^zv|`c)ck zZfvF@AIF{hu8d-w@Ebv@0) z;s_VK(r%$QI544Oh3Zp&KT=D8OFkIjdaSx z;pP8Y%kdAv7$*tbzSZ>u>6ujnu5jR{1e)joI0blO=ao3GS4O6B&$3@3yTt?_&crIj;j!)TyZLtk;9~@IrI7hGvwWY3BPVa z%L#>PM53&Y$MDf2P0~AN{o_ZK$AXCRybEK9QSr^>Ht6h$l*mE~wqe^Tf?^5PS2n z)n#`D{VLrCB_VJUi6eN6)u&iaifUSrg0LAc!<9peY#vV8zM!Ihzqid5SX{%G>9AQm z&WW0KIs3^U5SyAsF|3M-pDpN+|J5?ac(9!4%?sr5frOS3u4kn1FU98_?zv7_RBVZ` zuzOCOReW*J`umCNRU^1a#_FxN1^K+=tK_*&RPDHau)@md^EyT}e7f;_)L7j{e=}87 z)LXCR|33=3s#kgf)v>cYIDq)$!-bQpglSWS=kjw+v29Y08hU}c1fnM5Of3hd=o_dq z@sJ?;p;U$go+ zJJ@rml)R-L#3+8fiOJTyMDCW7!9sPD9HNI^LEVy6`5l zq>N}0`c292TY-I3H-APxC%iBad!NMUkUw9FvjQ_NF6&CH8&esC1!#gvAq|2tCl8A@ zF@rXyLKXX8czqAo1qsaE5QAizQOOD6LKbdo*NQ%~V0cRE&&tT_nG8xFEsk|R$` zb&MyMPo=$$en72{z_=j#oOpNw&sUmdSJJW6vM0#quHs;bi2_?cHZ#rUU4#_AY|8U~ zXXjIKK$zuADniTd{2uNRfQ@=3hW+-qyxezZRsbQR&^&&y9^30awZPVPBhetpX@Bl( zfAJ%M*-LFN52gTz4N>gAPb9;$p$)(d)37h}3B z2jb`v{Qu(LKUwoL(0sZv0Emmq(?OEXun;*YhS3xO7d9d4)p@sS`ZYALxr`|}IT%P9_OHG7SDTHK zAI=r{N$~NQ)3+*j`9Qntb_ItY*cW$iM8RtLm{w2)=){Nqkzpi+hr(CwJxuc+>4h&$ zISGX&b*VOyi&`@y$43%1Un1FUmy#HwMJQiohm}Eq%LdD#+!!x$=j?KCXwDhuL!>er zVS8MT$mr(F5C%K6OUbz2osgch9`)$03ZRjoe8(nXxTwc>Ox<%WwSp_wT+lPF^7Mt} zYtSzdKH!fYydC^8NnkBRR?#bXHTEV|1MHVt-G^@&I%<42WU{K}>4N{Uepy>5eSPcPM+o756rSbzh{ir?1&? zTC#2n7HD3p!M?*BlRlvU1Qs5tU{m@7^D1Cw2GmVZ;cEcm|3}OPUTyS`i*`8k7kiS6 z($^itz88}vF+9XVB(D8Mw!`zR)}fuJ*=WKn=SQGyU1Sr5|JH+_kz@y`ep}a=-f^>;&|lNaRlYdD~rjOT3~G`mPuBvygj))RsBbExZSr^OTl~Vezyi!PjhjN zFHuuGWvXOc=j%(J7M;uPcL>?Im+YuM#hY*Lo16}0Z~ZW~pXPBcg4w;k6K+;l2{4!( z97z`Ut(>%pbp*7I_%)8+#Ts+Q%bHM|2yNDpZ-eeKr%>gQf|$mlCBL#bHSx#`d|CQ3 zStg~-j4{8UFbYwF5m~TK@C|~voXIec82853@?<_=T6boyD3)^8AWB=0$gIE_C_n9) z3QU2-Wv?G~fA!BhI@p$X;J$LVqdrYv^5$kbqJCFK5^sV;LgTIF^A-P{f2ow7&Jr!% z(v9Wkm-J%PuS6MQJ4ZJkwnGmDbq%Q$R2X^21By%{&^v5Js_AO-C}k&e)xSq8>&s(B z^n-gid{tJIl(iLLJb+vyGPpngF#ouVkP5!HUdHk2=mSKFcBY9DEcXzu$Wr?N0tfg} z3fJP$QnY7?Nkp`@Z#_Z=xg!-VBE>w?z2xzA{jleXT}#tClueN1!f=G+i)qYWlT&4x zIj6~KN?qoQv%O`l^Tu}l9s;xbTM)YE*#^bn#+&~SjlWP5&kH&9mEpr~&~&VaAX$Ql z$9M%v7y*r0==@SMRD!Io=luM2f{DOf#m^sX?}PtGFkzu+_1>52J8S$);PD{?xZ;?5 z!3_L@Cq>Q()S@!j`h9_oNm07vdp!ykbd3=9geN)5#e)DZ?5<8|1A`miA?*qBY_`tR zna!iFW%E_4!cPaHXAXK#lP(0RKfY&IM@}V7V{1TpA_ zFQhS}`$>y$615*zy4;|J$lo-anCg}wK&u>wT&#vX+6_MS9!fOvYGr#2O<}O@N%q2` zl}PydD&Sk~w2zE4eXKFN-oY{D=b5h$sCp+aanxA?ypG^6vz;?__W~D^+x6C&>MyKt zN8J$Bo3{;e%qQsFGF~T=kgm95(84eF8szxye}8v|FV2fIR&cte_hJn4R+W3k(GKt7 zt<1ec$wq_^1!~Y}^@6vTn!rnU+l6+h$*YGwRJ-juM(!~2exsAZ8g1VZ%y80Z%-$_u z7WR>}S8`XFLGFvLA0Kx?l9b`ir&vsfwN2|c$shlqh2I}5#7G`OZQ8sh3nZFJ&OpuK zz3xwC+c)+rLNEERnb1%k`Ky&G4vAhZmE48+Lmo^=l}}cTGnV z_l-QHFo;;D6M=_9B_$d?Fc6Id$*@+<1+kJzbFw~-^)AU`?Vu7*jHn`#jYYrfxodpHic|JPVafun+RE5tYHLG4%v(7{~-D z?4+cN`}rwYD*(GPeD2BC2_7y8<&)g`4FouKL}$NKn3K$jEE~DCEf}BWt7qnnj9qAA zSMl%~jU2L1#w5{Y(@b|O9^>_U)~@g*k($8b9^^{PX}v@A5x9`Mw(DiFme7Y`(BO|a zw8QuQNROukwY*S33(rhbj|Aa|!?C6j@9WC`{CV4_>E_V=eqD8pAiL?5FFKc}QJeM{ z|JM8aoi#w%+#r7Axt3GM!S?JjVmfTh%4JiSet;Ybz>(&nx~-pXy>5AWYtBm~^#=<6 z_~?^>4FDpC7$P<8Z@Tb#PcK(syevUJtTb+$T`Ua0Qd5$DCrV(xw9Aa^@~~%jO-`H= zDfxxxk~+5ehS7L^o`(ho5&bs^ii;9^0PorP#Rchi8RaupEq5h>4R58SLi1Q;pov1bthhPRjLyzD#+aPSC_S^UF;9Q8B=MtR$JvBSzWgJ zMFh3LeVa#;z7)iJzur!%#d6*HYBDHk!rP~`b(E6u0o_MXI9+vmqzLKTx75l$%`aV- z6{QNvJ{OTJqecuLlqmJu@toay93ra6OFy8DeI7j^YE2tM)&J>%dp8)w{DUxmTT$%S zDjwTgH+u$A9}JkNw>$)OGbd2xZNnLTNf!Ocy?h=UswV?q7g;wL=7<~cw;Jy#B8s<& z*IXgrK%nj>UaVR<7&lI%dM?k5#f3EEe%WL}E1;b`E$Qq9YT~>*ntM!1TIj0Ks26 zoedk>up?Ha7n+W6q>_a52f`#>0c6$20dv!U@X-eb*r|HlFiFEAy$4f;^d?Q=es;p( zJ4ZFRUp(@zbL;!+v?J^J={v90vaQFxWTqlWK{c%qn%t`>i5SAO}+J0{&vlV>h-TLbx#D85cBa36@f{NMV(3m9VoK(~A?uth`j2c^q}c|V-?M?4NW_p4`; zIjrGN33I!Yl3CcHBPwa6%j4I-J&@aXE8ZiE>la*b7)bU;Y{^%UoFpjtyH^r9YRvn) zRZ^qwl&`12Nj}1p3mmJ)(FFRUW(q7g0dq59Pp~ycU!+lmF2bU0$ekg!4_WOCLuJCj z7f}PI!BL4dOiL$A5o=35cK#1+{l;QppN>aVfP`P-38TL0!auG=s8n6CbqdB3;tjpe zV|=ULN8zzoBkQo0#*1HuMk?&a8YxV}*l{`&&g^mRf|%p?KImSO)TcmkQeUm4S0mpI ziZT6At(LD&mp&mu94HmYfB?^U3v4Ztkl=$e+x8iNN@IhVKS;a8t*27eeF&?h%h%oJ zy;E|Gz+p77KY|YMOLfl@F^Mp5=S|S-Z^tQ)0{-it|DAm^VLtc6{JDn3|9JiYB_vBS z2=2m7Lk7yPB7RT8_I$9=zdv;Tt{L(6FFE@MB+v|XED;5K4mPoDpVbwzERD-Lm+J)m zEI~m*Qmm#C$Q#fYb~y+p8vHxq@a0?p!1kquL*y+a%gBj|@h6_Y--sovS@ zFeyC55rf2*?(g5E=>HINBK2GkAAvm-Bl9Gt+Y%7mBh>79^-&C3v|awC=0QX^WoMVg z=qp~#qM{RGEpBqK8 z;jmXif1WxfeC<|B(7Iy_bYZ(M*<|<2r+zVg?XxcPw7|V*u{ZwguR{++TT3#+)CbPI zaGW$!hw8!G^2!{C+)B_s2m<{6DW-r1IA?Y;On7o%6uK@28mb7w{64<2eG>U@_c6n7SW#@adwV=s!MFr_}Swv|!0R`=zNN^2#Z zY5gJbPss8Be?#8kGtGL3cR}BzR=g{4WDO5Hyqs~OX49A6%#|F8hynvxvP4ooqOan2 zw?;ZGXllS7drMjYRyL0y81ycb!|o3@yr{HvNyJW>FfBJ-PPHnv>1>oltWVLZkkcMm zuN!{s{5KOh2()Te;gMf0=uUm_)_GLec3$$F$9sp}(d&sSz@Wu>aJ$I}^66b_w3=P} zpG>qX4lt3M8*44jpAS@ublG~=f8v5eD6BeW5-R2<%L3hXnt!50r55h_?;I3Jmgw+N zJ5YN!@r~H%zwDTKMX^R)J)kGv&%=AJ{No!S!KgYu`~09%!xs;!?r82{$*`ofoBgc__qnB4mBn^<#Au$AZ;`lS z;r>_iLFZXTjuZ2}`?Igw`U>)}dpxrKL^a~XMf>#*D!=~>1cGhY+B)?5#;DU5jRUCm*e^j*AXuo$BEz z4VXp7_=!nL=qPEmZOo>oj-?&0xGiNZU$qaLm_|^?rSAl1ZmK&I3xk}fK6Z*$jG+#7 zmq$~L|1b?IC<^$J24k>zreB@xD^~~;_?oYn`BF_l<-ShdslHKjs9(R6P_$dJ1N}XL z9m;avIr+>6ukXVqxmOk)9E@>+KoMj)_u{$i^*A@5&Z{+=rEAWq`(=I-wn3Zl!RjGK zbFatc$)#IX6|Xb%b*)yr7h($ykkv>}u@1`|{gf4L)13d28OiBcBjsYNPf}{`!aucK zb=+RogiAXQ&-<^_*T_83gkZ}2umStde87oua~t|c)%_3YrS%&;6L2TSK9CCk@$HD1 z$5VxZr?E>y>}*)<8L?s;_NE#$>isOITECMpTSy;|tipO#a)7!y`tj-srm6S3AWVGB zBOJ>>6@D4TCs>Jt+-!6YMZvKLTuQ;&w!N}Gvk2=+hBz|?_ul&+Sx88Uu^IF{#CE(W zl1S3^3Ez_1^s0$v>#vq;t|^^XR_uDJ8lvG0&j!o&8BL=nAJS_>Y8V2G(vX@qJVY8& zkqTVvmOd4j^}zLnv-PEtkho{I7MeF7)VPur-1jR=e-Kqzo-zD#ks*H*=GbZkGfeRS9LZTtT76X0hl&aJ!g3)ov8 zQ!Vsmo7e*No%z~YqD2J|Cn7_ZL*~&%I4VV3jxZDintxZ$Pm%rn zn?kp6druhX&7na-dF$(~F9L~GS^4rs<-;BNQfG0eYY2eW@Pc3}BkO+jS)`cxctl&Ob)%mOnZ`+$5ttYRxZyUf(w}g zaq1Jp}Qm`hek?J z7#fC<5G15aI;0yUXK18B0qIasx|J@a8)-=?X{7tx=sD-b^S;0DAFj}N1I~I#ufW@-NCXH z=FG=Mm!&qG=!5xL$!6#AtxY%M&0D4gIG-B&n6sRV{}+wlLeoxclr(sO{Wv^XP}KfMjlxWZuLqd`md*LdX>jTAaL z_TC~9y7tQ^ziAOy_89ww$dCoVu_McqNj{%Qk9qK)Jf#S*?%+FStmSnPDF)DNuL$U@ zdC%yxV55zlZ2|_M9MrV5Fw|edW*=0Nkd-DNA&}|~^{aX=6nR;r@4@4R=hk^1j+wBM zVz!SsS?z+JM&B3e#Vi>vjF+|2C)=xw#5VTqm5nI4fQiaFiE4kN%s{iL|Aj!rr#9?P zl6SoU6#C#lIw18ppEwn(iql!rrn}MJyYjpiwM&tCv~CVcEvxD+69AoE$-xzaJX{0T z+UUyEhtL$N_m!_hl8^772n)yjo4i}sZPxvWOYc6XJH|xsca8hD>4dTAQT4=7WhqhT z^2@aL@3-xDt5@JMxxuGoB1*Rz0C*RQ8VjJ{rk3#>3# zBFfLc@?gdiB8em;SGA*MjN8+s#I0MejFQJe^Ykb{wCD2doQN z^eWsS9IfO`<4K82SD#pOMX|4i%BtGJco|%CfT*(u_PyEuwW}WDbdcZvw7D(#4NhbG ze`S^mdGL7_9{u?h-YahvV^ib@)c2qJE`C)7<5ICc=VbmrDy<V%DBg?l35)Fg!1)vd!=ke0{%oF6 z%ZQ*(^^Z_tM#FBu28kMzdLo4iuNaf* DWC@u*0SaCTZoe$rmtb9xw+ zq?A}S$#_IAEObg(I6lzUIu<{4=M5SyysX6E=@~%>is`$+SA;SZXr->ZqMI%|EzdS^ zDS0zmN||EVR!z<193G(L-;dE|=k~B01W(T`&=RH9i&uZev*Y(zU~{ zS@LXMyW1F0K!25L{t+Wv67LJG_Noext?r6XdxvU@m*IZz>f}ep*Cm~=awId3^!>H# zKVPOPp&0D*DSB5}TYQ-?U*lfcr6)VRzCwY3~a z&K6(tjP_tdD3;)o(RSz;Yfu<#vGC#(rFE|bEhTOn7q(wR8KQOsq+8Kj?$u91$1Uvg z4~Psh)y58M?qp>&QezWvyMj5qPHJwH@?6+Ma+`tY{(a?)BCV-v(IC6|XK3+!2Y_ptt+wp_OG20$W z?kZrVzuT5{D2iz^-xv#NFDmjcd&B)#_I)Y<=}EW%JJ9`U?VCy5<*p9@{o2ahy0D8w zgO>We;N8{bGypD4}`J=E=BUS%zQOmm;n6C-jk$qrjCuah4X4 z?)H*yyP{xcwzn0;#Sq{b8v6mImqzfMC*)7F=Ghy9+s!A9VJ~d-vF?z^MB<>kYy;pd zmV>-^yA@R4K#>tC)a2m&1e;Fg$fTv=u5@drS6C*9+ z2$3OW>kQ{*iouJ61jmpMZrbBm$!4Rw!thiq)2+Q0ZAj19(!J*Re<6VP?_qVmB605D z)Q5QUblESij$6*Q-E)N^ntl&3Z=3WN{D9XI0G@3}jcIpFFJY*NsYUWs>vy1UDr{9_qE1%tq&-UA6B5V54N6{}oNwfOv%QT0fnC1n3 zV_C3snNKxp)5S+N4WiF{hhnU>zV@k0YDBRQuQOPoc^FYYeo$(VC8cR785GGmxX$_I z=Qrn49h>%h3z1r;uC&I|hL$U@5+U3SLh4Yra+ZvZ+RkOCPTXyYmEElvN%uAvYS=av znR}zDz9M8*A?cg-@|TYklUBa#Xz23#&i!@v-@GJAtYEBB{~wrIx-L?FrY&dj+abm|B!h%V#yPg-`6^?Bj66l{6std2 zlu_V;AJM}%AC^tbz|6L-*tru;R8&a`vvP^jZH*P~(uh8(x zFEAo{0|rfL0u`c#GBBIWFS%@Xms9b5D{O`d0Xj?#26>K&eYd4ZlXPtiMOy7;S^&tE z6O0252C(JvGh-8npzy#2qRfT7V+jjRrC|*&d#n|i$$w8 z?m42{J0*TFR|NK(@xw3&1dCx?txe06P~P7E*>h$_A!8%msP65%;*xE;&weK2H?Gt3 z3Xm$@Cba%3hyc)j40M>f7>|l?BN;d$^6=alWK*-=>6^mPINucN`5hkOz?oX&vm;yl z5Ij=v;04=hTA>wUZ|@qkWUPiPbE^yqkQ~duJQr8Xe2{e`#5Bk%0mm+19oYC4$%LO!Wa+Az-KXszwJE_q zrfIBxq1KD%O6$+U-scabq7mVij_Ph!r0XVTWYf{{IQjs7Ps{tMS3?^qs8 zQ_{pxL6A{9fY(dZOEpkzMmwL2mum3#Iw@z)A_r@DO&l9jAXy9Fj0S11$-6NaqyvF6 zbmc`AD-wia8j@JlcI~rs945Xqn3H3uJFisd(`&O@nKQfv z_L;?`m(u(U;+^*x{wpW_Ua9wiK#;svULwE!I?GeA*Qm@w`ioo|*l7AJ;^l`tATQw# zIahYRZl~E6J)e}F^-$Hez9XbPSB_E^&dK6N9-Vj7X8~2V6yYufPG_Sa+VQJBMD4A+ zR4e-C_%Sp046!lA$gCrR4JC7>fUO%G7(EEB=DXIT>^3d)cOpX9{f&a-_cA}fdL-n6U!*O z%C9h+a%&V{udSRzw;JYeN}Ka`spl=@;H%!Kmpi(*@lJKuia$aTdA@eF*u4v{|0c$C zpl&V^sJglr${S_P);$x~c6VulZJ&P-dip&<7vE=uV%^T*8~*KlbSq)y0(z)~0i4@x zTQ42Fw?j1QTiu-MFmaIBuCJ-+xd4={Fzm;KoRa_mgOJsT34X&aoM|%KAvo zx18`H8nh`RoOXJqgAVM_4rHn06T>vjo_2|0y!L!pp;f#(qPDC3kM)kn_zvA4d&;$| zjWXz*oxVTWmSC?QfF|m#qM5Ez=v!8iWOvy}>L~$Y-7gW|(6J*YS;00k+3nV$^mE#f z9ZB77U#V}GS5CE9fi@U9z1IzogPHI;kCIyP#?G>Ia5_u1tCK=vJ2d3L6<;N(Y6Imsn=W&P3PuLQ!}hvhmij!EbB9E{owO0MPuLK}ADf}3!k z{qe?sjNkkXsLyWO!ejMM|6_i*0GP|^xM6p!i0$n0{`JI`-kI^+#(n)}o^Ty{U-KNl ziNCb~W9F7Z8Jt$Qc)7n~;EZs0tgh6+x=m;%C_=V#Xr=K7sQh%kpcsW#>reozmWiMW zmOzGoS6_y=8?byMwez;QC!%UF!JZC*IEaAYQHb74#%(5cK8T^23(i#U(GSu$4uP0m zM}Lh6YeLF8>X3pPh&LXHtd+)J4Gk531}Nk*K*wfS#;m$9UPu#+W4;pD40KSH$ioDP z#F&Tee@1gT5a$f z3fqLL03x)OsZ4zh9O81bHk;QpcR2q7HC2t{NV=3U_f z!*JvW;`nZr`P~{6LP7#WAz`{ zueCL9QvYGm;~*n-pzQSLXSJ5T(ZkPFr#GoEs($cOFX%R-a>r5)aW#9Dc0cHTt8V4{ zGEVWwJbl)9SNNT`;m>V&go+RJ1c=lOc7JS!4MJzIugBP~$k6Z1`W`jpwj<#^@}{HD znJ+!+rU|yOOLu#+Puc`s+OkhM;-~)2Kpe8o7ah(&TWJ=V2^wFN2oB(bhNZ&D#xlin z+dlONR=e`-=`6lmN-_Ixbb>euF!;HVkg+py9iWr!?0L=$FvnePD;n7xLU{XqU$nl~ zQ*JGshFWnqsc4`t%(X|w_HyCkP=1cz7WpLfQ&QMO)VG!D;|)un@{o}BgB|Q1qU7WE z%0fHPLsX{ofRSnH#qyLFT&Sxbq9?ZXXVUiC_kS7Qw`J} ztSo)bHcUrI!jC-T4>goU=0XZ1fw_@*uZ~Tlji=}1J%$@7qC@;5>D!}-o@Fxvdqr$2 z=!bqheveRe=Gqz?I!TzX4T($O+WJW@s)nF}Vgzh3H&R5$wgz1q0UhgxvlC=fo*ae^ zaQ)j2pWElVyO7GCpz*N#HUk@)+l>%yP0tFN7OF*MXOga($*E|CNjI9Dh&3(`lF8G` z&hk{gNED+*kQlX5*e3N&*(4M-iVpmT>AFc5U+Z9X&xwY|z39E_4Ni>ZGzoqB3XCqUs_(6OvT4wr7Nmel z*^@kd1|(Hig`3$biVNSe&HrWfK$srug2?zGh3U*PZhgWKtdIjd44TRj?9F&Hc%?SE zWc7=^j0NVmz*6X!t5g%>agD#v2k5sWhE)G|V@|z%wS#X5B=zhc0mx>R+A*X|>?6g^ zTzh0TV8UM1pY~E&?);^fA8sc^fN&iG0aNsJfwc+xtHho<$B>n?)fNea_ zz?U;SExwaI;m@?Nap}s8CoA{szk~yWSSAnoM8y|27vCzfZ0AI`bbu2|ZobF5DwH#B z7xH2kQtL1_y}J_4^g|f>2{dIQ*h`}|_)!f4C`4YVA6ubwH)=x&5^P=-4dh|F^GXAS zmEsXmwhlIx(>+C}fdgQ`Aw7N~v#ns;fxBvSqu>B$cQ<;c*n3?=F;K011oq7CM4Y>U z2BS~h83k>^c(w7i6n6!q%o$g3Uih{FXKUx1PrhZ0i9&ymU^{$=?18^-3FnPS&T<5e ztY?yRwVxBdgo!7^>2?9LVWl&QhD5BEl)r*)miSeX*5r=e4Y8U$V(Guyr63USG;BY9 zT7YwN{>trs7;J*nWwXosZ?IpX0=V9zi*-R#Z&Fa)SsHam!9mBUMji9T#4knQ%Uky zbv+}BDI#=w7wBG#b?!|u8@JbW=TeSp#Wi7$fh{hdyu5b&k5Loyh1#rQkd=BS&;%bc z#n`{n|1D#?+)~dLs2<#~ac9Qsgjg_0Je_GrvpyU$EYdJ;E3}Qm>%^r11(<-!*T=OV zS|+K}=V4%5x85{S%~J4#2Y3ynHDp>F#{8VI>T^g}sD3mQ}$)2@MT=xaVBVzIu? zGZ0fjl75z>;pGaPQnZ~M=w9CMLUpC=``D6^o z(59?QEg>tkz&Fi-!MOS$#f<(r#t3JT(bx!rCaDAO39Xh4`UI%+j1S&&qx{7ApuFpo zGd@@<^7a&`g7Quh3zt3=$Vh`VeCVCh)s|d!d4AM0XWu(wbw0VYm-1b$o|j$(+xJhL zZtQ(#JxOl*V6T3|)w4DoO`HCI$a?rB9hj6;>P$=&Z#C$CVSzlR!6AW`!PQg!t+13o z+pB+)d$Sr)Nq^Sd#y4$*0&*t}j_NsYWXZFvmxa3PbdEa%h?7h*5;N_nrX~V+k*#IeC|vo_$MRve0`zy2 zg~8J%m||KRAy&NLHuFiRB#XXpy~bfJ&H<>CSGag@)=uW#ciMl@h#F6{NoWA<0ZQIyu2M570re6u-^TA$p`0k?D+hJwIkIge=Z?`^)nES=epB3&&E z9C=Z&rcd6~gflc=U%U3g%0EIn_Uy;NLb}&>+38fZZD@wOqTGh#Z^8A~XlMiK&8T_( z84hhbAR=jvi!49f=UG&gzQG{tVk0*>_KgaKB*^Fks1(L(0x`w+Rp*;|y;jQjtCcyE zM)=iL4%jDgSiIl09>Z%xEm-;=EoH)YVciu$D#9PG!+4!;C2riq5Ya5Eesmr@fM*CE z6LJkaj=D1BM{Ks8t09$S8ykQ1eya=3;plaVjAdqC?rItbv#Nm4E!y1{($k;Nku-kW ztq_3&Sz(c!GUQHSL=uto_Z@538Lh3fzXWBxN}Ya5_r#}r(X&20BS zBWksY#X=lXr6j#wes<2 zZOP)-`#$Kcu2ydSHBQ+#w7DA?AK5zSy5lKvu{!N^nfP?g;^&P&@fW#fv%s}Lr}siQ zFgQ;u3+J-0M~rQ{D!3~o_Q!nvKUf$FHwF?Yhje(y?d@8b{mA7sSLo$CUVd_QFMrR4 zwJY6D3s(Y1MF9=ZR-28(p5mK`G6qyfx1iu3K z4E-5B3|sF#iy>516w~M=khbbcmJaU(yDpEdzS8a@tO9CmSrsBV;KWtg8Bieq9$H2I zr=l_U`i0B!s$WpfKy7CJIMvo{NQKw|Dv#Kuhx$O<7bQT`k_5;?z+kqRZjd&!Wx@^3 zp;l0c*_Z!c+~^_ee45kCYkP<7U>x3=>}prG#nlYW5$B(#f0+Mo;|-zkWMNVxxQe9& zqE+!|LWV~=;`P)an^hT3Vj0*ZKn_5Z$V1hLv6r5;Pu(L zkJqHpzt8IlD>cordGw`bLJvO)pnxZ1*IXFYU>cW#3$mYW!n8E#ezjy*-P$OI>iA<+ zwy=H-xY3hLv0n4Z$&31URB#*ADJUd;p9;HhH|C}6#HqBi7>w#~-Qvi#aP4u$c-Hx* ze11D*XJOiLOg*uU@^0ajz$XVI&}pzXvA4R}L^|`lM~=}XAdm+nPN2$5xrI4^Hv7Yg z-@C)V)y+oshKOPZO7KqR^ShvjsVaTws_`Ja4g3H86qhct0##@b!`Dk2@^v4N1cE@n z4Oii_udpUwRMU+^g2hIF*S{W^O@YZJryizVhn_TE{LC*X*h$|`|6y%jyZY4Xi(cZe&7?KX@L$x!TDB-a)k6xTbO8Zg2CJXN_?U_NbfBYf7NB><3L6rOTyK z+*&%|c3S?>LleKKHP@1zH<9%Yh+n*RwreO!e=VwO{+C86R8e~wXGCMU~PH?t;%w2iWg*M2jU$Ps0DyquSLO3V1=}Z>`;5g z4u(a|S~Z(eULO8MYlS!;dRV=EsqHh}kjd9lLKc&cr85(Vz=*bAh?CsotaUK-R6u4| z?v{)bg=UNF1QAh#(`_mozn z`hIRAWPI`2I%(u67gptUQ&YxA7AbyE= zS}R~DHNNpR7s>f3t?#;R`0njf)Z1fI7&IAjA5}HSYGVhZjno#Ko%Z%XUr(Us5~IZWiKYumH8%m8{Hl^beQzzCo)PEgUBh~W z2vZ!P?&5vDr4>F=M5hF*A=Ed)X7mC*o>?tN>P`uxgrTpY>_(4DWAV{Z=BMQiIoTX+ z)w0(aDPnV}!s62_aVsd>WWZBa%5`m8@Xgo2g9(YqbF-e_kuW^4ItEQL`<{*OEq(+x zvkJ;Zl`T=qFSENbIlGNmY?Vu(51$!)fD3WwJ-Gh@5)oOM+PF zC|0zaG-XEs?umnW%ZdBwi~A~yr!Kp$@uvEIyK@tdne_0!#aD9YR1a{sT-PR+v+9j1 z_>JvI7U+ZwaF?e|Y44p`$E{2yQ$Z`F`61!TzL5@&4}0(p;p|Fy{{-l-Z(53o@%3uN zPx{1mZp?WlTcfRWR-_Bp@K+c&!!S&7xQwu$5kES)s*To!AeWE7`|KRm8Ws#aO1<+Q z6W&>UA2QRb|52;UBZ3S&4RMlWf~dOS_)C(nYv@$tm%HW}DrA>hsHe;f-yVQ3?Y!!_ zw|iotkPJ*y#13A3TySz=Wqpv5NyIX^qH;$Q@w24p33niI0Ipa1R;n46?@vA}*1|q3 zB*IbFT4SV|R=nPqA1k45-NYJN){m+P-&a&@g6Bki#)+dT0zZ=XQV)Ida1X4}CwDY? zm=+p?Zkpl9wU_FD><_D*y~6Rl=(rY9Y&u6f?`P!jIJmxg1k|)914j|PmUdcbD{zLa z4ac3NB7{*`ni*d|i&O3&{;Xi=OvLqt?jqxw%YWzmYUxfhV$gA{JJe@=1V52cN)Fl^ zF2$}(ql}dDj@*q}KP|StD@_Isca(AAJ=}5JBN}FH=(I7o-HdponU$2NOiKKf2y@+@ z`122(e7*IOb3Ln0^itIo2kcIB0)#T)qBoBxTn)ToGw5dy2`_y`#TByQ(=rM8nS(Q- zA$+q>VEdc(?UjV%C}z5>u=lQ64m3Di|GXb_KHI|2eE5z3rivMk5KX+pp$;{v7ks&! z3;x`a^i~H7Mt;2XjTzZIuvz_{gZSfKEJP<*op!({wYN|%8-xc4FPoRodD1=XL)m0V z*@oK(*uEX1pb2Hfka=7tm@vGwGgVlkX)d!pu}ceaOpKf*EopBm}&r?ed{Le6&@`}xNN|pZP-*D~k z!e{dgv=@MveMHfO;&ZYK6})%9o@TLChW5T(XM7k^wx^!BUhRwVgG5kIe-6?cyZZ%8 z=I+!~{OUUQa|2e#JZH2Jq>Ci$kkBR!g4koWqA3z}s6d;qY6SJXie9HZ@M5g4J+>#w zQ&>mqD~hZ=H2)Q&h!^XP8=u^67O#2zW-Zr$E>FGr3nTqbB+bnjQuZG7`81amjq81v zooEYJdo+jY30T}WSW}ST)59?jO)?$$=9WrCk>~RQF~W8oc;Ou`2{0Rc zmO-&@guk@_Sa1i~bDyhc0WwWO?LW?WtuWCkD45;!h(E2~3!0`*oVa4lbZ~TzPVPj= zw*<@ar+QGgW!-;6E|zD&WBc`fD&%+#r`Ua|TgRz0%~f`;G_ttA24qn|I06}8aF4U) zlh{Ho4{A1)qA-;$Lv?zMQqSf1Mqe&)`zL7f6Kx@m+RrysG1`~{S$M}TS{QLzECu1v z%6LjslT<&mz>N@-6I~o*vqI}93$@K-z@ya^??s3d#|W`yv4Wh!;+fO0;CSDc(5@aC zT#^gyV^d!x?ucJ?pEh2_*}(MZc8#{r^xz^?RIe7SZyo~ z%7k>y?1y=!biokwoZa#$<<+T5^99rASAlf!O%vR&7Q{>1lQSz`a;=|S`Jcz6$(&Q| zz3VC4Uo(8+WNR&LNS0uyF4tO@IZvq>|UDWAj}O$?`t44hq2d1|IC!hP*@|9FQ)9lC?b(NB%0AxyU@=_}`USBLybv zgj_Xus{i?TrpZ6|ir3J$CH)T5W6;maz}Al;4}R z|MT}#;t{Y+`BpzUmHeG;e!T|ahX2&0325A^PWM{7xFn6aX5Lx*r`e#3;cX7&_IPq< zA!J?jnOrxF(|_p+LqZWydPjp(tm=oN3AeL%C>9c|W#AUGCcC{z%_HAY$IIo$>Ux@y z5>cW=Q8%wYHJ@}v4yLrM%8sbT%4#r07v&k|QE;KoJs9sqo+3)>mlyu1zM!VEP{_t5 zAMZ@`Xq|nUHHNByIpl!{ssqk^l9W~fd8_@;uQ@o%_WT$-)(GV_sEUD#mB zW6h_C?6!LEGUsyGMVOl69RyyXR(!P5^L`RIIc@Tp2(@-^MCw~cnWR*>ZQ#~Vra7JrK_KFLit>LEXqE)>T_~5$-Iza zZ3csK?8k~tVCV+Kucr=gthE^(X>gSCNE5CnXSf(Ab*0^WSq`uNec1$0R4W-ff)qt zSG!e;?DjkWZE*tAbdEBRpUmAN^3fdL$fLRAVRZt~h(xAayg(PO8xN}H^d`alrVw_z zFUoFJ8tQ%CBW2qHBpC~o?F({;)eH<9FHZ+syUOH3mV{~no^PfpX{M?n+GAe!l`1n6 zr~S*w{ZCj@$yGeY;**@tCcZxWjQ-SOGC~nT8H+xKh0{(KKvjl_VfkYi`CkmNw5HJiz!bS5*I60sz<6}=CvdEQpme_?< z365d|{xm!gZl&bN2ir66ug~nko|hD!g;&uC-m8%hd>0wmWbepZXIIAf=|jJgW4$e^ zs@S)Tu0OBy(Mo-A-g71WVGM~yQ)f;mk>&*crWGFhOp>9_twEa%jn;@Iq>8X>>ga3p z)W!?fgwHikTQg-;N+XO?V-&Hqgk_~cI<%T7)e6re8p*PE)u`SS$kTAK_rQR*{S~QZ zyzgAxj+6YK)c}Tpz#g-#{dWibmxn{}5wG*ENl&iVC4J2FyiX{=O0#bv zem(@>C4i5+(8UOL%ziMb=X_b@{0k76rj5!BijuR%sADq4!?SW?<)o~!dGwR1QCvb) zQ{@tuSP%(WAZQqOvM0dL-YDirrx$6&GNH7y@~8+P=)K5k89Ao#UZ^HpZI5@HAw;L- zM3SM2|Fo)f$IaV^+wvZY8j`Pq$ryflk;F?$b+ZC+_35#iY#j;4^usY6+x7__A|H-Y zoO&EuhPO`OPU9qLN$WL!f9^{kQMVMsdu$G2$mNg1hy;QPQWU_`QIaZi_?=PGs4l!% zrdaTnP)H{aJB4~Gy0x5PU7T#1nJ!AXYB98s&_dgbmvR{ChQIo{k6ZNGwC2dH&M`QW z7(X&87z*j)rsNJsF86IWEC$Z);0<%ODV8)?%Nal`%-Pfq;uyFWA@(6gh}rQfQY`el z*jWLUQH0nra^s%lT-4^la@6rp9ED685JQA532^!>d=gU`i_nPUvM5EEiBzCx*fst_ zU=;5uXWKu;9Plj%B7)3Ah|U8${o@%+^fCEewR7g3_KW-1m zplmvDp{T+{05acWo40yIxh^{2hoiEO=G#Y6?^}MUk=ZlE6R0BXWa`h}AO+=yAMu4l z#}pq5WuUTYZSnguD8D;x0C(DYUyqi}!|W_8l}tD`$$j1DO2~*ME!MeSvKyu-SQbIY z;F_dlX?$cggqa@I{=GKe1L4wB!w8D(^UsJoMcC#QidOY#@a2nx|2s+)kpa3zalS_T zPtY`o2k&MU3p#;o9_gux?qk0!@l_vK{`3o~8VZ0uIB!ZiMufECqZvmMn9TDc%Qg(t z>tp%wQkqwUwzp?iXzM;IG&wN}1wYs|2?}l0dd4IyWB55fvtwnKJ|M0{JUWGLP5z9Z zZh0o(C9ko=@Q4Ctu^qn4*RjsuAR;j7DGomW6ySBu6HcWh6h7rn73K{oJ1!VA2{cV~ ziw{h5jC`KB9c1a2s2|?v)hdNwi<|ULiLOa5*m$PyLn?N?9^!$eSVuO3Z;>&L=0iIT zc;Rm*ZhknIE6I$iBz?KJ{pActZ_xvxa+qolKvk&- z7?y0s&GqqmOYB~cFkX!>wiz-~=^9Nc_LpW^EBD<+)<%j)kyVx#-!3H(89x!}C0AqO zY4wM9)qfK>GJ8JkFr0J_(MLEAR! zlTnO+pLA{>d2L|Hyrp0aB#tdbK(!>1cmr?7Y$3?3zCS5{RfoR|9|F;*NsLdJEFP!_ zpJD@~8t*a_oEN)(&iU@~!{Cxa&(A&nq0KZyBj$X|(LD&s!6R*GKl*#Y!{^^aO;yEL zq+@epQ z&G`?0GU&w4nMSqmR832+P$7QJkUc5Kqi%uETiH?`pk_oRqk7oYbUxje4-#^)~=?;rf#Ax#nR7xKIDl$&duOd2`2hHPv{RtAlGY0`czrV9I-!+N9HyxAks$c#A|$U7^2*uTfj+rwq1C z$Wg5Sv*?J@<0GQSWc>af4BqQPu*o`j$sENZ(edlO)_y529&*sfudo~?&y#jB4&wpU zX90PLqp_~YnA#ob51xIH*_EuwuAe%5$2+HZndhr=_oaFIkNq?ccjKvKB~QNx%yE%a zGyGjoMf<*&?p|3&*l!5S8YuPL3k33C_{uWj{(IFX)Gti}1Mk|iRHjqwE<=u{%b2@6{(#`Q|dShw~{DWmqPXvL3w)x z)@2dBZ-OsXAI;z6jV>782|UX6@Okh|2P~vwKxHvGs1J-B1VGMDK-y=M?nEKlFQH7W zI!;McD_Rc0ePot=1l3j@>^2v}glp}0Aufg}vRz($wbsd=p%jGV@xL-=_lxF-`H>xtToG zJ*(6xKXJ023NLz7zwxH-eiCTbPG)JM91asO$Oh(AwS=8@sOgUbqkmi>vk9v&nzd@O zim8&mf7F$xX7_nCGg4h11%v2uRv^v&hW)H6VV|uht@5=^0s10}Izr#3F;a%;DLWPF9@gqb{wzU~v&bw(bIbO`ZL% zuh%?cLeypDi>oX3Gty0x9Hb4i9NlBy!%nX>1>81ITq;6>PxzuGoke&W)drr%ChRk$ z$91bGCdtekl^ixcJI!0x&x&=A6PT74eJ(&QbKW>;-1YN^&*uP9(x*B_ z`zAGebp3bwz7Ib4tvZTUc%?5R4oQ``lr`)}qqBwDst$U+mfC6vtn7bJ9%u6)F|;OD zE_KcaJ?|%NI!5|uHSe0lb-t|z0MusVJc#tmTXXKk!l^Ea1N7;4h%^0)WsxZ`5YH@H zJ|;HnY0OW(ml~CC_nV64{~@=*CDa=$*d`s1I`m##iw7MO)$!**6>+`WcWil@rm_c? z#{=q%rO)w~VGecTdTaLd>6i#53|zh%ttpqdsV~}Oo(1y>`P`j5$+GV_aaO{9=-I!; z1cvU5Hmv1XEewN9eQm##i_>Mk16xeKd086$pFvXd3PbZv8(iEaNDn4OzTXzBS)#4g zlCmXJ!WgpQJG>nGUX2I0g`#+~b|Cmn+@yTAb;D2wb>MP0#9<*)EFGQ3fP_(yv&^}} z7>W!l6ja{Ve%~D6VhQ(n&6Mi;;N7E3;<35*vP#vECwNiWY3u7-u8%zqsUAIyYvca0Gn z@1wFAIeOk(XG&$klkG2^Iy$%no@S4EcPyU@$94wTyg25$_S+Tb7b@4nxCyL4>O`}D zHFL6=z@x(b*EsBd)I4%LWR>2oZ&-EG`&Ft3qoAnJA+mb9s6A1!W=WMm+o{aKRk`60 z&NeZ9*%~a(OHR9bq>4RJ9E9l!67Wn~ttUXDba)cz(1T^E(_>Kxg%C_|68mEJo`V`m zmM%}rapa4ZN|Cemh8V;Lk(VOAHe8x~p_Q=jpJH%yr|eK( z3XY9cJ+N~;QGd#*Yhb1}zs^AzO;zyyK23Uy^T)3w1fpj)xI3rea^GC(@bZ{q!Xk)8 zXYrYs^bDBT84%Gg$D8dcrSHfLMqUKsE3>L_bU0$)BRLkLDj2(ppKuUW(_k6a%XsU{ zibgFk9ml206Zm?m6%|R7?EJ!icbF&eZRGffFwyb&QC;p724@jhN@}?7QAy=b`|*;4 zQ%~gHGX{Rej4ZuS)pB+E0_=8?$ifN_(GhPtcp)(>+QF4vw{HJa=wOvXQv@W`#P-p8 z-|~B^DVEnSMLt|(C3W`7;05o3o^-kwPqOYcG#NKbp=B)%;DfN!>h zfs7em#4-2Ez>{Wq{Gw(s*+A&o5ASz+$tdM%XNfCK;5+Wv4_=ZnH$2{WR|Yo!s(Yr8 zJrMEeV&oXj(ZE0a0c!D>g97%Xx4&P2!E;jz&aHYR(sJ7VG3pLIk0H-dCQhU<%Mo{2 zE#Z3`gpT3StHe*h++Ay?`JoGm1H-X!KpaFYU?f z4G#Dq%xa!s-=>08YB`LRZ%! zuXlkgx{r?i$(a$P9_q$#{-u3D!omZw7K;>RWxV=@`Q^8gJ~Q7RvNa_r|2z+(%Yuthg*!7Wd5C3I-|gHHo~AtMK| z$516_%}f3H3e*e4lp*s&7=zLi?-)>@~;UR4xFQXK8D+a|K%R;T*nYg zwM6#2{-hmL<8?}kWhVzG0om~&LIzp=`q)6^_eB^7pBt1zpVR4)?vwu64;LeVA`0UbbJ&(FY@8ClW75cjH+M`bvh!lL{O}Ry{3E5zK{+*!hw z;iMuNKXYv#_m$+e4w?#&_N<84c@M8z`@%My8NaT}T@PC>&wZd4Lsw=^ghoRGk?1Rq zVq2XVrT2?{Y;cp^c*uRpa@24LcnTw^7#CjTFE~v#8mQdK(ZRxpux|`Ir5DWeVn8pI zO&ZDlskitAF`q%+6!^}3Ox>@+e!$tcC52DX-oCPYUgopIPO4@XcqZe<9Jch(u^s0y z`+{WKc{KaQ#9wg>NuD!EJ0s;g89a|YlkvtB82?#y3YpE|p?1@yJv6Ycb60}&v27$3 zne=$w<79|=H!!V0*%FS#Le)l=&wL8oYar;2-fm50@cAfv zk!Y3UKo2*T*rzKV7NS{pG=Hkx3r{78OLuh&-r_L@GW{mv!Y4Q> zj$AEVH2=(#Lecx$fc=iZ$FG`De=h39B$4gy4Fo!oF*203t#N!`$#N2t}jSoJw1T>14+AEV$3;)3Ge^W^_Ed} zZAsTK?(RVkPH=aEyC=94+%34fJAvR9EV#RCaMy#o2X}Z+($DSgd;9x-F@Q4|gS~52 z&6;yoEeqCgfinaK$3#e0=!2Y}eGXi@v80=tmv3U&ylBkRR!8P(4iuM~&>r96M70Fv z=hv=yP#Ir@XRr=Ix8ng|C&3Y^bQeS`m=Qd_=iH1L>#`sAMLQpUk3Bx5Z$T#%hkbJw z*5{sjoEx4eht0-akOFZJBUk_FY5#ILfNTgF06u=B?$rNK>c81C{|2ZYJ8x>s&budX z^kMHi!N4bVlJmbL6MAs~_Rt5kem5huEh$3nyG0$*rnyq3@l6Isqfo25J z%d|2XL+^E*TRhiqFH>vZoiQAN+&5E0eib0Wos=2xw{?SAv)>Pwim{e1+-1CG2AR|e zh&B%+1Hcjj__d&gX@xj+qjNeZCHqn3mdv0vaGotB=mh(l_klR(s3&&;>atAmdfDTu5fzY|D5YQUj@ zk@+GddihP~CpamSV3WzW$1iOAJ>#jze2?kk+{UPM%UvRjE~7f@ciZ7XoPQS(BCT!InVbg7P-Q6vzF+vG0g;mWPlN|F7o zvp^kvC#kePYLD@097=1xvzX1}i0fob-aDqytpkb!hZ4AF{NbyaoIkP%4yHzl5T`aS zUV0*)ufpf8D}<$5x~J!zi+>0Ypi=}K1syI=w%8AMe-kSVdeMqs=IzLzV| z+CBYn7P{8xwlMx2Jpw3@Enr}S)8>~F;dTZ0K)G_10Plc{O_@eR3SfWnapybs5aTZ4 zimYy6+XAm0=c7ovBk#{4kM>TE1(#iEF)6Z-2n+3`RmTmL7VaL_C>XoWpVlKKA-o=m zu<7Ci5)oOpDQrC@E8W~C65A1taUYiqtb&V`jr$X@e!>)o2(iYTp0Dnt&dWMamE6{K zhY{)%732__2?u?PF)F&S97}XDaArf*8Z;?*o_Q=L#?UJ4`Ru9Isf4K4{tW$VX3-^0yx!vF3kme@4E>jaeXT25 zU=YWU0O_^&{S9jrr#(S>wMb_J=suJ-`UvuE&h@>V*Cg3mPC-ZBoQ0IFDixoR3y&pk z&U;Yj$5}`Duwe6gEj^VXNeG?HC0>gO`Lg!>Fb&MY{yB|J9edc$4*NYOKAZyx@cW@o zN|23wSX7~mLdF!D_C=W$#ver!uyPt|GUNT7ZY<$bCAbbG_fA5EArm%%H8OI{J$|CG zuKXFGqr1V~hR9SM1LT>JhLep)Ft6OF*dqeR7}ryV*u|l{o<;Zf*Pr>z3!sLZ=v4+S+5F`cD{Lfv3TD*~_teR0# zlP#8xaRo8j^XGG){k0!?%f~)WdKk9rRmZ;c8xVC5)WvY(+x1>+- z_a7TTqR|N4@sG}z3z!{wZB@pW$MDeHRm5KBc7;1#AA;{BV4NNX-N21LfL zA2##c+_@DR&UTPmANxXDgJ;8&Ypk)Y8Na&o70n3WICiseTyHK6tFbTB$IT(%sSe&G zk2Ws6BGI1LWz9cJvjaz+l^zOC!?;5T#FaWwHOocntczK$Q`0Us_!x&pax2IWs-Q5b z3CNfb;a=Bql89 z?<4j6Zf_{W3gCz|{ORFMLP>uYsH)aQ=9XhDRWLV7e})OVlb4LZ@FMIjd+H2L5?l9* zV~=|Ys;YSS$!2nje+$6?BXYq!QDzL+rM<-il(dr!9>Ut>YcS)&U8KP`;xEX-nQW~R z{UG`HFA0MnqYFqH?PQ0@;=~@phzBJ;BSFIlZh+JkDSNA736K4LCy#I-Pnp}l4t5Ay zxP3RLbIq^W7Uuy1UdibeAWoX{+UwY!A+HTxz#D@O^C2pn^m|Px(sZ}~wUb8|fXL$; zXgS}MzsDR#PYz7^cChHRM?QN~t0th8U)BP36f>^3+N&Y1Y|`(0rR5_V88Hyba+cz= zkOTx?4P>(zR2Z*NY$^H_oYJ}pS`@WaS+%7c7B5i6_#`}t>^8>>xlt_u2^VquiqiiS z7kfZaW~Z|-uDK6lX%3INBJuB>9}W_im2+MJ z3e8+5xx?=e6qf4G<}K8v9k3`dcF2s^Sj^X-c8#+5 z54-p)LG02qbCBA5$Zgz*b@h{>?I0bwFGfODabo2V89^6m8Fv2^n#tlY$q5zf5_>tXGEQ_*geOf&(EboMo}<9(u5ke&(_{2zL(7(>mn@UP__KT76@@ z0Kn>SY5LY5mqueo(C2#~Q~W~iO*3i8>V{a_J#5Vt>Y&=FIA?CBm&Qggru9R3)Zo_+ zhNt%KO2v(Pwckl}QBDTmuK^RNkeGEP7;R^jaPO3$^xX!CU<_KS2F3H>HN`oA4QBgC zB{)B_gS0>V{2u4O#m;Yiv-XeCkoOX3_t%;Fo#_0LMRQ&wJA*a?1*g?J$X$too4%C% z+t^Fzue-eA&pkl5jfX0RZX3-Jp+#WGEvWlP}FsiBcl z$H3({MaXJ<43Qrx5&pG!4vGBqQ9=7osiZ;dA8f;MzyJx}~W2x95-xo*{767S)sBb^SxKb@O7+RW!y);BtaI=?828Xp|;8}uDHl!|>3 z-k6lT(Y@xVg27WmAPv?K%e@4YA@4CH^Gr2jKP5TyTh zQQh7<-2Sb~a)J9_;&wuL??_DusOrD6BG`Fa{UuH3=tEq$p9isU8?c|na>R(Uph%+M z_EmdlMQzYndfpm55_Evi1;QE*4ER~&$jErMJdP2v!fmLP#!=i7=Fvo3wAC>UT&$*C z9NH*u$!$iA*?IyTT>HBPm`;1zC)T2gKJm>{S{**w@9hDeNmtyf8QFQcXk{t6ahU>$ zc{qtd3^B^xw|b{!N>X}p+MHEvb1V@^jPX577(5Op%#P#%zXxT5LIZmq)V6Q16}W!p zP|S78UxVss(Wljj4Cb+md44)kR8fACax|__!3rY~oVlXNhz_c%MAp_2#g_JF=j_yg zbZFS5Nk5HaIDGXs7@0u`ePazQr^Zqd7lP@XmmLp5t#!H?^&=m(|V=pqXM2^a$oIRdB-oRLC<#cF$HPN6a6qnciZAq_`^7OL+C-c!X#yE_l(O&EpV}Sp7rZu@#em=Y_CYe}ksY z?|Oz~)@E-KgIFRAH)yruYLC=0syD|NOxT#!>xnQfH&5oY;4Jj#Fd!l`TQZegiX$|+ z8fY2PqSj3Ypy*PQaT-m%KK4KI$ZxMX8-`S-@jgm_lZ#Y- zon+vvAU`1soDDJjJ$;vhe26afWPPmG_DNo|eI>n9F{1 zQ)T46?tcu~{|PBpp~vuSzc(k6vq*8!^{~Ob4tal-#wrX5in#V{u^Q!|rvNn14Zt=| znUG7Qen7_yprY-roo3aQWGf#1K&}_TjxyRdpho047j2_H4=Dq#KnHmuia%D-_CY&i zIJ3Gj?$c*doTl0@PLg)LR>jsdDL{*bfSO3Fe~d6UF} zw}l^%Z?*0<7qg|22!;t1YOY(EFfUH3g0O!g1TKP;O=y@A$nRTDW}`4XE<7i7-I`%j zWh;Gq&I^1F{@{l!JIM2o;gtWY0ajuF=LF2_V~ z8|GvdTPgE&N()Mt6C9^VTn&ftAUn$pDvN8}KVdww7$`*%m{)PD{ta)X#|rIMzQS&W zlAJYfU(O=Ze7H9FtJE2wL4g{oUNpX7*!Y!zfVf5Cad20{p8C6X)B?|Q@oyu-d<>G4 zsATXJMg~x1?{fF%e_3y8^0QvR=?%446`!q?Hf|FwtoifNx@r`GVNz3Xf1)V>P$DLU z1CqY4QZ;uju^1R&S_Z0!5ge!OS4Z3^!5ObU zxbHCO2%QDv#_{(;$DUVON|MiFwdD-65*VWH*Tq9Idk)U|TBJRVy%`+p?y8?Wxh;Uv5KXUO7^mCBPG&aM;PPNv>sWcRZV={zwk6AYXND{%Zz3O;dP z%qePZ9y0f@t(*0uvd*Q3}4 z&Mwov6niM)livlhW&O_e6X-(s1$hSa(1u8>1P#29t4gR7YueDY$(JU zZMkLjSL%8)oZplekZr;DlezN^zifM;W(@@uH2pUXL41g!p*-XwYd>{r~2lZ%Os0w=|M zc2{J7eWD*;+KCps0%aMY_+-?sGw7f(A$hJHpy7XKhTl|2$Ttu?4t2BV=J@a5_@}1} z-TR-5oC>~r=%Zbp``~6w_!R!T5`Bayhge!wKsg&i*>QA_Y9YWFnL_ZxgGLYb`&E7A`jRCC3NMF3X!OCMgD>K9cL$ z9&oikv9fS`wi;PI#q#82)yY>cSlliDq|B&}qq;O)y6UD{swyWhzvOU0h49dp$@Jj0 zww9Hgot~{t5$Bvy5ZqhtUcZ+;V#4y_ga7ATu!*aaCgnP(V(-mh++Pc^UJxo1bZ4z3 zp(sRJ?Bn&8?-q(GbJXPTby~d;6a{bLq#8StM0PQ*qwg&M4a&r813ai@4n7? z`5oD&;K8b)IeyCKHr@yIXk;Q$j??b^&hh8I^zyljdr{kgGuJjL=HQSDEe-z@{ea-j zdt=3Hy&4+t6Z4iYK{QBcFsk?U2&S2FM8+wp6oD=w$g5x9Ye*v<<0Xa}6O7lW5tc?{ z4{KGIIVa06Tezg2Uh8R`-GDR`2hncXCtZ$*WrVH>>+&W}_wNTgNOWF8v;K1Jq;bfJ z5vqS?FL?IhdtEs zVcknb*1-seSs;ybo8!t>ujZYA|@Wx*ebG^A=lU|T4 zW4xpdp2UMM5-}bs-y1Vt`1e@x`T_C&Sr^iOk8p6!**lv3E%|a{`X9YL!G^tFG+qNK zS@GtVtQf3b5sGX6JvSI9b*W_0`Gb|uWpe+wJwt@pSj1X<8Y4KenaTb;WEeK zD7(P-BO26f$f_f3u2Q4L&Jb`#i50luX4LJdJ3%Ajx6h#qovcexX>vchw$S$dkgcuK zG3UPNLvf#sJyXsr|(ph_GdvOw}W-V

*4Xd z2i!evW+2jQ6byO!of^{%=Q+DPuAUuE+j4d}UNUjCYJP(K{7iUQasX7VttkJBGr25q z5u_FxLK$V+iM}tJq4)kF9>8drT?9I0$8yvG>O~YeTVfy!xOZYaSY{_cwDp|TJu9np z#^|zj9L%A+Ydu$)=NnLkn{rdvaDVY@6yHDXWB;lyLQtS_tDAgHIYnDxl~DtVV{$s= zBsFd|o)B00PDEF=a~%wgmI{}%>x+5^1#Aon?yyxBsAg@nJr~l^Goh2H9;v|yF6ktR ztvb0~df=l8H!`@X6Kq|gA*@STDpfOC&%1-*|iuA)*Q(PeTp~f?% zpbD_mXj-_?BN}eggF?qn?N&OF*Kb}?H`YAQG+p#u_)w>Prnx@~F2ftg67iW5Y34Kc z$)+&os>lR&TA=wJp~CC7!eb0@-nA}VmIyUC6HY&a$of|T5W$@F>HAfo2F=#Iwq3o* zqOmPCXwQKnVdINE(O`_3)|)IY4x+I%UiuiG8)KZZUp`Wj^*07~L>X7gtM42YI=sP{ z`Y+$T(+JJ))?6B$<;L8kvz%%_aldWV7ANnQZG5rzqH8!?jI{RYLkK&3NIgtZN^8x6 zGp?*hA8N4ZoWTPPv4G}%K7t&0@G5pZzYyeXSF%A(L*Ep@*)Jy>l?3FQ$Og^fE}47+ zo#OR1Us1p@y{B)fkjv~?j#9bd)~M#m{g%3N)2{>uMTNSLJbp@H0Q7zsinG`N+O0?W zFG<`=DK%S#SVJi3Y}Q5Y%csZTLi2t)ChtG`mra9KcN|;hpiw(ZCNwZ03^kGJM1x_% zi8+I-%4QhK(<>!kKTzQC^cI2^O`tcdyf&;AA;L`Ee!m(AZKO904ffG=2~s zy+5@7Ni}_8qirCgG0P7KAw=&h&!$D0IJv^u$QeOlszJQNs`Z#{gr5dlU zrUhJ5q3_(~esFB{Myg#YmwlhfNfp(wrGPyO_#^;Z=>@ZNd8I}pOE#ghDBUBEVKYB) zCgFa}MLKj^)1&UF6db;x%9O+XqH6rZjC2b>;F&n7p?yBW;in;owg(Eix*%lbLA5msjKe zD1<+qoxD7#!A|#ZYj*kz&HpLq1Yd=&8yfQ;;{{LXUVx}xf?H@@$u};Wi~DC?(BKw z-H+tT@B3>|@+^303B*~3ESybUU~V2S3FK%xiTGSL4l*Te1ZmPT6=%F=_7$^v0s+53 z*w^|c=3|3bu11{+-7af|PV;Bq!hLB#>v4N4+8RhjJt;WA*pt0dnn6fRX~_F!4Sp$$ zF}H7}b}wTHJ%|i$X4Sb(qc{5+Pc8|nd;iWC!(aQUor>B}h})74Y2693SS)#MzI=3sjfcq zyc>}yCH%n~$UKcEj7>({8)V|gdASNwT@9T;EV=JsM^`a0wY9!eiCKNl(gZ(kxqBlFs>!VzUu@bZ z5VG5M)-^V%Z=C+C(EYcyfQ}s0w7vAT`6I* z^71P(H154__x%1VVSlN9?Opt0Q@RwPC2B7du~54kT@O$pjyv@}bSd)}ZBf-Okff(n zAh>Bm*en4OCR6L(+6|q(W#qy`t3_?8rxc-Vz_c7n_Yhv*GhChy`hc`pMjsPsNVBt(gK7zZs%o{TmMFh1E0gkVM5P}@@vHsig^>nY9*q=>jNE!tGsD+i>A zRc{XAiSRPBsaN%A*zM8kY{`%<;ecBf*`ho;V@M9_5i2`jz22+wQ3I#TcEx!T78`j$ zvtrQUWr!d{7C190XqH<*Lx<$Q!N{M1$edtMkKiuz_c!WKN}=?I+8MHu?d__c8hx^k zsH`AH@@H(q{{{dWaF6CVLo_-WF;>RQgyLy1{Vwq`zT$A2xgK#uB%95=&bUt>Tz6LEp2cPox zbTv|4@Hu+1(GwO;&HnaU+UvE}H?-Dlf__|)7cBQLYV28ZgsosoC|@<_Lt*0xG=+gnQ7np=yqV!u2$WSH+_lRF*Nv|7C&Qy! zAr0sQv5REP-cM#LYLXhoQRTjG-F&~67doNiZ1dm3^NZk1nddCNF-SXetDl{*%v=n$kF5>oP|XEbO>P8cMmGH0DWGA@pr>jVlF{ zn=9AeQfyOG@$>M~VoW;Xc-1>d`4Ff&{V^8iXj=HnVhe9Hn5%zt*r`zeNu6Vw@ z`rfXw4UHdZPp%GyYetb_^Vec=@J+k5H;mji4cESI+|16OQ9mW> z?%r^<>Toblj9QwqYe|bsvuVYP$|TWHfkA}}^+_B_?0Y$N*f|PJtjI&4Nr9}#ANh-Z z9J{#n@^m__AgEBtzNa7;7)U*K8`H8CyV#EO*&CoY9UG zzd@T;X113j@18Xf@b?GhOHPHM=KxYJ(QEY9PBtqPIK)8U4bubdWzzH` zT+0jgQh+H3o7g~@JwwocXEYKnnGtA{$hpHW(@ybFwYC;`xu=|rbt8k`y~`t3#8^$? zS-SN;=^MWB6!-d_O|q)=EppNXxduT-1+3ZPj9!{SddI%n0r-5ij z3R_;&xPl?eJ23o11&w%a#7xWDn2llnt?hlygk3D{*Qm`}Z8yT8d|-^_1P*(mO$Loz z53O`Z_pWANMRfOQrL{S^R9|`H&9D1>CPPjBGxO&u?(e*_Esx4}#}aHyDCNqc)?54# zbXW9tbhpcW+adEuw@iCbBJ@}bypKv}>*Mfkn-5lS3}e6WCM|af7)_nsiqBn?7xxTG z)`dB$IXmgUG|8Y<;Dp$S@dRs84XybI4v|y-^A!tWG!a02jB6*byd?bR+y8(`lidnd zS$Z6Eo(H;B6VCfMd;P-w66(+AI1{=;1IiFjoK(M937h9~LlpW~?RDX=hMXWyQt2Med$te8U`a7hIBbenAjTntn?|S}mP z9K{C5h<#+Oead)mIpaD`r8CMGX3CHX>TDn2x!rMIlHO7!`Li2nZaJ4#MVMSO)I{@_ zC2>*!!VM($ks=38iY8B4@Gfqe7znpnzhY+K*2xTQ_O@3?0qH*pF#c#@gO z6F2IUhgv?M_-KDTKfQd^CAwR|Ft=;eqv$-M<>tA46kFOz6PE1k{GfTeUD2BLO{P+1 zK2iPf>+s_`hk*S^-{MO7Iqq&#ET(a=Qcf|xjzB4*p@v5$dt??0>))+WK1}_DX;70-YpD)?) z5L}2g3fz8SpB)0qD&S9wV}Y!~^9>B_1kNhM&{$Wp-?Cf$==RqK9wpofR=Fi(9XzZU zno0UADjhIN<~2leys&e7-s9Et;OOi2`x#MaerISD0H>QossAck?1pm@td35fX?8e= zP^5gu8@5#_8Mpoj6||dkI$9bwo)x5=Z33@WUz+n>wMCDk`Ht=V(6T?;NL+t;Yt{9n z6Fn)68mMQY8(uI; zSpcs)ym#dr1BQAGFdlFWkDP@cR0?w+`F+>anBd3H7ogw|Z868q^UYwj_?23cn;6>) zTjNL8mNg&vslyQhfuws61;8k9_+=$-^#P66TiZ|^Gs9fwBg@a~)AP=lp;1-1Qh0}% zeVn_3k9YP{YV7`&6Q)Tpu4J9tXqKn#em_LY)fWbOdFnEAE|}d>T_46irI)x6dmigs z=EpQ_ckW%_>gXD{^9eeF6)^CnRx1zZU#(`7bNZlo@SxT&ElxfH5BrNJN_8P=tk*-o zLMnDoIe#DTjP2X~#1BJrdi%Kbou56FAIBJ1f-s5A3bP25C_Y_Zy8R&F&}UTBcQW>IFyN)8p5umypC z!eXBwVy2kjCStMzqAde#BR4V^7r5CCYuhDR(boV9IbPOpK?y*ldMmEFSIJzlR*mPN znV@~%jwT+bC`#=Ki<+oX)DJ&DmP;<^5eGV-A~!um>lWJ=Ew-Vct`Vb-6BFEiK(sA- z6Yi{n64MoW5DI?HL)mTf*e-a_pf;r$FvlqXML7>yQv~c`KPkx{RXPPC*Ly?Bn8N7^ zpdKGt*{3jd*(3|{@TBZ$_cwBjefUV(WJyZl;Toe zRA=DuN$Zyx32J?Chl(I}Dxu)QcE2)kVpc7;>(k-+aeN_Tkf=?2>+2i0uuJCGd~r7x zK#-5DunW)k4X^Z&i{b#Du@qdvYB*@d8%%Fy0{&P`j3)29YM=${Noas|5|n0_CT6qm zdV=9OR`V9b4|0uwf;=rDzXU@D{g{I6dfvDS@IVgKOnJWnjY6>i`Z!v!!c)?w6T}*d z;Whc{YXaz{8Y-nWg}8$A^pvv?nLXjqJGzt zUFT5cU4EQ~X6(5L#|_xpD9aQm^Ml}ud`RLYCbcnG4g0Io~sIvIEYyVo#iC7GDHG6=3f3{r+#qPbcB z6%6ANJr!6*_^vsTUx1t@WEus`9*bWY>7`H`B`{LN1G2&Psw#Sei%8l>~V%kCoO)1!U%PZ-?q1(Kj9MqxwIvsz&c69LC|T@RWJNn2?v z4sgvxr~p9^xN;2yQcYT8sq~4FrjW*clwvu!|Z@(eM*w#p8@Hj#J ztlrKb^YnJWAT9&PFxDMCtx-OU3phEidE06KADprgDKCUjqkr<6Ql9d+khw>~Fn?uw zqf2{x^zA536TdwVX611H@BBi*FchO0Rf{JZKp$SiMICCZ(k|E*qXdxp5p^eg%mY?$ z#WWj3L_g?AdNEh=lu(Ag_eCXvKNG0BxZN32`wM&|TQ7eoG_km(!6tOx6K;9l?A}Z! z_{OsImzL`5T5jL$CB~DPj48qOrl3K5(u~Qzpr7-h2@bz+%I-FlW*n>(#JmOe<2r%T z1dw8g7C*?e#<&dCmq?~Ao$|Ap$tbR|0It?Lq*Ci0iQ~5&)H^TXCEZAwHhraqT@Bq( zT%?{E?^+cN9I<)?jk||e0$|0Bn5M_BOWa+lTgH7l9ORUrt9Ez|MPy40ygJv0CCr^5 zLxQr~!plS=h3sXiU(uocC|G9#5}h@oRy#s}^}U(;!e&}h*oNfS={(xyf^5C>La!eI z^bF&lIJhOivJ@g$RFaMAC9r!eSJiVLViFDIwK5JISj$Qw)|RGy!cnU1e}^7{+vd4K!#p;D!VTHT>3Aya(1EaP$6R{i51G#lPKNCr!Lrc^?LE9=9Wm0J%RvqWG_N1z@Z{{KfEjQ;7+OKM$yhblb6 zoP_MvrS;p%@HJWcJr0C!6-+|oI((7&mA#9W)v`T|~`~ z8!YsFB>lLLx}FG-o&J$et?|Jom=io=K)TVx=$(fVIx&_;x9y@SLIr-vXLZAQD)5Ot zCu?#@b;T}K`7BvVcQvaD5xeOJSs;o!ayQFIbLiH|DChjC`RJ`l&NBWlVC8P#D2J|_ z^AFs&2g4L%R%`gI*`g)B@LB$Zq-hj9yh`=i^onn~&0l5= zrQo+02j2cs$lL+nqyG(Pk}pfX>c2HfyyNmAY!`$YI3P0cWj>p^xn!Kn!xw9npNv#z zUyKpcrH54gI#`Hbxd70%YrBo}Iz3h~{iqlvZQ`Bi`Jq;7O(QdiRAUW{DAEWi7$XZD zxnh>lOx7nzwS7ONC&{mZW1jsfzNrlGMI^WyurJE>MQAuu`k&ac3pWCUJUW$D83^e9 z204GZ1C+e4Y`FPc*Bn&mP!&j@M`v8UviOC6ce?)3R8>;}Cv&Ch7sC_!{fD(?RcT{+ z^On{2L*XG51j`Lf1hy)9q(3wKxsz^{545xWm#aroj08|^P2h>8)78G>)`Te`$TSg= z&G-K-y4~TcGFuB|^Tn`rh@q6DObVHdxXrIer%G(rmsNKORvtW@)!+hJscpKR+Wi+ z(Z)PFOo!5(^JDIz$0ulg#RK&!t!^l{J+StB3RMPjKU*x%g^P7PH&oRpd0!y8oz8p9 zcNdIzv}YrN`jpW03X#wD#?YqNu||THm2%W{XvknFrw}RYp)FV7GM+iuV_%>%O2~f| zzs+O#oD&G*XHyJPVc2_mZ1ivOn~GP1nS6#I%kH#md}U{9%c3WM_k&&nB^48fngj?L z=^whNO7)P2lZ=<;Vj;N0G-{E!xbOPuXHAJBjGTJPN)PR$0bJr1@j_M)C8gQ%!IH;6 ztJEmQ5yxo^1CGj6BQibVc^X@zc1fI5e9AiyBA+$a2z}ljaJU3;TC8oXMBK;TV6d&z?bnuVI{S$o_(6 z`50i`w%L7sfS6;iw|ZfqMO=rBfKidwh+~}MoJ#*>(UCpk`9Fd9FW@V-;UUbKGMWTwMpK4Qy2lZF35F_Ew%15u{gJ{n+6H;oGFuq0!9 zRRg^Q5)^I*5TcIQ0}5o7%J8!XA#AH~%iVCLZs}2PNgI6;Prk)$T#|jjXXEri%_4x_`>}oRkV1}RiqR*F2e)f)Ez$t zeV=!kcPu`{J2fT2F%xH`&D5Dt!Wlur8|R1W^}aig^es+6nX1T2pFWuiKZ;^4cp4me z^rGbh0j3s1mUZFS^Yeu;LAU$!!{p=Qy*+SphaH)i*2)O6O`4oY_O2+%5IXBe?%Gr+ z@IZLSMIdTUAojwWH@0K=XCcK9%;gBZ+vPy$!kF^az0UR_o9;@po%gRP?~-<_ZI73Z zyZzOWCYoRD$o&j_EO*x=4(VwnC{QW;lP~iVaZPRz{wEj{idSCGHv~Kw>KMZh4;0nU zE&EQHI2I2Hy>WUPoRb&x5q0z z*?OGkHk9AQV$0@EH)1d8qK-fyyKXvj0ept_oeNyg|d& zcW2LHV0&*5=Z3FOZ`&2)U#b7ZZdE)Kr&b&T7Q(lTjJ`uBvy0pK-fy&68_v$XY)D}r z;q&D5O>&liai(EH5Hd9+mJ>b)q7&6%$H{veWqQH2ZZNhMS^et5TV~AA1vYq(8<_M{ z3BW`8tYGI|T>Iof5G|tw!J;2`>J7G>Z00rLCOMFmySgQyw^@iEJS}^hHd&s(ab#%1IGd${~;3IHtj~W$33R z(6Ib+?kK$wQ7gph{rh5Z0?Q}3*|Qff?}T(gRpI2FMJ2ei4IJ)Reu&1->`xM3!yOJP zJ0NzC=8)f2b{J6DXCHz}Hwsjux*qXQJk`SrBNIxIn4xO*!9V zgNVyVi=oCPlH;CI0!>T<`K}oEDl%d%L)7TFP_42(3W9myziSis_0sYd5fH79)nkU?>d?!|jGpltD=Nx@+&6 zvl?y!+Y0!JyL-8hKde9D(o27`fcLKVtB?8-B&8d#)@!bf2$t}+gk@QGkzOCQS`s>9`iQ5<(KB;2!_r1 z3kKVK0c7wEkeTK@f@>WzC*OHvKTN?Y5d#s}S|hUb+k$2nJ>ilngew_EtyDJMVXQHX z6Q49EZGvGnsF3#+0X$b^0R@O&`ZDD=vtUIvIDFaL>WUmW3wvm~?gakR&8DlE6lL}h z<;H|_{zwt6tp@#HzAa%)gA(4k`ns_75fWkV#@GwL_|=jpqgJ<1(kI2-cZ31d0n8%{ z8gT`;N|#n_%YmOKFpC?A!~}SUU$8W}QR+2?>1JWoBZZo9^k@F6z=|L*Xznov5`Fwc=50MhI zp#{}viDh~-Juls{8cu_;@q5gZfBfE^!)*BIs3^gXBx$g>xF<;s=-GBi;4xw{ny)q z{rX2{?H`KA$v2wRd$ODCwn%T@!RwwM@ZYZ2M2({M?yUsU<5w>LI33ra&+mj*!u83W z_TUnX2GMm=J99BJf?%z>L=Dp;n{_#diLCe#5Qr*7&h-r!VFVgE1jiR}p|wr$%sC$^nTY}>Y- zY=58KclY-^?{5A6>gwvGtGep`T<4q%=WcLknA;GVV&mzBSy2q$9wQ2_bHTH6o!-RM zoF^HhDvm!{&AN>@7BX!fFjX_)^XG9!({c4x)blJq-YoeqFMz-UN_|i9)-s)%!6)3r znY&Fm^A(;*Crn{^m^e)RhCc{;X=tQc0pQBW&j>i>Uw*M~EgN#feLj-k%tS5K!5*%x7HcLAXtIVbcL{Z1p;(eCqO%WXpOK)2{-c z9e?tF)`0IrV&>8KG$6i&#-g2W2dH`Ox$6AX({;mrIJ0dIq=sc~{5C|?$|T^ljlo?u zagUNV3~~Je`nCJ(2zWNka7)2R-7gQseU{e2-`T$0ujfzcdSb5V<4P_PnY>5yZ@vK6 zG#(T&4JEc7^5mPjoO?f37Pqa4gNje(CbNS-IxYoy><@^P<{oWKfTYR~$ozuU%SDBDri1}HJ zJ;bz1#AsuiLsn+fl+7gXK7$iK%JI^xvz5J&R@Z%7XjB4+AGZ8Q_k&FZ{`+zMKksau zp{!606(s<8!rWUV{IhjnL1lf}R3K|HCWxTVAaH+pVyNckn>dvJLor_5KnlmAcwS8k zx8#e05SVc!u|rrGut38&0-aT7B@$ol?+`H&nmnCa#u%pFsl)0CJ1XQIq+x~ukCnR` z&!~x=(@N`e#rqX$|Jew%hqgqhDq;G2BiZJ)Znyj@>PU9rGLC-!qo*II})q%K|=u7{c8GRY@fZ+xn!naD~BSy>!Bxd5rvm!dLvh-0NaMgDHIXL zlIa0fK&YVfk_<2Tp-)Xq_RHa(iC%PrPA1fyK0+vM@wDe13@n|tA0bj7ljm^^w76sp ztDAf{H`L;&&1xU*@0bivT;peWZt0w)<*>EJL%CyaA7c{~vvm=}2O4V&@$c1F79}dF zuj3@tQ)4-pC&9%rg+fKCfp{Y$MhMDj)il5-3=3mDhAY`bz@5yrG zq(fyEww_6pHORDbdVcShcZ^-sZHh5)@ov0^e}qwbyjnca!@Yq(*+B#5s_r zVlLhgwYVW&B&+@rebtL`XBQi<461Nq&n*@Mv(s{(S^;_ASg~FT z0q(M7idn$_-r;l?i-M@dY&K?0pUh|D_Rwr{*2a$7-5PtoecFiD?KfQwde43b zZ+9UWX{nQA&~Z zso-!xxA-$%<}%N0O$aGU6YoFIoc zC3N)y_WBER;y`(+#+1X?$VCHAeH?v57lO1a$q>iNe})OZ!kuqU8W~cBaA6>M zYb-lJQ)h=wu9p^W*lf{CX4^9JgCrx7sS+Qqku+g@Pd(SaszIbI=hqImyuV zaXvHcO@>SEMnWI<-M9RtK+dtCUE5kFBLMhK8tKGL=G1K0Kd-D9A(@g(^Y_6QP>f zb?z07>g)Mo;esvA>~8@RNnBuHxwr0n6Q(AwDoZNjg)ex-YAI^9VUixHfWg5u~-=Z ziUc>W6&i^q4V+3mzp{Yb1t64)3QAVGh{Fkd@2Kjpq)G@g!f_>hc(S&dt0z^t^A-4p zJUc%V{Wrp+1`3&!22xbM=Y)7c#AZ_P#q*#na}qXN=xg&q5KjOt>WJsW;kR?pq2}@w zEw|zT7M10j)qv8)|Jdmx{y;_9N8=RP$l_moWD?Yrv-W{OdH6#E%GeU^8U(Hrgu(LJ zdPGfVhL}}RdvBYNJs{2GLZqW3-ktHgJ!Ynuu7HhclF^*qr&BqB3tFTSSA+tRu@|QA z87V?d!v%O&@;l@3+}G-o;kffPR&x4GK|`yILzDDtjM_FLW6nly#@-paam`tm0wyui zQu#3wkVbr7ym7DzS2lcHa{m*Xax#fMI%i{J)Q|c);PlxKC>_Vd>%o5xZ=Q z6)vH$f88Pw2MnD^ko$SBzWzvMmk%SqRvR9u6z3#iSU8T%iOAj*v9yPSP*=}HK~Wlq zA-M)(Sml?6^&RoG=4CDJpXwMTe<^bqB?`|?^^)(XPLi_l!PTW0Nu>$#j6Qr z3cxB#X;>&>(v*pscVJNHXkmr*G z_0O-DxfU(|y}9m$1vS^V^SZT-|EK@>XXfl0glboU->3bcA92=*==v~+`Z(`unVsDO zT}BD|mNo2un(K6F^imTrf!R&{&L7+n`_>-*x|anRoi;?9p4TE7bF6BgH(deAKLvU0 za863&MV5W~Q448l@ud@qW9iPy(c(~dZ53Ux%%}6`u-a2n; zG8|&$FI3T{=(zP|49M%!M~BQ}9N7@)l@KANPggi*C9IBZcq;%sa0;dV(picS^9v*% z!zN(%z}40MKb$6U-IVAicWp!7!va=w!i{ur>_q&%cl@)jf+3q}0IvT<#$p+kR_7F% z0Z%Z49&(x;u@M}|_oy48184Y7mHF*FsZc9RjXasBeA z4UE0RPs5rZ@Ek_&6we1U$|jRE9vuh~R2v^66G_79L}1(qCiW>Uz?Q%ly0<3#YtER1 zE~$S>|Ii-TO(R3-JAx^ktRq(KfaGRBkSr0%&)kl?A4MsD=8h3q0V98E1yU#lOk9s5 zDN5*8Sf*q(9p}Ny1^gX=2`=<*2rgmM+02%sq$_w1#QDj41dI~KBE|SzF8)) zpZl7mF~YkFW6|?h(f7;}$OKZ@P9X_Tg&F^XnX#$=8leRp8h#kl`h+xNkO1KFR{@5; zT|uUJzUby~xPVoLkTU9uzH~^5Yr7>6s7n6Dw2D{cDfLd9Cc)t93X*&gU?CHd)8y>O z))63otz>|0qJn#3M>mAV6Q}nimdT4K49@0naP}FLe>=goaNBnWjwryJ=(!LdWW9Yc z(@uZCn|gy6l&a${;t*gHH?90az}&w>Q#?#FcX%tF>5d&bT8x_7IVREC|EJoMfpSpc zlUkAp7wq0a7!9trVd!Rj5}+03U}!mI>ySXY`07=0=c^9R(xhy2 zw7-~@2pvswtH&SpOh#ubIFFcxA8{Dc_l>*q;HQl1<&DMTrOVA#Vlze}Of1y3CU!WNRK1XX-=l@6lDBWjDft(wp&5?De8Pl?!<-#EZ~r6?4jiNnoD9&?Gb|g-~w_E37sO5xWwB=;WLe8+&wM_m5G7&H(&lEp$WV+Jvu@ zMl~s)qIOlN*M){6fsA=za2;uIljglODpMy2IS+GeOY+z|Gtec2QG(w0$|m7PRNC$- zzMc2#AWLD|;0MIS9IA`TJ-hH>q!$u*pAU9q?|KXR!(u0r^D85_cCgzA_uZu@_DL!; zzUS!V-8~4ZS+#wqSfTuA(3mj6$9DtizF0sx2FK@?X}`BqnO>A)yIiY&j(QJ#~oL21qYsd%2K_*OMSuwgA_Igg+myCJN*4GWYTRRHsP*N*OS3z1+}x zmPQ3f>{E^wS$2Wv76muPjl$L8%P*iC({R?1UiNdldzPrwICU8G0c5^7WJ<4bsL6Ah@`lOM*GiyudZM|(sk*n{6{-;~mjEXe%L>^>3UYIA!{`ww;f%#!7$ zF2v|+@b8z9U?)X6yy1I#O`*bn>#-b=5THp&+@PC?!pNU_eQB|b*1z8pm~;P*A_?aU zY9y-y-3o?}XmPQd3@L}S)J9A$zWd+8ybO${dqL{8rH$Qim2JCejarDHPRZ<;ut zF&T4{M=}6-S#1GFYw9?K6tIi_n8P_UtYMOuP6_Om2Bxe(TrrRBFLO@UiAkF6&Oyde z7c(Sn>kqWjnm&*bTd-=f2GD|)8KzPKGe75FQa~(7aZ43oPSSXXM_MM9>c64YX)chY z5O~}7%J{j*-Yk3EneZWTLkU;Wljv&FAHj>x1fk`PMc;I8RP&w9*4OB8th9;4Ga){b z-BQTwl{ZOp)IXp5U?uu9txyV06S52;qgP5I-$5F0@;3UDgfdQn4=)g?ACLXafmOp3 z9PdiKom4pcK!n8yNsD0OeW@z0^I>vkJ>-ryE`pGFDSvsi-w5QnBN&0~dwWAoZbY{x zbvlPAUi?xk1xr6(jj|%{oY!oLj797f#a^{1ypZUMWo9aq#aG7!0R&fdXCvdY^O+5n zc#w|DA8ShTW(S4R*()Ag{Hy>l|58OBm`#J!>04( zFsklfdk>ZlG10Bt0YN;<;-fwBKM5ng3M?89SrO}qbpbjUWEP$%B^i`6<$2bP5H z?*e%$LiJULQIqkM|HAPr5^x!E%qu|>86y!Ys1lkf3qcI{t<1`NCIAMMg!dFn66Udx zts0wf#}|1T@Oc{Hd|#Q-Uf#t49oZfooFl|Q)RF#eioBA5z9H+)sKVb_0**FU`7|-& z$F5V_*x-vIOQ1U?Zn@Q>{Nr}F{FiaxcHJ+x1zF%v1F^S6Nado50^J^f3BwXpxArKs zv?%-Ef2o6A-g!_C9Om2;7)~ooAlu=U@i;>~^yAyyp!$^;4@~vauq7EY=D`m_EY|~1CgLenbYx(HRpj~Hpy$E9h~FL3pGif>vc|9oh%En&n-vKj}eY? z-^!=5fQEEw*zYk@(?mBkb6fo9qfTV<7spu_UeTu5oimLR-y)<*@|^}^p2mH4i!r)d zGTreH2P+zA2Jz5BzfXEekx$O3fw!8nD!#$6Pl6_3h{k>Xq04)kgKR5bA$Q6*l&J3T zfbBpsAJZrA{2$X3PYL?`_ZnQuQN?a@s4WD#>FTo$`nD;@uxRI~P^RUTm4fz~u;fBl zKYqv&FNMtvd6l1e$2nVHx*bx;giMV>rwjnc*5D~6nuB`UK4(dB(c~J;;M^KuJARhJ zN8+~z$J0=ulHdq1$8JOO)W?XHDZ31MRLI{mRS}B~L&T zX=?qn^|sX}pWwPgemmpJFxjHUJCnnya7n}7k;_#A)0hI~^lvZjbE!0xh}R9}Q%=T@ zYXz_Jh<-#z*&lxh0`$3#{>;}{76y36bKV)!PSJ%AXwpOxi7?MWkACf&0kV9}AySzB zuEY`Mr=>RFqR^)$-V+8tH|4jZ3|NC#DuzIo<_LqN{DNg@zOE^MVdQy%a6o>u=8T2U77i=aj~2PRts`5dR)N?3sdP zF<`DR&^CkT0|7W0&5W8AE#(Ygw~Jx#&leU4B~Tn*&{j5IDe~g6U8ACec@`PfjYls$ zPzG|fOCGHDUAfU-OdvZxlDkIH@(3eHn%l2GDmgmfY}&_}{Qsxf@Nj>hxZ@uY~anjZoHot+} zsnc8Fl$TlnKM!ZX+SVe-SC6AYyykEGEr4GSyvF?Zl+%u5f6?C@Wl7+WTbi%kBMI>A zQxPO!3YEc-`}iJGg|^w63`5h*JA+q>CJu{y6quz zOI(a)yHgs^_*r23N+9bl>n&_prmhiIP2nQy@V{s^H-l>;sAY1gSe7hFP3LO@n$QRq zN__lBMPXAUl^RW;R@{>MS}nR1vUeb~%!{Vo8F}mG3pFY8E>M2aWcDw}w%fET;8oZ^ zpS9>cHeBp`1|gNtVlA~>6MGDDCz4<}P~&nobBsUkCCoib@VU<0t3Q3)j*E|PI@ddn zKk)g7zkfNCPwJG=TCXOB+MI<8c*?4qe6!ajitGoGcl?v5pWTx%4I*Vpxoqa#Fw$_% za|eN9ok)}z#%%p@S<-1-#gno}%LUJuAba2#-!->crYGZV8L-8<>shh?@8r!IJKP1x z%MnF*c$k4^3~DT%ISZJ6QaE1V=<(5}6Lo&Lm(<2`32_=Q>bnMkHGe6XqreMOPFJgc$+jqj5r3sNP(Dc)jITXlh>0C)od89A$^ zTL8nq#+(1?=lWmFlr9G-B=z3w*kV!rZ&kYccOt*5S&&f`7u^fr2c+NUy0?3A@$l}y zj5<#tU~qb%;BFQ2gs;END`>4Lp#KCuL9y6nJCOPNi1%Y0waYZ@s5^ORu9Dw(uF=wz zkp{Ss0TGA9(WOIvm4(MtK<61B&5KVxKK-2t~hL!k>x zE`J#{k_K3PM1hF@kd=#rtj3nHP5Z<1%tl!c+IEK>-E(>#xVnk#Y=eN{sYCUZFcVg_ zNyt2K+l6x}k=BHc&_7wzM}96h^?mAiJyl4Bw0T zzNHsOs#F0EH*}Ti05=afwi`J~) zc6wz2sY*WJ<>PfK4BCXyQqJIgs{Xv%fVsrc6Q*Lz)kOt1s|hjd0i$0MYUP;;ClKH_ z%^+Zz3ZngbCUp7BoZy_ax(RWEjtKnpEPO8zw*8JvBB!2R0Jg9R{LBF68u8aqLuEYOPbj)z&z7Y8k5eFVy`WZBr{H^RY)AmnE z55VdAdcVdQ^8AcXG0TO=OzeGSiBOyN_og&i<~HT#1?Fwh;cv2n#88nS8cpctGeN>J zt}cA>@2G;SAO?RoV=x_WzB3pipViqu!NS^Fh`<$zwsvIXzSHyFJEIpq7{0+IX!#+b z)GR;2$?LrWZ)r3ekPaMg(D5^9kc-FtVhgaCJjWZu@?Ty65x3QAisyM?LaM3PCV#`1 zst&@5T$pB^j2mvYFHBsJDc~GjPW%xT!L6PM^=8l~T$lXR*d%O^eXFgQ4_B}n@BSu@ zkJTZP;m#1tA{*B{KOAw-2RF9@smF!!{t?F4A1RiML$FB(1}AHON`>oIGPL_p5(pJq z!!EB!Uy(9tOkt(A_<@>tKs)1b@ay1!>)|tqk1lbt7G<8F2rn<82Udgphizw7W4D*4 zw#ps((N(g?kmN%%w8IVa8v=&TJY#JSin)yr1g{hf9(k{FcwgwoatGK%sRz%$(oMTZ zjyM($sMKE#AwjuL%a(wK+!0by2HgSlLEi4hYii+e=#+L2t}a2Or_K+N?Zw;Ng$ zk;guy2Z0(&lre7@vt15?!k+IR*fr&py(i}5s&wG_@JB}A734W`3Dgu{RKYCe`Dqd4 zXwDAla6#IT6OZ}=AT|ri7Mqa{*>+VZc-I$7r2J$c|jf(z3Xd#T&J2?LQvfrsEBQ34vO59=nCe~k-bq6gn zxHAE|7n^=O{N8F{#CK30=SPU-B4fQ@*j)`AIYVdk(@a@)91RxH^B07;`A#n=Y~$(A zS?pL|dnn_3kV%y&Y`0t4zk2KeA4$X?TW$h7xp;a{vNuEps;_v}3Fbb=Ug@Mb8JRfY*aq8#|GK z>q&s+iv`E@k9rmG;ajnqXTEn#Qs!iJhAN zau&Jpr zowlc|>=l6H9dY7q$I5sNzqjF_?!Cl{KzdAmL6{}?LT4a5IPIaes~FiYw+-#o_zW%AX;5uNyAsHU?+-4DwWdG?6ZG`aO zQ|q^q|LFOPS@HKt{~i_UApPb2JX-R8HPB|Jc%}P}dq@1S^}h|V-B47HGc4Okh&^5p z>dpCFYB}i3z`4iGTcajl@Mdy91qg~laRs+OmAAn=`lhHSFvL$1mDm&c?zX6}8gyq0 z4rj1~dUuw+XPw$98;zLp9UW@t7oz`U$5}>*4Hd5gwl1kf=q=Tk6sinzbi{N!qCD8b z*^7&8@Q8}o?(?Ts5vt0%%IX5M zEngYBU=3O!Iue7jR$%5vsw>+gl2V0Erx-IT(zhBK1gIBtv-1ecgczBl`9mMNnKVoW z@JpPNwxKLaqzOeg_48Kkguzco+uOfG>DMA|qEvX(ti=9j86+DO- z=_qNmK4hoq2c%$+FIm|@a=tYNB}#e-ajxQ3slk(oqfdpIBrPmi0Cuiait!)J>`dS_ z_5E;_I*k1@HTQ{Cz3ZKXj9-(qkDm)}#j_k&SGNc9KI{p;K8H?aAsFcqoeakVXaA6= zR+WP#NLD97og!NK+HZkn@1idyl^=E&8=^Adq#9w5<$M z4o*3qu|kE7mN?&m_CgAb@!d+^3ZL-Pe$I} zNW$Ehmwyk3&k;3aL_F^{)okypG}C$><2xX9c5!|EXcI3ndwQu;@vwcuyfX z>+$f0xj9BT0Y`R3FTtk)DhEO$+MLR*8{v$X!OlfNPGGX!87V-QC zE`Ag+ou+^91kiG?1Z+J@#k^Y%SLeAJkb(k&Z<8g^ILhE1AnoU+Pc}Cj8#=tU)*i_mT6w&ZW7Nho4pAN3^Q33caD$rOChf#%Yc>G#)K{=*iO5Ld@ z_5bF*bus=Cu@jrYw^v|Gi1GxW-8J%E^!A}6=0tIZTLEp1_HZg?&}fFI^W5c0UAg!a z76-w|fVM+aAhAc<;S4k727gdNFT&-m$I^XZfMA+6S&#ii=)G%QG@4;wxMGQurKrUK$mK&_1CG4q}78Z1t$4u}EKU#$oA;=`cboc%lJ|HW30{nXZ z2)#W1x{XkKIQ=Q>?LRlrHy?TBv2?6l=nYo%?>h7D{H?iEB94aUV14+VdfR!24_Lhzjoh8-lwiB&~Psc@O4QlOxe-*Urw4ynZ`X>e9F$GPJOCg1W zUiVpdM}wQ`Go=!~w_P}W;eD-A`(sVQ$VVr#5tQvIEAv2A2`vTw@(syW+s$T?SaNzT zl){isSu2_TocF2HghofkB0Z%<{z~2CB*w0V;~_xK+*lFXRa*z2RttcRt`fC&n}DIV zF0KWCp%8Pgjo`R`EubEfx#CjH%{u^yi-T&Rug^Fq)W;>MRwYj$Kp9~D8eCHWJgg)xQf&9NPUweGT*sa zP_MP-PS951mmB=Szu+FYMZ2LouE`L0#HCUKv6@P|K>0AaL>T>jy~V#^D^>>da6ZiR z3dRt+jOlesgE9-(j4EXcP#EAM{HSvOpO>vxSSo>sR+~~vT8J%OE1CmH$z0WI+G0dw_(tMEyJH=36_fQ^-U zpM3_Gg-Nl+YDG6lPLcLD|q5-{HJIEUryg zbchP~g_@q0OpDx*L3iU%+_Ym6B={F061!HJ(%ovBc)i;l(o$xgx3l}jW1W=Wrt@ZJ zj;B|RmV@ll5%H8$udmaCe+w8(9v>w2R7YW-Z+{HXNsG-&j|F8y1p@GOL%FKk07FQ` z-ORHtbmMzmT-S}($!Pg(tlA}(GSYhcVbt(eeP5Mg+3ohi>|Fyhf2t2yQ*e6l z*P@-TQJ#DH_Reu{C~T=STOZfLRb~ZjN)vwl!J$PD-eY;_707sFw3_Rwkc_d`LDZA4 z8b`~BMoTsC)%dzqTx8oJU;9_YuHjqD`1w<5iywf?0h}4NA817ul{shH8HjY`(_r&La;!v*zpj4`**0O~tM3S!f4g&CktV^F5RHq-X)d0KGZg+ADb zvRX}oaf-$oO>$r&mUeVUSv6-|TCe?`?eBIU&Tluv&?n<4(6!34S-_!VLGtsH-qmV( z_>!HqnV_IOri$^O`Gqq#2RM8faf2DU^3))LV})jd^O?izr&X6r)Y>O9Pe79sp;sP` z9p_!_c5h9Z7I3J1XN~dav&M58UQ5Ih7RhRuBd+x&eMplN79UAe{6X)-`IOQWspS!RrixE1P`CyWl${hfP!04|X4Yz{-yYm15O0!IwS}JkN=9~Fmsa_~&g}Mx4y@3k zqhKT13I%Doc4}Cr#ax$$ca@W|bfsk6-vxHw;6_??DY=&!0tX-Ir%depWZIhZ0N`xS zAS9R!pmIMXFrs`^aNCAnOPN@jnAC0pq)V3%EROl{AGtrZiflxn{X~@Ge#yfS6dGn$ zNb%g9V!^^^|L!o^m2^L$)CVtkYoOG1{e6FM;~TF{+}2w^W;g}y#V?C<)fDr#%%63U z+Pk|LFyeQ_xzEd0aYsD#l;|1Oo8-{T14S}de!`Q;^6#hYR9qeDLw5q@V*v>&vlQB6 zY;U{>k@ynqBI4}A!*c_nkr{^b(Vr^twSJque*&6r5GIwg9j zWlHN*0Ig)Hm3)HmC7jCVk@v7&NwbW*L;;4K!v=gzxiwva#41}%MM>9 zG=O%bRInMt?>D{1PeTiSqRE{njM}CaE%J`~S$LzF7!0#XzWd+6`ts!33hpf3XEuu8 zQF$$bZ+BKFVq;>MhS2y-0tWOdKqCc`*tBJb?KXaS(?k&s?GNDOVVYzzZm9mnJ{g^4?@rwx`{K6? zfjJ*qq|a8s9mD0W`8gHE(8gS!YQ@igD{22KaK8AYIZ(^^y+v66S@f*veGAD3huB%P z9wo<{Hc8+1&=)&0H2&v*(ZXuc4{bQ}Z4^oG;RnXRzI5{o@SmRwVegpIGyqRAV|6?5 z9xvLi%}=|B^+NnkM;YpF`fb@J#;Sj0<>b|cr_yOIdk)Gd)ZoxTLe9ApC9<;i>oZXg zgjBsV2ld!64h^eCO#g~0uT(TxJl;f*iaR;$cYQ)tAH>M^&xLfl3Hoe%gQ^j!2w-wj*#h z#C>rB-(G}wbB_qE_v*p7Fzn^`Iw2vjVCE@4lAii4Q_B=*DbAs+lJ6m>V->g9nH;mnG@UQZ59WK|cNXf|VH^K0=JUq3%H2bq{m$8SL zi!(IlLw_%t5GV}ggR~__mU<|_l`nQJR}IJ2i3t-2yPj9fk07z(DUKEv{6M}i0TnG< ztviIn>DPf>EddMd%KecY3n}J{^+$0gWvOpWt!+%YuDJQHEE+#VI`b6Zw>OgL?C^~w z?&FlWxq->3?6}WHg*R$w&}$x^Je^cB*vUDF$a)<#P|J`k83GOgx>0s zd8@8S{%;aHiHB4_95L+mvZiK$(`P_qmVnvnu;)lFoVH7Q7veeqt??taBfKqHWD1Fw z?fnl|W?2)rh><>P6nqY{-wTV{VjFUabft!+xyl<6$rcvz?2w_P70t&7WC*p_Xw*AV zYp)pLWk0SEr8-3&N@O>l$gJq$3yP*4@EHta!;@pn&3_l&$_T1t%pWpTAIy2RBDIUF zHzxnAn^3YO!ydWJYkF{!X|f{0ye>&u6=HM`BM@48A#DWbB=a*+-iBJ-3A%))^NHmQ zNnH<4UG~2Sx$POOOZ!yEFtk>|eTV~;g;f(jz&%}i=^lVkl5Th-t@f<2LK?b?Zb(Ms z5AgN+p+rODzheWq$W}I*FEWN9Yjkzu?>-6vwzh|`ro{0A1iv#AftXB!)A*e;3kgoe z^vlGV)DlUJaQnH>v$k3VbrvRa^X%kkLEE~YVG$ts0?i#|2{7m#g9QLu^7g=a^VH+k z_?pbK0nTS>LI-rlgijI}#qc zLhv!6mrt<`nFliWB11e7TAR3+b5Z+8WYDs>gbh`=kx;~ubNB5{K8#2UP-IoDjjw#Y z$)J~iI&y9ggPVDO7>q<;e*3;425>FpZ&&hyF);7!^*FUORQWx;;HRx4?6JjB=Ka=$ z@krE%5R_tlP6Jzum}$}iR`U@Ks%^BA?hiwLWqOl4>TolK>8TaoL4_-&Xt+}dO5%R z<9bs(^!i2~#gI;2B6G=!@Ae#jSZN-ekXLM0_A@GOHn>tMCewVgKalcMNpe9DFB0)i z?zJp?2*S)pPZWMj^{YJNf`jp*)&AS8t}u|Hk}3S$(&Je(;f_FH(ujOFos;(uz+D1> z#kyo60o}6m-L3|$U9Q1T2{-h z6vIOcwJhT5`SEu6k;y$MvfW^!uNHRK^IYmjK)e4q8dMa|{&PnE`}hQ*!T~*3Lw0Ta zYk^uib=CG7^QQoOQ*Noez@i^MFFDhAS&U5>64lnAwEKY!h5b$m)xu2nGYd?KZd zCNQ2|!cpGGY<}Dr9803hu(mGdh(GvPZ!@(e@JnaYt5759Qo!cnkhe{ThvL8wok9O9Zn89@+Zf>zONf>timWHXu7>cik3dqlnIh(447*N<^#(?k8S~ z3hT!h*hA?hs8sen*6q=b3{~l>Qu$l0Mj5fhaS)L*rjT|q2JC8);}i5(GW4#uqACpg z0o)G=j79rsto~YT2I~IS$L^A-EJ)TG2CW}J@LFb0VMYviltv+_XR?>SnfQu(h|`kz zWr9%iS{m{Filn>~PB0z|i!~)N^Qi?Iv`jo6VQkBxVaus89-CEZw)^O`@5hGJRVFjk z_d>Pv=s0UDirIo#+B(}Y&bOY~l&Vj((_Zp#m};R7YWL2ui*|-$y1n$1J8SNg&tVGG zIe2171|3g%+(A|cPmBU8e9lN+pc8}j4;Eh zK!i$wiY)=WL}OEOcT-p7hNmPwgZJl_kb=oLdxhUK=h&hyL&o6YWd7vOE>%@F>GlKT zH5elD&1n+z8o~O8EO(;aep~e@EJp*9fXuwd|Ir@MW9~J{_ZPWTUXb-X$@oDF-NXIL%mp7oO8{F(DDwPz9 zg|3Lxt4tA*2Rt7Z?b?%_M|1`WFE^XZzy${T!t%}E*2swUdydkyZ`Aczk3@wJ$&(}L z*WZ;J#wwP3mnOvaCVd0d(GF$g8$Ma{u-%Qel_&P9j_pL>@50<%h35MoU_h`ljC*da z6r*jj?t?BpbdJJ)6!KljMIW{=d$8>8YUi63RQy$op8uyceF&*kgYIMb6)$F(SH~tG0BegZ{vH;yD(2eA^0)xdjScygq zmcb<>D@j4WF+M1YP01Z2IhB*%$(`EV5dSX#g5fI*=ZlPH=Gp72u1-Is zvtluMYh%|495Gh7{feBmvzNQrob#;kGh^8%xV-nvZ%R{_W8wk;ep+hx7*N}lkO8GP zl%gPj-D&XmK9r-Nf>Z_<3H0*R7zYBKwgMI5<~3|;m}q$*1;j0L09FuF9l|Kudf_Du zynZ%AWgz@Bn}SSZ0jl{%?wuNPVKHdD`oLT(8916Ku4)5lq8Rq!Opxa8sXH+E<5Q7Y z2Nf#eNIs0jSxmn%jjd(8y|)R?rdV(EZdLLbw4Nf>CQ=BCzLt95!z2){O1qpusF+>A z^IpQ&(yb1&84Xp=RhRYl2g%f)v{Ye2sm~_l<)RqIJ7yl?O2OCCZhWv({6_FAzaX~_ zQ;DNlrGZuXw)0()dMJ#h`YBEV zwpg0ML;K@!Uq~{mNTjwhb@=>|d9yK8$&qI|*GuL7&Re$$Kr6iXvH2SAca&B~&FdVu zvgj>*ol0hRBSe<$`I%a7db5NLz3it}CcoyK2Z||iM#M@Fhn;lp3l78-cu-t)TV<3Qa2)ey{H^tSQq_%atoE7qM7y0= zMbIxilxSgYK9-#t)wr5f-7qPae&7^2%gOakDDRH+4O#sg-zb|$ie*t3NAI*Bc9P`pK0C(vcZ zx0OSZ4=l2-dTb$Pzlj!90)~j5#oD)po~-cruwq}QR%;*+k2m{(I#N410#|RO&n@5t z&M`l)NLyYQFBZmQbUvFon2wa-blO)#rRX`@9LtoP@)t{ z8i*MR zMHdBq&e?nIpRLtv->7ALpbC%8cCk3m>=JTG9L<=}5R2A5BleNe21m2~{|?`Rr{!}s2_^}O;*Ar*C%CfN32_hOrLu<=)`sLVjey8EdvgcR zXx_F52C&+q2BS@Fs%Bk!C`FSU4JWQQDwBiM1>4X^1TGnWR1)PN-q2RJZyU6G=VC?N-CbuAZ|{vF zu$Tvb69=yKYZF>J1_kkTJCH(pBHRP@i?jYE6#V;savw)?oC**WUvgOLf<}gg9z?*G zyS(m|Pkc?jCu|-LG7eCF>grd8Uvz>kJsvHU{=)n%XJDeN&YFUSWKUzy(+=ON?g#PU2ocjAd?yapeJ?}%2cHrutP(fTLOq6sy^ohQ`=d86P{S5L*RR0KT50rLyb@*}7%UIZ zp!=#7fnUf-T0S^!lUMpxv2s^CTt+=s-IL=ysm-@!5_tN`TYW%<%~_(t2w*$_=mL;& zEN=qnPGJ}8$GpaWoo=qv834`>v9naZ-2CrKR9Jg~-?v|VuR_;7g2$HR*2@ITTsbei z{_*?E3IHln3vso!-hS}{>G2Bjb$=l^QNE3_ldYUuUz=qxXSvo|DVAV09UpRaWIE9k zj+Cl4_SEMq=JDXMT04B(Dk5@MtUvZ^FPF;gFH?Yzs--X3VZ^RP<-S-t&m|Vd;=t>q2j1!ES0J1}~M%M%c zuv7CiKEF!+N$ucVJ2N#WT&*h(PU)26#9q541K2dSo*aqRjJJlLN7$`{S<4bKcsfmw z9bUVJHfC>_IC_=A_;wxJ$_qOuSJNiyhq0c#pAFI|RB_S4-^t(qJp$8KG|I(`>NXHv z$;J6`s;yVM>GeMOv{_j8nj_NYN8*#0_jBO=97HD>f51_0$E2~dGHTFerY}yF2TQ2G zK*uBUsUwkH8u(q-AoASg9rBz!pys`TS|wvch)%*%sc$j-c6hRbm5_dqtc*miArVRO z@~@{Du9K1FVwgXi^OscRAe{@8xRHHwCc2sAYQRGzA#2;JM&Lsv3THW(5@31m*-@hz zhsNN`6M+5t6%$Txe?ZMwqyH*n^AFdj9<8DI1C3#<=&QsE&(`qt&xFA8n)XBv}w90cYZ>3tWN^{&gB*h@2| zNd)S9k|V&MZs2dep)A9!W&j{jqj8BMK_A*U$#;dN3NyFVI{w z1Dm&9&ZApJJ??ZY^6Z_}vKJX-DV|^lCl-jtm*+8vvEk1la`gma5_6QV&8NR-R{AAGN`G{ z0=-CSU0+%5AY(L<4UeoQM`T(6oA$dBY`rcc0X5iHhFzJjk(NKCFuT@t6_w7wuG~P* zLh$E61=SVaQJm(Z{{ReareNR<=XvQh|K_bYd1lCga{NhU+8*nG{)LOkFIEM99=@cbZbQ$~ykdR-D&=1@$Qp2Yu3&za!Xb3^xEDE&o1Ajbr6J-#potHo27)595F zLHE-Kp(Qpt)bLjA=oW7xmlD6@4`H)`?*ST3er!n7i8pYQW8`NoMqd@~dM74il|t#& zlp}l33tJpAgaTv}b?y}RldI2TBeJI8G)-}Z1o~3^ccI_}k_6*vCws>5gsTToWq%5&M&L>>acav8cIN^x08er0If8!!hO!B(P5T#1g{Fj zqHC(?ZX=cN2B{PsE>Wk)J5kVKNv~j*weSaa2Ge+`RTR*ks*M}WQ{#}(OeunBO;(Z1 z@lp`GjEFqP`;nQrRe)_0ILgKlEvr5yHRoNJ6`|7{e|+7O$^x&o`T3OGMyH9O37ozT zoPgDmrBI?!?}Qx<_;kH>s9nT5jY&%yw=KtqEQDg9gD<}U|5yb`o5^^^Ts68S*;j3{ z@xLqsA8@Y4|27Tab(H9d|HtjC=Xpl`o{fUv<)a()>7fnp-uEe!OiPU|_wVCEJHg+0 zAyA{vgWCha57mF5Qkrej!Dy{J=ohs&4FU2&1#Qv%C5x1jL z_<6wjeW1onEe667s7C!ch{mnwnZp#RJS^!xi)dw1uliB%v{*gnZk6a{eqpSSv4VX_ z$q4{<7)ErYCtK`>R1ZAM@RiQnZq^Givu1CUOZ_KqlLvX+V2tMv*&xqneH0pm5L#fL z1`6q35@0L3LYnhxMrJ$5@Jn{d?z0+dpok{@qEDj2*A@>b?h38%#+$XS2|8h7c0IX&3ik#&~Hce5E|J!hgQY zJ`_X&FnLRe&Pd>yc<)xqhK*sECJ=gog=ptM6~9_J3l#jr(SA)t*Q#++do`nlF(p_OCaxYFOpMOQCBBInu{RoFE5c0bqxBW z{>0eZ@nU9Cg{d*zdbUw+T3;e>%0mqm7Mur4)vt?O%zP3&#f%^p7FJs2M!3Cr=ybQ! z<+r@wphZm54VEiq9BG8tzV!t*Y@BSG8}%dlu~oQ|#F zsT@4;WcBF5F6ddy=HX5YTc1_S7;OVl^RbkLE=AwM?xcX^FHJC0uwOZHE__#RfIX~uZx-fIxMKe2C8>Q^CbjK! z_J;EIC0a?|7U#b5w$ElAFzm>Tx`5~a?5c`pEYf_I*=vDyM~KaF|f<98uUz=tNC8;Z)Jju zn}H=E35$a`HeuixFnvwicdT~?GVhdJj-*TpjFMUl;n87@KgphHeJjC`UW*JKdc*ZXK* z`bL!om^rS#kv+ZgUST0u>Den&wqNF}PzE!^uEqzO6yxyF8at%lop7@zEd3U{U~j-$ zjca2NIE#ePiyLxgW&S!b!L`(6Mo?!K#N7bw7;M^7RjhM#Y@6GH=k@Oc;K!f_ zasIQ?J>s@Auu_ejS;of`5`da#=<%+r1yrh|Gld6|vxC%iS6;C{Iyc2s%Hxg!?W?Ro z=?$mN*fZzc=?#%=X-|upgJCe%hd)wZ~18@{U0dgZ=&qp2ImVfuVeaA?MUtaD1CpFKY^}nALI9ZA8dK6 zRbwPw`-^h^xr)53o~xt7$aq(0W@ON~j_Z8G?XO3H5>LiUD9%R>&!137h0UkDj`X=H zw_lhy6ZQ2wV2pHpTClBBT1-3H&ViKULVE77nP*Ro!7dfQLV{$2E|W=kFflpXSm7=R zL-4dlL-Lc)_xgg?u|M_qxFn>x9I88&MlWP4X1KiUpVFgv zdX1|Nl(97OO~(;~*0a|hzHLISW!wR8Si`!OBh&e^h4vaWMuZvBVYhHpA7csNsIcE% zUJ?tn`g7Fn?sc8A#{wuDY(QJCJbcTC?cmd!`Fo+8i}YFF6RP9A-M5jHJwg>!Mpp~4 zw-H+{`q2b?3qIN_js|;b@LW+GaH0nJ-XFl3uuNUQ#a6Nc##mw`|F()6uquIC=wd$n ziQ&-uyX=7~&@=D(`#sw@-d0)bM)dbB;!Bo@g8OUAP9uMZ-kU+m-D zz)9DKZWl-vZZu&%!vUYX4Ie(nXUt1_*@?!?`6IpS3hZZ$0F|lA=DSgx)kH-z9ky3x z2gE+azrK%$@8e*&M&>2R@dE8+4L3J)&o$qjvjWP7;Bh@^d?50~2`M%ZUAQngaijk%ttK&`-^Uq_?Q#NZyaSPAx@3XZ}D zp*Bt)STV^jlyDz^K})bfMlW8JxUJ3LM<^I2m3*~#em|kj8(mlyADi=gCxFK;ai$s7wGvm#fn>TxU~iV)er(WPoS-F;^Wgi>@BaJ&L*6b4Mg*eaFz< zz`X2xkvgL6pasvNt&ibzw5)sAWJC7evQCDQ+qU)1VCl*UIL(Yxnd~S&PBqMOx1)i{ zLjNgd(O1nvQO}mj?fxmcFZow*7#e%=@(q7wxameMJmp~HBPzU6ei=VbCTQI@_j-30 z#>zTS|B(5V?N!=-|DE+p?Z`dZ&9`om=VZ>|20KvagrY-s>-7yb!VdsQn-obFa{tRg zYEk-cwI#u6s_{S77A)%M$BwG{D}?V-T6HLzAw}Cw_|~3Y;XmAIKCWmwY;c>|Z*307 z;OK|Dwk|%0^?B%i7y(Ra$C?PbPjLi9F*F8Op3XB*w6ry676z^RBJB|w!jnk;LulaI z8qjxLVfk)Duj0lOzib){>r`$>M=J`Fj#j%2{mXN^qWT|&l9crR91@?6jwruR2%Akz zQ2A0>koJbjKPP)c&B?|TP3o+XgwF}j4(IVHhFyC$`3|^NQcVK zd|h|i|HIXgt?96WJnB89^ZkPW*pAwdN65_>Tx-OA)BEXr3>s9_EA&r*8a6QKaqDh< z>!tlmmo-bC`6Bl70k!X+gro)W#yD$#6BD$#PQMBGLmV$labe~p0m zc6#|wj2wE*_xp}|H4#Bn;Rb0t9k-Wt6&`(+VKWAaz;zB^+Se)N^hBo@DQqKczZS>iBIMK=AAmBW@y|^|u zMh0J6>UZ&Ztf%b7LH93#f`4XGebWGVY;<)`ua7M)IbV}^FSZdGDHxFDftqw6&DEz@ z33=9cczBSA7k7DIt(qUy4DP-~Bh%w#exboI&V$TYe?5Hc>!0EU_>xl32Tk|0VcD&N zA*Us3+tErTbgt%GiUIiphHAd=2H~p#-z#G4+R;<$SKfv@TmG0oMh(B%v+J@CBUDhH zyW@uLOh9DtSXEu#so(L z*hmKtgYJKv!G>VSA_p&9px2lZU`6M5l=_RH!Ut$&uFwJS+^~H=XbiS zZ8P4mvvC$|zgrNdM3R>Np=qBq2akn8b?FUqBfwxsm)S%o%*9Up4J=8h=u{`@=zmuV zQqro{yfotc;N})1?kZa8XG8No7&SL&%u9WsNd8xvlRL^;#FZhV#pn{ySwyms?~FC3 z5YKFuZf_nqBR#GI(l>&wxIzp{@DZO{;(|-HF}Wc@Ats#5aQ?mc=4%xa8 zyYf=AG`-vhiBW?-Z!|j)50=X;uGOV$Xl_iFQ}>jG4~b)Q{*g?=eDx$Pzo_nT3Cc1* z5xI9Q?_wxE{91k1_O@=5XS|pq?G=jXo3LCI&4-*eYM)jzK}F{9Jf&#s-B>Y8r>_A7 zwyjc{S9;lTDDXYbO*IiP&sb2of0A9L<@;Q+u)JIiE>3B{$>q2Ghqw@S!CG=?=rQ zv>|A1mxnGI=-Kqnf*0tf8SVQ6@xZnUxt2YEnTA%%*2bgygOA0bY9oPrbbJ zb1+l*%UH)F-S}Sr|_L}Lx=?8N0 z0h+B#D=jX&1ltIO>Oq~g+NuBSv(-`95{C>9U&XQBiTdZ-)d$uop7#w0KK#k~Z&bsf zhmtrDBJEQQ;nlZ@6b@N0^Iy>YVWEtv|CNDzgA@?qF#W}5Y#`npYQR{8w)^MyGCCv;z{Z)6)x(uFD5&rW^AoP>* zj8-X_Ku_*%{p;bgetLyf$gRC2t%ITU`)b_x)nOlgVG^3y{ca918jfCA3POus_LucMUjDo4OUJ+I)z9 zz%^Nu$L%Xuh_0DFq(Kn3v-^evN&JQ|I;51!zoEF@sKlO#_+k4DKob*XbT3VYQnds^ z_fK3ad@iee-$6_8b*bEr-+?bF&O7`NtbcD!2V&7nHLUPfjW_Vux(x6#?W+vXoijCD zPy4S&Gw6O2aIqeK++7;5$}~UWBWWtuRA9W#mbfy6qGbF$F~aKgzy=F0PH635irIhXE4_!P+NnyYq0fh0>T^=!Thp7kH2_-bl^f(v`$l4C5 zo4?}Fo4!`|aG)ZPL@)?>fT!OFHZw?P&7E2hYVpFwO5Ti^$grTX4}I})066KKuB{50 z;@n@nE;DPeXl96lnvcs=7AJJP40FFfERX2g8kA&0uV$+6f2cxDVN|$zP zr&Zr;Sh3D&41LKtK7GN}*zo{w=9GXr%IP<)oTyV=YEgZtV7`JE`8iNC&{eJ7c{?!2E75oM#izj=6AK`pU5( zHO;zj`Ut0D*_UJ+-Dr1K<(bet{ghZeW4F(>yYpQJ!>mATt+X?_vZ+!f#)V!e=u=Ij zaHV%A!p*C6cy)-6uq;*Sy6Ien`)=In=14q+XkCLC&4WJ#TM)MD>!B5eTu^GE1{3mV zvU6Sk_?sIc;P&L6Px^#;DqyFOc-FmSxm0J@lP+?p5z3G}a(~`buQRPVD1VseaW&Ze z(laS=zSFrlmHY1_JD^8_z|PSxR%2y;lx6nU3R#Z21miv?=(=6a=QHH0;ArzX!n ze!JKFKKn4VB%H4$GI!18FR+j6kQxd$FfA8qrcBB-Xm$bLu*)?gAoMe_tLqZcu2%`IjqWZ zo~nHy^dnL)H$5-w`=MQ>+S*$4_AUl#Zn8)y?y5;CS`Of2pT#xn(FJ<&V!uH249I`2 zFJy7C=POj?H~g|#j3;7+O{_eFY&*^Wb2{h0Tn}xYe{aN1bt6-PYX26i1T>O(Y`ctG z^5nLsc}#1$YyC%@O%@KsD9nQTpSrc=A8)ADj05Ae4Xg$n`zkrSN$OhCYyF

J<<`=?(HQ@3t|QTEpc(Cbx#5Zq z^Jso8DjX>2MZ7f`b$m{LA0arZ?ecYMznhC?Y?JVqBcuDkCr~Fs>QY}cV&O}K$lGtu zHeuOSBqb{NIU4v74n5823te|SKhFj0^~c@8ADDttOUnIL~zv3s$HiOozCETs=1iwxX!X#Pd2?Obc^~J##|j^Fr@r2!w%O1 zq&A?oQ;NQB^vh2LQ5vr6-Z!J)>}7T=VIe`7c-w3!4$CCrbv0|+gr8h_r(IhEMMS7s z%9WhFkHMPqZ!>*gJ09tsJ9?W{Rn6R2oU*W-OqX)tL#TX+$%*y~L}U7LMRSu5p5u)+19+reGe1PSZBHtnAKRikvTU{b3Ol7-6;AEB4eW%g>TDjr{(OfLo6 za8w!|U4=#*_G0LKm_e67c#Y~4LfBxO_Wlb3O7u~25hY#d;-hJCNJNjXyF}!c-}Iup ztcYiVsLYZE$u2pcqXT%U1qLEBOA4HU0`(B%P5^mspGhbuKz8gCVYp~8g+<&R`s{;v zTpP{TOoUm^!!ceqs>56vxHMF6>U-iO-A(OI|6Q)e8VUWr7mAgJ^qrk z!a*G1Dg1*WPuFXxj1pHT4EI_v8Bf5xmQOpr5%NPLa%2jR8P0Cf^iu8v=By5eRamle z8ATqSlZ1I*Rj#(Ph=2MmrTAWRreij8gma?7f4yi5Y12gGW-wE6-uv6=J^ynVydTN& zpW)Ig@6)$g;|;o;i5vJk&-$1sy%iG;IH<&kw?X(1-(_Dd;c@HuLxu@^c^*m5*izxDp2UYpCmqW1 zE^QyDS~Kxd(m~345!h70M|aP|ivvJpAU<2(| zwXr((#9hB}k3?lI$VB^es()xc;GdPIes+mBObQ%b6aw@#bGHquH~dXh6Uluu{_CAJ zkQ}yLnMQc;d?jr}ea9=NS19kgx)~54frm?5cDMyk51wc{+wj}UHIZ1%12?hgbe@p( zYEB|nhfpPl1d)ay&C^P{#<+)WKzipRL|%(5{eCn{Uq>(CB%kOh^P4iy%#c_(DWS8D zFC#FX$>P_l8)0nz<_42sg97D{mEEH8 zdxweUFE}nz$b~7YFs@W9tE8<;vPj$v;#jfLH``&mRwCGjWk&C-#Ax)IDBf3z52tbr zoV^he3BhACu~M+YKtMBc&h?m{vJr6A|e{d!0= z6A8v`M6ly=i?NS;YD29thQBMKIn!JW#vchu=>eRGFJ1hG6xVz3X!T5)W)R0Us zM^y5QGCqNZf|@_{-LuItJM=!<>r9kCYyGRzG10ky~V|e zBd#Kj!K_zdVnyz!i={X~I9{x()6DOU)?0=sInku3;xK*x1;tz(@^v2FG9S$SSBM%gMIZEexnawL)qTBszHi_g&aCICW>OpmuK zsLKa+Yu0mNGgI_34bzUIJ$z26)?OH*qz_MXp5>sy$S&ElL8CI)4R2>v^_r`flpwU{ z=Xxe|rD8e6*4qY~#*&=nf@GDIO(VrgbGm^piSZ!C)i2~XftmvXH(>#`E999KO&OC^dW~yEuW*W6FI9?h=x4 z$o4|CEEOZIY#GVPy40a3>aEXrWQ(mi^obw^Hh&6sr}ke{^*-Hi#pHB_Xk~2I%t*DK z$YnpioIcFqsuLaRo$W(QC+%-|lCD0cadE@JDXZPBnj+;ZBtjtByyCEr{(+o33Ka*qmx&FaOxf$Is*nIOb z4Fp5MA*@vCw7$u#Br~mmM6{E1$oP;tr#S^zq^O7Dw}$EZVp5ZRE3ed12#T0Oig{H} z@28Bf5s^4n5TH)qDnRd-XvP~Haf~eALO)uR?W0C>aFIDoW&QDw9xzQu<;F{3Ew5S=Tk&2 zBYVUr$I+_tiJu33qyCEepKn(w?dh*z7h0N(eLNPW6r+UGn{M8#NO(J3j#PIPuZ%oV zDU!B(nHywmV>EuyDA`!c&&bx9XUXNki{drtn~`nsn-nLWr{h8ruJa}4GpO0f%Z|LG zryin4Wv_5`%dj$=x~`<$H;FMbhn^3N zgs2tRZfCbkt@WV%GImiiZ_8{S#x5MjVbKFM_&m3gYSB|7d!gDIkFjU+#)Rc)#UkSCR;X>;6 z!AOMi4boQ5q1~tW{Ws_unBiI$qIxi3i0-IW)R(=Zo>S&^_H-K875oNA(`X+QOQW`r zK9Vxg*0oKg-P7T=6&rJH^sYOY0p~Rs+WS7S9wsPR=`?n+0XC$FVO;TfJ4;6hQLBQ- zg#<1cqy1huuUxb$*2^juMCZ}DrrUXyR&;_({I*y^?aY?lDbGbD8`o_%m&jjWHDMyP zaTj|l4)iE5wZZHn{dlwFWT66N%{raY&N^x3Qr8RRdDzD&^Mo%c8b9)n@=W2nZfikE z6HUV9h+UK|Rz0U1-(;w;+o>xvG$Ig^t zFKA3(`H#9Bzq1ywSIfgd8ABSo4Yp3b8cBl`q`X3** zg?`u>Ct!13v{3A?WCl;;e{9Eoi*!ip=Ls~ilKk}JK29_bW-EH~_Uj1HKx{=))I{aO z0bXW1qVWPqQo}IF5+yq9`I7sOOEV~^b&|aEVhJHfEQFOaGwzPgsz9&5*}AA6v1eDw zM+R;8xR*C)AqfdhQ1Sj4wS20kC+x#o1tVuG>Uh=W!#5WXOV?vTiGt~aaePE3cF;6J za|u?-ADIk4L_>Wyf{}X6JL~=7mtS2EdUr&=EqLQ=7B@?RUH;P4>daJz?oV7#zwBsz z0sn~AITmFJ=J6TpOV*VvlUp@TRl#yzxsZr4cwt&8dtZu4Lx!^tOtrOcOaKW!35*w0 z)AGDant)oJjQ|bKx8BUHLE#%-z{4r8F!D5%fN4>*1PTR-O_tME*!gH;+#9vn3&pS`jB3&3gK81 zGgiH5auwwobW6&#)jf)|Z+=)fi98(dZ<(H?`&}3c_!~1i9_H2U*>!pbUhlOM6;eiv z7(9|1*i&k1iSyX9ji2(qf>l+qb)2=L9E+Zje9o&__E2W*VD6ttNjC27)Fa z{O}&SEiYaXrYq|14aY2%)5Q3bM0QmtymZ_*_U2e>KuZO~Rw53N0D!uV4ea zIJ*6S%r>1~^{bpd;=1vIYfIUsf~8BWm+%hNVEY%v#p1vLoV|%b^YVe>+2#_)vwy6Y ze}B79lKKO<4NWBD<5@!acTaM^x;iuJ>pi{`WD!K*{oE;he}7+q_@h(RIS>;SgRuY1 zXvf^o9jiYE)ymare7|v?Mtgzg z!qpox&#Se(*zRe<5RQ>(on|qUQ((TI9&KwgYF6Nui{i*Wja`+74?$h)hh{g*0{gWs z{Ba9_t2igL{ylRaB6FN-|Aj^*) z51J|I)WB$%*waxpq}c97Qi^iD?tVcPk4r@|_~ip-QZIiaM)uJtFrcqnhjoLshIss+BpJ$2AIJI{ea$X z@mgRiHqnZ z*mIT9+d8M))C8bkm`Tpw} z2Py=`Gg|nvU~Rt1e|-2y7wwwr=FL<=o40nr>eHidr}wU{?VgTf>_1Ldy!3WaNOL+0 z9G3dmxO2NyH$wCRQ$j+q4vNQYI@(cYSj+RJQULP02joPo2|#A@-9?_b5% z#BvK)o)=}0@m~+Qp;PEcoKp4P4`6uRV! zU2H90(EGBA@pubCry-DYccnI9iw|LBL_>Lr`kJcaX@3h91*K9=y@qbj=SomR`c}>S zWCmGs?rK&*p{SvQ>kmd|S;WIpVkeO-hDT}?>Sfg~Tzsl$w^Nm@Bd9BeveHE7}sLxJGYT%c(XE zJbxLuH@C0B)7jYeg-z*=!$l81yWs)9|Dw_8E-OY>Vg_GU%SR_n6GGPCBOMxuxrTJl z(+QhCB~Fg-X&AgHUPnY@6i*mTt$w6pt*PCkkg8-Lxl}s@ZO$TIKHnW_AvEYpMBNM6 z4w$n!TBaM+Ycok;Ua$+)8Yz}hMwL$d+C?|`$b*4C@$x?w+23b0k#i&;poQHgO+C#h z)aso@Re9xJBGO!PF)%bh(sv{wPs)N>&Jn_Ec}JNm)GSxP9aI*+WMy{3UR(RixM_V+ z6{-QfSi0H?_)JgFd}2NLULmH%spx`y(*DFqij;zR$6mJJGoj?wmjjZl1Ij zXLh_Vg0-xwQ{>pzikvje8?;{5Km}^m#RF0WdmjvQQQ6Lzq}2MW$HTTw|EPVjq)_-Z zq2}-QiX$OwdP&lJkT@Z$ROR-Q*``2^SK;oL*zBouJ7#A?7E3x)lh429V|0Gdr093r z;K!8xoXapUngMT8KE1n$6p1~1U)ntsD3#uJM{k2Ki*~IxaygWbKvD!AMs=RmJpeYVdK6U$B)-3x-J{B@aK=i=vbR`zA%LtI+FM$=W!}NxSSjvcqcpfw zI9DuysTx{MgNp5N_H0+TwW?Vitd_S@#ILqkw7KyyKDf>@>-@kynX$F;m$5^_Z&Lk? ziL-p6ii8{ByR2^8EOX0rr+3Cf14-Df<}Zp&iVrEIk5$irv6oSV#;V@CdidR| z+HYUt{*Mq~9 z{{>*zf!hH;=(FK8!~ekEi%fpEK=~NGuX{SIEs{E#3)IkQE_EE1`Ug&5jBgjlg?PT# z>y$>@lS4oKp!46^9nOrKw;af5~b; zG>pk|NZtu2y1C1|*I*p-@I7UO%Mxyxica+>3xL&@$jC4Qq-)L})NVHq@Gn*xwX9+f zdk*JRnJfY*i9{VW!aLrdm zQ$YfIEA=nnArkLlvQ;D5l?7DP)~mLqxSFpjx-cA!!!`qL*UB?cSm^fmsQH{e&yXB0 z`IDVT^E25oqQfK1n@{OUhtIhB=8s#C-9Ix_M74xD9=EhBB zejXoeit#l1thrL8nH@Z<(bwvPwzbZm&5=f<)c{1Y!~;%}N|kA?)N zCXLQr!EaR?28$;O*thhgrkU9>Osn3zXr1W`F=ND+frG$>;W~syH9b`Ey$G&^`NQWM z2{Rscl2FSi7+IISR=S!nD}l(EUSqDZLRX9DiO304r*2bpf3AGLbK8~f{(IA(Di#r@ z^Z}o8qWiI}5c0<{Q5O7aY)Hy9rFX+m*%BHwIGqOzN0FdnT=SXfXn%jV%)2ys=LCv$ z4fHcDtJ>dbQ}0TD&0Ik7lci~z8qqEfCi=^ZD8kBHGfXpkM108iPU#^ug?ambw!O6i z2yTQ9>oTW}z^v>aXuuV&RDQVnq8Cg7Gu;o_9Q_nlgsVCSSDqcLnUtDKC z77Hah% z)Vd(a4cIAbMLS&uLZ_DL^t>a)jg_NSn~oOPjTxnc$0f1nz{GQs*!MvjJfi1PmfuVk3Qop@PgXzX5;2l^+}QTZw`CDE&E z9$3Z48L0O#koNCS*jeR(o2GN~gX5JaE+h{F4f-varNC{2QQy?$HjQvf#c-pyj5fY* z|L5{tfy768SfPpxeWQ7dqmR;HRXD(n4E*_F<9az@9@P5e%r?+k^~SwAfuSkzzV?N{ zaMjp!-iBt4aKX}SyeLsYzaD?_USt`E(aZqq+&sQaf(b0jVTAhB2&<~`3C+S=7}XTB zPDH`WJ!OAt!YR!oaQz-XQQbCAetBbDx_5ZTk_jtPnRKZ%5b>#&OmsR3-+n(u!O1$} zx|61G$NZsX>6a0&rG`b9bg|#}JC(bpxmnM@L@6i6D?NIW%2pU*B}X0sL-NtOvOSBKY zeuyDVqvZo2kEU?(jMZA4W*zbc4qWXykhgu{=uzI=Yr2a=RtRIoA~I{an8)pN;Xa=a z7MBBdoL1E^s z;e*A2V#d7@-uJQiQFGw6j=7qWTcRsNjmr9uv#dO z(_wj_6>wIkuP%C2j%|+B^BpVGP`XOR)gJt4q_u9H@9?>A>`dW8(aSkw@;m^TJT=WS zrY+NV^kcz7kLg*<*s`4aSJ}2U+|&fS;sASkc#+4rG7$iyEeac^=lTZ5`kd!WaC=n| zObvQ@e<4clO~5?u)+M|6mh|xdhp)GeYIAM6hfis+;(_84B)AoK*HEBXaCe6m*Ak>q zq)4$+++BmaQ)nsfUZA+UeL3fq=Q-zjf8SqOtN?4}&Rl!;wP(*vLp^qwjN(sG>x8r_ zg;pngT~3_S!_8Jscd~zoabcYw(%$1)h%Y|aSNuRwyno3Gs|}weZl*RuHWr+k+%K!m z>BO&6^~FZN{v}vTsTH5S)_4Su9^o$pB>qD3^dhn9M6V(@sLuRp9&0kN@6zmJ%x z{#Z9K>SU958DGfakTYK(4WI(-V6#>x&yItjL)7OpRV?u~?O1B8<3(R{#x^tpUC1Qa zbMmdMtrCAHil}sTdkDpyFb32p{!E}=6#BTb5SE!ZxJx=c#UkMRmHsqg#wC*dvi=kB za87iAbYi*Z$UCR(&CLoYY)wN43-H6WCdz-+qI@;=|3eZjTU^ai% zJys6*BmxWkg|@cr@3SaWN!iov^~~NB?_2&fu1Y?d?;To$(-e?7CU>9>66S8?Cpnxg zWa=>x)50)VQ3etgTBfd}bYNo^_6F{a1I(PT)hd41+sq-hdv!ksSZEW~w2;j$1?!~z z*%eJ{Zx{@;=r~3WA8Rxu26RurKU$;CF%vDo;q0HfmW^9it zG7PH%B!$?#AUTqwuLt4h4qg+_vUlslcB_*>3#|YTY!cz{kpR4P)Ho09H4a*44l`Z` z+^#Uano!HWt{wU)Ct5f8xI<1I#aQ?K`BJJ_kZ)M$VOE9!B>UjXR%W0o7#P>DwLYco znl|HR7tFCfScALnWMcf4 z!uXN1FZgT!3!}1Rvm*xhwGRud%qJ{0?TK&fRpC8@j} zdC6^E-43t5|KkrD0HjqjqM<}(${50om7|t-&?%*zDaQBZ*c+huXw; z$*U3>H?58@fhuhk-o-pN;)E0NRmrdSZVCbBi7BN4g&~@vstLAi)urB4OFCWUgm~?C z+L5)IX>XnChiA@&idQty+dj59>96huXgW?*>dB5?q5ShFvzKbM%eyhc_W4+GL(xDcsl{yg(L$v%mymvsql#6{(rk%TA{#!oy zQvkpWx>7;hosQBI1;_vKW+Mv#A$@vhCvN6Ss3IR7q%HEsB z)ozcT83&$A|0sy}dg`It3xR+QKPJBH-Dka=DrGBnv66cto7zoxZ@x7#m<`tuDD0ytKN=E&?^G{<+fJlL4{ zmma1GU6(XEmQ>7p*NG%Z-v(tc=f)~3rH4Du&KkMNWGeYwk|2ZMNKL)tvfg4DgBt^G zA_2mlb{Wv(kD?7>hA*luv1^b5^JHeNX!lh@_Q&JPif#wHd47b^wZ967L;Ll`B)JW< zJhE^CL529L3!tv9_93J z({!nMKR59JIZ)xKY1^d{@*KsW4!LKx%IT&z4GSN10gYztnFm1Epfl4O`Dwn|mv%5i z49o7&-4lO*QP$-c)b)S^T6i12`Lb;4W%_Cf{zt8dzPJO5K?Cg6VVda~_uUfrEuPC> zK+YS9{tZvnSW(wj-cReU>3U?8BH>TRw0Z$kz}sC?#7-(TComhMp!TOb8-i>?RHkZ= z1&`kT+e#vfVehX;;?WP&=w(yL7K`-cRP+LVRF4Dg5-EEMiVs>Z(p0`XupQa&I9T)S!|%&+Vg76fI)G=tI?0JDv~@P2Px zweT3~1S(nj7%4YYb%F4$b1Q$ls~h^Hs;-Z;<*WjZCJhY$U4)FYGD~1F3Y-^&{eIRu znT$qTeq+wROs9TLw!amUq^gBfp8O~Z8&p|>wmb^Obw7Pr61Y*i;vi!(=pOWF{Z)u& zF5gK)ZIqd1z9}A8(JuSC;Fz{$$XZ+)-2N$SDeSY>;ue_PnPkA3MwDztiH3|FD%yJr zps72-PuFazH%F#SZECPVR0jS3hfQ(_ zC}jHIrPhCOyuZ%$GwIc2^wu;G85}8Itr*`T(DUGG&T!$ueoYJFokU2FC|~#VopID^ z8qIX4#xI`J`@vrz)E71$J6-3qr{u&e?W0|D^KDbM!D(S1_Y(7kQ2yWkJG$yK>`MtM zXSwNFPzt)*6z2to5|HkU^Ko9E4QoqI=)kf{@bE@ih`si zdC}V7&hPc}xRcee?{&)h=w0YY{LwEb-SzBqT=WXzax4iQHuj7LY_&F3clZ1X%7$Z(QaU=2M-0+i zL2FvU0({e9!%v9SgB29gA-k#NK<*8%YRcVWN6iInwOt>~7TqlKTc&vX%5|QZYJXm_ z&u(+l`3Gp5KjfJ%MIsJ1cbac!@}S0(#qf_2OktgjePa9J!b-cCt&KSD`>4Zf@K5j8LTsSBi_pXOpz}Goe^l)MCCo9RD}M1|QTL6v27(XWlet zSc_Sx4QFVR-@NcUzJTnNmGN)VI{F0N2~7v|HM{@VnTd-A*3=%LAT&kG=9N3jA7sv^ zqm?ww?p4U9`e7!GpG@2UP41}YSW*QPB<^TELh5WT=vuqx%G@0_jXlCr!BTr9ZqHGhbrCvFMg4O zQVKOyIMz);{C6*m&X}VOC;~a<8+{Svl;~?p(z#5Jyk?qCJ}H#ACjuL{KHugX6<|u~ z>WH!(&F>m`OuN5{MNHf${x)T6JA>}`Ac+2lDOI2>M(PhU^wOh0ek6Tx9T1oNoow^f z|D#+%_*F3jn&*KGy}HaaZJuhd@QTFrsgG%lLfzg`aMR4mwowZ|Y`<8;CnzCa&(c?T z?I-72#!`s>0NULx2+^w}UwF6s{nr%DtI-LXvXsmT+h*oaXwk1XbzC4~?;DFoOkDpOv7pB4)Av9`ube9>5;LXLgdL1hOw<`}#s z6Q~r4cHb1pX+^WmH1Q={o27)6XVQ!u1aU6t(GitVmlWdNYaTm`L)EMP`EEdW;R$b-LbUM$X5=Dp{@`pj zwI>(bwjoYe01IRSkfXmU2I#neeeiL?9VN*W3PPeomvRapR=CXYu@tpmO`_L&<{GG` zTsQYyyYG(_2O^n0pw~vGtPerGd zb2B2x_G@fE4A;xGGcE0I$wPfo{VEKdy9+|J6M@C!!taPw<8?A7ilb)u&Fr^?7#-)j zZZlAI{EicZhN>U#?dviHRR(sn!#NCF7}7lqW7#}KUS}WG0^-Q4*9Fg@yU*@FaJO8>CQQA7Q}yYGVn(s2Tjjw&{9|(k?Z9a^CaJ z!LpotW5RBuPewXJJ)i7AQ!>f*NyFf4Wn4X{y;@2z*06+gk&bHg3Zg^zmnxo+Ey0nM z8KQX1>~rIV<*~^&mc&@1mR z=C-~r3=H_fP3E0WS|Zcw;-*;$eK9)F%opr`->4GzQb|c@?zDmsJj|RbkS=$5UPm`a zA&iEK5(}}4>OcQ+b^R=7PNIy}+^`AOrrBLi?*iOt?D=H7Hq~-%c<&OkHO&socCv8h zFf)~m44LkgeN!BjCcI_bfs&|Dx;bRX?0AlQO?k<}VV)^oIXX2{iqNoG+B{s|Fa&;E zGflr`N?^(>&s)G9v#~24*VF0E(C==p4@s;v3uTv@7ZM~YeaXu(!2}DK`e6hc6NAO@ zjKgEID>oJPv1B}+v6!u)JP#?xCVj5hZH0cfE^CHC62Hmdl0JR0{1l#abl|1v%T@A+OTpbKh1{8q@ePl@s+aVLW^o>VoYu73=cc3^c)Cham{Tp{! zAGaQ5y>J6{Fnw3I{`HyjViKs7PAyddHzo>Kzw;O+(ty^saDB9E6C;i2AT zO3839HsKaDtqzfUv}^aTRN|5TTUx!}EEVPfEmt;@g0o^_xUywR946%k5TXhM+Lc$C=SF_Pi$~A70g)BgKh-KTe1y| zH|8W*L{LcxEqxP`<6)n;F#}%v4fcKj$y8P0(b1|9MjM>6vM6tTx zBO4Q~tG|>#*3{_~9wyjHeg&RA-XV-nkB^Aza}B6v_XSc*B5SE} z4tTo6Vy+qYx?>`w5>`9FTv+tzt%kS{5lI&g%Z_zS>a zhzux2s%$w-4F0+l=;mQ+uf1t zG21Smr`J`SRK>FEZO(#q=@XYEZPQm=Pi5);OVxeh>+Q!Rj|moWT4;OJrnY350*e$a zT&u9Ogl^i$2NmJsWvDKI8h1Ie+RxRKP-Tsu#1cBCMNqTdG0*YUo=fNCM2@DJjgS}kZ0B8r`=YKJ0vTPX5=GGvOY!+c-3%O(k5)bbj*7XwTon7s)8ipEPS){ zTi`+M%6LS*WS${LWArbOQC;LuMLZ#0slxQ$UBTwjd*0$cZN3R}{fK&_)+cH3AcR4R zSal6N&ZA+A#P1`&G4$d&d1diHg1$~qiS|*E*t^qmydr1xIWJaF2W?&~R`GyiUN}%d z@!ke1{*E8LrlEh5{GYgvP_{bDft;{?1j`=yrx5KaA#r)3CiL#G-Y)#!_$gvG@ILcj z@N16cChNRPw;Yb4|vpO2Id@PB9fMWVkmCsKh4-O!$w~h;lbGgJ^`$aaWR7tZ-=`l*VzlN$0bMO!DkLc(g z&6M|WGrKtIr1S znbVN2E^Z3@V<8Dz=0f?6y`A3rn$zet?JJ}Un_M}1p>|prWgW4_Q+LIW&@-L3%8mN1 zKKGzotM&?3+W+wa1nUh|+PyArS17#j)nQ?I!`g1xP@)Z&r^wy%6M2Rp!JuW8`tljK zmb$^VK=H0@X@LBv_pBS_z9`jhnCr>ZT4Pe)vl&tz#eB>so-ece6CnH^QWge7?dUEG zor<(tIW_A{4-FIg(ur29@cz~$y#%2yEr#Bb%upet{J~q$UU(Hswpqn3_(R{@)dzW>F3YStt$x~4d*iEB2$V)R8J3A*3Ux7fcp+sp_uj0!UG?N_Ly#7H z(>{0Ns#{MyR+?^RH0>FxdBgH6jRQ4cRmc0Ej>t3kbaqJEX?94%s;kq&#Ekg@HH4;a z1(3@{^5T5piA3nCRZ$iNvMx zmbn>ucm9whEWRi1d?o-`=}iQhovS36xu_AAGvQNgF$dOv1LbGa_zzv-PkG_74-esK z<)iTfs$?Ow1@R};{feU|rnLMU7QHBh2Nr0#7tK8G!GsfC?RUQ6urDNK>GC==?Q09f z&pXK`0BhLZF0OugIX|#6Ls5}hVbmb!Ps_YYtD>8^EJp2B4#0_&Lo91^+-|{?%}G!4 zIi3&Ng#nlP0EF;F$nfKXD9^Z^blU>QiCIwnob5O_QG`lH{}9K@8(o_LxPsny3Oey) z*;XC?u~WK}ZrgbKfpDm`n_g*v7z1lMNFUL?0J(eqS(vi>#kace549?0(MjyNAq#pQ zR0sut@jQT3E70ztv4RDD`63QdD)xW}t2&PN*KEd#qw)>k?D?cYN|rtMY;2qtVN6lD z3!SlT@yp;Owca`I(e(M?WYYmD)sm{9+UxpMw?nX?vqKY;EU)(}{cUMVsYg-tv+|!b z<7h)hqKcy!#>aR36$8RlnZnod#e2gPPw% zaSv>B(=oE%}{hdN=<#3LoiGJxuNKOow03v%Sh)pLcd5Pi7ku1;3viKspxhV!^ZgAw@y@p4A_WW8QU&PU;UdA^94t@4oI~CXZ zeBpizdM+ArfR`ch5kV|Wk=wTh6?y#1O*mv;??l5o13v%|_6k1zWSOZg>RrOpLlSkn z;_2z3adn2*D~czJWXN;zw2ZCNv05wqi_q>eX5~@@UklOwzkxuk6@W0TeS2R7R+I;$ zlD1r@!&fY|9j}zBM-03pi82Eb7t`h<>*4O4=_%EKZPQa>?6{SH_g3}KThw|gv|LzZ zWpHuj%zSA1ITHI$Nqdv65WWiKnW4;tRu5S!=bJQ~pNDUWLOh~69eW}##$P*idA{Rs z4Sqe3NJntv`5&N4Oy$mX=72j9htXy33sBdTr9rk$EHeSfm zOxc>{4-0(9`tFWjLuixuM=8)H5m4H@yg!bkP~Kjaub0TBf9RF+b|&|8Go^Hh@>`72 zSUv9uuQdWE|DCX_tN5i!pUdj@J-jW-2iCqgR|}bVgGPxJ#CDs5@ie;W=_2>bS5Jcs zOxVtCamneOpWJ?Xl!oXifpKTHs{G+6*`!2CgyxmT!3*c%S|wlPuP|0<1l_GPRGj>c zPEGMG9vp}+*nAnI4$Qr;B$*9GJ$W*6;LNG;mt4uJ6CUf{X798Q|BIkC2CR%YR_l@Xyu z)`qYUU1;kr{T$yBWrM`LE4=QB4z4ieK(Ad4|i=^%gfmWk1FdQSK-7 zN_@X-_<+84D#&&fW~lWG4-H$QN+0Nfs<1}Ai{vY+LidChf78*aOM>vWB^K~2avOp% zBg3QJd)H~EM|fx|m$_}wYo33=ZK0y~yWY6=tyib2k4 zLst5Z4BAYEr({1Spp!Xn9FbS0E~-Oe4%pMSZN1eFA=9o-Bv^#wBYJ6yWLAbU@hc4F z_*iBs^j$pz(eZ{!B%y3Z8j5wIZ6W?`gOAU`d2tgX!~2oCIcO8Gx`X~m)v|4HwHOeC zomAppQoPp$e$mE@RHZGc3~B>RU;HwN{RV7n58KPYzQrkcOW|}E(*PCUBhY}y#w@gOrtW4#6jlrB0@;$ zvV}&(fQk~2EUwJF4V`?kwa4zH?r>$i?rpY8tg^$`$%yj43*;fa8QG=yeP zr`Mhny5LDDJ|$ajjkDK6WqL`QnLF9>vTz>cd4q)#@W}s*ex>(Pdg(*yU5xqxW#igC zC_XopJfGxf01*`d5i*Z#i}Uvd*QE8ocD^$d#cbo3Pw{-(-yw=%`wnt5ZpaAqn+42) zQgg@JLceuFPxbqYw+~-8dXTxV_lXQODUK5v(>D9$y7m?Y5d0oI@P3|5u9q*Fju0M0D3pV`BZ|(5^nv;6|%|ZAUqbrYdSrZt(0l`PBQg z)Zx$Z;fwiSe|_DF?q>okvkcn!{aGpXyCkcRr;cW6IGk4o?xTMZA@hOo^+8aNKyF$@ zej-AJSf4?|sJ%X8(1%%B$|`-is?%ZbjyCsn>LIxk@K}*duVc0+^GXhsY4ju1)tA4; z3PE(8R?W9imA*rTE)ZH+zI0x{1H7xm-zr3}_5Srt(WP@h{1@J3Jt1R6L2yxT#1<7T z{G7@qDeQ#MIDd_Of>;@s4xFPYH8N^y+#0T91e24-Xqx`{Y}TD>%^wFZ3Tu563DKT+ zx{>Uv(jMCAL!vg=09e-K@K_1>y8IyI4b5K->qGVz9j}B}P%l^Do3(MTOfIHpqn`6d zDyU<0E&uw2zN<7C!(JBD*0`Yx%9(@e9i9rNUzVy{ITtUkH8$m6HIt#rOVERRwVLhs zz!b5mtfnhyYpWjJac!{#I*ISXZ+W~}Vv8JJ)Zn?i9Xt={&KRY}@4Z|!r-BS9H7brdqI8%Y?w+S`h(uM@sB$vF5cD%D;w3tqNe zN)s!sZ#LWhYA%9%uJ_>|T}-A?Zcp3wp6$u-LtXd@t9R4LFdo-`Lr*K>-5+ckRKhRJ zMayNN!jBk&m$z%TO<9l*Wrysz<*nn7fp;4#WV(;E<_6@=r=Q56E)&DKx6(g@y zlm?a~8y8lGy_`HO5??+_=&?Z(U&TM z(qqVMwNBcpyE`2?>y2nmBK3Y(_aAhc7|9u*6IMoo^^Y20=bcRF)8cmVGLC4wvT_n^s z*@!K1soVL$&Q!8~eE~VzxWa%cqCik7fApK7YD61n@4ZNl<~?F0!4dIrO^?cvFn{Zv zS(~)jpn*R<**v}y!&<*kwMswzu+qL!*w6bE9I{lHd?rw!y*!u=`sD$Oc| z2pUa1_Pc7G`R#k; z88CLD(}2N;1H?R(sIQmEg}Gi5OgB8DZ2WSS3BV)W4I+9THz-?Enh*5x^hc*{VUPFf zS*J4%AlM@1{GY|3Ww1yiuMy+h&Qu-j(9}fJUkEjBMY}#75 zmZX*}G~PVRz7mzS=X4h9WjfAK9)?CN(!}`#Yk+e!aZG635T7NPS=U&X)s5I)39pG& z70{v@uD1mZfFZQbhq@XoRctm&r953iGcbnniC~dBHhQboCnOSRLQ4(p<78HArQ@W> zlySYe0tdZf(Ox|8}FbX6lwaIvxQJL{~Mo!qzRw?yU;8Pv?RBheZAEw zM;oLs@9DG9|NZ5-6WEv!vR8Z?W6=S$K&-3o`nKvDvla}P`&okyWb%XeX@tB&wbfH_ zXVZg(9GUXj>0B^F;ZbYTc#>6L>3yE6Wc}+Xkl?cZMvpjW6dsDvL+1vs8-k7}iIcTw z^_`r-lGDl+h2xiW7fBRxe~^7C{!LmMD<=2G`C|bW9gk+m{PFryY; zfAA`>nrX0ppB|c)wJ{%PhnS5(g85`6$zM0&RZRKK@Pp3mt*qT#c}j(n-KBsb(G&Mj z=)_nXQsUztgGLB+pB@-JDF-pk48Jw9pCbVeco;m97Wa8_wgTm58&ki2CN>RUz)Pdw2|Vm6snbqms}R`z6yQyqj8)_vf#6Rss?0 z7+RvHFDZ=DG?=y*I-{p7>Aaca4L6u=)ZaFmC}LOGN|vlJRfVe=x3pCHkuMCQkv{BO+Y z8bh^IW)UGX`$8i@1J#~>lySRs2Bh@F;vYRPMfdP3j0r*c5oi=P1{XXUj@XX(pJ zm@N$%n6)eA z6UQqdR9Z*p$gY7t73HfG&9gDV1nlg7EBfGRFKp2KhO^)<#|S1@styGj2S zrn)Iv3-)2{B3o9Jc zfdLSlBm}(%=3^|m05}8f+A`0or(I9a$(V~lCn<-whwKm(|&*M#9 zk)=eXp)b+kH^Wj6YKVzDbl>DG@p@w=SeIIXev4t#pJm!g%u;bbDUy?!(G$y^aoeJC zV$G^!-AumbmV`#UHM^npEd}Vlv?NP`W!H5LFY)yhC!)JJAMfP;83FV7HaN@rvEQe` zF`D`sW$@?Ts_~ZFw5ian-gz5*8a zb<~ifF2wP~hPtm2JlJoEkQ&zaBRyFMD{QT)*7`NymTkMK4If6xOvw2teI{jr2_?1Q zf_qCQHSwC!;JAgU;g{NP%jUJgW%Y}nK?~jLPsvQ4%#t2N)w=@eJ%Oa)s`+SL%%`op zpCxUeX%${i5YT>ar#$>8ZK}B9-Gw-Vn!s86`QDBrfsZ&DMdgpg#w#rx0WwEB!T3waK8Kjin}zoSzYx=1qsvdux$ zqMd1F^YB}qE^xbn%8=8?0s&;lgLsIOwBXE8g}iJ-R0ER#`O;d>*)8Zkg?Ny2TgrtYGPNys~Go z-dt0)yt-(yDmy^ZR^~ z+m!?Y!FoeRij~Zk(}RwGOwbsR_L1Gbk~AeI!9e480(o6-3{s%xY8sjfg+QXpM`U+u z8~H1kYVx_-BcO-q`b<$uD50kgDM zn-C!759qdhHf=4a=Fud~9{!Q5-{~+T-pH|*siTC31`iq^CCQE)vB^01($yo9>~t}H zG)Y|{hr0TnenB6xjBQ8b9YC5SSX-a10&#I`DZrQEFF;>JMcTC&!H1Zco}E?3TT-aT zUx1f_WYFt&x2N^I5T}Oal_VQ=kpS!?8>8NL$1Z}A6j%+{z5Cezb!fa+(E*O}{d_~? zDrqNeBrle*nZNTmks%QNgY~G=xw@@CE5xL{jw%K)>vi+uWL*df@*TjmBTm+3OH5C2U5Q1C0rhQ z($Y)?%{AfMKTOODi;=kxw496HkMW~#vCHg~daA?xpDiD?gxo#PW6J$JmWH^?frL*< zAA1+PY8lYi#nx7_yT7NQp-xjTEaaXQh8Rkcvy7Ob8m4Sa98Z6WC0YiNi-)rQXf5@n zsX?FeS|5F68OiVuNff+4@jU+Fm+s<93@lGs@~vv{N1>gQtKyX5d>1C6*tN;z!rI;b z>{t5$u0FQu<>3dN_$p2n9b#GoQc3VbMS-8qnH3lh>Rnt?#G{iaWLL>W;-T9ZwF{^!Y4<$Nf&N<o zh1MyHvbTGmM#r$l?9@o=)%+E7sAd5ctD59rul;%gVGfZTw!X=rJB(@%LAGVgFJ|RHhob_o zOT;MPAs~ShuEo?SR!b^p=|_7sNLV<~>i-dqE@%M3hz7M99vf~CPT6*j7@jiy7d7f( z07;2lXtw58^Zj{}ALI|zwF#b$tG|MS*V`|D5uukIsA@RRMeHP}b?kLwzW!>q3ge zNpYazn%bXhN`Tr22brNidql6;5Mhl*6c!8b6GkFD#6E7{#iK;~(w%SF+5i&1e0Lv_ z3y2m}D2yw%pz8-l$_`b~%*Bi~lawOX6mCn(186Z7rrkyLsQ8(ajMdQoVEosc;~MT^ys5PFNM;!-1qqjGgyHcLzmQo27yIH@o#IW8 ze)qUZ=j(%q4>6_N7mw$*k?R1|DvY$BbmwjTz=Na+RMWp~Zl^!40=`*Wab;4YDbu?H z5e_Q6=S@b|`LFq9hx|{m4uiakDOgx&uO&@z6|35Dy^u)9=ox#F-?5=+725W)>!2i4 z&_YtCWd8%U{)C_|>MA|S=_^sv3sUX`X#>GKX8hc3Cf4siixR26N{WVvB8+TRRga#< zb)um}N4>={<3f*Y>XFX)r7@Z0grQUJbU9z|H;=ck}^{+q{#CA;eq8ltxCm}aT1hsG_ zX%woS!8@+GRWil=#XnsAq*_q$G<7@bn?J_9yfpsM*(Z88b3J3spxJH17AS9y=^1uy ze1fJ4bD)=*M`VsiZ?2gqVqXhENsn{o`>}=`w`qkEnPoQ-+NI#J7ApG(joCD@Fw9oQ zH9q1y!LII?78h;EM)pey0;*4H8nKR_X^N*ruauAXbkf8l=4y#(my~r3J3B5lx|<>g z=YiwSUt+sI(gK^Tnh%pyL0>Vu?q9-m!9y9~5o6~XSC+x7XW1Xg4SP-{hpMLEN;$O1 zIK?rl@iDu`3Py}5Slouu&EmWcGwf*>4_7YdBAI>zbC3mnM0$awW=vR57y-})e-l%% z^dvsjTG@Dm8yjaz*CPvaU{y}pmn7yZfW%%nDa0zHharaT1iO*C8}kI+Nv%R*4)%ue z=!rTD_g9wX@s`>sx~>R@oZcWyH!Y`rfMr$=Nh-(4?rv+1%f9~~FTnqetBoH3P?kYH zQg=unQm%BNz{T{+D{j{v%FD|!QBB^4%+Tnkkhcp7jJmu=&5(szV_8_)QcBM;%h+nZ zDgKuT#x<>oYDiIe9c9$G5hADWXhrVnxKJ-gcAK*stUg3-2-w!ftnx7e2a_o`p z@UK;bnfvO;AL&9fMiD_-MH)GFvQYWt{n_j;V3P>F5i--Rd)Y4=?&T2nj<+ zq9mV4A{Q;6`^uP<^a=kzo)_((cU)SB=J>w_{(E|tI{>1oovGty`arwURCRmh{z%~I za%EA?&`|MDFbKMnMVzOr$om6|2ByKoF1;trOKgPI&&&D=CGgxGCJP>9Uow(Dn&0zB zo*NVICnW(jUXnh3U>-zFU3ow>dEH_z_jP=t+^Y8U7X(_!vPPemDC0FY;|_Io;2L6K zlnKa{;ODy2>ZsJI>ZD316?{Q#{y^{UGqrG}wzFm%Mg{kT4dJGKj@6`Ll^J_qQuIq3 zJj48C(1%jNOya>Ne{2GW?^@^>gFc^?tz&EbKKS^w4~(d7#F@VKV3M3Z6F{uA=Iqra zoS!6TSPJHJ9Fap`OQbGZ)feLh4_dwcEA_ANb6t0lmK{bTo=q9kvx`xAy6&*=f%0Xs zjHdO&cP@xX6{`F-BS+W6_q6^(atK$`45lZQ1(^Sfk1B(Qe<1iM#CzudM$Zg9opO+V zIaDVlEdnry!4TMafBsW+Z!gy`OV5J?gX|G+v%V1RE8o{sUcG^*W~RaE0?r3@p8HOS zJd#nHB~kv5?V?TWp9+rs=cg7{f#U=gL@RO%nR-sfbVGzbVoE0TxjeJy_i1_C0bv?V zVX;PZLl9Gh>uZ6saPg4<0k5t}1MpZJ=`a2nrO#)B- zkV0(wJjt8gH<3Mdl9yuX*#0{I!5pr`fe2Uq~s}HZa5X(QJ!>8y6!%P)$0e@*G*H4e}+}5MZ zmD!@eftST9BNc`^WHBbrPY$2gOJvl+6)5kLW2bJeC<{Lp5+6aFF*@eOsjH?b`UOup zs(h~Spvhlg`}s$5{`H;#=(Y9?DX-A{U4|8m%inMWl9<@*;YP|2Rnsh!f?d94g`Izk z;~^h0=5aU-KnQPUI#P!Lx~Vy!nF;4qgIVWJv%M>N}P!joG>^lPfx=!s8{Fau}#`9!@m}! zUjqmw1L$7V0__t`$o#*PDOW?mBM8X(`?dV9pQ59*^+@f7<{>+SVAqx+zhD_Q1) z54L&y=KQC1Ds8X#?sebx3FYsZJ!Hs;brI%7u1x!T?NCW%%3C}|!++Ww{6Ym|GxtZV}IK>cEbpFtl zY<|{+4w6WfnI zl?0f`#^W!}$Apl$I|3Go0sU`z%eM(JF<2-6=pejcJnz!QasGu|6a5CICM z=zo<*(pCro`T6zan`##8<^P`ICLLRG*Y!nWSxLJ&pvL$0hb-yE8v1@~mi>>ji(vhk zf3kkee_pc1ERd$0pC}${N6T*+`!DwLa42-#MGYnYD_JO;$j17AtML|#Gt(I9;=_vC z1XNAEsL9w?E1jZ|ysYfF;s4s6K1lGpl{50)AQ#datj4kPgBon zAo0RjhkuKcb9t0H+Dj7)IAJ15;hr$!mms7Z4+Pk}&OIJkAQ? z{zcYnyTTpuXk_5llG@))cu)`oDURqTCW-_rdT;Fe&`p`y53Go@JLDG&Dg`)`<`)be zXt|s)Eud&?&{x*$M$vyEXTx8AMe=8gw?U$EL~4K}eZP%Al*j?-UA*g0&J$5Ap;nxv zt8b`z+m(KT@fU69p(?tVlAic?-hR^tHz6_bh+;JT>)8MEdd3q3XF%|FD4Wwx6V@)A z3l5l7A@h(yGPUyyKWs3j;eLxylmpuvE`z

zD0z#R?AslJrX8yF&y^)FQH$Z2H3G*|jLJ|_?1C1VR<}4EcM(Xs7Pv|u-OMq>1J$+J z#{PWVSfScc$i$>VVPKtZNUxYlER81K%(^zd)R1~c7=Z6ch%tu=PjcFA;v=OXxi@$| zo{(botYxeEq-3DBvTSrx+d-FbOuz8}^HWie z{1D=W))1woM<*t%vUMvPuR+_380Df>nvyLWxgh84&n*i7K4$;ppc_3tW&Go5pu^XM2S%b;cc74@T+h>PJ2Z2!3@#O=es7c>3}kyTm+1f!$sN~riy z_BXtDIYJwZ!GG{Su}o_Vix3TKm9yQw%2z@{K7ZYX^y%Ibmy=baWOOc{c+2D@np}!JUaQ^5W#X|% z%c$FNgP|lJ=(|74-;uESo9GPgntd)|-t*2|;la0TkU2~S-1*-JQ<`2e1LnxqS)$!= z#(m5-+(!Db+t@m3(aj0kB^?;m@MD+Mbx+G;cBR<8i)a+pCEjH(LXrFO2nw- zp5|%ufu0UJ^XV`(iZC_PML20E! zuQM@0wmm7P93a_{CNJ%=>sZ24Jtf*f8^n@^7R5*fgx*@v zf8hK-df){)s2|*`f*19FbvTW@U~oTUNz{y8D)+#89ww-%yQv28>pGl$&lhi;*9>$AM!X-Tj*Hz~lZeiC@Urwf#kj{$(4$%`xA_MerW4F6zHf-+Hrh~D{3pHl=7D!31kL0UU={Kddp;M*}oBhD)=IAhnQ#*oc>>h93O$*pYSAbM$vZ#dcyJg(jzQc3>2ubzt1 z%2?ky$1KV>c7Z;TG+KP)+6(QJDvbrPz#Yp>UqgvT3+CFMeJDLftTnLEIO$ewfQ7&) zGqKpQx4(_lcU6hLtE*x|mLxMQPT7g{je>`6mFGg4d3wj%>YC(xeYk3M`o1i=3WNrG zE3J$z*|@+jiG&uLTF4uhwp5Do4&QJoSiM=}fVIM=L$U`$D$}>B^VP+z(e2Bs%d7Zt zg3=%vDoo;siWN%)_R}JKd?-x>89j3v*My>Fkbr9d@gzY5D=A2DVGSrw{~u%sh}Zc7 zVx7G zMYwsS9x=eA@to0u0<6?+8-DPzC|5vCmMqW zMzZGRPxx|l_}JA8D$={kHf)$yrdvYg{YZgcEe87&;vBYy3zxj=V#dcj{(+WPukLQl z?x7!OHux0RB4m!vL=Wd=tL^^!Gvq*1dg82}60%VFUIrfD1?nq%KHbvbN>$ZLS|W54 zh5>P;J|Ty%vn7~taD>4yTJppwW8k{xzA}GNh01)QZdFA~bT##_OU(S`t%q(-qGzXJ z7`eNF(_kj~{6I6pbVx6vw)hO&R4dwn`T==i1qYQYJ3np>3nn{B zi;(>Va;RXZcldy?Y>Ujj*t9{(+$%%Oou*wXoHdj3Z5Ezd{T!^xF!s)Y)p^vZ%IBT2 z`TH8Un1HODVjRV0G1j* zLMs3{xB>iqhTq0ZbexX(4a@NY^eUq*MW`D-6~DBp(GRD&OyJuWA>lZAT86Z??x{Pn z_D1fpy>@3mSN;=pBhOQ9-$-d9G3u@Yf4lZO?k{SX5z_sPo1f*ah?wYX+2 zyDX&#ZHvUavU;fXh*;hH?%^tHt~4XPP`HKGhg1ERq?mCq*DjUHp3*XP-<>; zuM?5Mq%h~3z;Ek>1UGJD2h3{=!A^q_6H{v8WRw9G8F*oRXh|pA7?1%%1cbQcra*Te zzcs&k<+3cgqUV{i-)~luK;DZSaGS~OM7{;+n?qyG5?!V_2#_;GI-e%tExw5pLSI$B zq58byb*I(_Btit3leFMs$^gz8FA-e_t$p2@$W-0qW_S5}urJ6kJ)nHHIl5-4{FZ4K z$(gK?$PFb1!c=WAioZnMm#g!7R6l3;0wi~D0b7r5-6sRF(kK8*Hy6>EF+(5}gZqQN zwHu@&)oZtCYasLE%mBFfAX6TuRuuN)(WXZ|>HT~<=Wg$h**VV>V5;hQ6~ zY8)N{$VW85LrNl|^egjoOsDE%N1My~)cuL%a|thK!R)Mbr_52Yo&qNXv_~l4CN(EN zSBW#MN!BCB2C*d0i*$d_-!;a2p&Y|&p7!cAy8lWSvG5zAoJx`j-HV5WlPwNdZcb~v8bIc1|KgkM&tzr@+EBsUa0xCmaTn`t$Cp zHSN@}s_qWz)f0+i1g_D5x*th=Hc-hRCV!(F*wG~)t<3TMdnmE3eAW;j zZ-HFhXUzDZ9^D5 zzCfNK^*44w58EhpP~Bj2Cj4x}jLwQg%Zm7V)}HH1^zSszahX>xG#Vcl6y=5X&_5(X z!2g&{LFnTh1w;@lsV%PH)BI9^gD7b(^>6+>djo+zJH!wc&CrMIg=zyJNd1Ld*VUmeFPKlBs=5U}{{7rLXsMdM8(rHf{z6XJVUMJHUfA?{2QJ=0%eP0{{{HTuNn z*F+N#E({)s1g1b{DUIT2eCeSDtr;(2yho;};33wEFmu#hrjerLHhRRfKZ=~IE&K~r zfeN7TY7C!23al9%mwQc$3F3`3{R#*{p1#Zt)?paKVS`JR5MYCgLMhHBW&vc0S`vvJ zr}=Bt!)Vg3%1Ih^_E;gp#2r@=_)-c71nPob$r; z)*`J5vLoQ9yV62BOA})DT|`w*|1UTwNg;yXS{$n*Oy9P@0Ytr>kyFlO4sy> z&E*}DIOZvjbmn8cBi3k)%o#QR3Ixpx=VatcJHM+@vocBR6sLrulGM6yr9yrNK(`$( z+nM#k7;1pg$eNLZ1Uhudx}*<1{%_}dlcz?O^rwZD&7pp6o#{FoJKyh#p8}+b8lwyk zZXS=;dJhdw%KG4nuGK?h)cBLOXWL_9--(@U0!|a-1FlHn!6BnLu9n%Uuc z3%y{YWKE~`2V+DpwvnCe0@d?G#EB%E+9H|dZ*BJl;*>me_K}SZl^ig;iB8u<+FBA7 zTYfswZVp|rn6^S@PVjE7lwV@fo%KdsBAc3)lW z8Dl7oSZR&OvA{c)-~gHDn0B`?QDc*vcu>?XB3_>S^vF?k@9z1)zQWP5khAZ~;gIK; z=^1{fc5Rt?Y;w}=+>l66G#|HJ-i0K0PHkrpE$mPBJg&PtSY_RgYGuRS{tgS3us*znL4$iSImQka2h5IFklwd$eT z3P=ob(n$2hE5r699{j}_<<(>64ct!f}lJ+IdGj-@Lw8MHL zuOueM;7`cHK-(H<3jeAZ%&bt2Z*P~OV~;7K3_2)CY0w75vWdOaFw2lKkLhq_caiAvVLtTVW%DuF8kI#hN1{T(^2IG z+sM{KAPYnEZirr;rh~RE$tYI|2TQVXoS6+&(G~y+@JRnJDdw+6WME{K@6ou!PsYKE zg^wRz?_CeQDwT;KGX?{fXBe}%&*14SLykdB-AO1b2CzW$ai#{w5Oin+bOnLP7I|tT z-+=7}BM8$sdg+&e%1BB*tZH7^C2xS{DOK~l#r8n_@1^@+?bP2t)a@9X&rgi)A45@d z;t5&k@)>f0s(A_nB`Q@T5M|F&>BpM%5;Mf#76O#$em6z^%2J^*N)BHv;3?Gd**G$h zK#^XK9d)xkg3w&UhrOp|4vm#?Jgun3mNURj zC6zA&4mzQ9f4Td5prN-WNh`sS)I7ND`!(agya4ho9pifqNK&czVP{a3x1QMaO)x7C zOMD9ZGey_=Mqf;`btdNMK7oi3*C%EmeVc#!nf^BON6K;k=UyHE-9_Z3Jhdtl;nhcU z_waJuCgjN`j!|TOF_uCz`o`@>E5q$c!3vuZ+j^TMx4a)6o5W}6z0YH_^YzRd7BLwP zOZWD%x0gI_|?2wjzk5+7z;^NvIT&|ji#_n1UFs^f)UcGJL0D;mGy`z{-G(|^T&nWIe z2ZwscCI{0*S(=YvQFCKYzKn8~+1q1YwW!;okQMB%uh)NNbKmgjgj0zr9W>2evkhqJ z88W$%#Tf}B{o+RG^=B!!X4jI2a+UKD){E13nb z9z~*ha680CrOCxZk)yIWfC9Clj2sFVzi!ZY72 z{f{zVWL-4So^7fpaw-q_m6t4|s$|_eE;t;ZgijMX_VW}XaintT)P!~y&zo>WF&uP9 zfVwS`Fc>;G^&xuVeW{ehjY}fs$tNzX`-*m*^LmhwOLj7o0PHf2sTbYho=JKvVKyVn&egFO^_5OG6Mwh%;0zWhq<#&E}$T zx-oRRFmtx~`D%JeB2A_5Qu|aY^zjw-sCp!yydpLOE1Fa#2mKXAjI>78gRScKLGiD4 zO!sSRr`Qa^0Dh4#Dq^}GVUbj=Pq{VLp0P zjh%hQKrrv}srPkDbXAN6gVGb<+_u8#D`jBh%J27WA6dHt(cM-M3H0lA(AX zEIN1IkQ6t)QWTh=Y~`DNvr4DGn%JD*Alf{ro&`NsV7{w7vHKvR40jVJa)g#>pxr-9>TYRL%WCo1OYxR2Sl< zeR#vsY#o|yg-v!#;rjf_0yUtunCcTD#k6axwXu6=x>>&A8W#9P@T95HTx;Dv{sxFm zcS?!BZN%ImT-oApSTh_re$!faM4)bOvc%I7>%|P^>VA!~h@Ub17I3q~-W10|4l;!tul;) zPaE94H@d%`DNtX1o8AWHx%Mc&Z;H?zm!Ja)l9&r$ivR5+my-a>Y#!O))@vm%7H_u{ zq&_$7sygy&{}AgcpglwUEE`dZ=uo1;HB_ieQGxV&O`|UDFFGLO;h3U#sQcTSnra8l zmuP!q<2o!z12y)oa~*JbzQB)S4CsYQ@!69QLo6dc#3?fw~yO_dIM&3xb zTTGBGiy^8bFa^_}FeFYlauss)oL3zuOY9bbkeiGNudkamP?-uqeOGUY+^^`mcJ|xL z9Q(vjqB6wI9D3&(Eus{Ip%rt!6D4FFZ!pXHbsXF}7-OjZ-WB4-J$A94$D}<6--g)I z?(${E6-U#|atx^uuS_w7Q>&|)PySE>+k^YEg)E0NZ~G`ll|~41Q_cuAny9cNQX{P& zmd(&Dxca0+FaF))HlU=~JlJNSq})7@|V9IcyDv ztRb8vc)3Eem2p+Xih`J;&@ZFpO2Xq>Sx`D@T^bcIH<_W9St=OKo4Z;xz1J2m&l8LO z3fcM^uXR+#FX=1rTr}h&Qqd@oKlm5^XBTL&M9WR~cq^lmn5)ktFtz2IQG~D?LbFk9 zftqAPuuw;*A`PBM$ibbbzM4oz@0husSglxQvj8+Sg5^k=Qy~*}l9p$rC(g1w{@zx5 zTt*i>M%55-jp}^SJj9!mU0t}EM(l7aq2btHKn>6xh>bau)EcVcuhO;DARKt-^pjNU z&M80q4-Lx#Q?^Q|>{r&DQ`i8?=SZL#3W!_0mZ~%PD{4U|RVQ5Wf3Z<^*%Ll%Itu=; zg#TyRO;GqhY#)?&-(61p6H4?+;iKvsUQV%h5dnWDf zO4N=qbjq3*-&+|PTo{n^-|tZdvU%*Go|$^f9Zac7$VRnZ@BlE8HuAFz+NLnhNjY0-ck9WF+on@dP85RJ>p)4J?pfX|{W!8polRC)+h9419@R=A9jW7BW>{#?JdM z-KCXa8)LWUlA-w{$fj*%lC?a~mqGJ&K1+uCM?s+ukqe6rouqVA+wTaLsfOZ5RNh|K z+0$qE`dlcsg%lIf?9n8vZn_*gd!6cOzQ-no+$FDXIgPGw8vbzfJhF3Fhu$Y-%i|rg z&(CDrfy7C%hDLXPO^kUb%I@(lws)CHG1>WwPeA6%TNLvp2t{^z}>~tsE9$M`KC!Vy`{4MGCLS>!_alln(6T7i?5AJRiGJGcm)R%_zb@Yu+Akm!mUVkAnoY-o#{yA0om0LQ)j-Zr56f=Xg zYNLOwT@H}_DG%bvQnWBiU|U})iFJkWHgwE2e}b(F1Dq+V_l)J2_1&drKhj;^H}241 zS>nH$J7nz8*qGRU$l&?)8UgqNRF26Rk@e}KNZuMRw~NdiwYzOj#2Vhvr_V)Mf^xjE z72G~=>3+WZA&R>6o#YHZskvalU)}IoGPv2}HYGFeUaaahprtn1 zHNe>==?V_fnfJ}OSq;$ccnPXk2?G*$x zh%{;=39@C-8_1dXQYc&Fb!KNYoUG9$ zzzo}&!GTe3Hhb?1C#uRN4+z|&2J(sCy<<=v^M__RlZl5i_{|n+EpfTi-^7g!=1gH^ z8OVdKv4>)vTe7Qjs*AWagfZX2c-!qLINKn>m+6FBQT$rE(~^=Sxa-f~=UB`^F1ewr z8(Zz}UR0Dq`BZp~hs*NunVY*mY)H0l)KcHvl9$oJ55vM+M(yYe`Ky2a?P7X`u+6PR zSF0n*3587&Swmo8C|U%>__gC&;}P|eq-L}cjLVgr%GbmnECP_1;7jk(8Y0P*g7=E4 zC2we-L}WT z4m#e>GajJqst_+RpP!yQBbR3M;ELeF1*in?KjTs!e+&CT{1ciI?4OSXKHt-i>yEg$ zfsgBUIhGm&Ud@T4hx*E8$v^+r_d#|O7PdykmypcZK*TP9dZM3>C~Wo8SPEa_#Rf0q> z3SV1@5WCyxFo~k12+OgmGJxxhy)uMu&1-*DFsM5VWY3}My+tKXrS+U|5=*MMd5RGg zT`Vu(y=aB=P{FAwfkn!sBJIKF3h{odN~TPIn{Tv5rxoFMM+L#|k&tiDSkOPS&-)+m zDtQ%D^JnzYRGZtsWr#t&MDaMMM=BYU^c=*K6bT*jCh9jDEck#GIbx+iK40ymbUZ?c zJ^baKkKbm(YO*shNqu5>OWG6%Ufhh?1dD)0EsDbtdG(rSX3F)0XWUP8abYbAw9T%; z2t|THXv-FCLmU#D=D#B!TYTP4y)3xyicOIsDrODxbqfE4xJC&{)ia73fQ~2=by1C} zwCpXhRnogLGf$s1$8q2ZtDA^LJS9d}ggP4Ch^jO10DjC5Sa zWE5;)Bvqpunmwp`8$h};h4uTsPr8T_Sbe;fGt-&ke@h=c=rkDTFeUocHr*V!K%-G5`#ooD`qeI7F<_;G;=)? z^M#I>Ig|y1c%-7I_=9#(s?L|>aKOa~*AvF7s_5HBfpU!KmH`?Ahbh!o-1>4^c7RMrh|8@nE|W_Zo1i#+Jxno(=oy~h?dPwgx4>Vy*Hbr+Mok>f(V}>1?Rmk!s;vZPm(fJ z0Tyck8Y-aI;h%5Ce?NXFLAPcS;xMpEfyE`g8uGE-FeZ^DBaH`MEw%HzJ-?Z9x!(0< zPvc+epbM%V2PJQ&mFe{E4%5jrmOYSaJn(rhh5Do3WfOBS?uM2NaqapWFrl%MT411P zO^4;-h(O9Ixo-pJpxy;+E&m$0^{6=;++RsG*A{JPg&iA5!Nnrv;FHid1lO}fCQ*s; zzR4l3Y%ku!8A40m%1*tUHn4E!lfFv*8sRuC{aaRT4q2x;uG)z`9udRCzTkzE-Hwfe z%~i6ekgWMG47w)P6U$*nn&;C38c=7*-eoS{G4aflkZDkTPut}C1(`|>@&F|<;3W5W z6!8}}zpPVX(*7Yi{iivKH(c5eydsid9x4a@JwV%1wS{V)Fi- zsT^b7McH@f1@da^evy(udyLpnUXj9k{lam#ogAu$brhh5k~9{={fx@N<#mZ>w=*ju zK4qTqH>lJ?qbm(>`xC)?OM6TUoxnWKEcLS}D0U}x*fAV-v?mB%oYMF^Obvf?6OJQp z**l4hmwOR)H#Q*-g006m@aWaKvGXy8^*YqpNF}FB#DHM;wwI&nOM^gS)Nlw|naUh; z6?t=F5%M)zy?Z<29TZER+KfFC8g*p7t^k`D(*v&!6yVyeI=jNXp|Q0)V`-61fs+YM z$6h`x z)Haz!JQbIb6O@D*Z*}8{L>N5g%o;ozE+9hWQw>L;Qv|`-ADMckJfLT*}HV8-?&$ue$A11 zV8dq|24KDsC>tpLjdAK`<}ZAB20C)s`hzh^EV~6e&zhvayBsh-So9E!kWJDeVK|l@ zuGE6gWOS&*FO<#|a(fViCT)kl9!+Z@f^A-hi#bKOF9Y#@^t1^d562&h<_fX05xV0N zuk?^m zafC1ukm4kvW=8iyJiQPwD1H?w_z0wO=Mu2~vP)gNJDkh0j3jcp5VIa!1=$tlK~*2P zEoLLunc)ww7hU#9!?F~_nKi)97RqT4xq?gDW(!tY0*<8{>4+S%I1{pKEpi_~@!DR@ z#~m`LB4CR$zREBBjDs{pRoC@)n8`0JBTM*Z#c`)qy|DfzNx)|hBI0w)BsU^Se-K=^ z#TSujtGo%6!m~Y^Ry$y&I!vFaS*FgT_a*PGKNOte6K$&5i)}@}H2<+B5^${^R;I1W z#FxE0@I@C{ai}Jl4_X-^tdmu$Q#OgtURMukNjB+DD=w}T7)56Xq50sYpzBUU(E|EI zqXGl*&srFZ*jeBw?@`}j2Hn#Mu>lbn7WuCbB+k>59D56`|Ig;Dedbq2lcm{bERsxX z3Y-}LVN^9f1cV1>mjjzt5jkcg(GlZTYdaYN)!!+-e&qcN>jL)c#M(m*kE4vo-VY98 z9??Vy@sEDwVr)JcNBd5s2VZ+-`ic)1WrvDMP&0W0ecW;BvT0_`Q%Lve@1icw4<27d z#xqUUN8}aVuc1vm`(H9tl=llp`!U$u6m9gs&!QOVP+fPMu3s!RDf(H)st8&&PoYrj z2+kw1(W`xAj9?0LzfmQ|dnucI*FawxblO1#RFOC) zwM)tGLicpxKdaGg)q$=!b~_`Nab+CPH{g_6P8f!oyMuYS7Vi>0zl!saRuG;v3hQbf zTaow(rq*W6%t?Nsn{{idkGKjnpe}g@9y>MTK-iyBN_)R4fqh1gci;=%D z?-4oqZXXNndqpI}uCUnla0XkG=Bt;WNPPmMMfS)9#?2|r^J!5-su|9Rm4K@M9wIg^NS-E7f|it&=91GJ_&s2BRu?@ZV|QL{ zMBSq#N_5Jk|Fw-r<>exa@T71+bGa{G{{V!Ry)i819CgbkbZ;tol+ZoGYYy=nIKxPOX(^=z_qdbS()P-+ZQgGklc|( zXd!V_(4VA*?vx5I9WQxYqcKbi$DB@f#r1vE}Pjl#UV^0$7EvT_t zAuQ}fBj>`TQj<{x0{qT^wi`mR?r04s6tOw6h-0)xU&)$zqg~>n>SL1K6D_;_jZd0j zR+mH~?)=l)B4SBIBkg~g@b0=Jx#1X0JWLyT%@oA&3F`6$Se_eUa={sKH60DuLE)Iws!F!%Td#pYh8fl4JJ-?Dl#fm>d@am1mze3*nAZjX z*)4DT!)P>L-p}+HoiD!Tb9ImvKMCVLFYM-QloF=Lx|uj;_B4;96n4Qpyj%&>+9cDS zFn3PE4%MWcglBKGGVI>01TR`TnSpBk5dfp@`d1$sa1DxU^(@lQl7j-y@C-zQI<^qb zH^&bo=aIf)U;qbX5@|g+A4|CYZ>;c-f$x~ewh3Y>$6*b3@dp0v6Mtr-Pf|5mxo(`P zxeNDA_8W}xz!!aTBeVHFh>pg%q2TaV;QY~kJ-p2ecroYQqoGnl)_2o&nvbKK-$8{FWgsDAM{F#ei|d)hSTP9;o5WgpvMLMkosZkbgX*P!IhRuW?m0-hSNj~44$jK;ML)1oa!JcdNK2lWDg%K^T zQEo|W@$*DXD2u*2b3h@YBHJYg+RSHVpoMvumHx`(=YZ?J4BB;Zn|yzV9HrZGO_2xx z4gDHpw1&+5Gl{H9p0eu4MNEHRXLqocqw9{|-%}?~Lr!x)VuZ}S6f zG2$J;kt2Vi{3Ismn)S>Vj)}KB?PVCt)Zn{Oj$y?kFHqW@m7|=QI&qzPViswAr|7%058sjfqSP$q%yfivxvQ!2mEcb!=1VFmT#^?c zv-W22`i0ESk2wx%$1@kG=(tXLrotfgACwn2C-#q4Z4D+B)7JbVUN83#2I8MkRv#UC z(Cf|u_@4do;8oA#IWREwaOR=+Qj+<13I8SqQxk}>x`Uvks~}vSm3fg}a44)#4K0x> zn?@Fjg%-?4%-+$56I5J~%-HaY>UnicD^w0kyy9T3sQa#gi-)%rTk$pOH)5hCs9g!0 zt*wQ)u1eR5%)pr!3K9Bu36)r?kYN@kgO|EE8}i(sT5CSw#LJ(}Sq#4Q=^0k4Zw+Nt zh*-Suvzuj#!}(bjR!zTJ(%00Xns$MmM&eYTw_^wi-ez*QeViW#f5|~Wbfd{WXtV^~ zvi5*}o29DDA<9U@zIIvP8|vHNiO#uL4|KjS8#s*IJA+uV519J_Z!N02hKNP*T)dHk za3&s}-9MS!>yjL=QI01xsS5>CZWTMt&8aXody@QkhX0wHV$|qh1O2 zfa>9J0UBYMY_W?c&gD(M-riY@?wSU{+H0b`K zqX4&)WdNn2&_n5}1pgas_(Otei-Lazg&Xnm%GpdXMuB^_);OcQvDPP(4(^AINY2w6 zlsJ*}XkGNeVz}8`x-EE9uei8M)^u0HQDs}(9l)_K#u*M;a~olA_{k_~ZE@Qcm^ z2U?wfo7cLt?cpuRraLKFt~o=mi0#tVwW^rykR{NN4JN6p%u=Ll;IH-XUwI6fV`XK( z0K`Wgn33d|6y|zoUnk-b=(`6akh1s$mNqM?((&_&xfei_@9vUBd%}6H@U18p7JO!| z%bbv$_j9SPUs-xqa~bovSG2s6U9P`TzYRwb0a0OeEShBWFoa+OV|7%zc!yAv_Q(=- zd_@z?{W$-~Az1unu5mAh+VmP_Y#x-E>nXR0yO?BxB{80LKkRsq45AX#Ez4G_a7wBI zwrP_6%B7lmj3rS41&8X%<>>KWqEGhnF*;njqqbD1x`|t+52LnbnWP$85qUU|1GJ-( zI7XVe9w)l6`{eNR@Gp$r*aK=(kjHenIjA=;wCA3xHFlLfapyd3^)T%ZeK5{8H%OIQ zA+z9Jv7f@8K_kF%2)lKpaz=?VLS*X6Wnu-;Y{~N(yE{WSfgDr1+Q2lO4)#^X!V zqJp>1#|DoeTTwx^s35eDMe*?H!|o!S)^y0V;#gi5A@}(OML~y~_W^QH{xaG(zcOsd zu+9^3h(6Uo-8`8SVerz zkS9$q)LuwYQWhzm2>xg##9@UOd-Znr7nDyxSYnf&HgAxVuVqQhCCxr~yktOhsdJ#j zB=y;m)%{+^#_%I0;|CC#k=GxS;3h!z=)nV~SZ;<1#MS{tA(m5_Q#xExjV7#nH}wU# zKcDW6RP)_%W*CpOg7!OLW**-z+DJ7nm=~l#rLx!pgn5!pAKGxJbUE*zk#`HtUOuv> zC!449Asxi$kDA}OxT-sETaeyo&2sDC`IX5Nnv&r;14uANZW7t9TT)-4&3HN>xQ$ID zOcpf5k-K|?md?EcO(C_2UC<_lS)HSADNAUCe(HT^qz7Kf+8T({jnG(2ezabbR;&Kxr#0@ye^d!?0{&PxZMVJ1%+JJ8~?Lh!(#=;;N z_@e-K^i6Q-kn(t7X)vJ!IGryNA!aBk=_|Ac-%8A=ya|UJ(I{ zepxX35we>noDq2xL$swmCA3gS!rU(KMjO#n@^}I=q=4cZ!;+J;duVNi28MApeXo0m z#ghe+k>N@CtWM8I0}b`|`L#+gPy_68A$7GU{bday|B%?`6R!J$iN^hHdwAruh z#ngq_Q3GH+Azf?TU8V)M)aS|L4MlgP+TFy!xAH(Sv2PDo zvs6R99j=+8-ITgD*60Ces(Rtkg`y$dyaFQ=`ECc=dr(s7ah&;1zS6+de8nao=7eHN z!}Z_}f~eHx6oYJ)WID{*x$QeFudjNP7pqzlQC`w^@fH+nR(HszMakv&ik2tY9}s() zFPHMsZsyf$HJ-oyP7elyFg{`lwY+s>*4VuHw>+te=%H)6lx`c)z?X{m=duV_9clY@ zI`D}+?J-^=#WAP3)&oxb2v=ejJL!z{aw6_-)gU-@dB?jrgE6&!qNq2Ani*wM407rE zogz}5pOc)}5aOAWX|#W#%gzTrvIi91Z^>umn1AoG@UvW&m}Hf27mO({Fvv~ugBh*B9P5(y<5j`9Yw!B0w@OO`!Q`NKwao4x!Q~;JM0N|%RTRyQpp8hqH)V?t3P*<>di2-=WuH51Fb22VjqAu zf+!J4Icy4G#}AAb%gDx{#+gy~R4&@ikD8*HH02wtb$e4kKXY~wB$utVB=h?@?M71$y?z2VYPZ_7~j zhD?a38dn>e1nq@_gSgT*kTLjoTc+?9^t@Fgs2J9DZ;f;gp%8QL?$F~59MBKBi{t6 zQ?G+HeQ97;q|>V!ExVdu@J0A8V0vt1{oY6f?-v5pPE6Ag#ezY^RMe)jvZkyNdmOkHwF2O+gpxkUuxS_y;~#Yd8!F+sQHdMINwrubB+dkT5pySSyV&`H zFE5iPnVoipDXPLAVyQf`Jb&R(*$-Z70{1ouKaXYoKEa6(ke~aZD{C)G)+7aZl9V_T z8GZe08WiGMeeEYuMwIV6C^m_*x499a^I#lOCd$Ego8$2KrNfU@*yK*?+TnZWr!!aX zeH4B%8~z^>`EWZMbesUmga*}Yqb(muZBOPwY-ss_x#g{h z{YT?ROY&E32|q83?z5+7bh_^LBl2sl2KSfdg?O8noc0ZodFwl>)XB`Ykd=ic7J;?a*w(Yc$ zEaA@wF6GO|e1VPg7Mw=yjp$}8h7)rV?0)l868(?L{iBYS#&m+>Yq-$8xsPFLT(l6Y zh#QY}U}}U9nmMZuu$Di2bJ={*8cA!?Qwg$Z@dcahz>=$48#~?%AUS8b`MCNG-|J-A z9u8Mv&|tZA1fj`PEO!qkaq~#l-WTY(30c^BLO&c-5OUYnMOyaZg3#0T$i+A3(@xP7 zX;3at*cb?@xzU+;HWLmypY`ywa#=tu8J5O9E2ES%uPkzT6C@?=1g4!iCS92RnXYSm zi=VQ|am)p34Fif071%B@_x?=R2W~JmEByq78T9+WD?WD;aV&V}nT3XsbEuBS*hd&swQm;ZrzkZ9+x%0q{sXwzu||NE zri=^8;*Jij=e2?q=z1Kv5c#xB*|RD=eYxwYC~3jfX11wC9tWjSCn(%-hM~4>cXmzusVHbzS|6%K`quTtJHQpBY;!xb(T?!O;XmQs7 z#oeuFaYFE7#f!VUySr;~cL;LR-`@M|bMC!=Wrc+GX2Cb}KJ%GpX2!&Jx$>fntkwB) z5Q3#f(0#13ByHt5DrFqLrdp-dS?o%{O*3h63t*If&JtbaZr zVGy|YFs0%1!e!1XWLX*vE%N?thE;8YD7}z;Su??Z!<3{J(^H=TXXr~O)3{HjJO;Li z!8s=@DIAQ9oG?|l*sJl`6JQmsr)~~u9wzTbku>YXg!=a0pRM0kU;k4?GKZ{jW*U{&-LtWIIkp|Q z40*gsZ?6e1Ry$F6f}YR@GOVSF6~#tzUm%xuVnN)Q!hEr?0Qg%Nq@xvM@Bl< z1>8>2m25lefMns|$8lknWMGc(1c7~h2N}{36wv2!_#p&ajrWv0>pqIXV!btxti==g zG0pDob=>38OnGzW{#=}ph>55p2g>451)$Bp=-E4p(ydsKktwz7WR!)6&-(G|hi*V= zX|J7K|9W*D*`PT`iilqx@PYr+vrf(#DRQ;`fshcNx;m^V55Cw&+se*a_)t#|o)Eit ze)O#cf4Vx4O7doj6r2V&%n}Ivxd1(0I!-ZAd z(s5oywAIy10=+W^{a4TRT!EP&G#-aU$ox7Te|MWp;uO}>Ip*+CVtZ;>})X$2=V z?^XzTHfQH@Z*L*2m@*82c|0HMxe$?tbWB4Be!DeT{xRc=10q_y(+D@m9tIjd`w&mVGX1!em^E*uGhsMPzxGOf?0Au zV&~PaXVQ~NaUFq$tf@%j)+^G8uL!Th+ttx5RY$Bjm(Y08!)SCvY}K!}k(Js`KGTpH zWXtPy`0UQBo1<@n*%N{|1o=3t=n@-bgU#nP=6{U>XT64c&Un#HZeX#D)c=!3{Y~3P z(V*;U2d$KFg?P6RtMB=NTCqro`Napa@%X>$C`~|b z+`!0^6U()%w83a-SnE9 z%gF{=++mkoHKWM{aZkE>#r9vutb@yttfr%xBJE6jdSCb`CSs1VoLfh60JQiedV^YP zFI4hB9l@VCX1ZEmNmaS0q&?k8P^+SC2;Q*Y3yy|^G!J8IISCH3E6M`OmHp#~%#IzY zD{!PaeU7T=`e@xN1s~4SIqy2cYiM3lIJ&nV%PwEK?-#Uy!cCcN>toA%3c zrH+20z>K59*9QMzyJ{T`G-f<(Sss5hKGSm4WnG1@sl~R5jmS{*qP^i2i=OUN*^6*$!78NP^K17lg+ zt*Tr;Dc5pMw3qqS`_~1&O8Vj6F4`<7?!>%sZX{k$ux^0}=lheNt|H_$BR2`HemhJ(GB zu_53Tx$XD3=zk=D2j~051W(r}1o!~z&Q}LN+cq2Y)s6ldF<{o8{cM;e5fV&)PrlQa zd`tlA%AXvD|LX*Jpu>{!2e)Wtz210B1IJW8b(E927X726JAa67A|X_7&EpWguHxa_ zT3@S3r#*q2!1t_^WYqJDyvD3LH_NHbs^#?h_f$)ieSM$Q)g@=Sg!t>3aZPPMjcfUf zd}tu$XB}Ke3k|;HbD^|qC64>4PDq_P1QQx!3!tyax+UkQRjC&x3D zpYI+WusScBrV6L!+VSeQ;OD)-~g0&)HF z0CD;^Rg)9TV>P-ISFF7Yoc|kHzYF&257hBkP2R_O9ODpEvMawUv%b8adq(OoK({*| zm6KeVF>?1e=tV_EgXSu~1N4Hl)gz>8f3X9%Bp%Pe8rne?t<7lv4Q0P=>b7>8K^C20 zw(9wx4DbuV;lLB+MppyE+)QUE`d2hi`lbl0p^qCYt$riDoj}V4iZ6a(VU%sH&Gj z@-oeY&K2sB<_|ApRn+C5kK0*?<-3!p(i4-Z!?(I6+RC&>xbzAS=F; zV0evbuKqvLMn>9m_w!E2+HFKH`8!Sw{(&!jdQZn^#?>}BAN}dg zrcAlq-@Z3j%_IQ!*hT8Y)#J0e9iG#fd}F#U$W30~duec2o!9vHIMgr>Ml8TA6=PL6 zt-hT{9ou675PuD+9AWA%u|09Sm=Y6TXSeZ4fm=ljj<~v!_pl7r#30V62VV3ckb)ou<*smK~{Mp3Sy?@E~SdHO6g0#AvM zYQezOdwAp~6^Rx%bsx773Owiya>i%T?=tFRfMd|C0r;R9dP-Jr>xD+yhYF=}w_i6T zrrRKL*rW5DRz1#|p0)OIb+leHdGj8jFl$TD33m-AXXXEyWFb(7wAWazn(8O$cdZ`m z(+%16OQZgnhkdx?ji}?@Tr=YZnji+?ZBVCInw~W^3jktTio+pGY)gh69tHl?J1HUnZ1kAn| zY#>=u61k&Y--f6r#~_^9;MLY6cb^)?w5}xStxq&ruQnq?Iw?T?H65e#5@YTZth;}- z7tb?dav?^)e;ZCAkRSoU!}Uf^gOLg0qd*<@zwW z(XWn|>J41pP4Ptzm@%gL+p6XN2!T#@akBN9NG4|AiBtA0zlhD`j+@MTRl$F*ur+#xMBgRJ`Kc@_pjYdF3{Sqots)r<%pRa1%059 zmqUg$YmkAjM!voHCZlfH{2s&t=<18Q5zg!H!!G^s3$Aj8H?cWUMy@X0pco|K+Z?K5 znLw6pwKv=365J)NtXzXxqJaPSqzd7YWP>ryh}DsmFXE72HEfd?y*nP9v|7#IlDs3L zsQ&<}p!kbBulEW(18p#1^hNJVzS(r9UzsYz=8T>6p;-fd*2l48hCQ&<_S&7#g{`Di z)jgP4v+r29&Mqn}`GXjjBZ>Kf^jq<@AGz~7aN;t$h(a!kFfTMgTDs!xOo9BAmsw+& zCsC$R<`@u%$J$TvZ+0-|o${|PWg;ayz;8(aMkg7;5Vsrjy<8E=BdFs@|Ijv{$3GZ= zc*IiOaoR!1+9MvlVFN-uK{V1DTS&^pW3T#*fdSYk57M*bIbo$5`4^XT{-dP~5@H=| zMy!EUQuy_TAl?1rKglZyiV^hOpztt7^hE3V3>Vkw21A`e6w=#*Z!P(DK^qKtqXseC zG$RHIzznt!-nc{AI(vvC6tFbPT?xAUV^nzb52gGc&)pXo7IX*6{O<|)HQ3?aY28?$ zbq8gz6(3F^%2gz_=@<>|vRKr_wf9i!&sw$%@-ptb~mu_IS6 z8e@tQ`VM>#7hwQks*XL}M1*6MJzZC}%I7v4EDJY(fNi9Tx( z_zMS34F4J;tLKRw9(CnXe&&x^8l7t9qqU|vEF&_`S(mOaio5Jb@*?26ImBmXz4}i|#nrighS`P`v~FzWolIE8+obeLS1w>zTx%PL=#(f1*LS4RJqtL`b}f%+ zenye9A~mTaYjAEsb7P<9Q$cY{cV!E*V7+ZQ(7^$0gpXA5csw(LC`-tTg7Oj1!87`# zbBR}Nh}p;$pRW;C-6ba75F*e5{SPu?e*GtwUVJ6{1>&fPF=*ESaj;INpN6MG%Jl-} zkx?{ZAE6-Ls^nd6iox+c;YJnPx7(2rHh74NrSC2__&-P=QmzVkj^>Sf`ctvK@Cf&I zr<)@3c==yQU`Fl$3!`n@BW3VR`WBPAXHEbIr{!N8v|`{HB9Ik(kl_xpwDD1$St~Nu zMOcoE@BplTf`fXGn?GX^aZ-P1Spa@oJVUC^Mt{_`bIoe(dKlxx_rCk(>P|^RyP;<& zi|Et^#kw{9G-?6NHw&4a(HCSlc!k#4kp2R+wPQi3hImh9^4oU5nhwNVBUXo~&#nuL z)IDed6dMl6rZl~eNTR60109oqDhqF9om1^@L7`w;H^IS#oc*Kl%Ckl$Hlf`Pr}GnF4#{T@R|K!n7#0sy%2;_C6pITXf(F7+K1%v z#zV7ukRYXFHy~?SPthX*K6BUsc02hG2X}f771`%zf-7$0o0RDD8>+4hA^ewkBSC~i z;g8wm&ywHb_%~Uh#>g~L!_6c0nivPorvz8nN#9_n*(%!~s84VhTYCY2?e?cD$cWWT zCo8n=Jj^}K_v>PTHu`O}VPL;!1d2ExA;_*(Oo(Uq;cvc=Sbdm4yJb+?NMCz*%M09S z#_{fvf;3s|DfEr>N|nn7E_YUi7_&CEsrf8}__4s!^I`=YCau>F(l z5GyYTO7oZE&k$L2cjtJsijc%8R(QexPkG)Upfe=IzB_q;;pPL8O(#9m{7$=pqNK+6 zHL^o%c8@w{nKwNwdM+1ocGtAMQL(e1t*P~KIt&xk2>nh5*ZB#2^@=nZWEg2={BB9J zO{%-ws(fPm5-U=fPum*~R(}Mz28=JOC|9pWq`w_4O7nf}t6k3^6I3-&^zT86DO($E zPdo2zYiqvC-gOcC`r+Z?L< zcY!LPJ!8>u z5W>9O@do-5t{t=WHut=5fAtlyMoaIlA{lTr=)$E1nrt&uj^Zr%;wvG)KDVXZnJW~& z*A^r*j1^`42Ty(c3AFMQ*Oia%h}3tY1#$)XaCrRKsW*KSM{v_ zt8k^0KJUFfbqx9Lq@5o>NB&G}y%GLb>&wIBUwx}#w?66&v5592Gn;z4^QNJZ?j>ai zrtaT!`Yz}Ll33af4h_%&;6Tx%8A}~=^F=NJx!Q(g=~&XjTspDWy)+@m37Oz$ zFE8|&8T(@8=0F?YHrfmAtVbdx?NnM)k6jTrun%;6(c zed7nz?wxh3eK4q1!{%%bo?HyVFEW!cHpL;P;kFRekR_e&c=r*~hM^pQK!M2$$^Oxs z-sg2-Xg?|fjHtVn#I|vIdqv1qT3G$~!{3E*AlOPK`4X=!eYYR&OmX{o0udpj)3%FS z6gLMSZ;D8wF70kSh{lj|3-NX!(*U%fMi#|m^tB!}D~pS(G<}Fa8ievdIu_Cu8!L#k zH6)+=2}+yMb^5#b=A}0eHQ8da-ZL7?#Nh}~s0A2Q!IU-5duNrPqT9Q|E-?W>2gIi- z9naL$T$Sw?k|*knZ9f=pV$kg4P+vAhC61I4%9xq8?nS=0`9UiwM!SzakSv{rm(G_p zm{jP-&Mbz_d&9jobVQ%gAh&=@7}pH)8V^VRLh}CjHoJ`E&6AZ^2jh;ZsRhh%k=pZG zYsktPpszjg3C&1S2r@)9LkQN>TCX;-TJ?$dPLXgKf)Dn;JE=xEGO!1e9bU))g#Su_hi@2PhEhrG{98I=nj%XY5r5S*HJ-ZTg<*ua z8k_4wt|Db_De^!pD{HU~3BP?sP$k+t_v`?DVPYU#j zg(ktYoOrf=ECQleCyv!svNqYyfK#dZx4DLcZ@TA*)y&c#oZluIYK|@pA~3)DoT~sc zSjzI;9kG7Q+wS$PoYN2^RUK^_%%5!ZHNOa^^195+Kiz-`+We983fQ?SGJC9foQ-yP z?(ACPhQnpspM%b;{LbyVho~&@m^R(rS0(p{c?uX9wA`NY4Ij@Mw0$qO15cWs9#7V) z6MfTooE>_kh6@TjE-XZhUos)cGX_%$GAuB02PQ`2A&XBF=)L1c|6<3tfK~hE?m{pW zDZX1rthMb)&Gjw{GGww25lplYBD8(BkU~%Vs~2Z+3oYolW{WY(P;;lb?i?z zm!%}h9#4I`7y6lZb3*sSdIC77G|e_Wlv9Ppl)@Li!9YXMj@WyfP*`t#C?K8>9wP9j zlRGsra>VIqxv$`>G{X`?#n{U_+#A_=fjxFVB~QVpu*FA7V%_#w6S(7Am!sR?iJ@%K zUMcx1;tah-1h~~aD2~4FU6!JW#GU%2COray8E{0;6hli->;>}6RkiyF)Uj+9fRrzv z!YNUu8CR5;3z*6{wOnH~E1W$Jtep=HOKWy-s8-wrK0SD_bN8sG8@Pn& z>%u6nc7&?24b*GCcJ}KFYS;La)&;2^xP2@TG~DueU&I@CNxRsB*bcs>K&wDB(jhp$ z2R|-<5HDR5c{h(Nv#)+-!WzSOuS1IaG#5)2$fCIgX_Yvu&Hft2EHHSmLBo2NK}xB) za6gf+ho#xmE?(xa$qBmSp45if5r#-z)R&xP2Uo1dzv}pl8_ar}E<_V2SyTTj4ChW{ zbU5Hajb&s_Gz#e4p6NQ4QJER=nI@(@o`DT~RUo9-oE2i^8eeZ$W!C&p4ennC*I@*z zJJL?=)?J|nxsAHWi#7MQ{~Eb8pfn|bYu)y5mmTQ#RwjKz@ixM&gX5?$uX$uETQq~? z8Ih2MKV~&dABpqxTUM|DS;U_Ph9Z!ZM|+0bSOzosb0K#TeDvy^ZY;9vv<6_uz5%Q6 z?DLPK;NcEO*6?DRVW{FTw(e}!c)JA*T`3PXFyC>KlBbQ0Y<_c z)v(%6zZ$HX!-PT{;!Un|W!^Xde|Uji>Ij0ULz);n{$fDtV087t$yeBNSR+`Wb~$tQ`kT=8wMv;T<&TJE-3psv1+`$2(pO|btp2sre49fAwXzM(y(Yux-yJaE=D z=AK8lkKdJ3W#bO;J9xKO;fL6)bXJqqV`(k^1bsjoWBPhx0kL+FnN&q0mx&p%8phl% zO?Xn2x|m(Y)3TBJAz(yTC1qq zuRj#GTm@}_)C{)(OUNIBmvpv7i=Q78Q)-~9#n4d^`XjkjUc0e0;@?EP?V*SlTvIIl z?%OnxztEj9iUPF|Fju=IsU+p90lG=lx=G9{Yf3~Ghfy7W^|YSS#Vgg6q^HR}@1O^l{s0cAHS&VMI@?ajbmL*ZA*oM^QahC z4d`rHakt0mD!y;qsN%z`cIhsq5B*MVgn$nPdAM-EU>i#P;MNu-EKz;_(*9s1&3V5L ztxYE*2es5kFGK(J6BYIND#oYDpY_4t)rz;fx3kIu4&4qGDIN@36fH9HH{>zoKsbS} zJt3_g%^>E&?t}~{#19=EVTT2nd4*DgdGQbRV_VX0mm9Br=T0uVO29RTXZ*LD5<~Oj zY-kBn)nGfP+;&1d%i_FX#t}`Y-MEbBgGW64Qe7#1Lsnfh;@u@upX9j=3s-PctyFFL zPgIx#JA=M7Wxp_SK{rS99U1}_{k=&4yFwi$wS9=xZ7U44F*eb;KNW}(t_7Tc7t14e znxBqa=$-KZwlLWrWi_HZ(=e>mLBCB3dWW|^RzXHpIY9?PeR2fV-kSAOtlcCs7n=6D z`Bk0m+-THpdyo)%7e1Z@eC4_I3SPy$n24)ukD-krmjpqsf3e>Ih9_Ek&NiK~rh2tjp=G^isM)QjPzF?Ss_ z@yuf{bjOFMJ7U>9IVSQpV_#`~o+e>}H>9NvC!gf(_2{;)2S$WJ{p9KurPzjc8$Uuf z8UsXmO_&+MY;E=A^vy3*Q=G5al4DoS2mmCGi1-L}EzLp0%w&|F2zTdtZ{$68!$z1m za^$22RO319?r=rhP-&?2zB1=NZzB#_Pb9|C$=19AKE%Ft@5gWGjt|SvL?scMZ;(8^ z`B^h+CiV314Ag#k>9wwya&nAv@Pf@gL4&%21%=e1Xy|X3tz9G<>dWr`M4*mGB=H^D z41*)1(cC)MJnYf1*u!p)eB}3C6Np)!d6!heT&ChdA-Ok-0EJT1k7lZ4J>^+Fo0NkU6(k#x{WpR zRJcB%RPLQ<(|CD3IQon1Gcr16c^$REECs<=Mv-~1l>N$+>1g_Bzt2)F2duMAC+z@X z=}%;eMnxU)Ks58pQc=FFwyOM{DJe8P;`1hW(Y_;5{!E=?7mVGcvMsW82%}vw)K@_# z8ma?~6B-2JiNau1ky38MR~Ag{C?sN$_$F=6qNS^G+BK$0oF)&drS~uvcg5O?C;4Co z{J?*MqxwL;>Imra0zlG=28ulR8E*{nHxfoa7)D*VY0+g_D%lL3$Y!=)op2^EDD4;6 z(i5vdp?DbYeg~Eh+c^AGZl%3t5!(u8h&M_Y0{mf|=;DpSVdxZJ0xNsG=GQMiaujw* zdP#=e*uT*D^*Eix(;^xuVWj?+)|h8+YYA0Q#TH?zjA;|Un0Q0Jdrb|VSHKMp2~#uC zEbp@OfGNBcZzR+WKShY6S2EH+?eW`(%zDdj);m;X-L_qeV5*qBa@y4OkM%tO8i;35 zc-wwGgsG2i@Z?OL@PF?Q83CZ>eMJ?}@yf`Y2x-CC@EluV2ic& zI+Hff!FSU?AT#E=KNc~oeZQJ|u*EykJ@^n;nY8PvsBc3avr~~*iCyE`Khz6+3U_s1 z5b8jNEDvtaA``@B8>;@WAH!9{1CxXn(3ctPS(Er>C`!lYCx#0yID$E`cl22xWp@<5 zg%Z!oX)i;CJ@6z0#IesT1$AhKz5+K;-|b$HFg}mOJg~R%L7Ug;dMTH@p2VH*5Iq>K z!ar9+F8oI5(*$*z;!aV8Z5qU1e3{&F-6CMCj#zZ8%s0bfw89?TyB?U zizg>U;V{rp8rU0ay{g*h?;KnRht?vtI9lH9%TGhT2jQee(u5L|LlqW?tK1>3imDS>x-A6mJ&zHM-NI~RB|aP^6{9kH>fZ*41r~~*5TK! zxXWBE7USHKfg3bDkk66Tu!sk>kCUen($u+8d85;m!rY%b!FMU7Kd7bmWanY(5?$4^}AZ& zYxMrGrpV3Zih7ae|A^&wCi2<%8HHp<0Xu0*wJFY&F|+G#zH-L|7%B@d2#8}MFv{D; z$77r!s<1PrTKvrSwWnVm!{8H@tfuVi-on;oJyp>p-)&prW9NjSsrZ1URYi;n@HaKi zGrHCaBDmyG`|D_lGL`2(#!w$BIns>y$+Ca&z`gmyrnU9A15_ZI!S*C&AnS`cW#IyU zLR85_yV7;9wYT;RzvSVr9Mbf0RWD2b2vXDJYM-DWjL7RZ}_6lRms;yq%GmK+@|Bgz6(s zlG`i>Tj)S#q9DZq7;5P$UT1xUJ}NVos5uVVRAf`)t6Z&)vSk(NDR5-nPmKbxk&? z1G$4lE!JYC%i!uBUVt+kL#Ew14WCS56eJ_UIS z(Un1jV{b3~;dNh{};D~M_ zCasH8Y3Tzq-D-f^)zOV^SeJh!r(3{h8^I*aV7#NgnsN%EL^nc7t+cp&GGS)&jWFsMxhN>5DP(Mg6ugHMlKo z+FyQ!ET8Omd~a}s?!K;!A)$WY^)FL3N#rV?#rJEzGj7vtIN>oJWDRZiq)cU0))B@sp|LS)B%DqEbgX)M<1aj3OQ z2y=c9^yvk+Ht@P=k1~xeZcsWj1eRvunF?t}R?AJbYCyKhmC9+@wmW3TJ|CDZD`gdY zX`}T_BRs>&10_Vqsshz`#S&b2d9SYvMY^X>V;vmT8S}BQKHbJ^x^mc#ZN9^B#S$?R zz%*`b4jr#M_VAt{DUg%XUSAp6qx|uB5o>5}=FWTgMJBSQLKw`hWM^ejniE*hS@;;; z@xWP6Bz)7pvLn}ngm$vt)1@D4b*LF$k@eD2aVRl))FqlnePF0DafnK|1P-7Lm(DE} z@Q-mNCbr>!MyumIAK36Y{}XQzSp}dLlPVXSOF9jH-smiNubke8GjQ1}`lDMXzVxm(c_&Yttbwq9#;n;fNiPa%z1| zB5KntYMjPi2S*?>_c1<`{)CGMu~|3+k6|32Mxb+aE=sc7P9&Dh69(YW(spm3)H`&9 z*&4wddiH+NW)0pa-yqjfdl_j+ljY$^t2tOWgwisfOz|{ZA@s+i0%6V%65Dd9l=-4@J5m@#Y^3 zUo`uMrq-PAGCm;N9|GFWJY!ew1Qg*6tDj*tlVxM<3HELT(wuEa=%Qk)_VGH5?qAv6 zNJ=d{H=LM`;uN;S8!mcN(+^4)mb!A#bnRxHYN$0gBSovXsr8PDeWr4cQ=QHcSCxS3 zCZ()-e)?+puJ44sR!w>k>G)xdZ!zX67$Wsy{sv#u8d>?5OtLTCw<>fr?9RreIkLlg z_{T<4f0gjRVype%h`iCO=>PwU$e_*}#tJJ@Kz*NpdrXeB`*{6N{ta|C7?c2SWg`-p zrOl+W6Y#b@d$TcR;w65Xpy1=fgkQhh3eDYAEJ(ZVsM!+`LT0%_6fO1WWy>6tjecBE zsLjjK-P|rL#j3we%3`po<`|9v*sp|!GZ2e)_1;j3_4QHHAy#r~RWF%MS4|9r%wHe|V_}${=@2XJzOz{tA zKX18Zz%WAJhS`Wv#gfq&_NPW*h1pVbRi#b#!ejWoUpio)PV~(q;Aq5AAM766yxWJM z31gr(ppjVnQj*RG+cMcm(QVV^lb6#FH# z-e9VSdEG_$4N)TDC_^=wyQSF8GQ&tFmi}g+kj_|xK4Dh^cATDS3avk5i?_OtKeKvS zQGl7BJ~yvZT;JG1x}rUIP{oo#*n_uWM>Nxf#Y0>;aYc1;`m_jsr;JT`>WPy-@pPEs zG3Y**E{4_ZsCu-xffj3^Dn4T#wB}7T_+KajOrY%dm0F1fZ@hpC+pSMK=_fvCdMt>1 zSxQvFNv39!A+JKz;3fZvjoD!CPf@-H#84YgNe0UHJ5sG{-nAZ)wp-877K`9}Q&RrG zxs5Dq)(vyI;3(W)p>jqoo= zjT*pc0M%DR%=Aa_>>XLcSpMjGq*D!G34?hCDM72`1Nk7*Ac72HK#K&+rxrYv^E}je z2T$4r+;M(+=0gr;w<=nLb(SDRdM>_+C{sHZ|xxVUl z#)POSHVuv8DchAgGH(DFZ92OW_sg+2t136w?|fZ#P)JCWh8o8&yWu7$YS{2RrLr}b z6FS0J(tIC4u$t)mjC(EM7##EsSKYVpJNPWGxbSL@wf*rI@I&W>pPZ@tf^8Ce@aLhb zk*YslOxmt%k4ZMyT@YX!Gi9i_no8+<-eK0C|Qycdm=fkTRFnD%f&|+*B z!gCpXc}#ubHHp$>;}j45)TT?B(<=YqLcOYb5vfpJew+&Y<1%PQr8B0sg#_xt4gO8G zy@WE`bh5!d_UDi31Ijy91Rp7DM*bEvV$(TpzH)KJj=p6yI#M|x4rMS$keb5nj1RpM zm_2ehn?R+@RZqvDyUSJ;Mf3hkijde~Ti~e~etFSWZ_?=vSBc9UQgJ9Vi9e^*OdomR zAxW@E466?X*4HDiqau>u*;YA$TLMF@!hE9vYYsm0I5SDV>P-{64Z;Z-jh$(qYj|la zBOYDqa2;BO2G<8{;H;-53j2Q(Wdc0UvCXi^q1K&Lx=cbxVAoL5h>yjh5{nr(7us!$G!!lluMf<~IowO*#??vCF{> zgv^YEqHZqpgXoCW9U_uN%x0>{3B0Z8Nev}Ctp_e6(XSW=MX83%)sFYynIRBdmYIAS zp|s61UG_|ka#e|(1l{zt7BSRo0_szR;8LpTO zAD?9VRt0X9Jf;_|#S+WC4z)8NFgOV;l^sq`wlyZ;{(CMv|3=b(J&@qPryLY!yD2dJ z-#e<#P+?ZTtzEkv(oFrB5!>L@wuwP;Db*fd?SM%s>BsE4j;yW`h!12?mU3|1_OQno zU`Y>QAC077zD&7`Ti=ryG>GICeEAJoR!2(x0{^BHnQ%9itJNd^D{pXG<#|~kfsOEC zkN0Lmf+24LNG;7&?zK`6A@7nmZ>T+`U)SPzRx9H{=NT$^fxHZz!WD`A4(FuE z?nFYUtLPLv$`3_wF0fXgLmja|QyElr2UL0wn4swIh>^*7cSwP}9B0;n7&ib^f*tQf z-*Pvgb>Wu%Y!~bS*Wgcjc7f4)S@YoP`at?>_I%rNIbx0B8w68p^u(jb7tMsUbG8)S zU`x2(e5(V6=5r3_lSZS2`+;5_qTZ^9TphqYvCV3zRBRJ9$`NTJ&+X*%Zl6|!d^W9s ztQxDt9CfLHVR}q5@2Bl^wo>}JA8qnvaq#@q)JFr{#rNNA#D!lSTOogw>p=nsF&O2$ zt=3!I)+f~6MV#k?L=QoC;LGAbU3&4f&nYx~?TwXw69`L9{cE6&C%>OO@_I}LAj=mm z0Wug6S~}zH$=b`$uLr4ht!3yn-apV#JKT3WSShg1|CO^e63=zJ)K0YyFPh>wY0Gvg z5PahNdm~7#yAosx4e9UIuqcc(-M>T0P-lkx3y~H|mB*1QpNl7LTDWC-~f zbO^gBXw+k&LHwTc|K=3CeX@ycB?bgUsquz$#@?XeQh@7nVfWYzv3^RDn&P8?@tr|J z8uf@0JnRq@WS(vzbRa#gd(?8Es4luDt3$ym`+GqrkJd+4y)zrJ~gsBTko5;Nlb2e`dE9Dpy%X zKtu&W6Ka7c&93)cqIY(%+5woP)(*A5o`~vOUqf>PF`1U$1;_P@Dv+m67F99OYjEWE zX-^0!X*?4d>dmTTQZ{U4lcnLgX#SeEQokytCd8=54i2&4&&xnh{hU&ZW&Vlbpk&;s zRj6|!lX1(WBpTb28M^oqfF!1%jvdc}VEP!?Z7JG^fK8Ral+y30iVXmjillCb*cTQx z5#^LL|D3UgCh}tveH+H_&iovfhl`r{@JT~kv9u9#D+vqC`*mg&x;?~IpZxiEnl+M^ ztJ1|3sSa2A2Mp&NJ)O9{-rSe;Wuy$kq`2sBzh>`HRV8j1r!!E#5@LP6P&$$&1?kZROSW$7Lnr z{C4|A(vS->znHNKgA3*`e1wH$z2w7%)KA^+za;fT9 zPeRS63%-7jk;u3=;Ez?fvKyQv(AK`8kyMv~=War2)D&{t?A2W3Qf)m2kquIQ|^J)B4 zi=l7f2r&|F{-V+Y8=owrdbp|senzGkoNpGC8=bF2<^txi2AmPgtg?zCN5#mW3pAbw zM4~p@aVqi=S5UEpxnq1E5S-3MHb1y*OB1c$-2y~jKJHd~m5wC41eRRi>4s&JNH8SE zs}a-E!q_kVUYN7q$XOWi+;Kf|M>EM1fK^rHcl27R*Xy>CM>cVS0*`(?$$CKn>(QDB zytmURgf8LI=`d4gadlf@sU$AVm9G3i+V8hdTw3CL-4v;~!uj|788rmTB{4_tVw&Gt z_ePNss)W}F$gEI}2ruGrv=Krf$9|Vf@)Z$m5ee7plcX$#mC!f%<2|8=CyT^vnt0 z5efW$EB`Ix9}`$4tFi?ZYGu{5*!(kcY|N!XZ|IvRzd>hL1JhaoroHV%zKu;3j?fyH zn|_|;P?flNu!`(jgIreI?Bbwci`z_{Rbmp0=FQE;>V1c}_5RYm{@KW7QbwMQkAi#?wCip9dS#q1sRzj8YeEw8{>{V6hYs=6xsrxeDH05h z95`}b%$v;qq=gL!Z0vh{4IT?ymmDP9W&-5Eewe4^ve3B~Kt5yatgITp1a{2NI7 z4d(de_ZLuPr>j!x$HxNieWa;fbQUwoQsVeBJ3&^b&ii$l?vDrZvR2+y&~aqGu9hqf zsLuJY<>jR`jKssu1z~8oU+@jPLNmn-_=q6rTb3fl{1-*fV?PRB8m#`9Xs8v@_E%Ac zlbvOfc93El*L31TD%p5~^46EYr*$Qs%s0f5P?j&iTY3deOxZe&JB_WdM1@4nqu}Lo zbKUi)9W%1^+OQ%6AB@v1IZTvYVu@ zJcdV-T;MxV5pV#lrF!)qf;)+=a z5|k8(Zk)}X5hyE<LmBUa)=9t-7w4B!*{(29ybHm*NYh0R58ksl zUxDAcZY0g>HOvylMFMPb0J?Yp06dN>K1gZKlPK;;BG0P|OB8Cxx~ke1p$eB(N48!n zq)%x}@2IEU3)lLB&Ex?o%Ik|(Y=;-`SutuOGh8TFYJYvy~saCRArLv0=DjFj( zT1hdY^=Z6^^*qp$zDv`|#{R>6RS%ztZ(^qeaPkPxG09#$NgZg(KvB>AnFe#9c{ub~{kH`-~$ZEr-j4;~oEqxI{oQO3`AGh8NDD|vllWDfD z496^NiRb^y zVVLJtq4o3&E#D~Sj??W7J;)9;60I1Otp3eYjk=|H0$ajhu4PQbKLRu}8-;R=z1UrZ zn64ltUoQtzAF9fw?$cvtCNBu)S{Yvhevxle>ChyQE3EDPDbih(pj57IQFL7xnG>b9 zfF79yM1>3QHD&5p6~El=1+zpSxmTA44o!2=$jc)FYGw`E#D;qDyIgeS)8t?>=}L@# z7ohQ?|MIW`fiBsHrGL=NP}w!@&QNp$^<^TE0{w)NqShT=qa2GnN;dVqe~T2s%)yj% zhcd!lNGMpx)iaSF@EVVpWY8T)(pPJUWTrr=?>7U!CQ1`X{F;`HbbRKp`I!2c$vIQg zi^Wp(YXHz|QA#oR#W&$_yHe?=dTK!v#aBa(<`J#YQ?JSBpPsEdgJYr*#l_6PP=OwevMn6dIWX$&9AWwQN zkt@4Vn!<>k_%bXxPey`V8@oF>&}cMYV7>F_1C|ZG&d7YGQ{bT`OG4J3$)R?0_Z1ZKy&3#<+VM4w*qfG|Fqv z;w|$&rcbKUwwtz4IAI=SawJ+`H7Jnrrp^oLenV;1BROx@qEc5gN;nZVO7OGkTMSD$ zkq1(kDdacN_CLmTIx?=1b9#HSG1|Ym4h;A#bj21g4X$J>l-q?Rg(F5EliJC_tKY`T z;B(&#OlV->U6`((OS+h}^m}k_v)GHIkMV07K_6T<$H-NPEAW$l%)`RHMmz&T8a3jd zKUXk8DY7u93Kgx$oxs`2w@hi33;vW%(v1L@T_&Z-(l^{EdHd-7E0OfvWi zxmO8#ZhAqBb0C%-QjuIeP9a-V*s>&4uc1}3CDL&Dj0E<^IS*rHigZHzSd5!RPhW-{ z*%{67;=(ZejJTWP#bFZ$>c7FyD-T8*56@!%P<>^8<88(VY* zNv}$DF|pnvbNZ^)mj)3K%-5(2T=M>JxdNv>aLX^y590h?<$arWU!<+?lxraRK3X;R zfw-q7gJkH3vm+G@sSU`z#;Gn!Vu9Erz42#G&0L=zAaBxb+E3=f+ z?C>K3BZK;?cjn$Yr5WF=C9<-7W&wf~R}_)5WWY?v$`sx*EGQ{n5~juEp&^ZB&p=4c zur|fO<`(-B&LtzekaO#Wzu8{_jt_C~qjTomk$_Z&tv0WF2hS5tpNER<#A!DHy1s%Ush{sj8?-mj-S9d(C&t0E2{q?$U! z)SR{B=qkP%oWZpGR3o2AL%JMfGkd=t=kT-nPDK2s$u^BBJq?G}q>h7-;(*yUW+_&GA?~M?5$#F8=xxwqgy8 zMo9pC0Gh5m_9Gr*q3qoRGmxt(Y)@73)cD7D8Nb4`0<{o{_|j^jIE^XW1`uzNQ2WF_ z1s^C&Rxb0JdnrkAmS{r4)6ABHAM$%lTWCXzMi>H$$y8(`MpUD%?!PGqTGtY{q`$2k z8RMu)+Xj+I*O~C)W3VeP8*(cBH*#zvc^f%>;YefVjlU79hV~b-)gJ=hoySsC z%Cmn1T|9>G-f0HW)ka(Tc(6QI+6vq@OsgtBVXf(0SgsYWo_|V*wdzLc*@sPekF_`8X*+|>H(4+ zH#UlxYBG!x2pRHIw9)AWnI1s_8)?XxvZjkHCX|pvNJT|uXF`#@cW3>3Ja!sJ7&v&6 zItvb}ju#-zJu9yrki~$U{328AK{<`Xg79tV=_X@EV^a;(t;eqfOEgCceG#n3%2M$d zPd$W=&c6ap<7hwez#YsE9CCdWKs0l#X1960f)6vbh3!%R=HFo z@@%?#WqL|j2sc&m;F^Lm02#}0{_6}&sFM@&@vwK-ab2Xzx#7G~z?=`F$5)7G4p5E~ zeA!5sv}(3KL6sA8U6{it>2|S-og}rBmOQpUi^G5^{SuRA$=^_wXsy%ruBX?z^!3gP)+d|=O-BOATtIaY z0aC-9DJlZ|9>t0iVZ?HAuzr|eouIUOJpI8AK|bK8?O11tEa#EIH6lkY=L<;*6xV6W-bJq4`-7O*Zg;ys z&r*l`0fS%xBSIlbGc%7f@t zjYf$w%l^&7jTCK!hF@BgopQ=yXkF2#>w6FQ@*Ub~W9wVab05-YI6`1#rS8%(nk|hJ zcnh6Rg9ByUm24La&3qok{3pW35XqK%$xO{r;W7-lKphh=kzNZJ_>|qx8&1A0Rk_cK zkK+nY1ybG#MhWs$<&r<+zzKaeYC>Sr|0)qr^O+HltLesgm+Y&<8{b^*v2bZTB}R^4 z>@*a?Y69C)9(}NZSgmx%v`H$Ovz85h!{;0FT|NAU$pZm**@|s0@Gfjv6fqB>dzP1e z$G>l2pYoveSvOitohj-mI3IDkA)7vFvKpRflm9d%`>=4ebH11&b-&e6Gje9LKGVSO zZ>-9w$QZH@bc^jV4VP`6L55Y4nhyWlas5qR>Ky>6!t3Ikm-kQZ_1|f#f+qrZCa{c$ zxY?Md~PyHpiA*K-=r7SGibz0B| zHHDC=rGw?u`q1A|Bz@}PcHVgMV7o(>4-fa2pPhl+v?xcxZX-1QNjW_YoMOH~ZQUCG zsXWww<&%vU#H7LyL8;(mk)e=dV8hiR|KBb5*Ew-+;24C zI93dKXJsCwhYtTt4J(J9W-ZS(2*yp7?R&XhsUQe*Po z>Bt%(SYUgpRxq3yxM+9xVPmS*;`3@eZw(We3YC%_(v`?`InAz;!CTT1dUCPpK;wX7g)TuIo{2+MnyCIo$UKy@o`Pakd~*#35ZqFVWxINa%jG8B$+_9gKQ*SRuknvxd8N1 zLpHEIKA9dii(d&R?S8~eOPt8{)0keWS{lp3Q(BlzKHHObsWY`}+Lmp1hYzye7fW}? zE!|wZ=h7z|B~fo9pKwaGdJ_3Jgh3SJ_4;2F^yDh#B_t9x#ZGNPHd!jWvv&g@8G<9x z#Dy9`3jQS{94FKd8L++uFd613O6H-eLLXPmn!nZo52Pnc6|d3#7}ChT#YYBuHJ;+e za&BRn=$e{*Y(%zi2AO=l2Hj3^4DjxXbXaMPMD9cWs>5!9!F$zyxkYte^dmGqr|RfY zzHmA7p5s!2T_Pm@v9EL*S>=$SLCuIKSKyZxZz%F9DUVc3z8O|EHdZ`-Y~P_v<8*iAClvd1hp~8?I+Nw~ zaGJ*%%~af?OQ42&Y1eW%&s)X5Od55?+-w>YIjH~|EC*_=IP~I;5qp3+@fK^)v4|ro z5>ub=qYsTXjC-9bO|r`TF0Y!XIK~(=B$cXIv~SytUflfH*$sh3BX$ipf;8yEmk8nk znA{KI{nzhSsEOGg!O-`pSd`$wdCqXSlVwN{5{bCE53nv5tFkyNLYG}iP zqIO`LHT`1aWW5#rCAofZ#Fwv-k~@zV;ALg81u<=@QtWsOVhrj;+`vmN7Iwq~_KpJB zm?eIpYXNjJ8e`%VfxL<)ifbvo@ut~)r0PWooAk$xIVlK9$s?6xmi0UW*AX9#@|qV* zDeue1)dU`>r#7T|Yg^&84wm8mwJM)MIe`H~w z|8;+91`mlC&y^}_oyL=M2ZO3c;tv|nYmC9rAxZ?@rt(vR3h*-(D=aZ$jhqZlnp{X#UPr{SaY`c&usuIG zy~hT>MUn4?nx$lNnAoFKDR|?NxuILxC7@Gk+%xFd?T0N6h1n%uS>EO0WcI!Um+oz$ z45zB~0i?HOv*(AXLMj#O(UOx*Vl;5$+8T?8mI*GS={|LSd&`qy8XuMYN-&JZ`!2JM z^dEa4q9`>L&m?-Qpu%>M=BbZJp2llW`t9wGwoUbwUVK(+kSUQB_}V!0X6l)ZN&lPG z$wo#8o2KrXoyV;C zZl_1Y4B?;5@#G|vrcvBELrcK6N|MPy$e=`8%3EVk$zX}SuLAru4hu`edqUWjCNMF1 zP%^M+Xr63q`0=P8my39S5=qhKXVAN^RhfF?ku?sLf#wGqkutsp@d-p;x~N0kZgV5Y zNs{m?3T6=7w5!D$0iU)$T~_S3Z(4|r%Mw%6AG9>*&?aw$9&~-8Zekkc1GVa&+03ha zU+_5EHFrR%O*5(Vxu#K(Kr%2zo|v=vtaPUvu1gXZNn^4ZxqC;5!~TYyG7iRfnkXQ- z{+Mt4K-$B7*qgzuHt*R(6v3~M8NHrnzN`TuPw-tBCwc;7TY?HNtI5!rxbv$JjTpSo zkZabpVUZ-s+ZN~4!)YDwp#!MElC}1MqZdwBkZ!VnVkr?X5#J|7c%Y}|rzc;4A{?BF z?q14)A_?UaKg(}$nu&#%b#(_hR>Q}lSJfk zwQ6^MzfP+W$^I3+K1y(+JZo`YTGJ9I;;C0;Ba~F<+vofOf6o5aGEA+*51Dg`)?0;r zy3=b^NerJUJwF~!-L<8L>-Zo%uks6OPeTV5ule1i@|FMyX>bg`Z)dr9QI9#e`TAcs z_b;YwF#*_`q3(YNv6(=d?}*MMe55xoynP@wVH`GHjrK+mCmHhJe_=EHee^@D(he1= z1iAR80@Y#tAhIic(o@-d1xveJY^a5>et#$`vXW|~My21(T+K(zdGYMBgN3})=#rh$ zcm>p|t3^hw`t}I#+b2D;&P*))5R#a_aQP5_8Wcrx)lIQM3#1gB$3TG8kLHVr`w`(m8A z)7!VLcvt7f_Iu&Yi!L9hMfKLd%E$ejn+dpBS9Fay=w4{VV&)TFruFeZox0b8m4WSB zW>amT`6EqP85TXByg@FF*qr=6Cl=S{|zr; z)@GOHX@ir^Y^`Lgr``{lo?plG%;7dYFvDcVhcG8;Cm>%B98BGXDeo;(^4mhUzX<%fb}-ruRkaq0jT(OS`Uh zvK+-z)OX}Pzw&<dWu5gmGHG1I2W~2>{ z8!Thn(R)FnfvWN-DO8B!(;&nU1B$cNiadjkBB=x`!GKO?OlGaC(f19%s{)8aEFdk4 zOf!bAiEDZu2s75>fI@FCK(hv_*`I)h+3&+z%Y(FDtqLhTW5pxQ1UGOJY zqx7TGA3O7N9l3?xnGYurZdv{;y&>6T`02#FmV)m)`vjJoh8-@@ivs&AHu}fu|7PUB z69D1WMFIiE`F}-Tmx;+UyVQWf_uPQ{g*Nh^hYyDhO6*R5-GP^&6TiJ@^ZGJEqNuQ} z_x=S%K#oGT+Ly1~@9@G&66iZUphyQ{jH^J0i)yR1*Z8jc?DTn|pPqGnTW*HPad2!# z8@e2HEmY%y!RTviGf2Zo%-@3Y=8-QjhGia?Lkl7wj*j*POkL`842q>*_r22K{} zinP?>ofUv*7;`3yGf5PsoXp7;r@p<#vd7_ZVQsx42ITW<#a!cmGfICg7Xk!e&LLDu z4u8MXKVN+Dk)hrf7w_(l+mbL7dKG02GMMZKQy8?i#K8T5|A4wBwA+k|to zk$}E6GPK)%JCxGry)q4$|Ivm?sa@Q5K>FqRZaJ~L`(};L_+_V1rV6fU5Bpv3Jjnq=ig{dE^5 z*QJl=SuKJChF$u7u1o-hxV1+a_m{se?D8T;FDh&tU*zRWY;&QhTC!rG>E)0y3t8S8 z;1Ui;-7RIcT@1DmWSUt?zUZawD+}A#-#>CrBjbHVklj?^j~OVCCE)l*6?!as5F~5H z>@@(L^)#^bCCvR6CYPk$7y45r8-_jNY$y7jqzx2OJiqM(NnW2Julf9D5c(_cr#?mJ z-^}pugOCIG9gB0{|6zBSkl@Fc9*7sy-&U2GIk_lSd+nC&CO!EriF6e37aEb_vOP7p z#UOR^ex1D?4QZ}HwL@08S=f`qB$K0aKJnTXZK)z*$)cNcjLTDjPJTyI9f|e*?_z+} zKuF%dvpy3;FjIbud;`Gh5fkng51lIkx^R4vqv5CSM+iQqi+)g^^0U22-3&%_PRfyFLI=}Ce`dBUC zE%8XD^(Uw0RondrL7D{w2*doQ%3T0pu=F$xwiOD{V-nQEMu7oZ*u~7$gs%%9v7e$pmyW6(f7Mg5;3bvCo`I{Gp)Mi<3z^%-QtH}8K{w`M zkzt7?+Rwp5PM_YV0;&pN;AX&JOQZ#0Yd9{o(Bz*om%poBesK^Bn1J7~z{*Dd-_L%v zIN*bVphj4g!wtD3hz}=>$PW=dmys`6#{uE;{SYn)42{v}EujvUBY2AWgeSNk{9PFs z3tq$AYDZeQv!kBH?Y#=py_zpK{|!{eAgB|XJy2q?Kkq;dD=qDf#wZ!C0=1oB?Rk0p z%I7es^gv*KIkk@&PD1)(!DbUxR}h$SFIQN3bDp$5;~_FvZI1@5A$i}H79NOjq46xM zH9*y+jt;WA=5F?Fqgef17L0q>tS zhu)1M;pk`SyH?3F-ZhRXJI=8nPKHVR1F?L!_mmHo#CALbTKlZJz03XeO3{Xe$8r1M zG1Oe(B`DrxZU)c8xAyY$1cW`SYgUvDLKE3R?$7BEmZvX)0uz`9Qg&L&?FdwT_UoUK z>kynBQ0#o4oG`)<&XYo?ey71K9(J8bg*)1@AGfR?^ZG_^ujGcc&oZ2>q0hvire_%( zp(ge#3CJc8y)|ruykbEzAOo{SikJSC4|?X$R4<>$rtbg0Ff+=pv&7KRVrBoACGC4f z9C^1f5_3D^!;{~QDsXC+I_=G$-eXsbFPLO%=k!nq(siq-l z_A4wg%r2F+qsY?gtH&O5^M1s#^-QJ=)32<*mK$4Oo^r|Xum?+1bL6kE>e56`pq9

WMF!}9j&(tO1ui3gdah;+6@|gZKU}uAT`vFc84~CciU(z1QzU+ci>R6H)_ejhg!&yq;g}u2cL%DbOfvrB39I}QD0MA?a1b$ea*n_^DcvKw1Q7|`=Ra3M=}>5mqYVi| z)0})Lw&SG6N)=FHcNT9cEQA3u7Wg5<_#3DGb0vTOqz6*3LitDa{GAEltB&#RelnrY zdo@sf3Z9u=tlDhjzc9z~%N`1=R$~xWLPVwdgpFQODqhPG1DFs7nqy+zi}*3nyP(G) zy)=P{yAvrjlVKtS$==Na8b*w97Yf*7BrdILNxRLGA2t;K)zQE}R2KSqmI&x!JVTGr z)kFS-)n8`@IGU!4X_Kr^40@dpBa0sIdz{i;S|7&qp1UK#!Gqwk(H~KBL@8B5<)f|o z7Vu{w2E01u)7v3wEh*4LirJ=J=wY}+jAgWpa}3v~l-INNbm}ddIq#xgO1@7MJtRPo zX532kT6B5TpQHW=o#@HZh1(_^QF{4ZtIZ=1WACj)r@71kbqwgXiTjV_G;AZ29CdJF zZg#ACv=z0s3K$s~j+h7(@E#oS>8jGw~HkX*b<;kCK{(BkT@$Zpg_B8*j z=C7r-dmWLd^XRfrpAK`F31uK2l$Kk-@2I9YXI3yfrC(Z#3Jkea?nD^&dMA zylVw6XingGfa|K*2bNi;h1ofC(MMtGSVjByb87bRs94aoV_d&+MY`VF=DU|cHzSN! zT1M|{B;I#TKRwlkQ>k-=L`}-1;Yh6lJMaB#lPwXf=lu&_t>nxI-N9d~(i0`9=@xQpWHIFu^LIEpR{0yDe4 zy24&H^Wy z7^&U1wa;+GlySH5y&feM(uqh87GhUyp4yGiZg;GYJTf8uTEZu%AjyUBnW;l4JzsbP zs}M^{5HyR`#LmL}zo%@C08i4p_&9}5>g6vW_~(q(_~0uA?pVqAFB%Y?ek{qs8JU|4 zS>;CkK5ODvfZ?3n9Bj475K z^91$)GQFk_XXolvPWJVOv8CrZ(R70}pFaz7Eo8)^t4RZI%|IcuZ4v*7eBjk9LEXZ4 zo|8)W5P~BvxCDKFsQQQac$4wx_&bAV!V3Rc)o-lRifBJdd%n8t)7F6hE*ckhIIg+! z<^Xf%uhmy{fv{oeT(7&$enmPRFaqmB~e;%`<66bcFCU%MA*R@L2tUzYYb8qsG58oh%;J00t@+Jmse zE8g$m?fACs^6`;+G38Nak{e88X-FENC0Gl(EA^ob{PyUX8T{rOULLdw@a;-n|qoba6eakB!up<$WidDXYt;h_7QP zRZ+-G$7!M(v;u^+<0xbpa+H+Z%qsi)zH_sEekJxNWU)~zHSeXSDms2)RtKkPxJ*Qj zdO2$vos=Klo%Hi)L-pviC}V2<_|P#UNmv|omfaa0%KgWB>LuaHdZNiZs+4ax$7jwm z_`RwY-g*2b6ZLSuflpw7E}MB6;~X6yjeesqev3M>=sPSS@S!l7J{3D<*8A12jvKuC zRzwxwyTY^qb+f4PA?nX4KG+jVPYy=C(^DpHQRI?~jBwvwSG}O85-BKoGLHWWouN#S zkCroyOq#kZ{_A!nSr>+l&xjaQ$1>2Q0`(b&@|rx=RE^kd@vyW!7dgkqapgyRx?=Hy z=2uy;@Zb&XQ=hu064y>8qOZkWpBzMaUp9@Lc20Y|7!G-1iUPKj8G4%4u7br+T1^qH znqS1>kP+3va&NQEZ)GjfQC?n$)_QQ-`-5+wgD#}Xu_{7}{q%cgl>{G#x*J`ztmR^0 zVbNnzFwM#k($gP|--T(41F)ePr12QzPi**oDQ=$vAiN>>4_^HK z4B3|(gUMx2@bU_0%k^v{p~3smW#zJ|OaODxQafy1~^&VM8U8ow&zN{?b$b zMK~h(*ot#N8_>P_*yMfs0-_l6*CKs$Nh=EcN{aNet$BF_P7ayWJ&^J(jce0HuTYo7 zre*<9CF{M9<*IiaXfz&?w0WE#reIGwG>Ryg2 zd5r!4+y_CBIydMKNdqo~-Y3v%+r>?=&lRmh^YzJq=X{;e{+`-Dm!aMW^wfVtaDENZ zQ>VS!7=x`-kfqP%Bwb3Ix)+;EyZ5|lg|1)1e60f$IzKme^c{8N^9Gc*ySp1bM0Asd zpuxBmOeRO7C=ivTlRFK4=$!L)Wu!qdIB?&&>iv_t4~m-G z2fL@#M&c@BTu;eg$z;gW>||VjW>eGfA3*!&Zc6aehRtd~x;zA`;`3Ne8L_GQr3!>$ z+1Y_J7CWV={6ks{0{NQ{{ks`K7|1z@vtny&lff2g*S4V0a~jlV*L`;T5; zHbzOkofHtdq4d5oZfclFUyr*HsKbA9_u%o5J&5tk9z^nBTu!S?-vow#xnlG|U&j~e z!@QB^1kTChQ6(dX8fW}YwpzpYSjl=Jj7>!NBg0z(<001sxC`EdVadv}x9s*1LUoK* zi$+BZrMp?=1f}=U{u0j3I8oX55EN$+<;tu54~9JL9@g9LJVqRCF9E%G`>NF?6LZ#N zNoZvyVdaqLIsL1kn*uZjc6V9j|@~| zeEH~oA1&*<&l`Ee?|=qdQp(j-J80TQI5RIP#!T^z00!P{ zu*pW}^wOu3tv3H=%$spPOH*?h!nDcO`rRk6T9nC;!cvbj)wc0Vjnh=+kE?x4Q0?=- zOtxOI`21)8|3--T48WxrXhUK_`13cu%ECmqbNEat$(wIAOKY$eZw}J_aVY9@fi94f zcz6~4{oIn{MMVZ#vL0J$)yTL{;g1^@zTAO@IF?q#DNtZvuPQiHfWFZvG2!9CST6@H zLVN`uX=`iK^|rd{3Ah8i<)jWnIzHU|ZeUtQ20zjnTE*Rc^~Bx=?94#(+VlLZvbkT(k1@AxbMwTlHZ08T zZS}Kj&U6>Lc%AVh^oir+>dR#5jw!Twm%@@0mYnmwz?!TlNABv4xxB4aYAM0_iiX_G z=Q|^)?)OKy+S-{9^qJ4l@_KX%)c7PA>P}dqQ~kXVY;QZ4I?pn^GccWVt$!KjHfSbz zM%ExI^{H=#A8pY5v6Cfs@OcB_fWs-$zpFbD$8q=dP_Hw_r>?*Y zZ1NY195MV-$G#yi9BVR+fl0AzxOoU7#ln%fUBi8IR*5sssD_&79qb&zJ3S8=-1&>~ zhRlTUsUM4Ajy$6kF<(uimA0KON*sD3N8N%Ho0#n*~O&IhBZO9C}s;?&Yh{txCG_lNFuz$nX!}5_^kGJ1PNVHB*rX33%`H*p? zv{YXyo9ei&y*X3JDA^D9n{m!|2y~N3NoB|auk}<2^6Bi%seQ>Qeq4Xy^Bvu7^d)%A zs@@TS0^j-MqO1~5hm*X|J;;4*H$BSGe`7My^!pHerC4EAEh7C3lRgf)sz61{0bO(< zXGlsLJVRq1QE|g%OI9@z?-$)dz>I=Rp-}uw+x{0b^oG!Z=Z7qF=|umub@ixG)Z*~b zd9H{3f^5C_Wmj%@d^G=n-yb5VS658C_<9_io!@K25e3(hOfqY$1@Q>|S$evrfQfOK zAt1jjbd9Z;Ej97qSU z=%Ukk5bwgLvuf-7$29dBm~xH8^=iz`BZ0ZPYANR9Cp6@(iv`Bx`e+C{-_WZ&KV;QZ z3%+&1?(Y)i;pSk)RFS0K3w@F}IZ5lXB<~-{0 z9i1kGj&vr3Qhe;&I)Co&GB(DK+izQ=C-V;v*%7871lOY&napy9zpih^C1{hT_Z2lk zo>@n&WqOyA-qRNCt#9+Q?ouFi3=Avn58Jk+8|Qu?N$_#b1B8){D*h`ce@>1p_)-Z| zzMyYC_vMLt7K@ffpP!}PxC*E!WjPslGe8rAjrvL{LR>EZ9xx`TYS9|uMEO{8;>W*o zichREw% zUSL;~56fD3PF%75EZ&0Jtj6^rBFbSCnX-TQ?C@=xud6d$1h4BflIt6Hvfz(p4pgo; zM%c<`gp$I!Z^73r>X2OMS{5&%c(pCT2>Z=q(DyuLAiGni zgLg=_r|ENeHESpE^BwXAqo*ncbjt}j;m}|JDJRqtWG?-4{~fX1LBMvee{O@D0$ndf zHy|Ia^wCj)f74q3Sf^^8zqp>x6j~|FKMfba$qiw=_vmW9?m^x8cJqzjR3d_*pp@;m zA^4pIo~#!e$06Iqe3~KAWdYHM2YJmSLd4_7imJ0yuEU{8k;4i z^mZ*ob@no%H(?}k(#%y+Ssg7iGcI9RsO@SIPRA<266ZZ9nd^N9B&1 zaIEL5i4_&cc%!{0LZ_j?Qt~1d8Wk5BW5{WRNd8G-&a^RtB%Y>fgm4Qa-}95K89}?Z zd8U6~GJq_^q1o(tUH-b<^U2r$Jc-m+TDAft)xnrMHs=20srYGVl>H4CR{St#MvHBvPabp@ zu!FE|K40a&H#)hRh(^IKM_?bKyNvFo_1n{O_BPTo+?ed_i<48 zPbmAn_r8F^Q`gBb@akXEW1TFxej^~b(|WVD@H~XMHE-xYPJUhLBQMjeoR^!Q2$(Jo z#DGUKrDZxVHw8olDl!y_mY6K;VZ-=o9($3BT1=Mf zY3T-NVw^H7jT_a-axdOc6BB_ajjljrcdD|)d}^u#;ESfN&r&G{{48akhmCc&-ABei z)gxu-j}Z7{E5L^F37y{?Sm`UHE6j1Hy9`&4?_pMovW%MVL}n zxAop&5c7%k&qKp@}Zvuucq}SlHfC{A{~0M2=S$i4a@fwGvr8&N#wNRZ3}= zv5}YHG*niKhji{1p^xVaC=3q=2$!f) zyC?YRx4cjtzCN>ZMdcJ`+mX+n;sqmst3l;+ui4xD4L%NP>g{#DkbdRKLp3z>zLd%{ z96REu@m-FLnY+rgpKV*6bf=+2ya{Q#>eG=#^Jk_Qm}ihg zaR`r4{D_b=22^!QrO)!;aR-3r5c#EUL{g}wUi?elyn>JA!`b_xA-DCZ+=rm7{Px^$ z4ov#XDsHDIuXqBQ4NFUNJ+D!<(;8>GY`q}fbFB0%NaLdL+mm^X4G<$LPV9r%?(tGq zK946tP-bS;nGR>V`wCNuJT8w`kzr7-LK>+`XTV=QtEldOJTYm`u@aB*sm?M`T^r3~ zfd|6Qk?s-yRVBBL@W|Emp3E)(d=HV&x?pSgScKQ-P5+Fkh8+7-9nw;6r|E?X8k(7I zh531tYY!x_E+J+695?s-5u|zBoc)qw*+_v);S+|wRuw}`1&<4OM^#sFeJ-o}PpbUB z=#NeDp)-Mt+}@Mq+cwS5E=&XvjNIMn>D|7TY?y%5H3PF79$`Qi)Nl3i0UCeMxlgo= zh>5m&tX%mz{mpH@(0{3$`!vb1l7XmrliYvpunLYZ5KyaQvK>K6a2#u(N3y*rZ?lo? zi5&ioTy>=$tOOA>0pFrGmjIp8?V^6|Z2nL&1oI_Jg8H z6_-$L%+2Y!3-PWns+J)FT`xqLGi!Hrq>@Qe*iw88?NVElX^q z>9CSP$yP~-e6E)yWvR}+26t|$!s=evCNFdCne}4N>fH#@*01T#sSbX0D0z<0=<-nk zmPbHQSA*nnc-Mx~3CwE6&HdI)=)CN?p1BADY9-!&K9^9ubw^a9q$5H7jl5`B{}rDc z%<}l2uyfkMSJCi_`3AdZZ%hqaWo);G9#TrKpJJ|ZRO^UjDPw4sNTv=>C*O8&b_2+r z;!6}ZAig)nt@lcuu6Hi<@nmQiQB&xJavlTdUz;D$-cLc~x7WW&n3VQsSg8F8QRHnG zCHmd`LrrFqEB_hpPaK{9ay_}AcsU?s&=3{3?W>^?peKU{@8pDQVJeuD`RJ$o`=p3x zf^}A0bhLLBR;H{hS!VOW^BfRI$7PT5RzH;l)V>I>*UsXPt2=E(c-^8m#EncNjrhP% zjb21YgIjbU_v?yOkI~l-v%dI$`z7VzO6n2 z6Kg%0+Vzi&Jo)Gg6nv~XOXf7l2tAQE30&G4bVpFSuEQ7weQwZ|u+6ueCER&TCMYXe z>#Ph56Ge3bgqhMk9?wOQ$~84+g5XcJuR`0>$=1GQbxx<|&rKs;FnYeyu-FaN9WYN> z9(e+L^|CVs8>;QC^9eWvabrne1AG@!D00&<8 zIQGa_3sv8lJ4VV7+TIn=+R@MXO>4AUiRr0CqFFk_K?qZy5qNisT4iJ0z~9K>mj!aJ z1a>-V#YxF}paQk)GCv(_8On%wNeL9}=_JDqhdh|7x9);XwmMlS5H8*kekZ-7GaO5+ z$G9(XgaLmKHD)o(`eo}GpZ)NgK$A>NIi-Mp4tx6_qMZ;B?GE}7<4V_Twm)OVyJ86u zTbYmTtltnNY@@|`1f4J&1&)&NggCmUu?Re)#MH5cY=DW#Zv0YIR`H}29E70w@DG}k4WN<~Kl*t!lS&=Xa^^$ZfXn9}=MkIBb ztLK0=Frf03t~6(02@8sr=uSa5grGSo7O5?nLgw%<82`m=4!!v0Z(9}8z5COQ(yK%f zeK_zTy*iEfh8YQE(z=8*3(Cdd;YhHNK3iNzNC?VpeG}@|op+A&A>4NWtw)6R4>sB4 zYl>Nc^f9hS0E;OVw>#a*zyP6)>o%0*<;{BfOgJf3I;>h@kjiNU@Xn<&MM>m>K4jL` z*ul(KPj%nd*sZ~yz{rH>$&RfTLf1PF*K$-abS9^!st4y5(8w?73vMN2uk9YTYFF=lA<%Ig?xSHbpgVO2L~}|m zjgH7E1p8n?=hn8Ix&7uvXc1%s49sr-a=OE$mIra}Ss89`Rk7>FEq;o#Odw>m`j4;V z`~^~acF2RkgimqG?>f&>VT}fchMt|kN*&h_FFAN7vlEV*7Em^+fCM{n3sYFtREyL|p)iZ;;H(?)%wnvPq;}rs^LlTFD#kbUf zE{;f7J&W&|--ej#<2~@Az$AUJS>|P7AFV(LeAA{v)EIc&M6*+4j@VFY-j$6q9fs=Xn8>8bt>`HWa2V(TSz0KH; ztN7!Ih~@k5CR_8;WjOG_Gjz{=$_j3rgW(WWCnkgZobGMOj(( zM;8`N6rc-ay?F{$p*`|%!iX88-uJLE<2_rOxa9iO1Jq>~{h+0KufFt%>$MrTvng`_ zI;gsqBOYH;nv8g~e`v!|&SIQGZMUE6tqQL@8~x<@MSiXrwHi4&Q=JtO%k7{7xv#4! zvT>(zm(OmU-Xteo1kr$a?Bn7B+^Klu#Q8c>r!8xusDS(af#!s{z|(|i{rzUo$Our;|Umc_D<1#ldD) z)Z*c|xZtik<2&paO7z<<)Sv{?Zp4#cAKiSn<$0=e5;Sv$s6Jn-mrU_1KjCQ7=5yWd zL^eh5T+!nJCbdX{1!uy6%F$Z|NO&&Wami_qx>jn7nQ;HU2wfdIW{OLe%aS2Lk;5D% z{pdnqWXuYFX0F;;K`zY+<)o71)AK>eHa=(#rAXzCld&wk>TL*>slo+)T$F>?O(Q@+ zc~C%6qhO*2WiWJ@jHxHsXrJTh;+c1sL+J9WZLz69m6xx*uv*hm&6wSyFx@0!9BB-q zr_=gHc__X+#vt?LEb`S}-eU?>SnQLMJOyN&@*Zd>1RIK(#C_zF=5Jw-3#R$%XURf} zPaQ!>osS>C0+MVqr$Hg*LOB$~0Z_hu+UrevmJXzY-1l6A+;4BrbqYWZj&pex;{Uze zJ0yUSvNOk+RQiXS1k7xT$i|13V7}u!#PFT_8r{I-G#keMFh2J1QbfHRg^!=4@srWe zj<%Xm&ed|PdCH(sgof(XFMLBoNVakawN#tdr+MNyAS_Sf+bxGYxx&|GPLh{lKE>XLYSvv&I}_%qmRGMKjp>ILy4G z=IBlN5>qTDHn@k)u+y@u*;r)hfT=6^W#9At21a`uB>*__gbXBC?VKyFA?&=3HKmHAZT?y8v#0p}__ML~UA)Bwqrh zMik;^nR>~y z-J(EIvd8EXu5onB4eU$LaRv}^37|{hDizZ1bGEYXjs~+bg=Q$(Ie{n#!@roELex$I+Mo6q71J=(|rxm=EXGbjO*78 z;*ilEsg^Ue7&;WqYk-b-SwsgM5dmrRbX{>dX->BYEQ^|JZ}E-i)vHQ--w{%yg@b!j z%1is_AkF9uKm5z~exthP{`@^WV9gJ=y+I|@J&0IMCWp3if$$A(pK}tz%!Uf^OO)t5 z(CZoRWsaruG6?13Be!u+YZEwSzR{E8Z)be$*^VFUuO-s}aHgpF zwUK$w&F*I=yZ_0}92Dqx>->VhR(($T@N|I|`GU7pM&FSvX(RtgCiNK|mj*)=7Vow~@p;`cfGuQ`w-xZh>G)xtwHa-s^}(npWY zB5avn2uxByfC+(1DPBMTbfpZ;;!Iwc+7hIp0fgx>Q~*Z{=Q__xz^Zz1DWdTPPnR!O z?(OHuyv*UhLoOV##AD2h7tiO+pJ9)vQBIT5jgwSrz9N3ytms&1`50Jwc+ydT{j*Ff z*7IB#P^@wyq6MvN0v?x~6vngV$K5W2n8`}^Jh>TShU#)-UQ3ID=-()&^$m8Dfi+cB zn2wv$!JiMigmB9u@pS!N4_+s%=u&}|X88%G@eo_^i(`OOr==f?c$b;7uJMY>%G6}b zb)>}^YOfeXvOGO?r4@}j>B$lI*L|{CoHI;opp6x2EE8gG@$ZK3 z-IV8tGZZAo2+TxY4>nxem!p)6VWT34g-`{|2Wv#b z2fr7G0;WxXq6ch4bj36UaI-y3HSX96s6(^VyR#9pVMv`9=}g|+LC*l5cd9?odNN@9 z=f0Iz3_xf!4za0`s%a{=gL9n*bcgy}uIBXvpxydE*V7W9O|Q~Tl#HLupm238&r-jgRz7#cK) z!2`-$(l{Dr_e&VMwm42%GZy7KjCd3tfvysa3?WFbYQp^nwXt(ns^se|kKCShtXkSXPR;%;Wa!0*(L6&n87>G_>#UQ$;kyUb1A$#SBRV9@Lb7 zA6@T!ETxNh^YS!KaymrFeSCxL3k3ywN=DC*0N;nbkICR5Y@71|6 zT0?Xtz8Y{E zq5+x7@J?Wgltnjx%;iDTsa5azt7y@kwY76?v*RB5{f4wd5h1$#jizP)VK^Qhd{qnT zY(y!a{Amqt{Jm5#lddP?9-tNok>OI5x68^=9z-C^)yeXnB9z7{76B54e0Ct<%K{35 ziZt!!ZLmU| zI31%H2zHgspmDLhNvK*TtS_^@1S=B2L3Bt37VqC7>svSAwdxewKOR8UY~nC{Ax5IA zR0&ZsmMw&@%76}*<^bGu5y6Z|)Os%g1Ex&jS5b|x#v024?^)s3eqCgU?CsmE*USS7 zZUHcwscwM>qm!*ZT3W1kxVrUFfbxVzagVQYU1qRZ176fmvQ>Xp!PyE@ptVUZCjWy*TqWy*eD&|N z8OST%550q(=ei-HLUqI4HhpQwUCJ}2B4^TT_&Xi9W{+>?&7uUNL%FE0ECGP>?eG%h zN)~tk`jy=IA66Ym*A23OiOnnBwuMgXUwK35XCLfHfoZUw7jTLgkl|;E9--bntux|H ztG@kXOp`*MbG(WMmqKyzWU~?cil;qMOnhXkjZKj(nS#1Da`t$?v@Ff5Z)u^dd_=w( z+0jUZXv$LJ5hA~T&b{92Hn^6>GUHh|iJaBzX3i!Wl=sC1ymrsRFTuwbha=D6AUU@h z>Fcv5T>K-T)|LPr)rp&`us==)ADIDZZ-!+Dga}GFFW%31ZFRKJYtgy2B}Rp{4wzjq z7kI>TBcg;5!z!X33y63)&`dAH=HTG`hf#Pa(@j*H8(yn^Vn&Y^q>* zNpAAX>4dXRn|fe@{lJ_!lh~@yUZ{#(@REX48ayMb&#sZw_Uy7j<)sHJg6Q&x#`sK+ z>xmJoOT1Q1F8|Ig9j6$aw|-ABw}jU{AX(z-GMuZ2#b!J<8{2tYQkXwXIZ3esHCbyx%{p2J_=jcCpCVnRmFaXMV;`Ix$I@)3o2f zk+aYD1vJuEtM8m#^FsLFnETOp51J8cD)%WKDZ40fbE&#jl4W}2;xv}ob5rZe8@()d_+C}Y=nw7QdUB#X|+ z6d35xg~IpsPokreQl|EVT-JFYf--Q^QsEYlgAOlWn7$g?AWKl7%4A8GqW>$(Lpv=h zAO*4#tyfTwmUrG6w^sMRC5sB>1jGC7TKoV&z8N|*;lBaT4_nffr4(jU2xHG3U`&(w zZgCRzaKNC*Y)s(rFa#4}WLLO`Y%cEIF!XU!nE)B`dM_T=q0cz0QMn+?ypO)-ljsox zA0j4{x%1=6#D`5SVjsoeXsrw^UbX}+XKYXh9z;f4OeOa!?kKCkP_U09l#vaLEosP9 z(I*-Bv>sA%-m|dq$aSY=Z6wS{vym3X8ROGcbj~F;GwWzXyUX#N+oNmXX>m2OeLwr4 zZ4{({mpKh$Al1qvOLk0Mm; z_RLG!vbtZ9W+)%LJrp0?C8hFt2>b1pCHu97?(CFSKEwXqFn!mvr84cx(0G<_tLmt? zKX%sfMOH2$-*+`yz`Ep3q1KJFhJq_bC{aa>e{M!B$6<#f=*niDIr8b>@%gNmsyst< zl@<>cm*+zLFT+7VJ~_JY8aY5jjC-M9EOA|59%cPy5K~uut}h{X_XBhcAsTIjM))+j zre?XX{aG2&V$g>V=-1D{(B(9zr^6;pWK>eky3jz}X9d0nTF?HLUb1 z6c!ofH@A%fhz=2S&dTdND)$w{Iz>l5qWGzcPO>hJ&P%w)G2ri-+#Vl`^C|TS$;@x} zDml~N$nqT;A7o(H=`Rxv6LfW;bKgCrvx<(@4mhtNRz{hd$g8OVKX!z?*@t($@=^nVeL#LU4(N;2dfJBxAHzQR=rFnZB z9piHJIwN3G8u16&hjdg*q++tPDc{&RnJy3^qGO=lO85g{vrdbmUuJ%cr0MH*mT@OHFK*i}%1Ne0$2syvU+sC7l zRVJRS%xJ(j9Kmti`*S%OB%*!0hZeKw=x<`!f8L|A`<0j{Ot|qCL+Zl=mxdW}%%*t4 z$`z)dE6zcN%>N11ndeZQY4Kul`%kEnlj@ggg((aV!d)C+54Zd8M?c#Con+^qlk8$1 zkHXGaFe^V%)esBpY_b8URW&4Wt(>$c?LO)hkd~Y#6PI0qQx9m zH^`7cAtw!ho8a1>E}7WM%(#PrR@m|mHBTbOr7@@7<;B9}_X)YIU>25-z@GUe1l|5B z+R)Wi7_Of%7Uk;tVR&efTz&cI;_PhFH&qXpxSpLc3zMC{4%pz-_PTe2YfX?aqkS+T zp)>$mnUDiu?y2+ygSJF{D+(q+zh1rm=6A-wT}R~9Fm%HIh*|!0D&8@&e6u~VQP&Ri zkS#tUAo!<0YmR@~#rYP0(6IZt@c7d){$!sDq?4>>5ZBB~{Ez3ofjeM3yQSmTfK*X2 z<>SjpzY8L@E@flXXDAV%BB`(X`<1n;0XIKd-6~wW!8i6#jirGH*57uGA6$`-JcuYg zxhchBCS6duDA7PW5*C@3ES=Oj34~ICTjzaZ=c`v3Nd(JAL3EB%&uNr`{H*U(dMeJ^ z#p(9=-UJcEuAiFmCC%#;-P^||BTCAVMJL(OgCYMaify%*x}3T`8g6prYZ(xHFn;53 z4SiuAt5mHnpDazI!b`njY1v5>W@j7mb=CE3?jwGww#!r=xZSubYyandCY9Yz4y9vpo+ z28I%+U6e)e-$4Zh`~o2cY@oA03x?wUPK(c%ZL)Jsn#i?G4=Rz~{7HK>ilM z|18ixxxJr_N6dF7=)-3>a0iQ>+s^q{fmnjSeu?>gqaKkd8-udXE%pvIm?{&iTD_2@*us>Ye%U<6s`vxqwzFhr5=Kfc8Nm8EEZGSc64B5lt9y34tnFUfw;Qr{$Ait(UAQFNtga z{q^(XjUL@zo(0-c`#BficSVk87|Q2xD`l*&RsT=^l3 zKmOdOwRAXs2sxx%{;ROMM;v*ji-p1vvAx-S*&Mqrk;|vSOex5Yi(+8u_?kDf%$)b~ z)tJd9om3#**DxHH*LDk$xxB|fdnf7LImSkoCq4iLtBNEoGOH`b3$R33nE|qw7tQZg z?5_*^XobLoNh<`9o1v#L3}rgR`_5`<`%oMApN=uVAM>>*!BXANl&s+T zc9^lj*qR;7`AQU+ssm_PT1$)~i#|Zvjy*TE53Fe4Uy8_Cc=_CE^kIafTDug4Oc{;C zP}cK@OlYNHtFq2)T$gRg#j$UQr2QSnTUR}*RVr1E12eS|!FnMupqa?zle%nvj7Jrm z38ODss!f@~&4YioWd+seO>FxiX7T~lLtg|eONj> zegLU5`n}Qle^>Cu_-Dt{cH40Ae`+&Z0piol{#ehQTn{HjG4Y=j%O8$ir~W`wl?Sj% z0x@NmCLL5d(Xm_foUTu;JM+px_Mt?@{V?qY9VNx~nz+b|p{9#;eW(rEDbp@;G4x-1 z8Kh%y1TSw3dx}fMPmPFz<}0}}6QmG}lZQgNxe#khu=aj{C!*ekF0A@3qb5to)Y8zz zc#eDN+s?l#`G&doo9VpJ7xu8{ge$x?nf?ozhT)oh!6?P8#`kQ3N+%}+prLAMDq@=V z80rJcLT=CmTKgzVISZ4$%HYh{aF~W3!2DRQ@+H~U0==xh*Y@0NuI@W^F-GA|zs|D7 z51t;tqE8p1Akf`5KT6qV&$p{q2sgH%YuRB@sTny&jWH_vII!;-|lI`H7P0FNA@Pb}Pg$28ST z+I>9n81fT)BhtR~sb3`F;k|d+g0}mDa%avj#TdPOlE?-DX^Z0RvB)aS)62kNbNt}^cmOfeS%i$7?qWQp+End1t#i`2ndK92` zuY7Ts@h$`xse0t@s7#yDFLcUNwjS?KFA+SmN;O<~gf*@=ZPp{DaW>a0dcuG-DP2#f zK~?M|2gwlvyM>@ho};xM?WQbDV+(Cw+{V2MXu#w$Y&Wn!t^{;}R7HbcJ&(&@aPc`W zs^S6ZQf=0E(E7h&2nDrxC{|hjbjoqH#aVuGXxI6$-_G7&vdQxN2_3KASHcEbTYO?J zIGPJ6*Kzwbx6+D`fKAGQD_CwrI=&_lTF_~eWcstO1893tP_VuX*WcMUy4z;iQp zkdSo?&X0-|;&np>{0tL%UO1L!+b)!ibb&yJA=%^=DN(@8#EYGm)0gZ!{Ey5v;KC`y zhQU;{G;J;~&5H8ESy?x)r``UMYNjccl4P%yOGSeRQ;A8aslBALa130d7o1;zzH2`JSohls!UNshkD6+}f+dR!BGilVLe6exx zG`n$H-NODv`VoZD0X+g@Km*QtB#?KFuv&Z$lQE6Cbk4sx zgA@A4LG*+1OtL#wOhEMwlw#Q64YrlKd@6}+7Ot}7V8vfj;l<@A2G=~}#7{lxzb~|d zF;InM`?j6CC7Vc!%626@A97d)20JuA_L=oFvyJ_z-Stt^*g?Tl)3+Yhg|)0VXaW&h zz7JiBhmZ9+dd;#R56FEzij0LQdWEKUNJ+E$?z2Ha(*;)NMXkLY^7n&HO7$Ao=<`kl z*|RKgBWWt9vTEey;nj&p;j!e)a`)T)0WO#8WfwgYZ8-_u_V9SKyVWxTT)SbtYlc&~ zgD|g#tF*!D`a=z^TqHa}*AUwXnSaygf50lXXMvinwH3tq9PoclnSc;<3E!RW&yVY~ zcvIL%aQuHE;LuMI}%v7}4p9kj!^eZOWq7Y+R@idmd0V7F?O>=f~7h1m?THPtUvCPRCCzb=pS$%{!`*+u!rw z;{dLlue5PdUJYn>d^7j9pv5m4`7(d(6;XMLu%!9CEpH3P%SEw|v_zdKE*YA9HFpMb zY~&}*+Z%#%u@@2N4vb_96c6($3k|99riJY64uRBzNOydvk5~9p(UF0Cj@^;fp>`SQ+3_;OE>rM- zOc`m!07Oii6VnL(yGDLa_J)|BA7}JPZwBQ@+oi!GVj9!}r%``yyiohBY(T0mP~Y9( z<1tON;Ed&k-^OBm^jt$OHh89RGt-9?tZys7e9Kv0@BG@>$hm$NFlGGJ6m~u>9MQeM ze{y9dl;|CApb}T(`vKieZ;kwY{i6lAl2T-aT4(2F>&b1-E)ptIQiVHDprZ!>)eT3~ zt(%CTP$(&fLN+qKCpe%7{JETSJ!d-SSPh;MC1PR*Pwgd&5-ARjg{m|{)vdylzuhEL z)2zTmF34Y?<)>qb=S*K{#V7OBRKd^9;zv82AbCB`k95%$G7P673xf>*?7g_2E;L~0 zsG2Cr5J%`NdA^q>?$=w~nn7iD zKsQM^`janjuEli$H~^Qs|2d=6A^z87{jYBEN11r*JEiOZ?Kls~!oS&JK%KUPrmi3w ze=G_LiAmJFc-lw%bau$E^#dI5@u#bcEPxhHV|ZUEG)ce*1dRqyB;-?rx)O|s3U-*e z(PI^?Gk|}}Hjpx>=RSwN&os;Jf3Ki8xbK)#qae=IftZ^h#;vkE@{9Is+;^DYZrMf# zv4FWFbk~^#=>CPa%DF@pL6YJMNU&DNeB;xK_sMxj)VL-y*vJz4B?^WBQ#+Fh8Vr`i-M03GiGE$%FtpQQ(j>J4Jw zSy{a;EI?hA3@>R$FP-a&pq}LY{(yZ>h1e6mKlKR!{+tzRnbO zS|nZ}eEop&Iv1Z5{Ga0e*|8^!1rW`$b`^ATe`D9@%OtRY+l*af!|85H4>#LCZ_c56 z7CfTK{@letT0kEWR>K82_x#qXJ)o*-lxml#i@?Xny`dfp2bEy5i965KceVf<&OxPD zqXKVyYx`_A_*)Jg?m8?W@Nd_xk|i&2HTw7S8ZF)@5KHSQ#94k!N)i_)kyCHgT?Y1v zyYw{J-tKO3;=ts8LZWNggGUwcy3^-AsbhTTEGSu-%p5xoMUgmMgfGd%9#Vc`sm4(Q z!KHe5P?OIhCz;(BwH((aYda^O+o#RR;)8o2CLiEKt1UZp6ojk=A6|7YwGo8N`@Mw} zXeLF~8ujaceB_Moji_+zziYJFEN-NEY;F&`R`cCX8cCk=;LUyzHHSxAi91mpCguQI z{|1@9kqzvC10YUh|#wYIC2Ko46C zK4aNVWZWPye=5Hr00It$4l3s;)7vF_0!!0_2jUBo!!DW@*jzGxAmSt~{>27zMtH#hjb1 zD8xjX;prC_Lt$kw-J>6~4GuYvnIA_?U}LwXn%-WdS|wIg1chk&U3u_nk?q7Cyakx= zojNb()?C65xY#&i_Hn%`Y^lNd``)fH$zfd2UD8flOn~F*)bpLvdPb$RO(DlLiLz>t zy#;x;Y_T)6?Mvyp*gzIs59-l5Hm)IL(_X_k6IR9y|Moj*{%CU@McOc+wxu;=G^Y4h zIs*b8*z=X|*`Vfgsi{iy52%770X7Bv(dtHWIt_MeI5lH*@VTj9yDqHw+Z;v5^9-yK zb((*l+CAb@SmG~e9D*x2q?#1{F0ViejrSXHsPkrS^d0#!;0 z>^llw8}Nb!2CAl3rw1zx^&1-x{-C_i+qz+t^+vPYRu_MzkBO79!_3?|m4Js35L#r0 zh?)>!{S^?T=#rA&-%AhAa;XnGMV@!30;THy!L zd|uaeLp{u>sjHhzCQb=g$OOi}xc$ou5RiEoHfEdk-Vn3H_kp{E9kb$-& z1$g)z0zTyRK_UTOr>%uEt?%1(kJ(QzPFAl+wd$LcUzPLU3UfYgRoE@3(0b?LBLb$r z*McgWu=B?}$QijC#?%0;O$q__uQBxk1D!tAfpqz!dt@`km*iEhs^$6o8gWd`bc^Ic z|CB3d#J_*7Q({o-@<-ziJ6X<@hSc_&RvJO#bvo?N}1?yzR=;4`F%O$(Yg}amDCw zT=Se}f=L@fQksBSN(o`w*2H5%727=g_1AbhI^9(@<4N~eY@)HN7rr-$Fld~-Tq|1!G=o% z25nr}DKx%{?#U<^2`n|xf2Nxn6frG_(mMmGk5MS$R^8io3vd(C(&k+;Qx6L@UdVbr z0Ly^E&lNP1B(;$)+VH}gR1k{%=T^y2g+9rJ_LwtId@s6U{#_}CEd zszvs58gL}(1$Gpar7TSNPu$9WHrpyF%rCC|KmhD_5SyVV{4H2LjVIHB_CX}KI^AoJ ziDf~PD>n&N|3{)QaotMS#xe!PKC;ZlEyhWcK?%1qEh;_p%Ndz=y$ip&W;A!MA@_k3DGh2E~&r&!JxY z!wybXjv7yMzYMy-3noG_7W_n~NL|J`tM>K;H1EhO9>?JN@Kj z{A^jKcMPX3Je-UNGenWmlHUD>O)8`tRcS57NQLu+jIrZg+ZAC*w!2X7&6$bKQswNj zBZa)`(UOx2=RHCrskmpZ`d#)@!ovs{r03ClSA|!J64u&L!|K~ITUKX3{fTCTa|G!) zl*mWqay{B3cXpy!g$GVoc5Xpyk-4A7?GesV99eBAQLW`BmEklu1S$QD6N5^^W+ZJEMw^(1W`mH0a^;cs|B&YJKiuG3!C#cD;0k2UO_j$c+>~{u&B4 z`R>a6QOmn=%PIC90_d-5-(?(0Z(OK@IDwI*vN_vR7Q}fl0-@ z1R>?0j9M8$Tl{sSDHIu&Zf-PFD+O~&7gFUqyKu;|$#PgJ2k%%r_opnNn@n3s82NTx zE=OunRcAjl@4e>GSQZxlfzF1uGUBl&%-ZLle}=PK13|h-b6{^hxi);kn*Paf{Vj_6 zeIO>jn%A1dS;v^^$C0*_qgGQr8G%}-b_Yj8L`Lkr5G9>Lx+L>E+AT?2wigK zkupirZ$eD|tDY}?L9{JI42GK#JpF%yFF zsVa`kQYh(nDRCvqt+;ZvbU5EmvgCS5Tkgi314q-NswM$%58FPg&e!hD#e}&U)f1GG z#JNhTNgFNCJ_lo=p7{Xb7XA7gAA=(!C;m(C{(C zqfi%V`iM#1ZAXDCp5ll7LDf*EOWhI#O84i2?=OcCB5#FUlU~Yc4)CPUp<6=h#+0vy zqj@JZ`RbKjuUxyVH+qcCuTisI6jFVm>L2P=)uo67X+-JCi2a@<^H~$6yG&N7U>!)X z^)B5aQ~e7h!9Q|qPB|Rm-I0x^-}Dcc>d;Q4tjR$lAE$rK)mHeb^eU~G@7!XX@5c6s>yMYjqIN9=Uh|+g0 z4(h4-Etk*qJxW8hsOL@YTX8TOBHwyrtoaJ<-3sxfK4cn<4#Og!Av!(kyPy&L@CJ#3 zgiZrfXz{!Vq%!SA8k3-gkl*ZPnn9;-RW<_~&02e}zZK=K_b^H&E6-*ap4PGu0Sw>`h)fz-_-C8s%nU|!PlT9(#x z^!m(yyQaWGr{_bTxo_d>UouM->~6K~)%`hLnAOPGGFGa^;jwJwwj}SwpYBi{6gpT6 zb{=3`)@>CiSsxfPY3V3N{GE0;v`=OI$lD96J*q9^^L{hLiWMf*JwOYq^1>;2^f+wP z3dd@31FlneewjaIdORgVi!0#3x4bEe%KR+hGlXES_)-won6_|O;;%INM=tF+0@gf7 zv;Sq*=Svf$`p~=t(I0UKNL@!~zW6+O1z1uG0Z-CWNS^~r!|f+=ND^IAt#452kux)T zV{$hVkRVGW8QV))v%Q77zcZJ8bSX$8bc(>0O{b`@6i~Z{HJv6^o6{mG(6aH%wE_nIGg*uuV zgI2sK6nfon6Zb%*H;wG0TQz;&8s`+gF^aknN{1wsy&7**y2O$n(47N+s-gIOXMqXK z{E%7axzTL*xFs00C5!h_yB%HwB#!WCmtB*PP?TPVN(y!Bz$yx|bUCl9&$}&qa3W_O z6@9Q)t>vYYpYg;{$Fu0~8n-VO8fRf0&REB(LRBf{PNAz-e0eVt@B(YRJP5_x>RnMJ2FsmB_>3#+oPyVSa9X|^hq@=Sl^U7>MJ_gRChFtXX{#cMf} z9q{b$CSVo{u>iM}SDR+peq^{Cq{M!lT?Y~QDCZ{9-dT{|9fOuvp8`Nc*H^yj{)j!4 ze2zc5u2vT9oOX_puwo9634Y!poa^RbyR+r0oz;4z{o1fO@QA(hnn&_#S$WyEwBRg#)qk{HEX;4;=&jc*(QSN`6)CWKx{xRUGm?j_ zyc|P#h5(6nb@|8O{7DnBU-?Q(dbu)tzBx$~*b`EwdjMx7D*%BtVcj*fpA1%$6_^R{ z@r3@G#0U>g1Uq}PEgQ(bfCQt+swr~3qjt?(W)9wM(#0EB;G?BYUL=(Ju$}I~Ioa@z z$GVNJRDq$Mx5NCAzc1LWRS!+P^<>llx>8q7)9E40D!sA*kt@xO74Ph9Yj$*r4l8&m zcd@V{guQEUYc;*gv^}0TcQZyi=x`l@OVkORIlFk4)egfM`x#G;%|IC(3pqH6BJdg= z_wqVuHRSc$;Rg(o7lCD43(dQZ)=e9>?NJ1=R&7<_YO#uSt8reVBc!tnxd02SxLTXz zPLOGou75+JmUW}Z%0uR1((>6|=RVW$Cst@!V=GhI6oh9)^2byHUOvRWfSRXRuul5& z*A?PQw}6pNHLA1P3V1`Q)*G_sLoHJsgsoqhB}8@@49|HruZL#OmzJxoo{O)Ws6Sm^FgSJkLO?&_jTmP@8ZJ? z4U_xV_`nwrQN3`6Ur7%`ysxVpN@bdC_RF+T+B~Xnzj7+SIgss)O&rEm60dSU;Z46N zHxg>wdg_<`IkUvGC9Je1dCWt2^m~m)CbOUmL%hhoD_mE)eL_io$oJM_ew^?7L>ik< zqZS*N>#aDy>Jje~r~EOU^ya zzDUsNiSb9(P(%>mk?f}?z491aEH~gRo&LzLH$7FaQ(P8r2HWIny)TyOu=Zho%fS9m z=<0<%Ap5y!KO&gBpnry)>|1$JiFScjJj=R^?v}OeI3Z}!{~#@~VrRGC_6i!bJ4Qb= zIUm=I3w1!Qt9|5SDZpp+Buw{qRs%!hY)hhWqTKpUnk~ zTZ>Ha<1&b1FY!&7)k6>B9wC>=4Tf;5Rmi$S{wp|?QByXG_{j-vxj`Yp^!FINvkS#D zRVlBM@(;Q~_FC4D7jCDO7AhS>7O)U;P`P0dQ0L|OG!9tqEZ+nSr!D00r9>bm)YS~6eiXd{%PDm_YcHQL$@fQ# z$eb3uj$*+6!ie>b4QgI{Y@ZHavq53a@8gck7d9vjvn9?=`RrYn0yYvwtI@ZN?r$}f zk;%1om;GMMykQj!F^Zx-+KbCL~2E70XR1p^NZ3p&JI$ZbrM;_T?kT!&kawau-O@NtsYSGx6V zocl^ZwBBZN>xa0-E*#Nhu@VE7YvGxLOw*00?A>l69}OqYGuGyV@)|<#Wk@M1-(@b7 zDOXEhCh4a(7rGMUu703TOXG8|hng=-pS7C*h1cqTP$Hc*Sw}y5rQf;LtfkHjjc`CE zAdqwi^*2y|4!)u`Aj9pYJBj`c>I2?l+lxmi+}$U`jMCkL@v)zVl3`{PgMn``9pR5S zP*>xwW0X1heKUe!A5P}soodq}5}TZMqoSRMM}VodEqK6OD%aq9jl(Z8n^aESL#+N{ zrzLfl=r^Rz`Mvw-JY>n>0c+K=o0hKfk~({JX)MHwAZu>ysV#Epn!Tgu+O5>WTH6~I zmyI*Wt3~-S-#d?E(-mEPa4-QLa2kG zCEG)3WBE9nfg+e30;`0^t2{Ok+m@tsK$HH-{K9gc@gt+vp(dlizKbUB20Bn1djOkO zx#^wlFY-(rZAl%)kmzzk-mnerBU`&Td+G!T??XJ-tena~sMY1hLPtMIdhd+p>={4o zQ((p+J~Tzqf#K>~yPMI3_94TX)eFsLEiWn&`;TmWe&Dm&}1bxDh|(Z zD4mU8s=m!`2<2bP(u5Wim9Bj?}pKeEfOp_IcW>Slm1=Vp{2@ z#;0!yq|6nhOWt?G4--_kH&GJijY(qF+MF71hN7zUxZt?F>m}$%>JQacYgCZPtSghD z$_vc1HY=R6nzig)YHYeXYOZm=VPTxJ;12Z6?YD1uZ8>7v8uM*t`Ot;sqA9#U@f3m; z>6t0tif+WMgDjE8WXwvWi^RRi`TR)JNa0|!6eSC2JIyJ)%+bDO5x zG`;cduLS09Zs*Q57keXFTW7iwkfHN~?W{dlf|44B>g}z^&wU$Wq`mf~H?>(FUhC$$_OpBEixuEENH+=E7+v)Eo(2CP=wbi({ zT9SPr0w{2Z z0naS{IOxyS@=u~IM-QksE@}Dk#Q%u^oPcvX-;yP+?c1!V-7mA;xh-hWH-s6`&lpJ# z4%PA9C>^$Q3jWk<+Je}shR~WmoMpRUM=XjWry*>cR6d<$Qn72zwIz=;XE2d3a4w|o z6N!W#i~|cag0e`?{?lVAfM`^VOQp~-A6Bzz0G9ziAHq|gkRYBJXeGPemGg%}ji_pi zild|B;w(-4zOolp-nO-tUzFH6=3s-=s%1o&z$l`KH8qZt3HL~vf9Xw?M~F@R>x4tZ z(KOWREhZgP**VBZ;Xs(bG9{I`{zGixPSx=!&9*X%uSFDU`z1>)L*`S{+40>n>mH}R zp~m`w`xIhwcD}(lFKD(Ysw%$bnt%vA#Jcj`8)Oo_O?Wk5Z_)FP(0A7hiwc-`1?ZK9 z$e#`Z!}n4M!KXbhYsI;->$GJ@4qAf_nr6N}7s)OD){99lLwP)DU0+3?X)tntYFR@1 z7d!>1vkPGORaY};pa1^nU#8OpI7@A4buU)Aqjo$X~* z`1=Vp==_cn#MZQm(cxe{;iUam%5PIS2??LEVL%ig@S}0NtN-EjxS*eIA=x#T4fRJC z(>plD@D_7$MIx39V9bO6^S3ym5c=&sb$>QX?i|}&G`P@ zn4QT}rJsDxR=M8gr6-(-!0nq;1S|!AZW@y?-zPyV!^c))u=v5IIFWGRKDxxMq{LlF zl_*QC`T3}4D)Z4qTT7?_E$MFy68EIK&6N9oY?^;>Y!N?qWsyw;sWTNo%IVsa56J*c@ z)dxS7tGY|Mq@XmwHtg0ywIps{Y8n749hB{4`E#EACW#?r7IRxY{YAJq9_IK)_8$CX zek!{fyPUbQKM?J=ty;!&>rAA^nC02SMl=a^bwBC097?)UN{;6(VioOIvNT~O56`vH zuLtST^4;+I`06?Di{VK`JJswa1hUJ2wE|bJIcj0O#T>P=v|ZAL0g)%;eBIuQ^|Ct+ z1U)}d0anBfu_h^^J@es&N{Eca4<8BbD1!J+Q|vKoWzJdhW_^nZS`q?#GZ7fv(6sQd z+JB<)d9Z!n3kcN7tG~hiYd#6&WWhGIKf##r|2_^VSmL%VExo)HsKq7$-W*Azug_zPafp6WpqfkW3#?L)a1R)G`5f2r*dcguJOt-Ax4i`bwg>xY zZ(`)?UGW?wGN3;X{W&y6fJlmLC@BTvw3tNU^)DLM!5Ij3ovQ5DA2!B99%uH_93>K_ zL58~wQHV2#`sjVE1Hlrl97n*-N6LP)9R4hhb7@#AmCvGOX zY2G!zg4AE25t`yd`WFChr1@KyQW9JFuDr{Q z!M+Hr?M1DoP}lNI^g5-@#tw}VbEa5n}7?Tl0MWw~ezQgo!m!^_XG^`8lUt_l=hc5pxbwOCmN zbWMtvI9)CWK+vD2@NgbHepAlCH&KZ`$2|c8dQ4f6tl<{~Wr3Xa6UvR2H58oJKRku! z7+Z3Bycm?tFZT9yYS1b~1nSTn-nFBWE9Vv#xGHW`p@^)iqyhDycjppAt9*bw0@2Y@J9O>-T_2&1mC z*2vNP@<-OdEpirc-G`KE)>)@+@$t)}@!x({EmfZ!@GeCOXu{Y@IjhMyfu9-mmd2{B zv;Ooe4vqRgru|5)wm|_JRNFv1f*8<;&6H^ZU#Ly~J#Loe$?xK{F|&gNA_)lQfEZiu}0db97+Vf$3X zvF=fG)HA+#0p$ms?|%Rh{F@J>Lp%tTX#5S0M&*z*f6nkv5r6UI0SG zYX*dVCKB+3&rpnS|2--S$-pGscU(;Q@OSVCpfhf8!BcM4}~mac@88R0LRT zDmY`Fg8qbMyU$CI;I5>S@MU<5f?eXp#yeEdjkjFtQ4OT6Ndjr>LAXS%CGWBhWytip z&9|d02cRqVp6QBAo7dp~&=sKoU9pJ1IPm_@hxMF^0ueZ|D2mqy3j-5qE;Frg?vCx? z{uEcuodcxcjqw;YO1+Mn)y}p?!A&mv)06Y_JHe%B0Zr)UdcQ$SYovRI)Tvp>q}%FJxE>P5RW(O=D6_%eF{g)47>qM62-ZIq$_`&))k3t2M_ zuu9!IOYXu{$)##{#Q*L}Ump65;i>#(>uE;c%7qtDYLZ8>QD&7;mOr*0=Zf)pWUrjx z)ZdkV|0BJ1WD8IeFS?j3A3ahK<6pgeo&2UyX+dr>VT}51%9|qhw(GO}Zs#bSdea}O zbXnrt>V6v;kuRW8o);d0X@6A&&i&0@Gq zE&N|;{h{d@TM%Rt=rTcIjb#;FPvXcU@paslH2U@L%RU@<_Nc#m_*rLmuW{eN^_bzGC}_m&AN zprV4H0)i-ADh&ctM38QzQMx5Z!&F2;x*Me%1{*z4M7pGNNcW^;#P1m)zTfx#{j(2# zgzdTS`<&}s=Q`)yBg=&OOX%q9;Ph{}M)V9I;t2<%Ee6#A!1}3C?RbH+5}Z+(?Zo4a zUo~(?^{;dzdZ}>44nU+VgocbOuUYX@y7ErM3-wXtl^zMh_a>t+7LX&R>c6iE}`#1+*bd&t^H$dHr zeyFCADyzDA!6S}-x-}*(X8*SUJ3|u`s3WttBW=Ql^kGcI_^4$FEy}}MIagVhtX~z3 zU`3@U|9W-4-^D^hQari4bK{{Z?wmUHE6I#V=1w)>Oj-h3n9a*;6U}9fd+Z{)yn*7_ z69kum=i}XO_i_4DORm1quOT$oC`a}M z!6n4zx)k->+;SyUvjUm`TMck~6@Gy;3C#H0^hw^7+3Lezy@8X?=#S}~479W~wVv7d zEkBZKf3uuFJ{eALu=B)?VYenpBpErXMBNCf=Y!_Q(n}oNUHq*}^;4^S24$Vv;EfFL z1KBLqtpkn`)I~mW;PKO?fwjO(*_#RetOfX^TN(h+=%LxOj>!h_e|>MkOT%PLZZ)!J zx9_2BKY!aCB0iSeZ{j*!s=xg4-gVhjAXU;|;WZ#~KTD|}^Xr+e-zD~Zi_Y-O+y^Ul zF<~VO#LAV1IXa&_&2!LKRz=Q01+kd>RuP~#QvfjPrH*H_cBqBBU{fSu^L~)kr>U=R z3aD;t8}kll6t>-BZL)UlRXEHW=@aA%t`Ak?CrPb{U24>sbgYo5?2)IuLfGA zlD~m-XM^EqVdr3zGf6;QApNEE9@{6+Y@G+KVrQW0SAk%C7ok7W^0KTE0Ep-OO+AgI z4~UNJGLz=@pvWLdYkI-<2h&d^mmDjWHJt%X;vcsTM5j;L@D?vKUvy)igUY&_NP+9gj z!h#d0pUH|b;?yvJbD|>!*8e@G?dPBM8~BIHF1_AF*a?$)^%<=>1?ff@Wvk!l5$!D}=~e zvazg-|7!ixbmshrH{4Vdozcs0yC2+VYHBchBcRS?gmVKOV{RGP6^ZK-e$TTDN!ex} zaxM|;nNrD|??+xWRQek=z@uD%s|{T`#aLas9B!t>CXo(jea%NDf)h}W5Xxv;rtesuv2s}5bx8I zp{SpuK~{ncBEYZb{%Hv##l3PLv-}#{jZ* z?O3PU&U`?ha3oX3pCCvhR$4?}H&T&JY~y#|u)&v+Y9x9+`Q7yHmf8pL{!r#sZQus1 zu}tP)Ok}y2(t1I?Zb?cXyt;>@<+!7i{y#Tz)yuMS@RUEX7_7r5Mq$ww(C}4G_f0kt z187Gsv)*S-ijXhAWJ|}KXaK&|xj6m5I^LZ_&{cS5b6CGAOT`7GQ}rV8LNrp+HX$L+ zkDMnnD=SM)T#X*YML+6) zIE4l1LEE6dQjnt590r6I5NxV$>N;Zhl^lYe(+rTQYV3gS1dUFu@RR((RCN@I5=`p1umEtg0Ggm8UWccj#kjs0WSeFMc`>az|D~0^|%f ze<{J7ap1bnw#J)0t(#>v0gtjL23uE;>QwFKpz?G2V&BJZnS)?S@0o?I-|(kN;debg zNg~Js-L^W!ieA~*fvjH&Gi?SY%3IAg6a-5hH1B(7DzdbpYr&{#_6BYjx#-6aKRVMj?a^iQP^P_D z!jenk-Q4XDmrJGtkn@KM!xaV{U0Iy|vz$_OeVts49*OT$y_up=dz+g;*Fg64^iUF) zMIHkOOPVW8Zof9`H637VB9>+T36lk{RdjJyTW*BVAV2}_F;Cc2t(4j0=GCv3eg+x^ zK0mofTdMXS!LB<-(P}sS?{otPS5tLGn@fDT*t^)N5O(h3O(oyetj7;iPZNB(Hc%A1 zt9%r@J7fDbb$>y1pjq*RU58X}cxGSkz;S3KtiLSdb)AwgTNS5Y)R)v`V;JH@sn26M zl+IQr#@%UAt8OM$9rZ|!GGH$&TMf94l+k`{nV@oKPG;H&xnXa>R`n(OfrDU!dbvtY z=jF>vgW{rqU}M6gMhLpF_N>}2+^;VfOQ(_lq|*bnzs;8?nZ8dGxzxz89^qdlY2+$g zXRf<*WY#5CB<~>ha@o4kKers}Af@-}Ef;U7LiUxAO7HNf;n~Y@3$--=T)r~Z^-lXiem z;B7G-d>Rk{(#?lc7qo&WDRYTV&PaGf4ZVL^Owe6C{_v%<8)usgNgTlIA zsy##lf?~S>^xN9(+-{xlrr?KprfvUX=G}H-ZAfl8%H7oCSBhIefj0-hW-Gq%?9;q< zyGwE{(BhqzJ`ls&BTl6%tZpCmI-4x`M7JL{kggAJg}Ie7e*%&+V13nQpg)S#^UM3S z%F(W!5Z5C{KrM%?jt9Y(^EvOEFq1N}>xQ=^cNYNT-vZ}Bd1S`9{$KKPP{D(FDA)T- zD(eFKYq_Nl6d}6d|BtW)IXb$647{5I?gHD zKyHj==bW9I=UPlt-8oLE6I}uFF{xo~$c`JGlVtp{abDl_O~@o(i_4vgK?UL-PA#RZ zp6B)$mS!Hq=I9&=_Kb>U&4v{rFYQ`cn;0vwQ?I@L^)g`Eh@m46P)kSrtx1nJ7~28? zAL1*dNLRni9nRrF%+xZK@AMPTPtDC`m*MJZ%P*>U7{4TpP(O!5DGOSHkywc4& zlK1m5LI%y6dSoKl^8zS6up8ZO7Wrw7X{~&cKp%93$AeaEO*8t1?w9eI9IrS2`82nP zEjoTXYMvcK(7Zj*AnaTO!=Uq)M-{aIPNg*u_kJ03fF{p(XgEg6n&+}~c_7Ju!GOf<0+e=A~LdzVpdS*4+&!9phs z;ToahWg%!bSk{Yx-|G^lDlx@1>j9XrAGQ(uvdndX=IA7nK))#eLc~*}{vSgS6|cjk z3xIstc0;wdzH=ezIhQtcOnyMvH;-bsCwLp=eioKH-{``J$0zd@GeA+Q`E0h;qH+4+ zq|T5)VL!j`Px-FtOA0}qzQa#zYST=V3*7?9y_RLk2| z4P-i}+>*dVmpoUQ>7rGr(!^TNq))23_(z){QKP#hxkZzL$PprO`K zlYe%aCZq#5N(qmA*=>$OP8$Jb8Gx!D0{~}MHA!8^c4>t_qUKh}t;Da(C9ke(IB?SN z1Oio4MOiW;-OYCvZ~maZQNcSo`#^zdgC?+$B}IhJuFonV**JZ# zK|P#bM5P6l#w;VG=25oiFE~J?UZzCFyYxa-Kwz^}7y`_%I?sOd-EbONlDVUwL^ z&a!CKYKh?X`M$@+ zs9CGG8@O-|qD2K=A9Wb*;z(3TA-Oga9axTfXg+P9KXs%gOI$;(Kx*;0j11yrm260*#`dZpcc3PK$ za(=03G6Kp)l}R&D^_hF3D;sB!^pcT+$szob+Q9xpk4sFIbFZLM*ACYOy><14?O3Vv z*c=KI-%?MH?u-#Sa5xc#LfP~6zz&Ng&^Zbc#XcJnBFT)B9An36E8QtV|1u6I16Y3? z0G>M55gaZc*h4LD%;W_pN+D@S7?YR>gk-T4X{M&_-C_#aaBV4R;P(wDMG8`D#8sO< zppHS$j;V(UxTg6!4l7{*;M@ya+V?5Q76l_zxZgT;WrHivJ8s}hrZu@;>;8tnJ~C?~ z``(ZA9&1kFh=ATwnU3F2M%!NdDE}zC)@(1~Uy)}4AOSSa2b*Eahl289j9Z`y6gU8- zSnV26M@(SYRkr-Aj%R6%pJC-*X=GT&%)iu%RQGkqujgw3`Yu$3OjikRC<-67yf~)1EC7N}MWUy~8KIAos(;364BSdYdN z{M^%%WfOD~Bt5~37m__}-rA69Pk7{%#-95`dDozD-z)>G(M2mIk^~C!Q*_ja&Qiz7 zvAkk7A27$`mAdcHIVG(P#%4{XBBMx1g-F7|c!D-h)aL$gXSb!ogmu9NdKm#}s`7bD zY-#jBP%qWr{rA`Eb$gu~KJ`Ay_W+%;DvSmA2vdz}*9(vSzeWpS_K@n@doUccECVhg&%nAmAPhl$k6U$GE59DM#F>l^el2cwPrF`W zvKhP5JYhz&@!nZGHF8Wf%Ms&cPzB(rR3X;;gw9dR^@0}jSb~9;OElLzBUHu&W@P>- z*-nhYlfdb(5xIKFpQt_YkRQDIrAze*Xq{??5S!&GL;KNA0m$9K7>DSQHTwAWJXxXV zpP%IKXH%7K3JI=H@tjv*VJtM9#h_iq5(nNh02%jDStW4;PXek+?98PDjAT^3XX$m3 zeVX!^k@4k#OIDxOKRUrj*Fjo$iP{B=D`sNokk;^4*E*8Fa7K_?KyBdufI@HLhbIo2 z9WSIZo=RO^Euwy2s`*%J_S3`CH!HccombPpoTn6JZdB{hwIgNq{TOoP0#iOvfT@JE zW*6(~CD|dHud~=2B%9}Zd?9oe*woT`>rlc1?RLB39ua31nz)_I1AH+!W~rF>?orcY zI~kzmW1fUPIL(YrC8#~dp3jw8s3h{$3fp>psoIl15udIDS}alFH&egJ%P{LpGG1XH z-Z{`bNC>f3zSyEZSmj))&L7e}g>XnIpPkYw-VB{@+zm*w#@%;Vc3EFPsCuVnI*(SYuJsG=eT6t>j6&#RvrS}$DNBGaambN-N>FDY8Vq~ISn8EM zv;iLoM*sXN{-UiPvHx;V{TX46^N8V;KhU;D{WpK&8aAwXQnp2uHC>}Px z&DcUUO+A-NR+Uk`_-O+6tx=fmKLi-608~uLDRQW^2MA2ygzqX>VjaVp5#x#r5T7q#tUqCWwWDiX)GS zN}vVRT(cXZC)`}aA`n~{Dy3nncI~I9w?(b$!Y(>(o%H^&J@b4HhvC;Cm{UVV@9N{U zCg%}B>~fBiJ~@1VmWRpdpVk+k(WEoTIa32+Yqdl^gp9z8o&osroJh2?t_xTNp}v@W z?#KA8pSKig%53LZ#KH+If$=1b+$SzuxFY=Q7SGFp+|Hh1RPZ4Jh!mHLEv*#yn=tG@ zl~LtC1ZwR*?XB~X&9(Ej?dYV;J8pV6mnVC;jLKBn^?ly23$klX*#D9x?BJ9*;LHwV z(SRi>@G>>|H@2h!jjTIQBD6m}UCXwZ&yW+(0%R483Wo=v`&i=uz9AjjT+Y`_RqpWj zkfF3EkOy)hqojxqsf8)1Sg?q-9o{O0IU~wHa4h9f=UYL0@$@xXJSO^J*@5N)$#Usi zm2P#`$_%_V%)#-4!xd75e4Ur`uFY1s<;8H!Nmje8y;|P(wYLwQ8t&~x*o0>n(K74o z?%i5rus?TEy{eMUtYNN5f6`enI1fi6?p86Gy#@@Su27u!lF7lQ9dY5&7Kv^B!6EW6K2{v38H=Lmq(6@de?FSC}y7E2DRKj1`HsK19GqtVag z6+-9MB4FS%qp6wpoiOI!UuKV!h4mQ zC~Aq$mDCdT@aC4Sh7YX1G>DB$NE}*dg~QyN>~Oee0|fEVQkyS`J+q5t)4K>>`?Zcw z5$(n7W1{mM3o&i%Iyt`X_Nz#vx#7Fz?(KTho(qd;AswB)4mjqv8Ie&l{}Su1Vq=rh zoif%UDUB!P(;`0MLz)pot?TNF;`62APusj|oO@tJ;hyHhmJf)5`oa$B{m=bM*?rgo zo1P$!8ZZ%Z!Ry{C%T3}`u7n5dd)+?5hW-R}{bLIzmQlO`@v^{BnTPet$IxZ2L)TUAi_G^Y{b`N&9XC+#OyPe$C-& zkg>wYr8}KzdrIXdB3j4vzMM~`8T1&j2A)!$TUE{oq8$~RRe@12?l(kiyb5$Y z=>^ECg~#~gJfza+Lc8$KEni)Nf6x-KEt?&u>Vi})C-Bd+7td=@9V{S?5Q5dE^KL&^ z8P+JDIS$_S=!M~rZwgLXw%&iNMcil6Sd*MyL4T3t9&wKrMMM8oNH zpX8-xWjjUX0fg_}OG%u*|Lk}HTFy??e(fp7h}cA^@6<6$rjs4XPpNk`Jt(~PDDA0~ z~w_n8Mz|IDYSS=#=_ZB6>o!m1z%g-3rrq1GJwYWBxH0-R95cBgKJTfugS*_1R zfok?j&2zC@Kvyt$T5z**Zb@aO!q&`0y&3QL1n*tY&)xd;P}QBa z{hcCx0t3d2?4&$U2ndblpA%K;}*Gt$ysx$S- z{}$f1}t&i4;q^62C}P6x*Ed_c0!jzR%8-NC$3viaAj76K=|h0 zqV|wNd+-ASrNJwrBlP{vY4oe=0)^y^T{+4R7*b0J1r7I#SFA# zpNQ_|*qSR+NV#LdIhzUx_fs`{)fVkuTes@@Z{iMiGb3kz)K~Ce3VJRBy5mNS=Q_|5 zqD2_W-xLkO7ArblKaes5{$bP>s+}?&-u@DiTO8K_{LXc}xm-O%KM3;TK#T371xZyMUc4T?!jhiQt7eI8%^1ATUCuIHZBP49c z6<>Cs2DWi6(B^a}2Cmm@?YgJrl?%1whLFYP{T8M=DenN+#_GrHUDn;hPInfbUsVMrm`KBeA28mwHuwgU z?{ss(G%2S~?;3LIwE)NENdjM9N|9w%tB~B&K=Pz09oix==>eyu~g1x z{I~{^y)Z2k_IR__N^2Nz+>PzNvE1;q!Oost9jikF7n;J2;YyfhCl~jfhDSwpOLu>( z&!17JNg+0-8qvJ?M<-p&tM(t(ljQj9YkshVuX@x&nOF=g&4pR~FhC#jOF(kA8(tHb zY~vr?+|6!@>E<_ibD~N4fD|djrl(h;wHX*@`3W{VrVVek3{Kqmmdm_yao?e5MJUEA zMi{=si}CK&Oww`tVa|CO$ey6ad>s2*huk5@Zb-MoatiX`!>yILEY7Vu)T$O)QMFxW zvYvsQ;M_6yI^|`Tpu_e7tSz6|VDJL5X3(LHK&gQ}c$+T&_LN^^Kpp9b97koJNU>WO z0h;37=N|(+nsu%MZBM{2nUh7%@H(4)PUPXe{8f}{Q}lb7x~A&Y)dnMf7~UsUP%*4> zZua{nKwjnu&%5wwl3m-qlx?RW;A}6?lRG&5&-z4ruy0fG|4a%`u}4nbVL^}_HRP|s z&rtGVp79zRwIZWhkYYJ8GBNf&4+?wE&OClQ6nC(#Y_GN4?}mC&9vigVu`Z#tu7jL^ zL)u>OFrC8w6lsrs>hiB%Dys`O6eH^&=%+V)bGTwp9RL;FYk2`5KjEruxKh(EIv;b_ z2bHW{6Ww<$AI#RP`3E1^ znpWO5G7)_&V7o(>A%z#m%{<=6lBCa$NiM5$3PVpm^Vnmq6~<7VROgN;`H@*br%37( zUVkYw+_T8@P4hLk9U;%Yh24t8eE=hR4sOGaI#aQm10BAQoL8=0>WiYPPqkmT0bKub zoMl}JycT?}Ja-IN&~5lKoiQ2r9XuW7SPC1hsQfR=G25-tsKh%qTn+YI$D z2^cTAkukgN5xM2D+sx-kxNcoLQ5O!Cz~dLNEx|&Li}~|+Y_Jw5t9;YL74KmCI1XIu zkNUz64aDJY`~H|~Y0|T81U?Fq5KM+_Iw`^fW(F1{h}6v{3(Wb|AZ%SD3t#xMi5vYZ z&?uq1SrJ8%?qDVQptqa4H_Rz-Qcs#8neTI;N+%y8y!c}&Hl`{Q_rVYEv7oldNHR~M zSD26E1I~Ds(&!QJIKbT`OR=_L`z=;(WUG~~DE*_Z#lIHOUId!73t;^P#61%$V$#E$ zS*{Ln@Oj78Nd7+@5V&W7pzd~7tAOG8v5y|VR((dce2*s>4n1X^?n+qKSlL4~+}V!G zp+sfq06aRoc(A{jF^Tpd(yS_f(h28%#V^$B2u2LTifUn@xifP&fo5C4Y_##Td({wW z<>oqqVqbSr$(xz-_xWvlW`5jf1=MhU9APTC;j4A-E6-C#cEVFvUw!>wFQp#UNsL`8 zNRgkVnMXwsV2=R@cL&>C=Yc-c`&aXO33#e8kJ+~NI`oGHpX>W4O%cZe?s3X#g>$N~+eP3M2Xy~!9rzOg!jH8) z%7=TuC{D-HVwUUNx?clhU5D?pmH$h9 za7F{V`;k6l9-#(h53U$>^*Y#=8+9f)Rhy0${;V3fPl>XvbzRUAm;!}MZ62V{AlZR| zjnhv$`l$=x_S&TtnF_?rmLiXc^}+7YJ*%DhI3q+_?>_d> zUdP@(F)MPZAl3Iz*Cya#i}(|5{2E$3du+eID{#n00Cz({=NV6DI1fK{h8$`UgTTF2 zV!sQ8AuI_0_3Xd`IFaCK%0gw{jXp3T{9v6urPbZ+D1|*VNlnp>?M_md<#W1q^XCG78~s;1;u0`y%1 zyRaF*D!E<41fsu}3%19#K_lg6$=z>ly<)ZEfA(2b8(&lQ&OZ$ZJc-x5x!$t5xpzAw zL?&==%-6l?ub6nkA)>*FtMM+%ykqs+IbH6~{t8CT3*9$Jj&%Vr3K&RObkWN_^)ESE z=#Uo~<6a0kNQ>3!S2+n1jr<#GE-1++0(RIK#mU%?m&7xYzC|WPc4{0aCWO2?<7nz1 z`<8C&_9OeHei)TY^IxEQ>dk$iZDJWEU^q}&Kd7NNE)DQ|RehFo$IS^)Ci6{5d z>5UleM4(x6kBp&hvMnU6yW?}uS)$*^qWzJLuj9cYG&7gXs))C~<#n>0s6Yip+et&12|H0Jt{T4 zKPTduym39RQ98v{U1TF1x7Kimrj!Yx3v;X$Ub_mRos#}13GqbwT=fz zApv+ZCVD_WvI+lm+V9jJ0NRe?=w7eWrF!?=byv@4XeG@(Rxsij@Y~U1Sj?N%Ie6y9 z(`pXhL zo0ZbiqSdCLG2j)dYd>_hj+O0`1s=N5E!D(eAUBY(3$hr(c!eD$x9uIChiu;Sv~xVcN}@V zu`zV_IepfAUh#Uvty!8u`s|BG#taq(diGS_1wH-?88i~d`%52c;qTr4S5w6f)w%S!Spsz7Li7|hCQmz=})**;^_n54|tdcd77i;A} z00KhN8)?IjC%+C(A|$yi{3LF3gv>Z*actKxyo6+85 zJO+8*cYjCK$Ai1?ZHTMRr&EfHMSiSpq?907*r}MDJzegT z$36ojQ4e)?WDSH4yv~FvG(8YwE;4?3vQJF(ft3p(bI27lg?kF6kIi(G`__9IH(IQ^ zs-+@9*zv}_MYFKVwHhcXnL6wRs~F{9aq$HD8u2GaAO$~r585|9gEXv^$7&+}+lplq z*?~;IXohCcaq|-Mp&V~~5lC+Q3Iei^ay={pnF2A2O77*4m&i*CWZH6b6T~N)Q#%jH zOXRZrPAaPDrU1fR~U(-n`)rH97X}=x|iD0x@r2_RT ze)x0Lhi=#I0tKe$nf78(JGU8JQEn32TWtS{8G86iNdVslvQa;KbpEYFyZnKj%esN7 zXF9QBU{2um4?jhqL-(Az$HI9O)_G1?9Pq$Ew|p5kB_SLc;UP=^nXba0)Af;_p~&ue zSZ=++6=QAaT7buwAyG6wu5O!~OopN?{@=0j2;vQJSLkEYbJaXn1ta$+LL@5JS^tyA z{J1u=i-}{Zn3Yym3*Flqmx!}fQO>OuJ$}~2N5E!J@|`w$d4l~2^x60F%c|Tg68lqH z`LS1m9k;@P6Rq%ox^^<)@2Zwe-Nj^cNgc$hnz{AT`vM7T9dxkKmJB7F3EO5}I%cY=47i%7^5qa$gtZ`xkP66PZAdsVcf-8fZ}t z@!tX-4aM9!=~9If02gHBP}7N=_D3k`B+iEmGkXk}Alc0UZ0He5{nHoc3~Jq4mN?ic z#*XH$v#CRwz0jp%4V#)Tpg}hPQ)|3Fv$H7OnBXQ;nufO12707JAEAf-5%!N*vvxJ# zZ?OHN)mStXxXU!lV2ATREoJV(G1NB^}vuqZCvSU>%c7rwl7y z1E(0Syx63I8||@HTqVEDq55aneLz7U%BuEt8r>JhgAJ6IzkOvh$kE9Q=b^l7Hs7Or zcGqKL=`4Td!@cn>4ng3Ok$mbm1RvfIkXC~(FesR(d**6^dp77lf2e#VqMAHNIG0(X zpkx&0j5LYaqyWim2a9=n)yRU;Y>w|-klZJ4G_HcFl|joMTb~ZjrngSU@AyyX zxCY6DUi`yXj@(EYkK%HF(LN+cehd$`{6vlIpNj%Mrd|-5qnIX{teo}9e2B{fNfJB4 zb=Q`I@%W8)wLC#;@fS}2Ob<_j%H_$E>4ZGwzOGy*)eG5sBnoZ8hbLVh2{uQ$rK~li z-E&na|CIAmmKbyUHXRa!Zfb-VFyPuerXE`7WOSM}Sj-`{Te_FqMru5b|IgX}3p0e~ z>c!gMClzids;}Oy-Ck{Lvd1|M=$C?Uyw#xTcEgaxVpxsR3!C&R$f=*wbPpFQB;bqomtZFg_oVLwG`5_YBuRoord(j}0ded)LPg@M@v%$(EIIXCv7mwKY z1q#V^9kAOEbo)Q`x44rs9v@;{>8yN<{`$+hsTPGR9uKDGx-)M0KLGe60qFB;Tg1=0 z`1aeM)#r)7Z!Z=PIK4RyjE6rtgEWM+s5{>Kh1TF1#k1uG2><5;+X4?f@Kp&N%?8UL zHNa{eKoIW2V+d5{xqE8Afp{Q;&0+ShS$Q4m&wu@r{$AjaqY{1vdtl&=3%KVmhQj8p zt~4|?&3xIdWFu>fQG8f-jt;0S9pIa9J0hO~S1S2_7qE<-xO6)?jP`%nVj_FK{g3i% z9wMCG%m-tHwSxAUrk^nX+T3d06BEwvgPQHTGV)fMsbqVJ9+^R47O=lla}9-mE^V%U z4P{MmW$Jk5&48xamswecgiarx>U~veM<;fC((95%kKcZ>q8SN#G!hjHOpn3DsQc0a zLIv0IH{N7&2|S6d+Wito|35)CkxlO5%P;R_XVWRxbZo;MwcV8YPNk7UW5K>OlU#uC zs!7mEw`SH(Lxfd_3XKf9qhB0*Zs|QR)SNAj+vU%!f;r62Z~G#$yRz7S`CE7AA4_%F)%jxtmgx6yOmHKE{YN_veaU|hMtiR z=9ys2Vfi0u!x4o3Op6ba+gxh=RY9IhhUSoEp8g-B0siS3b>a?caK~OF!sJBTv}|=^ z-=jp1Is%s=umzCA^G^QKQyLd^_Wbiv#30;3aWR>DOta#}F|<*0fIeFqN#>`E)6^mA zn?Vj-X7?GoWoD^cX(eGs(%HB;xClbr9iqT$O32*D(6Hw(J8Qldn1pD@ll&73JYnE| z5hBTaS*poc^oYxMo>wKu{(XplCohrofquh!#6EUGTxh3PwTDl*aWxU#BV^Pdb4(S^ zKx41=?X+@!q=3Y(xW}Q~=(}YeX&;{;@W8)X<7nISUeH(!=o{j=L~@~1$!jrPA!@~J zq=4BD;=XdPGFMy4`A$Fx7kAx6(IdURO$_i)gZH5|rW1Zgk#Ou!MP^1=b%`$z3qIxg zv3IgzCr?YQn+WE12#~)2Q?#f0ybtYRl<9j00P!FNE%~3Oej5>L_2OJ}wKcyU!^(h9 zVHE;v{B5Sv;)lTlEJ;1IaSxw#GvalfzxuYFH(+MZcjJUh0m-r)4^%ut2YuXY!uqpd zpNG+W;OV_v-HpWmgKTod7dDuKVRs-|UQdr)RE0geC~6_=q!&Or{(n3G%Qf|tsAB+N z)}5h==@5I@aOkWyFFZm06hf|uKMg~X3|A^DB0?`weTJ{?7M6d+)DRWH-W{IAPxdP& z{R*JvZ+#rCQV06c9K1c*L8glXK6*9hTCRS$Zz;9ZlF8=gU2;IknM&y5nlJM#tNb2*6l5v=GN3N_;(3{RO{qHGIKs6I>~hOPUU<1;H`pPb`k#IawgLSL8F=0>Z*>o{dKpqW)fVxlvz+O_P=^md z9hnI6ER|<0ee1Jn3hnU1t7Zm4SU^$+VXp6_Y~#2zAidnPQl;h}ZEFW~u{9G{sqU>W zm}tESev28hWL(3TE9O(6Hk^oLnNWgwu;)U!L+}4MTOc3KFeES_uMd@0>^R~mXzOca zco=UNK^cnTpB#Ru>UL2gU4h=OvMyKRw)GArw zxMN-gqP4GnS}js&AjBV+BgQmKA97v!1XSe031*P>`~~73c}=yeQzVkT&HDd;9U_10FmWsrxIA>wiqlGroF?79|02(Xg7O*-qMnZytX<^cnTkreuDJhto^*-74ww zUAMd|ZDt|T8r<`uXP}h05(zHaPmJt4A6mPu1(DbZDE62oH-$>N2fk(JD9~`_yx?p9|RB(2lmmj-(OdRlfmI>KyWYSDJYsZVo9XeXDm||L#lY_42l4ZR1i)8p*fi)mp7~`yN-^4P8bfb-DBt$R z0b)TR=ohy|ihg6vfNwpzUt|bfmG&=UBlpp>lQG79FtJw2QCHB~d^q!8ObtN({=0Go z<5LqsZ4Co-VodD$OJCYjCM9JXaCF?60;IJPV*}3T&JHNJ^Y8Ggy>1Ym?7bTxe|tP} zQqrJWP_&Vc8T60kV~zgfx8GZ0K*rKnc?J*m2$&)})G~mVXBTjnN)$nR=Z$mV105~3 zrOxnU=ktsQ|4vX12NvCvlf~m{*tj<$wd{ZMZji&`z5A~Nrx*rbwT3aLBwCmO4xnU0 z@$CY2ASH-4gif-gra|4;S~iAmn@lV5U+W8utxmO{7uB4LyK>C`f`{%69Zo!*Jk*67 zY;pxPsV0Ng0+iR-ZEX2k7}h>_rov_W{3&_JxcHvk-m1DIL1?_QM>D(J%6#o0vV`q6 zhp5S??=9@t?FZvEhDxHOg!Z1O*?dqhSc+UGYFK7Q_CyQE-BA=U|M{FFP8LrO%LEL8 z4AN|4yTJL66&T?nTzOT$NXIatd)NCxj59;ek7)~7mfCLC;2Hx{Fo4)==h~%8h4x># z>OFg2@qyJH&$3Jn)Qd{wi~fN7R-rv5q=b~Mi|Xw?Aclv5OUzUmolGh=q6x|zNPE)~ zO#hXqEvV_PLWISE)YKr=)I!78w&B|ULRf`_b!}p^*h?0yugm%Lfu75 zz+vdoW(D~~)84Ina8GVw*0A|0=^(wH?7rFkb9=WXO+WeY$?c*bh|1<^grFxXz?z|}&S8}0rhdGO@@q{k+(!2x%aKP7iq zjoOtDWIuY?*2tBp=Y!|m6C4F|S=uGt@lzoKvGUV$e2WvzOvAr3%#aZnWHb}2`+-UE zW*NI{{!eQMdlAQ7zw(wA6b4+Hq-GSQmS&xzC+l`#@-Z*uEPyVJFBqlcat?<)nWM3 z!~434xRzBSW{#T+YQd;I&BH{a-V*Bgz+-k?)|4Hl9z#sKzwUkV*(WHr4$?5HU=GsL zU?7V1=)fC`=a&9EaiX>dr9z6brM?yUM}#fbb@@kzEix}pfBXgx7>qLio{n)?$T#Ww zcA%c!G#k2gvozLF>3*jP2ZyZMeCq*yLYL6%;tD4Cid`bL-rBOOnd;$iO;6pocIK7@2e#OFnP_gQ^kp}^*VF1 zdXrw5?U4^MkzIf+Fnk@`zh>#8Fv*kl`|@;vun%Oxc-f!4xK949Xsv=n@0H0YN^)*- zIB`J4A*$u4Rfm_Z-UCcjJ!VyiM`k6L{NEXHz7aGSpP1HFLd<~fpj*|)=o{{dlVJ$k zJAP(!q$Z`PO)Fc&54Q+)v_;e0g?9}NFcQ0^vvC|D!}ObXfcpt&F;q-xkUsm(zD{>F zrcIVuIHy53auwk4BI6g!*6vi9*`f2C+ZZu6M!H>>kAw#oa$bn^#bU)tbRwEr7VnK zg3BNn>4M0K%^9}k%P>vAadn`&=n(~O^OB8oS(M#UvBG=F{|Z6*W`9!DM@~E!NzuS} zEgX}@J{?d0aKpF&0L<0=^6K2Oy7=YQYd2xWWeP9Nzcu)P`oC-HEGes6T8)T~WDHJN)jcIsD;I_@ z5aGlS{7wp$ChCbFw9)#lyZwWr+pPOjzpd}W>2*WZ`p|YSvgfmXVnv8R4{cfNDxMQ; z7)65s>lO#n-6zAXh|nKEChI5`a1GV>fabH@Puuf(6%vi_g#y?1mdVFgCoYvrGS&dS zc)F?8;a)nDYo2F|NYRuW>MKiSCvSL~EPtE z8NanSo6Qm^&GJy2!9}&Ob)^SKx;QU}4K^Sq4$LS%qy-Qobs|bt1V~6PanhWI8_;0+hJc&^y~6R@5!olfPv(d(+> z{Z;R2DQ#Ib8SvuxecshPH!8Ub$RyV<06I*+mdG0Sl?&q7{C{~m!P)6(PWALN%SkQ_ zIh5m`yR6W&?01V1S%hERRis62u-^8WDs( z`x2)5zdW>6bfa|dEp%jT$hE4q#40ST~ zJ1Fj|94DRBWIAj2O)AB3?gvcreDk{x!~8FQ5bBwc?O4eD2{K)R6>9etPWb0ZVu-_x zJ2tGBU}6_LRBHT8ffW-u&j*MYUTCV=9h3_7gT&XsDSAF zn+JzL---Iq+u*`fsE1N~Lo0TDdUkeIbr|FEiI4JNs3z%$?u@%o08A_9Oq*_2vTD#fY<-@b3jkbrY8JeVXj0AtM`1SRnxFVL-( z3TgqhRv}RWnZ21eo2I;A+(*#^*c9jxF#|cb=9@|vGmDCR`LovML+M8`cj5~;+puND zzX1B>)zt_%`U3jq0c`8XC(`L+RO%<8wE)88wT?O_%C^-6)$bmQTwx=1z^xX#!qC1E zOg(S|zG$pWPRr!5v#%pn-tPRTp3!%wXJDhQTjw85_aw6CdFSkFpSnqsw9k0zsgU|1 zV3+8{io@kqhmv>usPSFGpq+>fihG{MZ<&OOGSM6a&iu zGL%CFYSaVt-j)1U{Y9+K7Wnp6)QLNQ*$B+HO@p4!cPoyRx%6Oyfs)ISXcrg)64G&! zH_tDr`c6Q=Li@XdTdhLx$A|eWc10npbR$_tx3LUC|9RlM0SE>Vq+-vXH%=P?dwgFc zabf@S0A*nuvx+!8ye_&xUggil8PvL=)&7)Re(GB~zFa_h)wUS^q)OKHwi)U^i?WfK zvv)J4z$8aRg$Ckh*BTEb>US1OO~Ym2}?1L;|2&) znUe`NqCzQ1uo4?sKInTngSt~`n#^@nr2JSk54%O@`_@Ia6j|Xy%yP|3#+fd8O+vC% zi%Zyhlls}OShUL_Shl2GKJSmwELW_3In`J0v4h20CUO+4=_$DsKc@@-0G7Tk)}Z;b zNG4jSSTYmiHpW!}=GJB~+gW$YIXh9pR@*qpJJ!av(mi+>IsWL>SUWMmVTucF0CFS~ zz4^hM z(fc7W^TijgG6&p;MZjNl{ASo^)wZD1O*Hb6i`7>K#&#`q-0bCk(QDily2z;$3moAx)DS|x6meyG_w7Qw?y#Ap!_c zdAV(d=Q4+KIrL0ES{xQF3}aPG3ECMYH5q<`nB5h|Ae>XgAhJ+Bk(h)lU(q|6sCXYfj7t?ooBkz;b8v1P%UEFDi?gp`iiLdAGt{JDX{Vt=MyCmP0`JdR z^?dEyAs@t;_z!2&!%7h#J3?upEcf zXXA~J*iiz!4bxrecRqq6e#!;Rpn$+bwwgAHB=&YIQKjaa$AeYPUF_GynFtI1Bx^Uv zQS7IEw_@5#1ldG=DVKv^O7BvDXNcahR5m_}n<>lM06M#_5?bA&ore`mq&rLGsp5aV zLyuV*>MDlk$m%{5LI-Tl*&n^`%w7TF-GXJtI2mV8_KbYdyomnj+BqPz$A_IfBn9Fl ze*`FqbT=Q*dc!c$qo@+;v@3OViBk>SzbPfl4I3PP}c;yr&2qE+c_gX{r_ z)!_Myh0zT8Ns7#kQOud47TshGtX^SoSe*;G*4eBs?enVFIvw2Y_v8v*ZGW3c+sam3 z>zj&ss`l4xXO~O2eXM85Y6_P;-P1g9KrP1%t6JrZ_A z0Dr8{C-Vt#U8-|1hs_7CuV{du<-wUq3d*cy;zb*!hD+ zLvSWuvh+Pp)*b1(>dn4eHHF5z%t`$?vf7pIAym8+T4h`CdM=l`ngBiEHhV{_?dlE1 zJaOe~!HZ)n$^eQV-ud8(UMBW=O+`qWF6vTWt{2jGZOLopLv`zCNdtlR%o{3HH%m6| z@F%#Mf*PxMzjF zPSjOGj|v)c*N0oNt_n8_jJD6bUY_r_mR*;p0ENp9^UkXgXTdXAptKFWbfv&C$@Lm@ z^p+dz+12(WCB?hISDx3vd}2KV)lC6)=k9DZx|L&iX8wK4@I?+K8p3pox!S94Vb5L| zZqM`fI!#JHx`G4gK(wsBpXxmXa@ERMDA<&3knf2NIJyUN(=p5ybDfQD

g5!6;63I2p z@-;-Iv7WNQulJ%gI=|8|m*u{UOM=PowN6vt?8&2M)*O)U#;v}ia zJgYn44~8kli(W*(HDoyTfXaVsL%Dy$VO{>3_sxZJMGhznKvSW94{2j+SoA=C9UnW+ zZu_X%muNi&cKY<@3@6?yn*IKq z;qdk1s6n#z_K~FZ4H_eAKi;Qvd3t**FeJKieDF42jjJmfL8pUVx8Dz3TLOp5jwWQL zwxaB=FMZ#PubD5^9haeqGuQrj|2%r<`QDVZGC#9(Vbt6}xiCmB&FB9d{ThI{8Wekl zftzj)s?-fx%5sl}QnK~lD-!~t-!sA1jSqA^L9h zx}F)Nqj>AeMN!zJ1gWTCk@Ui2h)4kAH#+Z-p^XJ@R%S>)_^^#wdjbg+a%R6=a(A-e{M) z@)p(yKUY80CJ_wC)6%u^KE290Z(bPRJWm{1B}eOJh!;9=o?}QCZJDlU8SUOVuG-<^ zl}@|%O$RPXp{CHN0CC~Bjlq*rT4K9i3$W^%t zb5@6_3dek2e7NxJhC!fz`x0TA6e{xu{lY`jLmfDl$X_)d9@GdHpLRyYI1Ssb(=LmM zP^tUCIW5}TyFcndsNt=sC|nPpE!L`_b=0hQU2Nf*`7n4Rt(f5y!a-=!Sxt5FR(JCm zbFJbx>@o8Vi$AvS51$B>D;VSNSGNR}iwHfQ6jpqBMMF1hbJ}SB;@V|8de+|quVqFPD(0cK0Cfed68^4b z&2CcI7(UrXh>H0a#k~d{L((X?eC>%iF&6)a#;Fi^ooGlK9YrsE+PpS-JtLZW3~Y~k;95o3(2*i$*I!uJ z^4s&ht7AU-Y16{6VT+!hqox*>pB7^qj@T3G+N?BWFq9?)wnW97k020R3VRDg$gp$i zRbGkQ_6~;73g3hHve|~h>gI2f(w7$B&}M2*D9rClRy?pb#U#o)Zkl_c1iqf`0bu;m zK#{Qll`N`dgb^HjlhFFS`~;480hA%r6JoWsBYDC-LxNRIW7zn}YeF8~r}czmLRP!0 z^J2Vs&&=2?PDW&(wPFXKWiPNWEvhAsQH`wd*Z80Zh~*ukPL_GXjFfn@_PDCV*6fg; zC;7vb6L~6=(&k42;(_W*nZ)5LV0rTZ_iSpSZimnaBv%i8M&XyXAa<}!ygRp`Xq^JWDj(FwDoL*PG2$%w`?`Z{)>)Mz?c zBWRhOB}>@k?b%-dl!XW4@%6=p_u15+S4v*I|1D!9doxZxU64@{T|a_;3<$mHyu!ty zWsgE4`kl?LmMLe-!YLQq#fcZ4a7gKAf~rd*?W_A;5s$6_rtHtAPvCnhoa5qI{)BAQ zIgQlrh*=<Q z(AA`W>#YkZx*Hzb))5RiJ+(+X zmOoy@dQWJ6V;%IqiIZ`ykMf=#Zr2x)rUU#yZ#St$9{L z?PBRWT8Krn_@m}AN9x8+<%E3YoF%Hn4Lqqsd5u}79kU&*?zg%7Qvnx$)txcd7 ztZJ}Goa583kO=LluVuoGL;P^PC*l1>ytnS1es-%s_i2u>A}d9(ej9`+&9+dx3N_AU z$o)vw4j&z$=GA95nJ<%HpUk$epvdeTOwMKlHTd(ABLOlSRx}XSAH`l{Hz~XPx!fIB z?Bk$VqlvleV&8}D4B3GY4hgiOG|dkgO0)2}Dv#P+BR6WJ{22|ynb0k%kW&=wZR=uf z+#KNrHD2Q5^&=?^1M6$ms0dpSfvZrA6_6mGQUe($N)P#}msu6k7VL7JXSlw}GY9ddDRc zRptq`-rjTGkxM9c$TedL$Ko+gkXd!snD5eS3ppQ*gZzzO)Esr+_Q}lf1@H{E82s4C zbf@@}YV5*|>yrke<67(>Q&RQfI4zxfP;74E_x4*-cKegaQre>>+i*rvT>_Y_?=Kt3 zJrrrnf<`~_oF)N1iuf>2+fzATJsa{ZwZki0M@LF(PZ)3ada;l9S3y!Unn9vps)eu$ zZxnQg8?l}B5s$}mEtP0Ft-xtfE%t#roTDu%bgRpvQEcGjaJZ;ESX$!ZPj6fy59i3n z-IeLog8>8vN^^koi@Oxdj7zlh3j0Qwc!G zT!?VYB)MDEJ9HFLl7gv7HD8v!IvN^8TInR891&lqSF)gx@3g>_|7!h#`bm#e$(&2m2a9y>;dFf6HQ#3!WlxxLLsI^fu;0PixbLtkeO zJ`{uT4{STAxl(;t2hT?zbT|Z@=!zezoU_s&6e5>)Elpr1a+PzcJ~r^gPPneN`rgo6 z!&9$no0>g?lET@ntw~&A-M;WH&njAr#;noLW9Khi;!@Qmu>*?X3Gjn;F-XA;}ybR0F&M z4~s#}7oM>asP$dH?upJo6#t}Oq?rHhx^=tcQ$Y3y3m~Hd3CHVl2-A^Aa9(oW63lu2 z{1mnm{U>Je8>mZG>NP@&s7k4exal|;m&lMTGxj*jfZv42(bf1Qgtts!g!DVs}4)Y(w`Sy>6pAwPG%JA(sTj5K}H zz*t;>q{9o|h_^My=)GMy7+o}fA)39LZ9xLF3KzwW)i%i1pT+e+@+?_!&q8Y|1@ok) zVzlXsw>ClB=1cQmUB~zw~Y+$kL#*$`DGZzA(hBoPv_Y zWaLOc?;xksoT%Br$JagUDg=wOG@X%0R=nV2*z{-X!}vMSJ%uAV@ajpT9f7&dyIosT zM#EmOc6FG3y!W6u%W8a|U|pngKzpAiOET~%hS-LIMWm&^$2Xx|0-pjEws`S1YD@*| zZ3M~KoYcCcUE?iZqelCCI+VvZeX+MntvAiGzg9v=Pcc(&(yh{5I{>)GzcRA z+io=h%67ZAaDZphLhv$}SKMsbGoq&7A)VN`4aPBpLC9bs{UV#Y>oyYYHB z{gqJBqeMHpUx7qXm(9uSeRHV$i3j@c!Asd3XlEVm#(-NH3bw=OP2qg69@VSm!i)E8 zitp_17rmb#OR6I2nr<2<72)eJT?JB9xb;hgKx%IiEPSlCulgHNqRI2r1YCNoKQH8D zSTLS;4X}1AHl8$0qDb%L^;gEP(Zto1dTzpazI?EuopPoP&SO!eWdCF*eESpF@2fn^ zcL)0uQ501(gWlLa$sz3WD|70f_diwQpcQw2$MJE9vC@Yy>L?btu()OBN1BO5#dF0U zb;Rex&U;kSoOOLzl-~cU?zd+U@|hrKAa-26_X|zp2)vH{{!LjqV8D;~zL zL~%Tv$8T8c*ReZAMgb@WWD9l%snxz-EmgIfqc_9Wmxyc~8_gkcChq?8hY4BfAv_Zw zw?f!I=^eMtT5t_Ci5|43toae28Lw6o8Q9eD3Xn`5tdf+tM)m;e@PQI9vECiFl*^Kv zT1iDWb;2O0kjE!mR8nLVdB5KzK+j5#e^K_aY`0IviTL47SIq?i=c;h$!cU1M)>_Kl zlTCEuHV-^iGgY{QT;ah(IIH+-aE z9^qQBv%U&f%h6P>7yAYSxAuIm6ifef&1AjrBeA|ip;Y(_bcZ@EQWHUpvg*Iun&M~@|Jl08wz1GlWO~r4 zy^;7pkOdk=JuayHGh>u6NfS@gRHsm_c;2_d@*+Lu+9|IAT483C7`V5x5OLbY?^CBT z#+rP^#1Nz0K=akQ8;=DPU{I~?`7I<}JTDuBoEN$8yg&fhaqkAZiw~w5sdA<{(WYQ> zqD||u--^;*#)Ojr8?+bED0l=Zi*IOZkLK^uS1ID^M1O6{B?6KQDuZ?F23LW>-FPCHpOK)v4kVqZrXno-mBP39=((5^5F0kb~r6w~tl)fH)1(ng)>UsrJDW`Fvw?#+a*M0KPcM8S#Ah*MONb>T|#n# zLcMrY4bn~|c=&3d*6yS0^LoA!h@D%q8!axv1#fR+MymtU`e+g2hoNz&rUoxPRP_ zo{d0wW+CmFMP>cmc*Cpjuiu>XY5wu0R@8&Es?tpp^xT7a_{R(K6$C!JkKP3xEHK5* z$m_gBv{dldQZfyS$9lvqoefIDndE|NLfbM?9x=5 z!(Xau(-UU1d5=vE=k}x*6tU%OPTeoK=Z)S@^x!2t)|jiN_C;})(51ZJM{OtEa-kG2 zb%w3j?<&O&ISJn7)xg)(8J}sWwBDT4?TNpqUBqUU2^4CJGO_J(8gy3Aze;$44SsjE z|3i_{s*I$ob=i@S11m&wZ zkM33b*2#R6h6JK@{pDkdOCJ;w$uq5&In<~wy%VHWn=o#@e_YH@!VUe5*=}aSxqjsr z8dVIet=m({!?XR$hg;G1rf~*{ho2mq0>d%OyWWIR@IW0btc##lFnD=S^91gU5Y=~9 zWGp;Tm{}RS@}?oJqt|p&c9>pfM4(KkLs~#XrT3FG%Lbvl;6|0OL9Umht6OtN6y zf=UsoxOvkTqIK=t1frb2zME5l#tidh%3HH8*Uo!kw!`P(#bv%6`^GF8G{h{~88eV< znC!6rm3i1xXyyHfmkA^$wRaP&Fk+40>5yyo{@KUyUtv5on%_CR^+MQQtwbf|3Lo*8 zq4_lyS}W0*Z%&&gL-+s7K|$C>?3ODxK*sF9c>yQm0)fnFp)039wBMS)bj>_Jz}mUR z3sHT7vNQ%$W5`}*bDlqnPMQ^)0UpI41O^!&GrSC{_x&O|_Lh+(rB+Jw3|LSp;L%kQ zm!K0*uE=c=KHkt@Xu^`nqHxMq{t8P_$B@cK?;h#)3u5CZs z9)yu6E4Y=45Xa}|9dw%RM-wxMrsAfceoQnG0uecIeD6a-c-bSQfwE-~9RatRLE|an zd4EuXVfL_5v3O6!tvfz3I&WHjZBa#|I87Lw4Y0&Oe|z!mEBob-Ta~JPLt7gL zHM|2GTn5cbe{Ae4W57yNc!+A=q)>92?YW{=)RG`4T)}t9$oJuHvTYp+1=X8T4%ky?;aP=a5O46uCiXkIyT9jF%k> zB!Frl?sWw*c*iEDZjUq^*SIjhBG+Z9KT;>XY#7-?yz#>fUS zc=m?MqyBl~w5s~Mqy0lwZb2s;A{MV`?=A79=ax}`C4g<=u$b%`lfkW^8$B6!7)2BH zVGA)0DM%^Xg#?ixy>L#^{beS<_q4sd211Uu88Mv#qg8bq56kCs+pPwz2mCjFM)>QC zmWXs0Su~5Ck8g!rG|LVTYh!~h_g`O65KXq+GnjAm5(q4kk^KJWCgm9hsRFy~a{cd* z2Gj-od2hCw_7PhKud*7D&6NWT#^?bI6^~HQ(6|>O5olJ%_SpQD&>h)ks_%M z356JVhejq?GUH`caHyPVb+xsQ}+))nLJf!L-@^mM~^?W`2lzRo|>{eGyO)zq?k71 z40XBUYvUIM=6+~8Q|%7VvNX6Bdi|cg8De#AID}K2R}y+y`d)?ul}IRj^6P6NgZ2lu z%C>ZoOpTJarT?-u2g@EGr0OPfEd@+8%+PzwA`N4jn{;%sVtYsF=Ow1hcsy=9e)x77 z+Ab&I(z2PDx3*RSZNeg7=?R()4`Ph)Q{}lnKj-Iix*=yHwou& z=;TYZyshA{_D1EV{i1{-kFmZfgUi#;?_W^^w(k^b5!|82A^nTO^ZjU;NBGTeohsDP zSVw8((<0)%J{gROnG#U4q$*}Iq18Eng&Fs#e)Sj-P4+1oTu(jEQEuJHeWo4E$ymcJ=L6%z>QvG7MY8Qwr7FMxwdZEvhQ zXKffHQD4YgV}oR(2>BklBt|>a5zRfMEB8U0$5?4;q}9}1XPjHru6mjj5o>v5+vRM{ zow~po|M;H?By^Xt4H*ebw#;0?CY+nbhLe}VDIIAde5fmyS9yPc zOu?xvja*|X6x&-4-1AD{kU!SPXfO}pa|Jy zsQQwFuqkZ??H5qgUT3S`o%`p)I;iI;u!l>JpX|3!Ta@pU`9E%%K)tqEtOG6**tK%$u?;G(5#a%lV%Q+IBw1d(9Lc3PgSo`}HLB+hZ49 zDIC%}uJ(b>+SPQI}fsj@5pwAQnv~(mqPM83%=+}!y2^Ep3A%O0eg&ucF3N*xPm-Z{$>8xYL!hJ!x;hK zUHjWU=l^#+q0yTv1s0ERX8wHal>hj%hG6QFHVGMYVl&5iYB}|Qe&BizLZFUo$Z2D8 zG4-=2rE`{p@l~|YnEnAi5vWXKF`c3mYHrx~c;LP~3@e52@;~v`0;yXU_=wX!XOT1P zzf~L1Zup4t+Efe*cS%Dv6xe0l-Wcq>*9)+ljgeV+f?oXcwYS&c1`bWkxo>sa=`ofS zrIL?*^Xm91hWQJO#<}rs)}_CF^IQl>$6F7im=)5u)?Uo2Ib!A0-+MldkA+rn*k%2> z#X-FQ4w`GPZ7zzA8r_mlBXRb-`d1lA5|WW@Q+IdkASnQJjoKcNh6kbWiLp>xi(Vt8 zpW_tvpKg_IV-V)#nP2NUV6)0Csi)sRDi-K=#)*JVrf`JA6U=H7$Ns5V}8#d{Y{S%wmRH<_2OCA+GeZ9y@9?I$JytDl;QrQ7EaUwIiGiiG=;uqH%E8J+) z{KG|#VA+GlV1u+JO|D(i^bnf-L(ikl!Yx0|C-pFh zspUd1heIBeJjtzXhXT&ZiUwtE^z5md0I~Y6*Qe7CNMA74L$xAT<{z;$H9l@*bQEU z%W~`KtBx*P)q=N6-w4ow3U+jU4N_x(QV`gQ7s%4gZ4zMvw!)hfYwb<(bNF2c;|%7o zh5tAX%9{jP7AHb9*&}CbSk;p~45}7%#hD>PWj0_-1Z21vVM?P(SUAElJB7{aEB2lg z2DXUP657mhyE;p@=MS5#cz1q|{qr~|^{jnvOkg|P>t_B1_E*4+gs2Fwj1{Johu;T7 zw!L~VBac|6q^M}8JM=uJolv$5YWA1|e>A<|BkmkDXXnZ6hg}0%YS;U%hc8{f+s9g@ zzHiC02<+iOf;vD3S^7{8;TUEmde;8Vl+Zlw#=mW?$J&Hk zv6Mqg7-M2th<)hnpQr~1LaNUtewrx7u(864E2hN@LbaXc&w(1^fmVw6biD;7Zg+>^ z?Sxc()(@}|@;tjrEcuv+)epmoy+6U#7d2fiCVgjSoeP_m=L&~;Hw`hO0~(FdFJ-bw zfa*k(UDCGeC3P&s03H5{J_693TPMuywl%$jsGZnungpH^r$V(h;zv}n_H^0w+mo6> zYlIIR&Myj`V#q*f)UR~+=&=Vy=AQzBKxTrJz~q5HyR4|9@c=4+dvYW5S*Rlt^_PhmLwOL$=B# z)5sU*Eas)=4iF6rpfLJjF!9?<=Jh#WAA68~l+*jJoby(v{4GdAkL2a!qj52km3jcY z`}ZV~QJatfPv=O@aN+Mq|6xu+C~Uzzgtn9E3>_#KW1~Y$3|59v%7FFd!Ip0JaG}RX{N$Mn7L*z311n#|9Jrp|vd@a$Z*44p2vg+AL4e>-WYOA^xZ z!>{pT_RB`afLP)qKDdEv=WtI^FhmbOO}W19anbE(5CYA=$}S+g?i?4<{Q<|@S&Hls z%lpPOCw%GJ{ML`PWrezN?cHNDAJIy2nnVbO-fX+jxc&9SaPioM|FGf>WOLLVqJr^D zqgsWL4v&hC9{-;v`w=pOwZwZO+J(VuGK@=d5j+keRUfzSC0A%_9az}RLgpcsU?yYsDpSE)aqI?AWnElg}#Ba}$04bqtarp6qT^m;m zi;$HUB|7D-H*oEjpty0$QNO3tXgi{i9XIAaYgE|(^!SgGS_B57hW6LiQmv>}@sj77 z-OB%jMp`i7IDXCj)&?Fy*2AvDDtS`q#Mnyp!^&iuj91sY{G)>8H|#>n*5w`pbpAd; zasWplc=8Yec(>Q01}uEuu3h9jTeY$L=U&+7mtj6Kk^yBGP3Y4))?0*qJM%ODCl4j2 z5527#W7I?MHNJ+jUjW$*eVI66Div_#4O$v;43U zoy^c8>a{mXN#ZBqql&PfYxz@<5 z(nHaYeNbaO1gF+mERe2GtIS>3D7SAD=aFUyeCICm*HMkxYTTw9y9`060fLGOq`qyHraErdgKk?bzL z`>O&BR$V`BH~Ldx(uWk96@#jA7lo1jxInJ;{Xy-e>oLl^Bxb5tbfTz36a1Ds9THSQ z5IngmZN*$4r;B{6Gx7lBt79K9kHP@GN6@j8pvbuIa66^g-nck>Ym@$;xCl1)cR6hu zZQA<{%b^nPT23=0?yK2P@jf;RgE@gY+dmXgpwUVs2u4p zn>fvWo-=6*woI#Q3&XR$7@g}k&Xo`0S0NAW$w@&`T@a}v5O_-mn%?@%FX&ytT%b#m z%IXL5QGurGO69H`19jLOm;v1(`H<6u#FQr>Xi{K;%JdWB@4or}YA4yvPI4q~!z=@_ z)okw@kR#I6hC|qZ_6sOLJN6X{o(GW98D{rUDgB)_FJMv1Pi8c{7#0lvW19UEH|duY6t%;)9Y!3+$6CzGgB%FzmD}_aEjA#d%1|;{P~Ss8+Pzpi?3& z(lOz$>sbG%J?XcHj=Rp5mM-4fRY1{f%R3C7WxHhb`tx{XqzaXsb$~wzp=$8|w6sYV z0!%SBNl$^R_uZPE?`#B0(!9Tnp~1Jx!`1?Z+S5*POEMdYI_>BGTBH|46sglT<08gm ztiV|aOic%e#KQxyV^WkwyWP(#Y1pI{O7wXNq@wLvNcxu3m}%(FOB#o6tw4?nx2OHz zTttiP!Hx{fjMLB&@(*EO3+3j>54AQ8O4E@v1^MRB6)CV6a8DIobO2>bYK`AtOG!1T z7MkYkK83k@Auw&=_yIePdI*cYe2?aaO?n3zirSM9h;Ha(qskg#pEs6iZ>T?il~&SY zc4<|^E5O>ra_hI>s5!^(!wIYiamB*uecB}2dfow@dckrU^x+*^^aI|nnYk}{5*6>P zIuAR|asRc@2!aX?9!V>VGnJ)6T}$}~E}rNM?=G?>0*gGhC&$MlMF&La(31iUvnRWb zx3bbrBc)`Rm7S5*eH&$;{6YIRW?Bqs3AvYL@roAStVAppSe+X`PWd0_%y!cg0tWIG z99my=V^^H`U&h!>0!^$I!YL_Wwa>ZKX0A{Y9pxw@dV25XG9<`C+fJg2eQ6~Ob3@-M z@^yXUm)Or^rp1bcK9o~D#;8}{sAYL$dbn`y>7STMrHpfTwU0Xb&P)HG@%7Hqat_V6 ze@*J5fOgu4(-mS`1l1Lw8bjrPPU)U_<>p3v%OX+!cABHTDa&K%h%0#GiCf{Iw+SkK zb2`-m&GHh&&NRI}GrToId{9?{joW5(`9wAg_h(bavh}DX8o1J1BK)a#9T)Q(-a^P` z%TAGrxxxUQX95eaY;NKk1kmkoYQ*?B^i@T$)@vwFN#KUo`QTKvV4w+yPRK|0oyFZ+ zEhU<4zGJ)O8NgWKyf%amb1I^em7c}nuE+faV4&LdgsWhnA^g3qw!xq|2o+hp>FJyG zaphPMqa_((OY#FEQ(V{;X+bk75!jVsZ#h9hxK_crv&HlbWbneOGiUJ3e5me73%*bj z^j3#^)4XLfJ45(o`sQT{2FGN(c1ca`g2A@_n{wYJQ$`VvPCD~TVM?M2^0Rh$gj8&8 z*l$eoY4tA}zqgnfwjICUSvU~jf9?wW`4KD_HZCC*{5hNvUv^-@lWcoyoFiAhXl;1H zZnKwT9P{D+w~iniiP)%m6;~&3pg&QUh8@!^W<_5C`jRj9RFkvQN&dwLk2+X$=|1B% zJVVxAc3~oSSJm)HcsOEGbp7Gd*!`gpgAgT!>*$|mlfhvyu@!Z9niQ?6n(tSCS| zJB*a(A7jIl9o!ltTTk1m?Rzvdl^kmy>B#=?$Hs7+oG?}=BG`X+zZlD(F;`j^O3e4>jUUu|zp8Z56KynW|I0 zLu@J?jB(2uSt~7EF;PSJ!KZz?h1cF{B*KB6nf3mmAs|VJ5{*i1Pa>>U$2=ET`-u5N zO(MAI{y9o)T#LZxSlx{Uk{>RkKXC(dKJ9pC?>gQzzkU--3NjTMju{S3BfREvOKzG= zJTDVFqswYhcTGO&oIb%@G{D;MwG6S2L#cWLP7vfjZRE6!Cp!ReQoFalo8yWxW7x*DttCecSLLP z&rAp+d$dFE=cloLG_koSJDbd>HkDIL3HqN!>4Sldv2 zEa^jtvhq!g#i;z?>v4WDeAdPZ^#Ua0m+YDBI@NfuF$x~C7E+$breJ|vn8}9DP4i*ZJu{J z;Q@a_5$;L;4c+$0)uQ^8-^S^8Mo5^d!-)Tgb8H^rvgd~5eer&nD_7u=c`py_f2o>A z3iZn+b}O1d3mRurIBMoo67SVlI{)LV_f2CDO8v_ zW#dM+G&$d9n70vby}FJ-vD-}uv(XUGaR=MtMD!t=u;jB;GJW^;8KF?V^$F~X_U z;W_4Wts)pW8V1p1XR;4jnnb#M{5cC}yFaCE@vjOtjfFz~9W{${L6S4^_o}e%T;E%V zlBDr#5!PyFj~_dkz$K@;i|E;~Y|BoMp~!6}+qTr)QvP?Oh_HW}v8^K&-7ukD$(aa6f3-35f_$%}$OcG_!Kdm0yyM?k>I8(`Km+qCWRlMrl znf}_UBXBX^%Ly_@6f=&Uebt+%7bQJBv;y^}&fo{B@vM}0ZG~HN9$?XLT=xib3E8oF zksdzh>6Dht?G-2^9LjlF0Fuus2wGNAaOAc+{y<8vb>#jn@tgs;&TTzOgGq{}P*UXD zPl{KWq-;A2pZ+$F4E?p?tlG6y(0LyfsO+0@7rRG1>N;7kjlSWw04g>qg|uWToW3EH zbe(cLG0E~AH6}6>6rxr>DpdR;aPn4(vu_NeSFzPHQ}aG-EKwQtkz|C&ROo$RLKv7LO;lyccKFlNDM_?1-Hv%yaSn2@6eg)~4xJe{#q3j@y85B( zkvk4U>N8v=E$s#G&S1tNs-V6WVi1$lz$qermZg-hfZ!I@A3+{}P0DF!Gj{8=UJzn=34>c2l_#$@cEh?O?o@5jboH+X&SO6};3A|8yHL8@QF>-Edep(X?E zrLPMwbp*`^2SU zqR2K_nMKV)+JeGP_ut1k_M1zNH>R5G2VQlcreiAoG%kW;53V%hftf7fWZ2%8?l&$> zxJ0-5>l=Ve<_OzE%q=UT>{kPquu-gs?*)UcYN5^{7doxi`>_e$q-S9>n2(iDaF1)U zAo8X@P5{F3H{$zWW4!WQqH(FCyNc~--ZV*e)O2EO%o<_`;@Hg$u3+-3 zgdBhS#TsDKrSSt&1fRy2J$?I@kfZ>A{+EGMT<(1@39gRsrlnm&8zQF~d8?|mg0xsd zOD7X1x^2h*!idZvM%1XvgNOdB$6*j7I<@DxNK+gkf$hn}qH+G8smkpy25xq`_x<#O z%)w-Y?712$2oVnZ`Tll!Gv{ps0O~O}Ow`IJbPpIuR!Ld2s`Y(GkDI<1m;qyNSw^k? zY0ewi`e{yuu%cpBOz3f5tUc&_hd%XbsThD%{=BoW`FD1g!PqVpya%ZhdGPrIG_4~tws#d_iwkj>YzZdt_T31BGe7D0=^`JSy6BskA6vDKE zzA5}-z-rNl$zqZw9s__zJ6n=%28<6d(43V9U+>b0-D>f=N

mKu!!^l=%G!MCIA!P~C+6P3*o~rmn2}*tzlOfayNKwklpX`Qy;mw>N3yl~g zr9NuOSSTlsTPL`g^rEXM10(87>`QF4B*_Cm@KJxZdYsJC4_dVJEgHuxl)vk$Cx|Gmz1ixUchSm&QR=QNVkd^S-hZ z`((|s4Qah>*>QZ8PrvC%$W|RJjiwGwV2b7R>Y+ter8n7?LW{-|EU!e#rE)%E>Iw1r zd6x@(M`aGn%CPoY&)Boz?T@ehZ!&rNLW-W^--@G@jx8;lCV1^KnhHr z<8>AX_}1}<9eVT-1-gXj=z2%Qh+UmezA5^M6(47DRUU)r6u2u+g`!E0^MT$~9ifMQ znlOH|jw6;!jiaK!k;Oj#WHRp;+3+6`?`hBng9S^)wzqdN9c2ZkRNZsXPPDqdv6_KQ z6TVmdV`?lK(|^U{TUyu1LNw#0%`2CcDWJBI6PLj(A~6XhhD4A& zde}(&R^0T#yC@po@2N#O0S^Xb_VZG4A&B8c-(^*#X*H~Pj{MM&c^2)Tp52qR9UFR= z)%+}Zp?$q8XqkO7B7iKlRI^jPtzW8B&a>gO{y6LXd>KTa16`)~eMR9OTDM)-WnR(9 zc3gm!1PqD_L5O-QP9>IEHrmFVt&oLte_yMYlp5R8U)%g}Ch4(h zg*%9o(LwbA&gp@hMp1!>TRul#UKq!eg&*|Ze@QVdB;~+Dde+q1|CxG2;q^0oW9vqU z{>&QJ(8@cNz2w0FVJVVVkH+3@hIqd7RLMe_3Jnn@K2J@G=E14X@g79swCIldbQ&S7 zC7>N~vv~G=dfLSLSgA?*^&YVH>Q`JU8kz;}D$r+YVGLfV4OtoZpL_L+G&wOmrOR40 zKMrl#XiQa^5t#5}JE>Xaq^TN|7{bs>nK^tNp5AVn7NNoH$FjjODrYMsmx0gNkU>oB zHgw+JdXOQsdW%~jYnP1w>xIGR7^eg3nG9YkmK2y$wCr8Tg-6O|@}pAovf`cQqzm6h zFCp`+!UdTdco%XEo2Tj$XMHfK(*#wrI|clpa$vzw0+|ddTiOwi1?cRzDV^;x-kRM|x%G z26NxtK6D31lD&wfPFGE*9QjnQqP7&Q(4S9aKEZp4P|n+jr#;b8sK7HVDQMqETlx5~ z{`5oFBqzs=Bu2y-LfIfcIT9;v7Y`%L+Qxhi*~A3zPrNu*M_TWVi0Uju=i@RRWK#iL zR%F&{?LHf>TN~lkhz|Q+1BeUk)QMkTef|eEef@`5ABQE2e@(bI565#zlM-xw8SdF$ zYW1D)*e89DT4a-hg|?xY?xf>_=OWLU)S>mBg;ijAe2La;V<7VK$R2I~#g9{`Ima6s zB^d6i^q%z$?;UN&sKIGtbG@Q`E3SRghw&p`S8}KIpn4TyOA1TzV&!K)CwgXXUhNMt z2bUn1cuKymi7nPgtKKhX({lRFKS1a@cO{dKq(8SFs-K;UBT;{Fo_F9;zD4@3A4w#k zy}Ox5jjMMp*kNVt&5AjjxBd%S_q5AT-t=FY#74X+_fBF*t1Y&b;(1h&hL2mVJNh{? zBoUkiB&PY?<=4J?oq0TGhU!(IvdoNOr`%kx&D;8a;$x5NWorlQ9WiVx*m=?CH(P`E}n>Zj4F&!Wya`+Z#I5>{v%NR-yH z+;jr%_PxgnKRc+|*)LiIk_u4kkE<5v*$n6OY0PbS6E}z1CrL8ak+~G-g!?`=zaCGn zp|tg;G+S9ksczUXw3(;>F~Pi<7=9eSgl@!BzIVc-+(Fdn4umW_yU1WjYaF+wm2UCz zZdX;$V0>e-npiXsa;=L9o>}kqOs?pU7$?fj_nv)nwAPtNOGkw&^Fklmp71{5x@WA$ zB?9#+;2SsOs_c|c7II14J)i2P`>aZ*Z5Z#_bBHkEqlDE-?J`T;xv!M--@}H!P-Y8d zSqnoWl5Duh%_)#CYYOcAhH%dN(1^#t$7*y{$ z`7|hE=8)^8o7o_X`1`pKRZ??qed@a}{N|$zT{A_fk>$*1 zspw9FqtCcyT2-sppl02n7n7PA$$!dB!kmAgsvoLsSg@tyyPhniL0G#up?5wh-GyDq z$C4W+(atz)Wb1S(GSvFMPr{f!p*|B?}y zW4hp-brNu)I!6^b@f+)j)b~MCsr7T8SR1_GoS(a<*UG{(zZyNoH2`h})fy2<5q_tS=+eVNNkQGXu)cn>CDu_06ER|LzP zDQif|L&dEHDl*KgKUZ5HF1gq?Xxf!Tz?hfjud|mh#3ZvmHfpzi5#VFPv@nvEeR_!& z8JdciO2g7GwlqmBUq+iEC4o*-_aUQ9EBN_{#$DE$iK?@OkN0r-y8XdR10m1sgiVE3 z_xM6uHCh%ZNu)T`ER2Sz7X_SfJV+>=r9fkUfM&;B3T#K1%qpE$k)BAG=uBQf9@{=C zl!Y8h!fL@E#Ujc=q~%eUTGiih=FGI@3eYRmB&n0Zkcr}w zwn%>^-ID)jm3#!Nop$ff&74K<>LY>1fxHm}l~WE38dbt{JR7MJL#JqN(q4SY>|uOm z0epTUes?vh^u3<6gatCwMU`WI}Df@Z;OJ=ttQ|Ev>s!ld7Yp z%gjfH=`BlviM;Dq!xz88e-r#4&fYpI%KqybHwFn&kPuLE=xz|{W@za~U<7GtMi`Kg z&Y@e7knV;7lo~>m7+^q9Qlz9C-fQmf{XFmUtl#_B?=RQVweGcUxX$_Pv(G+zE3kOR zBSn;MjyrwwTJ6-qAH3aBC2t&t_ ziZRc6svqYx6l0TRtQtdo2a;IJYY?{yoa;{4|4MwLX`d;-Anr?*5 zf9t3O-W8xXOk9m_tWi1mpZAFlQM-&}*c?WlRqJ(f*XABkofAWUl#iWQ5BgL(bs^QG zhWnY!hQJTZm&-SO6bbfWbK*NWBDt4=&U`l+yRlEd-h%id`LBHxH-Op0w}RRyFhqW_8=|+2-eYw(X+NT-Q>u)PH;~ZliEuGA@;*P@GL&xyYB1 zu5X_vlHEK0G*}4x7Dx*K!(uQepG2hq%vj9uTUEu9^NnNI%UvsOHDSfi8$$Ig>VIDD zxaJ`^e?RvT+pI12n;Uo%h`hlJRlii%6znPL`0V?1kK6J~OD?>8>D5FG5i9dF-rw#I zOp9^C7GWc5@N=sQ{tr2uiS*(IU0;_%e$1=|NkxXk8keMY>)ae3uB?;(^tmSPno2m~ zkHbC$MvHtW^z7jIzNohvwrORp#068}Tw_kL~ zRVil-GZ@O;c3I?kPb+> z1%#JOM&2*jDbCNFipmeJr936tRp74G=XZKEI^_2j_0n}+I2W(n2c6|F4`A5}aY?nn zMr{v2pM{kvN(1$NXewk*MQq7t2^y)l0V5MpDnu=tF5HGQtux|7e5F^Akq<;OsH+tw zbq+1mooGcsz$2408NF)x$4;#HOgxUzK_jbcdEpi4aO6K3+DBk|z&y?E*ju3s!Z zlO4T3!8{TgL2X2uuk!80TK3;R!m62?KF%jbE_a7SjO#bRt5rCdaolkeoCO z#w>^`)~r&pke;YPEBD314u2TgAc>kb(xqTVFn*{9*Vc&sD=Te3#^t*iytD3o0c-GG z{`C+BoU@h6^EhTJj@{%-v)16V6NRr$ZrrZmM~$nxgGAdTjg$fpQ~kEw54?xwNuK%A z!EN9^ofjLXAW~SsKEBR%h}S#n3o{`W$qDewoQwU+o~@Hn4PWwotNlw2vEI0`b!ssY zWaKMNJgI2^B4|X(8t074LRilc(v6s}1X$ z5gl)8gw=FBou3$D3TuMxj$=HQhhZikdhA6e;$u<&gzAxb~@4$p9nvIr_}-Au9JQ zU08q5q~)G+$dgAu-=S#KsU>V4?R>m{Cn%OYX!SYfS1RrUv5`lM#fewhjBHtD`UIMs zWXYx*5o;Y|kR0bL{l~n-W+dv_Q*FngrKh^?{<}?cE@~XcTJ5|`arAeW6Oe%9FOAyb z9zVzc$EYO38*jY$*w>qKB~^SHM>c`IJxWDoe~?qN>Q!*XPdKd;@r+FOmH>*gRqnC_ zudXbRfJa>r#S(0QVoITp;hqMy=;Am{JLnW|%a543h_`*^&7-@`uk{A94rDF9f7TZD zIhis!vc)DYt!n*iAYD1#dCcu?N<<9(FJ&1-=V>4B!iTc!Z=39%sU#X?nwwy~_JHYm zN!zZkatZ&oji*!=yH>Y@}hL&+3tn4(yo$|a->4p*lqo0BmbysXwsRGT)KnY@W9qM`F~ftigyQBwDKQmT5H6ewtH`h5)Px8@=AQK%fkKXz?;@P~YO%tgOcqn2V6J&Q;@{1P z-x-*Aru&=zmyByE_ZUMrpy=K+OtXZAlj7|&g#x(-xj3`9l!HV^c8h4Hx#IN8)aH&? zkq%tohT!2MDqa9XH`XO>ODI9$!{GPa9A>N`7z!#XJ3Vvk}0SUBx- z(?5X&6k;%#7@y=mhX4LT1ztaoFRtPNFtEJ*!AMUpyZ4+~>{FSrUai-UkOn1MK2|8c z!W+4ws7A+?M+F%`4Kvo5DYxT}kluZ!#hm4pv4q3^LD@NF+|h-MM(>+O*ocCCTfCcI z;MJyOHIaV)DIkp8^e|cGH~0ID7%V^k^rs)rH6Zg%iA26kX6sTQ;(NHvs)T;)E+7DI z!@sj|XR#HZu=F)5a}cHBeBwNs;y5iJdkk2heewnlCQvrsI1Cd(%!zL-K(kUzn)p<( zAUqq)j73%HyE1EEfvC|}eFwD>8Sqy)tJ(|2Jo8v-YY^ zg*t-A5>o-173gW@&Jb0OJjd6kP?}P#?OZK$ugtNCNCnUn_P?5pcetl3#u^`T=40q) z00I@N`*ENPL1EuMBshRMh59^(jx7NDK4B_wvoT)Xpdm64LVm2s`}RA@9ms^rucWa^ zYJzU;&0muI*-md`0?YMT-c4%(n`v3Y>hw{2b{rH7zTSV*#SjN?;ZT@q(*Su0Noo;> zYfSyc>*LBbKSS&^2#QshAgIwyrAHGy%VYlCcWJc;%(APi?HU=b&*~CB?IFrnL>g~1 zu+n_FDSK@IF=>dKxH+E=ME^RTa<(;NROJ{SE`D_RIF`N~i@jaE00F(`cAZ4OCY&#k zY67yKLR{9jFmpWTYDrqvrvAcw_b#dQV|it#%&APgI&(3-!N2`g1vBcF4$4(S89hJkzen$i+`ky=iAY&#SE z{5z6s{@>E*qhlVV9X=>RhePk7f?2<4Mv0FU*pD{tVZ& z?1=ftIGYIia+y?Xcdp}0h=7i)FGo+pWPpDv959F1U$yrzW)1sJW-8Mg#;+!vuCPkCuI1TF zO57TFVi$9B)h~*CVHoOMb}vJEvp)Bz0+Jx}j!Qq!jL5fF5FlKGyWMHFa~ZV=U+Zu= zzcq+_6WMYWp)6rd@=|Sp;8PL(lkhV7rv?6Wq)-jj^1%<;n0k}xT;d_X+JR2|0`9Tr$g_@4Fp8Vs)nf> z7z{dnk^3xfVdZB5GM2s1v}e!qH#tcpR(vY6go>Q}w!yM$f;=LoYn6oy4Lzl6p ztd+Tkg{&HyPdz$38@X@bsR8NJl;7eQP>{wtfJbz;aJ7+{SYvSep7k4{1&tE z1bu@&F5UDh_Bt0D?&3dIN*2AW2C4UXzWh+$78If4G7fbbik zr;b&>52!cN1p;gr9T#0L%>cQzSHW2t^04Tw>rYt67d_qM#lV}=1O3^1SATnm0%{B@ z1+->{pNKCALM}-rv8K8_FVraasn2S$`s?x%$!+^2=^iSo_UaS|nzb$=(Gz3Sk_#gn z2KB;P>#F>fTgnHqKA}-5N0UN0+$i6EDi0^a;QHk@e^%zl#~cffmSttx4hna}S0vzt zl~_NGt18dYX1H~oIcf-Fh_E<6&RdQ#MTJZ_Su6%KY@0OLSoPvEu;*Ix&AQ{&!MO0w zx_wH91Am)-woABtxJ1^P_xk&r=;Qz3BfOYsV2ILhHK^fjw2*U3w?zvs5ml5Ll}hSb z;JIh&7`DYrW^^j-2xh&fFE_`eshjq$7H3?=er`rPqLU&Xo7cwLPuEx1U#lsORnF=> zioWb%0L`vT?!u-34UkTr3z22nc2lEW9{jlU^mh8u8}P%D<;stxpX-`VXVMwHA_9?2 ztr2$_Y&GjeyUs?{Ce0-Svj~1CtdA_-_Iv8~;U5%~m(rp)O)E}Ep|R_03~e3ryGMs( zR^goF^=QBSyl`Idh#7}tk~1u|A|}u4NAre{6c@oHDsz(hstMiiKb<>qnZXJ5VRsq} zcAgU}hwXM~z}G{NAmg&h!E6-U>M^^&Ct&A;mMVtA2Zs)};_atRToyDlOveYN?Jct} zTQTV5&3ZN?0RLW`nnfZXn1Ws+ffX3rT7qfhQ=K--RiVYtfFX@(PQdv_(y%sS6dvO2 z`~pPNkHQXw80if49?t-QwK?p`tm_;0_gxbn2Wd|)Ci{&|`2+i;5kq3q1bOx@tC)N( ztM$5;%MSEI&Ld8h?jo}Td04Jy$qx7;h&RZ*w^^vOF82KXR+Xi@0=QLZ{ zecy)eV&-|mvvRL({NWF^y)*Ve7_WCS{=1@&t)BfJdLBkT#uT!Te;El#COL5sPYy6y zaC&y50eBMY>Tlx(IEZS{8p~L`L=H1itvg1+9zmJy(-h+CxaEN-yBL{)7*0aGnXWHd zG(^yI1`U|WZZqqT?aY0Z0vRu-+%ZW5wx9#lyynisfxGe|ssm$wge^M>&`>GJrF@mB zQtNaQ3E<;~35zGeiPg$3R}k1JP{c<5%<6D=`oDQ*WW zzR-;8g?A|6aKugqaAf?eL=O1Dm^QHg`=tT={(0$squin^?q_+-G8n-@n`{cHdc8j; zDhbyV*uUTc%>p;~A1$O=>RmayzAuAs>dWVvORl~GL8GR7S83=p`YZzWBH`Mr$BMI3 z1|-Ep!C?b{O*UeNRp)V^*+p_n4a4?x;rXYp|JdShbN69YwgF`QF#n&>>L9l%}XN_$&z+G%^TTM9X<=W$OBo+;0kNE zQoO^2U_9pAovuOqu%m&7O)gQ_k`eBpSJ#!U?LHPvoe(Rp7d1Tib#M>6eJ~~8U-OY@ zpVSrx?e)IfnQw;gyZ_zv8#||5w6fsq(%TxHe(JmkZdLIQN9Np|#@`qj4`*7YHq&+rVq!DnkezKxfA}T1e=k#F|WCGtZ=ZC z=rG?>1#77KknuB}c$b!P^(QF-eWmgJKOoARFxaVz9@rQ#54jPHIhgy&$>KzUQ0Jc< zifovFsV-@5W8gInxnre7Iku@0q$$R;kSAB=!wzT0|c9?D+!7Lo%6Als{P#GbQ zX|hm3i|&2YdjG>X!c7Ck`AYhbc~G@UR>~EebOggSh@#(=%>N^jOqrF7-3q#rpYQ;q z$a0ZZUZKr7u+O5ri{V@8jD`KogcMoKKu(FD$%y6smlnWxq|)`Bw6vY%=v_D|kz|+T zyHFZ@NNb(v*|o&Q>{ykaMgS0dB(*Yyz;n<^QQ9RiOhIY0wfRFtT`A9`&#fe~hVK(Lw4_`@0#E`Jj5sn*UvG9~0Cwq||Jp z;@PXexjtAn6(~Pjn-ly29AGD@QLZ1`sRZmeYNX9IC^TMnYOc>L>PX746+OOu&+Bg` zN9Yj~a5|_gHD2~m2yMm>suu`QdJh3h$O(N6Tm2!=q5Nc2Kl&wL3{7-DkW7*i!0qui;G7a-+I#xNy!cc62}?!+4(yIsUZYn=!kWn%4}Noh zu8$1Z+gJvLY$=ubOnLG5(7(R~CUNsHBM;urME1vZv+GjQoktEfcQMP#GM7@ZMZ0!T zWqof$tYeqGc6Jd%(l>DW*fX~D(62Ro%gi0oE?+H4tmy~59;nyzkGGsU=e$AFe?RwYvm$?{gmLap?m}& zq*uuZZ6g60NB%){c!0ybp5Dm@k;#gnh+#G1`$={xO$g8||A1QF2@lOgIK4QU@>>`% z*ufE};byKepez0hFX702o7fFl5Bj!-)H{&V72gtf_kL1iXe*VO4Wp$+j3KlBi+^ORhp4lSM_}_RWmv2vTX76mdz`sUQI%pmuil(#%VD%7d7p{ z&nSZ_3yjjd64!~xh`-GwSXUn(qK{Fw41?Eb*DJIFLlRvjm-hIPlXI8pusLuk=*1A# zajKKI$(=@jfzk@7Yc$f%yI3Fay>}5Yzrx9;GNt!{ENn@6kfUb1oCMQsE`MAHw}!34 z!-=8ToaN`r1J?yy-6GpCG>L3e^=F4^@hUcf>{Q1~%S-cmlU6$i&SXOix*o}s?>WHX zz|nPw&~7My&`+rbzMT&Ix&w|}ak5P*Kg~VU&>6t;$t`4fj*hc|1KCqDa8siFqr<7f zFP@(cfDk}vx#E;<&nA$v>9w6^0Wx)2_)6Kz{KgpDp}4v}HF;4j(gzv|h|$5m4;x4H zT_$ZjeWus(zS_tNe=SF=kN7exFrMz&s$T@vO4%Gic|=N02XTa3c2o?TMJ-^DsF8aD zm^+qV9aU(IN?MAySkjii{^B!;$uEyzI*FwKz?e%1oKA}t=qKe7STM#R!tK)8jdzIO z&-3Qsqy0bJW(5^URY%$3*+4#1X0bx4@WGqSmi**VCaD*9Hw01)ncK7#@UhDYH)5lz zkLKn5^n+zBPUfS}f^>COp0PDpHacpt{n9V+5r`aw)x0tBW4>8S@n*hJt56qFB9jbJ#kQZPc{{t$@CW*+@nG`ai_B!l0XB{OR=q&CsLrk+WvRmgplqH)g`*OoyH`G zHngX+zl|qhA6%EL=ERra2@;RMa%Gz;Z;`9H=l^(UP00UO`PR6!DMDsm~IdPBEb z!Sb`${?6;7ySAlzd_esz%D)zri$1Cz`dwtqxdkLhBuR@~fbnsp@l%Ul#J+gP$gZbi z)B)Ufiae`QFLS%K#0_>#YFz;CWJP96p51%F!CX}6k>HUyF@9B={Jcs-LkY~_&aT7c zx57wg%u1HJ`BCS4zv#3SO6rcR3#|yJEWpG;7l9M#=0^6l*V`Isp`8SKavw;j){O6Q z6O5)5e}m@{sH9Yh(0GEd=K!z{sYpT~&ZLa9gfsSnh_mpP^rCfj{GVR~>RVHRhgrw8 zXN~NR;2{=yG$*7v03e4bgY~JTJ*v*|AWht*vE%ktWf+6s?7Nn`MAWJUuNMp=ZAb*)XC<7H7J1BNy-I^ZdE|pFpg{ zas-FZ+lPIYFoQQ@uujg6Y$7p3n2YYMP12<8q>A||!+;Xd==w+BTL+_cmMJwB7^B5t zscp{~*XYkg2Lije<3p4p<-ty+cWm-xtlHxv=~f-;*Q^fQjQ&xl26gv`%UDWJQM%Rm zU$Gh3Rem4%RJAtrsh${0UR*n7Ex#jK36J2wqZIr8aqOVbCRHtARDU{bzInr_PpE=H z?P7_d%ZTDafsbqI&4JA?$2_z_hyCk|u&q}EOoLJ3U^^|p<0iW~O8mMaBIxU`lI3vX z-&s2^b}}&j_f}h9F|grG^`5%xh8po#=l9Nd#>Pg{Z)Tjeox1kA6tAi={NOyc>-wrJ zLX>sVIgm*Nh&j$CS8k1bIrTborsx4gNPtr*@yT@ z5_l3McT_*MAJ4ia&9ztohlNTT;XtRmm+Af(Tk>Ar*sVr$eI$Lf1ZNOK#x40O!nv^b zQR}d}L+~T0K2=e%B6$RUTi_CD-tR56&TSYo8T6o#&gR895y_=ck`scI&_GAldt`5X zR(AHbITnt*v;E)IZ?yGK=`Z>y>}LVTdM8k4heUWa)d0>N#|J?IZYn)|91g8u%QJOm zs#ULI0U&0$w zT5s5^%kPN4{|cS7Ju7iv&QgW&qs7S>)b`zA=J>rN1W61#g+n_VuB+GGi;o7$s58<= zRTI1dLHtaM_RCf3Dh?*m2c!(ys$>dl_1?Q+Zm>3^j^N3bxC zzk+UT`idWn9&N>V&w0>KfmcNCXb0AnQB zoQ?3{1Fq!j5IODED2zKGU``cHohEW2&dLbn!pfJeWRT;nQSZ2fTRdet0(+O zwE>=bn?y5JxW;gBTh)De$auqF4 z@hb+bqLx!S-=r~gt+{Qw=W(N*#xf~t^lIYh29Ekt=uW$FdG_oMxg*-~Y>@Z!E>H6P zG(Eyv?%m|UUFI%b^S-1Vw*zQiK2z{$28LZhe;|@Q27;Y75FLpC`g1}V(cDR0TD{DV zemOikN5$9-O|1C}*V+#|FH28TEh&mR)}B`lcGC5KiSe!5QN0#l=H+GC=(wa|!=GOw zSt3Q=cfULCW9aV*q&`=;ZnkGv59~jS?D)`OWaO}J2>0ZaxwyUMigBJ+T+z6zOj1M!c?00%O65R2;Bz`r>3UVra{yjbw zgdhHVc|!6)3f{+Q@dBGrrk2U59n05)8NBoA0_Va*F*yZ1xJE9-K41pSUpe1YjWh_< zH9)gE?~B>-TQ^t$%BG1DM3+wV$y1obW5C1o zCyI^AgU~a!i@|2L7T{OH%}yLGFHAZ$|8l<~*k&r2OxWxNHcKXoAJnOzA5H3V>R*;n z1#49$7e}N((enVc!^y4yHq!Lwoa158vbGQyxKL`y=p`HLO`u5BQ{%+1L;JN7*v&N_ zG-{H2h|vA2zXjoyfGICSoU~9dT2m0y)E|l!pp1L$}|y5 zxvA+ZlIc^#Cv3$mtDz$ArvS>8VVj54BT*1*WAs%``)vYQW(60YqB&XZ^9&zke4Tq$ z%}=u^ZT9?%`WJn-*Y4nVm(s;RKxmQSXxqJVHu?ym1k-8Eb3>ve>Iij={<}|`t^MFZ zZ|v@&ucE_-@UhB3Q6-t|<2{L+CQV&DssmHL`*G0$Ujecrlu-2>A;a>;;!VJ=vc5uy z78ljhsno^R#Kq+^zJJ+@D|&#f5LTid$(0~qq%0tY^zpMEjL0SECy>a78iycIeRv>@k@cwp+ z?mXAcJD)_k9sg*3D=a+Q;hS^E#ee^j)cG-J))q=8HNiVrH+T(8lnIcAr&EyZY<1km zCG0$zIgq6bt{9jDJVsa*5$9{fgzsMIKQsq0yHP81bgy_Y{of4V_oWZ? zO~Oy((vZsQ@wMK+qm`+f-57~Mv$5?r%Nzfwi?Hgfe{>B0^N)1#JHuWLj^8LFZ!_=d zC1`vLEUJvASDQ7sl~<CtUqR#fO_qE~BW;8CD%FV@AE?xS zbXL1ywm7kS4K^xwG!02^zHRnN{H;&?rU=0I|5>XRK0uIY`N*jH_gjnK0galCEKsF? zK7wAbv;r&zY|7E%Ad@)(_%NHaNRkSKj`1qu+cc`?>G7GE-PVYVSf<$K8DO=;#IJc; zR}d&G^aOkD3h=AfYXmqb&45k$RCV0->7tfIP8;#!dAcpYEi;AS^q>Jy<~H*3V#X(V z-oGW=f&iG?7M82isvATHS{er~&d-}Zs^cAvrV=8@Q&|nS0p&}Iu!p_PD7k!Yqxy*C zpHCk-a01#YnCephppyLnpPut`fq1|9%o7U5*PshyZdOl@h5Q-A zEPFfETvyJW?~P5V?_AATLqg8%#h7NXZLvmEF@=pb4SIL16JTIMi2|NReIKzfu|DCw z8s`=E-c4T&HXc|5=ZONtf+5lReKkdva|zCyhtgVgfDvnnZe_=q*K+#5-%R6wf#&(N z_YL$5g})(b>@j6OHR}Mvuocs}DP;b!oaSs7wnqUhvAQ|QXHv`Q%imcbiS%TY`HNCS z#sUETg?o0w67Yi3CAV+KJcIIz-$V6T3|lbH0`^Rn?C6PC{vh8)mNsxf6}&V*-v<`1 zuHKKAzD-9>ckacyW_z|TIbJ%WY%F4z?qwCKUNWRt*um#Chf*QN3CwVVNo>vj@ z(|xub_DJ#m&DZys4WrW-AA_%!50? z_I(O4^wpKdXaf{&P0;SI1o?-?(DVZ5e?L1$hHtASs?9Wv508Nq-zJi$scH1hrlG_0^eeq&RgCocKO(fg+R4VKyuA=;< zrcQ(-XT-z_vRvaa*M0dH&3-_RuT^V==fox)T4a&{B zI_(s2PCF1!z9Qsj?*=RWX~y9qwA}_|KfLwABD9D2!A{~PtD>K;VSwq^pFd5lmr~mc zHeiIwHwdNil2)Avw+VC`Uu;&cva6lq)$8=Zz4(F))~LSCiAflRih=N zmfF43QaCV6w*eE%`Fka+XUhJuOAn%E56t=Yw64eI-4|8&o7d7cvMvS&Ykz+R2M~ei zf!C7~_y1k2|LKVyidZH+mWq+T+e?j{K2$pHhlo6MnKEFyeL_!#_Q#t=B)>$29`SB2k#KBIDu$m7XHB8?MQ|qXK zXI5cvghU&2=U$l;pc|P@vK3C$nTSU`%{v>hL*wI?{;?&MMeo6G^>pDtJ;vX}h0vpb zm~6l#aM(E!uZ~2D_P8coBiB@$rIc0psC4BF@O{Xyipylx5qtTa4nmEEtVK3~?K9$q;Q{Tmit#oexLy4v128igi;VIh0 z1y${dLb=47IQJ3=ysPGIr39-r1g91LmMjg%0S@{EC{8Zo86#}{R)hn=ZWE>Pi^A2< zV8EvhPgZsh<~oW3{Agi+4uFd~{T@lJIQw?ljGw+h`Wu?5p`mJo^eR>GULphC)o*1j zo)Sb4sn{v)`f^YK%+Dv1t_^yn^}&Km#Hd~IPuuT; zw}Eqp@9BR{q|u94w-&f|0o>Zi_5lz}BpKSNP$y72+@6I8Ebw({Fa8*IwIM(f<;F=2 z=`18CrVIP2%&4x7HtbR!T4_B`pDs%7{HMN2WP!O)xU_tKT06oQh`h0^E+Lj|cXA5e za&G=%Abs&bbiU^HEZk(yAew#?UT`lr<_}&`oV@`H+{a34`()p=CfkwwPb(m=?yTO0 zjrsiqG0<~0r22FtDCR#DBP2GyB zFdlk9Ke!f3zQ^k8MZU1@uwK!%PS67>rF#r~ytkjAq1v^3R zD04MXm;v?s3x4T<@%<)?JB8zz^df>h#5PKOwJ)7|IDY1p^>OlpBplf$np*cUIk+LU zC$kf#b0C)pSYZ#tPu%ZIR)DI^PmKN>@In%{)s7AEq*hnihVlpwORm##L{Glz|1tm4 zj2y;Jazh?W7tvj((HJ{J4B)G7*|{cMU3$|2Sc;<^RtSuS!xJaI7+OSu*ev!oyRJ8n z#0Z}6dz?0R3BFIQoX&KrppNE|SUQoR$E)N2S7`hHLce&RwJ7Y;|B0ZI^}9{5jr({2 z(7$pe1j)%DuOj5JJPI0)noa0k-2_e6j*{^iE(%^CM`Y05)`7 z3*p8tnd7?@S?JF;{9jstl&F?6e*skq5}zxLKzm&MFVJX(geew+=46*7$g^U$)TH=C zD;y_1jleA%I@1$p&7I?lh>h0KEK1hI(@9;eocTMYU;HwYd}AaFon*D)jGrJ3X*!SP z|2*!M#e8+H_&I8{{Aw_JvV^Yx$$vUQQm^#NKNEA|Ap=>g@V)bxE{5e+pb@maQ^-)* z|69cfKCR-smtdM%PVS*HL=|^~{Y|yu$r#bs)Y5+wbz>X&IMz|81DXX4s*lvrxEfcf zq|l2`@(-B@O-wU&&y7ln&w$X~b#eq#l6DNSD3M_Gs)uo_w01HpGvnBDKvgXp$k-vX z`t4LX%Vt;pSTh1-ys77?E27s^v)!7|Xt|F_(?iSF8(9W#bwEbp7!#JYHPC_mx*D{e zRfDC}$eq95yXGV-d>hc@kSY!tSCfD()xc7rnt@m0Wv51duasA2>>2m( z=xLMZF2Fssg*wFg^*+@h%=?=3Dq{(;{?9Ie7`ekd7T#azga|)#nwqMgn175%=vW zK2yH8^xKnC5*A^fIo`8TZ@1MNz`4E|QrgOa^-8({o5h5haZ^VFZ9;-*^V--Nd@!*4Y=vxv2|PP(i`2x<*Miy zx7}Jm-5B5^MegCgzrN3Se$O-GjuY~Jf9%al!QqSRt+pMB0L%Z;l=Kt6bO=@65UavP zlW2gP5>j&XVYBfY&gwZNnt4JzduYii+#c;6 z6>@sdPc+8sAhF9d%lM$_tp2eTZO(u=*|d=#mQvq7GH!VGA7bM_9sYlh-(TG&O^N9&fb_y^_ z2K%2mE%u_ApJ|_;_E}!`wbAJxYJ%8gxwpB!`>%4QfZU69N?rPuD8JLy{C`F4p>f6uEHNVJB0MM35c&swcsZ=Z>raA|dMHOtjlX zn}HglfV_LmR{An-ofD;Bu9%RM`d7S=j(DH=00FVq8R>s(C|9{sEC3tg-^gl7#j8_s zQ0X@}sCs|>m+0nA!Aqv^oLVc3K;&I&f_-~c&J7PFu$AMmNQXrFmb+b@j^gVl_ki95 zyI@yQQEduLkua=E8m~p`#W|`v&_&am2Iw-azPR-R*z#?*#?gIX0um2310qsb1~FNm zS*?E42uf?HfwfNK&bTQBa;JxCu~%K+#Wo6)SmH~ob-veE+3}*r;OhldoBg~0B3(zK zAgKTjEnx%dn0WETuct`=B+O*z=}98^wAUSwK5t&ur56QWAVo476R(V-GLlzffXI#l zo+nw=Fu-mIJzz~`4YDSWd^fEGR{T3SU774ij_WJ{ zEToj(+u6uKCEPRJx#JZ}95LOaEo-wZ-d9v{)K`!>C}tgC@5By5r-jZ7F9Ut3!pH0d z=40G*hjG2#s3X^`$UTO{Vz8<|-C9I;!;ho+)m>&;^lr_gi4i#G84Ro7D5BR8@XI#i z{=V3mwxAXEn>lsyaatE(#Lv-JnDFP3bkbgaq;jfA;ch?Wfjob%Qi2z^0utbI+L0B{ zDqx|mj+v_-LUakR(F^HG;P?}0LJR>eZs&RuKa32L=?$Or*4Ehpx_?Wfyg75QA4IpjwhMPuJGMHMxg(9oln}tOExvilTu8Eq9;fql}TJ*%XEIZ3|h$AQAj2XO`RM!j?Ve zvgc3@{UO67KyrTv-T$*;FZ@=;_TUrsmq@+XBcH<8vKXn}k^Eh%r7R}gs4i!gh^kCa zf@i7`eD~Cn2sh2GZE#)JBrU>zqMPaZ0Wl>o!o0<(bRkaRUB8c2d*(Vsd`&&I0xHsS2K&F zwqMOLUzvC?50g{>16papR01i%%m+2bC%E!Eop=B|=};L!6*Dgs+ZZI#XEitL;Zp^} zpBuQ*gMLAe83B&c^p&f~D3H`-FrK<{%EOtoG|XfYd4wKO7hn<|oDx9Zz8KIOELBG* zQSSnB9;CIBvmaW@akFW?@YH7E-5z$_2triCn+r7k@mjIIBzce}aceo3C|7og6ct>O zpw9IOya}g9ygGjnQXG#1Ma+>1yO;r}KdBR+7`IQiFdgdPlEyPiKrzt7)uG2xt>w50 zxFfZOPFgvwN#*h93RY45=i8`B$2&aIjU~tBB-bKOT3J^7trAM(SXy3;$3yv!eb?P%3M#>#L}DxSu+`Y z5|M)J#CsRvx5PX08&!TQg*196*{?8%TOlF9I1b^>I9@U{T7%OR8e< zmcxlR_S4;051r*-Vp6e=LKjdPkgtC!Xan>>s2>G&Ae7xn7^#)e4gM|>VV zZ)akAh=n))6veB%0D0HZ$^|uL>uv=4`rp)DBkC1<#?Ul_g`IQ2b&Mk zIOM`XZ51cV6KlCFLPbqZBDlB?a$aoixFr`?4YSNuwORs>$9(azb{SoC z+!Wevmq<-cDlmF?)Zeh1WsQ$KQMVYdlRC&azgh2lK5V!5pw`xAZCVTdNB8JP8psYv z8)zyno~ z(yMM}bwpD};{8G*p3ckPG9V5Lks^B865fm7YcplStW@It)?iAEJ*IdiSm2SoHWyKU zsv ztQw8{m5R+2Wug$n;KwH%rjb8KC4jrtk+8!r9Ro5Bc8ez>Ye7@YgH`Xb>V$kd{u5P1 zQZHko`sZAjIk6aA+~1U3hi`z}P%L23j|#Bshz{*e=*^$psl}^HwoLedsALYVXw;>^ z|Ly^4L+N|D%f+o=vSpa;r{8+fifmrL9PBjAqUS_?#Rylns_7Rr+2yl1lS3=3 zc{>lsQJq*cwSnZ6~ft!6$Q%z~aZ5elvoOa95eG2FOJDtyO=K{P` zq`6Lv{2+bB=_`v04aq`0_?cQEUgUVc+naVKEb!L}m>7mx>eEuWvVft-c)C{ERwMGG zKfXT!imU~(HTR07nOVC&MK7T!CYgZ0RkUah8^2iInzT4@3Frb9{uM;`M+VS-0hrL# z-ZSJuq+J3ihh*fDOEG!;)8&li%zr^nbO=@fWaP$&@xB}Muv z0e7YU(9k>!qfp+$LAwU(CU@n{PPvInXQkjGs11F*@*0M}9|VIityWLsl-?5;e(#aW z>9wXZ#(Do&sk%ydvR(oBQfh9DJC$BC4bN}7M%ceqQz4WRi4wby-MzmQGhH||-C^E0 z5lwh&)MMs1=>c)9pI9nO{3orB1S7VX-X@bSSvkW%-arBRT)m61oSS#d6E_Z1W$wB? zBUS6Q?33f7Bj82fp{!V!gDq1h@;hPKn6xfW8NeZj@osUz&Y zdfp=MvmM4auhnzA%RI~k2HV$IPQevs=FG1P9O5C$ecvX;B5uyLOb{jCf|&LDi{W11 zNIFK60V`k9{*uU{ZWAK1jm&Bgm&8`zp{&thR)|rgxy=<@<(|Pi)xa+}gqj%1}KS?+AqL$^W71)z^ zbAip|U?dq*+Hq;Rll#o!&34oET2=$W&oQlCu04N@?rub+hs=y4D8xMqX@-wW3@?`+ z=%#c`baBM|2u`^t={pZ_2VSbF^&Xla6*0+vQ}7GwBcl^qV4nt7QQp)Z^;n%{!VYCZ zW&C~V^o*m5WVq)tnOmyb%~p5f;E0QPli^#{r;Q%)dw_B>&d=5Jsa(;{pWVwE50)Z5 z^-$~N5yJJ!jjN9Qyk}{~2C{KY8#=u;w_z%g)>W(Lvu8P_Qf%DL=4gNS;;GTXr zW!^8*17-en1V2%<)pNt2xQA}4e>o4{&p7Q2BDJ3pdSFDc(@yJYnDOW6A6p5k|34r7 zZ&(E_XORJdFoM+h9CjwsKMH#Pycy?MgVE1^1W>Wq`L^qD^%e4;)o%1L7t6houY=m% z53VyaA2d|^z|da}eOU}YFXowgmgGw$%f#IHV5*X(uW=7c$EHdt?)cgGP@6g0tmo*AnW_KHGMgo4?1k0hs1$*0&QK@95`c)cw78Xv0)+tp2af#>2{u!)TQtEZ)8`1gqd#W=4fdxSN1K+uf2 zmn|2xn50WtrQzwWdi3hy*m=)Yl;XB+sqD@uVTss}L^Hw>c3>E|3B>OUab#3nYR7*F zqcC&eknwXLy5=QK06CDU#6U^U0X2`#bPV{!#pB4QJ&H*W;H&ty~#OLj1@xZ;R<| zObSX1C8icGa4 zr|MM0sTWDh9|AXX5W1O0D+2Lr=AG94(`{nzgzm&`rri$=`BIx%fk!OX5ZP8)n+$wi zie<>C&#P#%yX%3WUd-N5ahu|S4x!+o$GX~6#@Z=C_ub2nYicHu<%ka*Zq_y@VKq0a z*x%4@)YY|eZGlsNd}iL z5#QUsBQMy>fXKCbpxc6*hBKneC_~qQ?&{bUeVl{Q(0Prh_E~qkKlK;vB!Qd!+iR^! z6ysUXp5r~db&afDa{7&2@5A-7t@Wbn=c(hk82fb9RCrr8+Al*K{(u2mu9$R8Se!Uc zw*~E^!L(&pjqCu}A-KrCRQ-Lt3Ro!pe8RgA{|zgsxQ0=EY6p1AwvDUta_WaLEY?_q zX$9jnI`+<5m{kx}@s8IapO+dVLtRq;QS@=N%JWx#z4)ACEYZbZyMQKxm5#Ox_u;^zE#cFnBbV;YgK8QvEWipBiBb5T=L-n zf-D>1zodDN`x7QC?)jFx{|P}heajQsy7{qLI#;=-go@$Fwdj$<8eX}wlil2tdt$EB z=9O&zg>Dr=R^*rNR%u6OCHyy$F^DtO5OmRPPR7s#zX-)Zf3gKCIUTb(!J8p(L z?GY*KyB%E|Bb%daLM2ieq1! zGsUKzO7oF)OQfg(o3>Nw;=`Rg|1s}M#`{%metYF#5g#oJXxD5cu;&W=>uYNKz`HZX zjstRZFqb9Zw(G9iCCT~l$%l0Hablb?JKg)3Q+E4d#T@s5+Lyk8;b1gtZHqwn)Ydhi z^;jBU5NZw`im+?ff<{xU>!u{{YGhUBSju`U`v0PmJq2#)C0_AVAxEFvo&JY~|34Yz z%O)*n2xUI57%}sv5w6?h$~ER+D(@}0`w4&@l7V85s%$#crW~tk2m+f#-3*nehg||O za{$O415etra*6<27h~LD6%+gB_z3U@9(}b$DwU$w8h#$Kc?_K=u&$%z^P)vU)vD@A z_ajF<6ZSAly1cD&cw4Oq!S`3QSor)T_J(Rwo^j_3z#vumm`8TUtkHI#Z2q_ZCNvq- z>xLIH^O4XnD%{^!|4P$O+_zXx8LhH91?deVFl*GE4Ljy3&)|E}<&m7&iK5YZaU}a;miLSlP$t=it>nm`-v>y2QJjtf= zi=2|?FG4u1OWkC8@ymS0;Kf}9FUP_HCE8w^5E}FRlN(XonikfU*(QY=bQo`Ag4qsO z2V<_LGOnfwFpNF*rLGU!y{c9f0HQkc0(*vB!SEmNQxr1)I?QZ?T$>prohEW6F`H-4 zPjfEtU{DLUdE&Wu!jQmQPg{(TOQhJ+{bs&hT5A$75s55W>#Y$Mdw&HEWScjae!HZR z{(c8+Z8xsvvrqbY7{!8e^T|NM_HSrDN@Y9r{4 zG^jU99%ED*>8hXdHJpJ1w-Q8+>+8HJ6TvJfIfewgJgEgkGp*C1m?4{`l6aG>^gYj3k%^KpKK8TK=;vix)0&`)yxW^#f}FZ3s(g06Y86^M;>Va$ zn6(8ah6NXIfq7%%<%_h5QwbY|+l}+;bmNAoRm1s3_E%J()Yy`J!n91Bq=7%*LKRzC z^5~VjgK;e?vrT}*A;a)2&M@f+0R4MHD#y8m?#p3(PV<(eV&i>fuE35%vFy|0Mp6o4 zEHfD`2B~r%YDF29qdH5)=PSA+|6(YawA?N!7S_r^Xg3rWxKkFj)&m^JxT@NaWt?;` zc6!zO@!!tPG-!Mt(1Yy?t|gixb-C90eP|tnj69g!+LL97&jiS36`^((P^Bo@DC@oY z6A8-m=2~pHW*O^MC!=sBYQB!>BV=6t*pD>Y)$70*E99e94Rk91HN^fB|BOg4+#=m~ z`_~%#@C5+i4_`bjdjKA7Mc|EWF}mLn?_Qz)=4U>}0m_`Qidj~o()Dh5do~$6FNtxz(u$Ptt?KOsK3OI1FV0;{NR@)Qa z(=bsFzuM7>;eLZ~zd87}Ztqn_Y zU7Cfnp~QVYI_6G34T6tXLr;2Dj)fr}vsrk8JD`A+_25>$wmBzMIfUAcXmfi=@VC(wk2 zb0&^bPC_4VLpPJ1pTe{Iv-7B1BB$_btlDGAjvSvIGVeRu$xGLBtE!yuCr!BIy-0Z# zNp$;jgH_2oru|`*?MGfJ{%T?24M6Z#6;-xAo@cOk%cvC9jy-U;FmcB@uQA7uP}!zp z6hMr0GjuJ#Pdh}2z*Q4JKlQ`KgQ?*MA2kCtKT8Am&w_kdRn!dki2g{&#XH4{Z4<(IZ+xl#J^s5CO|tRB=hg-fyBz;k z+|pq(HONpXbaCg^-lf){X6)CGStgJ~6RPFS-{SW|1 zD7PJIP8IaZl*?-7{)KB?yx0O;;E?!fDPqDxg?Ty4If zM`+iM=O>X-@FT|`Dq%&Hl;A!wY*xv*fi}~l^x-6|*I!1hnsjNm*zjtz>EZ5EiEXLw z**`Ff1T05K=4;hZXa8&8_hxYaMJsYOf#Dsn+F+yDq_oGSJ_7@FafDTFmjy4Z?AIq< zS=ASEC;+c$7Wc2+Zdt9397h21RnXF2joa4+RBdU-p#yW$K>}@WxRFdAR!JkZD-FuY zXfKuBr^F=m!E#vyP3iK^MpzmoSjFSo+;`;nM8?r+`r(oF#|$l-vhB?|w&ljalis1m zCF{{z=CSAgs{Ayp_AY9M3O)BIvG$y8hZ{`MpKLj%)oJ{WaQai+aI#>$YNI<CKtcZCbo{gb(Wm;KH~ab-hRJ#4gY6dw9+d};_x)wedW#7e4Uel5#x_%?lDJMrKX{M5-5hxII64lR^G0&z_q zqoF>J+m9ex@>iesJm))49yZEXX8#SM2#tb9)eOIA7-_tKrJg6!t%1N}{1)GG{~=?x zjivC%?{S(2+GuCs(mCPrYmYF@=*3Tmll_b-@T35xWD|7tNtv~zT!ABz(d({ ztKQS9&jRa9Hz!7g-IB*@zKriU2%Teey?Fsi6ZM~q7l@H3aa6q@oc0=x@2x2bv+uQ? z%qMp}%zn>`{;Vvv8%-5L9zyp=ljEP!5R}IBnCII`<0FTXy8k@HuRWmSi2NS0PYA_5 z1UZ}(BZu)YhY>+w*(p*&!lWdB}iK`3>#X|pPYGI!_pl|$O&}Eok~6BCq~^G z4JItM3L}=Z|FuZ@w-EiWfl%}_C5FtE%p8QkKYqMr^sny{yvi3HajFBCaaCKXf4cIo0k3V zO+J8rFb04c#kL$!vn%c@p(nhqCN{5Ao{E}QJAy7(!w`%)iXef>B2z zSDhau!1X{R5-CD0fGveFu*$Z$38>xfNU$1L?a6?cfT6d%uF5yDm0iR&M~fb`{q`FJ zRDy3GX6?I0XQYG>8K{j64e&Msips&XXbfsLHbqc9Xe}Wiw_0KV?wJPU{)hZ{OYn35 z*ty;o0=11OS^yuzu6thDbprsBYl0WOwbfBKYd^3V0#NfGYWB5Ld@Vokj*)>b`TP`+ zLE&ZdpynDEV?ktkQGoZWiSR-l7H3BYH+=vs)#jBZkl{3ook6EXBwl8B4%RKur5SDk zkDLlv+J%=%5Wg%xTwMru3l0iRKrcN$;Xc_xp#jQH!=i;Gi{rR*_go5xVe{_Hb#!CK zMdSGbT>QJ1*$aUb-s{@g@9MQ7?c_{Z>)%48W z<@2Zl8J(Bc5w z8z0(^^vX^U=t~6B8K}#VMV-~_8$D|(_>(~yyZcVt?crmb@cfDe}IIf55i$pk2@@d~V zw)i7yx~L1AGfD@H{5H+<4tLs8>pz4wsH@pR|6Nr5|2}s9J=rs1EZIl6uh4FhU$+Y@ z(~HlXh*p>ysah_sKK#7!NvlTXcrDOLhx^R2jPSuHF%4r)uRdiaSOTyqXsn(9Zq zLWjRa_IO?P@MJ!%UnPL8^W5wY;H1Dq5G0jsP~-POu40?$%M7&IeZ%OXPgHI|$8BsG zt1lK(s~H1MX-|o)FcT%0B=NFnT+TQ0Csx?$k{Kj~#mmHIO(4JydCTkft(c4Wbt-!r zZvnI9A%{U)Lt2QyEK+K_ktTq?Jj|b`WTsGwAaQ`|`vkm0fE@o!lj#n67Li&H3@|1z zb9f~RE;>XmJI>8>m~y0-YliUJ@Nn+C@`>0e_-xaJB?!mJsCj)^clKO&etamC@^#ED z@<-voGT1x5O+Z`4aF|ZbvSpjo&MPs@Q%*BTa=12p6lU@K7WT>cR(bhC6vF_RBsi}a zNZoah@w{B7tgpNNb=U(R*?i~waiU3h((_^c4!)7Y#FS~7aG7{q_r>ds^+#_ByYTxR z#J6cF_5;G2rt581>vp@GNBK zTAZ}V`}k?^M~y2_8oEGQsEENynbtj=NAu3t0=<0ddN(v7BC(G6D7*!QEH8(j>95WF zS+rQFXP0;>-H%pAZ-_WPB83Bm=>JT4|CX=+ewsMN79l;C`J+5Obp!}jo8oo_uh~eE)6>|BVBG2^u5iqPTIUF=|(p)}gzFE4Aew z)+YBgQmAm$V7YohxcH$M#x%FoE)ETC-boMkk8!D!D{i{SE*H>pt(3H6Fpb2y3_9Fd z*=hOHHG?Wpc1B$)m(w!Tg4R(ePSC* zmCm)?BXF^8F4ByD&m`3NeN{csm>P?crf6K51WO=l%0jhSodYf9z25?>u-pTcVk7V) zTH&!=F&31yIwl=JG%{Yb=Hyd59albl)d_TWe9=ol9)`W&CFyxVHRS-R0d$gDX6Z_}>xy>#666 zHlAMZbi~7c*}WgILe`7ASg<(3+=lu=osq-}D(DHJABlb`Q?Mc5X?M{7&5OYSDWRcXuhSP<*c*3@=ewIW_leO_*i z+08}ZWaIk%qib zFsPHy7~D?W1>C(H#*E>7g{tc(C#@PKV&388e7E=779gQTkMigZT8Ebj!H1FSp+MI1 zKhN?1={~%^qM@QRfeNbSr^a^*e;uEDEV)$uKmO!vQ)ueezew(kjY&*#tur4Yx$($y zkSq;gGp4?TD!~{yHJ(aBZUqt-{Tmm#z&r~2Rehc()Je;cdIYk4wYKo9V`H7-BvKBPrcL?h`NLC`*4Z8isHbyEIncREP0~EOuSA}^0}}72)Gt0#iN#F_EGEN zr@eOz?^CaUDM#w%*=BLMfw;k7M1ILJ1nD6&B02I4vxeO6 zWD#Y1C$OS68dKVhQ^TuxERzaRC1_r^T{8lYSM+`}IDOHa^QnWcZ0)1FQQJ-`iM;_8$0;YgBnRnj z*@3BVLDi?lwKlo{Zc(xbL1St#gOtXK-0fceua{s`x1i7F%*{qnh2YP66WpqZi&3KU zDK707`etZb%lDMLIhD#P`~@qL;!K0OeyxFej~@lf=v2M-3z+A?*t^k)2?IClxm}pd z;`Cq^Dd+rJhdePDsbFkgG`7lV%cUOKv_K=gDz-~m4H-yacLF? zc1!{kx~tDl{w~=^P`YQnY2~o8nqX+KQ#HUYf7_yA51J}|2ulceOy?1gIXKpG=)x=M zcO;GGzte(ltL&C~Oq})3&-tq}4StD-7g7H29p;@qG-_|lQ)Y{B%V2%48X+wIJF?^e zO8kzQ0q^G^A$A`AmP@C5u61Dl;lCC!f6pub<&kF60N1WId0>7MW9zne^z29uUXlnW z7oMuT>a=))_}js|Uyld55hZBfnvYD9JnxgK{pd!hme_b2^uCtAs>+co-myOR#&v%k zWchdrTU^EhsIp1@1$9-7bVLm__xYmoYf}0t4k)v3O4wxOjKcs2)Fkwpwa*DuQOX`N zVbeV2BWaJX%*k*_xg|zyCj02Di^J2-^zC~R$3aL>kIO&m5YGrNNG=-{;*#)+H_R0w zQHY;Z_jH9+lCx9Lzd^sq;2a3j&)4EFG2diZm0x+fXKlkzf){j;Ux4wiJQFZBb1>Fx zzjcPo-|%#jnpNdFY~vIx7Zd^5teUhrT%0p^5%x-Kpe|fCQr~xfgeUKCA?1Aen*^@D zxB`2*wBr6KD27%LSigTTJCFfZJD#}e16~Fud^7@mCSv8+GeU?fb9>n04)r4%AC|?J z$!FAs4=?U&*Syk3o?NEMOo+DR>deBrtN6b-Gk6)=)0DtdMr(2KQ@6U;mkzms5=1R#AclG&MWEwt)g%=4 zu9UODo^@m7!NCKGhuIBNIp;vY8&WG3#^f!s4(;a@e?xXQ@#KeAl=l6kfrTa+VSSFc zC&+IB!td=T3-i-;iV2*wm0aF~{dNjn7OT1`5VIO2RYuQVMa|rqiaF5d+H`C*K1?(b zp5tcZq|H{NQdkjtoG|}W@^jkpJzV&FpGgHO z`il3snE~Y_vz7~|Cuk8(b>;QgzloELX~NIP#_cu)CHGRbl&yK0b@I0i-hBn;=Syq% z9D1K}*C%N*3vqAupBL1mYHjm%_PXzqaM>h>r^Qii=>&dROS4$M7ex`oI|Vr)fOMcF zpIik6!)M8wNPSg)PtaG^_)5;bFRjA*=tFY*EnW88U``t$Z<%`&77My?+uAXWn8VTy z=)<~e^GC9@oB`m!L^4&@Yjb>Ui=B0o#vx63QmV;FK0iXj;tB)U+AYM4DWMe+x6yd! z59j~i&YPTephq9x%P2L_H9XNYmkfRmjN#)`<6~%3eheRcf}~q+i_uLzT~gDWIar8# zV*{Mm&y`~jBT;g?iay(s=CVDILgg4xw-@BEl~qJUfPsTa*fm(UUg18FY$$|~5hr0T zbv?`i*Z_U6YRjPP)4=h@DwyskIbc);%14{2X-`ac$ubzE)?5qbtMwFK0Ig77i%NK)=a^6|KsPMPrp39fQGG-Q#BT|LkFyf zsQ7yppB!bC4tA=KeLB=N_0=D^zvNtm9FtdpuoYp?%f(J~)jx!-CM*cMnHik5&-67a zI+_zheaemR^tBw$U$Gy0OnITN7y}%KPV^^27XEj2G#==`SGi)O zqm<0E=r?aA)l#p`qHCwjj+EIbuc>_znR_Yi@stF)kQ$hbn*S4jMD6Dxjf)+3P^;;0 zth2KK&nv)vUs1db>0#+>a$6$1bDmuS`ex2K2pOD6a=P+SWf2eiJMC-t(|`MpJM=qI z7p^^yNxS=&|1%;Hp`4qD9g#DA0U_a@_Xk=LTGMpt}yvdP~U?^dY^HPH_!b@v#+{4UYoK$__WB8n0)+S~`~_I4y#IPD=+gxRo5z z%2<(-_SduG?;-v4V<2g-dhh)o*`;ayve6Q6XnAW`K6bC?mhf+Hdb#D>)lA>o{qaTz zXr2&e;&1tkh3wMv|wUr z4r1TH1=Ml<1Js2yko8NSfo0N_8A;}J=H%`~i^j`D1@4W=bL>b4W2#Z>h1#Pbs8RLX zPg_a2$5NM$_qLw(;;aKgzqjlmgUP%#m@^bw?r=Rb%k0a;(DvbLudmR-cOmW_hZV<+ zB{cADyMg(Q52tl+zms%9a#w)IiFNT%0%F*dF;dgXM~ydbV~l4D3s!3@K0?jH&DsWd zl)oegByOg#=x@jkWQ0+7N58$GkDQA;<{F=p`>vZ&QPq+W$Pv;8DFv`nfO*<><6Agp z6;G0`X>%Mh9yz44dSbfI^7Hke>{*j4l>ohOgj>czY(8r`0JJzLkr1SA2e`qGXtwMv z$8xv1Rof~Z2%JnMXVHfok={jAG?r(;yte^#R^u|DJFkk|o(|!~@4cN$&D5PZR?~cd z`jjYdwQsMV?tJ6=8Mt)|rC;kTAl$ood$B4@M;^M_J5`^|-GHUjRBOuBjMs(j0|2$n zn+9`EXjS&t#~-e~`r_+yd;x&Ut{}$r2KO-sfK+yYmg3i{SIQnH%&6*_A=oBT@1n7U zw-c3B0IdMeZ~EXiiFjViH@oZoNt6m9p8&sHP4GCU>K~bJ{MGFPdImRazkSV$B=7)# zQHezvsn0_a(w0MYdzM&FF-bB0{Of1xZ+LJ1_kVrog7*evszXh)H0Q4O6kg;{wY+Y{ z9i54$aq$Wl@X3!Z5@wxzg?8ox9(Wu7!OxO047riL~5X59f7Xs4Y6?h zgr)D5dy}T#tUq@lL$t0GfOZ+Ej88gSKaNZ*zKiz>-_Ng4{2T|MP%(--b9%DC=Ce5NK@tK-a1jCvlnR5BqAAI}&FTdx19tu0m zWYN0XNbnS|#d_&!H}a0lQDbl&v(!PvIRx?EXeX!jkNLix@41-L0hm}ZGrH_H41J`Ges2dNLH)pP9nfNczHPx>y9iyub$*1l zCqdMxW0^x*pE8|f>yWigb&HLfcS%W^m+k*2q>M7T1Lj;}@kz4%QGBolkL4TQaLd$(W#87Ybc-|_g7Gh63 z*a2UzGGqyenRQY_JbrBJ1Jj{LYZZWl_+da(5L_C4tmLnl7LnEtWKJMrv<~FVmr%dM z!+L5oBKBGMa@cWPvl)4#^y!~#`?OJY4F4(65B6SEfmca=UrDKo!y$l=<_hI7YS8S$kx)O`OslH)W1>~3M z$dX}HQv?4gMpi7uR^|p=7@M8}joFh+5EY;{ z*BQ~!GAXuS}0A1K(P4P!>=+>&UV~Uco)n9*bxbR z(>uvpUXK{OOFj~DrdHVxegFfI1yh6>B+7e?Y0Br_c8mA@dh z+4@mYGm3VE9xoe-$ z%t|g(;kD0!>RN&(&(jFfrYGk60zd^L-ba1nz6fx2#kc~bUwFfKZJA?|blb{|wJf;--Y-{tE8TyYJxM3tt*aA50i4_E8Gpu+lBK9ors)*0Is zZ^8JQr-okqESf5LWaeGc`vxj^1@7#=3lLz1dO?Gm5ua>0)OH##J<=3WdKlUy%w7kK zUiR9O+U*c&YrtKV_`|OFP3;?mD`HMZ%x+(C3@V@oBq3onv=?%DIXV@;t1)UZkrkU<;*8G{e!U~IA z!)T=JXG7^hNp;)wc=L<{DMoYX$Jdq^-j(R143t^|vTZ8L`-@Rp0F+7nKC_Gm0|BhQ zC>0XvGfj6eiryP0!mO-1adMh2`LET+vu7aR94}VvxjEeL-PQ2e*0D(b=Fm!N(NG#N z!#-OJ0ubpilKu5qKPN5*ScqdJ=4;(hJP}MSzrUci6oK$Ou0CvO5UQnq=SvF$khIH< zdW03$52|;7h{0xnEYfsLAn2eb>vh_(8?8IHsSy&w(dI(% z!B{y9QK85Uou+gkj=~OOxf4UbKjFDE!2sU_yGssV*D_ z%s!XLPdW9M^zbBQ!;f+~b~a)HWT{vV*JH8pUqdumVuUZ+E?kw9%E>*JYtn%BHej$yD8(Of$%<k z%b>mi0BPLVWB;g8TXsR+KUYoBa9ms7TH$ZZ2s{RtAWqr}_sosE-ue=Y6}MxY?)F&6 znLkKnnmLa@PWAu7i(hfCj>1fls#y_+i_#9Tqaaw3i6mXmP^5DEZT&`<9*>I2hY8d$ zbuXj$JoQl$ej5@k8TD>)xE5E^hVDu%*Wf2l4fK zi#`Z6oE6x-1SZ68tw`#Agz1#wczML2$Up(-w zL?z%G_Sp!+0;H(qOI!g@$M%ebC+T^ZZq*$WAcX(gwZfRP^WKKibQjpgZ0kG)#|Xyw zg`!#k<~V0W&`Yq`*CuG{yAJ7CG!MKrHZ6_C7E;jI>Rt2%1-G@)>~#F24U8%MBzet3 z4&(7uwt2o;An9+oitko7L}DRD5aKvCd0pfv6W8(H$BGWRNcsvpnWv^;(BahrHcBWe zTDC!jG_eFqf~x~Kl85HeF;w~KJulBopYgQC+9tpVP)V$jKecXVZC;d|I_9fg=fSM= z7M<7S^WNsgn@ck%?{;O1`Is!~Y73l`tQJsU* z^Dboq@axaq=D)UO)(!F5^n4vxbGtC6#=60FH%9A*^C>jXA%iNqFaFR`^8c%Dh73a* z10z?|hiR`e!ee_}WQPx|j}X&raf)X`Sve$?`Vb_<*(HdW^W0lJBMtD-aY9BoCxX9m zn_-svmKvpC{b@Tm3;+StF(TR`L2DQto>XGmsb-Wb8vl}3I*&kmFw1-pT4Q1_b1b!D zgVs#gIA&f^322g?LIkr0a1!CHjNen=wyQaPBAfku-@+f9E&9B+sUe#>cLS`N{C>M{ z7*qT+?(WTDEqBO3_`J;6RmOA&7tf;^jiy9(cxm0Pt96_(d!pXGSAhi!BjcZ8^j3#) zky_&Bx>RGsdTvy8SEf$=NzyHYOI*HoBnpe1*f6W<$UTNZhHqvQjl+(_fN1B{dMlj# zR20u2!Xph6AJiK`UyJ72i29}+yq9DQQc`7?yhg^Y9pLZ{TYFmh`9{ueyy4ZDq5eCw z3V>H+EN}4M;p(A&5jOsEqM@57J^|;FO5AKRPkdE1t8zHkp@MSBslHji9=qZjnh(9Uz*_dskLAwNe$zy&4RcE~ zC{)LTjDonK{igRPv&b@M{oZHKVTcdo)x?n8SGsWTcA;g}MnmGf_;-p8rEo#k{z53R@+D{M{5NF}RIA+x{#uTJrH|LJW%Ts0%FireZ zXA*?C$Ibj|8k5u)1AubQPU|oUu{*mULZnc_{d^n>d^4NDB#wY|wqGCLR%6zoRzG9f zAv|$l;I@{tmjO|cV`A5|4*IPa!JfFOHD^=yM{oZU5_xD?4vJJKD{8YHdd^Of3v=|_ z-%liKl--x^C&0;?0Ti|6gtoqHgTOpA$8@&D&Jzep|9(U8T>;sPNt;rQX>!N9+ZttT z6Bh4A*fE7kxbQ`95C%DBERvmD)9JY5QDe)26@Xx#D`Z@loB8!VvDF`ne@ zt6oGv>>HemTZfI98iXdayCr@7zSDEZq@O^M%>U*t~fgBQmO zM&sS-*Wn@TO>g##G+T>iu0NC*(w+|X@U|WEtTWp5GkLNN{Jar9)xlHsIyh%arXRDP z*TCyMC&tf@=_FRqAp_B!%p01gBMEIkemdo{=ojjipRy-S?tzRNI^3~ZJ;XiCF{lD+ zDaK~cV^AIDhx{rmIrlk#IbPTnf1)~#KX|nV95GPrS=9&k6Xv%JPIOv;AU(OS*UUnp zNZTr#?Z$bmZD!)n#eoEH77$;u66}wJXyHh+!Sl%*B8v5xx$XS=; zSM~G&;&Kqd>Iq_@$39q%d$$jPVzuQP-SmiRP5*sJezi=I6kU@EZR%-H(vlW;kK3R5 zrDw83Y2JBf?%@^0ana|meX!HhK(m;F(zlwixz4jUSMK_&89YWDuf@4#`B9n!p4sM$ zN0$%{R-gql)uC<5d^O$p*UXRHYQ;mwX3!SQ4|$lF4F`SUDXZqdF<<-Uu}Tu`z;_#)tok-_!y5Y^*3iZBdqVQG|> zFtJk(Hf+6UVOA5=5Oed+oF}CtYwK%H$g zig7DcbeOP^NsUY#lTDI=hRDAq=-a4taHz5bF@5MN%&3#3x0X6x@)?~Z85dn1z$R@5 zGEA>N%q~+*xHURcS=BmkGuc z=oZLAiuG0>4_M{Nyr&NT`9nPXp2TDufX*C9SQm*_I50Kn2C1+0=vj*j^odtgei(h> ze(S)x4)h@DQhG!*?>eO<7nlY97DekJ7{LIKgA4Peb#Nk6%62mrJgV~He$;Yx4QbE& z#zM)*l(cvWB*X#Jt`vYD&{4A?EwrhUz|4YSc0{>w1*~{8$x_Z)t6q{VXK{cEtU;8x zaV=IIiaD#wMpbF-uKTOr+|!V zL;KsCpL@@uI(JA>>rXGt*zl=Q`D3uK?)p0mIjUxPhmF^?zs`OFTM|{q57>tbRm>+O z)Qk!eryq)S=Zfyf`f1k}25=_*#P&Q7{T%%9FW0U_S*A{`nJ6u}l5~HW_Z+i^9 zErf5kpfD ztb7?7G_!e^RQ9y>3uc@oc=&NqP;-WlUC(?Is3P=9YwY105!A4Ao5PWAsa4wI+waf8rHOn)L%lT<2%E>_7$Jo-1JORAChG+3uCxl{R{;xtjIcH z$(m- z#?Yqw{HaXSA*EX1t%Qm$%%i^Abc@IQ#^35Dyf>0DL%+A0-F6SVcM=+eDyiSSr+r6< z_tWY!viQe=QFo4+K`~M90kDWY_zs2`T)(j~F0t$sbRld6hJ|7Uu%g|wdIQH0a ztjzkKxY*)vnwK3tf-Q#5r*fW&6JNHnc2ac&U~2Ba92Y7FPWa1vW^e@lRC^pEYNzZV zuq5c7nhw;-r5Fa_IyZcKlRM{#X$c4fS7bV80B{Ku1#pOQX$=<-=DokJbsB1WRULl% z_TuJ1wC^%$(klst&kb2f+Goln2Q&n<%c4PVX=LQ8$iqy%#cs#%(_%?NsdEaOmg@}f zyUb0V_Wz5oxA2RqVY`1x8M-7!IwYh)Qb0;TBt^PoKGua8bDxZ zhL9PRp_>6bd+z&r-gD0HJ)iRr00Zo6U$NGAS#Uqvts7GRM6T{5oV*HjZrZ)v?=(&M zc;yKc=e0g8t%!}hqHIWE)J{zLJ~+^hEf_vzf0hw0pAWC zzGh>BHA#{km*Yv0nhBA^z*_t?>uz2dCFkei1x<<}8Y0MsiAw-1<0GxlmEQNEIQ};} zb23D=l2V$ca>vXT*ntJizawg#iR9z1A}&wrOuD)Z(@-Nb`NJBlJL^;%cgBNO*~WNU zyb(|~@ikGR1~ClQS64~u7)}pMBX?f=7ETkC0Oofns(U#cCeoYl3+0SDgn}}*YgJ_4 z6pz^uX%45}ET`Vo{iC6S`lv`nPN0HWc13*=9+fiXvZViz)We2qiBn6u;>ta;jd`c6 zy1f+F@EEE>5#3idI>5ZqiO1kk*jpkPU5?%vwpNh&lGSN3&RI%Ro?v0{n~Ao(E5Fxr zs2zN0>YOz)AD2`K(I9{0V1RtBCq7ySP$*=dd;VblVq^K2W>cJiU5#T~bkQ2uyg^Jw z9UY=gK`rHx<>sRhH>T5PP0rE}d$)(}GCN0S~a1Rm!7mfNW0e`eo1^ z^I*N|61r5mfbOjp{Ac!r6mgOgHDQ_1JQ$q+An}9%v7|o#g!E|yV8#f^OP)V0--M*5 zq~s1%E2gy!Si2x4dF@Zzm39|LdRc1>9EQZyvIVlcd=Zec_V`LxAPYs@1awv4#&P;6{zpO5uHzp~4EHj3) za#|~HKQq{3f5a?sm?ZNhjNqQLe}sd9)HK{)tr;5s8lgd;ox7ESMZE^;ug@>!`K1u+ zOi*o;I7V(MZ;6MJs+QJU^;CoG=^*T6D;q(1eupgy%B$Eg^+x4r3@cI)6n6r}a&{L7 zdh5p*DhQrVLnjD~9u(4K-y@{`Dn#=2M^T;J71SSYAvB`f5*TQDTiZOzVkS}fL)ERn z&Mae^pHR!{sLQ?=-01}|bH751^isA82WG{$K<=^cSG_g*AT<0=^%4`7y7$bkFLlS+ z7pul6Zqt9t~dPfyq;! zA*dxZ<;-NNp3b696(d@;OzqL$Te;_>AylEqWp>}K|AIdG0Hm98gV$kas{QsxjsxalWx-pUPKK$F^ zU9?ZlN~2~#cJ{dISvY35klws*;fplxOa14{ylPLw30g;r^8+DRc00kmm%{KO=;;PV zF7})BwT~i=YdHMqO!3V9Y(;SjENuH5cZr|WLhMP5ka%n@hg`wD*C^zh8R2&ed)GE8 ziTNwKzqyRP9Z&b4cz!MDn&12s-on$>BBk5@Fxo8fwNe&jgPfju&Z4Z&`IPBa5<6~FQg#nO|C za_@@VsA||Tx#8M)xfMpP9&yr+9TM3bB)m zQgL{6NO3fO>38v~;!akQhv8i@NT0&SR-xm?#F0DErv6>Oue$U?9K>>EIC7M|N5w_A zNKPCtXD`}hT19%l)A7pdhR(?Nf<|cQ_>qw02g>=L9fs2V@m(r zp!u8^e1LX%p)Ro*f2;odH8r{|Eb*$UhDO$S{^<5q|2-dJpM(8_Mu)PrmU_}^*`4(> zaL!q=eY{mPN35$GbSdF#lH+RfvG;1oUT!`%bzXkRh=ba^WuL0YuNF+|l(K=~tR8Hc ztaK2~OW2Rpb)_5cGn%M80*_C-?j#oF#>t`usapitc-(u8>BqJbWwd&f3dcj88d@LWyCT*e zA4bOL*FTdYT|9?%F?_+xIe(Q{g77+uTg7wHz_?F#dv|O@y3i)x{A%(cGzbxLv zxvRma9@bD=gEvg%O=5Yi*^Ezb`ZD`+Oq$X85AD8;>kDWZrE{&dy~C8f(GDJ=7uP{6 z5M44q^C&EK3#&0^>{)SHD3`4*laevo-IL2!uM$`(<1IyE7Z;JRy0z*p(3ad$HAWmg z%{R#PgpmN@fe3s60JK;*Sf9I0nRz}r5+Wg`(#kv`B|o|iF3Igk<+NH5t;7T>u-)m9vF{jX;oOng9;l|tWtIZvJsRl~>O^A-!jU_91G+L-2z|GuZ*GKZIyY|Sl^jkP3w$!g`#Kd%=d`sqGFgO3$XPT;rfUGrvM^% zpTdqU8VqhN?MdKIk6?WcZj%zUv0y`B$Ie*5b7;4qw!1l%Kd6)M)N_ys%(M38a?Awf zsqO-ttCONG4qrR3-RsXQnFkeXii0l%7VbJWz7RyalAI$15nL<1sBd*9K6i-4HBbv# zv3$`iqfQqe34c7s{8VCn6hdj((Pj{Z7wImM=rJIi)@feWcO@CQIr_aU%=q8^+rbj# zTH<8ko=*e~1LS>s`0FjUxrF&GFvkTV8n>T0wHA6)-bESmcU2xS1DwjQT8|xaJ-$ht zpuI(AL6tR~ccfYrXn?u%ux(!y_4tsV_UZ2<&edr<^)UEB{pwj|MX)qC0W3T3z_4$yZ<1#32YR6z?Rie3fdHTj6j%}yj<)K0yq{BBt8sa5aCmE@}a;A&k-F#alPDq)xZ2*X`Du^&3{_Q zlU=R%pv*$`Be<|}Y@?#>A9`r-AEALeo}lP2th4nJ+jkKA19#y{ys;id&pbbjKgeEx ze1+289Ih6{0ik>TH6-GXXpSs)(_Od3meDC8JAsOUTssd^CB=I)=- zU&Hyhto}i`82n+PBtEP2cQ<_kXelcp)I^>hhNbWvIafozfH0&iG*Cu=1V`WE znw(4-S3oMChHNN6+)nQjosi>WL1=c0yw-%QCOZhr3j<2p>vtn^#}R0D&|e35#jw=3 zvoSEq`p0*I>fPp4Qhd^f`CY=@7OUw@(-q^jcHJ+gik6E??_#%gs{@qRQY7dtzx=7b zvQ1afW2ua^Y^(jxEg{XB2pWFKlZ$<1t9tEqEs6iZ7thbh;XC;(Vm?@Teak!wf!G7Iznoc0Z?0Oo`M~ zS*JHp^sOf)PuUSx@J||MDJSs_bjTRz!O~?<@BLjrU-XLf;SM81!sZg){Rs@*s!D*3 z{U*=)y`R`ZNmuM8V~K$Pa**lI=t4{I+1G)hksOWOrk7`pVJixb-R*WPPz$ZA1M1s6mc-Zv z38q;syJ<1^6fp+mXX>(i>_&bIQEfF`Imn69mO@z^xjuJ`C^4JE53@L$8q<+JR=1ye z`D#Vb=OmZ3QiS<%E|~drV{#pGlDYw0JgEH?%}bW+-B}1oQh`?t`*X_rQ(2-w3j9~* zw<=?Datf+UP@;RZjNkk7t>^R6v z7YMT|u%PXb zO`$i?_P-T@*T>w^+>;bfmkboEA?=OLr<&osi=`)k9HstOOJ=E>=1QsFoG6GL{q#_t z@N-0pGt;&kX!dm&X7#Q{%ueZi`Swc{(-2bjB=P|nVb~!R)I-NFQr(t%5;EYSCl0Ydf5-DeKZk2zVoB2a`}vk=%E_ z{AyOmHv#RBZLNi|k?A_LzZ#`STysaIB`bkA>z-T_<3CC4BqepoJ%#R+ZfqcB#qgnMT`YscVSS6n{;;*N^ecU#lpM z7tKcm2<(~6BcNayq9u7#`lY1LJGxz}2NGhZ+v)_(kK;7@bh_l6QI4L9L}?l}KB8l? zu4_%zaQV&rq*fO*^fqvlp5hgup zn3#E3CP$^wgL+g^DrVPoTrStl^ znZc9p@VKlRv4=HqVIP`&PmbsXnf5E$CVrWJ=YlQ=^)AaSY7r9hW6GFmtB(p+WAn%> z6ee@`!#EO6F%l9yR4zrbq-ATje_~;Fj zX;NYQOuLkA5MzLNA^KWIPUv|fDWP({2b}u6`pg3>jAdI7Iu_&f;(alxd=|PNP$+@2 z7XZpe)ABX6+baD=)zm47_0>25i92t^CWwF@`Rd*y`JHBIBr`64X?mp^x=2J7|ObD(1;8D_aZqXx@TjO1Ly zs4t|ty_x@-IDgqR8&|FcO6}kCdzWIDDd0)dZ4T}s9Yr%XQueZ|3@#f1kT5mMG+)=}E8>1RO*@IzYDXR@0OB~=CEO!qls z9+m|i#>({UT95_*a}p&i&mNZ%CH?v2;_dn4%PHjs>Gsi4+1a2oGo9ie3ZBZ?rj)$C z^RTgIFZJ>A}j(Bl(2#mqC>11?*UV9tQ~rlVzy1RjM(7rmO9l7#jnrA zw(}FZDseKxw#W1ptd!Ag>Ugvn@A`>6CG7o^t=+r59pYK}8p7ZNhFH?tEm$?JOPyZ_N_co(QM&9EC+GOWXNM!l8MA4f*VP%1k zi;_Pduf`{B4aNe+Oi8#8PlX4)^1+MzRzJr>Sopho7nU^2U&!~yH*rYa{ zY-s|@g2==wnSL4c!dJZpnLn$9zZdGh)WR?%4r96N@4A*SUH!~EG@6?C!4y|w1;D*x z!P;_)>2RTEjXN_%U3rTkO(?Mp#k2KA@JF!oxfEY-k3*U=Y62E4QvFbH=SKoW!AHQw zBS3DRN?=td%V{G2nqOx+6ihZI#;%Ei!Lq%q{ zaTH-dw;+!c+JUoU#(uF<{t}ec!%K2Bu=ZZMLo86dV35Fbp@_RcLZgdpBU6cpYxT(| zBlmOIJG$`trHxI2Ap+p@NXI!rJ(^2SdU&2Jgdx;gumDj*&1Pg`uCU8 z{*rRaa8Pd3_On``b7BaWX0;W+-Noi7JP=yZ=EtiO+ReE$ARSI%K^5rO&P9KF{({Ft z_~ZJ`>-|vMk7q0-uWCYJ(}^wOk}s_8Yff)B59asHaZqtnk$f5xjHSot-Y~3ftjiv9 z>8M$m61$YLdwSn#vjI7iXkHvVjU2hylXZ{5;0YonW`hSTxQ- zoF*kiWd;dcp?7y1&n=_WJ$`#|+JfRjtHjX658af`Iv1>zkeL&Du$RLn8J4Po2y?M@ z`ZJX;uFV4`q(Xq$U7+(%-E9l%zGsChVoA}SPI=Ry`~Is0 zKi`+?f{Z=uG&w^JkKL+LptPp+&T1;M+j+)?7HxfbLpK?>PjLo>T9Aja_VnJ>Uz)k} z!-0eVb$c^fnEPM8jOFi^!)R_j&U-fZ!}MvzJv{zeRX+38@~htZE!!aEM*G#Xw_)6U z_CNQ!uFO|>_gOk0FzdhMJduBMyOQ*;?VhFeJzn$IEg~dy{j@xzU0b6AX8k$z9}GGv zD|p<_bN$<`RBVpskpgd-#aLv6UB4Sk688+47rWbqoj5HaN&~HKz*!f2QHN4XuAUF9HX{c) zhQn?v<9Uk2$Ovf_8!RA$N+P~g4|mRIw z;)1auQxvO>^j;(H^54Wg?Y$t5cG`P=K9iCO5%=B|iO(TmIP66No9ZQF;p-<(K}EX* z1Ort+P<4^yuDOxSvV=@ir;y2ek)1MWSoTKBPCeii(M+S-mP$gWzHgAN_{8aJjTFC9 zKH1ZIGdEB-VYfQZck)8!+ooeRn8WJdzZE~R^2fyk+T1wvqo!1&id*wWX?8Twe7mJJ zV*$1=7RBeEy=1l+NkqNDsTP+n!Q1)N%;Th|Jn7>DUULOa86d#f7m-dZYSY4M*$qrEASPHh$8S7@diBBv=)_P-0r|JolKQ&a?X{RHx<+Y@ck z;(q~~jrD2WDg!OC|C@E+K)Dp^t&tn9+uQH*ef?D(b}#Yd z?d0C|%2}%kNI$WqWnr5`Cv^i|gc2H1;T`;_QOHiM7N+<0o)*;d%Cl*|=}dRm7J&7A zH0kah5u{18{Yj$#Qcw8JANjmweV*Xq3IE9L*@z1Nc8MOnfSd|m#jlULKYvcy;2|-| zrQ6b15{nq$+>9FPi*5c~POa~&b}Es0YK;_B(Fk-o$>eeCRH|GQi}om<`(9O^L_Z%g zlq^ONlH0`vEpmVkTd*o0U5SOxkDP$oA*5rpC7Eg5vEngAT7S$>V1iJz8=>*8NMx}) z`})MqwPMnf$1cCv@3>Mu)xcZk*Qn%@;hd!zN+dK!{(3bn`n6C3!JJ^;lX)x8SY8pU zadgdS!6+BPBcAG=|8GGcuuuhO5Dn-eo@u-kPjim@rdOWu>$&0a9dmV>c$yXNx%KH& zvWd*tWP!hY8w1l=+~1A|9Bq=srzJ_Xc-aV)0KWWfi$qfVP{+{YIV^BD-kGtrEe4dJ z&#$J_&|5_J3nN0?K2QT4q7v;OU`nP3TWcOBZB zv>d9N8O3U=Ufq@(qp$YV8G9cSneb#3ZY{@z(uu|IPs-WRKWP}qF`w#jBdR^uB`Ath zc8bvIkaS(=dd*uYSa))VC6cgHJy-V~QAs$ekd9g7aZ0m`4WLb3EcScm??51%$Xvb~ zI$WL&pXvSk*w)V9i}lnQ8ExMRpLt|t644>tpz*;Wj1bcGtW!(IDndJAtcDkK`73Ya z8{0@$b7ciLBgVZ92ulC5BeiZ3u1wUg?ipbACy0T<{Zf0sy~T$<#RU5*Y9%bKFH2qR z9{MIxQD2zugeQJU!)8DQYp;@)ie1M=NBLUBU!1!}$-*i1k-V`la7Ct_D-2i>=Gt@NKMisq=a*QbGD|_Cj z4fb6wUFw2$gP*IzI}$n0*AGM=RUjRi24eG1epEgKVaNyo$*+*~fhcaoOPO`Kb1eQddAN<&lKKq4}3A5^jskEhA2W2FS26mO`|-EY zb?F3}=$k!B0;KG+(zLzDk3Lfph8O$X5}puP?a$VLMx3&(IZ~wAns*&-ac| zJ2qKSbVN0kE7e(zVLh)wvkqtR0&dR9d}a5~e|`UGY8Y_DJ>7As{QwV4558Lt6xyoK z{wFnnAhEJ|VZR;tcr{B1h6c}It6lg15o`A*F$kHy zK>dafIuBbu9Y;sSZ??FdW1z=N-r@5+z<;3s_qL<&0z7}|I>#D4OrpzA$!_Mxt{=bc z2e0FRc{}{dPkNdjFY)g28%b^;*Rhvh0Pg`+#H~oM#7B=Jhb=PPC*rBhjHP`379||~~X0Y20=mCu<1iFLsN|900ds*`2{Em?DXlv4;2;=3bYZMBVo-#ZCQ(HYN-7yZFRQ)zfW+1AUfwuVvti& zI!ola&+sV>bb3Vxd+~R=30!=P@9L|2FJ)hP_%8s5g6so~w($9r3j)C$q|Os}s`$5! z0(jvvVSMgno+eQ=p3WW}$5@b$RO1B|1=WX+YsqE{BQ+QKKjS6md5pzML8(ig72tvyOt(3 z;;;t%j69aZR8Pif#`d?pBe4g|;U6AH(o^1bwYcrEsi=NUH|iqr=NVFqRyhLjWBiHW zc6)`XH^%efNj_d79>nqHRcF^BcrEn~Z%J)+4Gd5kLWocrCPjnFKEp z$+p8E5%N==$6e+}$jc6Q>y2BFRPWI4;Os*A>lC(c9_BX0OykT8K@@` z!GR-+FyRcXT1X{y5S`Pec88A!bIaoL4k8)v3$zN-4VXqBspOF=tK)S5L{BRykn}!M zJVH^lV3KjiZ9!EL7VKzEN^(0!8#H6Hu?wT6rJP45snAlazWOPS@)7BDh09dy3>G=D zt91m(k{55j;)jPEeudoJLL;X-{(?@qpL%fmF)wMgJz=38tGYK-W_q}68 zVd<6*9D&WLb? zq&!Uje5pNq+^L{JLh_AtPKZ$+FGTz~yK+z+El4;BQ8)ed5xv!7)xsX;7U~n^J4Y*_POC!Wf7p zo98^@-yV}zRfHbiJFGiLgt2rB&{@gMxs3<(VeYaqQarpe-rdn;&;?&9m2! z{o(+<8W2IcQnXJM?o2y0>d;6y5&H3s)`#qBDaU8}YT0SV2%i=j&x>9RdsCR1Zo0(0 zQ^JaXjxyizl`fVydN(gZp^Pz_B zO?yxVB}paDEu~;RTUh2c@Uz)v@o*v6yw`SGejp3nHdZ5TdgE_$XyZ&(lQg?m83!4i zfH~*LC+m%l#+OT1IQ;lNj>TGFkjho5{wwYH;Xpv4jI}XtMf0z>SWc3*TC;H{O(jPf z|HfE}MiBh;N=j`0uf$=)vHzK@KA_1jk@F{04P`lGtNScEOJxkW2aqRv%B9mzaI01?65Y2k=u(HG4nAw4rDH&+AQc`uv&0%Pnk9td3A!8XFi&nxAt6? zOZ4MobU`vGw_c{0EQI|=4!hn^-)sdG&!^6W410L+t%WQVghh&f;cCP5jTGA^#m#Vl zR1lzy3X9Z%6$~bXx!l}@JH0-XMz6p>pH4w{_ezOeyX0p9gyEu9+^x?3$`lf8vO}nu zy1g-AfeSPyTDHqE7_Yt5Kh<^y{GEN*&J_53A zx{EwMB}MjGlyEK6S#tYmq9!cgCDc}OJJ6fCWO^vl3(mZkapiLS^#o;rRM1qe5D_8} zCUIe27w);Eep7|@YmIQL?-elF{&*iebUP4-E`Wq< zp!knyJYL4Sj-EW?v=ZXhsvplB%+v+l=>dU1*qRL;{kqnb+!=Z4VXdL^dxSS7E)u8Z z>@@|}!ujE6@cA2j_q1E>(?S40?ZpJ|?+=YBAFhY3`GWw_gWYchx_-3%lu;vr# zHnog-w$3u&A1&@9HJuuD6xt3R)oGm5`Icq0iL~_D zc}55KGQ4dPzsfqVxE65_aJM#?+As3*&|P!m|5;RheCrN1cUlBg3IK>bGQZOt9d4OA zWciLlI#ks?GJq*MA)!btBN`*3t^pIyp!EF~z@YXlBl4n1Z&axIG3C(nKa2jRJ~8)r zW!x+1nw05Q8n@C6rjhQdZtJD!e|=m-?y`m%`V9D942(bEluyiW9B+mRd?o3 zf?lA$ZPV`;8G3w!;}F$>F^`;^C1Uery#LDGwAW-ARjqU!7s|~FqytBrKKlqvvf=bS zFZ38gdJwo!wNUM1^3^O=xzGExtE%7s7TV6cFIRyfXQ#Uj%2zDkeLp7Ky#Hp5B z$BtHW(o|%QjtA(fTF+h0J-h%B=SXwRoaK!{!4WGdGrd%Y^HX_LgAEPLtIp0_f!(W( z1GO59E7fiG_$nBAj|xijR$rifRH8`v9J8+Y_k7$=@sCluWk)GR z2F9a5&pX%O1wCeLO6EOF3-fBb(t8{7D=0!ZREh81<6>mLcLQ)h8=6yg^AIZ@`6;}u z0CMMLH*av~3Lht~aF&(Vfjii=zq3reZ)***+{gef#Jh-Oo42 z#N2_XPk$4@i^qvqj6-CKJ^Vcvm)%Akz+nieCk02yKyP*XPMkaFO0)fY)qh(%R(zxP z^5#I~gLfc=c1@Z?m@OFJ3jcp0K^Q>J4s--(%(U|N^%*JReu$IwYrmXl6{hDoA+->C ziIC@(=fzSuq!1E63{S~@v1Ns9wfe%tp3V1o-CXlyzT|*3B>O%UKgk#cscB=zEujY$ zz`q#8VK~p+xex|s7#uc6h|vWEW>po)y8yFhg}SE>=OcT$2NM;gBU}#8Dc`^Nb>2W= z@e@M3FzB(fdpDcYp3^gpb~463naoD)YT zjM}-&TXy)yP1N1Bc#-s*)^s2V17i3`TK!@8g!V7mi?9KyIH<^rWye2}Nr_@en0HI2 zM1iS{9SKZt+ySk3T&UhmmKS_OJxs9zJ%yf?-|QWi|4&;rwiJ{B{7Ng$+zZ;gxu4+#rP)tgj{9fX@;eg)8yQsT}-AoDbmHUC8MODa+teI8WdR_~s z>C)i4^Z36{VU?V5VHs)kfYN5EOuQ0zR`RcEncE$}nD=tBU3h;oXcUPSw#M+3H}qnL zK#RnW#8-g8wBi;DQqMaZAN+)PI5e-7Y4>^jt5hhiA?j4GJp+Yl1lF0=d{$(?xi?FU zk8b0w4WDjeDE8sP8PZH$Jhh9~fXfR5d#|B#@))wn_3h1Z_|&@+&=MkQG>jUn{5V)J zqwwPnrdVon{FXVNtwnflhX$ukwHv!I@l0lF2L@R(LH`UM!IhNe8(s`RH+Jh$(f(eM z+ItIMA}W?g7&jC-caIAx=bY>|@0k5&>v6skdC;?vK{48Q;KN&+l48ov-JBg!@%uW7GRUa5d0jCM4ElOn@;Lmfb8-feN9(a93Iec)nNT%uOrFo)0K~4U1)uWn*Ncc_J zF^5w&g(1ujkr;y93>j9`WM=?<=I!FSK~}$Ue!<>dB=ae}9YD1%snb}SaTYuX>o6;T zg?_!!$QQr>2JUlA@cxDksLfvgy=-ojl^jOyB2X-}sL%bg0w^2_Iy`XQ;Zyvtj zJKh>xu%Bzh9`kLiv0fQYkh@d3jPVLJoG&uNQbHFpA`IbG5n{1n6;laj&s?_`{@Xs) z(o{E&pdXzahhrNTsziys8oC9PipMqHEmt2XKG)&Ahi)4=Ucq63l)54A``|V&6X1a{ zub?P0+Ho%owVH~jBvun0+0ngFK5ZF47zZdyz(9Pl*KmX3Zen%1L4PFr>RqTUkoFmb zRh0P|d1zIkVmg5W@$sFRV#q%)BnNy`GQu2=gvT^|4G3H@m`gvnPg?0nnMdfa|J{2A zIm-Y$fw*8oPoG#VzXb;2Cfp$G61~{yBZRf6pnejPGBn_VvR3~KUT88{dz`j5e7j&f z>uonZu{^zSC=7}}CoAt?^QG1R@#SFtwTdrJI+dNyOh!?yQy_L_B@NDK+D3k(g=I&d zM|JJ;YsX8y5&lv9t-vG_DHbi9DN(bZrRVz~WhjPRb5(krp6EQwSpT<1|LYqR#7hM) zf-XhHKS$J_p+>U%0G zr1Y$KrIBoJO35dA7hC%hgd4~D!hhDm6n2zCC?Wu|%@Ty%$%51V`lremccwhLL4I+> zfgbkl6~?CsXr`hucP9JBuFlH=W(53C?Fyg;_Mpf2|L!ZJ5jMadXQX;d(ukJ<@`$K-+fyYFAJtC@dNv=*}4&%{3eNlO?qQrXIR;VXx-+mC~!@|4e zgkKSGJ27*oj1mplZ-^1NW$-oK&KS$<`_2UZ4fv1NATdO=$E5liUl}!FI*RkIVT>or z4t+s?KHX%byP_MMZ;PL|Iwod1xEGTLMC0W&2xiv#B{oy%4d$Eey=hL1qVAU8?N<~d zcaF{dc?)~Ty~mu%{T?E7IG;F*3E1cND0|b_*;aem!`2oGYw37;GGY3m(x>Qyaibu_ zb9q>5VDh_i4v-g39_sB|&L7wFD-v<_+OYP(gPgYRbe9+0U!Ou=s3d%tKqF_gFv+OZJ z$$ZdF`aI`t+ElIZ?8VrK_tc4?)`Yva=7`UiPPe?nO^Z@N&z+Q`-!_(U3|d2~ehKUO zR55dmnMigHlhr1VNmtDzNoU}$e$&I_iQYD&m3HSV zj3req-hpOaYO6xHVidEsznJ#bJZy76{jXAFO|z?`t0j;*GeLT^)$~TB2qAHrQqvJ- zHu~tlgXC~j{MP#0-7*XR%{mxN@&56S;G_dMrO(pN;&VBLeoLB4;NrGe&N(i&C8)Bi z%3|v<@Gqe7yj_IbpU8=8j^;c6_m z*@a{A_1}6^MSD;-ZEyk#H-QiVFh}TPbU7~et}U{l$oQx0ZjMTJ)I#2J7SPNtr+@jW zTP0T4EJcHE*rQWP?fftRT_%O`Rclc}&HQ&i12hFNwOdDn%@oZX18!C{bNlf2<9~X) z6Sinw8XvIo)*ys|uv*GD?+`|=IN*eH7(5&#zoeugG^pYtGBBA zIVRsEi4t1Vk;$b%&s41oM^C4xghcRksinE}$tRf!le;Ep)BU?OH%U4$5?kb>3EsKG zdvH~52ByOib;Jrj9Y3~>O>Ho_Vt*z|F&Sa?DOV3`)b6wFUfR zv~J5vy}o#()qRS>&K!T8;-u*d%ZWHxkA9eAq2iIQKbfy3p9z9)X25OUTI8LfMnV&l zge(Q*Qsv}z=D6ic(r?j6COgYS1~e%GeHl9vX%rAk-cjza6p90q(4Y3C2*zqK_h4RV zGJEfZwugmbNdzhHTWM4m-Tf^sjge{z2PaQz^)v2z$mKmrLi5>YIqEWI%WvaUcV|(_ z&WVyx7vHyAq*Ei9kJtLV%${>WmhN*>Xin|TQ}}UVOcRlVZ^{zGrV$5dSHf)3Af9s( zS#P6(g022JANJx{=7EBD+#i+f)j)RR6P)I-n7#YgBMwLJ{W~{? z$Z+L8qw=Uv%{Hn-<*Pr3xniMcMb~rE2G3OhEVx47_3WRmlU-OGdVxR3;>_*OGvjDs zJ2Nm|6Y6{TEC>&>`*;CIn+U)UI%6E{n6#*s%6pIZv@F~GtrCXSGl1z&kjbcZ=Sz-f zR7=AuI$L4tOU6R)c0;w~6M%vz60Rb5v+sC*R2qI_$}lh>l_moSeq>|GgGA5WZbly6P4U9oAIUavR0A=2agLzU+Ar}qAY7;< zzAX+qK=zEbLw#Do1W}5Vhsno-C0moa<*l|Su0H%t2p*OO#=sHbYS2W84RUm91<4aVWubygKIB9nxf zp^S6GFB3d&Hj;a)SfFwfomr>sdWrxy|Lzd{J6U%4Y^9n9%%~DF@rt5bl53c1UPetb)d_qz&udeAEDRJz>6TXx)BfbO))#5Fhr>hKnAQDGCnT(`!J8>*?fjO(=l%Go>VTT*4H7^eU$#rTkUnMtY9HvU);qo94|kV#q(s(uMq?sQ zwo3PX;1T9KvCf#9oJ4fS+iv1SNpV0;Fs(fgu!8>eqdk82>vCxRveoqB)HKBQ_lV!; z!r1fjI~mKUw%OzOiWsM{e0QpSpk_3gP75c!@hEXvq=8jFc2%FtCJ^qh$TKet0rmBJ z+mM;N6HLFb8(SETki|xCcOSGyzLjyua?1(%6v|HaR5o5uJ|V}VCvivY6pqSc^>}G8 zbCyT=xnK|)PnS$?S+R?H7ri;ZKPiww*-o6}uer|ZsV%$}_GDEO-KDO|_T^7!)nCM@ zEF9yvTJwIjssT;g0tI$j&1f7lg^6M@j6axP^hq)40=iWhnPd+e*bqls!Fi6tT_Xve z=0uCz(C-2&>NcSbRlU$>vv-LCi2)Yh^4t8UoBvZ6{y$iv)c~4+Gx3dB!Zj6+JTzv7QNTCYQqqP3e3(w)_Ag-RmC;(sCcBM0sS^>-uL#DA~#%>_PUa)&%rQosNi2XTwK z`!@Hu5WR$9Ds62zFsETe$1Dcici37{&kRBrigZ!o^S{d9STng4$3K;E(RM)upq&3E zF&`FjS8ZlSP50k4+66E{%j+LriT<$_di4b(SYR%gVM6`K35F_fdo7-%3kjElP`{Xn zWvmMB7s}3|HKV=nA{1X_jGb!fcoQ|9j|ONzs%GsAqf}1JG-ljiBtpHArcUR&JR}m} z9!kOS7nRm^Z+C|`77bY{ZZqXLrP~w5jTmcU^6Mhs_N++ej^Z}^kkxFr&9TNXG4-FtlZO@SOtX(&Czq z7PoI{hr9pQ21uz=L8;B@u34w)2~Zy@BYrL4W*-O8U5tG?PJGpN%1tGZ?o{wyde?- zK&S;~&&b?uw!*`(F`8us!i+~Ms^!F9!)S@Jj<12#TP^kU+1&_9;(Nj1)Yhz%L{m>@JLW=?!A#1r$7?8NZr>{+Fcg|FJbTrw0@}PlRabkF#Nk@_ko03@d~*sb9{o zCjn;J0@GgkaOXzevNupqU+BY8I?Y=X3K;6^Rcc1p!T`iUC!68OS##-71n<-nb3GTG zI3JQV)t}FI`3Nj5+}WTc=jMezZn}92Dr%JIM1isoEiP6$H+`4^DL{2@tRC;SUh0H| zR^z6JS|7XAHjqzfU}IaW2O!FkEmZnA7AI32p92K(1&~h+lL=vmv$(`xWwW|m4yRSV zHviE1^BunWxLBdFhDx7GL9WNgI1&f$J0zu%W(!@chZ(zLY7p?3l$yS;i`Bp|v6AzV zwm4`d#AaSCWkz1Wq%OPivPBq}Iw5ZLOHh9bHvm#1jV8SvvuaM+|} z&)Sl=Kb0cIW(%Z0(4K-1Nh{_62|{r{fEH?1>Q}Fo{#^6E!Q@;iNsP!kGt&v^PS;08 zynJ76y1PB__JVy--gw7JR$%#1Gdr2r)$ufJy?*YI`DvVX(3>DvRg-Po2N{JpJj8EX z_uZTG&a)y~f*B&S0h|74+yiee#4Zxs#JS47?lNMYgFRKopf2^X+n`lPeLq`!UGqT@ z|8~fB!TcS^LpoW{Qr^#yB{z+WVLU9%Lt$FeeW*Xi8i>PAw^B3a(M^97bcsw$nArSrPEqar=0@z09OTbbGa z!E*2rMoT(j`P}a%Wm(vh9%FdiNAqW)EGK#6VJ-%!F+l($wre}fWO}<M_jY@cSN3 zuz+g<+rm9iJ-Dyv@B51z8`xXiGmyz^aq;SH$_bB z^q<_!BZRz9N>TT^E&!lqI~Jhel)2lI8)-_`rbb|1`SQy*sUl7T(ZzKqO90Etj?*zM z5B3EInme_wO;$m~N=8F75)MD`w&g&Ed7pF+#bE)4m)|(#|DxJ$Nogr5kr0%W?#_`8rMm>_5r% zEKs*z-lJzfMSQ&N%SFyw&Pz7+D|X+s9(_KUBAlnFR&s1y97H`M5G59;eEnf7<2S?i zh#V)w18Ukx>Xp@a1D>kpdo?Ff1?03cFI;EKh664n9gR3J-K3y%M_L~6N|dv8jnm2r zm(mPMTbhEz+l8>x7}mCGdV5o;3uG93;_jfp7DJWpgbx8-j7?sAKBi5L9JiA$IZB${ zoq=>|xaS4RFuomSH?c#yM7mIA%?b`q`QVPG^W)jBuuZh-zE;u3sgR#+W2fVtogXgo68vL zu_#!2NJZvrhx1F_mC2!$!Ib_K(aYpt6(dW*u{DVUnL-A4wZ}_ z?@}B0ZAQpRJlL2%YlYI-8!&u3Fdk2_wol&#dL z)CL@1@l9-i1+u&|AW1+NM{RQ8iPDcgA}YLinxv@{K3~y1(cNSWDHqs;a_a2$ma(U) zv$&DyR$>_jSX3s{o+Y8&2a1Lt1WLRXzCK#6=Nb<+QtLHQu4RloR;;>R^#Tr4ARI@@ zyms&QdeK?*rA@09S^+V2RL)SjZO#LfiJ+*QK{Yq|ug?9y#_s#GcB>5ikGM`5wu z%14bgSeczBZ^Yz|5{iu^2#4Es9YjxRu9qi}el_oG`^~T^gnlP;{fp2i zjO;=>^Em0;XHg?!ybDQ3?O$$owO`bcpPvDD@0R=cjkI0&zqM5{GAZ`Gd_Kg&hZmNW z|GI}$iY%vHxG>4!;elm_$UtZXov}8JFH&8qyL7{X4SONj^JSazyC*fK-&Yb#n(q4s z3mEQ&xaDU)J4hGV zo5^{oi%yjXJgglM1i!2V8ft`puh zOH)58`!4sRmQ09HBH6Kju7Tuxo)_F*PrA;u+X8~S znnX*?9I;1Hbr=*iOP^$FOuC#ul`Wr5PC>@s$$neO%dJ8FJ5iK^>YMPTgPg5@^#%1* zmq#RLGs?f_>#$BOo;hS(*;NtfT%a5_$Wx%uOw)qx4+(Q=BW?zSq7O05^}VOWW93as z`ZyL{PTrk7d;27PM7hXycsU_?uGZab9E@Bc8r-yIyN8@sXDvoF5rMefB8_b_-cs@j z>0exS>;57gyIW=bGmEU}wT+jxe+gR;ytdo+zKH-(w@u-_A;4Z%dF< z>z(PVxH{=*D1H)2QHX(PIKiL#Oxk$#Yw%V0Yq|8wgDrDllF?Ax(-po6zk*)f+Qd>p z+-&h9?E7BS{#~Wa^_=}%#~JJh$W#n;{r;cBZU1FOf+A)2(b~8$D?>SxdC})#iczKv zCbSD8)N9y^5pISqIQz<;%ln;_jh#WgE|Tw)FvQ!6151#@(4=ITde1rVZ8jGT#eb5> z+KJJ^P5aV;mnB+;0Ve7y^_%D?@fVK5xZ%=Ap0QEygT|pJQ%OIoQhz4A>`C&g6C2O( z+VU%Pg^g0%`NyjmzRh$v7SZ*)l`IVf7o&$$pW}QZd_p4VUWv-wrtS^!lSgv+WHloE zR|8YeCzwwJp!ai1dnEE$X+2zt>`0?TBkgWuLmnpt+jDm|Y`qYdW2194pz%f3(RMg` z{q4BnZ0jZ&*);KgwK4wk2GOR~XWG}ObdV-RxSNn*sN7K(x6kvkY#XmswABy&FISb6nFXoi|31!005C;oQiKSj(n*$CMe zZ`;*1Xpwq7gB!xULkq-8)QetP!d4eeugS)uuLmaF}d;9RqA=Pa37}GggC6`?J{7L zqW7;<7AxD5xt(fSoGUl*;PZr?qe!EaObMZ} zo<9?S7ubZ=XX!oxBTrkYqm*Wl@#@tI(vmwLEiPa6)_ef@rq`KQRoGYK-b155;7{cw zTfywt-xqKUbPCuOX{J(Q)y&I|j~_*T-V|;4i1K0T?mp+FQA;XQ^-|kD@65+xzCe}S z1bq5IUBh8p6VRd4(pMIsr`k)+Uq14LyUg17in{Oi!A;{8?t;2zAP zWbCQ->`PYn#B2=ZymgbpHp{ADmbN@c>weo^(4(VqXG{3xQN=19L`M(|@~yRH-Rw8| ze`vmlrv%Mb6Kroy1HLgXVXx_0TP?z>+5%F4&zsaTM=ra8f~7})!fl@2 zfkH!lqbtR;d+4rjSA;HmO{2%91RQM6-T3^ID7P#wAUEyx?uu2kIv2m=YJ}k{hq*?a zDiV>B2}oMELxuCR{Vtpw^eXp@r1EpVQ-=z**C`HrCZxARX*-I01c==NJRhz~SHawK zHsd){dIDfEnzjejt!V@DDc8Q+aUvrV?eEZ4R;0EI{e2>DTUsohq1ko#{qgzJ92nk; zCwO#yCW|6Baqj4&)2l+K>nq-J9T8f@cq3-Q+o>qoKCse`>F4hDuaD>7GHL%EF5QDs zy>LKw^S%gDGD4rP!yk@Z^FA9AeL7EU@{-t&*u+%l8$3!l3dt#*N-K5;)*oB{h+MRk z7Fmeo^X-WbnnEwTS!ueC1OD}doI=Jj4I=aP6r`6kj{HlCnQD1&L6Lhm^~F0bAZng>&c zaFGTj!aduO^)`YK$1TD!R8x$&M~}gqC)9_2j`UhhU>i|xJfCQB{Q5XO0v2xnyudu` z?Fq09P^F_^of?&bJp!s%pE(($i|W6#b}O;mX8#^oNM5bi&|8(^;XKm`?8*ce6J|eu zji?hYNs3-b)3{<0gUE?I>EZlJXB-GUOo&pGS4b*Tr9w?*gS# z1QpdSF?6gz_9Ni=^?}DfvGF(!wJYSN9ajFpx8eE$a>8VZE0L@1d^Jr6Bg7*}5F4oZ zTWE6#`?+ZMxhg29|8auT5GA*wtCwgaFCUNdV*D(wEU_-`@3w$sKBD(ClU-kL6$&t}}HG)mP#YM z!xv_kfHCgTS0u>I41R_7spxz8B(C;QCZbu`$Wb$YTrer0u1H1f5Fv}Zhaj$s_E zgd*zQrjKVBj}^*R-Z|`UTthsK=ZXGAQ?-qEl}VB)U<|Eu3bCUhk_8MkRHm1&T>3B_kqnDuGDV}%oXr6NLWZUYj$3GM=PDkhpUEJsD z(*Ry~PY76yniNRejo&v5m>qENW>^uNW85CBxSCV%k>n-xdfaW&JD}o}>#5o--?Ra< zA{`x)AyMN><-xR0?ZsSYroO^(AM^cW;N1u;xWcq3vB>Uz(+ZK`^RLC@K3Nqz6eA?7 znc*8AOg$+VELxHZ^Ju*F?xI(L?cJ=Uy!}a(PdZ+ZkgC}sVrSEwJ(YhGIqsa2lrY)# zac;S`i`_MvlL~FXzSvE4FBub8Jx291u(B33TrHAN0><5^BZhs-9VmnIZqB;jPP$h; z?lg;ne{9p{H|MhF(B~8|Yz&!yiEf{ae6KuiaapvYoR#c0>e{|fk; z6hlM^eQZPRBkkP-FP_KRK@%e0vY6m8h%VLH&Lv^kE^}o}-zVjJWEA1jV{l>^7PdJH zmdu}0Y~pSQ^$A^$_p1yit;LdmPsR+^{Zu!x&~@a~5YP-i1iiJ})D=v(;3 zjuUkUYH4`3#pytm;jClK|0vuFYRH!fbB&QGzoMpPj5_8D@$xTx{6fei8%Bk4+`jRFYXdlj4{fN_|f}OG8YKmf`Pte~} zXT+ylIQ7XHUJ;hV!S=-H#A=dskFT#|Yy(Am)WuGi@@n<5S^ z@6{VpebqkZ$v7+XyNxBYs_ngHpg|!qGsF__ae<0@IUy4l8xr3vR(yxqkS>S*Cre0Y z&l|~0DYx6G=?LaBj^#tDMyw@*(Qz>vd5+9oWcYLOTWK_5lGV5&B91$#856X!iH0|2 zJF^v@g8v{X9pL*`fa9}G{ZC6M5{6WNeyv_CFBA^5-ZN8+0DTMflwXXYADB(HLL0F~ z5^gK*JHh>+jtOC}eS}#;o(71kaY5AkQx~U`F0{=_H9%o`xc>X;2r#4QLQf824(*eL z4xnQ!VH&vyQ=Tj_ChTpEw~P<~%W#eD2&57jc4K8JYFK|Jy5!eH0x-C1a)N#| z6Hd6zB(NEnE>OK=e@oS37SD6fN5(71$vBNFibqi)nfpp=s2Zd0PWmh!aOK+{w^4Fs=Xky!LMvsrJW^%8^ zZR^~wi_dN<--I_*q>EIgB)~TH$9Dy`T8vNsg|da6dHhj(#a>Ov z)CPhVb4O#7+6cGXMEOSL!u1?Y^Fzv}rilyQlwDDeqWjanhNF}@;{Dn=(xZKP6%yeU zQoL7s*9soPmFtdLV!A}AZCR}xKb8MSZ%rl|k^EC&n^##IBIaEd7ZiS$I9m5D#Jf9z zE|1~GHy<5eM@WioczFGrCHZj71j*;oYT>Q8UU3FfUiN+T?LjLa6K*Tq5$eMYC+$aO zu!oaiw&42noru3(vV310fkY-O*s4F!+9e4leixhK^DLFgEt> zDX5pz1K*v`fLAXDUad`GOCRFRAP~CsK#yFg?cF5DxH5TRNKDt4xsTI7a`Bz1bp?*n zE&$0y3y`BCt3uq^-J$kg!?Rs1f53Ht!g&Jw+*75r2KjyE8hr-1O@YKcE=72*xO!sT z;&uym8877ptfT~@nqvwyD2+&dT&GNoVGwEllEC?#6`v#j-WvCr6^^60e;_nrNZ2=J zKTxc_N+0K=@WCCLdo=BND*Q(CIk>!Ec!l{I#ft)jF{#mDbodZQD=j8`y24cwOsGX5 z-F*7hMoJ)(my6Ig{ffIqDnrjmGIBX{Nr6s#AdRm;;%F7d@>9xy*Q)m3(9qARLxmW$ z74rAu-7EKwsRGdsf^)WLQbTU6!#BG>DR^RgL9(+=_a+>B1WOULh|ln@EEvEo{gwPRDgFD%3i#l_VKgFwqI=PC{N`It9_;PhlWHiwQFvYYG0supIPdzM zs%by@-i?Nq1`kOZbf-XBh2*>Wq*84mbtF8pf+oV?A|f5M7pTB@){EBfvk zx5TX^YOnJLX3yC8n86%p3PSrk+=5=rN+%Z-&)+qsey40HxD!z-jGD@Uj{bWpM;Q*( zbBXM=6MGYg)2JG?h5FxzaVnV%dRV-*;PI?RKHGF{cwqAFN~~|@{O;LNDc|CcnXNM5 zrb@m$6T54auWde}`F%&Lz6eam@k2O0$1Sh?-J{VX#Szq>?74L*Bd_^9GJa1uoN`a5 zm1(pLSay*lC}9MKBko<^TYcQ7Dn75*ca-v--{d$&FY8y7a9mpW>j^&DK*dE@lghrm z^G7YZKk>Synpku2Vnn~78}+H*S=2UCX1QEqyY8w!M!CHW<5N~wWOzpQy1XVtE8>@| zN{x`64yfvz)m_f-v2nh0TGc671B{JONX~+tSt51^;n`1TWZ5nXjXKn*`3-yYzz z<~FcD!#lcX#W7lvpMOSiRh*>8=YQz17{F^X9DcqMBXP-1G_Pp5h`o#Lz2mt^H~W&< z9W2|>9V((Mn!5R9bu}|&Mf0!-TSGB#_!h%Y^MPB*)adYnHs?xg^WO7GHJec1B)f>& z!D@|%7UsA0MRHnw+OM&(wEhFt zztSg|Q_jOIpT(m^O%f1W6nw7!XJYw(Gzb2J3zKI-hwfX1zj2;0`S;*~?tL_IoP{p7 zHiFDic6?q)Gb7aP@@b?*cqk4R(nGY4go)E$q3=y`u82}`#9v02sx-nhqSof(ok#(_ zz}MdSvLpu_2gYh?B81Y+f$urkskX#pLvmN~u7xnY%!W(zUr-%vRd4i_bywsvr+GA! zblE&`mg?AJ6Bk2^FD(c@PM)ncr=ZsOGh%Z+a!`pXD2D_9zs>GHBRsTadFh;i7n7yR zc84XgOIaKS7z5Eyf`LRV znn$+MmC(E1vfWHEyB0QiS2eq9SN!dgKCjqTUtL6i0) zjSbuqg15I`}&9-L|}Xg3R?CKHVzSY;*TjFfb9D z$k4UmU>=FzEj!)9Cmfm50o5JM!(9jtnA(}HxF~2=utgK~4w$$F2kMoEpOx7JUz~xZ z0GAY9$1d~(gi54O-0SJL0{++!3KxgQ_GH||3B8L=JOb7B{TfJ3o$9)g+ih{8LB%ww`{bG?5vCS4 zj=ErtuABzw{xu6=ga&Jme@$+geBQGBNdK_j0!)xW4Mn>yYEwNJIorvKFJ-%;FQP2<2+H1f5=0)l|CY^H>y$ zb>*nB7_Brtl+RqPW!X&!v@HM{T9G*bTq41>B0%r8#d5q^eetD|pDwDV^4@F5D@W0P zN}j-*(;c`PZl81m1rE2`rpM^dRvsjX2W91x6*<*!DjVpB8SA(XNDw)wj~HTqE(oWR zeIl1&k%FhT8!^tmdN%2LIzSWY*C--=vcDn2EkJ^vvJYcWN2G!UENpMC43p!Rx~&(G zouR^7M7_=TYcp1ew0h^ym-JO}y3ZlOW;T7grF`A@HG3Xf2I`4-OkU>wp3CJEnG6FG<)kK-8 z95G^OGO&UPm~+NpWc0t4(0xSN;c#pU0&#d73(eR)dRXm~KZgld#(xlT)3t8h4PmQp z;ZiehCQc?oZyg67b;?X0J+d8NuAJ*RSS(TX6Y(_sljWV| z4Xk;}{(0Vg6?C3B)ft}y>l09g`muXwjTY(xH>34lr9k(fi0iVKaKOEC5Lfw21Us7rGX=fmm2_W~8DxVV-gv8TH@n2rvmf>R2|Ed0GQ|AwO^lUihV z`&2aok*wJ2qKhWq>VI!r|1nYDHEVL^*l8j3w)&JPRqVw)>4ZK%- zt=kYiqO7}ye0bq$%#4plwB4*Wxmz*@Gv}%(Jbn)hhn_F3SWhcewuF$SQX?6$x&02;Wc^r=cE2iN+z803Hwna>x$NU zLIh8=L;PZU~X5Ii6IEzBRIl=;)~ ztX$1zS$rafclm8^zb`{JpKirVd^-|O&NEvK)w3RWx;kGM`kC34jyOPlE_t_(`K6&= z2Ica78B#kKBPr%Fd4tb+E1s|=k;BR6X#bP$)zlQnfgDzr%z~QP znbvdUhW6)gI#tiqXGVV)&c2*f{mnvN`0ASfyXVX6tmXM10s7>IhZXZLCK7)Ke}o49 z_m{{Q^dk++FKsc}e|@IujIcErpqW|~MWFZ~Z! zeUCV~mNMI!U*%CtsIrTvPuzc5d+S>sp#o$)?;U4X+&}+4?(+{K>tQG0`v9C!~#L`hfUyBgsq z)(z(?QRlcJ?_Vn60w}_V=()Mvwed4=L&GH3_48>6e46}aPkt*f!*lqD55oh5Y?5(eLD|yA!WH=6hg|H5WxTs+GU1H1pZ2&%1g) zI22+CJ1dS%Rqd%=W8MgV9gsT^(&y2cekNsyT$3kLFYj$e~A5s z^^d^X^;KTVC2Y<28kLqLkFY{G#%1FXbHp!xVZuTJBxY{7h(FjGH#Gs>sT3<^LS!zmGKPRMVqf6Kc@2XZ`a@-bH^DS#Y-^{du4W7hU8DW~{k(&!e+kj%c#VPqWZVl`D*6SW%$_ zUdY&wo-w_#MSU!P=bb|=W}Sv9ejgg!$J{f{2AqytYMUx+kdhHF0%_w{7Wm!P;rcM` zPx2!9PXTKk*`FnU$C9`4{&se$H;5X3*mp|dPTfIE9mb10A#uB`*V#KJr zU0jdW^zPsg!!+?(uBP+V%aS`RRyJ`DCCN|BiMTm2@N_>8@%;Ucejndn=UdyU9k z*jw|{o#|fI#w&f{LgnwV*9G*iwzP0InJ3n2cN;7|G}=QPChk}XZTw)?R5-tfGa{c; zb$v2PMjqa}oyxw{hW{GpY_FEgY7bbmaP#ihh^z%o(zn<;$&0TCE`3F>_&a8$jhNpz zv-7@+R=qeYYP>P$!J}HUfv)MeZC6kUdTW!{wJzxY{zV6muUQ)_`RcOQjH$X#SWZA5 zP)+EyM&ZR(N79XTz~Qi=bV+jk2T2=I9$v`O^*FL!G>(7Kb09~N_OOG@X6(ZtW)+b* z#&)V*fa423V!GT}UR8Uia1fY+r&EK$@3AJ(GA!uyS5jBSYt?7I-zDiTt@$UEAJ9Mx z{>pf2P`uHHzwa6jR)Tz&@c%F0HRULN^-ghhnlPgSF0`FWhxb1VUz&l1T?IayndfeH zp3j#9UP~z*1o8W?9A2nQ1&OZVnkKb(iCm*`8(wCwxb?9I2Tsw=!b7dMy34Zhy5 zU4hYmkPg<0QMyT93#C!mM_1ECOj`XI$Nph4YW+Fonn_4%y)YhxcukqIJELRf>dc0B zd*=!qr`w5Tt?6b9Hfw0FrGv?v{fcy^f0DRJJN~bTQi6U>)dzoPSQm8H z(;chA#+!>|@9iJ6o+_3dm$vAVX`UCk*AEp}LrFOEYbpC@SYSESc@i+cxnTN}dJ9r7 z=G|p79&7TY?qwen5AJmFv&)}!Y3MXUGs9F{WE_Tpa<9%|wx3DsB6!y`qgCu&vTy`; z>&gTLw+NrUd$8o!58#eL%6+(>-|ZiAnp!C#%(JxK66m30R`V@>UT(XRWLAdXWE1pZ z15|nMUzmi8vUQt4u^5W5XVT_I)_iN+!;5jPV*=!mS0dsegUr?`^Ykmz(xm%()W>hO zP|29(IgbYzO72N8Ni~Dv0d=WlsYwxM*-J!tZebm*WGEY$57FxlDy3fqa!Pt< z^@Dhx{f0g1y#tPRVmEU>c#tSAv%`wV4N}CxO@nyit)T*;>}elvs!_^`1?j&rtm0;O zVboF*>{GwX6+6qJYTx4H))xE8dDmXbWfa)$9bZgDe+5C@AKmGujCpFh-l z>OFFgXNs-VooB}RD>(5MD!JI6*;4u4d?}IfR~$l@i=sm-VBJhu`046BfuYh8NMEI0 zGjBWbN++o38A$xGi&CMQ%#w*~@{2>vw}qS$+VQZoPjv<|?<)Hh_iQw%B!EkGsOYB* z;We9#m*oVv=1YOM@BT@Gf2Tt5l|JU9XUNl-_}?La-R(*kC>-ebPT?T{Y39$poX)43}2a2;5ss`1gH}-pEXB}F^lXwZ5J66e}C^70z&r{ zQQjv`)vb)oSACT%tPmsWCYp}ery3Io!Ski)Zw{LyMtn9SbPUENY9lUP8&`cn7-&y- z?%S2{v;PdP=wtdTF;hX*Q9-JXKXNYd7iLt!gw#b##snalb@m#3o>f?kRzi4_U)qV> z3&3|Iyqw_*6N$B;nX(%E7Dmv}f#IFQR9Mw=v^_bh>Av4S(*9XQp+>jayHts_@O|B3 z<7Q#4ipvj52QM)^!J)ej@cNGS`qLSU!_5%2Rx^0hynYZFiyfF`maOTJPkhGEsTEsZ zSGF-ykVHVf5^{08nIuK&F;pWWDZ#!g|2q&5J2(E#j6_`R4hkL`*dg1rxO4<0c!Sr< z5vzSA60H6e0_xS>KV8gP1>H_?+Tx@gDoD8LR8 zNr28(c^}@T_OeV!kKKRPcy$oc?Bd-^|0wb)ty;>fe@F#m5V+Y39_`iS|NV4fkD5Fj z)_#4tqe#h;!K=Ms8OVEZH27LaVyUgxPCTK?a6vPebG8|i($cp1QLx8uq6$?vmvbMb zkb4zDGPU#dN|FsuVct^GJ-U9uQ%xVXh`nhByEmG3&UWgX@Kq^aE#Mbj=dxRW%G|2+ z;dVEYw{VYdSQAf@M&#q!n)$bXbK9v&(ANNBqfR%2 zFVEX-En9UmVX-P`1ae!YBKp=Ya-FyoloE$hHhl7LtiE%Qzd z-|w~Cl}QBUoGVW%u>MSi5e`9s z(z0R#yc;=Rz26V<$hVaHRY57mCPkZ&YDB1jC69ofbTJh@8~i3$W)*$f5*mQg(b~gp zq}fpp+N(ofZYWa5@M3QNzU4_#=wpA}3e;)LCT*#=Wz7E08h`Um)Yo(c$i>r21^rj7 ze*-@PC?LNC=AtejzH|0bz*I=t9Xu21M)$U3Ki&Ydc03>ATQ!)V_4a;16KUjiS6K2; zjIUW91({0q;x==dxK6-M2DW362|J!}Ia8NR`WR(ncTz~AL!~|7IO^g`iNir3XKx-y z7PxZlMx2AxT7RJ!{$G#uS6=()$Ml-}zr33_-XXev{7<6wZ_*|50Ih!aP3_;uF((}L z#Nid+o`cM-B!EiWX^a-5g()sq`<+()<4-RD+xa2TKkG26C4p@?{_|nfcWlQB6QUFM zfqFNm+E#&P>uzi!mU00@rY8u zTwv=Cu`htqMV>LV|9Ol2^GJp0<+{Z+BgqF(|HEfc3sc9^F?H$Y9W}Z=jo5B`;XFiY*NPok=mXGpfOIpSl8>? z>AOln4^TTMaGL;Wv_F)b?{`l;duts)KPv#dasorWvT@tid%fI~mIfHuye6sde@h#K z26)hOyv}XV0BLse!NlXH;D7&;xeMTM6Hb#p@}!-dui+f{Ph^p9J*7t7`3m+6Z9$dp zIv&TL&%vA73wV>RIatvm=eFX->v=)HLP{mG~TJ*6>>{`S7ENs z?djX@9)yAW_~oKAKLBE!#y!NGX1^aD0uQ7_aBIJ_qhGd~sw&}Ii8ts0pve-HEVf^; z>RA1zjieCvtRv{4iF8m57C8YZgXcNhecs=m02&*Iag89mm%c^_anx>=%FG!G=r-N* zF|FkAz6yURI3b(DKYTK2(|A2{G8x7*GiF(TJW^@(3-4W}Wr7;ZMK766onDAtFV|@N zW>MqJP0|gQejAjDQKQbes@ixBxbnOJ6aux1gR ztMQ|79E6kH<;iw0ihPY|*a${fh{WzgPW29&fC#2-407RL!{yXDWSi47i?6Ce81glBO`INHL0pa7hDwSATqS@Ft4 zXHdLO0zDDDl5AEfzB1FV%T@gW*jjxT^rysa9^Ni;Z{|p60LMcb9$|IdT_FqA2_>)$ z{Wy7+>b7IH${eay-dHZ`W<;JT%xTPKJ=kCx0eCAnfR?coL|7|qp>l0t{EY~4x&0%% zUN&+E1PM3T=P9{PszV5N>{W@ply!j-;%6=shlgQT*;3l#?t%6M2uN}==oPCJ(ELDF9FyIz80Mv`X<7R7$(_~dR$KvQ8zGor%h-PSt2)p$POw|-NI+EwsTSUQ5#RUn z76`c+;A8r zs4l_D9zJiqsKK1ON1+bOrl#Zk#0 z_HbTB8zo7yXQsM5S9Zd=d)E$c0c=H(kA4u{4_G3;e>b^=n{-zls zqKK|G6!8+-Zc$Wk3^bL5AE#oEDo?3u9f1<1rsKF#^DLmwRpx#vMsTVH(h%f4fJx6n z2%nY~da~F?wyPJZml^Z9^t_`AxrJdOBMjrEdD9|DI9m2&#+6CxV?c3OT}O56XECaf zkZn-jPgB!*Bx1T4QmY$!NV*Kgd|@W8Eq|-`GzL?TWXC?x*Y4`b&vWQrc*c+g!#)@n z5-4ib{IV*)`9yQgMOr6cgiuvm4U|g&0!dO*7lHZ(Ml@-$hUp3n2fcmt;+C($9&jR! zizcO}`ZI4Soh0&LImBdr6ng*b1S#E%wM(GOGl5u`33~e^<5i!R+JkH`_6|)G0z4?$ zf)@6ba&C@0807{UecUJ8$sBK`jtZCTP zb5(}S$@Umy++2Ix`JH2h7xZA5zAfM98r2*O-=B(}x`W|oxd7`!-yROKFRIyKWLgWu z=6)$+x!VcIHsMiN<_A8Vv#f@rk1NxZgxU?hy5^Zhty-+#T`EOJNmc8Euh|-kFX5WT!3H-oODO0>e7$m6ozkFVaT;#yfrVOXP>lFwu z(Pv;W`wo_kxx?JPVWVdOwB(kzQMa1vCJU;8KIMU{3vFL=<<&$oM1Ah4tLhO2uG=}B zP(aRiLRcHv;xz4pPyo}XT&vdcp1AD1%mRJj%OH{DBLLFXnhEt8yMj%BVzjU&8%ZyE zSCTkFmIWprdq1YTtKl^5U`5G$I)y-7Jkocc%Kvlnqj9_;JibSQ553f&GrS^$hX}RfQ|Rt>OHx^0!rA=-4DW<8t?pBgDsh8jV+Q$!xpNuMpiLcTM3IVWHUm17>r zvGvI%aJ1juzuE&7*Lq&&+MZGrwu+s-jy)8y`!4BGp3I={buX2zaCYwi;mMc*-sXsm zz?Z2jxp6I9n?;*Zf8yJ@c;W>&RpA2c-Y(p4Y!__B!vb;PgaJMcK2(WKCB&+xJ7l9; zPANw30P>uJslDGCW6#!VF$MJUd-9Jld*cDgZjZF=V)bDu6$4mO_}NbO6sH|+1a^l& zhcin1H=lyXX-qF5SWip^I)z!851b84{_Qtf5h)TZB?by-bu9DJ~%f22s~ z%_>19qd@_vXg!WWDgrw~{}-rrGWBH(+k0G4kP))sc4Ax)hK)nR0T{E0UcpCRtS(%Y zE9=jCoc3Ur=;dEM%?*83n!n2OEdj%_r19gK;#yl6yJUS z&*}c(5P}M#ob(ZJfm+WP0XV$?S~7FWBB8ZYRrF(w1wTJ*q6xz)@`j_|GJF9b*gcxj zS6|GLKBlp!^O*M|%1`=&?fWp0SIdwgQs%Vy=3lb_$J0Nnv_I+M{$TelWdXUiGFUfs zm+=i1*$wqW_}v{xURD3wUogE5iJ--+i(-hPmCLL)u;=RK z#;)`nJcX}>#LUjiur3TS`1oE1W3mmFczhro$=lW_WsftKOilcK;=X1@QFU0`f~E8? zLbGU3@!?%$6fFuz)Ak3k;ljV;XLStQ+;{uq#_cI$D#O-5B`JY(3ThP^Qd3oX?Fiml zj?}@zMF=(3DGyPoaFtNN?Q9vHDdZ`y?GLL-?t`JgYul7-Fhc6>=morm$aQ4-%FMqm zH}t>V%io~=&YlDFV)h8CY*!O6R&N5{%<$^wJF|$QrJ3$057Ak=QCBN&o2T#U>vHyq zcbZhUOj>UVzk(xa&H(Hm++K%8vgkBChkd#joxAyH!Qp{l!q9U0Gn!6AQOG)9kt}S_ zWqYFHwsEG-K!%^7)d)m=N168}C*?hx`}19XFJmj0X=eQ~O9(Pp|F^))dyJxjMimT$ z|F40^6$k>4D~Ch*0sN&{I_NHswD)7kYbxq9pL(e6u^S>`o6KucpF{}Jd=PLHA9gU5 zyDP2%O@JlYT>-*ELH;RAgiuOkiV?nieRbHc5?VU)&Z6BoZWrJkn0tgSmdT8*Qj7?p zlPviNECmiFuuE%g=OBl^g)!5XQYUg-nfsMXd+qh`;nDVqw)vT6eUmDIsL%EieaS_v z%e01En2zMDM?OINyepr$Lf)P!dMjx2>2^@V$0j_wDR;X+*QaF323o#;+dBxI%Lz4?>h^K%FqzkCZzOJT?Sg~ZiL?UG~)nP`d( zzG|aixxp02wH+}XGD7%`u?@zv4;^m;t1GwHcVDI?QNj#x5-ObX1|0+ZN&zl#thrzXb?vQ`~KU>uQuAKbq8zn1L zon-q$aYsCT3mwL31umSCijcLz?1<)h4i*+bszu5_BB9Ni1@9{CKha?s+WE8(hn|5o z14CF;%zgE{hSu2C7tq>)!vbTbc_<(JMJyl@v_pkoc3d;m zQH!ckkv+D=(ZOt{(ib37luvJu;r!11Zs*cH_Bg7YSX?j*%uzXaG7#|Sc*{w_ShBGu zmOed}vHYFWi$UxJ^T7w#y3`zR((aVrNEXzv8h1e@xftu>&6`l{sR@`!t%zZu zGr!y!O-eY0Kq4lkJ6o^bFuz<0WE|A9xYl@}Gs#s9_d;zoBJ87N5vjp1@d*!cDTSuy zxJhw!lKsa_m%Ba(8KAvjL|0~+`S8c1ted44{ljZe!3}QJ`h~e3A`K^;iKU5@coeY~ zb^!AWoN1wvX^U!DdzMSCIGddt0TB1_T+9Y!R9@#wyT{@BqJ4QEpuq0UrEab}xa6ia z@7M2ZH2SU3GLuWVyMuj{CBb_;)r*}GKg{mJc>;KFi23X@&1M@s`YPPLwn#1V^!V!AB2Q(LqtAtO0q9#zcT>~!dV*sa0@w`|c!N5@+ z2egHg>wEA6r04bVs7jkxElCSc*Bnp?Y30oXx9RJXeqPa6BVZ*Ou{u%Hk`OKuDBZv_ z{eDobu!>O#@PHGywl4AzXC^svFe|iz8c&n1-eD@L`?OMQp7Kr2i@DHQK1VZ0hqV{HBNC9{;~sd-HIp+y4K*WKA>^4MN6}l(Ea6Eo)^hA!OeQ8M0-| zK8!VF8x%sw9%ISAWesKDhLC;Vx8FI}eO=e*^SM9w{ky;4n(rxJ&D;(E3YTaW&s2WUn?ZSu(odSK0HSBe+1I~61YMG~p|KzK+#C0+g+6dv zo4C85L~-tEsZ|up`bV~gs0oNQFUB?x6c|cj+4DndIG@*ac49;YTIFeE=rGf1`a8IY z^DjPsdB@lqGLEgA{aG+sN*SWOlcW>%fzTND8%T?G*Mw~1_XKSy*MZtOB8bfs8{Eox z!766peX?Wg4Tmr|dP;ftAO?*Ed}uyoLrlytAilkxz_fGl{OWsSyks$<+3&rJa7JRkLUobqMNE1t8lSJ z4)<}q7>dvcXVQ8x}61wL0r~>4z&XFF~Aj!(I&9gcq$=E)g5X z-R9m0fg3Ax461o`w3jVu0K00hwogyCzt;|aafhJQcen_icft>-ch?x5hw9;NyR0vK zY@V`TX?w^2dQk_;!E>H$xV__%Wyd?|#JyX?bJCV-_oQd;U%P)bNr7NEWcG9J|K0m7 zt;LQXq2@Ersu1$Cy>VQUIy+EvCu$NevFv#^`y2&<7(zgh|A(ug3i2aF$)tKvI(XZ~ zs=~whyX$oqR3fh5#ZM0y+`fXj7fJR-JcJvQ zJrGAks@%35u#J(3osmp+@-+LY0Fbl_#S%Vc(T2%OM#uXbb3>*P6sqX;V^F`VIVIqw z`#AuulvwwN$ZRFYJ9jHE67F>ay+TB3b&@Iz5G0hKggjzwaEJp<6A)dmFgSwIe&XrL z(P(Y@nEs7O6|F8HapztI@9vY_Mea|9phSJ#y`?om!G6Ee>i1OX+M{+imE>G|f@|6r zE#K`xue4dHVCRz0!o^p4!F{2Ie!iZk2lJU=Pq$bl&=O9oCfl+ z^Q00$oR|ZL#APG6?Z5cSP-J!!xrK(!s5l4Y)%~XOpL~8w%pA;=Armk6xD;T3S~G`X^uj`@Q~a!{ zDKMPFe5BM`h_SowXsyv$NK-S3cxd+Z<}m9g8ZRmPS;X+M#$Y??D{*m#h)% ztYpB6F+2+I&)=OlY7Bc>bI`&oWqGRo+)DpetkFS49DWr0;*f4w|2tEacAkzgzQ9U+ zW)rLSC++ZmQrJEr2mMYy>}Q^ANL>!0eOm6LtZ*4u`7t0g&AolVO?HJPa!P>U<}i?K z67LM?uwF6$K%jfZhTz8tTEDFy4sXt^fk(W;VpNmG?kJ+Pfff#J$Di*!-aj-H6UeC8 zf5ljWZZ}gon!VnV)TBbFp~yo+mp~Uo2}WwEMtof8N=Re|vO7bf2ECq{WcM6EKu>T6 z0nR#kDBjy82w(XOj65}G6J#fS30~Yufk1gYIg?o zx@O}HuQQC~XmN5rzl?4?an#O~E>laDoU2^Q=Zr_{s6PpjcJ9WA4up+11DO;rW}@qB z+xc{VlAza++w71t@4a!C8}q`P01u<%d@RylK_^wg1jP!@4Cv0*U4^d<~m7V)fL=X6VarFpetS+tg%5?5i!kY4seUiHrlDkn%fo ziTF7&*L9Yws|P5gUa6IFTL}{?OsV6nc7K}u=qk(8Rd;a3oAFv|m- z6Rb)Lg^266wN1*A0V#wHL~=!F8lEz5L#Llwb6~NDHtU2)3wdbz7tir4OR0w+{=l5h|Ad*^!J>fM#m ztagG0dukTQRnLRjxKH7ncc7|GBCJpVH2dfln+40rCG$X@9@;5hU4WzGnKa_aG5nsE zLs*Z?3?koOE%e>kucQV-%Ez^aum>4DBU~R3dV(o~W-|SG<|IK#(#x6(8N%O+A7(p?!!mDw zKf7_?F}0^yviNyAAXk9?Z{MvzY2BL3)?#z6K>^O)7cK(~t*TS99YwQ{HWmwc+NH7e z_;MU&hXOga@yejSV_3cMcm%%J6l=P&O?5~G0YL-A=Y93QX-%ybi7X1lWAU5kT*8{tCvHnSgcztg_lN zFoqNja%4%rLj#lx?3-O7S2>sOKp(<$>^A^mrPJ$=7E}!r37S&c146=RV;W&`O%jV8 zEB4(D`FJgPGPB0;x2R;i;GeM!t|0}F>S%KsH^iagD~qWUr0o=74No|>0h;=>l$0M? zsX{esSM~V-oRqeGk5omQrxf&{^|CTelZ2{`p;wiA!MW3)t6c!smA`1#NIn{LiOvM_ z<|Ywk0TxjS#HbEY2%p%^IU(B-LfL{04>r$KEl+>O5M(cCs86DcqxX)$ItVb!QO9x2 zXV&1&2kvxZx04GCB9~e|0%ifrJ2RGIA>g}GHrgH1AAEsQqz>OA&0qP462g&{@rM@j z$N59?GO_M!e3;CA3WoP5VV59vtSu@R$KI-eTV~<9VDy2xH2=z_$014k)yl}vG4T6$ zpYl|%`-5gB3>#0I6wjMpaDVo`ovfF0!^T-M?cq{MAt3i>7Abi-DoZ( zGr_R-Gq>jMZ=_^q=o`=YS`W6&$jmqc-OTmn35MI>Kl@tnjopt+udFm6yG`YHj_{q? zf4DdPJBak}Kh7b+%e0DjZ^Z#W$9V>INRt?D;`@htUEpHa7aljY#@ZmBzt9fkW)(0y zW7JO+yGkN0EFFLGEKesm->)7s-i%-0S{6sGyTwSqYtCO46G_IozN1bSbK)nJ(tqs# z#}4jn%$;UPP(BG7VJK`Ly)ymYS)}B z?$S*+({Us6<5%EJ=oX!4SkkEl4cav!1KerQdzy_}rp}kYdHkvN4^K#@B|Kbc`QKtp#f_&!V4;J+qQus6bv?L&t{FFG|pRoY$ zDl!<^&f4T8fQMOMR&0^|(Uu4J053r0Fun@HB4;%Dn(pj^$$OOwx{+4Zlp7Lii^T;J zTdJmkPRwV^aO@j$(gP4Zz6I%o#b6ei;Rb4L+iOkWs&@vLZU9g>imk8+I`;y|N1Akj zX6Os)HkTrM#;KtzKeY`R zW1xy_fIKGgw$!K%C_6CmPX}4m!Cw_m=B3Vx;_m%W^<*cqd%tbo-sO$j18JLGn8pTz zVL<{rxdl=hFzB4SzM{xC+nE+-f&BBBGWJ2Ne(JoN<}1{g$wqjx^0|D1-=;H)njz>y z(TkVZ>j(Ah7t<9ZC?#dTcQbHtKLKT^@bLP)IG_?VgD^?bv`2jpc!nuhP!?T@2|ymr zd&||rCPbqH$f}iyZJt$c)yJWbcW!DTA<(wBS-|+%RD4Up9``bkSurPLAa5;~{`{Qq zYR&IGW1$OlVAko`(ztUBj@6fpxP|Y!rUchEH&-d%qPTbM+C(qOc^GP{3sAv zp1Z@XlBsxsuZ(+>s3%sU|Bth};`DH7rS{tz3d*`HAk+i@v4r<4Oj50Pc2-MyTn?$E z>{%%d1B-B^8Yn7rfcq~omDrPPabNZPaci$&{a83yrlLmeO50}M!-{B@#S_^+zSSdH zAqG=Z_#x?@#@tG^fc=`H>-A~6WT6mok5BYF*kki?)iI~|%e|KI0*I%jZM)v9N2M=P z9#P)iRv&$GY_`%|@x^wuOq5=4R^0oEXVivISasVH zVBXDIFD~YRe!%%uvG)COl5Lsp$Ta<2mW{09U1-<%ud<=WjQ-zRZkXbTm1gP zFPR4_!TB&z@Y}k35%8)0`vVRCt@je3#NoQEm@H42!*w3URQ%?hQSUW!E~FNl&d@Fp zFp1GU(-#w7%FF|g&$6!w4PFT+DDf3e3k49Qm_hD?2U z(QkFDmE^dLnst8x-jA|4u<`j!OBicOyRV8|nq3hu22~h8$f(cllXrIE_Ppv$N>aof zg5M8#z6vV6{gqE31(U;D5+fCcxfLKEG0@SK9zzyfHzbfb9 zG7~18n44dDyBLcQbZM}=QrK1iP|6!0a15l;q_Fbhp{p9NAH$96J_H4{=c~P41r2)} zRI}2w7^6fRM<0<7Z@ZuXMR; zHgK!Z3s$}>14tZh0)xyoKO0k>7m;QwDfr-slYvU44R+=tYy0w z_}=kkD1`dBUt1Bq-Qak!FXjQfqhiSag7Jkkq#P%{AYzn_k z)e|S8bY!=svEbTbL`Au3OIrVy-~$6ag$T2kh-VGxC?7$yD!Yu*=AI!3=MSiRlSbje zU717FEti{+HoMz^m~4glZJdG<YnPT7jxp}RU9nb{^cm-jISt1_by?N zzl0w=1V8uv3_);<2ybQJSwc_3prt~kEdCH|Fa9>-`oU!q1z=yxAS`p&hPp_@2 zc%WZHci~nl6-moSkm?-5nP14#n_fE)3I#A?7!A5>$6HJF|B3AUE=r>$O&gNa7m|X>2{q9p6L8T;eMf33TfFB?K%a3;) zA?A7qGup;Qy%laM8Sm=JR&zK(iCsPSv`NGt(Okw zhb-uDFqPLuH|NxhQp<`orQ_a9HlUr98ym!7TjKMkFz4dz7|C)Vl#KRR@0IFKR$TFc zQg$NI*2u4$^7GpihU+?)<_oQgflBDiC)BOM4WStW8}pMk=>*HJL~|NiF^vn;JaTW0 zi;SL33oc$j)>4T_W&uKTK+H&d-axozoo-sEMZ}xW@e_gWkU!0^01O_JzQz*zs=k2& z_PL)JGZjNr12jMbdG#c7Pj$o40tB^_Os$1+nVv{Hw$<}|%IY(psql@P%Tw>PPGEiE zpmuiff=RPJbs_Kj#53fm*3jHXw1O&=9Y093r#+yT#cl)VQ$QWovp0_R5#;26;O=Uy z$nSk}rwU5bmm(otmKCE`PxcP*go{wf(ucK7#aa`pD-4;W7(>tVh#811yf%4VxWQ3M z$Ej`um`PibRr@dP0)N;-D2sNt1av!oBuErU;L*&Kqfa#TL7pfJva0m+1fY8eO zRbr6!RzwTc7zOgwY@!+SW+UPNv8T=;>={Mxi9Wc!HI)taMWb$kcT5s~INtW5Z?w&> zQ~sYaK(m^HJLs}q{l%07v|5@@ftT~gr(Y%WRoy1!wikT6J{}|KKQL|K3h&)93M zPHt4!yZX^zr&kiyMhdmrhv(xY;34KS7s`XFCk3AHJ!wc4Wu&JGV6@t@ebZFJbBS!s zDIy1FFHK~-n|c!xQF60=jK=Ma#JL&PD#*~ z7u|z-aw)?*0(CmkWGVERee#X++Ng_ro`=eOQ7tm>UPKMrGvN#UVEoOJsg*lHosfaK8RPpg|Sg@?l-As*2km^??8{-&v6n0Dp z8!vHlX7Wwj5m+;aM1J8gt*x&ch0HV8Am0nrZq7ZftNQxUdkV;vBum#hORuSvj-zwk zUHc6sK~(;gd~d{dJLZ{ELZIf0&)dXnCP;Q6WjCY8B4<@S@ree+*TKCOlHx3 zw}j2pYkO(j=Ibzt8_|cB2p5x6hc4p;Cg-IAu6fCpss|%%GuJ6=tLe8|O;YIHU}h7H zS9Nzk$R0XAaccD>hZfcr5j=FI%v^QVzL)e~s-&KvhmRLY&%x{5mztI~wj)#fi;+Xd z{hkg}css*O@=t32<)YhX^2wM#%V`O=G)_66Fi8bUnSya%rGJN>{;k)ki-G>?fn~M; z*u8GPX{1Y&XmHV$uMXf;*JR`RZHD8uyI8XxNo0#iF_qyW&l)p%zL);Kik(cl6b5H4gzJRPR@qfx9dQz%_9JVbd z@5T3L!-8*`YrNp+g6Iz@szjT^x^xF#j=aA0M5O&-K@G8Qf%`&ETWCyxc85+gOOo=q z*8WaIJ214JR38!y18BLMdsAWieqFpH>ow!hkKD(|b241$lk}Eh&34^Yp~PlS$=t)X z;;`xCy>9WfU!{zz>7DdLmwbrSxYJwA`SSL`+dqcd zfjgPzoI90igJ{*pP8c?*=%aZD9Ub3zkpJl4mGOQ^QN=4T(Cd9nL36yNS;hfnG_}Ay zGJEQS*s3eD9i5~0bElsskB4(RB$b11-pZEKQ|0EHbw3TDPGX#&d6CP?>y?)3gFzBTm*MH~Oul)eZX!%pMO(M-oh+(TEP(7TlJEEfyP6K+ zGmF(_A-ndQS9mf`8)h#0N>4BrF<)8jC`G2+B}-Wu#)Nf=#%Ezsqv|9`aoN{<3~wOO zDi?;ne=87QjHS@}EzHf;+6y~TaT(hw{*4Z$u!))VEs7Dfb4>{(Eq;`xT2Fi{BZ3~i zAMRphQ#k8;IP2CrX%skbxhg+KZgm!_-Q8Rbj(0t%w;n!R8&s%4N#D=Ax^)^w0dwtsOOI!9*6sW~4cg_4qXRpTyn&{V7KnD3d;J^!Ku;vyvA6 z=BPfGAa5limkE_(=lV@}h1^G-Ee8DDI`7+99&EOU$(~_*4X+WdK|;rc&LSn3jWEQsma2GP)vCs2-ht z6i2;bsctvX0YX*r7~Y%D| zPA8extsg;aBX!AM!&JjX6Hcob-$k&B1!JRb(ThH}Jy{SEyFK;ngrVOwx@|HzzhGwV z(sjY$C_4f%%CXZ-aG3qNnXHbcO;ZRq$ZBtLzG7`3Huw$_PD#hlrig;YIxi0uIrsY( zMvkgIFtp%<`Etlfb|-{Y)B#KfmM#x8a^f~IP0Ivb`7}5ZnHSeHKKyY zXi=uOe6^d5k+_$ua@Sg#0j9=t)2$DXm#qw=6+SE|ll)koAtgd)%;=jb;0+W4!sJCt zeUelNf~>2_fEZtp(eq zBgTBvg=}z7tC@@@772|>w;H-rBnl3DcmO1aP8P0oXHHtiS~?Q?*w|@lXfP5MclIU= z-0tBMsSj#ykt_i8L;c0?`f#yV;la)JU1`aYmxVZ|-TH~voL#S@skZvcT@@@s;Z{AU zAHyOD2Eg3SCWdNt`XuDa5lu25zcP6;k$hlRu}YhAE6Hmk+UE(otMpPV8yq*Vl^r>f zo5G+*B`ET*0Cr2M|{nv5AQ~~CdJ4_a3}B_`l2UE zFPMtak8${gr zO9isn8OiXYcOb|j^#o~u-^gI2dR|ImjrxWMu%{*8BZz86YKzc3Xdm6kZzdM73rF=0 ziZG>;-=Rdwh>I2&gLbak?Y{>_4gt$P zvf)FNPfCEKv530KEs1(~B5fZ~#c=}ta5r36qr#%f-~CQ3s+(bcP-<^390`(fiMaY5+i?6x{&5IL( zXl1rHZH&aLk9Lo7bE%!=$h=qF<_?iuWi3wnDmNfNgi#8^3U*UmqeRuYmO0kbqV~Hk zw_FgSMn?4*eE*0$h;pNzxd#0bDcD7zD`byXJN;giL{SlpW2aJ9^erl+w(|TRV9AA2 z?33`#p>fM8R+_qV>tk)geK6f|L-c$LH6%>B##`|4wd#ADm|mhiTK{aX{XIEJ%Tu2h z<~38-8@`4cown;EfiIhk5+~X>xlP1p`Id@uOSSvk-HRWLMN)Nla~I)}vy6n{Yt~Ds zR}$VE)fXOx?~OkHAW>p<^VfOkUAu0=J%bcs>!kw%%9vL9F?OS?HzLh1nR;~6kb0kl zwWYOOo6y=&4L+dvye{);P3M}V)TA&Vz4rG3kHD|3kCay}MjW!3GMF;f3vjXM3*Gxh z6MC0)(qJl&e&R8@=&f5k`CKD1&9slVbl2NWgkV((7CG_&si6>`F| zE=6FSa+b@IyI!4*Nh*KRym?#g@A3S<{s3g9QZUJ0Z9EaX1;G?sU#uslA`Ln=x^Qlu_*)EKpy!&s4xI*wcv8gZCkVhw9!S(bgjh+&-ZcV0~-t%kgYo(9sax=%V$ZrnCU=Knxq z@Nx|U(jZ1!sG6=DyhPUay})$gTEiPVe<6kHm=s-RpQk($iUX{M0I-;nsruCo+G6X1 zY!K7py6mFH?6Is%YrvESqRK)X>AK%Of~^o5-;s5n=kLjsQFTpz3~Q>f@s)!&cmwcK zTQmcY-Onz}D-&o4$rwlT(U8gjQa9#tXZ56j9j;-qr69XYu6>-w`(T!)itjscI#_MB z1lrf|@*4&Y|ELpnRwUb?Ll1uskk(&du-rjC5TN=Fr~A_L%1HV3#~t%Yt{1QX_~sqS4orF-b%}kS&bU9t zfhsXdtV{j^=pz|T{X%f_&-badQjiOQH31<9yCQ`8D33IZE;1({2ocOZO}~57RYuEf z9g9aYl&J(>3?Po^8XjXFMf(cY^goN)=R*)QniJCu3;J--oo7OVXo93$k1~HT%#njn zn!2uQ4|({sl_^GCmw8)A&+c@IlTepX^>=BUN4T$b`&+F<@KCRSzPtkDiCrK>5g-{< za&jH`I?|FKf>XInnTB)~I*~5ErI4XB;HUyB{O4-Yt zEldJ(4XI29p`FQA0pPu;#ZaNKXi!WQPaxx6Fw4X-3@&>d?5q*lVCt~AX+SIT{)ls= z#%rlvAa5%=e?HnxRQsU(!jI3*8O`jGIe_4@2T$^2DBj5u z6{0TmkMTwbJJ`{^wtE!^Jn!84E6WQ`XTmRME~oSO6`*C30Cjg`A!gSdqmO*$ganAu zEU865cO;{LMW`sSjQed>1M?2ChN_6Y2mYg#R?@8amqA2sB2xfFEEl3k`dMhLlDICP z2mHc@mr$-W^Ibr0KTXS@n zeCWAHd#cil+(YFr!3fVsM8jJ2h{di5#C?#qquYjE(A^}yhiMa}EqpD%0lqwWde{5Z zV~KE?An5rjqjJ4Sr#J+kCVEmt8`XeE?_-FLPC(d?O~>?@hnnbYjC9?KYNR~V{n(1L z2QgaXy$UB3^mbo&p7_-X-fGx8%dYGwmfV~z0Q&)(^Wk5F#qH=ia2!9s?zyeeIF{@} zV8iyMTWo1a6qwn&mgjDrwrDB4nRj=1B+jn`m~|9kQ2E2Iv}ucF-s~QuP@jqEkVn++ z!K4(4qlnPB8%Q;~loYHEn;TEEDGv5@wvcQq;WYV~5f%(^N1jFjvU-Vk2Z*G)b#8wb zN_>C^V6bvMNv?P~&(V69e9jL0{8nVq{Xe-Se9qLQ33R^@|M_#-bAZ*S(LRPQ{!PGzE$$Bg`-n1Le`3u0GD!`YpY>elFq1soc;lb$Vpz`9^Vtu%4A!9e#tJ^DWymJbNQNgLg&yqPJQQI5T#0kX{{pf z@gH%2iezRHBGV`%uO1VFn++Z3gXCQUqw0sRA9m(`g zInnf{(_rARjE?!DUGU7hBu1FA!BD>{_|u~-;yt3%8ob@Q+;03zL8I&3%g5?qm5Ta?37++y+K#byO9;=R25PQuF#ZEWz-$el9PMz#cPF91Jw5yf^1v#n~Nhy0wUQJ|X zB$sH7@R63$o7E3%T-84Oz2*J84>&MDQ3w#|hyGc~sGE~c+4sJex!|XcYo;+23}STF ziT#$u&qBar6iQh9oai4v_cIw(E(XA5aw!~T&4S33d*%BkqRy%1B&n9<@^#FNYW&(U zlgGLbK90tZ&G^GpW^%KWVjRIfKmZcMghn_-g!6^4gCZN84R>I5hxHO;70jD%7?e=X z!O1m8gIk(vlj0xeXy$ z8Q4K z1h=0L(-c&1-me;}W$<}{P}L*caak^ECC)Mr6+JuNdSpP1{945n%MwWufeTf}rhlZU z^#W0hHqShFeq!#G{Jv+srBIo-$nC+@8bCoZE{G#HYIKTo^33>VXdYH>y_qTa*BcT= z=(>uJ-mH(Bh``75fY8;!i~5bS{h*E;E{sx$QF=GuB+xC=7<%o_?RgJ|5)~SaC(DQ9E|Wxq#@)gF zwqp`ODybYi^%bJpKRkp~;T>~)HT!Y%zgNerw9W1;J^l0V`dj?|rw`Ok@l}s$jwaE6 zj~vN z`GGa|xskv*VRS5CCelB3ZpoJjpKS2OyZBZY@X39-4{IDW)j)8AMW`$?3nbA+FF-b1 ztG?(jeK{#e$&MGv>u^X)qZhuiprDY_c`wPpGGQ%WIibh{`b`_W6{Tu1pIk(9-! z^7mKJf5p)FK4QsHn_;`&93Y0D`mJc&VC=_`twi7Y?B2b}_MxE1U_W38bX!#AAl80G zbj&2ZrPhx|c~08WE`RKzUntHIZ+Q>GcqH4}fqUFo6|jqsbxli%SC!>JWZ2kF)NQ}B zxa>4g{%-!A0SuZHyqpU{ei-y~z_C0B5Kdv6i_^YttH2^>3bMXn9xV#$5+s3srtZ7T zbRN~QD5~2zw5{H<6wVqN=3l-$-@MLb@xek7 zNtJED_34AWHW^LWd)E8g_!WwE0D_dT%DWX=*FhIu=`#>NOW0bZK1o9eM}6#u7|fw% ziHdQKS4U{pK+}lXSOY-4AgJ)vayI852!gCHM_^GTR)*Xv{3fkA^+e$=-aNk4q9lAB zH;2xavV|KxD>4aC3D=?TEo0K%{!r@1Y5@A}p~k!YMEOh?j9PNm`V4HIHHwMY85#yU&*Ro69o!SE3yO1)JLQfUd5L80`5lh-N9 ztWbv1R~w@@LlAX)?V|panLDsK&9bQ-9rtYQ;!O|{=K1yF=Ooc+;Ay3s3*hdS*m}4H zdWeFzW8M~%U~--pxx1KK&^@fr{>f`7B%RS<2w!yy;<~SBzf(%*~jzOszChgwf6GacY041r7=vRN7+BtaKtgi za*deu^2jQ~B*bZyV9NbMw{PcENegw7eOQ*KF^Fm8{cOb*?gm?7TP8qbg+KEi7I$!$ zm^je@vOWcWo;wyBLJ4#k3T`QCPDuy!FM^CSyXfh{;Qmasy<7IZvCPe8d`CY3qHf^I z*GPsv<{$LaKrh%c(vXgM8o#&_gk6K)+HWAlG~@#cw5cCgIIC}^te*qa1t0Sn0{;$c zUu5d;Tnn#$A)YtCeP_Tz%Vo^aV^4%(g4X-(G(KH#XKC>ATlt>`z|bC3TRLgUH<9_Z z>~94{9)bmXm4gsBZlcG16>C%iLiI;(?I&8kO8IHP8)Uh<lDtKf6bbKZ)_7+W z{TbAb^9*n24x}Vr8h1}u^|#FWbV(0U`|G^?y3-kF=w%JE$7hBrt{V#441EXPRO|Y2 zico{<*UmVPch)`Wul~cnR9FeNC1!eYY7dZub4#XA!PlpPi zDbv@2)I+6TwKr%=vO=n-uP3rY9#6B)5D1R|q#eF54wSz$F;Wa9QjA0zM&Pp0*St@O zZDsQIm}!zeaO&3_~iHwyif=pU}ezg5~I8rpB5GeeCzCi%TFaGQY6Fo`%#f z6%ZRoH%-&@j#JmFjlDo0H~wXFrx_eUv)JRztM}M9j6*jK8mBQ84fAy3&Ushq@zRew z=$%Qr3w~S(uN^CYOR#4u2jR}vTO5i&9I9*99Iut+i0e-cJ!~NA?#BLPZ!R=$bihoe z;e{Wic0=aLIQMFtRx%Ft-9P)x?YrW?k){*|`K++EK%Tw| zM@zpKz$1M(}x0pLu@<`^;Q?1u{>P@(rqp4ME!mojTwSD<5+} zR~&D4P|-1e-x>GJ2cce$fMc9v&>l|Xic2W;V>6N2d;-;=A}Y2wWj>TT-MEY{1ST^X zaqd8C*vc=^NAu(R-UDEdw|$2VqzazvVCBxkM?z1_v$V^E;Fm{7d}I7<#9a-yR+VkM zrLxAP{|%^PS@%boENKOR{xRP4ydmtx`c%D4r30DS){gwpBg@bN!iHxU?+&Pq`Wt#0 zA9~*WI%QnMa0Ztad^Affm0|vAi`Sv5CY*Hk`oc8$?ZUuJk*8^D`_3r{J8auz50o$x zmPC&+)w?@C7<#=P;{_sRr>DR7W&sNVwva#H0_i7&L*H|NL9>1=;vjeQI4AxE-r^Ey z>6LPUG$j>q-QON(T@$f?KVH|~45-kUtx(L|!5LnmVo>DumN83WA0k9|73%AQNK{cr z1R-fp4@0ZV>& zcc^h{Goi=eaum&iKHNeUvZ(0#VF_dzQLOSFOyfHlyHGo0u2n89c0bC($7cUp&HES! zl~l=b!50Ia?4zJ5=mc4E7JuX#=i%PCfxnSxa>jn4YS#bqF=*cMAj_bKBC83x(#B#l z0zAf-X4##Al28JoyX7n!LB%vQwf=khucAR!sGZ9rLlts|x!4^npgh-na2N-F4Jq@V z`Gf`x^v77$Y=1#R)h$FBk%tS3nY)?04f&#vURWe<*9ZP6B*w&M8f z+P^hfCGzcS03t1@czn%?q89TauPAV(16UX+-cDZ%$bKvRX0fRjdGPTiuBMrG+7}t^ zJk63@;|jbCNx*(O(oraS-jhb-rKUZD>Uimm(=7u<(OnSiD1ayMRRw@Tb*~lxlky-% zjL|_S_I4x%nhC-Nf7nKYO~*;J?B55aTB`@B`EqTxBej_BPp^8XYK`MgCB2Sa-EXZ% z#V|qL_3IKUd&#sLr34c9=V+ur=lZ`2a#$B_AOC#6m;e=JOJmxyxXkXU*XtNVPnBOvT5Ll zBvlZJ{Z$xDU*uRW&v5`;8M@j`QqRCuDh%4na=Hg{I@Y7FnF)0L6S`+n$G{hUcAxro z);C2-pJhOgJIKwfqzQr>ysB!B5MKDbJ0(W}Z)2hNF0woOFc-$~yxQs!;h-jdofZlmPHF z!#o&ge{{uxp_j+XonugjD|$WyhK>4JyhL=kx5kw41-#G`l}mjspY(3N4a=SW)gAJQ z^WH+6`#`Z>VGh6!zD-fF851X;O{q)bY z?|)Je{@bT_67Ydy70y~h|9W+D_y8%Y8ET&UxvZGw4ucu@*X=$Ay~JWc_P$C14jZWRdYl zgQRKFJ{)m~Yn#ghxnsBHtJ?8^+}FLSuWyF0VcZ{Lq<2BFC5XS$1AeIq2h*_bNxAE& zZvh#ZZu=%{D)*L<+y?~KehqO)Oqw%~T$6CM58tOC83vVDW93F5V-WNJfK8+2FX1t= z=fae3F_0D-EfCZrxD!7rfJLewVt?1!hn2s(jW9g9uzNm-A#TtEd|4JrffsRCaHKg% zs)liX1e>Bw;Qp13JCqpiyDP$}^p;l|5hKA>z_XTOZJ=WSm$le90nuv7(Vy||!;p2% zqnm~bWL)DiBFEF3^2Zwy-hv=s`x5LYYv0y*!rS(>8cQ3~W5;?H&!IkH>pdJFx>5v0 z<6MApwlcHJcP_T#QEGWVZu{3QSCcmCiA>L(_!c=W^nEO2WPvw-1h_&Cuv#!!j^rJ( z5GZ*!o+GR~USTLVNQpz}nk;Ps{O;1B3vmDC(K`%EFZPntDX?m?u!r^#BA~ zx)S$F_Xp#i-q>fl9)l^~!CY;g(LMd|E_6I}RSSDS40;6@4F1P5*ZpIe|4n~_W$tgF z$MpI)vmdKxQM~|9(tE5?{$edjo6EC_yX#}izM@DV75dgjr<^4`IHIrQRoqLJdE4Gp z@(pAi+eL49bXb6amgC(NX#5(Cs*@G@_QsHZfTj8WgYpl6Nz)@J4svjBsT*ktB#?Qa z5f{~*W~XuU4LB&xGu2X4wBHYYd72?kWQu)& z$qH#iQf=^%TN%JZo$`y7uZG8yl-FP7d_t%U6>K1hLZF{RxgET)AoBa$n8#L^Pn9`F z`du`Vp*xDy#-Ok*&Jn~Q%nfi+BL_edoI`#XWDj`TQJt@0Xs_$v#V)x5q_LL!-Y zn<_{&=+o5Z;Yv@(M4)O1z9uf=Iq*n%k1@bRVjSvI0y@DnlyCs#HPi8ktuM)7VTU)` zl4*RTTG^m8x$6qdQ9WV?eRGn)5+!Xvm+!Llx%?@!)2%3ZapXaLFqyIF&Z=)Qv*sA6 zsB8@DztPP>Ly_ZTnYNO{fEX>q`Sc?b6?S)%$umVl zoaDJn7=Wr?ULAb2$EaF~jjfc{L9PGbYPnh44UIoN1|66VlHEjurj%$b&6?(i`x8$n z-@fwAWV7)PC+}-8*)*1Vi=DxW%GyAuTI#L@5u$P?t>&1rIm}ljxvv`6TO#m|xLpB) z7Sc%QQ~c;}x5T6SW55rAByJ3_tof7(xAL(8CG(uUIKPBI;w0-J7$$wGD;Knpd? z@)jw5$eeH_l&xc_`%+G&M)d^lm$SkOtuO2>Vum(@lK{Nt(Rmy6H5rnzeHltA@b}j_Lh*Bh4bA8OdQ;Z1B?alm{>h|9NS-FQW*WahA9%d1 zv@?*{ZWK3!UAFA>n4e)IO}Ebn6XM#d2@3LHd3q#>g50FM{my0}iJ3F%_7k%R>#IW_ zv=EWofKj!r{eUeni-JW239{$lw(mC9DCWsPKR{z?dyzw*`_v3OWuIaEjstqJucqx6 zNw__*hf~!k0kgz9Tbe-}I1d%r3oe4c${hi&Y9?%u;agrz%v=WOYPXNy?X(}}5Rb)8oPop>H3wk?gv z;o0GxY5f*Oxj5zez>6Y&tRbB=BJH-5w5O52<)KdU?z4&KYaeB5Zf&w3m|$5J0dmO9EIqg6#0acHx;4G41kRn zUu~_7#qWDBkCP2)ZJnN-m47(AcAMp`DA`AjSh@5HGILcWM>!`e2;d}Rrsdip{DIWB z|F6|r`rtTQJe`$3e+Z*5VG?*7#bqB^3%ew=GgEe{uI|DB3 zAgd(f>+RP%=(A@?eB6J&N<(b)i?6>McHmHhnWZx=&!gQh-e*UX))7%;Q0a5$2_gUT zpQ$q{IJ_g}%{c;6_&@yv(S|cbYFXZ!{3*w*P816=cJ2($I)P+V?(H=0kje%8O+fjk zR+S&$d=RVn9oP@5wD#>1JBU`Cs#EeKi1PR|kGKZ8EtPrVVYxLek%6F#U~ao0Yn2dq z{pbJ3*muW8b#_||is&fC0HSn^1qMY>0Ue4UR(czH6{JWN75oywf-eG70 zQ9z|LjFb^k5oU%eQl$CqBbwZM-z4ArPktmB5zcv@UDjS}ZHlJFX`CijPd&7bovOvE zl`6`hLcF6v1hshzndr=K)K%F3WNds4d)OJzu*LE{rE)MzY{dozyrYPHotYTxh zy?b}Iu3SUb!obY$LZuotGbbpuiRelUNE4OkDkPMkU&rT_2nyuR(0%^mkvt^N29NBR0*d3-xmJ8o4Ugi+cnb02JBfBj{ zD?=%>E4PCi!g*9eM2H`XQAodV%M>i27=1_rJGgkt=g<1PJN3se;g)s6#d$xh?AC}j z9``q(EJNzQXW7J>!_$|F<$Ye3EHVM!+Ka&eb`JX&Osq}b{Ia4lJ8Fd!^M{^FyIpRI z#F3&wvgLIHi#^ZeOPD|akvkY<%2nMTXUuQ89fAq#F+Fo~Y2YDgNR2Kai4n**j@q0S z{(D983e`$59^mS5jLWnazDau^Uw+Hpu+_f z8dtj(Wn1x%^zK(L+cgQJIV;7m-B-r*r&mh~M*S&1ih=gCu^mg_TsZYj5{0%rR-^b_ z7|Hc>SpYoMjifR9vaQ_IeZVlXAj*$2YT+Zm6#6%Z_U9Q+*vT5*{`y|de;)ndq>IS8 zHb0gW8GL~w3r6Uo@flh!+9n6)OR1znXE@ckdm5bB&0o3O%RkEbF9 zYI&TSS0z+9CH%q!-APn3{tN42+0zHJGQLs-(LOE_O2K;H>ZFM>M8^u4RySHvFZ#X| z&f0c1i!GX{c*}2GFG7)}_%qA&<%%_^u=?Og?^ihircE>;|GYN(d_bVaVcOt*L*1b-&+ffs=IfB?;c*690LBi+XoV9;GwD<>%|>Kce;JJUZiMZJ5OGM)=kC z43yx7GoDl@97$dR zkF$6Flxc)xyCAQtX7j|`T5JUI zu>*iN@4*L4`hSRE$YZ$80YQu}`1^T~7iZIuV#bYWAl+&SSb?3jW+D}s*pI!6V+n}E zTZTV*nV(44N2UTw4J+n!vNamX?=*6>GR)<`j5QnxwXaPP*bf#Hn0ShlCtYB_%%oV@ z)r%ce_Go#GR4sd##_ysR)tmJ$Rb9BZx0>?hfiExjkLPqj)7)lfYnXE_Y)mQehZ@Gt zS=7Y06Z*lvuNO#-1ZG=UyU?=)k6_3H!Zu^?eg3m=MS-4F7T0!bGXk?`25rba4Z8Df z63~8H9u%xs!rg%;I0WigHkEn6q*~Ve@nWR#Yrk$D_GjOYi@AQh+-p-)cqG}crvL{0 zx6ZFrrh;S5;EM=u@+r{0mjjH%(0lfC>#zN=7USJGU{?L2uy*X}$Fpm*H+gY=n$sf* zI-JHX!H5fv_{^2@kzIR_oAS6tqzM!f$`0oSZhURQMIn~l!&ZzuEs!L zr3kKTh$lr@dV{cS-H$u-why1N`r% zpi}c~AgQ95xK0(p&}T+0sfi92RJr!oh(DX;ygVKj=U{LTYH)oR`V9BZVhNOsQX?8a zo}EN+lAwSz7&3uM&ZfvNQ!R;$%~Z9#9loz|eHK_RAK1Tnm#~%X!8< zOgmWii9LfcLs_%_`~iVn#@FbeJhWbc@$Agbfl58G1OI$ON{ryqdpPr74BveAFX+8F zqKOe3;30pT#zo83$kBS|c~> zZPZiWX61_3I>5>L!Mse0hwKHe!ZOmp3M{?mb${z-94Xs&*G*oRR0gD}N}x*kXL7q> zkrg+p@nV9<5@*i?E436{m86zq<>td#_?;rSBdbg4guoK|}!qVdg~J0$}#= zHhZB(_R!sPJZRYq>+q+KnTo_)Irh|z9!iuStaRqz_6OJ-Tt_$ryy-uK*oBlT2CJ6) z`z;anOYBjD9%NqPBXqwIMu~&6U00zKZS$IkwHf@P6X~5RF1)ayBa{2iLP`Pz_kP_% zQ{H)k6W@~)*X{z3-)aBx7^%(QLL;6YO2A^o`xxjFAr{#;^Z4>~VPEVjglW~@Wv3ef zX|NKj7n$!i@nBwE{BgV3>3wcL*r-?spTg%VISr0_5VK|ViJoCgY(grq1zm-7L(-HI zydSYBd#&tK6toHLN~yZGPig0 zGbIKBSb0fuaTJ%tO9WL^k@K83_B?s6wufmCAy_^`UJalM-?)%g zs%u55&S9xqt9y5xw)ICSKxc(h)bczn8~kK5%A{oPV6P0yb2>dm%q20eQJ3-dx!~t> zpe6BQ@+t(wlDQ8pS&zf%ivcb!2jH!`NOZG8lGkL{7_S1e)M1>iGWOcb2RB%9x@->p zET0CBr$pxwnxR+tRsqwWgS@k_q;ZUoJwb?vHj>Aj@1y?$Uh6~m03TNSaAsa((jbgY zew{8$*zgVBAS(%y0pvJ*Xak%@oP3`3192n4WpH@A6(9(W@$z}}rQv)&wl9mt>Hf1q z`SbKo3dzeqtfSwI9aj%W>p|HfJk^_}o>J;W#(-<4v2i~5UcTy+P$s5dV(C3Qsr~iW zl*CJ5?>%9yCcnrBPPt|q^5dh%m+tSgfQ_W?Zhdn(%oysyOM>735)Jlkca7vB<0j+i z24EtPSYScS$%F^h56%X+q{!BUq(0ntb85&NLjcwcM>L@Rpc)#!(#{&lEv&~-A}SI@ zVe9jF-&&pdP6SS3p1WfkBKB#KS3Ywk?CO|5Vl!mrV3@YoCF?*OhFGlTD?C zrAK03va1odp8hh@hVF%y1=)^02wCG}fr&dg?HX;Q;)}lttrvEx*pmt6Fuu1FCLO7y zGZ>&WmZ6V1gQ=x(T-&z)2s3}a0RdLCprE6^+c#g*a}|L?`Vt@5rn<4dH3^hu17NAk zt0z+U(BQS?h59_T<;-35B^Q1b$W3%&59?NKLX+9^vMAdB^8Jh4c1|=J!bFo|HNIA`vrYB4u)@ZQq`M{!4azOq2&*z!b!Iw|Tv+VfdqOU`qGU`IY61 zfBtRQJ)!D;?!T)v;QMEupL+*Pq*8Iq7jKZE&8vsUO5uzd0ncj+Qco$AY$FB0eazKJ z4KX6=&<(&-AS|u;ybET`1Gsy-Wwbfm2@R$)$Eg6yqlFltzxmR^PTIJ^S1<=bLA9K$++*Pqp%IPt(*$6S%AGBeo!h(S`Wbxi$xxEd5s8=Ks z-{B0duOZ7(q2%jvw83G?@FIt0xFsDX7C%7gb1*4uQOf%(Vf;xS-9W9O$Cs*ZxuL2X zmYnW&K=&CY*!f-`F##4GGi?qyO@o5rJXeh>9Bvc>$Hx(wGCg%{{ZVKCU$|p4PLwf# zY46G220==2HhP^qVT1Snj~efLaQZ+02!6Z^+RSR+ne*Roc#8Zsx#f3TVe7^#wx&$vo@`g8aA#$P7QoLgrE{Bwm?WS);NX5=4d@fX!M*HRdj%qrd{*| z)sFz6qCs9z);zC0q$%$KJEZzElsQ*n@~_R*f^f4qbrGzWO)Zyo3J5l28Wi>w(9IEW zNQQHOXSj2uvQuvL4e%GFe$dlwtP=?CIUUQ1#SABSqjOi~=JQWK88fVC#FPXyvGUHYTwjM%FJM z2!Ft|y%gk`)j84ywJ(YNZG_(UEN_w#S^nr7_!oS*Z+U@Dp30BM>LWa+7ET@-Zr3}m-#Z7{-cNOoa1SfgPvk&vVr=c!u zjPK(x78dRLFM@UIK<{kc)1b<;>ev-L&>HWH5$BQ4d`b0tSKK_)6`}7`suCxx(zC zod3!jSh9N+FbL*=tfEXz0X{ePTq^pQQDZl_OgS(f$K55a_f{}V66fuSoARuGt(-id<~(W zu4ik^fDCJ*;uQdllK>icj#`^h58!8uGv^LP*)AE?NdnV>b9muUI^=<~>X9j$=@+XD z>g%~q*}fxu4r}fJs~nH*z_7N0PPZe#qcfnPGGkz zGZ654+y4n(|MOoo()&`+ua~ze|J{kY;|*koj&-YQwmRCjIv#sE>f9JE&NeE*G^{M>aGK&~BXk28tfU;?ybEbTDdhH*>zf!8tEEhH zl#83H>#bkMTfhlN1?aNsSWE#@Lm0`iETAu>UQEm`;}^O$shs3cSpDfyd>i1)pGYMV ztlmN&^LrwWf_JpXY7~7p1*vlF01wSiG>)WtsBG4lf7Md|<16_&_GNhQ3)E#tT3DGBQ0#E+TP`@LRGBRdhhJs_;@UlqvXrCb5qElkkkW|@r$z=)o|%rg zhH6Dm_(GMz@L?6wTE55B;La8iBL*M;9A#%OGpvmcZu?>eYj#sgo05qiN6&(~dfYsS z<5}k)y3?0@Eq7o#I4o>%c4=~;7qKYSsZn`N8{}kvsLKmWTowT&xb`LB@Q;q~?;cKY z+OJ*3mX~@J6|gIn;Wk`p}+ui z@(I6uK;Q&mFdmB+g}X%U7z7rixdS|oGN{l*$1wf?yNT-4>|u=z@5pa7Oq7`^mH z2sz>k?|~sKkx6sF&<(5^R&3{IYJDlp!>(2xV(szjSmhgdgj0vHo}Y@^@ztIYs*!cC=34H%h{NKdY@i!62j@zTTI;=e~B*1x99`c-LVn z#<2M6b8~_NsuiD014H29H|%@YAqw!2ed)lCTkcB}e)ZaXprxntjag{}M|&;*O2 zq(7Wg-c${cjBD>>FldD?smwj>D(V5~BcA{hKvK#dkW$rGEPAH}a-(yb3Ubg~kBwog z9xpJz#hqV8K^jj1--a{#k&C4+M}~AhMAjGF(91WJSjNdDpP%oO?5|jqfN^&GGY5Q- zLx8A}C5q9CDDDY&J>heeMn%&=Ju=(`@U_)Tu9oiSL%4kD9qb$`LLju54iHN~*%a4d zl&~HCf9v(&*`-piz}41=jfezN5}+`t$1uHMV2OD-wG3Ab)9Yy+%jbh&62l$8Fa3b6 z|9^+`f)*s0--aD_b0I%OO4Tl*QzYP=nM)v?liv2I9HmrkvI|87ZZ4<~3shmH0}=hy zZyksT?k2{~9B>PTj3Mehok!GMpFh6n10lx{!eT1TbCIurcB%q6m=9=JeYyeQQdf5s z7ech^0;<<KxtLAW)N^Ykr!ThfXuqWR52^Pr?K(Y^6%KUM{W|`iY z5ZsF)v1gQ&ukDOQXCKpErD&T zQob_10CO^fSTr`oZWWA(!063+)@}0u-P|z}M1~FzS~Pt_8po3f&{b6c?6tk2r#{{P z_CNmq(l+uHu)-j-fhij_RSvLh!B%oI^8TMk?q9DaN)sNY;QLbBO~mb&orooIKM2v@ zjkzm^fuJx7K^`-|>0Q&7uYhw0y~a_g0$AE-2tb)@+16}D0J`hB=il1OdqAgzpnyjn ze}esfeA72}W2o)4;8auVfz!ngkPpd@#gHVEsddn<>ZoL<1y+K`6D^ zUV}s+0Fl>kJ8Q!g-TvyDJ*)SPtsZ5TGf49V6-Gy~l=EhfxFxuD4`Lwi0OA!VYr^*K z@qimb047+7eCouollCpa2VmbqS^%*O?i@dBiCu9G5#Gq!m zpo5fjWS8CC-*24PE>QI~BeaLSkBTg^R?uLXyo`lD)J;X~6x=!p%BRRFg@e%IOaYFd zS}jLWi?);3ooDjot$r7>YZBO`s-8E5vqY5OXqnFkGx8O|s=-X-mh)_gA_Sq7zZ(PW zV~9y=IJ$pruc)ytRJf>2>}g#(4l}^Jzg9a$2p)HO7Rfh+Vn0HdlR9?l@Q?EpEVHKy z)cTHHDGE-eaOf+6A#_CjlhK=#f&xZwj0Ak+%#4@5PIA~-c^`}B9O?Y*qcZm?&Wvs# zWS_5ss3L5~y!P@9Ff8-*_c0DMimU@0pvK5$PuKi14_t(Re--`kepedp$ zdb5sO{urY^`7}liCD2nxaRwo>F8o&S{0G>h>p+(@2_?O|rFNVVd2QeH`$viSPhx@` zGL&K+ph$BnraB>OdB&}Gh|e5@rv@0I5v)gynLe5D?0n6$x9+{FlE7arvla(onLWG; zu_^e$uY^*j4&M*RB5HmhFke$Nkpj91@@VX%T0-40f^;oNV=)ruETp3s$ve6%*Y~S!uMyiYQ4u@1fvZ$wiRr)9%i*|MCM<%dFgz`Ddv6x91alRRl1NH%^ASyT9ME>|H$WT?!S}?Oc^ySiDX#0FY0O zGn~kT0Z4Y64+spE4M0H?QapAoE9&t!D-f0;N8U{A3FIvU2xwYdStk`VQLWegxul%n z+mT_kW};tZ)%N=py>bXx3UTF#@ju7{_p0zeF$3Z$c}?ko&~LvNKvY+V*CmGru1-k} zL7EI%%0RVVBpo^)m+w9PoaqfBY$1cP#3>0`k_Eu{J;(v*3?{Z8=$ZV+&ZGK8&k*?J zCABA?bM$|8 zo`fm@H@G*IdF}c42Mcs=WM3OXKPlpZwUE`kFt^{Sr)+VKfdi-5PzY7m2Gm-j6Ud6* zno(r9y$DEU=I*O#d1NoeAhLsou;()%X_YWjKlwuN2;Bg1Uku?Es+e5D5^}Vp^fJ-7 z`YEtp=f1a*#he9`c>C8wD73(L-7TW}yWT2n#t(Z#5i6HQcSIj;0^rHcktHaW_2DWz z0y6FN2r9NgDE~qz#OE2{&EMDwcwC+d6!TYF=75(|<$o0rT_*y9xc2QiV+`zwdHVsb zOQyp?{;;m-S%G4cW2OhAdP0lB?F z!#$&8JjmPdDYfgjLLl+KkSRNCGJd`ncmgj?7}b7YzQ|0Av_#O&Gi#`a7ONvdLX$Eo z=hGT>eCi0i0X0mXd%;eL$j@W180Qn@{0Y87uc0rp_c6c2Hx10!hAO)?#XF~p3+~_? z^PuGZ4Rm$Q>q~HMtzq<6bPP0iQ!H(Sz1P11-a7vHPQA44nL$$dQGc^uPi_-7YK>+| z&yqAwa&ZB&zafM}a+I0hTqt)h+?VmiQ2sYMb z_K}>jb({*`O2%VSKk@X9w3?0BHo%HM)JI7;za7Q}-S@nI*l-bXRauEloywkh;3Lop zr_&DD@ySC=ut9W!r_b&Lxo2z6DfI}0@oXd}PGvIgXj2`zgn%7T>0kNE+kaepJPVXz z1BfCQyn)0cjE1m7N-Tf$$YsvRu6$d=L((GpfAfNGOAh$Z`5Wk^;)agc6Y*me!5s~A ziwUz;h+Phg%xutVtOHI?k0QMaPj0e<0TZ@BRvTBVwj%&`+K&fcq<-{E8_4m~JlWoq z(sLhVCX1SfC5dvG^F`?6^~s00AG|J`La2`jj>vs)xGb5X-#c>ni;4cKYY8fFyY1`G zpIbsVwu@UdZS#B*#m5PGNX;jbCArYOpi3?hU&fP^T;_zau}^?5Hql585T+?0ka&!c z%cHEd&a5Bp@>XFPQNn`jyZUTUDS)+I2=iuX?|@yyZ9Pl?uA^H#yHhK$ps%^gJ;DW? zqN?0NHx@l$tdYq@|AV9PKd_d+Qu1G4$?ruF`u7pdUEgDehf^?2NfAh%M*vZ9kq;&d zi6O88g6mp#K|0C}rdS)2b!Z|6daSDH+;?#&^PS}N?8vyS?q5DVhv+NO05s@M@=?lo ze&SKwP1iIn0UfFPc4pIsAGlX6> z>Gse*_oP_7yNMUDnYNLv?_}!j&?BWjk~BWEbJr(NdEMZXq1+8nL+j)^Lnj%Ia5koW z&S;M50gJ==CL@c-x87#$--*a%xal{-i~9(^#-W8R>L!694jK0ah~DgMw~-y5mI3u( zD?bTkjHk1<|cY*us8U5a4GZ`B8lD zHFa#=zFRExc^T6$vFG{>$0u$)i1C*ji`@4}o~3PWgv?%{EugJ%i6H}bEIFI~MX#a{ zu#jTiZy1h4KpXn9u0C`cEBtsJFqtZIcrQh|Bg(*o=9Q5V9`L)i0`Wd;cX^JbtPq*NF$upNVfwPFBBxv)NENjG_2PY(isgKIOESA7Cgh&sDYzKClX0Z3+SU^4lLIFMn~MmpZCX;5 zVKowzPwu$LZl;WH>ob8jpC6&#e`E%D4o{EjT74gfs!6(^=h0BMG%~JN);P_?sys^g za#~{2SejN#9mAyiAYLvfE6YA`tJA1Zjqly#j|XRl-py+qp#AXWN) zwj6lm42%tG2ix>#sE}DXQ&KiBgHQoIA*@Hy6t?E%$76MNsC?^{2n)GIc(EhghKMz7 zJddL&>+Iqbbx%Eki~N$&l}aCks>)Wrb_#X{ya1GRd+!pZx24Zy4k`+%&;dW;*IA<3 z=!kB{jW2Ei+pUOWIxLo&j0R?eir!`mc73gJEtA!7l0h%!k*eTFuUJ5@7}DHL`20^t zy%6GO;KW66iaKiJEbfO{&5HFg~Q?sXjO#EpZ14t+gnZKfBbJ#v!$(LKGvto7nl=GPcq_7~d1LfPSkLg#bkQwt=T zGiFSvVO#;vwA2>As&uFivT&TxrmWt=#Nidw7wsYx-}>x`st**_*w6g+r7cXZc1knb zCz{>>xipaPX3X={qA|K(Wc68AG$)90i)U~nvS5bzzThsOVLGd`dkw`nO+0rsAHxzZ zeZ@WxV@f#FYU?9?7Vm;dM+bb7m7e>YB&Agmb z8n=)Y5ajtpJT0-8;X-*JP3D+31J^=z4`2)e=8u3X5_)x^nq&F}n$uBws$tOD=X5hN zRnz@-pt+$5p8s{6sqQ8FK-2ExG;jNaxyW7qBaxiOYElBZ{(7tF=jQ9noJn~Gy^+8S z^sLRk>ALK!{zz>EyO1QIIriKp_*}P7P>52ho^#r~lh@h4W$5yarII$(o;Ezsb~gnP zJDX)#HjVLXSkwSAnvX1Ak&apvPdd3C0PL9t{|UDPF`|nUz9^MV>fK+d>F>Y#3hjYp zpnrn&Cj46cOBYiXA^4P^WsXySuj+k5vAR@$foa{~F-0l$T;(vQ2|YdSSSO8sruk8= zpngX5!s>acKAT@K?FUb1PbZ*GE{m@eQ^Ky1kLC;9q-P4KTcZ&gjikcDq!qrBPVBdL zzxhXvw}HZK*dkWNePb*m(U*8l!WfK|ivSE0n_g@$49eS^$vug)tUVrqbs{7{Nn5d) z{B7;XrPaqyPFP0nkvq>j&kyM;Fp{Hrrh0U$U9VMkKBsNZT*^&MAnXlQma?J+4n}eO zqMPDieGVI=a=uWBuRmd;$f!F3MMzG#GSb<3O` z?*nX3lN}<)K3i0mQ#lCJ_dJiKEqz4N*(#ypbEB4t2*UJ*(F#|ug$_v-P-GW6Y^X05 zngG{SG{a;X+}(i*4*(c~eQ!r$3RZf`Yn!~OD5}WYo7m4H0=d`Fr|}vYN`i&3-)q3c zllo{05)8|^5R}PEPr%dYJf$JU;A^trriJaB!z!3f1+EyZrWAq+8|Jc6q$jEr(6F6o=CbbMC_Fpf?5hMY^>ppzZFaG@oSHUaYOJ~gnQhzARi zoNJ*Cxj92Q=iF90cnV;pR@w!(ZA+T^xe#tP$6TGRX=LBsT_HxiiM4pUsOtIs5*SGcV+D73lA>=vr6Axcu z|Ak;{*&Q#{bC)Q-N?v&ZU#Z4 zk(BeaoLM@Huy&By_!$^m#o8u)@i7h9Ya6g)6!k4pvEu(y8{txXRW6oZR z5((`qhe7Z10*uJ2*AxD`UO(*+^!m1r$1mPPE_)FhYQowc_x}F&Q_buIif-dYTtjz6 z6G2mtSm*2MspwgSk`~A<7J8FgOtF5YlaVNo`;g5Zz+*ZtA42~KZzhbyh0{+;29R(_l*NrnRzZBrGaQM*L_bRFk&g*|d%rn`NW zK#>~WDfD*Dz4SWFtBlQ!Oh%A;!=Uag^!i`NB!SA6!C|XOIc&>d@Bk?S z=gsPrV^H}JOMewb_-Y<`PLr^)kYwCEv(xiy-wcPVc1wd-22Cck#IIGuWUNn6+&JMD z1EjZHdzsLAzYLUb&WDVGb$<$%nnJSe7*1Z71!{_Bq}#gCrrY@1Yv@X0cwyj|dEh%= z#Rz_~k=M2S%)+HLp~{lbU7yxvp9VtUA|{|d*X6M$p1ZjcAYs?@^cE?b;IwEVTc<9l zG3D8Y5fBlh@~fl^yoa&=rx5RMlvyD9O?FWn#uy#MU6?i`t+^}-#bk_|&gmT!BUv*B zqoS`zzqaXF$jX+r#$nExLdz_EkGOPc|7v73+?ujowdm!9Y<7a)7GfNRPvktmXlRE2 zl9EYsuA*Cs3!c6O<+G}lqRrxpileU_?9@T6pjo+?=EAZ_pCy>hRyGP|URDb`F3oP; z-j{KjXIo^4^zc``Lc7=9j5{ZmMrX)_{0r;iZ%25V=2^ly7JS!b5BNBoHz{8)=Rb&M zh~!Awt%rBB#ylAfs?5~O))DMGpTTG+>^JpIH{D++c)+&m^xGT1P1e*H!_07u@AErl zlcHupzjZm#Gj&`T{I)j2@})Y}`}r<;`zNSuss$s;AQ!EhH^H}WFH`>bf=%#4peGwJ z^ffn{$v#yWA36`zlNX=5T>l+BV+{3VD6O++lN@7b5&-;SZ zW&GA$Ok(!@ZKr24fXJIjaq&xPgbUzKYUU*75!^#Xxams*WKd5dK>`uV-givd#M(VQ zlfXpDbY|Gs$00GSd5BLRin>QxPWy-vuTKDWT!C=Cao4bVhsivJ-2J$db%ff3RH08T z50l}7Si%siKrt$$i;!b%N=2t9cFv~_-68bL%)dT4eG!MV?v+dDeooA(2v}cn3bgNe zdc|kn*?7}l*g6_bmAa~yCjo`%(^!c_;qW%A^5boto{zPHE-38X z9NY)LN2kc+3ohVPGwcTd)~sQ^-=>r_&cXGWY813(w z12gW~5&|2ZmQ}d6yEUwkTqYB`WkKwr700@1s<$ogFAOyj#~F?<$p31lov9-3&wp7L z)n|8hk$jvDr+mNQW-YWjzq|Bra1Ajo_BDC{)lXUl0FC6fGia`DuqZJvM>~&i;z4#F zNDU(NMr`_?iyOlPBzb|-dt@0~Qt&X~fNaX87c0|wTH!s=>U6(*D>*{86fHCfauJx0>-1Huy!Mublr18-iE)8oDe zKU1e!psFgo-BhwfsAyg%SGmWN48Z)UwMKx)(> zu1S$DVyRoTbLEbXjcH1$KUrDP48F;p6RbSEF?`!4T;4r`)+kx?8&9r)#9eIddbwr-m3*_RU1T==UO~EiyO(rnA|Ksagy{zsK?gq&-XG zL#LTX6CR;=jETe)nM3F8R?;>mz!KYZ6~%Q?1P;xhTz&78kV2n$CA?Nw2cr~+j+V`N zGlu=qMEzz9ve$>m?OQ&`x(Kb*&u+cjBhfAMrE9SX^y_O z;&^-fV}6i6QfX*Aj?B`!1Nx>`%f58>ip zGmXFfN?;WR9oF9@ul^58=>`3FpksGUvaMfVG^*SS^UY5 zCO7I1YRwa*VN-Z^GWJFqX&3xv{(mrv#Y9MOZP5wB(h{<*(zXl&*gt$QVOv*PYAfKn zE!!$38lXlpVImHQV@+Hd8Ndv;u)2+X8_6#naLnZE-lL>+g=g-~cB4f_pE#LI@b+a* zjj#X*cTekxGOkP|i_iPx9vVy(#VCN5a)INH%F;Ml1qjsQyG| zU|lYz=nK@BY;JtoSsJ0fyGq<0a%lzV?xom?xzxy7YCvKhLbF9gLpQHn1gSa; zFgZ3B>+vKL&zOyG=x{K-{UixJ@-Y6MbBXBN(K+G1sTyw}b%}Z14oW`kV?0qy1{ho? zcOP3C=?@q`yNsJ7Q$y;k3GiyoSKRr8MvpM_$DoQtc1((#mD_b{rgldwbvRY5xTz7H zw2I@?ntk-&)p75Una#43QUCXu&38Jhz^-k4;E|xcbTk$dkn^h!Ch2L3`NZzc@pZ5a zo5u1LmU|j;+PIfGDK3D{D+np=(joyt`_lGTeOnK)_o3o2K9S(@yspH1kmJ!SyZH7_ zDY)GVfUBJYwB#G@+!Zjubx-Ysxm1h341lB+u#jY_2IdAbUi&V2rPc0k#c#ET@!-t? zWVfmlhzgCTer4c@#*zl_upP9gd%e;beDE4eH}_4{~l*aoH+?0;MnmspHn;H)kvmwW~)7bKkk2hy)lGA zLEm)M3&7l)B=%^Mhf)^1kR13Bgj~S|>}0g&KtoqgaC}>PCjMe$KXi+PE$M`ppkyqd z9DS*Zm|+gW%wRY$x3p+RE%Ewx6c0jenSPx8(u!BR-KbEcwi@BWeJsKA`;;%sS$@F2fdtlXuhq-PK%>OTIi zY@Bt2C|Wc5{=OE@e$i6rvVKb`-tX&Y1^xa8K3P$BQ( z$&we{0Ko7GA-C|ZV=o7w!|h2jX`-C?j@%+Sy~F-H1^Ej_S7DnK_?Xy$4%AibpzOA% z0Dn@L#i!ljR7~|`+_N(PzR(t(9qL0enut0Tq*`@4rK+?A1X9G^-wmvyA#lp##<<(Q z^akpL2S^zTb~)iuXEiSNcEGR&V1kctCBfb{USkCI4crXxeEO)65EQnx1MF!~=K?qC z5YDDB&wl2%6_R@-)aiGUygwymx<%0!wJ8NFjZh?sZ+@?P3#J;{;iJP3=!*uk*xCDv z6R!XsfNe3rEvf3l6~>Hzb=T)bvnT*!Qy`KS&Qx(v8f0lIg_?!ymg^!=x8@U0VegfiRaP`{X>E zwX(d&vmiQzLNeJkAfCi=^frhSxyO;w7NpF}HeNfkgtLPj;C(s3OhLGXi>Z}raRedt zEY~A6H;rd7={X~FGfx-yODVL(+3 zw8=9qr5anbQ&o9O&*ZoRkm0+(s%QauL0i8J&O;NAFH&O)9jl zY=NH_kyry2&aFLx2`DZaI-=AA-gD16jUYHW0{#?5d6*r`?0M|y{qNi%%X1ND23X-L zs!GXlGPP!+w$uaf$OA}ajJc+On@Pj;#O<5~h^gHa@?AK9a0Fw@Cmx(1ZCN!Gh_DQ# zMf3dDl7vZ5Sb9=!8F}Wg09LBqDp(=(YfBWrvvciSSbLJR)aWwN|1%7@+)eWQ9Y^ZP zWgYb|gPCkx1k1f*6yu^!p0BUHD@PdR#7lU1}3frwX z!kj=lD%S75wF`BECPUfUPT~7-M+FX-%2^|jjl257fb^z8?md^P8pqQDiETIbFhzz( z?K*Z8E01g(D1~{s$UYLxgdThdm!MSj+WdwFTGYpQl?wIoYx4caFD1QM5V(oZJ0eSf z>v&iC7NYJ8ojDHDna6xT-3SnV#GiNWZ@&6JBry1J@O$ADF%2jtfGdS_V(6{wuJO8F zr2GArN~b@I7F5i09;t7{Cqro^>XjK8cn1yrGUf{U;8U$ud#EU@Kef*U<%Jm4`{ta} zMyZF|!?hI^n=IsBd}GN{8410Q62XaqHyZ1CA+*&G8Fz`g$0feJ0{N5ZqNm5e$KiKh zSFI@{VY?Nq^)N@|ZhP}1L!mhJce;G_ZDI_r^&xYK;T{}T)#LSQY^;%&8E`%yB1FUK zu`_O;sx;~fe=?#T&Ovtr-VKJ0Wp@^1y-uz|ut4}bqQ+UQHm4^GDG1jOe8}$a{2B** z*e`NKa91}+yz&e`ynb~jttE%Pm@DgCavQ#gz67>a6d|lw#e1YHXWmvxIltxUt&;?S zAWnLT*YjF21k^IAdvYW2nU9%Ko{`WLoIE266;5NkzpS6JtsF#UU>iyt8zMosY%OuU z@3L>*FRJlKMAZ%0W|dBx1&#&5($K;{_MQB=kQsG4*Tt{O5?4?h|8L6AzeZK;w?RZp zZ(%L?S4@?@7v$6r$ToNYx#kYT994k5v~*w5lg&>c#{P&vjxn{v0VoW0Q!oU)Vv&|~ z-~%q&5muIgYC<$#9nYLhak#U_+zKlRyAidw)B~^493Ubafy3a@tN*+I3Qu&1JSlb`T`;Ke$Y%m|7&~Dp={Auf=XZa+@AlGv$AN1E z4%{()=ZBm5?tc|T?7noN`RoL(a&R@7D2Q`-4te=)yjlvV$4~*nTRtf#P4<<`O2uB0 zUj!-`bCWv7Rs;4C8bcB1b(0-h%o``fLm$BQ+t>w_6liimq8XZ%g6uo{O~?a9CX-cALMUI~!V z7-HD1papx@%%a|<$jUycf~9s0L7!$`0&?l}Ju=VF{p129pY?gBSS9VAHYcQ?<2Y55 zkjs`&hzS$niYAUL07kE!|DL%ew4;tHHZ6h$Jkv~BSi zh>ebb&@@^hZ*(|R`dv;h9#e2w1edN8Pb7h+A`hFZ+t>+8!l*N!;!|oK)2qoXKeGLb z*sbt_6htBWl&O40;J1xMXnUmNzq_Gxpmi=2)R0-5%J|EW9j({p4Q)m^v@J4!I?qHR z#J1pGFh;TfplDYn7?g~wCUN^`ux0CHY2tLhVBgRUz-kB*cz{sD(o;qt&T2h+irKqH zyC4g7Bo0)qna1SV8$b`cGynmbcmBz2fF7tAD@TA)ePGOwqhrZp5IS2jgHbbG^MjMO zPX>4JLT^v-yVuJ9M9^hD;5ENHRt>K%+c<1 zR>g2(mRxH;9KgzZfY7c2$YUQVicD+z2x2jREDtKgd&Pu-WT*^;D`kID^8VM|`zyTu zBG6+tG!7Jn0OIu42J#p-DGr8$WAU@dwP1Chdcy~_9 zTjn6)22|1HWk{1eb*YS8!Qo;BCUm1VDW%TzRuYkNTP_ zV#+x=aU<334Wfo}e+%-q3h2!b%Zh3N!PR<74=mbmB}T~|!O2|znxiz+`*mn0#-~fM z>N9fwm>I2bwf6fH9z^0oqi`zr4Z7j;(3)mG4pr&fKNu(XL0x*P?7_^x`ZoPl)V19(vc}PEYNtoHX-_C4B*Q8(n>2w~dTZ1TbQwP7ZXr@@9)3d&ER1|G z%Iv>lkc5Uol|3qEMF0z~3XY4D1L860VRq(gXyf#yKXO56`X+E=KKb1t-0u!hGQ<7GScWtt>LEwV4`-zIOjwUeFv2cKO%x)PMn# zrX_WiA&Wz4F*6h@Ng-v6Iv^vpF&WXIn0p+rVealO6 zoGB_GziVQ@&Eq|5JX5AJKpp4QQPV}Zm_s9b`_(47$8N0N zWRZJg@!6{-6qB$-C5lXacn|Tn98%;9m1H#-3+6%0cd75Q`CZNp@UYHXuXObd#t)jI z=5t@UY@SL{xMQ;h`D*Qyu>R%`cRjpGH zjsE;f{x{a!Vfq}p+C`dzN6k>F-(iZb*pMVBDBb9OWst?97KCi~G2Nx$aGW|-ui`N6 z_|j3}iBkeH)Y7RzUT}68$krSc2t^?uSo-2&sBVO@+c?v=pvk+${y_7{Wn2@s2%8a| zggLdMr6-GH#m;twSF^{%YBNrgA}XXSiBJqtLX+b-aLFFiX9m>0dLV3x)cz_qScZ)< z2L>Brs>TOw{1?~?i+b@Hz}|!=@6neuunys!;>ngzK39Y~^GYSdr6|ODG$<{^3uxcU zL&ie`aZS!tJoohb8j#>s`j4f_mta)TYkBC&pu86Xt1dfA&V`~fw>)l2etW)m9nSP3 z#M_#8l`M`T*_j26qoRp#4>W)y-Q;}2W0xic`KcBvUtVPUAP7B~!#}f^^l!)jao2ng z29bU5_xufY{`$ylMr71VQU}}U3Y6H!E(_2|FbD7+56X+oq5eX+`Wz*d)Nv9uNHhM0 z*^wrZ#CS@S!M}XwD}|VGVvwTqiu8v4zMkDG%`bZi^l6g&Vm{>r)h&k3-lXfHL?${U z3SHjMOb^nrW?m_3CQW(#62q;r!sv<)b&Ov2hfJm5CV;G7l<|j)z|W0{3wN#2PA}oQ zFK{Lhd}(X%mC0e(avVi086Nse%>jV?@&b!zmt3wEr`a*}@d3z;BKyK$~u!>N~ zD4?L0UP&8rC3Y~Pr?#R(sB18ml3zNrM^4l|vdd#GdB0B-Az`IsY}6ZZ1N?$m)hOW1 zRwlbTeaz2S^(7dMdPfjF75Y886@M)Y=zdA-q{qD`+Jq~O%lV5ghhrz^#cP><;oXX$ zI6LRjJaVA6t1Rd)c#R69ah*5$w7x<$ywI}!zk?(%AdqDDpy~a+|JiDTuo2kH0}L(f z@^j@Nbsj*hd{G_3JWn-JnzGQLhU@{_Map!?%~0bLfrz#f>gW^8b%aZJS{i-!s8*#R zLk}|bOR;eLZB`37^GjIMyRF{;_l*KWu*S!bWN zpo|$REZ5DU%GY{%{fq%4LoG*%jvc=#)HuwNaO|aP&$Jx}+8OSCe+5=b9|l+^=-2q! zoTf&q12u}RT}zi*zn|%G7^mk{IcX5Ue4dl^yk;xO^wdH1zUo0w&i-3a@{|HLU*#`s zh>3K6z092AVmu+)` zH7?6Wjh)~QGhK9-%H!8@X8e!G{N<|UepB2lDj+{8_f76#!6cUfYacg+72d`*t(&B+ zI3VxM(Yb=poupn1*h}BL;Jcy2)nMvZ6fzS*9`#@)K1h zjJfWysL|#xtXeI*X(VSM-~`ZPMW=nn7Hkw?358`y z=>&o_KE}9~>ui7@>;G%-%j2P3|Nf(-MvH1hNohmMQW|TPB(#ui>?0z}SPKzJ6lt-P z(?*m%%h)ID5DJ|viLuWhS+Y$fON8I&>U);&IdP8X^*n$6`b#xt?)#eS{#>8sy@XH) zG3z3LfDrHCf8%&bBdj6BMB zOTr$P4P?!T1KRiU4-1|gk;&!@Gl_b&hDSR0ZEX47XP`54 zqyR)^&g4JfngsQb-Y_GZS=11)6YS*{a-P|AC04~*qQt?E*}xoU@zSwb(}|o zEQ}%Uy_6J`KVZ5!6%oopVg>mtRPvb&s!vBaj6J<(?Id|CX-E=T8b3%I!))9$`9a1k zX=kc0sR%n;m;L#;nPT8!8jgBai?)wC_8EwX7q*wd=;&3U+TmQ3l!6CjPooiS9I7%d z7dHg%+;%O0P11C%v?UP&DTa?&1%-#(cEyXa+L+Nj*6}qVn87_CVukNxp4!kv^82HC z`=8b14TvYbo7#JD6Y24_6VB_G+!of0((voBh-Ocd9uRcN1+r0IYA(*U(WT@ZOUc=L zDd#iSfM$spt*^etzY7wHk+S-MGs)eC6^Z$UMESb?Nj1^u``h!fWJF?(4&WacZ`%7T z^@*$S+jFTw4>5a@`oUqhDxJ}Le)+Tk_d0Ry6($vlzJr+0gSqdd6r$>Z9$3&3r@cA! zN!nH}URGCL>bIi=LD!(S7uC!Io4Uj!&h83RCYRWaRcTqBi3ldk3z$Am zIcOQdkC%S%#vpF=ad`^sk;(2e9bOY^)4A|5gB1y92ez}J>Tj@=WUk4Bcm4jcxy~ao zhMdo8rFC)4;3<2`*89B9Uh#>e$%^3Dn#Ow8LTf;04!FemPqP~FgaFse!UmbKGW4(M zEF=b)M!xsWTO=cZ0L9l)x3>M~7wEY2?p+2)nx8`bN1aC;ORd;fU=RC1Z}e6t@qonw zzw)=nJ#QRzcYjej`3DQ(@6TNb=*jGxW@TpKhf#ZHioyDy>%e(_*CGerc8D%_d(F=o z%#WyF=>fN9P<(^SbpQI?-|4ru+0bWg1BEfI+l@i^!+*Qf1^)Vulb1KVh(mipeWRD_ zK!n)AN18GbF7Q@L&B^_&*8bm7PWr7A-1qSd3+Yj7r43?H9`ss7y9V4 zDPFS}WRoeJ-@l_R-!&Qdxx$uap!4xuJwm#NvE<=zfb|95=Z_l3r! zcKdxV$)F7s;W?c({%vo%QR ze6Rn$GXHR;3U}6n=25IT=hfe&GXIxr2M?m$|LTJNxGjy?WzY&wtbS#>sLuJ{R_N!y zuBgmh`wt88$LIe0)noUdpiOk%ufM>9^z(-=5K;cK*s#r(&bMj)=l}L^+wA787ocll z2Ko`Jbgf3(^AHNLYC$F z6VmgSFK}oV#5%XTtE-6{ZGE6@qe0Hz)0hE*X5zm|X5ads+!^ZJ-xn&8od3>vQ(r*i z&8)j3*ewlmxY}99+-#b@>bel2jp6%G>qh5}jDGXI$07!p07@W_Ok-dyh*Kj8oHNdm zzcQQn|ND;nv2S-_;o+)TKv2X$$O(ys0*ter3j_)rkq@$Numr7SU5J_+T#HOs|(N*=jg**(&qb+pa0EA5i$Uy{_rbI^FP1} zJCKBg5r9tZVG}#7hX-o!E5cJr#^|eyZ8PAlsT+5k!zk~3oKbahYW}a~K|Dr}^&YwY z&?fu$=!+r1O-DI0FJIuMZ!FvR8{oi%kM~WHRy)hhQMuFYIkewE4-Pnx-u|Ik#{+s3 zue`_x@{5ZbPv4>lxLKBMUTrpBnPt#)Lt+fR)sLm>5s0WM&J`vyy74DBA@zF_Oua6= z-u<8%`p;$n?>NzVbruxnhLD`p&!PmaFu8E-d+Z$ahcH3!MX(ER29QmtFjA?14)Z_L zFbs!a?%8L^&JyN6C!`vGm&u90RU<+V2bDXK967@@=8**dg|^EHsa_X;ec%*}Jp}P`kkD&yOeG8|dV<|R_SD#* z5sX^e^*2xfahL+o*pfG`r(hdDcKMts0Qyg&)qqPjhnd5zi^1iZMVG#Hy1^dIL6YpE zT}YD>W?NaPXO3Ln!%UGMU=2w3e7x+ifRe!vO|#)v+=wK34&K^%E{!6yw)lL_oaAie zMtd!7RjkdO9oRiK_ck8a(uvu1)A~;IW{yPB8@gwH5!bq!efOHO<}RU|ns;Jf9XM{I z((6W%D;_LLn{MyOx;!13eW;^}iW`;fa~|nA=UwxS(bIDh0`YK73?79E@HW*&8g!W23NL1f?a@zvij?KioMT^%mx_7BG?3!60h#n# zwqovkpZs&L=?mHg#I9058a>${E8ZEwJl{Pi20d`MlZ33xF&9SKKSs6zzSVAulnaVV zBxvF_f;dr5Md+p(xoWWQM#9Fh>GuvCEA^?PIp*XK~rVKW1P{!ko)rX z$XX=kb$3Q`@aIQ<{xn1jLSXm~t~c{$1d=Apu%ZQk>#_%(ybJwrqps!PDITtzS~3s} zH>Bc$Q`zR217z!RLNfaZU?^#=om&EdiW9)$@E!Q!8|dDVhxTNB>iZoFaB&EU@gk6% zad;|Vle~jv#~)7T!1Oq`3E+)hoI$r6&p(3yQB1;!dx(M5Jf~A341RVpXB@qWy)jt; z5pNti0r|muvPqPgNo&d%#J(B&1D0) zg*kSNq2N$^j^k-<0sUIuMgb*~=Nj+e16eSMdilZ^(*C?p>G6Q56|PK9&+&bS5wFZN4Ery3+<9N-)?;7sEmliIi_I0~G?u}J&TRZMQ) zlj_BOk*DcD1gpWWT=ykKU|GC3Q3)TSL3&*B$quz$L^bV0GAsdHEvysYtLliA)>)!a zqDj{AUwRQk9RpYT(;c9Brp?_Au!56j;*Qwf(ak$t15G+lF%q&4>k1`+f}SX@(j!#D z(L@HZpLV8(ouJxnDzqYLPwH*|U>zC+-`GvCOuCM6O7DNkSNe68v;R>MRHvI1 zGe2S~{mbGYXgCkYnG__t*>_#B6J3?O{5=YrxN(qtW2~FlAjB&J69!}*=1$}T!Ya{e>DnAYuc1h9WHrBx4Nu^&xVj(ltz3V zD4xF-SG~NfdrCGL{4#8-bwg89#kjsuzqv%*2=j9-0s#~NBMpDoPPQ=|E?Kp>Quc~M zBhvct&<+atOBVLqY5hV|gnf;C5=FcE7G~9Qm8j>Saa$l7AwfKfWc_03F^X20s{q0( zp`@8U-YiFDM}oo=VKDBxP6q`f;e!dU?+b+^Mf3(O?kzZfF#iZg6B2p#N#=I|y1$YR zYIc{?bxI0BZw?5-G>$saB&Pu&H5x16yG+yo8D!k7!Bp@mb|)|QIgyfy#$%R{ zeInpfzOIHN);bcP!!LKo19>u3Kym=*y9THsfcfiYenjktk~@_xZlsm`#!r}1C#R*V z8`Br{;tQzK5puNx(=h79xsMD}-g5{e$o?^qIh?rco|=0aVB==Q&;E*?>w)fmD}>SL z5m#9wk)cG&zBKJqvQ%8{bL+ZNSj<&h5oug>Y!F#S0K*W@#)&**f7@=u8WnEX`z&Au>?~4kj+wAeg(uNo>!$ zcB_lX-hjj3nZT!lwW zd^_ZH%3F^3Xl(KnN`>Hi&PR{Dv0}5|2#3O$a$p6fj#b6%BcNOIA7C%*9&s-G4;|Js z3ub8A+Kx`xT&i5XK!0-Y2d4muT$8>gSN9l&3km8G>oaYiB(~_rFdkh#!nL^ca|w8o z!Erklzh&Kgr?F3rp@L5Xz>i)*)bwn!Mh5J8%gfz?@>%;Z%$#y#qZ~^A2nzMKe)wGV zs2A?eP@&}a8al$xvIPIGu{rhK`yRsa+3M^XnE6hg7V7&bLpd-ie z_9X=X>xE4qz(02grn)WVVGy+qp@x{rp_V2!o^pJ*DP*<(3D+VZ9W?o`-L};&Z52S9 zK=HqEFkY4A;EB*Y`9D%pG1F7{KD`hL%1C=r#m?I)x)h)!{0p&wR2WshG9J+!GAob_DyeA!av_Av;e3 zI|RfcnN`tR$p)b@{1Lw}>qYAZxumCN?wQiO$$c?>v6`O{mSv>~!AF~A`PsDIdT5PK zK9Rc1WI(VLP2nCcEn_kmCYk0+w^|J}l58P$Reh~=3qi+3iYB9{ACKSToLUpPlPd&Y zsnhjQU+p=)&v#mpPCUB$l%S_v*U~lnKrGdq#k;IRXJ<-j+-BT_p#HYU0GG-y*AFbJ z!1zO&CEFE813dA%s3uTNRm!eOTCGb;4@2HwpuiA%t>Si$f?5sctw$E99do`@I|#LU z4rq=}zxi5qhP=%4Rs+{ee@t+`JXJV_uN(BAcT00H7O9rIA{M!&92LDk@9Uj*U{b&( z6P&X?bWFXxu|aJ(tz^>yivZiRUzMZsAwctN)Dtu-iP^*J3Am!Rp_VKfWBd1xTFi0|;4ph%9nTeEm@q&Fzpno|c8hrV6oUxjvhsLe37 zg8Tp(EN!y^Bb&?mCZ2_m>(6>(DhH)@i(#}fFTiEyPBAd4n%mjuiH5u*Bs_`ydKj*;No zda_s+^P)T) zFnp70IX6b6=+j7DEzwMpUMbM*&n;x?CE4`CYTm+ho)*(A@_dq+S8>^AgGMLF2D%If zCN4LZO|oV(z&Rvc)YgW51@-%=*_*9G@Z3+#eh&6l${yhJbXM8H%k9v82~gN1upWMG za;Cu*Hgy{an;>E6Qrp!aGfqc7s4u^_13Mhy-c|;OSNS65A&3;L&p5~xLIK8uvAcBL z7I<&mA*g~FH-wugX_Q!hV@IqZo);g}nJ_UoHUXwJBp{<4GWft!Mm9grd9;CJ&=m2QCmi~|IeTVS-BdG-Pfg{N(^ zO`e#~`(V$rZkf8!i)-{ae{kLuCdk7FR-gs23f4g2{hCIG0n!idSQr=JVl1=+YQmk` z%%iUi0W#DE+DNi?w_>(~`q#~0j|$xtGR#f~`OCJ%gvhY%mztoX0?Fb1f;st}yfUCG z9-v`vx%DMH?|j_Cu%d8U50BfV7$DD9V8eI=Xz!hFtm>UA4de!355YHRawuaD0C?EXDO_08o=e!8K*%{iv&wBdv0!aqPT$FBSrJ!9H=&vQLh@A3q5S|hRUxE z=|>u-P^4V?Lq0}Qq=vKWca-KO+F{7+`7uYXb4Q#8YiKk$6HGAs2S2aBBnS%YArB8# zI5Q927xIgW&>vhaxV>2+g7?gru={<;q#x!yI;o(mb{A7+gTV@zf@{kmyXP*TUQqM3 z^#oP)BKR!_*wTx=i`iB|cZ5cX?L-T8@_IUt$Jq0B|Dp#Z4S8WNdoxjceb2g;} z3G$nodG;y0Lg%s#xuEoJkCYHnM|<8_g-bX-FPgtw&vMAKr|aXP}ribI3{TCFfZ2|W}ppw4i%b=|d`wqkE@ zZb_%7#SQ=zPW3U|;NUadl9jOM%9E;V#YTwup`>kppyE@bfIu7BR?khA-k&4TJY@td zO?g!#L=nh!G80TtwXvV1V;f1(96VlOx__~qf-`WG-w4#7zd3YncL;QCw8fHop+}nq zhJgHq#n7BQ6ut7Gp~4SqESO7utI$%&20Hf2U>?WAf=n%0HPUaeQ}w&r*e{|EDc^Cm z>??M;_Ijk)lEydIO{tbO^{3=%P$>4$<<>K`K*OtyJnpgj5pfis)!S7CA#Eq~EhM!~ zfKDnHH1e9J6DDd`RSqbEI-#A+g(0V=_7np#kb7-fbA8wQELcqFGTjIZaV`73%}Vox zQ`U|_r^G`c)RDMfKg|Zq2TxB^=mFg}J809+kclxA@MgO^WtV*vql9cU0b0X3F^=l- zunbDw=#%~C{?l0+QHq!My2PL2>bu&-2=XmJG~ekY*X{fp+4yoRuOs)y%aCSP^AtQ#*8_zh^)q-al=zqh}*~B=6&ZC$3 zav5LxY8m4M5Lwu;Rj=!k$jR`XDr-3Hs=+_4wDy(J(~cm-^xRE6Hw)SR_nxj0Z{1~+ z=7bZ_BKRKvvG{wB$cVh^(+*DLt}*XZ{kO?3uPu@xA@QrsJ4)(&#;IZb1rl%PrWQC( zit+m!{p6uMZiHt$AP2d;V)T~x0UbscDm?7~ofuIXIzzj1^kdjbr51FAnbJiWC&Nhr z3D;(WoUG757kJv*0I#OV^OTt?%NSPu77k%SgbDeRjw)=Ga=*1JysM!?8iEWq=wcO= z21ba{17+H57>Iz^L#7zkC5B-Y+|^%=x)V^GR)3vc*>NhH-T6}|X2oD@VLb9JYy*ke zncYyar9+uK<(>RF3r@}bX{WX;`0W8A>rmRatfiSmIsDQj36Nhdgwc^))Muc6^|e}Z zq*LWtUY0q>GG~5S#k`Iky`DPmn767o-*x|hrrLP{+w=#z8UhFG{~~t?V3ys95eJKyIu8R zAXzi>#4%k+FSv_0Nzh9mH5nd12{%oXC%2c2)g$2MS->7;%GiNP%#NZB$7m~VE$VxQ zul+9IB*L*9=6}89j1Bjv@{>N4C)jRc|GIU(FJaff!vfmSG% zOIc_QhTn?8fRl7%V@L!<3^@F&>=jy?69LZikoeSkc<@Cz1zW@&=9CN zJLMiw5oLy?yPcp0tqpWAA@j(i6gnd2z&K=P0((3Kw5jKEn9CtIOq!cOXL1myZG&=3 zXSU+&$d6BeG_ypzIu|*Y7ueBi!PNs{boMij)FQUDuqmld48PaO9h$PJ%~g0qz!6GI z!vo-vUH}x@Gh6w%B&j?6;;#zTd8jej4$FvGlji1Nkfbye(YZ2P0?X?Kdf(q40O;Mm z0Nl`Lipz#yIrr7L9`11;g&>~Sm+#!Co->39EG$D;ogu&$FcOrfb}W@Rd{ z#b;Z09KD(AugbzGQb-bPd(XMmy-12 zNe!uU2t4WrQuWN5*br8df2$t)ZjxrHHdNSJq z8ZzTR&&}=3;cTr5mq<&*Ng6&CC!oytlAt^RD&X;q)~nR!6w1@|>=7!rUkdrj+_zfq zskDy;AVL%UEMW`eK{k%=+EI!u^|n(HD{3H&4*Dj;vpsq`Xrsa`7z_|>(>M=M8Ml4M zr-WAeKX+xHS<|17{Ys_RTh9O+lIEy6`8{8pr5oolJ0;s-#fBB=6rt|tfZ6wo+3QSq zZ7L9SZ*aD3DSg$Z1H0bm@ZPg3H(XrYU*dxd6#&QDR3}e0Y>a? z-~BZiGy2;z(V=>iQ^Wz}BfqST<9$+^=5dNipM?j9At!R^n$bJ4f;yFc#vB$iFve6< zOABLKy1W_cjlRu_I1KgT#Fp=uz`{{1yAw$*UN(wjPC(AA+wNR9bmC}W^Y?PChS|Pr z)6>ofJ{~3mo;f5W0fV5UTmn^zrq3etILF5}KI746I)bb5?}Ln`@@?r}eilbK7p#fH zI{lh4FM6PILcVlxut-mYwO#|#YT?Q%Jn25}0%4M7cFjG@yZP!K&h;Dk~z( zJ$%e>KL>qWxx@)q0b`IIWn+VWRqa=q=@H3}GSfgv6G$C8pWibX#R*Mynm!G2MIa_&x&BTtHRK|nZJx^1;qI-#H z1bsGu9uQIgrR_vl-Gpk#Bbba%If4O4H84B$#*Bd30b*f2IZYmH-F{j~#RsNs!MXB0 zgVDEy56tLVpW55W@QbCGCq)?!7u`_aJ_ulL>go6nE%F7i|N7$pv1%|7fiB^on$(VY zQ#lpNl~OAh-o9o(v)UwA(FIdTJO4&#qzBG81K9Io?cvO^#Hdv@kg$#ThQa9XmTgp{ zp?HRBM8c493*Z}KQoAtOf%UJ0{4et+Lb z-!46ZE50i3QQmb6cw;kY=+;r(8LXhT_!3+{ts3)PZHqN=tr?)_Vu=_vfPLUUM1`D) z@UY$1I&h51F9mu=jMhL`p^RR{i8RwDWBJ9VMv%1II-eQqC-sbXXyi9Gy~!kP&icyb zz1R>nOK8zs0=LEK#EE-?Jg?Zb(7;DH?6H8`>p7?Q*{ZF7~y@S z_!g)PT7h*xphzaNQYjrU?zsF`vpSE+P3@oM2wQc^vNY~G$O7U7uv2N?GjARVyi8W6 z0k2LU5IDwr9U$W*I2j*yGI$kU)qW%sg8#&&1GS=DAyl$wmkqgjz>~yCG&CWf`pP4u z9e>+77nra#hGOPUZSsd-^$)wwkUE&XYB{*@dy&)7(5&}?oor;nScsmm9K3jibJ zZ05S?^j;RCe0}$?nhUq}B#Fy>5k4Pu;G7za+diM)PE149bU_51+eixV{d2KxA`{hK zf8Rh0q#)k+VRR#ZB64)zDd~@2a=L~#Dd!X_ECPQe=28(e3}>+DNc3?7WU_KbLGwpm#l$OEuO)Y1B->E zcGN+Mk+T`(+Ri{Vrrxnq>cG5#`R7}_0?YSCdEx4?QxZ*0BUukw)ocN!+Z!^Ih`))1 zqfQ9t?ULp1e)jWw{`FRV-x}*sj={e0tGD#Q3$kXJ9Df6KLZEbG-6nG(#kK$K_Q6vx z*Dbtl|9bh+AR%+seBmAH^uuhum9@}~VS-?Mz};!($ptY6aganykzF}|`TMt88T~Z? z)Ew`x_MQKB7rxPXugvKr;EiSDw{mhWHl_c4UFZKGxH8#)e#K({_y1qnVpr lerped_path; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/safety_check.hpp index 858d742be867b..8f86af7b39ca1 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/safety_check.hpp @@ -62,9 +62,10 @@ bool isTargetObjectFront( Polygon2d createExtendedPolygon( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double lon_length, const double lat_margin); + const double lon_length, const double lat_margin, CollisionCheckDebug & debug); Polygon2d createExtendedPolygon( - const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin); + const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, + CollisionCheckDebug & debug); double calcRssDistance( const double front_object_velocity, const double rear_object_velocity, diff --git a/planning/behavior_path_planner/src/marker_util/lane_change/debug.cpp b/planning/behavior_path_planner/src/marker_util/lane_change/debug.cpp index 1ae1f8a03e0c0..2345d6f40fb18 100644 --- a/planning/behavior_path_planner/src/marker_util/lane_change/debug.cpp +++ b/planning/behavior_path_planner/src/marker_util/lane_change/debug.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "behavior_path_planner/marker_util/debug_utilities.hpp" #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" #include @@ -24,6 +25,7 @@ #include #include #include +#include #include #include @@ -37,7 +39,7 @@ using tier4_autoware_utils::createMarkerScale; MarkerArray showObjectInfo( const std::unordered_map & obj_debug_vec, std::string && ns) { - Marker marker = createDefaultMarker( + Marker obj_marker = createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, 0L, Marker::TEXT_VIEW_FACING, createMarkerScale(0.5, 0.5, 0.5), createMarkerColor(0.0, 1.0, 1.0, 0.999)); @@ -46,19 +48,24 @@ MarkerArray showObjectInfo( marker_array.markers.reserve(obj_debug_vec.size()); + int idx{0}; + for (const auto & [uuid, info] : obj_debug_vec) { - marker.id = ++id; - marker.pose = info.current_pose; + obj_marker.id = ++id; + obj_marker.pose = info.current_pose; std::ostringstream ss; - ss << info.failed_reason << "\nLon: " << std::setprecision(4) << info.relative_to_ego.position.x - << "\nLat: " << info.relative_to_ego.position.y - << "\nPosition: " << (info.is_front ? "front" : "back"); + ss << "Idx: " << ++idx << "\nReason: " << info.failed_reason + << "\nRSS dist: " << std::setprecision(4) << info.rss_longitudinal + << "\nEgo to obj: " << info.ego_to_obj_margin << "\nLateral offset: " << info.lateral_offset + << "\nLongitudinal offset: " << info.longitudinal_offset + << "\nPosition: " << (info.is_front ? "front" : "back") + << "\nSafe: " << (info.allow_lane_change ? "Yes" : "No"); - marker.text = ss.str(); + obj_marker.text = ss.str(); - marker_array.markers.push_back(marker); + marker_array.markers.push_back(obj_marker); } return marker_array; } @@ -167,23 +174,28 @@ MarkerArray showPolygon( constexpr float scale_val{0.2}; int32_t id{0}; + const auto now = rclcpp::Clock{RCL_ROS_TIME}.now(); Marker ego_marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, id, Marker::LINE_STRIP, - createMarkerScale(scale_val, scale_val, scale_val), createMarkerColor(1.0, 1.0, 1.0, 0.9)); + "map", now, ns, id, Marker::LINE_STRIP, createMarkerScale(scale_val, scale_val, scale_val), + createMarkerColor(1.0, 1.0, 1.0, 0.9)); Marker obj_marker = ego_marker; + + auto text_marker = createDefaultMarker( + "map", now, ns + "_text", id, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, + createMarkerScale(1.5, 1.5, 1.5), createMarkerColor(1.0, 1.0, 1.0, 1.0)); + MarkerArray marker_array; - constexpr auto colors = colorsList(); - const auto loop_size = std::min(obj_debug_vec.size(), colors.size()); + constexpr auto red_color = colorsList().at(0); + constexpr auto green_color = colorsList().at(1); + const auto reserve_size = obj_debug_vec.size(); - marker_array.markers.reserve(loop_size * 2); - size_t idx{0}; + marker_array.markers.reserve(reserve_size * 4); + + int32_t idx = {0}; for (const auto & [uuid, info] : obj_debug_vec) { - if (idx >= loop_size) { - break; - } - const auto & color = colors.at(idx); + const auto & color = info.allow_lane_change ? green_color : red_color; const auto & ego_polygon = info.ego_polygon.outer(); const auto poly_z = info.current_pose.position.z; // temporally ego_marker.id = ++id; @@ -194,6 +206,14 @@ MarkerArray showPolygon( } marker_array.markers.push_back(ego_marker); + std::ostringstream ss; + text_marker.id = ego_marker.id; + ss << ++idx; + text_marker.text = ss.str(); + text_marker.pose = info.expected_ego_pose; + + marker_array.markers.push_back(text_marker); + const auto & obj_polygon = info.obj_polygon.outer(); obj_marker.id = ++id; obj_marker.color = createMarkerColor(color[0], color[1], color[2], 0.8); @@ -202,7 +222,11 @@ MarkerArray showPolygon( obj_marker.points.push_back(tier4_autoware_utils::createPoint(p.x(), p.y(), poly_z)); } marker_array.markers.push_back(obj_marker); - ++idx; + + text_marker.id = obj_marker.id; + text_marker.pose = info.expected_obj_pose; + marker_array.markers.push_back(text_marker); + ego_marker.points.clear(); obj_marker.points.clear(); } 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 28d1b30ca5991..e57c55136d1cb 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 @@ -74,6 +74,7 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) LaneChangePaths valid_paths{}; const auto found_safe_path = getLaneChangePaths(current_lanes, target_lanes, direction_, &valid_paths); + debug_valid_path_ = valid_paths; if (valid_paths.empty()) { return {false, false}; 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 919541f5972a4..04224b380414e 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -396,8 +396,8 @@ PathSafetyStatus isLaneChangePathSafe( return std::make_pair(tier4_autoware_utils::toHexString(obj.object_id), debug); }; - const auto appendDebugInfo = - [&debug_data](std::pair & obj, bool && is_allowed) { + const auto updateDebugInfo = + [&debug_data](std::pair & obj, bool is_allowed) { const auto & key = obj.first; auto & element = obj.second; element.allow_lane_change = is_allowed; @@ -438,7 +438,7 @@ PathSafetyStatus isLaneChangePathSafe( lane_change_path.duration.prepare, lane_change_parameter.prepare_segment_ignore_object_velocity_thresh)) { path_safety_status.is_safe = false; - appendDebugInfo(current_debug_data, false); + updateDebugInfo(current_debug_data, path_safety_status.is_safe); if (isObjectIndexIncluded(i, dynamic_objects_indices.target_lane)) { const auto & obj_pose = obj.kinematics.initial_pose_with_covariance.pose; const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj_pose, obj.shape); @@ -448,7 +448,7 @@ PathSafetyStatus isLaneChangePathSafe( } } } - appendDebugInfo(current_debug_data, true); + updateDebugInfo(current_debug_data, path_safety_status.is_safe); } if (!lane_change_parameter.use_predicted_path_outside_lanelet) { @@ -469,13 +469,13 @@ PathSafetyStatus isLaneChangePathSafe( lane_change_parameter.prepare_segment_ignore_object_velocity_thresh, front_decel, rear_decel, current_debug_data.second)) { path_safety_status.is_safe = false; - appendDebugInfo(current_debug_data, false); + updateDebugInfo(current_debug_data, path_safety_status.is_safe); const auto & obj_pose = obj.kinematics.initial_pose_with_covariance.pose; const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj_pose, obj.shape); path_safety_status.is_object_coming_from_rear |= !utils::safety_check::isTargetObjectFront( path, current_pose, common_parameter.vehicle_info, obj_polygon); } - appendDebugInfo(current_debug_data, true); + updateDebugInfo(current_debug_data, path_safety_status.is_safe); } return path_safety_status; } diff --git a/planning/behavior_path_planner/src/utils/safety_check.cpp b/planning/behavior_path_planner/src/utils/safety_check.cpp index 72bba383a22f7..ef450c3538f65 100644 --- a/planning/behavior_path_planner/src/utils/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/safety_check.cpp @@ -14,6 +14,7 @@ #include "behavior_path_planner/utils/safety_check.hpp" +#include "behavior_path_planner/marker_util/debug_utilities.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "perception_utils/predicted_path_utils.hpp" @@ -49,14 +50,21 @@ bool isTargetObjectFront( Polygon2d createExtendedPolygon( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double lon_length, const double lat_margin) + const double lon_length, const double lat_margin, CollisionCheckDebug & debug) { const double & base_to_front = vehicle_info.max_longitudinal_offset_m; const double & width = vehicle_info.vehicle_width_m; const double & base_to_rear = vehicle_info.rear_overhang_m; const double lon_offset = std::max(lon_length + base_to_front, base_to_front); + const double lat_offset = width / 2.0 + lat_margin; + + { + debug.longitudinal_offset = lon_offset; + debug.lateral_offset = lat_offset; + } + const auto p1 = tier4_autoware_utils::calcOffsetPose(base_link_pose, lon_offset, lat_offset, 0.0); const auto p2 = tier4_autoware_utils::calcOffsetPose(base_link_pose, lon_offset, -lat_offset, 0.0); @@ -77,7 +85,8 @@ Polygon2d createExtendedPolygon( } Polygon2d createExtendedPolygon( - const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin) + const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, + CollisionCheckDebug & debug) { const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj_pose, shape); if (obj_polygon.outer().empty()) { @@ -101,6 +110,12 @@ Polygon2d createExtendedPolygon( const double lon_offset = max_x + lon_length; const double left_lat_offset = max_y + lat_margin; const double right_lat_offset = min_y - lat_margin; + + { + debug.longitudinal_offset = lon_offset; + debug.lateral_offset = (left_lat_offset + right_lat_offset) / 2; + } + const auto p1 = tier4_autoware_utils::calcOffsetPose(obj_pose, lon_offset, left_lat_offset, 0.0); const auto p2 = tier4_autoware_utils::calcOffsetPose(obj_pose, lon_offset, right_lat_offset, 0.0); const auto p3 = tier4_autoware_utils::calcOffsetPose(obj_pose, min_x, right_lat_offset, 0.0); @@ -183,9 +198,15 @@ bool isSafeInLaneletCollisionCheck( const auto & ego_pose = predicted_ego_poses.at(i).first; const auto & ego_polygon = predicted_ego_poses.at(i).second; + { + debug.lerped_path.push_back(ego_pose); + debug.expected_ego_pose = ego_pose; + debug.expected_obj_pose = *obj_pose; + debug.ego_polygon = ego_polygon; + debug.obj_polygon = obj_polygon; + } + // check overlap - debug.ego_polygon = ego_polygon; - debug.obj_polygon = obj_polygon; if (boost::geometry::overlaps(ego_polygon, obj_polygon)) { debug.failed_reason = "overlap_polygon"; return false; @@ -211,17 +232,21 @@ bool isSafeInLaneletCollisionCheck( const auto & ego_vehicle_info = common_parameters.vehicle_info; const auto & lat_margin = common_parameters.lateral_distance_max_threshold; const auto & extended_ego_polygon = - is_object_front ? createExtendedPolygon(ego_pose, ego_vehicle_info, lon_offset, lat_margin) - : ego_polygon; + is_object_front + ? createExtendedPolygon(ego_pose, ego_vehicle_info, lon_offset, lat_margin, debug) + : ego_polygon; const auto & extended_obj_polygon = is_object_front ? obj_polygon - : createExtendedPolygon(*obj_pose, target_object.shape, lon_offset, lat_margin); - - debug.lerped_path.push_back(ego_pose); - debug.expected_ego_pose = ego_pose; - debug.expected_obj_pose = *obj_pose; - debug.is_front = is_object_front; + : createExtendedPolygon(*obj_pose, target_object.shape, lon_offset, lat_margin, debug); + + { + debug.rss_longitudinal = rss_dist; + debug.ego_to_obj_margin = min_lon_length; + debug.ego_polygon = extended_ego_polygon; + debug.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)) { @@ -229,6 +254,7 @@ bool isSafeInLaneletCollisionCheck( return false; } } + return true; } @@ -259,16 +285,19 @@ bool isSafeInFreeSpaceCollisionCheck( const auto & ego_pose = interpolated_ego.at(i).first; const auto & ego_polygon = interpolated_ego.at(i).second; - debug.ego_polygon = ego_polygon; - debug.obj_polygon = obj_polygon; + { + debug.lerped_path.push_back(ego_pose); + debug.expected_ego_pose = ego_pose; + debug.expected_obj_pose = obj_pose; + debug.ego_polygon = ego_polygon; + debug.obj_polygon = obj_polygon; + } + if (boost::geometry::overlaps(ego_polygon, obj_polygon)) { debug.failed_reason = "overlap_polygon"; return false; } - debug.expected_ego_pose = ego_pose; - debug.expected_obj_pose = obj_pose; - // compute which one is at the front of the other const bool is_object_front = isTargetObjectFront(path, ego_pose, common_parameters.vehicle_info, obj_polygon); @@ -288,17 +317,21 @@ bool isSafeInFreeSpaceCollisionCheck( const auto & ego_vehicle_info = common_parameters.vehicle_info; const auto & lat_margin = common_parameters.lateral_distance_max_threshold; const auto & extended_ego_polygon = - is_object_front ? createExtendedPolygon(ego_pose, ego_vehicle_info, lon_offset, lat_margin) - : ego_polygon; + is_object_front + ? createExtendedPolygon(ego_pose, ego_vehicle_info, lon_offset, lat_margin, debug) + : ego_polygon; const auto & extended_obj_polygon = is_object_front ? obj_polygon - : createExtendedPolygon(obj_pose, target_object.shape, lon_offset, lat_margin); - - debug.lerped_path.push_back(ego_pose); - debug.expected_ego_pose = ego_pose; - debug.expected_obj_pose = obj_pose; - debug.is_front = is_object_front; + : createExtendedPolygon(obj_pose, target_object.shape, lon_offset, lat_margin, debug); + + { + debug.rss_longitudinal = rss_dist; + debug.ego_to_obj_margin = min_lon_length; + debug.ego_polygon = extended_ego_polygon; + debug.obj_polygon = extended_obj_polygon; + debug.is_front = is_object_front; + } if (boost::geometry::overlaps(extended_ego_polygon, extended_obj_polygon)) { debug.failed_reason = "overlap_extended_polygon"; diff --git a/planning/behavior_path_planner/test/test_safety_check.cpp b/planning/behavior_path_planner/test/test_safety_check.cpp index 07762ff96eb67..2174ef47a1c86 100644 --- a/planning/behavior_path_planner/test/test_safety_check.cpp +++ b/planning/behavior_path_planner/test/test_safety_check.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "behavior_path_planner/marker_util/debug_utilities.hpp" #include "behavior_path_planner/utils/safety_check.hpp" #include "tier4_autoware_utils/tier4_autoware_utils.hpp" @@ -40,6 +41,7 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) vehicle_info.max_longitudinal_offset_m = 4.0; vehicle_info.vehicle_width_m = 2.0; vehicle_info.rear_overhang_m = 1.0; + CollisionCheckDebug debug; { Pose ego_pose; @@ -49,7 +51,8 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) const double lon_length = 10.0; const double lat_margin = 2.0; - const auto polygon = createExtendedPolygon(ego_pose, vehicle_info, lon_length, lat_margin); + const auto polygon = + createExtendedPolygon(ego_pose, vehicle_info, lon_length, lat_margin, debug); EXPECT_EQ(polygon.outer().size(), static_cast(5)); @@ -75,7 +78,8 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) const double lon_length = 10.0; const double lat_margin = 2.0; - const auto polygon = createExtendedPolygon(ego_pose, vehicle_info, lon_length, lat_margin); + const auto polygon = + createExtendedPolygon(ego_pose, vehicle_info, lon_length, lat_margin, debug); EXPECT_EQ(polygon.outer().size(), static_cast(5)); @@ -102,7 +106,8 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) const double lon_length = 10.0; const double lat_margin = 2.0; - const auto polygon = createExtendedPolygon(ego_pose, vehicle_info, lon_length, lat_margin); + const auto polygon = + createExtendedPolygon(ego_pose, vehicle_info, lon_length, lat_margin, debug); EXPECT_EQ(polygon.outer().size(), static_cast(5)); @@ -149,7 +154,8 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedObjPolygon) const double lon_length = 10.0; const double lat_margin = 2.0; - const auto polygon = createExtendedPolygon(obj_pose, shape, lon_length, lat_margin); + CollisionCheckDebug debug; + const auto polygon = createExtendedPolygon(obj_pose, shape, lon_length, lat_margin, debug); EXPECT_EQ(polygon.outer().size(), static_cast(5)); From 3fea24f2e9f334ccddec704cf7adeb77d20bb7ee Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 27 Jun 2023 19:14:32 +0900 Subject: [PATCH 036/118] feat(lane_change): add param for a lateral distance margin where the abort can be performed (#4083) * feat(lane_change): add param for abort execution margin Signed-off-by: Takamasa Horibe * fix precommit Signed-off-by: Takamasa Horibe * fix for merge Signed-off-by: Takamasa Horibe * update readme Signed-off-by: Takamasa Horibe * fix doc Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../config/lane_change/lane_change.param.yaml | 1 + .../behavior_path_planner_lane_change_design.md | 15 ++++++++------- .../lane_change/lane_change_module_data.hpp | 1 + .../behavior_path_planner/utils/utils.hpp | 2 +- .../src/behavior_path_planner_node.cpp | 1 + .../src/scene_module/lane_change/normal.cpp | 3 ++- .../behavior_path_planner/src/utils/utils.cpp | 16 ++++++++++++---- 7 files changed, 26 insertions(+), 13 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 049303203ed44..6f5105c46eb99 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 @@ -57,6 +57,7 @@ delta_time: 1.0 # [s] duration: 5.0 # [s] max_lateral_jerk: 1000.0 # [m/s3] + overhang_tolerance: 0.0 # [m] finish_judge_lateral_threshold: 0.2 # [m] 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 91c3c2a219a20..ae49542b3970b 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 @@ -301,13 +301,14 @@ The following parameters are configurable in `behavior_path_planner.param.yaml`. The following parameters are configurable in `lane_change.param.yaml`. -| Name | Unit | Type | Description | Default value | -| :------------------------------------- | ------- | ------- | -------------------------------------------------------------- | ------------- | -| `cancel.enable_on_prepare_phase` | [-] | boolean | Enable cancel lane change | true | -| `cancel.enable_on_lane_changing_phase` | [-] | boolean | Enable abort lane change. | false | -| `cancel.delta_time` | [s] | double | The time taken to start steering to return to the center line. | 3.0 | -| `cancel.duration` | [s] | double | The time taken to complete returning to the center line. | 3.0 | -| `cancel.max_lateral_jerk` | [m/sss] | double | The maximum lateral jerk for abort path | 1000.0 | +| Name | Unit | Type | Description | Default value | +| :------------------------------------- | ------- | ------- | ---------------------------------------------------------------------------------------------------------------- | ------------- | +| `cancel.enable_on_prepare_phase` | [-] | boolean | Enable cancel lane change | true | +| `cancel.enable_on_lane_changing_phase` | [-] | boolean | Enable abort lane change. | false | +| `cancel.delta_time` | [s] | double | The time taken to start steering to return to the center line. | 3.0 | +| `cancel.duration` | [s] | double | The time taken to complete returning to the center line. | 3.0 | +| `cancel.max_lateral_jerk` | [m/sss] | double | The maximum lateral jerk for abort path | 1000.0 | +| `cancel.overhang_tolerance` | [m] | double | Lane change cancel is prohibited if the vehicle head exceeds the lane boundary more than this tolerance distance | 0.0 | ### Debug 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 2a77419092189..67a23f23d5827 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 @@ -34,6 +34,7 @@ struct LaneChangeCancelParameters double delta_time{1.0}; double duration{5.0}; double max_lateral_jerk{10.0}; + double overhang_tolerance{0.0}; }; struct LaneChangeParameters { 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 b5da46148a9f3..cc2d109f0cf1c 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 @@ -306,7 +306,7 @@ bool isEgoOutOfRoute( bool isEgoWithinOriginalLane( const lanelet::ConstLanelets & current_lanes, const Pose & current_pose, - const BehaviorPathPlannerParameters & common_param); + const BehaviorPathPlannerParameters & common_param, const double outer_margin = 0.0); // path management 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 f9791b8b79b54..c3191d5ab4a2c 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -833,6 +833,7 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam() p.cancel.delta_time = declare_parameter(parameter("cancel.delta_time")); p.cancel.duration = declare_parameter(parameter("cancel.duration")); p.cancel.max_lateral_jerk = declare_parameter(parameter("cancel.max_lateral_jerk")); + p.cancel.overhang_tolerance = declare_parameter(parameter("cancel.overhang_tolerance")); p.finish_judge_lateral_threshold = declare_parameter("lane_change.finish_judge_lateral_threshold"); 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 e57c55136d1cb..6fb84577a3b99 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 @@ -396,7 +396,8 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const if (dist > estimated_travel_dist) { const auto & estimated_pose = status_.lane_change_path.path.points.at(idx + 1).point.pose; return utils::isEgoWithinOriginalLane( - status_.current_lanes, estimated_pose, planner_data_->parameters); + status_.current_lanes, estimated_pose, planner_data_->parameters, + lane_change_parameters_->cancel.overhang_tolerance); } } diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index e1c2560b1c0d1..5b89b352d9574 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -1114,7 +1114,7 @@ bool isEgoOutOfRoute( bool isEgoWithinOriginalLane( const lanelet::ConstLanelets & current_lanes, const Pose & current_pose, - const BehaviorPathPlannerParameters & common_param) + const BehaviorPathPlannerParameters & common_param, const double outer_margin) { const auto lane_length = lanelet::utils::getLaneletLength2d(current_lanes); const auto lane_poly = lanelet::utils::getPolygonFromArcLength(current_lanes, 0, lane_length); @@ -1124,9 +1124,17 @@ bool isEgoWithinOriginalLane( const auto vehicle_poly = tier4_autoware_utils::toFootprint(current_pose, base_link2front, base_link2rear, vehicle_width); - // Check if the ego vehicle is entirely within the lane by checking if the vehicle's polygon - // is within the lane's polygon - return boost::geometry::within(vehicle_poly, lanelet::utils::to2D(lane_poly).basicPolygon()); + // Check if the ego vehicle is entirely within the lane with a given outer margin. + for (const auto & p : vehicle_poly.outer()) { + // When the point is in the polygon, the distance is 0. When it is out of the polygon, return a + // positive value. + const auto dist = boost::geometry::distance(p, lanelet::utils::to2D(lane_poly).basicPolygon()); + if (dist > std::max(outer_margin, 0.0)) { + return false; // out of polygon + } + } + + return true; // inside polygon } lanelet::ConstLanelets transformToLanelets(const DrivableLanes & drivable_lanes) From 37c8a0e843a15c87d2a33983345d2026c3d14f66 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 27 Jun 2023 20:14:10 +0900 Subject: [PATCH 037/118] fix(behavior_path_planner): support separated lanes in getIntersectionTurnSignalInfo (#4085) Signed-off-by: kosuke55 --- .../src/turn_signal_decider.cpp | 84 ++++++++++++++++--- 1 file changed, 74 insertions(+), 10 deletions(-) diff --git a/planning/behavior_path_planner/src/turn_signal_decider.cpp b/planning/behavior_path_planner/src/turn_signal_decider.cpp index ac11941ec1eb6..78ea16dbc3c05 100644 --- a/planning/behavior_path_planner/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/src/turn_signal_decider.cpp @@ -140,29 +140,94 @@ boost::optional TurnSignalDecider::getIntersectionTurnSignalInfo } } - std::queue signal_queue; + // combine consecutive lanes of the same turn direction + // stores lanes that have already been combine + std::set processed_lanes; + // since combined_lane does not inherit id and attribute, + // and ConstantLanelet does not rewrite the value, + // we keep front_lane together as a representative. + std::vector> combined_and_front_vec{}; for (const auto & lane_id : unique_lane_ids) { - const auto lane = route_handler.getLaneletsFromId(lane_id); - const double search_distance = lane.attributeOr("turn_signal_distance", base_search_distance); - if (lane.centerline3d().size() < 2) { + // Skip if already processed + if (processed_lanes.find(lane_id) != processed_lanes.end()) continue; + auto current_lane = route_handler.getLaneletsFromId(lane_id); + lanelet::ConstLanelets combined_lane_elems{}; + while (rclcpp::ok()) { + processed_lanes.insert(current_lane.id()); + combined_lane_elems.push_back(current_lane); + + // Get the lane and its attribute + 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()) { + 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()) { + break; + } + + // assume that the next lane in the path is only one + current_lane = next_lanes_in_path.front(); + } + + if (!combined_lane_elems.empty()) { + // store combined lane and its front lane + const auto & combined_and_first = std::pair( + lanelet::utils::combineLaneletsShape(combined_lane_elems), combined_lane_elems.front()); + combined_and_front_vec.push_back(combined_and_first); + } + } + + std::queue signal_queue; + for (const auto & combined_and_front : combined_and_front_vec) { + // use combined_lane's centerline + const auto & combined_lane = combined_and_front.first; + if (combined_lane.centerline3d().size() < 2) { continue; } + // use front lane's id, attribute, and search distance as a representative + const auto & front_lane = combined_and_front.second; + const auto lane_id = front_lane.id(); + const double search_distance = + front_lane.attributeOr("turn_signal_distance", base_search_distance); + const std::string lane_attribute = + front_lane.attributeOr("turn_direction", std::string("none")); + // lane front and back pose Pose lane_front_pose; Pose lane_back_pose; - lane_front_pose.position = lanelet::utils::conversion::toGeomMsgPt(lane.centerline3d().front()); - lane_back_pose.position = lanelet::utils::conversion::toGeomMsgPt(lane.centerline3d().back()); + lane_front_pose.position = + lanelet::utils::conversion::toGeomMsgPt(combined_lane.centerline3d().front()); + lane_back_pose.position = + lanelet::utils::conversion::toGeomMsgPt(combined_lane.centerline3d().back()); { const auto & current_point = lane_front_pose.position; - const auto & next_point = lanelet::utils::conversion::toGeomMsgPt(lane.centerline3d()[1]); + const auto & next_point = + lanelet::utils::conversion::toGeomMsgPt(combined_lane.centerline3d()[1]); lane_front_pose.orientation = calc_orientation(current_point, next_point); } { const auto & current_point = lanelet::utils::conversion::toGeomMsgPt( - lane.centerline3d()[lane.centerline3d().size() - 2]); + combined_lane.centerline3d()[combined_lane.centerline3d().size() - 2]); const auto & next_point = lane_back_pose.position; lane_back_pose.orientation = calc_orientation(current_point, next_point); } @@ -195,7 +260,6 @@ boost::optional TurnSignalDecider::getIntersectionTurnSignalInfo continue; } - const std::string lane_attribute = lane.attributeOr("turn_direction", std::string("none")); if ( (lane_attribute == "right" || lane_attribute == "left" || lane_attribute == "straight") && dist_to_front_point < search_distance) { @@ -207,7 +271,7 @@ boost::optional TurnSignalDecider::getIntersectionTurnSignalInfo TurnSignalInfo turn_signal_info{}; turn_signal_info.desired_start_point = desired_start_point_map_.at(lane_id); turn_signal_info.required_start_point = lane_front_pose; - turn_signal_info.required_end_point = get_required_end_point(lane.centerline3d()); + turn_signal_info.required_end_point = get_required_end_point(combined_lane.centerline3d()); turn_signal_info.desired_end_point = lane_back_pose; turn_signal_info.turn_signal.command = signal_map.at(lane_attribute); signal_queue.push(turn_signal_info); From bf0a7e158167ba8f1801191e8cb6054fec53aa8c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 27 Jun 2023 20:27:02 +0900 Subject: [PATCH 038/118] fix(start_planner): fix winker near intersection (#4053) Signed-off-by: kosuke55 --- .../src/scene_module/start_planner/start_planner_module.cpp | 3 ++- 1 file changed, 2 insertions(+), 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 67ad82a489ade..b2cf74893666b 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 @@ -846,7 +846,8 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() const const bool is_near_intersection = std::invoke([&]() { const double check_length = parameters_->intersection_search_length; double accumulated_length = 0.0; - for (size_t i = 0; i < path.points.size() - 1; ++i) { + const size_t current_idx = motion_utils::findNearestIndex(path.points, current_pose.position); + for (size_t i = current_idx; i < path.points.size() - 1; ++i) { const auto & p = path.points.at(i); for (const auto & lane : planner_data_->route_handler->getLaneletsFromIds(p.lane_ids)) { const std::string turn_direction = lane.attributeOr("turn_direction", "else"); From 0e733cdc429525ca46b6846066cdd20b5fa3ef22 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 27 Jun 2023 20:43:43 +0900 Subject: [PATCH 039/118] docs(behavior_path_planner): add documentation for avoidance by lane change module (#4087) Signed-off-by: satoshi-ota --- planning/behavior_path_planner/README.md | 20 +- ...planner_avoidance_by_lane_change_design.md | 40 ++++ .../avoidance_by_lane_change.svg | 54 +++++ .../avoidance_by_lc_trigger_1.svg | 205 ++++++++++++++++++ .../avoidance_by_lc_trigger_2.svg | 85 ++++++++ 5 files changed, 394 insertions(+), 10 deletions(-) create mode 100644 planning/behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design.md create mode 100644 planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lane_change.svg create mode 100644 planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_1.svg create mode 100644 planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_2.svg diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 8bf46fb3d3ae7..07d949aae8a39 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -16,16 +16,16 @@ The `behavior_path_planner` module is responsible to generate Behavior path planner has following scene modules. -| Name | Description | Details | -| :------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :----------------------------------------------------------- | -| Lane Following | this module generates reference path from lanelet centerline. | LINK | -| Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](./docs/behavior_path_planner_avoidance_design.md) | -| Avoidance By LC | this module generates lane change path when there is objects that should be avoid. | LINK | -| Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](./docs/behavior_path_planner_lane_change_design.md) | -| External Lane Change | WIP | LINK | -| Goal Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](./docs/behavior_path_planner_goal_planner_design.md) | -| Pull Out | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](./docs/behavior_path_planner_start_planner_design.md) | -| Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](./docs/behavior_path_planner_side_shift_design.md) | +| Name | Description | Details | +| :------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------------------- | +| Lane Following | this module generates reference path from lanelet centerline. | LINK | +| Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](./docs/behavior_path_planner_avoidance_design.md) | +| Avoidance By LC | this module generates lane change path when there is objects that should be avoid. | [LINK](./docs/behavior_path_planner_avoidance_by_lane_change_design.md) | +| Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](./docs/behavior_path_planner_lane_change_design.md) | +| External Lane Change | WIP | LINK | +| Goal Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](./docs/behavior_path_planner_goal_planner_design.md) | +| Pull Out | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](./docs/behavior_path_planner_start_planner_design.md) | +| Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](./docs/behavior_path_planner_side_shift_design.md) | ![behavior_modules](./image/behavior_modules.png) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design.md new file mode 100644 index 0000000000000..2c91cc43995ac --- /dev/null +++ b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design.md @@ -0,0 +1,40 @@ +# Avoidance by lane change design + +This is a sub-module to avoid obstacles by lane change maneuver. + +## Purpose / Role + +This module is designed as one of the obstacle avoidance features and generates a lane change path if the following conditions are satisfied. + +- Exist lane changeable lanelet. +- Exist avoidance target objects on ego driving lane. + +![avoidance_by_lane_change](../image/avoidance_by_lane_change/avoidance_by_lane_change.svg) + +## Inner-workings / Algorithms + +Basically, this module is implemented by reusing the avoidance target filtering logic of the existing [Normal Avoidance Module](./behavior_path_planner_avoidance_design.md) and the path generation logic of the [Normal Lane Change Module](./behavior_path_planner_lane_change_design.md). On the other hand, the conditions under which the module is activated differ from those of a normal avoidance module. + +Check that the following conditions are satisfied after the filtering process for the avoidance target. + +### Number of the avoidance target objects + +This module is launched when the number of avoidance target objects on **EGO DRIVING LANE** is greater than `execute_object_num`. If there are no avoidance targets in the ego driving lane or their number is less than the parameter, the obstacle is avoided by normal avoidance behavior (if the normal avoidance module is registered). + +![trigger_1](../image/avoidance_by_lane_change/avoidance_by_lc_trigger_1.svg) + +### Lane change end point condition + +Unlike the normal avoidance module, which specifies the shift line end point, this module does not specify its end point when generating a lane change path. On the other hand, setting `execute_only_when_lane_change_finish_before_object` to `true` will activate this module only if the lane change can be completed before the avoidance target object. + +Although setting the parameter to `false` would increase the scene of avoidance by lane change, it is assumed that sufficient lateral margin may not be ensured in some cases because the vehicle passes by the side of obstacles during the lane change. + +![trigger_2](../image/avoidance_by_lane_change/avoidance_by_lc_trigger_2.svg) + +## Parameters + +| Name | Unit | Type | Description | Default value | +| :------------------------------------------------- | ---- | ------ | ---------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| execute_object_num | [-] | int | Number of avoidance target objects on ego driving lane is greater than this value, this module will be launched. | 1 | +| execute_object_longitudinal_margin | [m] | double | [maybe unused] Only when distance between the ego and avoidance target object is longer than this value, this module will be launched. | 0.0 | +| execute_only_when_lane_change_finish_before_object | [-] | bool | If this flag set `true`, this module will be launched only when the lane change end point is **NOT** behind the avoidance target object. | true | diff --git a/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lane_change.svg b/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lane_change.svg new file mode 100644 index 0000000000000..78ccb44806661 --- /dev/null +++ b/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lane_change.svg @@ -0,0 +1,54 @@ + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_1.svg b/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_1.svg new file mode 100644 index 0000000000000..db4987f5806b5 --- /dev/null +++ b/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_1.svg @@ -0,0 +1,205 @@ + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ parked on adjacent lane +
+
+
+
+ parked on adjacent lane +
+
+ + + + +
+
+
+ moving +
+
+
+
+ moving +
+
+ + + + + + +
+
+
+ outside of ego driving lane +
+
+
+
+ outside of ego driving lane +
+
+ + + + +
+
+
+ parked on ego driving lane +
+
+
+
+ parked on ego driving lane +
+
+ + + + + +
+
+
+ count only these objects +
+
+
+
+ count only these objects +
+
+ + + + +
+
+
+ ego +
+
+
+
+ ego +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_2.svg b/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_2.svg new file mode 100644 index 0000000000000..304cc33614a90 --- /dev/null +++ b/planning/behavior_path_planner/image/avoidance_by_lane_change/avoidance_by_lc_trigger_2.svg @@ -0,0 +1,85 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ lane change end point +
+
+
+
+ lane change end point +
+
+
+ + + + Text is not SVG - cannot display + + +
From 0443a08de439aab33457cf599170f6da076d487c Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 27 Jun 2023 22:47:39 +0900 Subject: [PATCH 040/118] chore(lane_change): don't exit for danger param (#4092) Signed-off-by: Takamasa Horibe --- .../src/behavior_path_planner_node.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) 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 c3191d5ab4a2c..4ed96ebe463ae 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -853,10 +853,9 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam() } if (p.cancel.delta_time < 1.0) { - RCLCPP_FATAL_STREAM( - get_logger(), "cancel.delta_time: " << p.cancel.delta_time << ", is too short.\n" - << "Terminating the program..."); - exit(EXIT_FAILURE); + RCLCPP_WARN_STREAM( + get_logger(), "cancel.delta_time: " << p.cancel.delta_time + << ", is too short. This could cause a danger behavior."); } return p; From 7aeb71647bb03c44813f6f7ab2f608cf43caf83a Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Wed, 28 Jun 2023 11:23:49 +0900 Subject: [PATCH 041/118] fix(behavior_velocity_intersection_module): fix condition of use_stuck_stopline (#4086) Signed-off-by: tomoya.kimura --- planning/behavior_velocity_intersection_module/src/util.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 2dcc6a0ef761d..88b2599dae03a 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -278,14 +278,14 @@ std::optional generateIntersectionStopLines( // (5) stuck vehicle stop line int stuck_stop_line_ip_int = 0; if (use_stuck_stopline) { - stuck_stop_line_ip_int = std::get<0>(lane_interval_ip); - } else { const auto stuck_stop_line_idx_ip_opt = getFirstPointInsidePolygon(path_ip, lane_interval_ip, first_conflicting_area); if (!stuck_stop_line_idx_ip_opt) { return std::nullopt; } stuck_stop_line_ip_int = stuck_stop_line_idx_ip_opt.value(); + } else { + stuck_stop_line_ip_int = std::get<0>(lane_interval_ip); } const auto stuck_stop_line_ip = static_cast( std::max(0, stuck_stop_line_ip_int - stop_line_margin_idx_dist - base2front_idx_dist)); From 3d293de5da5db4e68eaef5e135661a0e312a4ca5 Mon Sep 17 00:00:00 2001 From: Manato Hirabayashi <3022416+manato@users.noreply.github.com> Date: Wed, 28 Jun 2023 12:34:56 +0900 Subject: [PATCH 042/118] fix(tensorrt_yolox): yolox extra bbox with zero value (#4089) fix: remove unintended bounding boxes with zero value Signed-off-by: Manato HIRABAYASHI --- perception/tensorrt_yolox/src/tensorrt_yolox.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/perception/tensorrt_yolox/src/tensorrt_yolox.cpp b/perception/tensorrt_yolox/src/tensorrt_yolox.cpp index 515ff1d3c6e9e..0950f46f30b43 100644 --- a/perception/tensorrt_yolox/src/tensorrt_yolox.cpp +++ b/perception/tensorrt_yolox/src/tensorrt_yolox.cpp @@ -428,7 +428,8 @@ bool TrtYoloX::feedforward(const std::vector & images, ObjectArrays & o objects.clear(); for (size_t i = 0; i < batch_size; ++i) { const size_t num_detection = static_cast(out_num_detections[i]); - ObjectArray object_array(num_detection); + ObjectArray object_array; + object_array.reserve(num_detection); for (size_t j = 0; j < num_detection; ++j) { Object object{}; const auto x1 = out_boxes[i * max_detections_ * 4 + j * 4] / scales_[i]; From df8a43a4f583bed3e7f7c07f46958512a3320bd5 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 28 Jun 2023 13:32:34 +0900 Subject: [PATCH 043/118] fix(intersection): do not plan if detection area is not empty and stop line idx is 0 (#4097) do not plan if detection area is not empty and stop line idx is 0 Signed-off-by: Mamoru Sobue --- .../src/scene_intersection.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 4a5541508d65f..0512e90197237 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -715,6 +715,11 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( return IntersectionModule::Indecisive{}; } + if (default_stop_line_idx == 0) { + RCLCPP_DEBUG(logger_, "stop line index is 0"); + return IntersectionModule::Indecisive{}; + } + const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; debug_data_.pass_judge_wall_pose = planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path); @@ -795,7 +800,11 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( path->points.at(default_stop_line_idx).point.pose.position); const bool approached_stop_line = (std::fabs(dist_stopline) < planner_param_.common.stop_overshoot_margin); + const bool over_stop_line = (dist_stopline < 0.0); const bool is_stopped = planner_data_->isVehicleStopped(); + if (over_stop_line) { + before_creep_state_machine_.setState(StateMachine::State::GO); + } if (before_creep_state_machine_.getState() == StateMachine::State::GO) { if (has_collision) { return IntersectionModule::OccludedCollisionStop{ From 2246931a4ea1e0ff82cd981f5b74e8702da2e971 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 28 Jun 2023 14:06:23 +0900 Subject: [PATCH 044/118] fix(lane_change): do not prematurely combine lane change lanes (#4095) * fix(lane_change): do not prematurely combine lane change lanes Signed-off-by: Zulfaqar Azmi * directly using utils Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../scene_module/lane_change/base_class.hpp | 2 -- .../scene_module/lane_change/normal.hpp | 4 ---- .../src/scene_module/lane_change/normal.cpp | 16 ++-------------- 3 files changed, 2 insertions(+), 20 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 225b093018d95..e20c2e8ae9091 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 @@ -204,8 +204,6 @@ class LaneChangeBase const lanelet::ConstLanelets & target_lanelets, Direction direction, LaneChangePaths * candidate_paths, const bool check_safety) const = 0; - virtual std::vector getDrivableLanes() const = 0; - virtual TurnSignalInfo calcTurnSignalInfo() = 0; virtual bool isValidPath(const PathWithLaneId & path) const = 0; 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 f7c6cdc07a200..cac0252e274ae 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 @@ -104,8 +104,6 @@ class NormalLaneChange : public LaneChangeBase const lanelet::ConstLanelets & target_lanelets, Direction direction, LaneChangePaths * candidate_paths, const bool check_safety = true) const override; - std::vector getDrivableLanes() const override; - TurnSignalInfo calcTurnSignalInfo() override; bool isValidPath(const PathWithLaneId & path) const override; @@ -136,8 +134,6 @@ class NormalLaneChangeBT : public NormalLaneChange PathWithLaneId getPrepareSegment( const lanelet::ConstLanelets & current_lanes, const double arc_length_from_current, const double backward_path_length, const double prepare_length) const override; - - std::vector getDrivableLanes() const override; }; } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__NORMAL_HPP_ 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 6fb84577a3b99..c004a0b3aec26 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 @@ -158,7 +158,8 @@ void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) const auto & common_parameters = planner_data_->parameters; const auto & dp = planner_data_->drivable_area_expansion_parameters; - const auto drivable_lanes = getDrivableLanes(); + const auto drivable_lanes = utils::lane_change::generateDrivableLanes( + *getRouteHandler(), status_.current_lanes, status_.lane_change_lanes); const auto shorten_lanes = utils::cutOverlappedLanes(*output.path, drivable_lanes); const auto expanded_lanes = utils::expandLanelets( shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, @@ -763,13 +764,6 @@ bool NormalLaneChange::getLaneChangePaths( return false; } -std::vector NormalLaneChange::getDrivableLanes() const -{ - const auto drivable_lanes = utils::lane_change::generateDrivableLanes( - *getRouteHandler(), status_.current_lanes, status_.lane_change_lanes); - return utils::combineDrivableLanes(prev_drivable_area_info_.drivable_lanes, drivable_lanes); -} - PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const { const auto current_pose = getEgoPose(); @@ -1118,10 +1112,4 @@ PathWithLaneId NormalLaneChangeBT::getPrepareSegment( return prepare_segment; } - -std::vector NormalLaneChangeBT::getDrivableLanes() const -{ - return utils::lane_change::generateDrivableLanes( - *getRouteHandler(), status_.current_lanes, status_.lane_change_lanes); -} } // namespace behavior_path_planner From e819ca68d9004adde6db8ae3da94b6210fb04fc1 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Wed, 28 Jun 2023 15:44:06 +0900 Subject: [PATCH 045/118] feat: add visualization node of traffic light recognition result (#4099) * feat: add visualization node of traffic light recognition result Signed-off-by: tomoya.kimura * docs: update readme Signed-off-by: tomoya.kimura * chore: change image Signed-off-by: tomoya.kimura --------- Signed-off-by: tomoya.kimura --- .../CMakeLists.txt | 16 ++ .../Readme.md | 40 +++++ ...light_recognition_visualization_sample.png | Bin 0 -> 637103 bytes ...ht_recognition_marker_publisher.launch.xml | 7 + .../package.xml | 30 ++++ ...fic_light_recognition_marker_publisher.cpp | 164 ++++++++++++++++++ ...fic_light_recognition_marker_publisher.hpp | 62 +++++++ 7 files changed, 319 insertions(+) create mode 100644 common/traffic_light_recognition_marker_publisher/CMakeLists.txt create mode 100644 common/traffic_light_recognition_marker_publisher/Readme.md create mode 100644 common/traffic_light_recognition_marker_publisher/images/traffic_light_recognition_visualization_sample.png create mode 100644 common/traffic_light_recognition_marker_publisher/launch/traffic_light_recognition_marker_publisher.launch.xml create mode 100644 common/traffic_light_recognition_marker_publisher/package.xml create mode 100644 common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp create mode 100644 common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp diff --git a/common/traffic_light_recognition_marker_publisher/CMakeLists.txt b/common/traffic_light_recognition_marker_publisher/CMakeLists.txt new file mode 100644 index 0000000000000..d028ab21475f7 --- /dev/null +++ b/common/traffic_light_recognition_marker_publisher/CMakeLists.txt @@ -0,0 +1,16 @@ +cmake_minimum_required(VERSION 3.14) +project(traffic_light_recognition_marker_publisher) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/traffic_light_recognition_marker_publisher.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "TrafficLightRecognitionMarkerPublisher" + EXECUTABLE ${PROJECT_NAME}_node +) + +ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/common/traffic_light_recognition_marker_publisher/Readme.md b/common/traffic_light_recognition_marker_publisher/Readme.md new file mode 100644 index 0000000000000..1cafc619ff6fb --- /dev/null +++ b/common/traffic_light_recognition_marker_publisher/Readme.md @@ -0,0 +1,40 @@ +# path_distance_calculator + +## Purpose + +This node publishes a marker array for visualizing traffic signal recognition results on Rviz. + +![sample_img](./images/traffic_light_recognition_visualization_sample.png) + +## Inner-workings / Algorithms + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| ------------------------------------------------------- | -------------------------------------------------------- | ------------------------------------------------- | +| `/map/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | Vector map for getting traffic signal information | +| `/perception/traffic_light_recognition/traffic_signals` | `autoware_auto_perception_msgs::msg::TrafficSignalArray` | The result of traffic signal recognition | + +### Output + +| Name | Type | Description | +| -------------------------------------------------------------- | -------------------------------------- | ------------------------------------------------------------------------------ | +| `/perception/traffic_light_recognition/traffic_signals_marker` | `visualization_msgs::msg::MarkerArray` | Publish a marker array for visualization of traffic signal recognition results | + +## Parameters + +None. + +### Node Parameters + +None. + +### Core Parameters + +None. + +## Assumptions / Known limits + +TBD. diff --git a/common/traffic_light_recognition_marker_publisher/images/traffic_light_recognition_visualization_sample.png b/common/traffic_light_recognition_marker_publisher/images/traffic_light_recognition_visualization_sample.png new file mode 100644 index 0000000000000000000000000000000000000000..a9a782e4a70129b40cccc0ea984a8b55ec58beaa GIT binary patch literal 637103 zcmaI83pms7|39vz6D2Asy(uAbj!=eFDyJj~F~^YD9A}16DsnE#X`xg^&T`tAGs$6< zSj@H@SH_0L%p86YueH-lbIlL!68NGS~VdbjTW zJ-hZDlT)10!d+|KZ?)nH*@(t< zZRMr)wWS?h>$LC=Zt6O(8kg1C5r4m|GPE?s!t-o-%H1ed>;o6i!?(LCRYO%H50=hU z6l|SrpY0c2Ba5z)dVI4!%b=&D)-U|YUO(Bs{)ft%8|RgH81eSyT#3fWI^Iroyy3> zw)8N3WlW-*#zJzL;c>-;7ICa@wqE!on;Pz}fvJxPY0Bj(HyS=A+Nq z&+oD$Lki*zW_Iui2_!fM#QYQ9_$NxBE~(JQ@As9^e8^`4*t#+AwEobpijeR)Rdv&c zs*ws^zZQaF$6qNJPhrDK_Z^?FP&e(WB#2m$5ld z)J;jmZuZ*W=f=S5!cW{eU;x{)d}dg1&4hdbS$&tW(f!-D3=CD(l=Y}$^Ru|Z z=h>^v`5lyrVTumFHNWXan2ynY;Uf+NlSg)rCG zI))MGBq^tJnN{qA+>D)3%#uVJ>aEA;uU~~MEzMJ;yC#xyJ>D1GV`g1}tG(xHcK8m% zMG@=@w)B7w!IPhbXI8T-vS^haD~vg^Of*h697+TaUNmx>{+BgtOUn@IjD~FV6Y%=f zlAL^K<4!lTAUU%44jsmM{K!+7CcoGgGq!}=_S80QSmWy$%08qp*TcH#)&Yapi-Xsa zo4M_-0$F#BkH;JhJXv< zghX6t-g}q7r(RKVMq8!taG(P-VWU*Y{(s#w&fIskt6Q8WZ3tpjYK$MsF1? z)T4e;1(^*ljV{9rzHH%Q{;MgjqAs#sNo~%)AMRq!h@H@EPADaJ!pzL6i;>WHiesiD6g<-<2UNL0`aP04-?&Jn$23(xLUS$qZ!Chjw1T-i}g4evx z!3l7A##4V)eVbNVg1sTZD~jn=iYG&DF9pO_;}rJ6W#T_J{-}gQ&7dXW!@;+?Sw5IU z^KHSr7ojeS)?*{KJ9Q-V#2T9pVD>cfSHYjHi`#gTwu%(mM&QPaK6#F5JnME-TU#0v zj8i=-A<;))NHdX{VFi_0*LBVDvsbx09_riv;;wMiQd3hy27fn0v*DwIZ1mo}dqv|f zFX0JZ8ZNro{s_bZJo_a3H@tbPY*#ti>#TU9VPEp^fZdI$$_|V3sPFab0VRp#1oJGK z(6*+c1PkR_UnjLPCL-&)}o@}DesFmDK9fK%`Fe&nXI|7D_}vgF%bm?pI9r< zL$>4w>Om8|u$3CCe|W_$h-YHkaujcBn6@~o{QULn$%xM<(44@nKHLx{CdJp!Z)<6FG%C*{BXC^*Xh*B>aBsp6I68jyNyWEg}5G%h1tMJ;wul zm$KN?>GP48uUpOwidq}jwERY$Z^b@=*U0@5yV$mv9>%NQUV1umSoD-jRhFsQMv+*$ zBJum3PO#I}I|4sqYT9tNmLOaq0-yas^S;%N^6wgI}T2a*j@OLkrtcy`n*JC;lk&bep zQ-RH&%HtHehRhEcn3viqkw){tWw5`}tn!x1eC~P}m8FL1S9 z)`ey&slx14SgoBO8r|bub}UA6c{R*7U^^TJ|8b>wPjD6uH2Wke*y&;DMa}JY4CF?amovAePNx!11_eil^tY&*cWAmsDW#hk)}SFPU7I{4Jv)}-O= zEi|i)g}D;;JSDvRSmfHyaINEXi7#fSmvbdwjW#E8Zi{_Z{x5u>7Mh)r>%kAst&o8b zczcfv*;!gC)m;a(A85#lZ_~%jq7_S!df(ifbz>yU6)c2TE^8`MVRJLsozjLEL?f#; zRHxrC{M!zWw5Uj#T7ZU$tLQq@HmW1Ny0U5}crL4?#RaSOJuxxytgi0l&!4YW?W>t; z-#=`iigI!zD1nFfMw!U$k8C+^Wn~3xLe|`sZTb3Fuq$4Xf9>g7EO@gqZ`Zknu#YVCw3$0kQT<`s9~7rqql@O>3EIWRoL6-7XrKxdpmaOwLk&-bud_#`G*`nE@rn zMT{;JFRL2kzK^R%0*SA+HCO5#qB;V!`5UYE@@KrpPvTPw3UUfgZNhDY$gi4`9~9GW z>Wcs-JYYs-m`r?!n`GGkK=)7(W-G}yECx}}Z?b;luzd1-_qGmvUb#trgtMI{X-E@I z{{+M`G5j$~MgCSfw0zq8w&pz5fl*S-ms?9=0_JghE~wy6W_S)L(mV%dXh>IYae~v5 zMjnMa!GqXEbpLMN>=pQcXf0x$;AL<}UQ${5SK`lK`xlpwR@6io8Mvov;cIFfD{ni+ z)xM}Bu^$!H!Iefx=+)@4w6U?Vsy3Fc)GKI5Y-}ullGJM|lbWGe)Vh)pg0Bfl1z56N zVQhT-?J5f$gdgsx7avFUayVx_GEQe+>$h=yNJ{&XIl*8&CyT~2&`WOLD1+0ND{Xwj zr-$HKQKUFA1M`q|s!k$$`0DWuRKUGru!(|x+d1bJd*1rcKOpx9{;VDV19B*vplK0f zHnDpi;7z_T#RIzWW%R{`cAhN3_UU0|3T5uc#Pt*ef2h?k6@j9-WY#dZ?9%oUE)^-* zYO9c65OGx2f$6P`M@)g{d4!z!`$pi*qkUDBkCVe`nyaaWsiYlWe$ zDW5!Diry(0yHy+ptg8KXSHL;xuG6`Fay$gd}icK;z?v($6u zZJ9*Xte3z)tn{$EMn)cvKw?~9ZU4*PDxfqRnCCbsp6;$zfO zr5rt4_!nMb&);QAy&-AqGcE;<1 zZwS#2d#^o4hG~!k2Ud);cldZt*2{PE>a9RFdi^E)|J1kUcmBiENULOrqFc6=DM)N= zAo)&R$TapnZSwhL^GlYNuq21ynR}4k$!35CiS>Fl5-klm9O|s@x|Iq3$MWoPI%@vJ zKxaTUIcZ+}=|=6F*0rF#TQGL1sX-;<4)i`3UmP!a)YqUA4QapWxHaWc_mQ+id_5C~ zy4xhu{3=`0@n-t_p1L0XxA0fkDb?cf6q3~2Iz{r?o>^FXFra!)YdQ@BHAJ`SuRYSP zpx+w`_oPw3pz+q8(K%PuCYe4&#OLzD`dg-bPidTM>~y9+TNg#LVd;%R7+7UyF71rx zCdi>^OK*bMJeBs3{ImM|hHI}beL&a}LqJapS=6ayi`WdzOnDBpt$e!OO#C8D(YP*> z7P{-*4m^}lz!tC{iW(8p5OZ9~lp!|QlGDEz|N6#cgKL)~`{&Fl?+D|?+nxYy0#Nq# zt2sC0*X`5>BCSH0MKX6@^Ux@H{vWF5YLi4e`=Nj87MF{zvnTatgx_t6!a3lXL?}6a z3z_wvo}nTDw31^xha~><&ei^6(L7X7#gL}E9X2KF-fK>v&8sqzY3wX)czvwIYY$aD z?Q~Rs1lH(1Iy)@`4^0X>E+bGD_G)oKY}jNK7couJ` z1P+Wss_{2i>QJKKw{B=LJq?f@$=N zr#eXsceDcY{TVWcHLTM9ll*p~8a#aiRMZYzr^DBee@6&W> zYIVlNvthozO@Q*g`TC^EvGLAnkJxmsUETBQcO=enQwsnSqoSe|L}KfMbmdhWGI7Ez z!z7i=Yb0(KIxCY=Ls!oxkT|~q6F>UTKhInbgOczjda<^p(Za2#rP@>-Nwz{-EEd0F z#w^dy;On&AocvE*V%Oi7|3lUE#A~M*@da<*`>v0p8_Y;A-nfZJn-Eto|9VVh%ZGxY zv*vxKpOF^x^HsGPi#?{Qx{f;8csFiy9hI|`d1lWz|MX}^j)KiIbFoP&$G6Vpi z)wi2Q$UdvB{YEy%0gY{l!(A(0vOQpcSqXG8`|jje6p}p*vz6%ZwLKcOK%9WG`<1pZ zcTW{JQcQcrT;3NH{G;lh%BZg*L3Vwlijid=aD~|$WnI!cK4u<#ns2FXuJyd~Tlk!r zX#?W*<8qt5kD znm=&1=U#6?L5<`q?<0~%v*?{CDoeu8SO5A(UjU39hH-vY?W`tePdxLy^O2O{FE;nB z#}NJ+o<@8XCCnmosLXo*MvGdh8hY+eY~&rA0THu9v3y{|64@&&sBY*#+yASZUF+7y zR7{R(!I_oh)sON8$Z)b^+#v&Bx-R+PUodkrzHsQ}83_X+^8=L_S31_M)=oF=C(t-R z4WId2!zBtZ=aHRC2u>H)~(OuuMf?j#N~Dn9gaitz^MI{O)B^%B&VXQ=9?+P6Pf4kEKJMsKub zAyn*t)}{S{40@9g<(*Sj`E_C@^!IKS@*tt85;nAozm=Z&ySMNrKi8qF9G$c3{;R5t zdd}Bd@g^Ul%=wn(QjmhjEGFVdO6#_9{cYyE^|v8vmB#r??Moe$Qo-B2{6@$lqsjw& zZ0Dlx;ZxqR#xcAzM<+n{($$4K$g_`khFH<=zj<>aM>dDbtge`R!Q>_j3{}+ix z;PicK?eJV0!G&SeebTTw;2ey}O6i)Q=rv#~CLdIxL#rRx$q(rz-$WWN!?9svWT`Nl zlqI}bk`%RafNC=P;rs?$k@S8b5jmo_KJ^@Q=V$D$P4$X@uW8>$|JT{&_Xl85s$v=u zL9VJo6wQ()DM~OJbSw3p@36C@<_npB%wzspzpTY+bqa6Pnm7Fa?s;2Ocp}e-vgpto zQ@T$nN8fDO?IJq}%Y~fhQ;2u+5O|?VlAuj;yjJf|&89i3kF+Xl-J4XmZ_P<~KS}(~ zGWIHqI349yy+?*=uGyBFD`%JlRNN2!1>|3E9-~mkSWK7Qg<+V6uUPluaiOW=2O&C0 z#ZvO+$Dr_r>_lgV87XhfP3gpG7y+r+!_y2R}%LB0+rys!?zl*@rzy zHq9p|Sdz_E^@7KyCTnY=LL9!#G%u+2UfE>)(z0@!{O+YO7Rf(lh9FLVhJTpCiTn(- zN%M~l%`jaJ{ytl{HJE7pu_OxdOs^t^_n13$oLX?lKGg>u87x!J6vo-$;Bnr)!Ub# z$qF$!XvI*1L0-?cn#vR)$LWSHoi{&VXJ@w$h%|A^krMuF1cKs*j)FS>*gD1Aglm7)VyB!C)RlDmXOTk;61}fmnJ9YUXFd&6y)7DFe+Bz?*w2e zmPuZzS@4Aq5uYooaE`{jlv#Wqts-;mPw0vl&khSO4Ibq$UYxzvzp`j&iNp;m_f37` z=g;#Mc@sTDFVV2Lkw1Tu0gbzJ8mRgAk$NYF(dd#}@@p$BGe>AE#zY3TOgd;vAP}gl z3qf&UbC2A#Y?BCI+0qyUf!lt3=$6+~U8086`>i4WCs?Ok!9_)MQ?vFD46I@k`2#U$ z!hsOBCij>F7h3`K0aVAC1)So{zm3;k`!8^a^2-;kepPMk$;obdH;$$@^b4<_$@&0+ zR?A8ZLsoj5=c~GVRC6#ANToDe+_j!mKGV$Wn0>KP-i@)&pCb3Uzv|tCETCs_LVG7B zqWxONT>0!hQ-0AEK(#~qvY&dy!;g;|;!+5$ku4mdZlw3PPnAy7QqSP*E5nDQA< z@w**2g0hhA_wd@qpWn^mFevB)%E6_gO68=#wVPw}Z;k7fb{Upj_RQ>Ki0mZC4WJ#K zpq1^W#IvY)@kZ-dqE7EMzA%1MUekw_^oP<_j*feL9aTIc<8Q>7o3AM$pg=h^INAZ@ zj(}6xKIUudV_tTRawJs?x>@9IeK-j2+Vkhnt75x!rCK%jvx<3W-)ceIqSHOW;Up<- zy`Vkyb9wm)fmJ#H$W&*!Ni-*+XD_d-O%*#FYmcOhRN?%|WVeAlnSOF)M$g#=@-{q9 zP&sB4$Mh%n+Attln15H4{_l!%agH=@n05y%pZ^XHz(gLo`0)5WqvfjO3;XL-+P5EnFB^W+DyU(TGzx9o z0?-lcgSYhE2}S?RV@gU&SChaN34Rd~W>0Wt@V&T_8L&5CJAAa>0?J{aS$`{h?3_{! z?NeuGv@lDsh8|oyu#WlX)UZo-2?>BEWZw)UY*_jSxucc~?^qo|v;=tt^c%}8ZJI4% zBL5yhAGtK3qTPA{_hsbsaTwEvE&>37-wWAA-8~C`?M=F4!iH4a2qafGZLL)OKHzL! zohdk2uj0+KJ}J6ZajmfFrnG5#MPXETMDmaEAVhp3w7N)hl2f*Z{H$1h$Uxux01r4& zL6FJO(F+w56Q*Es!=B>jMI(=ji~FHawVDKPHUgksQh0@GH^F7W!?%;yW@jMOfolN{Ukg$)K#E;s45NbS;U=i`>dJf91T_aB;SQd`lcq5 zJ%JU&)5zV=tt{7$7eoECXrMR**NYn_4I5FT>&{?y%>kxpA|qwk?5OgJNH@3ar%1Ij zvEl$T_w`vglEYS}rtWzccUb5ory<#96@wE41wXbuNTkX{ll?h5P4*Z@(_98CXe0mto}Wp+krEQ|{OGV50? z$Ehb6_d}ACk+E<+I%HzP=GE31j6^o8!AVoRlsjiE1+ z`J>VGn$b{bBH2r3^5HQ@715`;9+Xa|W)S`cAv)B7 z4KJCsNYP0UD@O(YCkx;b3i@)At(d2#d(Zk4R*=^~omhT9`OAm(iyP>Xb9hBXV4Y)? z{Rqfgb$Z3FZ;eX=-HqWDvz3F*-+JCQ(961-hm136l;|7NOPbA{C--uB+n<@;J96*m zhwRzPhRIe;6|RSgD}l}%oYhU1afT0t@cv-0DntxOJlm~ORAjF?rYf?+k66>QA`)=PzB`~_8~+%t)Uu4{!1AEz5v$&*dH+Bs|i0)>he0g0*`0` z$FJ-3wQJXg;+?<+$DH-{>J3Da-($tx85w87Q+v29xb`yFOJrpKD-D95|gYR+afKY2Ix1{EfA4GtObrsUeHulkXtUE5E3VdO9e)z_ap8vraH4zl98p>bZ#2jq&DJ z3fz}|%Dg>Z9hjM+%wKTs%^&9@p`k9bIilsqTMySgNZ8+yRGE?^`-$}uoaqLtH*GDZ z?vPTMXOZ-#n6Yt-Wy;aUT6)Qjf#JoiE9_x}d{+{LU{iDp^d=zNs2?#WB0?G}?UWF! za4%gdgmA*t0>JI}1u^9cpk#x91w46>MjyzWVNed$T);B9t-b=YKMOhVg4N*gd{6>CSXeTh@LjvWgIvYDN| zb6Evu=yz|y3$m!EDk56W-vn9|+uM-Fmw|bFi0V_^&J>2*Ez5pWrHR!8VNKKVu{1w z2UAcWY1&sc_RV2!KDFu$H#>YSpT3=X@COUh0SNm5R38ZaxNDZ=0TwyAo{K<^mB|0V zt!L-RGG?qxQM!yVENl*k;nN`eB~Z10aoQo*I1gJB?BH7^{g1HYWW_Wfn%K7b7g>@e z(~YaVNPguZ(~JlT{;fdxPLgB6J@UPJB?kj@@w@!9@VS1RVb}V6MaBKfAGxpZK$Dq+ z5qQO`4@LLq{ZP4eV@(JF1-Rp^o?af2{!D5YkS_SwmNQb=tvXcY|3YrL{wxSJHmB}Q z>k51d>sDs{l!oHgvjDmo`}60cVz-z}z^X<)L8Z~c& zp+uP2GUz?D!O22Ysx?!j71!p^#y0}aExVq)r;0od2^DkiC(Hg!AfXAH%K!Y)e-Fh} zRcb(NE!-SNiU<{rg!wjvbTcBL)zAqI#d%zG7;$SKO#I8%DYe1v8JLa|<5oJ-MgK46d2mrs#jVznkzqNT0`dx6?MG&wB5RJ&TKrpNyq#s(i-{ zh4%^y%60j9C$*GI4712RHrsc$Y-BiqcLtu&dYk)_znp4=7*csc!w)F<@Z6(`9a4rl zbYv7f;s{VBtF*rdL4a8dtquvG^4AQ^7MC)HI$M^-$c?o~|(jIDd~ zKgU3>$<57{{p9YG{!vq%B`4iH;7Fb z2pJ}QEK-Kf!HK5ZLZpq##;7}U!(VHPeod6TQS!RUZ}Mbl(W{jeW>EObo{9`_bWn?F z$cg-`ZNpKlfNQc{&RKChNm3qmyNQ6*5m=>orSU`?U}$kd(&ze7}bL z+MoUSeHPs%b8d&yocUb$#%Ea;nnj83;-!TU{K94T%5r|UWf_4rC0w07&0s&%TKVnteT|wfyT%p6uOoS?;gi#u zyi@!}o@G^%rDw|&qwA9`!?#_@E+x{^+78}qGhS7rWNrqk6h!!evx7Mj_}J(fyH$G9 zDRU~|F{iJuZ;{|$F-VaPc##$^4s9S0Bgn%$d641Q+eJe?>ew((U?;496%(sUKf}~; zdjD4wGkce_VNup;Y4YNW>4DdN7eD4m6xlwtity0f6L}r-%l?17at8cMC;kW z$Jn0Q7xTJ@2Ut|{*jd-xnr6B+9ABc#Vb9m6-p3xSC}{4WeSTyTe}!t!SpR9AKF z{2|Rmzto6Yv4x*IZbo%1jk&ZxaQ&XFZr}X!iH-Sb2RjRgwFk8;5pt}5dV}<89{X-4 zbEOQ2m=}w6ibc97bo?s5lebrBB^dS{a4{jB3X#ZO-`F!Gv;kyPJb$R~L1i_3=GHlM zLN(cyskF0}mOxSf1!0$u&N?1REks$_Az70Wm>CeZAg3%bXyEUdHaW7vK7p$)K#Geh z{TEbi`wKA-ImaCrxHzf>IHP;dbEY_}_)(WjXIh?LXPBng4T>gPZ`${{PlL_)>boi7 zVuFf!MD6l!SN(rDH)V2~I#>{smlrm|RXvx(pJK|;VPU;@)q&3ZTxu6EcmR|ZxqON8 zrd(meBPloqz%mH$9zA;W`hm8h=AZal`8hIuVQ0iEn7$6CC)pa`F}c7(XNNU}e|TJN z9E#*$;`Y{yPyB0<`}z4b&&`#c(||OAHfi+)DRvKAL1tpkFd3{C6)z?m2m1xocul2) z24CSxLBB$=4m*60RvVz%tJ`XT94Dr{l0*!!l&5E3|xREFMhyVU!2i%ELU+n|?B|%^E zAr_)uk)OVFJq&ORRM>8ZQhmdwhyFK3fD$6#3_&W5YvgA$R3X6DP%Tzrx~1u+#0@U8 zYWdvX;p|Hy5l(30g<#%79)f5RW_^s-n@kOb#8zHUO*`E&utn7PuICLSNxjBPsv0}> z4LBz~G9vr$wKL4x!||6vAW`k;-i`7^icf$CJS!g4L?XOEBl;aMlv|M6#W@+5+59 z!L@OLYKNKPmgT%EB#=^ zs7)~4($ccXT;tHPjk>*mOly5n-ve|+ATI%3yX!PKUo6f`a7>^L2|eiy_(fQC4TB=) z75IJm8GAv=iP`%`p=+@|mWEPZ`*-=ef0sXqWgP}-GX7ywZm5R49`-`0=IZF0y=bIh zZ&>JbsHW|Vyxe+l|9J#!%-_E^veyI^SmImVQI_&Wv>7v2due?@!BMfwLw2sy^itx> zSNXHMi2Qg;v90i8A~$P9qzU(!b8P3IN+o6n#uW{ge6$1PoqymcSoYXSZKYF1{jd#^01&C04 zyRSCHxvHK7-pyzeY2))KDyx`!Lc<-`aOnd1Ag6jlm+EOW9}9rdC;DiV(-NU!Sqc>B z@fnc!1Y}60w)hM@i>9rpUdvaMryHmPV&+49F2oBr`CV+EY${&AHx#dg3oT!g&$pzf z&Q^NKuFq-Kg|G0togs1h9yK0U*(x09eU^D+Mra>(1+wE7PUNficg>D8DkM&TZHKLUBiB z<aOxTy4lPbV#~#izmSc|F(om^7Eq^< z|FHh$I-nbYgd2}EUSb4)4cfd6%qNhOxRy6V^;Mh1iNWs7NN-3RXNrRu6g4f3+%o(~ zI7_E3@#^1GK>C~HgT&fe51Cv<9C~HHABk6z{v|T};`~sO@nSTX@$3oF2@kf%GgBVHcqrle0(! z|6khzPQ$qFPSU3LNzwQlfU+4LwM4$Aze_+_2~S9i9K*%J;9KnZ9hup#&`aT+>mDu3 zk>{`+-_$+4JnjFEwiL|H)t)|XG4{10rL4#%I8rk1{lk5MX$WlMa5n{n4S_|bzYka@ zz=-|og&NdW>a-)CF--cxWP=7evn1lF*frtjy}t$%4QR|pN(ac8Gw5brhwMD8{2YiV z_SMp9m*q`m_P391NY|js0w0i#{%PxHPn-+E$$Td>aSk}f?c%!(3TwFEm;QP^Do=_7 z1(E{aD0_LQgL+-DGMv?`N@t$iru!c zSMrWE7&p}^saE(;4^s25tw+~!_)+_Aq>H+2y+G(NiJ>Q(ueh#YIA z2&jqx|AR>$K*<}H1PsE&Jrw~HIq?s8(;##o8aj*@&&tlOuvS>~tBAqrf&|CP8kflf zlscK`h9QX+1R^aTdqM~w%Guhu5mGF#I>-g12>`NrX`cV2$ylxp>Dx3~1hzj6REyt` z>bf`T?-(yofeQ)%59R8*#~n{_`N?1(!tezm(Kt*bj%jAM<4K3cbO5!XhUMGg7tIBg zxOLUIj=6DhpAii{pa20WSJU+WTImnY6Q4kp&FSn;iVH`4aHo~y{X1%dRBSyt2i zGm-70g{pO4wcH6WkqIaEO|A@ca%8fL`4&jp0{f-YK9pP+`ToqzRZ>A5?>_rYS0J%; zkjLNRSW=#ETNQ-xo6Q9W^P4*Q>s|>-Zv#t9kk#La_P8b5ntF_U z+Qb?@#QPh0yv|O^VH~}w(bS3mZL`2{i;gEd51B_s1iT)KNZ zpTS9nM86ySP+Wzm(f-oY$KQF_FGQ5qqiQ(w%H|1(j@{m2!-J;W;CVio?2Ba)Qtj5p z&iva04Mz>qR9crG3=zHaJ&vSwNmmR4Pa%4&W)&}8?mdN_1X*kJ9we(zP*AX6KZ5iR zAJDF>l~Si@OrvH!JO zn-pO%S~XHd0Q`i^ieDlXRi=rxZKWy#-UmlQHJ?2S3I>5 z$&6OtOk;vR+oG~Ub3hAkSZs@6SOFwG&GE&a^N^DSR*^^ywunxad~Q1%SaE>dB5h?S z)&a8}$ECb5OacLjO}*fS?w~=kb4P>FH9g-S5~ug-Y|q_#q_^%-iR(p9V#CPln1jlP z!QN~cp6!kMo_L3?zI=oee5=_}aKAatosgz^-c=yAeKt=unPBK}MJ`THI8N`2aqypq zPk-1dw`Xy8ImpZEt!q;x!dnV~A3z$Fpc<)(SOv{H@cR=wU>_<5AfdP(Z-3$$66N0S0^qE}L*D7l~hW znpNr+Dix_DFEeWWEpjmw6VASpofzUhCeBz*P|aOk8`HS39>)^ixXh_}n}PG`x3(sL zq2d&BvExy;0l`xpUbrtcwXY_0OOobsw@+5Z(}dC@TW^7mytGAa0$1_VVf5FA{z$K4 z@!?L+k;dymrn2tp4ax!IX+M2?o8srmS!F>oJE&2zP3<~Q)OO}9C2)dr1GKli6DIY>S@i5rMP2kG;v+-n;TAN@~Jl05+P9Nj9@SIUxq-7HJ|Y zd+4UT?(IHsfi@6e)E8J4TJyOupy&8h>S$U-sm)wo_Uz*{=dgH9T;l`p3 z1u!R@-y~7kbo-7?$7UQAMyCu*PqI05wkl>9qNB1L37dJ4sU5(l|3#esI*JQn*VBAE z=xbyKbrXYE>u(Nb3`QHjSi*xUdGPKuKf~CUr$aioOSaBIj*GjIAoE>5zyRY z+al~st~5~HK>(>k)xcafT`nYF!5E|`-WTkqvN>H2Yt10{OtQ>XFrH*_C}HTDR>&6_ zj~x%UNa%%a8z3^Lri`LFC;beWn`RfV>%l3>)_OWOYYMwXV(XdI07Q-%nbqFfNzu0j`COrzZ)Qg=UFmcu;% z|3psZucyNkYuY?DPn-i1i=g0Pz?Vi$VbiWu>kV49=}v;-ya)geKyHga4@{e`F8jc8 z0B&PJ3M&Da0gKtPw92M##&tg$PN~A*fYA5HfvV_Hg)U&#dOU9g*DQov7ZQg{DDE;g zKLEr1`5j=C;tHA}55Nn}6BF;wHA9*aZ9YtIyRIeKm{|z(7BV6);MlL+339IEPuw;< zT_cdnstd6n7_xo5s+I77MA%W^uz>+k^?$KZQEh9jZJJV7Qvbc0gIX*9$pS1m^Xrp2 zvC1~%%-kDx!V{I=l25CfcHHnhT&nbm);@hRS##im<@H1IZkCS|2`_e~A4vqMKUmK< zwF6F<{&_@?7n;9QEX%}OJ$Cv8W)p##-R9hMuX4FRPjCIuZ9)CjTF01mn(SkKLg;Q&H44~+-?SAY<*Qa2xMO(q!*#+XXvCUMn)%IOWHJ~XbmTp+%^Np^g$1$K?p7E)kBJlU8M0fc2Cb(?XYiX zR<*}{>?69GNwQ-x{({Z*E4nYDOM{lOnvA(BkY+bt6ZdQRkX~su5NrYXAAs2^L^+po zth{8H*a0$tVCddJ2%vlr+4`@5lD8Ylq`M`!mo+!%i^=L2VCMM~aFBo9&pDEJ1IY7y z2DeMoVgS+OrO}5#x4Jn~*l55de2==sd6XcluNKldIz*ce*v>h01NrH67=v*bWF4rh zON{z9v>F&M2(LH`4n)Uq_`cwKIh&*?Ong&{y5p%N_s#U_w4XrgubnNWnbp5UUf5-j zrH!zH>=2TIWMH3ShFn8~0{v!45B7<;b?o|9|G_oN$aNLFCN_77?@=q_c}vlCs1;#5K4(?@Ik zKVc@OdmgS#2OJPWww_B7cna=51Z{Tx;KB1-KnWrBSnvQVWdMPG6cW};^9OYyqA~?s z7EqW^rvs4y=mUdZ?Ho>RF^v~%;HR0>yfN3_TOJ1_4YrKZ97VBv{nH*naGRj!l=?hB zMRvUEl=_CJJ8$&Y;#+_X;W$&V|63$NUw0(k0M#*sxQAD`JN2|(G$;3MqIBiY!@OB+ z;cO4(+LQ$_!M!n#Oi0)qovGJf9C8yLWc5+%SWWA%+rKpJ{=^kQ?45&XfB7YMb1ZjzBZ0`iws_5uW*gG>4i@?DWmT=zyZ zvs@%#{d+!6~G8t)*-Dt?EIywbD?Jx=V`^9lnwxgFd8X_(DhQ?37`T+6V$kR5&giR82BaX05r^^3RZI*8Ah zy-UNt8wUHB(1Uz6MmG8sCz&r-jC?cIniP(v@sRsSf6iS9*NC#OeMqXgsB87=r`DbC zUUSA>J${hKog*5(P5$45eBw{6tE-X+jpSn5B;VcW44kolOSIe<##9Kjh;q96`a1aC zEcD)F_7|3RooRS=v|Xw%7SfLL5TzZoq>mm)oN5%-E@=bke6dx+w{S22Jp+W zk1(Lsp%@s?jIO{Q>L1^9T5N548^LYve*TUSYRAc)5y!yCN`%$~pZ>mW`ZX#tw<#{GFVgt)TY&)@X8rja%lF+}@1z>Q%RPOSS!27q?Lkf_-n4 zo|hNBOI+>Qy38mYT2r>#6M6l4ZicF^4)H{`jMk~G#K*^Cd&iGI=T%OtozlzkAJpoe zCkRrNlPcss8DjHX$_XN_CZ1T-=tJ=z4w$MU!2ml4Sp4J1OGUR% zZ2Wqaa&xjwmPU-^_J>XB$$L+DrSa*>oE~sY=se2Zj0kW;Cj8Dqmbw@b9Yn9pj*)r`OA1Y;1yPgqfa;aVJ zlq)^{qZVPxIt0~h0&NaL*!^jA8V{kJos4ahoQ)N;IZE;FsG}N~U;5B5DRA*f{Pu-l zXwpB$jX7#$1oU)zw`XqvYc2c*Jq4qMr)Ioy0FM}aq#e(x+j#6d4>g-iiOzXY@&o#J z)v;9#U1hrC#6D@=X*=%Mch^p*sc%U$|eN-8T>vaL^5Y1h)>fc(h+$JKYoQ{BJ+Bb8DjLPchF_Bfd(6rqfp$SC6=!jZiW zvS*>}y(%GOuac3S#38H5>e!oe@Vk!g?(gUE`|G}CoO9l<*Xz2T*Yo+ju2-RL`h?JW zVk!S_6y%xL7%ZQF06a(-9RZD`)QY_cCnh{)d*Y0}+Y0Vi433VPdw3+d*L6QVe&&@< zzM1g(nnCEz0~_l7`}b>ISNxzIRU)(lDf~SfMFbCv=f%kd=Oic}p)XaNXJxjRZD3$v zaBOUPWwO<=#;_)hne5*E`;*-%Qf~_iife0CDM>eHK&~<>YW?_;7{Z|iyxdRwTe4|0 z`9<{;y;(P7JEky^S3+6A-R!|k;1zi?L9-5jyHQVK76(!;`qB2D!B-Kl_@r>i~mPkMe{2 zTO~(6N3%Fg?)?CuIo@07P(Ei@-kf`ehGitex9E2N`JzAk#(!_m>-~T>&pFr_yu7?b z&|=nBS$}lR+k)0TVXIbDO;1mcC9b2*)hK$WhkI>rCD&Rusq6bAA1vR4`tFqk#Uq0E zf3O;^9Ud#PhSLhMbc7}UDbJO&>@}{AAa*X9tC)}0QW=_6n$)MZy%f;Wuk}T!Fg0`C zNq$;R_S@A8>kKVzX+Mo9D{16ee@mI>KC1IFER+7>mex;>p_=eoVjg5JX#7a(j6EE7}%H#VI1 zw_D{_K|IpR?|*x-YrbaG7FNQv0c~%8?X~sA|^EucVL5iXi zFd7Wm)5!;CKJWvwX%=p73GmnI@vFCG5AaV;29QALFDSU;$IKklcF#BG9^Yy+o$+#) z#Q5^4%Xo23O~(VlYu1n1@D01adFywkFV^pE4r9D+X~nxZFV@;UzrJn%$00pxOC8A4 zZ1Q|+%Dg66$-2u@boW=!@yYl*ecw3TVR1KvBHh@y!am{LljG(ewDj>AENtN{Mg|&_ zuJ$A>Ru`(33X%JDc?q!jB#EYn8PxDet_u8~JwBIsxO~@L(}KAK2q(5NAYtita#Yg( zl{??N$W?N0YPcS^jQDyXM~gwT5QE=G2{Rd^AAhCEWSM(+Q!dhKj)7N2;|up?nGAXP z3Ab=Rz7RSeO^M&TXbgQ`#himgOj8(j4@9=w+RpFaFMtbcA5&5oB~vIM zIEBpEh<9L&(Q1^W@LYR)pPxHL2NvN!Z8@iI2q%P}dk?Fhl#~S9wq%G8dJjjcox)aJ zZH_v$qCU^8{aSN_@JTp+q8I8mT~)X*NxOdd{hMdpYm0HzHVz({j*bpAgGhVrep~EQ z4Zc`0YLVupL?4J>@4EvBK!ZPSXk;YYsObL3rMxt6Ns;pn)zvC>MtOa6%kx8o{;`Mj z--~%)sDLj`FhO-$I?AN@R*vRFbMt^lWh$?=Gy5Ouxfo{Lg&nKK9|taJh#*O}%iL1g za_1nD3@=Q$T`I(WKgzw~J}PT*zu+Ze`VJl4297Wq=B|oH5r&&KY_p0xa;L+T7O~+j zlN8QMv6NpLKTq_oq(mMzm6Ov8W-{o@OCPe)*R5N|c1rcBnTJmz#LYX&)=><`g9)~U z#+}$jPqA*ds5JIA>#(V@=~;;lY23GXM2L81c@7^1tRFtsnnh9 zhMikwHHEjM*=-&_Ua>paw1fW+#qT~UYnR*WlUspZo?cd-vVvkr!?~L?eBk8d9Jrj; zX2wNx(#FPSdB`G7ueAp|TR!fIr%^29gOLzt)3aI@oJ)TbVctH5&xanz*Gfc9-7DsC~ot8jaHWQ==P0`*k4wkfL zw0xN6uKW0_`qnLzE1Xvvy?Nr*AF-`l z7U)5!4U-Q~H>GX${GE&m;E&wFvQaE0nWLn;NZzV)n5JQ->-w{^K3CQ!C|Xp9gh+(# zskRTASC4dATq=DxSh+YOC(wmip-1gwBJWgBA3_#NSw7Zw^1~&3IE^EtGd+vO(r=wy z?qw*oU$aE+t;h5g86r(~)gJioT)b|5i`r56axb^gvt*UM)B)1Srx$6zjpitiy6+witwzk%R1iE6u@B!2hzAIO#0yCV* zy}va$ed^+?r|*6Kt+C9ssvHC?bvRHNB9XL6&wA$b-x>?h*3milbO z!Hy1x56Td`Syf8!4*KUv(F?tg%DRKqID9ikZTlXT$*yPYbKIMkKi(vSJ`(&1hty-Z zQy^BR9|2hcuvc8ikfLRQ&h2gtxuAeq58779>RQ}_LmJ&spQy|eM&zbl@(M@Y{9{~9 zp&J3}Q2L+gXuaxjh%*~KnuAS{6D^LcM*oZ$IlA#Vb99I8NwDnqENxY{@_UZZYk0fw zmSu@8p1#@8(>j=kpJ;D5rD7f5GV4kjL;s$m`8x0M=GV7Ucr$N{ITi*-KRWhc8jsy@ ze?R;f>)He2lxmxx`Um*<4+M$Q4fwVAXscY7E=4Fkg$x4=!xh&7t5{l50kdL?uFya} z4&9AuYmyxH9Iqfh24M^iBkIl3>(}_>vhH#X(h&8m+1#l>^;j1G@>BX^XJ@wt^v~Mr z)a{nZ;&UWhTU#gmd|;A`19sp_qhOPhAy~Ev`<}3LE=yxMeRK8>4)O&$rVt3h-&r$? zeDb7kzjnw*^R;#*`k;QHa2$|If4(jR=+~q>O@cjf$Wp7(wA;6D!@sEHoP9{IpZBV^ zHFYT-z)d;H2eQmHRA1w;o}+8h$wz%GGC{-H8w{PFR1JG4x1SX=S zchJKIjVG)4dVt;Qz_%#HOJLaTe#26I?{XUSbaoD!;Nj%@0XO-<+&#=Q*5xpVP!c3w>QNo1j8 z<#RIE<7B?9B0tehHdG&SlsR5`llPDK_Iu1aK5bgNrS0?dMj*{NN~1o?xh_h$exD;D z4Fr~sKNxk+xn>==Cm}l%aRfm?_$0{8TB`QeNg;rou%uuMP}9PdLXa@lHNfO(^Awkt z2V$!UzY8uVGhyxgf5asuVCaHwkrB$()zUDz5UUA^YjBWRO^dg1#^I`tuCCtw`&rsN zD0}-4kVYf&#OnG})LZ#Eh~{MhA;M|FSP$QY%phv@p^;*Yw^RU6mtSyLPAhs-H_(&%I=$e@c{}+DPj10@ zIj&inB01&TSzF4SFDeLs33mV!lQj;fYm9*Hru77O*mN0)M0dy&p3bO=ZMg-XEasG(7<>qiKvhSxy12+o|whaTt7DW8bIhXOoTbL;oCo@*mJ__zN_PgatB_ zD9l8-9s5JhPZ~(@*EF}Wua&vYyKQxwa~8~GZJiblab2^d30aL#-p{wY#is6CthtVG zNr)|elD$VxV|866S+Y!|Igg~CDLm+voa%bAQWA-UM4uw%0&szl zzE)hpQvxuZKCs-{%g!#!sAx-R<@>YT*AbxtG$$d$1m)yh2Ff43<$`X7`VnfqETbam zVuwPbLTG1t3!MH?-2ss$dO?pfdBzQt?|}hYLM1Wu{X6TaPfseK?s45^S0>bqbA5T` z)b)3{3|wnFv8j^?i{xjKlW>08kfr6+BTXwkH5;*-IyR?2eW}iJadw7j1V{u!y^}$} zIOnwI?+y0}q6VUAH(8LV93=txI#e+b;A0%X$8gMLp_zx^5nEpV;(doWrdLE2DuA|!vW3T zDEL05L}}fHVWxA*!bku{vc+`}-`mPcxC>A;bd6|oWiV6_a3Wv{*bfP+$HuonPqCmS zo1dRgM!hkF7^)dMJ6pd9Ndj`{BJGf{;oxl@RF#6P#7k`M<_-UIUYB(SWPXb^eyg0cGAsH zR*riDk&8*+?HapUF-d#5c_y{3oj+5TFH%pJDP7iDcWgv-^}5Ilw-{3VI6kX++Hmw* z^Cb9@*DIFDL|1+T4gUvnK`H87qei1BE-RMQHGz}0cfKBhn%jpWNHj@JDeHMe=h*PD zsf9%ld~ArI0sf|J?H7p~Q4IP8wBUxA0?h;rcZs=>Ko&=;Oxe6D%FE}0b$Ra8v*j)W z8Kw~H02Mnd^L0wf*5ZiZG^XQh{yhS>sv(3`*p26o+OB~^HHJN;fEqHIxY5`=rgB*A zGVmpwX+1HyfXp$@JxrG_mDJS{@?l&@MpzrpHes4M66Dee>ZhD+dHV z0GO1dV6FXJY2??e*vj!wlVg=dsUDCrp_$}YxN5Dk|0b7Fwtu-SyJm$hVEYSyhbD}- z{!?CO<5)-a`hhr$tvh3LKU;REg6q-kYo5Dx*yQubt9~7P_50r~Pq&fEBnW<`kl|!c zQ%5=a%Rj|l&+r2h%j3$ocQ}pU)xNoJCovG+AC*1gd?l3PVb-gB{Kk9s#f&`UNde97Ey#xN|ab-=&WZhA;Ef>3JoK0a zOD)((A$qp71n#AxDt797pnM0IfQW=b2=FKvyWlL>)Z8w<2PYfq>$@t&6&0<$y;N|t z0irzbLh9-3XZBjcRNUd=Vb85m7yM2SdKyBOdQ+G^*9X1h+wd2G2#h7P zo^I;*Mm1vEF4*`!inZz!QLVxM;w*otp7ua!#Xxey19Y*(xBd`_+xN9BB&6+DQOB@fV8kT>B3K#ep~=MhIp z)+Hs4EiK1@lndpC&FFK0?>YDt#N>^jrjw&TWhtIS@N6$_6a2nghM|0BRw^%sWL(&!Ck?!)xalcT(ZyoH9Ls$d4@kd<9rWLg(`zcz~j-m+<@is?xdX!WP!rvU`1{}C}LFN#F2;entZfyvZTH7@tk*3 zp`HZ?I3n_@q@)S(Qa7V66~jA+zH0)dSW{CYPW8abihw@s5B9y_VBJZT{t1;ZVLrNT z1#eMW9`jC1^Y8L$GdE@8`%6)aNkM{oUF&A(*rS*pn@( z>+783taA+L=itmg-@e!5Vu13=l}1WF$ZiL*)w};Nr0N=uGL{0~m~Ak?AS|EL5f1I(}^I zQh@x&mb-aYDn*#A@udc5X*eip-n%DqXwbWTX_ZfAx~)ynHKVfBRz+oy(FxUUtR}#0 zSU$juP(pj-S8ir>c)m72pqPYccrr{v<@IV6(RT6d{Fd$S1@H<~c zfjTS!ZkUiR5r}uFsyd@HAS_Hdz+PMa)kX~kG|cQ>{mxw*h-w#4QUiMTI^{di6J*o! zw0WS4=L=4nlx~Hg3OsP;a?d6#!OE@jNlqJL;Bjbi(Ev^bH~D0BVffNzp~(xaLK-xL z-LkqWyy3priE9Di9YQKxXlGH}F{=Fq)R!5z^2BM$NXJ$bzrlGVElDS4{?^|^*!6R_ z{@}oC_URvhUeW5A_k=zWpcg}HdCg9R?2rjZnJQei44`T8BUc`~n%9^D<6#xN1*%KHp#>$3<9zyB$RiafSK@~jf&NYB@fae3~sFU9u!+B@$ z`*+DTk4`CB+@36~Ep&%MY=OugIs@q$0%tMgKG-Jnk%8f zhd^TOVF84 zJ4aFf@>Tq~Nr;%XK{y>PzU_>dr_HKykQfjrc>6eMxwaK@nqJe zHy)}bwerb5f=)CPiGJ#@Ud2A7q?`)PPGCStd^I~5qo)Xh0?B`2VL^nt%Eu`%LWvDP zixWualTidQr_Icy;UG5zJ?SGc@uLWuk>MG#D+7O8QC9_&0{}^w@HJ$!`n#VO2%-hj zvV5WI5)K9s!jBCvtiqw1K$I8Cm!_cDDS~dmw$M<~b1_NGh3p6I z*$sqK$Lrp`RiB6wS?OGB1sr534O5{KE_syF!vr;d!qp5Dpd3M!V2_~jRdnT@uI<;q zpJ%}zX9^HCw?F>P2{!?6nTH?^K%vO>LdChZGm|+)uR(g+Q*;7FqXcCS+h7N^&eC>XFlpK}#(Y`kwTX5dN;*K)f%Ji8@(uG%GUbF9p$ zk;ng6D7*iKn-_(ILO-0B=xr6P5*PT~(e%Yb;q|y9rV2S7dIz!Ki@C5B7^y)_A;Gqq zC8o;B9ux2V#)>=Y+?1x$Pb;+_T(!*P52+aaxi(NCt6-qUZh(t!>DT^4`qdvFj{x}& za*ONa9syCJBn-Pb-pIstXuQ_8k=V2pHIcq#JiF5M%PpE+p?8S%DGYsdl(ZY^cKn>$ zY9NuUEZ7sR{sw0H|}m zt_IZIsT&0G2ODYcHeK^2!qv+Evnt1pI-`mMi6UId_Rod*wE;eQp`~+Hi6ua*!y^18 z8|saHn+x5Zr1Iq0MB&VbXs0<|~cvjiY z~Xb!@IHC26~s=XdgO*=C-Ys%f;V zDq6C+IVa!qLVGi@v}oka4e_8&5vCNaeM6Y}5B#g=-UdcHzh7dk2!sO!1%wqSSa?-$ zYAArhaF>fR@aO%}O+V&N(nMrwo1a)6L!mOWbU9(kAt+&ZkH>Ir zW}($a>L3AGkNm}2)b&;DP#yXo6(ORt=29VVbkd27eKMAtHC)L(EhIJ!x610NIIE|pC$T?mJom~D8MD!mht=*;T%+u(o@b{fv9W%aVw_~OIYeL} z)92*Xr9?!e8%U*S-0(R6uh=E$8sLy(HUD&%gAT(#faU*A>3@f~^cA!O!rp_h0Oc{y zi%`S)%raVwRc>Skcuio+*N0FWAXk9Sk7kF=Q#uq&8pive<%#Hpp>Mu!giQG69Ch=M zm)kVmcfiiX|DV?KY;EggC;4EDkX_;9a54%zm+Z6(rn+~O{dh)!m|*b+cFq z!uv75!#JWC!k+xu9Ct2J{qY(g;&znN-12suHmBS!!3^0hslu#1%JB3@x?mRkME7gshD_nd*ziA8?o||tk@tf zxu^eH3?6fa-Gzh?l2+{K=%}$%Rno03u=c@z*zy9KN`X$8r|cc^B$>&()ImkewJC=; zP(b8@cmgUSkad=#B@?y5s}1jF;{kl|(dro+A4i@bMgDwNyKj)H*y@>>3lS53yiEV} zID|fkr+ePUKmnQc3N2Oh2gv&ZRoUuXg9`HA|hRDu1r!>4mPFJTris zc8slaoD8s?!VPUvAJxt8(YUEq4U6*b?bx)|O%$$KZgQ)-}3v}`3{#;N_H1c=5MhnY_TRGY|g zzXyUTt9^YTYSa?wnA;N5rt@0fs43$U1s022%BqRmsxNMY%4cX;+RJchf9XH%SQK!< zSuwWZSWB-9aPT0y>~#aWbvGTjY*Q*j0fnt`aM*ix)3~ zaY2LUMfdsx0{n|#!(>1FUsfH!Zz1*%u?~RXS8nz6c<-$!(^oNa(;-LQL6(y4&ODR;!8Up4tQv%Uv_tDmjyKvLC-KZ)s^3oPX_89}|6> znnC7cKXq(-x8&4Q%7vr$)V(`tf=JmoX^3C~1^cAOQQJ4x`(6xb ze^(?~@!!I*J3Y2>%S#I7Fe1ihX{F3F*x}PK&12hRIR-bEP zsHYAY7PCf#)0_uOhkJ0E`sdjb=Tn4rx;urIDw&;5$2A^V)u$G||B6cFwgg#UY^STL zAVbMK;um93@k}qu@NDb#JnoEvU+PPCN%_wE0AEO}em@4{yKF#DC*cy|`=A9McEsdrf({>FuuxP4_l z^1DTULGHw={#uael<$D54_gjB$(WgZ+3?iBN8*a_kNxIiCtSlRNW4>3;}xik*-xA) zL!M&bYK|}EK1Ecl$w17=Os-v)>#$p?g(RsZ|K&TS_0ju2cPfHHEho6r_NyPWCxSL* zeA=rTYLg;N$RvGEECNaQ4CNtbS+GD7^nWIna71;{M-x_GWhbbfUc3OBG&y|fbaDKx zX}8pfGKuG#NZ-{UhwlIAfm45j^HWqpQb>%OOLMD_=EzxS$2k$9 zvC51hHOT;tGyO6gdPXeW7V(lNkE>nh)YfhnBnx&>{HjX9Ks6Q3i>cD_(C@o*&Ikz4;60I2mvEHTHm0&5EbFLZw$Hw0Z7V#(*kA&^_*# z@23j~Y%J9@td&%HO`Yrcthx%cX1o^G#kOBh+PjWsAHBYP`a$xzzBLfQz`rRYQTASh>>D6b4eGRUYI@dhJ`f=^LUmQBtRtuu8EW{I`CDfKNOlm@-g%$$MK50+EzA|W zl7nzy*mRSzm6bh*&GR{9_FjpYEyt21C{Nzoh+AEKOZRIcT2;#+eFhPp6Mb#_vrzXE zxJ4?40TA4MtqqkdbdS=2j0?1(P9?SX`HKG^Kr)ZcNcf^UfwfGcy$saqr{q@fPeHID z0wxO_C2tE0fm;D43;528;TITRUO{6CWFfj!ekxz`YnRgt)VLJgy>+YPoxZvC&WV$M z3Eh96nJn2F^@RowTB%6W0P`nI)K}1{_aBb^V}FkL`~0wKJ)ifIbZaAirMB(5(9+BJ z@iA1g#6EvR`6%mJ)RJ4OQy{26lUrp2MU0aZgGp%#xR4u@TVYgFd3nZC`jb3PrnYX! zKR;4SO+YMtD03fsF(4SBJR!6;-Ox0~ zpy!&|%JST5=L1=^c|3;}O1{qBRX%H!Qtz$mEB-EvMkZ^#&B>xcA5kB}fKf;aoOFORpoSGZ#Z7Y(yaG^07a#;oMzF~k zFC$1YmA65>_44lOee4ZRi2PCn%yt1959lB$vc4~fU#I+HBVHgVFzJa>bq_@4UZmS~ zVwjtj{Icc6+u1Nz-Gf+}M3hh9-Tor*G@d_Bh(?bV6a#oT8PQ?~201aMU zblkJSs%EXFPeC+s638CX>qLiBc^;t~+~R`fs*~yF>9k0iGFEVkN9N|tvi%Y+G8SG= z?J=Fe+9_PRL(qW#2hry8eE7(cMeWHDn}uu@$o%_#PCkvLe$M6^a zh5L!u6^eb zhmBPLd2TmTce@lP6*ia@2V<)biPV=1!^v{p`UOZ%o*tZGtma|)jTEE@!4SBKmVv}J zTDE5wpEDq-#WiSz=uZK@hwT#0UL2zWpc90Cq{C;vvk>h;ii>7jZX zC;H-jhIZtzF?9dz^Hg>=Z6pq?`v{dj=Tqa*R##un(`tG6x$-Xau@TYc+h_4@{?P+( zA4MD~*BT>RK7wTRoVh|S+j-TN6qli?svh-mek(@$AYl9)sGtlK3mz8H>;R>~xdyNl zMx4<#x8bl@`d0k^6mQPOxxjk|Ryd^tvDh#kx3(S{zalnAk76i=S``XEn4WaBCR){A zrVx88jc!m)GEw=m2u5)YJOtm>8uo_wk^ik(;NLX^oC{rRU<&{gF~7L@)wY5lVsY@p z6`1>bI0BgswDU4pJ|=OpFuxQW2B3?vxsVEv|_2c9Np$owQ0UGzS13}qK6s9JHga;QrnX?HPiyoNO$eEZq>EkR zK7VfV>iK0)`@M@#aOg*7z8?B(Jyz{rIk$X>K4){E5JWLh#J#-R&(mgq>*H1%@f(b3 za;{@S^PoWJD&V2CmhTOx**ZD%Bodryz3u2%Kr{v?lFiAxV5ET63~)heB-_(Y#!HY3 zg4zNa5FCjmnC8JuF=@S8PO*OI_X0!k2KMG7wy-VB4AZ|82tO2}=he5B`%J{s@RSrKLBZLh|xT zQObfx4=aOJf`SH8UrBwvIs?J{1@hbQg3+zmAY;iRj0C^(C0WnU4fu|RyL_|-gZm)I zx!0vSz3m(a>rm9k2M-v}_@va1jEsPq3Zk7Gep?9083Lbi_>w@{IQzj<5CT67vJ`4| z0&k(s1DX>pwVKfu7_zw`Nw6$w^9Wsv zA~*&={k+R@BH^mrIc|yz89m|43E}Hg-7x&L$##qf<;SM438G zftw+hRI=rX80mROjxz}it{>;?C-`av>j&Nvo#~71?|YJwE|#h}uSg~J@D}H(hfe1v z;>~loB3fsEK66ei@lemJJ(jB?^lM_q7u9lm+IQKb1u;#G4d;8I0-ua%@Rc*_b83{b z(xZxDnEz5`fHXI6uC9zo_oS+Lvy21<4EY>MAE?tbPbdf)Sf`!fIyE4U|AK$<1R{v~ zhWx*8Np!nDF)T+6gmv$%RYt}b{_7&#uKQQVthESd%ec!077`ul`Nm} zfRnxRmofuE`XICqMktl9c_A1|z)Di*u?6mg>76y0;apd7DK3OvRLK7@mESWmQsOpe z8-spGr*uwblgaJ4moEuM)!~J&1T!9K4h=}@i(6p=^*=TjhCycD-K!r(=k-DV0}N=l zsjbs&mj$cl6nwMRbLVShE5Qd0)<3XT1I7nGsB-C$f;F^Gz{J#x0X6mY-7pu2pz|** z^;?SG)7NiYLox+HXoaogxzVpXQty=nOaMo;P)wUWXwmyCOb5>)2tt}t;jW>){-x60 zFOS+l=KAxxpLGWl%=K+^5|hw@bM#)6p8t*-*}>w-zAeRRE0s55Z0EkXXgXN=<(W$7 z0`J1#4`sKubfD3b>34MeO$yxVu@fPa_Swje+ba5{*=R;^>q1f%B+U6@m(pCFo-Wsz0|DXbX_Jx!`PseBHs7>~ z#RD9fKveW7+@d>q6s%dG(|%9=X>WPd{3k)K>6&TOe63Jtbo>Dt4Q!0ASv^I2)8Hr7 zWWz(>J~%%DU6a^gSlIV=VYVM>6|ZKbi}!P*wEo)$tbgQePcz87K*xej6Wn6m-H}eu z;SiTLG~9va1z4_kj9GNel~ho4z@;Dwst9T6Y~aNE?#O}09HI0{>0?r`d%PM2AZUWI z0{A-R=)sVfLwf;G484}31hJN+8(|DoJ9skQx50(7O)VpGuFF0kINm)(fdo&E+}_+B zuvIUEuQvcxv^IWqu;7AH0wYMIFM*FqIpgk+4uJ+U(F-Ya4>zQHK+3MaQ>JhJ_%X0j zp!q)(q#s;Vh|yebmD_&~)?bJXgF{2b)Hl*3Pe$bDrJEYaD0(UIb5NfvBw`A#swaAs z++8>@;Du(hyk`AXTcjm#iRA(VXhE6QC(>0$k3ZFt&ED#_s|XF;Ee}~yFhD9wI063 zIib2_Q)e^-ErJ9qYDL9@!mA}*dDuXB8=)5mD0|SU!BryF22kS=#f42G5Ro?y#gsql z80_kX@e0N*&^Ew|m~`PswFLI*zGd%)95IzV1XDtu%UHi>jK-Q$e1nE#XrelEW-{Fj1_YeK5`bj!VGeT6Cv^8dX?e;UGBR}qOQ^c}ro;2omOk54ntW=i&vM?c@ z1b1K0;z;YG9FncKKJX&_@N`z~68c)-5*c#_wL-(rJtG4u62%H@@;^;AFwF$z+2FgA z?W>c2^g$L@B;gd8vAmDjl<5n5W15olpj3oRg{yO@BD6Vx(59Yuqhc5wvY%azpEsM4 z_y9El%^(%FqnX+~kQ>dD?R?yBRu6m+g;AY)E5pHSOpX7k;P^}b3JtQts^c}22;j5; zM;2(wl950fOPv`C`RFErD_ZD7u*3O;z6e6pgW`1`KO;vt!TfOqbVkUHFt=cQe^cW7 zLV3!v7zzgrA%J8WMXnsEaY0-HkOv+n&^%!YziPf!PJeYRq+e1WqYJh#EG;P%Nge6K8ycb4W{)PrxP7otL*@@eJR zf1z=dSIjx})Q3x#z3bPt?mqI27bclBrbysPB_+(KQ|)-0>ow;&PgvzWed2m6_g)k4 zi!b#(-<(z$gD$7%ZdjvdV)aO#N^GI&$b5zG60;V(w(L4mup_M&;$so{DXeeutpB)F z7~@>Ci3Yh#zsa0#2sV+2w$uHy2ezk#VHEl;;<}m17HINAn8e@ z+!>MAV5tE_ZzFy?tM>u;b0J6qa)utaGOtJ=hCF4XmT(sSb8xsJUvI~ucjyRhFd*Br zmJbj#6)+G1NCI036k2bSu+YSYuQ=EouLN&aOdBaw$bNcXo+Rc%p|DDDfp4#v5@N^b zMTsuFLiE)_QMJcu(6r{73L2?`MiclD9*Zu5hT=5QjOtumzQDPSd zY}9eMtRd{;q)etSx5&dM?Ok3z;!L}0o^^R(fp6)O>h#C3mQG$uksWxUtQ8!X{pr#k zA~)yBTdp|alXt91ZvH%~M;12AtiTO4TVt%&&ry^ms=Sez*zs+2LJM8kRN zd%%gvFKt@a;qjp%8NH8sPL1>Y{zNf6sOVpt&epAa73g8oiOtoM!w zEaBj&*KbddLnTQ3)^*&rf?$Ls=xf_xFo5Ko4duuJ5MPA0xcvNl%L0Js+x6gUHUn61 z*Rc1JV38qM6JP`sWao_y%q^HwY(XtH_L!!J zW!2UGn#;~$Wp1t~qSxZodcqZ=%C?>6uzwL;t;PERur~k&63s^Dhf%mj&DlUt7zb)q zF>F}?cWeRL1_Q$iOsXNcSiskZde}Qi_8pRw;Hd@nTY$O&SY`KGLS+u+6i}vB2Gc)3 z1z9j~gQo?wWmvP%;A^o;1kMhCJ`$<~5Y;G2L1F_q4e`*q=8vTXz@Zrox^FWBJPwXO zpkSB1(jePI0&O)2U-n!$TVuA%Q{P)*tH) zVQYe8-Pt6s*Ag0&K*t1!Jq(HuTf)ILIYySfPwk(?gO*LPo%F*HL^M^;x{xo`wE8y^ z(_^?p)I(x#WP2WRa5wyBpt0SL$p-`QQWKj(K+*P26F z-b>P4+1jzH6Z(bUe~rzWi=9oz_&?WV;A#HQl*`@RgtC03CRpL%kxkQ@x3!S!+}0sl zvi$np?6!D!E7%L@1L2fHcUZwi14LN(IL>^m?Xg0`j=vvaoasL76iL`A397(vY*w?! zv<-?1oS#Yhi1?btwflf^QOVxL5aT?Sgq@La>Pm_|rzQ51Fun<-o~EmZdOH*SQM0n? zmjffWwIo%Foqp@P_)6a$NPLtyLDHi>qj>327t_~Rww&#cD0+v1Ys94|8@VYhy8;J1 z3&p7H?H>illgQrfO)L|=Opbp`gMPyBJ#QmmNh_Z254Arg0<$M!vSx&mxXyc+KYMti zJy#A?&cIT!jm$7Ip%{i;H^6#GXw0)myqB+@d&fW#M3?9zIDGW_hp%7H0&Owp2tAur z`ql#&3{>-Q*3E70E)PgHz6R#5 zoQ!j?A+!(AKuCfkYk(neAL#8M^pBQ^i=ACv(1-~{nVFsv82kF>nEfAsXR_C_$sQqU zQoDEosA___o{R+Q9WYc1XW}0SesD5`HW$#|Aix3>20R%k?32GR&Gpbo00cK0W)1=A z1qTK`w5_6B2X8NH!)^ZdhOPZrKT)M->RYP;+zHEV3fFuxv(J*;Vez9pr^E8rhwj?T zTFIwa33Y`rVecptCuf!qX)>l%^qhNK%9YW%W@Q)Jb|rf~>|WXnzkWYu+F?hvu)XLg>HpAj@eW`;fY!i#B}WfX;aF!<8X!;u6$L%3 z1v<)o>)NuVQ=?ahGp?yvC6B<}%-i*LlILa@bvA1oWOk*o0VM!X0K`I~QM2)(Y;>e5 z#cbhLSVTs8oPGNaWN{*OUoNPR?C3dHkH^Zslrh>4i)%!D zyv^o0uBu}W`?rE?`)f7d(vjdxG)W6@bC6jl^g3(mu}aqP;K-g}bJ#R~K{wt(p_j<5+fmY7GDS1LAJCR5 z8l7g*lL}2?aOIRZIXBIY`NldEFIKaj#o3j1yXJq064_2V|M)nVBwm1#GZPTItLkvg?Vtz&p~?!X(O5J!`6Y zmpgE%@*CG*nnSe-u7nW3uf^)ng|S)fb#vWqfWp>mL4})O71u8yw0!~*IsDke%b19X z^^=#*NLs`Nsf$Co=wr15&*d&!=ho=VDt;HY9)lIgfEj` zVX^nUoMXwY_==`~V%%4=>DS{KQ}wXb&{`)M6%EbML`{Yx(4HN>dymZX$HRvoxOkgg zRDRxS`^5Ta+4SLmI|=TvfVO|AhTC880v#$$e`;`eSR@}OAue9&ICoa>%#wZ@fM)kaVx z0SSTKE4IVjcBJy5P|xV1h+V}+5+OEZ$)iSG97#d@3`9Y z9730jFIBGq>?znZ5O)aO&;&2goa3XD;@^cp`|{`_{2g%JLo`olkePj!FV93p&1ccO`wCE;StU+F#F9XCZ~sIJtpc zxwG-M$NpGasrn-P2s|11u%Z_twA@Bu>Cx*O1v6Z!Glb^%xDG_*)7a=OAIThDrGuq`%abL80AGtaf#_vm=Lx1w4La@Puw2w!5ez~pRK%m;`R(wtf zYPUP)eS`n0@{yzR6RP@XGFv@=yX}mo!)=wbtq*Hl7oq~rO~IJzW|N)Imd6QF2z0R^ zB~#9l5~J~xOujKM;fB{0@PQIIu=QCgz)d>&=C(G*y34MN)$cMzhMaOeUu&C4rj$T$ z1gtkS;PTu9l%Cfod}7-F0IiscMVQI97*1ep5?=0g60O&1PoNC0GQsNdWK zc2{7~Li?03m}wA^UBzIgOO^F%hyH0Be2&zQnp@$nlP*`2QXj^-0< zB+Id^>t)d&Z%X;Z+k7F zr}xx{v9VMq8e>X}lo5S;Z56_7l{&a8DPlnAV80XDg^i>n>O#iAUjarGKK0=Z=Feru zmp&fu6nMssaNTU!iX^e2fcJp>!CNhFopiWU4H0>#tH-E$e&imvB8?)4^%y}m79l5F z-!P@ScON3iX^2o2DGpWm=I$#_UiQKX_CUwV1zkBdswPa@el6!!+!dbYoW}EV94@`s zFNr6Y3u3cBP*wflZyVjAGhpe5;WVzW{?LAqcj)-kph?i#%<7#z`Vs&5 z3$J|{SCL{a2yp<#pMLx?ve$Z8ZlAd%O_*UPs;2f44~LV+dE*z1x!>H}gbEB2MWJzn zdg&0fY-@2XZn!t0Jl_n$7&a*>DKeJ9kr6W(WnC#WftZFY2qFpC&BwiQSAd+F_?koT zNrS9U=mh~%p3rvxemm{4-K(twXx&QE>4VgV%mic(ARTZ;HQC{C?-D6E^-pbQY^Ku3K1C1dbqIYGO1r zVa^PCIBf1Z8$w?>41p0ee7`Q;>dfVe?(Rs$uD1U`5J*TuGzutqQugj&#GTh+a z$@Hnp?61Q;99z6yoLNhNDST-}UQgfLPxnZLCN;pEEIEX38;~taYig|hZAT>;KWuqH zbIA7g_KT|KB9j4b0sjZ07f?`LLxVp-=pyU^5+K)qg7nFO^%hPzq|Tu`7+BXXp-04q zvLLtI>u6SPWgEFx}>bE8C;}ClZ?+> z3}cK%-6v4RI34E8Dk{R4Kl_JWJNqU$H~b#uWwWZr%3>cL%*W!2J-QHD?MyBRh;X$f zbSo9;L=bYh!6_B)2?SwO!{Md9upbzn_n-|P z5H=CemT#ZT%Ut#F!X98|s{0?E|2XE%RY{M8OT0CeVlj+Q-(Nc@c~zu)V&1*@1#S1Z zMREVo+a10R$kxncog{u0sO|dzOk1xBsK3$X0oVfJC3S16YpPEam@Dem;@4O8`R)d< zs!% zM?EszS>4b4lReI5#F~g+SOIrDtP%`cpou{$dVFS-fV2$fN9)~}$HF}~=#>1J1sk{L zBi>=F0TqCw*-B21w>+wK^2t_yGYEf=n^pjF!4Hx2+uZlu`>sKQS{jpqa1IwpL0s=^ zfsyKQ)d7G{_cX0R759zOI1mC4`$RN35n=$D8{!X&Bf?Lk$C zb<~{KO^qgKlKS+Ma(t@`dtX-8{hZCo=@vZe)*g$~ z+-tTesMqc9tFGz4W*dnr-PEO{S|5+)e^uX^Fzt2;$Y$tj^q(*7=`$ULf=~G@WQLF! z#6^#c1`9nU!o^piOE@JiIVp-qy0Omn4F#|ATCsc`owzTBhCXwS?r*lGao&a)nT^5u z%EAC8nSD@xstm;Ss%BEyWcGhImT0!)WgYkP`Cnp9(+uyWk5}xEe2Kzt<&iJJYeS{u z&1o^*UO&%ppKs~*A&d5;MZ;V0eHtfJ zAmZ+wiHuqrZ@7-Us-=A2L$MsKCu#T^1lQ^t;YRvz}FP!6KRHQk{7|H2>ZFvIw zTRlxDyrTAOj(q?#>F;YNT$xEL7=wVL)?9IuCh>FdIUQ;$DcgNldoB3w6=AgcE z!F-huS5Fz<-S+O_%RP-hNcc{;Z61Pw!gxn|q0&u@E@lZwAP>Pg0!egXR}{2bo)=_( z(lRg_cNvIX5MileyKhJhmbsoz-mNe?l^!-(S~Rq@b*C;(uXwRm)g94hn>y<3%;f%1 zo}m>fRv7!0%%=L)lQA5$(yQk6>DKFBiPV$5ayI_tN22&=MY(lkj=0_I?TXvpS>De( z%ZnNWV->Pb=$#en6pr+aGiR}6S@}oFr_o7fnIsnL_5PoR`XvzwiJSTTkhekK2b&0) zOsVDdTdgk8`asu0#JGiWbZpwgZ2>(=D6u@@+T3rC%CrK;hEN1u0YVRC52&mRsvH7T zava`lzd35p4IQ!sbBMQC$t>khtO30@75@PtX~ z`DwtW*OUZ!2_h^|SqfwyCni{p(R*TWEn}Vmf0_gO1PfI0HZUFqpkALFJHbFnI7?6y z0_CZCitNGnU0axf1mO|XPPNSyXqr15wciQE2)rdxH4sw>6c^lH0;)HGX7%v!m|htw zFWueB3&ZN*-_;7}y@cS`DSxrF?Iyd_7=pK}3)$z)wN2D{5>uM#Odkl6K7HUd@3d9%p#?gx277VqeM8250I{pZ zy&R$If|lPF1A*C<6MSFGN@;(soz*xosRKX|BUt${AyyYD|fk4K-DllSZWx~}WFF4WlvE)sw_EPp;qN2e_}Yl4}}^geELI(gyu3t346 z(t&TI)QSyfc&b?!j*khy)U+0xjtZ1%(HM#9N*qvv{=BR3g3r4ZZ8w?q4tC8qXLoZb3W9#+G?(+P>oCSm3_g z{>rs|m1<*<+GL>Ua4wp(VX@utnt@dnf|k}B_T>V%D+8~BBt$wZ+qEVZX9=+hpqY@& zQV*erQdweL{RsflP6YWdFv!IgJx%6{eVSZJR0LEcc#Zzl7L zIc2dva?B9YM3$B^wUxK%rc$H<*A!tJ!=;iz^`=!0#-z(DjgHQ*)Pe&%B7X(`j5 zJ&OUE-5J7gR4)~=oPZir|yi(30Py$P%YbIJw$cF`?B8zjcJii&APZPr^h z`$(ba6-iVpHM(E3=2%hPJ;|MahSG!$*W_ZHyzDYE03YQrufZpYbTO^MD>vNP(d3&S zX;3KV(?giq^C`sM)yi9_M*srIOs&3^4Fh0f*kNMup>j*MmK)d=Sc8_%}pQV1K(T;7B2kxO=^z^bTa7hP$IzHSA9_GOg0%s1)v%>QKwdznO7v!ZWL)o; z4i_c?LkA-Vf^EPYd#=N1^wh{{8`(1;l)D}I7~U)R01%U)gqnNcf5hfAaZCQ?u){kT zAK7qgvH>L4SwDc7B!MxKG;KbQf-lG8gR&wdR>4RS-1AmcFfRa~PDpZP8Ue zUM%z6-;QtV7296+Y&r$Sztc&*vUBV5Co0b6C2{pD&%y;GK=mRM!;6 zHa)H$r~iGZgEkbZUGzWn}n;Jy<;AlKw_pe!VJL!VXH+u%kl_t#)v)wb$r=uXSUu@8A5aZ+c_WZbNFb8`bk z)^AKIxZLy(5+jF%0xIki6$TtDyX%3e+$h~&Z8(sbLS=`4720B9VF3a}V1}MWVk{0H z5-%u)lY0&BR-|=+BZWvof%2N^egZ86L0E8&A3dZZ&tC3w0tCqw@B9%Iu|kS>Im+?!8=;E}8Xn>t;#; z&j7mJJu;f>iY}YB^aA=)wa}IHea)dgHp+aSyBYC3jPD#YQdBQl5B@oKHgfp^<%>K= z)=A7JBQ{-3otO3*XN1OerQA#|H7#mvLgGt5Sr!x_1#n*OLuyLBHw5sm!U6IO!C|q= z1xzu5gbeH-bc+sWIXfw*vod<{@%>ykYf4sWx@TP60sQ2|P;UA2T~d))Bf~ZG-k=p?JN4k$lLvYKX#rG+VYG#w z3jk5xxeZwu6oZnqIpEfWakgQJj4huD23|;k0;dRg{j;*NyyW*F($~afdU?7NkdbfS zz!(Nq9QYy#4JCXU2!6mkvpTo%_iy&MS$Ap4PzMwG!TFhOXrH^mzW)Ht27^q6VLqsv zq3D^J&Hn!K3S@QAwpROZUx3IQD-2uq{bHDvVbV>&g6$Y&RbZQdF99Gw97@Q*gTry) z#1i%fTLTOK)fR~xDR_i%`5^$MfpVByXg$opCqo%ofKlK2i=Hztr0en7a{eZ1U zT#H7yCHptCO9P8yI6u(F9mIv&R(=O1=i~-RGxx9;7yN7tT7Ue=GzdW^fu>$hfhvv_ zS%Ww{oFK3mt#6v9F0z(w5fFF5aPSC(igPEwa+b zD(e>M&i}dkpp=P`)0U>OX>v1X(((Jv%Yp}p>=9Sf!!;VmI__$iXf$7(9CYx_eQ`^j zzdf{7?g$2hM~^-K)UTYqP5nYyS^J)5%~_JuwNd9MIa z`u$$G6}1Ly0&s7AG%Iz?jEsD9i(h!k-JRVIb9i#*5hpxiM3M?z4uZg>Sb>}hsPU@% zs{(-G=ouNC#KRsg8#gybn78+!Sppy&q5|NUwU}{+T)YhF%pm+AB(o?%k&c}80rCn8 z9hB_y^5%{XYEUyz;{*4^ky9p?o+-TtM<19Z@I^rWFtBtW0Du|}9R!g`1V|5Z;b5$= ztANH7sy#cNsI7V&nn$?Y5Ihjnl<2eYp1{zIv+ksXSsf@WSV;ImC{@VB!rZ)3#ln`e z$FtiO?pN+yNu2ePXrDWAPerBYuo;FX$>4Jo7#yX{E=`O3JM9q z**Ca#ON7Q3Kou}w&+W?fja*ofGhk9}l`J*-HaFWXR1k2g(P->YUDSpf?A5;aZf0!N z8$snvuHRmsx{(qT`{Rk?_2|O8k*=9LHOb?cE9nUZKC!aTF+EW^_d?g4zWt~viQ|^T zrZe!l$mcMN3l}u3%n7Kgsbx$PUG=M8;42d?HdXkSf2?1QZA!uNh#UO%?flhAu02XFZl!Ro{x zQ#QA=vDMiHdU&)_%O!o(TIlUlfCq*f$M36Y)ZdK!cFt6a?3>b?v*g=TQaVFD4t(uS zA7Y~(N7Y=KJ)$r4TZ!s+lx<3-TEbWwE)=uCY&Ki`X;<*N0L#!bQLdA@iQz?pqV5`c z?^v&?dW)%ri{Kw0?cf(~GaB~)ZJE>PVFFVi!?TARB6QAeEqRWWS0Q^7qRvoX0r-Fj znNiG`N06Qdqyr$CT~LcNE-bKv$q{ZAgbxKE4N^qlq(DkQ+3=KC!}e)}ANunLga?`l zUNA2obo>|(Kfqz(P69X>nkYEOi9C&v^`x)A`L||a1NrYs!{(_03RPi;7hmjTLD~!I zvUnaU_z?H&Vv`dcD}6gS6?_BYVq?Lu0qVK3s;Vn>rV3|`pWn4(Rz#?^bWI4%p@V#A z$UkIKg(3c`&V=2J)~q|3b*^0*~GHb-%6@l*_xtpP_GE)uMC!&GVTO(;Xkr78Nkl zsBYiKRHJNqC9D6Y zJfCasGCRI=l+pR+qGjmjwP<<{V`n+%A8t+`#whEQ*7DX~Vt$e5wmBt^q!0O+t?YaW zW#R2#2*t*qeZga%$M#4&;^M{TB&re(h8IV-e7(&==v!fvMuoGT&@_bB!vXM%Ck&p~g4q@(NBEu>>5*~7S|(#*2nDjwXKUqG z(aqxeg;PN_5M`pua4|9oV-v9va7s=DgsJw9C+I<{ff zAc!8C11cjcReBnt=pJiOJb-T`=|&2b@}uP zZ2)o(AzE;*h%;J*s=(zbD!||X@$Z+AEWTxS6V(?*?l*Q>19Z0#76}PJpl^4qB-M=C z1C)<24y=5Eo&Y?2=(vm<0H&kgjRla$upOKw=Z9n*~{GVEg??vNe>Bp^C zT(W1o+%wM@`crcW;P zu@7A{bwBM0esEmJj_g$A)m}nTavF!Uz2fBkt=xlJo}GuVKT68WQ2e39#=-CKp(tkR;HKldvENiVSRdhMz$SAc)~W3;~!g(D?oHo-yJkmDBT{H7HIf zy^t1nDy$BSOfZ)~QaoH<&}6|t0*xE+E&wXQ4OS0pAc&^t9#aE;3>p-eEruOj39Uzv z4+z{Ov}jPx5itS$36L03pG-L#dFHZoR&4wJy$i^G1h}xi*nJVizFj|Dij$sEKrj($ zW zM&e8}=Y6t&Z9J=K%<^cT8+*n)W42x+D{LRI=6yB4zvykBbvF>{>(j3z)T~d$&P{H~ zzq8c}^bF}UtQLIV;_}p1H*hk*>$(P)m5wkypTRO;aBUdDyISO$c>n|OcS?~-nH%CQ zw7KL$LM6^FS$RD#L}cTzzh)=C{M zFr~dSh7Q$>yvLcA>BD|MA*hwPQ=XBH()j3f70aNcNfyzgFLv!{-?#}$Ha28RYMe}{ z;BjqYxI~b56FP#OC8#p#8?M7m6l8=eX z*vQB<1lY5iWWu;rZVzhL9R#$1mKXr~I#a}R2QUJ(<$bo!@PHF}L@5GBE_lHL8Q^ju z)(V*MnI%A&;ei3|o9;8V#a8hhp(sGE2@nOy$pABk-2DL!GmUoOMd1a2+iY*mX+H&9 z)NHoDHKcoD4GI%-%n<<_NG9MX^+C1-N)R}+fX6lL?=EbDRT5;{z%idFGyvfvwg|!G zA^f-srcV+?Sp?~7NNac|4v><;8}^$|f4ba}J@drjuY?v7=r1Uk_JVTG+g}`EX`Kf} zOJx+#gCy3jB3g!J9PmgO5yBC|J%FS@R}rc)EIxv?J!$E8L%S3rHQt7ZFk>NEQlTct zfYj{ra#z5w*{=5`fdkvEWd_78Z;wG}LP2%Oy$h1VkJgGFdTRtLjd5CX=PLK+<)1z^8|w(M%EkPBq`mzdT8u#bc+Yw{+s zFthz6BIa0Nr=YomU*4N>+B=Ls3!?##x~n5^ZO@6(Z{PAjFDmdDIUJA=2~mXr0YVh- zk6NE3Fan)Ot#_O*PPPF38X&iBo6A;^6Wr9(gCMvC`A+}0zYG*|1t9i=q(oZ@u{=MZ z9$?cCyaI47LX5Trya7m3X=SAi^=IKuhl*Q5iDlZBI2RZ(0U{=2%^j9D8H*;e5xcG7 zM$E=N zEaRsh1D}8Nu7`|kv%2Ee+dsu$N6Vtk=%rQpmn0yMA?uv0FDFb9E)$lhMYT~g$20%QPTv? z_J9v@R&Gs{K?(AG%~>-B^PwvSkrF)X?Aa5P&la{pkA^T)F{h+7uWk_`{t~>QfWLy& z+PLoiV}P&V@ia{=>U~CKGNn{Jk*8G-*xw#=gYFCxx1lwI!}`Qw{*;uXGaMt(jWV#g z>s0?+%Jp}w0pHjd!~hwBz$d^5fPoVVFPKDgR0fbZ!_vHms z40_y7+MC~l;T99ipmeKn?v(4GD2QwB-HWNNzR2wgm#eS5aN6)()rjL0d^h|Y3^$;Y z$_#`N64MjQzO@hAPeFJB3O{*;dxhaq({Q2`1}Fc(?e?*JqSAl}rAm1MLzlfk2s1Zr zAj*mt4>{h)c`Q97QJ`J&8=Lwx8x=;DjIAnB&ftB}?6RD)>hn53Z1!$yt$nK$&IPqo zOE&vKNIgS1uj3tUsMu;%?@_8c`mt5KiKgS*TiTZY;it-7@9z)A4wPy8gvqXd$Ynb3 zs`!rlwLr^Jjinf@W)S728v663WcjxF=>ogPU4JNV<|bZdp{%63vA#y4GI0PM;>= zVVHgJbU^K!FQwB?<8_a|h7ze9}osqM%wxpV4F7m7nU&i7Q8*vEpB4GJT+sCH@F zjSYPLnk8GeMPP~~iu>0=76`P}fXH94*Z{ELu|`X|U1+VpU-3^T;9fb$?~& zTe@g%i}Opdf>!_zIT&RwSneHqR!ZPe2L~5_BzS2qSbC4%AB24xY4{_)dt;!R_6K4N zVhvI|K|wj*Od)qN=8sPUhiR(hezjF4boX8+>z{+W@$)bzcBV#^OicJ}n1>%Ddu+v5 zwv|_3VDIPn_LA*;qj1xyWPB)Na$-S+zx?GjYL~qg&sYLSre8G8&I9=RNof-83fr;@ zUj5sqqaOl1eRmD+&bcvnM*XKG8AFxzxPmD1>ZK9GYhygVmuSA~QHL3mn_(l5Lj+Te z(wp<-M?-F3MhUcdGW3!<9>Psc76`ukO?p_#St0f!b8rNK{>kz8!k5Xg;j(d0WRrY7 zRTm8kYwLeiQoM@`BjX9CrHt^NULd-uB?yzNM>^7e@ZVL{_*ynUCmb!IxN`LR_O&ai zLJXx2@!oXQL4{&U41|lE-ttv@EmL0`emnOg^drPjTuHHlt^~p`i@L7OCnI}iz^4kj zR|-z@3d8w)#x)RFgI*V&Cwt&d0{jmwYS<0fkJ%gakl6*m9bj}w_=VORM20RBbyTqg zxJN)qAt(gT2xJzZRq`pwB`vBSDrxIb7)Wgv=2MEktG) zYYF8G5L^)V9*9w)SsyAf5r0c!I35T&82_LVXrf}C)>l+m87}<&^CwLebzt@PfmswF z3)mBO47XH7yvRnk`KvGo6ej@xf>{7K(s~10(UUP%z$ri?&dC^W_yaI5Kzrca{v@068%zAIDEHFQ{eDfSK{kS_SR?pYTHc7VqFIe-HcFVPhqPAU-@&4`h{t^%71s z*J#LBV}d5=T0l(aWW`vzV2~muLo)rYvfeRnd zK;DC>cm{pw$qNlj=Yn4`cR_Pb=WW7)IXdqcmj_9ycmUd?>HRJQ5M&QzEZ_|SAvN!U zAH@2WlMNEu4N^ZEShKJKo5__At5bIM96uZoume4&mqVdb0XAQu#&x;_t#duD8?aR% zjo>bW& zm>CFZm8VhiYz8UmqNjnT15yLiVOg&S!LPOg41EWg#J*`BQ{*<<_S z);C=Ju4UN>_g}NE=B;bvqw&{njM6jYBV%w8Hu|xJj)u^oFx69A;YqdgOh1!kepQBW zNON}_sz#+*VJ_XQ3NXF-o;umW1YN?Mx1)i`?KB8NMdrQvPGn`=BahPJbAE1 zAI){X{U_-p3zBj-sQX#-{tt+~#rru*K}C{ThvrGRH}ym9`Vop}CRQ$N4K91WOsc}& zh7IAf%0eCbuWrCAcHnWdG3=ScLF^C^g#aOdD3LHFXpjPmTfqMSV&qMV7+xP9q6wBw zx>kcfjT0@NevE~ifu4N!j8pdJ`eZWB#M76`4E{3=EJ6P8}V!jv@^Nv@nF8tH>S+N z=djB;q2s5}C&=PLZVQs%&nk8lWsjeAp~*L;KjqO=J9+1HiLL{Sfavh9S9}fZ+3ugO6l^%MoU+NTExRB8Q=7@dRZ(7gV0R)*hx#4)V;;@qre3rtU)Y8i zryfyH&O3&6`WlhCi=``Bz?OQr?0895ooyfD9E1M&}pu(#MqpgK;* zv=*Uq_#++OE*|k7-hBPV?){<0%j2)zAld+l!uj?sqq<;~h+L(8QN1g-CVb972~d01 z2-($ef0L8KzAY4SZKpxO%+PZ?)f2fjiHgGGjunO=Y#bPwx&Ab=#EqY5Qkj}_Ph7ai zr55ifRiiMHV!A+(?V2k}8v26bG_9#?Sr)LC5xIg66em*t?+KV+5Y|9j846~5q+aDX ztfnMFBF4!|7DUfRrN~Q8^HDNCJaXq=TT3hTo2N|5nCZN*^tJIRrRUnO`vC!da0{)` z(olM(y%H-%Ssq0}HlKHX&%m0GD#c7{OIjmp!EDmW*rwCW!MctNt%FTOD+WiA%RcVA zPDNBoNO`4sGOA7EG~2=_qm{tFwv~yFe9}fgo!P=9uAaEoiZKbhD=TSHDI`Hspjy-8 zrr;vNpPYCFeJ!R4`%)>>%XD6_*Ya!E8dFpZ8(z8gdDhy# zA!JNcexLsN^QSKRZexPPYZBwaEF4JZ&ew17vXQ@k6OzZ^}H|D=NHFmT4`kD-w{ye z(rT@l_4d|In3os#3iaD*zvKBXEAfs1i@XW0#mnChhx6z$`&pdKrOucr!Fgj-o{9Q0 z#yfWX+x+3rFR|JkB%QaS$Zuc6D(zMJLniJp8z^~YCi-y1|BVb4HAHu6L?B_>PO=uASKXf|Pjn&tA;tY+zWc6V$y z#b&bL)dVqRbOgONXPP%A)+S_=XlkY&p{e^$qI*5vYIET;0(0Qk8CtkVIYa13%5Moe zJ@91pl0N-Oga<`NP_mOancO+elIJHVJbU9b%Gyn>*mAEak%tO-9U6c^0Ra|6FR1mx zTo1e&V4D^an%u7c)ohO6Zy}1l`@UK?SQCELh9&Z!2BF?oM^4*fQgC16PO#oFoX6tn z91!;Xc<_K^B3#$wou+m3UCm^*>KCP0YL)P>OBkE9U9*Im|4oCRT!Ne#ci?TU7UM zuB`G;D6Mb5O^fkatiDv}m%`b4=uTUV5xenWij%6{vrl$YccyV~A`2u8KNV?~QEzZ&4|G&Yv{=%H*pguCdp zEy#WKSU*2kl;xe2pyXC`PPI__0^t#-DgAhr&?lGIB2I5>ISu~+K?VaE)5tmU|EI9d z!C%>QFzBhCK)RnB*l-s4^I@9*XU2E{3VQN#%K*p;gWQ>e#Bk8IKp(Sn*J*|T->o4fvpJd|>cTwhxT?hJ^;{Xq`YF2m5Vz;&Qhi~v z`EHj)7N|P;z6(SsrN0&6=1w}1n~L`drElddrSPe%Q^`}QkLg-o>R_ne#4%Uo zdeF|mfJXutDX*a>uDI2u>yDT?hHcMo=J@}*&yTMk6q{(;=(A|IwJc;4deMf1_!RPj zk16!-r^8h9Uoge4E50?E!c?^c^tg$1PR^dFJ{L$WEBM|ma@S@m*v|}=H_5uyvfh4? zEIB~oBh9^y^ErpF$&{(HzKXu$e{r&!d1s=zFQBh0a(Ps>{*k7+*ripOXx=%tFLo=T z_(*4$wm@Ns{Vxh$R-Q|?X}uWVqM3vqaL^F66!Yj;Y;HN*M)o|%tmPYN{K5mJ_&D`M zw7~_{4pzxB|CH)0>3N^q*EWO0Ppm5?#%uCEA3z(h&C&=iQ|8`kOTK?5V4{QgNrdIN z!V1;9TLD(KVXv@}94MgA{<$=7XSFzW4%3l;L;tXq(B!;TX}B-RgqPRvaqAj_x$_Pw zV(1xKrFe!*>az_w@I}M76FkOcv-{kO?}z7|#IL!t;hIn1oiKj3zBx&zb=R=Z-eu1} zb_jW_%ov8jXA&02u3ga!cD*6=fhLscSP^K#)4QBcr+z%*9P&^vkw+`7RhRb{PtI&& zZl=ZdqyqY^L1J9ehqHBi)uy!cRt#t~b}G1bRQ@alm19a}uUE)JXYHBlH8=dSG~@(A z83tPesGoE4L3*Q_5JAUAdl=l1yLOo?|2<*-9)}B$J=^C_r3^;|2$I)aiZdq3>8YCH zWVwlJAzD1u{F|6VQUh(J{>ZJLf{RyBt)X-NM@_$KS61gR;|DBueHQEoH;?);NSW=2 z)roJ$aJS>v7!!=F=6|3soUQm^G%`T5B_jUd2s7`NV?+MQ(^*mOYE-o7!Z}$97n-^L{vSNr&nF%hJvwcJrRPWpbVG^fO*d5vJaeC%m`RE^8aX{ESJ`LtCwjD%1xg5j-kpPSa7c z(Ja5uuIY$l94Vk9i#aSepY$v9bz55`E&92~him<=6Fx%A*y~c^aB~!hg)plGg!EIp zS6|{kC)Qu7h%%jLztUGlnhpDBD20=&N1xZ;jb=JhPVq1xjAsonK4(fN%LRCvjb~h4|8U z;JxHImhPdub@#Oli1*uG8+~m}qFL$>U$(1L7#jAfJ#s_GRMcqQUwTGX{Ek(P&DmGf z#hlmrezCqQXX^?lIZI~octFq6PB9wA<^K7>3%UT5s`Y0=9Cdej>`r;Tsi7XPfB=iC zy;g~9@Ax#1js(r4ns7~ZQ|$d2*N|Rud%=$OZ?(qa3BK>&*Ct!N$QeBOcy`L*QIFg6 zLB4w7KXZxXzqY*<$0z4b$4WJ0qN4Ji!shBCEt?*@d#}z zAekn@Up{oimf>nklXzf>B4~SxhLAi1QVeeGA~BEX^!GeqUH)`E5d(IW`j$UK=?B{b zGJ5YdKlm-#Z%EK$QO=mx8zFxAx;4bGXHx7F)+8Dynw93OX*zYsM=iI&|8*+uKJ|^r zjqJsErEhE1J$?1^Z|e$}W@t>*zS^5e|D?Hbi?TlAb*V(gX8m;vp9EcR3Jn3hTnF^g zFal2(SEUH;l7Ap?M62K7t}&G|5=Sem>59yi8|yn(r-m;6_vA8@GMBCUpGu1sqAA)_ zspK-S9}D~M9?K5PpjK_YaovAv;CL*Nk(#=#=h7|d_RR(7TA_lQbp{e#=(+mYOyk4} zEfI@Ak=^^&OeZXyAAAiYpObo86}d)nGDwA>%h4Ckp;DRJclAlQJK3&(+d!FY;`$+f zHYvlOdC|)<)6`GYBLwkR)Rz`fJ0IWczq~X@#;JX`RML=T%16!MX%jc@4jDG5a2MvIVamvqvc3&!0gx1{CpK$O)e37zd1+O&f(rTl@dP03 z06}C@g#!$bcv1oT#Ml#>Pqn2WLe)ACj}`(vWN>Q~&fhj6?ET*oZ=eGIx;e*Y-mDo> zX?e0>Hgid8SB5)d*2j_J-9YB@m!DhuSu0-1>vs7#w^GImt#4dk2lcdg7Zu@T%+0MT zW6G1E0-A_ik+uf5v#z1mY;;Fq8n z$j&fGUsupVTjZ-hyINjHzp2+eG?1}EUHmzsCi9-z=v7snrv)_e&j;D9I)a*9Zch1V zmkwEiBv*tM=q+egL8@H5Jt?L&YV0|4ny7?=i5VhCFQGB3_vL1p5MXf}8zX ze`y8}BPob0k@TfC-iRiZ(hqaao?SzZ>;5^ISV)b!nHH8R)7$;L0c&T?Fm+dQdaV5L zPN!Y>Df0l+aaXdsrlkp;m?gU4@r?l8O)s`{?XRm!&XtM>7x3pKDRGs*A>fk^XOjh8 z{#6nf`}@{rvVuPLN|%C*r#ReVth!h0A$`?W!upu4Y4a=TU$7$>wD-urC6E74=89Eg z#4=r2(}c6%IP20k)N*V3ru4bZYoFYMqdC}N**ihM#WO$Igz37+EWS#`jDUIB6L@OQ zBbYe0WNwjo()yKG&aQlyCtl2A)B#_}w2jwG&S@P=il%R;@267j<7m1p-Z+HL?xD}S zIhcIZvYb750~6MrQPf#?{k`Mp3T2@M-^C6xzkv`s$+}eSC-_sW0{B$MbGQY5-E*d- zb|;Mj`~SZ3nC?Ct$7dwp`fAoW^N6YrI9OEZ$pM|5({`=s9gBWx8DL|BlOJ-d1R(_l zvi-6L?bnkw2Qi7mBO?^fvGX){_I6I`AS=qJI}lL>K%@|c2&~anAq?e=edVdjyRamE z`ceZw5HJ-pS}XMtYm)8G!)PjZIIX*dhP+MEq0@STQtUpW>mpoo9C8tSvNG1I&%^lY z#DW8USLHCQpmA08i&Q%#X4;m`v!NR-=S_3u_g#7fFr&%8YaJ!)_ilWz?^0)nyYT|MM?Jt`vBBgF_8kIeIS=C3_O1jagq+@XKZ0YAe=q$;yt0DaC)8(P^%!BzV z=d43RInL&Jr`sLB9a+AGxx2PR_<4i^`QSlr!Vzaf)q<82Y=oG>>fGz3X{ zDt>Tz3hS?B6rEb*QX7LzPY>K=X*f0Hpu+^@j=ufq#Ksj7$r-s{6I4za?+S9<=uqbu zRW?r=C7GrM2aHoNePEil3Gpw`zK^Ebjn6RSUL@l=79$k+sJZDJg@3-yw~Vzj*~R8g z)>7J$O(oEx&5fTH%leLjNvaU0!OVUE$fpgs_x%N zW#DW)+GkFydwI=3r+9l$-qeM=E9dCRf+$n0Y%3QJKMG3O9*AK=?3ZRX_Lz<#d#U@mLUukon& z8h*du4Fw-^-!@jPDrSV2y}Q!}qf@(s-4DLq-t>9V+3RvSy+`L|4NF|hG1(LhD8FBf z_c?RfCw&8cy=FOQu6(KGZ> z++_{u=~rLkv2a7%1OygKVl^f)ys?DYfCYhqzp&5YZIT|qw4g+-87UZcfZPEjNd(pc z$m~I6vFD5zlhQ3*P|?7R7-@mXPlNGV1MY_Vn^iFj+h7c`nei(5Vz&mX8Ep%)U;1QD zTZFHZarOp~m>2Kd$NIm!+U3(Sq`$;3LpWojUlx$z7JD-zx*wfG6?d}tGes0u{Iz77 zdrI5f`DWuEL%3l2Pukc!s%mPFZhpudPbw)C$$5uO)c7K2G9jF;(f>E>+3yrWgn z={a1e25*6({p_CrmAD61SqtkzQV0^o(zGNDSKN4TH?Y>2Phv|JKIbSAN_BY_*s8q#cCkc!cI-8q= z9Mp=9F5jN>$tnpyXZ{?%gEHH?(9$2dtg4+$z06ff<#H^7PmW8NYnfX~xH)P1#{>Gj zA5N@~>3m7WQkm{&L`Gx}JDq>caM)^F7H{ICjyq@GWod1`Vt~zJY>19h{_nOt!4>ip z!m=Qf)D29m2=@=6?jQU5`rJzINu2Z}c1t1ufthA|r`GvN0UEReNc1f%?*v1bng8nX zG5>X-NC?%(m#xXF#}*)IqZ3f`q-*jMAVz?iBGY%_zQZsU3=|IEoyp!j#RV%&q zQ>qLAF9Or&3SSq@Hb_27Y2fZT2(qphinT-_>9VXe{5W8T6i|7Z(muWDu)Crocg+hkf0~DePKqa7MKF&_ZW_7Ci+FC1w1$^+UmTw`Iff zFhVbH|8Bebi{QhlNI$X7neFw*odr8dNvg^;yq?|RR*tnk#Bo*(wb&HT5xMwqyo<7! z4u^|2*!c>a|JDjx2?eLoR^nvO@Gf&#jy|%j0tj<}3m>?l%*ctc_lTKpU1qdjn#sh~ zWFV(>*x}pTF7Un}y0pJU=U7%;?JwmMZ@;haUj22cw1*0ILrwbqyV2gL(JPSfXU+RO znA~s^YFSFVu-K_`MBJA%pNCfIY33o3bySkYl&=-_W!4b9s=xmFoNxW{wZ}L4{thMK z=DWE#y%bzC)xLaQ{UAAQMj>A42QEZsOs)HZDj&4&aHF}jvg+(1aoPLZ4f~y0GG5wD z(-4q_1h^rKKQ+K(CVM8QDiXSK7g(=Mvb8JklTAdDb)ELtoWSVQ*x1;`lTjq;1*vtQ zEdV9(k17{LmHI6b^5368fH&+rg)k?vguAskoS@1JYqkk z^py0d>ZKsQ+Wx!eJHO4abMrP@wEBGfO!`!Sj--I@!JA2v#n{v2uZE6_iGci$`-5EO#Oj%$ZdN%;)wt3<{1kLU)5Njft(9822pv=3qrE&P(vAb7UlG=FdhDiPs#oKSA}#Kxs~ ztl^NeN3CsZAXeiOm#nEuPkG6<-tAK9*zUPd!N4g}-Oc=v~;BoGcoIj^|!= zMbi45b1iji^PQO({MN4JmI){k#P1fQQvB~oZq!3EfjLN;vWOy>ny!0vKx{vp6%a=N%e)6sK;XxP8KJCHN{F^hK%`R)7KA0t!7+nfDz3X* z9-waDT*9#w6!MDCxbq2^bhiA3HQB@~1kLW(t9>#)ik=x?~@;O>OX2FcyDsTzXdIv-z^0j=<}Y@|U@jYn#RSs_mJbo)cEI+0 zC1Si&(YZt6Pb9+iD!;p;3sSJV8AwX8P+D#XVAUmhL1ScI9j8ME z#BqZ7K|%MfG5U(y3!NOr4A-Y~uTgQT#YIISDJL0d*cr&jDcCD?14eyrpC)O66Ie+1 z;P!8lw3OO3FZzvvwd`44&F}Wb1!`W5ara$)YhpwM8xAX02Z}S$=JT_YlbeUT2iG>a zIO=U*gAg7N&wgE2D5#AY+`2plKo22 ztQehBP*h9`+Xy#6$Fc#w>Z2fIktowD6B~Uk`(t=`0-_4QnE`DcSi8tc58U8zS@b|e zi>B7*(COMI5f9)*0UmM!+={TKh)4aO?_-#UqzOtl-dYhyYa zc4&|gGk7H+hMW{!Xz(K>jo{zxQxifkV_EaLLn{v!u$6lj_{fPkf0;EYEVc6Zdxi;_5v2M zK>0>e`0#u=eiqzGh-T-uh<7n@4x^?MxwN-3XApKh9kt{qtz&0bpR+2``1$2Jzv`yA z^0_OFpYODZbYea}<0DI^|E#B>8&gDaM1?;0*eXVnVyz1Qp6lEho-~d`!ai z6_ieKq}dCb^^a;kvc)$YResUDi!R1j3}!SFbv_5;S{=`@#IQJ*xPHXrRRquYr$ zO&_^bJz2Psd%b0Dgk7R6Z)Yc9Wb8crzW+urujurUA0Uv2C+VrQ%=0p9R2B~f5T4x9 z#u8!HbnbvwhbFypXki^9Apqb99XxohCgCOLdmng1^GH1iFX+h!cLPAH2X|SH|Jn)l z#5bTwwgo7$4mK)59|(V+0bd=%wAPew;Xt~}({uTM-h!DMnlEHwJ7I|x-d%}%6^0;! zf%q|aji94S;-P|^iU~LnnGwHOlt7($@AD3nK_oOq1MTVQ=`eC$eAt}43aTm`*hN|V zpnw>c3F{*eSs>~COK|30A#h{;2nanjrXOnUvh7ISb1Vl5K^C%8Qld7%3S)g4T(0CqydiiqE#0WJSNuiJS7BQHdr&tXPzQ1!`` zoI*>VR!+&2oD$=CEE<~eU=StYEib_W(DBbbQj5>qwyK*x)^;09wYT>K<{2z99xZOo zYsFmR>6umaRKWJGSrTa$XB9) zjhT9u0WdqjD}tlJYCvf(=J->B8+OCG1{uWHR#mluN>!1*YRnFDgDwFa0i#px@O1s^>d^G{^th~+G^KnYUn_f?YrSELCVL&Mv{D{11o(NlgPuUe_p@q z8nEHZ?5irJwMSstFi)&y!0xI(3|BUUUri#gjR;10SV{nvLU=g*k-;3O*UEcvPa|7} zWD!#W+-=F&3x5N$W%1Ct+yMYo7JtvU4jVZ#Vgh$`$Y2K8LSYXUBvoq*K1qHEpUa2H z3+izu3cyPKnW`~t$H*IfWvW~=&yy`y@aAF5_5?>ysXk(5<5**F+&bd!5+h4{#VQ<2 zRo}Dd{)k=@rGx^^(~x0UCvvhi*KuyK&eiC;(-+fc<@X6|a8=HW=5@l_B`|9jm?8T_ zRDQB#KrR^lXJU14Dt5+(#48f*xBFSHdJO7V~W5D)e% z9B3rUBGW&zmH@^rC~(@EX&>_W%y}C@&&W?La~Jd`acAV-l{^O96j(JubIYTSXk}q2 zN5sC+2qIfBVEZAI9WaHksQ;7dJt6Tqnif~8a8&*C=OhJU#;WS!U4NBZ$}4NVK5A-N zDk1zIhtLT<;ny`~*@IC#;||Q^wS}wpEbLOjX#Zlbn>z83;X{~*D9QLAplh)Q`RFIsOZcW@kb1@6t=GzzY z(J#My(cKIqEZ^RvOG^x25dY$v!Z>}p(44ujo3Eqx{DQJTH2gmT+H&6g~xTO@f|A+%bfc(jSz1^Ir)a-=n>9Qp0hw6!o5U}YtHVYU1G?bB>?vMZs zJzk^H1_?SZT$h!oBlrrwFCHSp z=ikGyv9#1CvA&6-V}YJGMh(T8>9+cRvGv{YRQKWg3T2fYWsi)=D6(gSY>F~NcE+(c ziL7iPJ47Xf>=ohI3XyE$Byn(LbAI>fd7kg<`}+NU&p%H~<9yzq_kG>hecjh3`bP4# z#`lo=@)zCC9OoTNO|P!G7a2`XY2;@rTfk|67{K#j8u%9<0j~$Hs@B$oA0?KDUW_=@ zsOSRi4yy#2(W$6?b;lY*_LsIhoJKZ_iY6VS6DB?30jPd*yF5V!=o1# z9pBlxEXb-9;LMQ$FrDnwwz9o?2-Z*Fv^Gf}gq+CZ>BLke@y7DxYPY5tEoR^R&?r8S zD6)fO#i|qyd#+(_YG%>AH>4L{+1zs!TH#L|H;#ORziRa<@|RkUkQVY8rh>MEa*jCu zBkAjX(Tx{~=FFY@iNb?j8e7CKdU-r7W>adK4WG>I?+h{ByurmwMPfQrav8eC-h_Kd zB7zo_6cV1xV|rB580;%MACeTwEirbubg9Md1G5M(1Kb1#I>SbjR4VI7IV|N#4<4AI zX3(gJ`t$!7*)t*m{Zs&o0@e@&>LiU|KT{tjikz^_LM=09Zn{tq?AW^cmF~ZNGOgp; z!SHx$^s(6K=6duCWwr9vgX_ptRQ+^3uZqRa60T-I5i_+ox$%ONHQC^xrpy=PJ&@v1 z|L%W5`>F3hSb@o=mPfWywY%l_we@wQmkjR(FaX(`&4SCGPEDS#(F6|_BryB9hscOC zr>_F+4ioR#6v1fR>LPd_;$mjuI6<{Iz4WlnPGkZ0X>qHljORB4SzghAJ*O?CWNP`P z+sW}r-3MBBEI9aJ`%SjS9=PG(H#Yu+k^ZYsjLrwkB%D(K)G-_x3;}o0G=Mw$akED3 zA@CPeyq9s9AO0*DKrwLG>zx9=%n`TDhI7{e-~fdv@7XNiRZFcB>~
RxYC7PX1r9(31x=e}wx_3~e@Zr+C?`MjcQW#yu$ zmYPq?DfyqMFqoHDa}DTstyH`&`*3Ae;}VH!o=%?nctZ-6`JTZ&L!L@@t0ZmJ=r9wM zo&M3s597tPVxa*>g`CQYdYntbDbH6ZjTl|5F3nO9Qa(mAV$LI#Ewa>scY%Eu@K*;HG;oJ9>YActzulV!g6poiNKbbAaU zUT`Lw9XQq!+~Fb@eQrH0&jF_|oB=Dq0B9~fB;lS&;_P|Dbo~_#tla|0L8@}Gw2isrX|~&mSym{lae-)lH=A}}AsM-UAm=4=(-W;>eBWiZ12iG#{2vW# zo|iTbBoNef_xz=%re}$1itIlSGJ_h=D=;9jQ5?#;T`F2X$cF6t%z$9l?LygJ;pm|r zmcBf)By5NHedmr*V)FGK?&}qM?T341FFtJw@J5Hib{;gv0MS-FOwMgz|0w=s7rKgM zcNjEyHJ%e%oWfC{NQq@ZI<7aLo}C+@=Z^!vnCI2+KxE|px?h$IX3%{I^ZWQ$p%JG1 z%9%Ua+uUDMLaX>Cq+|GL&Y`KH4}j{fP6%ViN zh^&G}VrvL{G&F`d4S{tyx4!$S;1>hP9CkuC$gvybIF4`VYf40=J`}-ypeoI-{K^=N zru-3Wb*w3M*=FIT5qc2QbWs=Nsc>RiU4e!N=nTcmYoWbkfbSJNI52^v-4fDxIklu8PqI`6LLP63Q-t1~|5DG2FwET$?~}=-_ZOvIj4f!Mdlc?V9{Kpf z(&;Cg9xN`Jx~#VXN59B^8asVf;R)@01s*{|UXlChiwYE>bO9b(z8qe*`-rPP;Tfge z56+=86zM>hbvrsDg6!c$kdb=JXXTZI@-g<$$ivDttFxFER2Jd%Kt6GXk0I$%C~uQqc+4cu8jSlTz1x%f z!qw~Gusi7lw8K5%n4$XMZXJNDDSBR=&6FEJG65onz$iu}#N`3MzZndF7JuLGFbLE= z57@{W=y5Ot`Hms}#-may3TBYVinSCONOKv&00vnA*4i3C8?L9y%lc>pKLQ5=XA&$u z1U{=mWB_sC3I-tE3zrU@nayX{FKg<zO?as{3EY>sw*%(5VBYH0c*6nv zgyx6ng9}P_ZI3s8lEyFKyO}U>%QD7n*)BiKT{u-S_JN0RUn#PRa_R2*McIbhA=joh zg(@{|0vgrRrWDCkex6G7{}7O$D$gHBY|F|J#&QXQ>au(^p}grqi^2G z-sy>)--Q)Sh`fiy2I%xz!=O;~f4GZtHG@AHnv?qx6RzSv;AdgY&zPZNa!rpWJbU!B z5w0_bx$|vakZa!NUG3PFjt3wjJyb=FTkC|`$_7df`vTYuoCA^_crsGKJJ1Cq!CSgC zxbqE(0fxEO5^EiieJSb-26rs48_ZK??#+V&NA{Yh2 zSv(_08YD5x&o>_nNg7>m7sRg$WxZ!AjaT-Oay<^Y&?e59mObK-cUD23Mj6OAsK~a% ziHzlO2m*4b*bp=9-X+`$Ly*>4)ZE+yn~IXffb`&2I%S2w0mbj%zki@lh6kK&*3HAL zH$k%St>0K^vDS`}L_6z#CS-R}^^}#dlSBN9V!T(s~MPn?zq@j zKk9Evp5cE=8v1c?)nMeVAm4xU53(;tV8^`IXMWNSt;D0!)?ch+qbbmL0&$4zRaPCu zCdH%jdESwhjIVA&5rVgs{(QuaXcwD{!8wCYuEp1|q6XI~aFLoxoM4g$f?b=ABL|TZ z7@=)_HQG=lf+cmBbU-!J3fB#0Seya7@ zgseH&gBF<-QvUuOP<|jC84qo+EI&A(jwKYoO2{nElY8g&A@qM_&+F#gw=lNTR|;BJettldzg2#ec&lW~VwF2< zEQk8L;rh_BZ|R@SD+%?-lWTWwr+^YW#cOKAV7qU@Ww@jF?h` zzMYE$oH{1ib}Kecdxdvkvjin)Ka(cpUZ;f+yRJr-jz zkR$nb;!iA;d>O7E!N4`>MK(4zs&^APd)z0*6uqj~wW@QPP`*$sKtf$wAQNZRFkR-v zqD%=|BVZCszE(a#%fkWIF6q2|c zcw=#=eL?fN9(1LvkAh9j#>^ZwGl~lB4@~^pBBIW`lBdo4dX~;tfJd`0sVcUlRVbQF zSX} z`!XgktC7!QHd9m#9wPZ9v>eKd*TN%cmICiYE~2DYo@)ijm}Yq-@wn8O-e;Y26&J`! zcE}@TgIWV4kM9II$H&L03wsh~gZ6RzK*@t;8%P6va!`Y4LW>!+Z;mmt9OY|Q3W@|^ z047@M-0gDZzFxxE{034+wQ2%}?i9+2n(~v=)1Kptr(YKdyx_b{P3Y1!9uiyC`l!98 zL=-2RjO$aZp7o`|X!$Lsh`qw)#&nMV6=KZSQG`+4P^`Yvn`!3_<11(;1Ox`fjmcWj z5EKMqfZ%S5v-6dT(lLE$2dYMhEy|`xJsm?TzVtB*yO#Y9Qto-ZgsE*y<$2r{U7Sn06FIke_Jkzj#F0B(tq9SU8k|&j_F$Fz3YaSp2Jh{L=gse_p$eP9HZK0iBoIQZy}> z<{LKeAi+4$hrrNM5#7~wX3fjLi*^dVJMAf9yG%_6ObYzdK~w|tG4MjGsrdye%<;u6 zVap~&4!4@6V|AwT&#!l)9GcdxKjL_Q(54=KRMR^61^&a0st9Rj^NiLi%zq$@oJijh zsWfir*cNU<#3=QvM0b1HS6{A7?&p&{6DC2e3n3a0^Y4?nF5AWCNRop^6R$ZB{Ut+1 z`lmz3&gYSt5As(p&pF0=pBHdbm|!D+98y)ro2z(Dk@KcUs*tYenQKL5*H32;>k_Ny zKaE~}_FesF9pTpEMP^l9lBJh)N&XT>_FL?N;eS@bDKrQ@SExaFNU`AGlKr0SC`476 z<}F^QW3?D5{%JwhEe_*?6VBo$B`QC*>bzU@VZ}3POy`lE7Gd+ysf`qCQz`-+RDjX> ze=5r2Ukul9A8u7ki?e<%9#BKS7%_Ajo^3twt53bNn!!;C9^*@=)4h|d@7pMk0Mv!c z3D`|A%mLP-k(utJn&%_UjI8@d%ug*QX8SPeDCxf%d$?I9d|xEb>;}RPw?PRsy}uV` z`nr(USC{{)fzN7rda^RAe7RWMbbrG6%;&FdHMjI%hi*RX=gf9>_0VY$FOJjUy~0Pq z_a{M9Q~Ra_&$wM_k$JAvZ6#}C%s1LyePJ_NLL=U=lBSycYQSo?OAhW z18%oXOJyZ65GN$wJHGe_5%=w4eMVE$kZ#Foz=Z{<7`IosO8j@P&s7p!r zPl(t4q4G-I?D?N5Qqz=O3Ek-VobAY?$nJQeW4ABy6J3tg-`thi4U?+hm-Y>CYRspe}QEXX?SP-j;6l1=guv&AFnXf zy$wD8aI|wh$)-P-YDiOhi{cqeX^k@77O6lxEtoEAQ){KP$KJozN0Q?};>JX365+}h0g=Z7 zL|=Sz$b%wxj^epmn9~uBncsY)3UxXW&EDnj7+g%&xi3F!()6#272;8b(9G_wVbQy$ zM3=)0FN{UDcVB)CIEZYKks18)nV9}Xv@q`65d{!1D2#o2hY160!;S;F@AZZe^EBCEAhZ4qb)QSeexJ_~ zj?CHH6N;G@kopho;D3x%w{a!AH@?*Oxxu5S7)N;n6;)KU?kAG7LG)05p!_Airs`gn zkU7Z-;q6yH_QRxeb!aZ$rlr-Lx!D`S`kIn}%K=-bS38!$-q+n_wbeuL-1=wlCh5>8 z($h^wvGR^YpTww_!Hp2#e5!hmqKEB2J$kYWB9IjK9<9C(7=nRjGk&3C~!$h__ z6ORoQ6F9mxCz~|`R?|T24agSMs@;#R{Cxy-&ak)mGc=4*o3*pOh zij=AO4GBD^Bnvs)?_N9ihW5|8XgS4;=QIVV`SZrF_C+Y%yA^r?DJny#Z`g`T`?9+w zUePh{YQhZkCa43UmV%;cat%UM9abe7+WI?>TP{KyE+HJ}yO_}o6IWQvHBIyGI6`$` zq@kk#q|e_6k_xcAPn$z1^p89IT~7fEnOp4)Gatr|0*q!>pT(NjwC*qNN)Iu&QZD~p z@PhW-jQn54*=CN_nQjG&xx$>59AXB7X?`_ z@#(*mfk;);# z;!V617Lc;v&B*UgkT-I?PP|I9LL|qO652>caYf}dkNn<5W{kA}AFF?y}j{)#L{B;%<7L{h0`0hZ`CN(2@H?QTy1x zo1ZYgEq%~hRka93Q~vJ84K-CG$M*LcI)0f(7#rq~yYX}(8ORbwLtUC0#_5=_{a?E_ zlNR@O{QrLk%3zv7*Nn)bVAWhXLGX@368Ezz;TMCSEwA{gJDDf1GG;p(e>7%Ic>M0& zv!U*59NpaVkJFuP9Tacz#_CBZvvp&xbXMYtuDS3YCc{NigylDzDl#T?P=o-+1| zLTcK_HS};hT$Kfmi&W+-p4?b@+E;tL1Xmc+;`UKmAC&e)m8O($7*LpnUHYB(r)sNy z@D^`0YUPec?pP8N%V}bwa+>YMaJ|v-yo9`X3JWG(^DDsufkX>$)Qt+F8FkIOjO*eA z+&r$y6I6JvIhwLMm_GC`@YtZc=wq?cPIvnG_Gh$wN__XG%qa!evWlNZJ~Rrk{pB1> zce?qh!p45+QqzuZaLYW*(ewLNyjG~qEc)WZSWm$PvmCs+S2x4P?Bv+fnCr)W=)V*x z5xn+BFh5Dw??+k;XJJH|CPgoIjMNX^FU0XxU$~m!oYQ2cmB?h0qLFv= z{Rg7K=3>dU_8AStIuVOZRu1&*e|L%gE(t5rDF3rj2P7A#S{4uXLci4GS1GvV1TisK zX|dgrYQKEZM4%Da&Dv6-a0z9E<;r${h$dAu^oM3Y1G9q_5LG zNXl4d+J5?LM^kgp&@>$}yqT$b0{aEH)l}Tgb?Sd^E`85l{~TK;$|Bimduo28wCW#K z>>Pa8+@2TcygKdNwf;STmkDE^1M7C8NtdZ~3}7xr!&YRmuy8LyFrGS0NO-qX!U}A81QmVR zdPz?`*17nD*y#4?hojI9=>*x{c-3Q~CFQ+jj?hBGb?t*6x|xL)&vY)yG36ayN*=p( zfAmag!j;-DJNeIo<=--1l`h-PyDr`ScN z-cE~Kh2BhFUqccG(=Sf(Z3LWJGU$mz=}gKDSRt zTxaAMEv=%arW;ikeD}kZ&x<$jBo@RJ(x^}7vR+c>CfzDJ6ZkouWS)|UrRt76-9^9m zF{%;P&3kzU4b#m}JRLoRZnaufc1QQuNcW|7F4 z6r*4UIi@6)f#C`k!8vP=P=tn=V{#`c9zim**)@5Zi+Lw#T1*#6Qd0@H^hei%UsO{28SmxhHO+Vl33MhT>8uzK)*StR^yrcfRf z&CJZ!)l7an#qhQ;b3AwopN``Y6J+QrEv$ySVuJWPe;gg#U)POkxjXWdr#=^LS{w$+=PAm_oP#}&B^s=5@dehmcm?e^`^wGlK7zdSTqD zW5~a4skNYiAIiqqwB1YM1j}7RuOGP{N6XDX_fDt%!*ZNQ#{74l&=Plxn<(1P{~o|Q zzO#+U!t}H5f2gPw;7BLc9ZN57(OR`iY<}yWExmr@Fe50NIl_SCu0&jN#&^jDBaZ0P zrK76^zW58@UYI?67 z(T6g(`dL+NgsYxT7k{lZ$Xu2({Ykm4ziZfzKu zh7A$VJ3|sBq(+{0u3}Z)b=$GUD_Q==Lj98|@PmykA9^FX*B z;c`f;COm4(-$t*lI z_9kD5XnNw_S9MZ_f&7Z}^#gI9G zU$~+0J2yGv&&{;uC$@BiVqHt9@IU1pAGPFn zXaNr{xtyb2f^VFUBF%AMzx%2X*L1Y{PL5 z{!P|~s@yYzK2F{{1#MOlD)-iyEf>73ezrVppY$AHi*zJ>8!@^uePz`+R9c){+!il5 z(N?VHWXy*7l3sTMU0XFB$@$9COjHpmU9{Pw zwmCXe+uU9z%c@DJMlMXL@bhfKqq$Ch%HPXW<9Ae3f|{^4ai%S287_Mtxzah6=$`DH=yAKl|hjz|&d@%ja z#(9iz-P?Vy$J&-yQ?VcHw-m7E$wHYGb+m|wzCyQ1c*4_m>y7tNW8?Jtnj$qp=JxB6 zQ$1b^l`Vy8Zo#wSNUl=MbWJq@SG!u+bzuRm3QO0oB(=>uh(ByjY)qDC%7u=t-bLBf zjDJjv+Ts^X5K+0n;_9iaoU5qEPtlmvf4A^VK7T~px7}WryqF_@qQT~`4xW7N7z)H7 zFnx>Z4BbV~R+$L6)W>-V*6>BUiT{?YhlDa16ZJeC4wQAwc$%5X;OQ33 zefKT`f%rm<#>x3W-wYZWZ_?~--ypwr$>jo`1u#*CiGW-EkE5fe%*IDI7-&~>B3(_| zQBOJ5(g$o9Sy;eb_tXBqgj$jZv9#Zev_PZQ?%THwM0@Bpht?ql79wnG{NV0Ttejd> zS)**nX7HGJ9*ER=xX zWC%5C@2kT; z=B5hCJFopzW?rKCZ>)dmxaeu1V~d~v_T#AW!qypmr>M80x+(0(9FJtX%9xyGcD45A z+Fi1@lg?SJ#$(fDSXs=qD{e*8mhtmso?_6u5~Z4L{rif|ye&IDBM+wJ_g0D5cY^OLnrq$&L&o?KzXr=VtNj{Gx!YthP?_EXv z?_Jd|ak9XORTZkvr#|4Or>0aU9tTMIOauQkt7v^umIykGq0 z&Bh$;9#wKYOn=?)$;yx(F3Fj7nPqrNtPj-y1;4x(VR@2Hp z*Y-H}x`zHRJ=V{|^2puZGT%?Vvc6s9@{JYUYDL+QH?@&Y?{yWk&mUWcb0TkD9KQ37 z=kjfme22x(Kmx>tMgFdi^g@(5H$C=yv|ex=r%da|eBNXCz3LdItS3e7cP}%XB~5;x zn%>{mJ(iV`;l!x_Q06V?;e6JXVC?65sobGP=3n6Yjyq}!`kkc8z8AwV`@eogLw$tY zv#%wFrcJIC-J`rmfdt3^*XJj&`UTh5tWn+Dxcy>OOWb~PGBuRNk5`4YnK0VOK&17J zOkqaQOu`o8pC;ckEkz~A{`n}D7@?C5Bg#Z)3x!nc>2KtoM{t`(Z_&KwDd&lHlUI_T zl{olF;^Rmrw)gtr3=1DiQM=1K>)(v{R(md83Dt?a#&h0Q-|*6W*ks?YrUXyk8r9CS zil+O4Ef6-rdqqTO_M1fliFLRthu<2rQQqY`bJDog^jmVNpgShEG21D(*_Hi42Zf4o zMO0Me`$5a>&S}~s{zzI&>f{b$1daE3Pr0~saV`6djG{N#(W_`tFTrjGYHDR-L>5K( z8vRWgq>}yZ(YWcF*`*yJ*R{nsqlkg=gCCtr=`)nWx%1J4WhVX#vJT4oJb!fO_rLAd z7&1(4UDY)8ux#G8mECE1^HC|ijW;RYb?IE$_r30eM`2D^e(#W^y4e4UMdyn}c@Ja~ z8K%uFF(;8^P#M0<`|ee7n!Ss(a)oGWc(Dnxshllt$QTzepMsLmjRX7O&><6H4NU#f%d z*cOzLW9*bo%qy6m#w8Fovus5vxwi?`7I#X+kF@F;O_I0-P<9QRkIL-b$d1!~OGWK{q&Q*n^pn7U^Uz&`f z6_c&M_A>IVv$i)f5uTo%0kXmCY*(VU!ox5Un)k)u^v-00%Jx%?cT_QRfgoALaFl^BAXuq z)C?Piiw+MFcI`FQsSRa~txh-_Jl(W7_*HY|Y_F}%bZM0Ljg^$)N=(6jh<{{37A)9~ zW;dx_-zNHr-ztg3PKX?xb>vm@8ILX}+!$h?`mlRw8a6QKh4$*rt=Tok$M(>lAQxyNDW7_oy!Gk8dLqW3~i7eWqwu&F{_Q_;akM#TY<<=XjS{JkF)oK}t7o92|q zRM{)VIfmSl#8;-a6jHRQ1bdAq=S-$EUYa&uIw@dfLBd``BByWo%N9Wi_6Ybi*nzGUX4_`qF1eZNypyn%P>=+SOyru{%?0YoR20V+fx ziSfGR%`M`xdp^j38y#f9?aow!l`2tmUD=(qVs!_n4bZ1HDR-Xeb21$qPBwgXXDTx~ zJWMI6;bRtz>yk)1*K9RgqlKA!EtbgQf~AkXoFZmM=5jkYvzWL%IGyM5Jel_qsk4O2 zSWI)|7MtkHigPxNtQ8l;F6x}uvQJ_z`ko{>nry77!hlkZvtWZ7s2MERon- zp`225P*xd*v&v)Y`c}zVHb+n0wxcE26-*Omnrs6wan`;!X)deE?vz&-MwHZiTVnav z*?It(P<(>VBvHG@ci&w?O2^$(ReZvRI45&^_;q~YMFECAvwaoS8#*n|itO)|kDHj8 zxw*M1-n|QhZg7@qHY@iZGNf7BAVy(2I|-qjTVI5B0hZw(-LQhjB(U+ytsuF^9s)SI zfCyJs?75HLVj!s@<+@a4LKpqowP4G3#GAKp8Gd_o1MJ4(kQaO*%5xVjH{g>I(C$d{ z7(h!dKRG2N)62NRvKamY{p3)g+(rxy|?hYw|u{fXqU4;Mb4^FU4E!`E7gV*;a1W&O@A|~ z5D)wSNA9foWOy~UY36J1RHf(EPz9sW;o8EF{5kvJG5I;^&B7G@jgJ zSKRgI3vFCDvzp~yPe;lkX3pQt*Lv^33|+L%O)~fE-1&${baf6((<_sF@8&wU-ImbC zWr#_~*J42o^OF9wR!$=%r3`{)k|@I6g)@du#tPHsDXukL&U7a?zFsnPdM}1P9-4G) z4HlkxY39`A!{?Id23WCL7c~?a>1|dlV={HC0&P)s;al{3kGL15iEhf3Egz%yWcM04 zjZG6C(M6WJa&6tkyCJ^Bu&^e&|HoWyJWZUkLn7bdW_3%`vtY?2KmYv{~L4-J`3x)i7{IK_hifR@?MXFaV%oZ|8r{#{C zr{bTS%HFffwzu$Bl#rVxl((`$ zIfSl>qT5d;QL0IWtEi)2yE4kUIkB#?Fsdy3G$DcP>4B9T@J|;#WfdRxFm!GZ_7y*| zadUG|qpUppY}(NU9wnb{ThzvBY&8+~0a>{Fk>yovc6C-% z!usy~mD$I_MeZ6P1JpfXYbV*Bo{UsQ1;lG8@m{VT6;aTkTWlmu9^D;Rae8#570}G0 z5;>v`@6OvRjb-A3-~Gh`lL~{Wel)HrQL1J5sWb`8Mo&xp^6E!0CKvJ|pwl|#jikK5 zE4{}kLi=tIk*WSZ*1M2SOx)@SYdnixuQ8m7az>l@REj#ghffN$iO%uYym=tAJLo_8 z(QDi&esw|S4raW9e7I@Hd_jXReg zw@SsNs3)A=!9IDgiFQF8W*4!W2C~kWc%N>pc<$Y~XvEeMDDYit{~d2LYb(Z&(((BC zQS2Mig#lW9%C12Rr-8ScNs)8fht$Rv>*9T#M)?j;-qaASAv`JW8dom)5C36|XtS_? zq-p=@SNs`o{V(qXkJ_K!V4Ba2FD|vH>M#lZI50E!^yZ~SWnTnsRB4pS6KTE5$6IS* zTDlNnBKbwJ(VKS38ZpjGCIp82WM@DD2fiq2h7`QyR7u2Mo$souuET<|i7nALR~r7ETCPZq}R+c?h`DTYe++oTsUGuJ-nx zw5)gI_s3f4! z#31t3+O7qkd5?`~I6HkLE!=h5ZAtExm=$fk&g|{|5^rEF7^@JzXWG8- zvf((cD!t+3MncTdAZC@d!F_6-y@sub)jRHF@FaR{4ZCt2IFP21J6ZIA=6Fs7^;# zQY!hY{S9@^D0V#^V~AkO5xPjf=37dmQ3u%sy0%b}R`BOB`I5`Ixs8L59G%39zbs+` z!Z2I`MX%q!jZu+!unI?LX)6g>p+Y{#3vS-yIFybnw8Ksaer6oapZt8|jr%p)*U<5wqe-h3<)6vs8}dJi8QT%EJcX9qdYL?S+A8)cUwtEt+xka@myp-2>8jDqZzw zuN0e<(16Jwb3PH@#Fk4lykzi|%>|_?q{4t4P)keen{(}Vg;E~DggF|oLD+w2be9Sk z(~Z~&sv8oP&>DPcBKWFf0=TN(~6;9~d|Xkye~) z?V!o#?qA*X4KVXFJXB|Cg$5`8H~v4jW6EpViR*ckY+W(iwu8c6al7nC%|uw`Fem?9 zk~%x(15t9RrC>S>UPUY)*I;AiGp*X(G@-|uxcKjoc)lSyF^lQgx>j_1Pg>-%xnvi5 zVz72bj{lC1g4qOJTcUY&+$NHuAD{B%lkYY?gUgj4HgP6L=WT-{sa--xab^vn za8??b1F)q8=Lm4%{Z!r5SCZ1SON3NOLJ-W=U_|2Siq74T^#htv;+nR$HbmM&d0zb-W5-5q^iF5&PPNdrX+2o38z0u|u=elr~it;jw^pV1$MeUQvyy z@vk{Wy!IJh*b5FsE!EId(@n}fJmX_`^j#G9CLaC#r;`p5`FJV4c5_?3>E6iP;g7R} zi4x;~7*uwr&`x~4<#NK052jMO=CTiDnjYM#AtktUCm~pC-Mu&XO6rL^Li`=*LRV!Q zR+PiObto;*3+$b(r8e0Q*oP0%d@`f!22m*Gh|Ed(#rXUH^7H58suRL*rO@Poci^`_oHL2rb8jylAhF>nK0*yd(2nGQA@RMRSdQ7n)*lCv^7GKV&Ows)5PbnMJFgj!njx zR=RmHO0JJXgNTux!6$Scma-%(_}`i5rNr|tu!(pvG~s_hF$Pjvq5_963VFtf4YK)o zpM(=h4g>`~6P{M0ZJFgoXVJAg8taRR#yZ+Pdh*Fah*MXQ>T=5`W_NV-{+vVY;PAID zz?FkuKNh`0^90ygm^Qq-bVX^c_4UMplAJp{76LB4Dnz_(KXPA?e}u1jZcO&@cJ>_4 z>~0BL$N2b~av6mnHl1=u21P$lxSy}dJHasMJ04)FBX;gp;tu+;)z3>dWj4x+7G%}J z(lZ=)Tb|CnZfSE@=(@Oq7M>EvB5<%KpS}+96 zcBQ$Xu!1?>4#T|UAz8*q06z|yVd21nL)ECZI(b2i(!P5aK6aZbh*yH;LXZnjuf40D zg8$s)_~Nx)pPzl)Smrn^ayiZlY$k`?=L%GrFU$t_2!C&0cip`tzqkK#-)BT5#d_lE zD0XVE+VP)$T>hVG!x<^hcFi}&`;9psmQ~R_tit_BdrS`>TS{xg(L})_p|ZlbtQ8QL zcUoY7PlYv9>xYZc*&rZ`g1zE$vp${1<_aI(oHQ(#W_c+l6V3iiSVR-kle0H8pH)zC z?ykP>DB-KC_9lzdTjB(44(wFPd*xE?2kTyMi}K&8UorL+*fpMfbL0gbx@OaB=Vx@2 zF0lo?JQ<0192!a5kyD`iFIn?tSq zr8KNr@cw6)(pUBw#%24gpYekau=3)?pBz!@UBSDyYZ-vtbc2-sL2#`6?`bXA+TX6F z)Uwxkg;r6{%Q4)qv&(4*6UzeYGon@Nz2yHTEijaG<`^w=rYE-rDj6)}qBG`kagu z=|Q$rYO=R_7xOC4Dc^nn<_1m8M!PHv_viuve@BPNo7te$hd~T(wu}R*`MgKs?R}+p zZ-G;N_4HQbqE60v+n4+aYv=Twn~hIi{6gM*u7cmRZ5X;C+;yVM9E1No#*>e`|FR`7 z<%P)iocEqZu?`?6@G50H-gu9fEUrutoo_EG;WH?q9W$!r2W!D3l<)4YylzSw()6qt zu&35S^suLrK7`7S%pV*Q8(ay@w1_KuO z&UF6fSBI~}t+N@+MFC80#4K5;HtQUeFZbuO3R3(*#I@Mbo%RaS@-2^ToL*1 zVXBtjzmMYKzmI}s&Rm(o>fT)Ae2jt6S+r}b9aiS7K=xuFUy>AR4^sVXeMtXO5 zt+=ZZjja+c+^ajn>`0Z`%|^brFZhj(A;R*v|7j^md0x(?5rmH3nvL$%6Q!N}PC73t zI>R(WdC2(SsZUUEH|4s+E#+l;>>k& zqLI&y;UlL34w&eafH|1zzFzY)XjMK}%=40u!ZV6tFX3{#fz@$q-#j-}x~>|P__ zkx8R`NRzp0b-7af2*;iF`Ce&u^})9A}W6l{d(updD$-cilp3cEUUDwug^ zcAY~U!=%G-^VHPF7mISosoZ$hu81C&$mBzV;((uz%bhgu8nT3MJQ#0wpKN$T$;ZjH zlE3(P{p5M+Ytv)hgw_(C+l@@d`eT>XvJyJf=*(FfemHu!vd+eSI`L)HGJny_fe>ps z5mpXvBi)jS=jlyjc<7G5bfJP>l`NCC*)Bv_n9LTa1=l`_O0(BI!FU9TmW|Wk zCCCol*)*YnXFhLl-(~T-Z1;c2E?C;(R6G5dIOP}F40+>_cSaG6%VFhi+&sAXGSMpL zxM>QNK7Jlt>z%ihXq5kP8@nfvmX(_ec3`kDmMv6{Tv@4G6(`SSxM}N8(ez~FM91*3 z3?HkXy~V~Qr$+Vmt!33jKw7eC<1)<4Q&=efokg9w_aS@DAnfh&^!kUd3sTE+k*O>oQNpr$nZnx?ngvK zYF;7+oFa~7#HWxgzNiMs5IDd3X!lP-Uff*4dgjyKyVF1R$HafzcFlh$#hQwYx*9n-qjv!@copsse>bI}tFCnz@r-plJf>lw-?8T`N~L)nRY5<_nk1j3`2ABS zZ)DR?f>0Jh$E#32m)s_fuM)MJ{wy-!&d6`l2z}yTHSzu)|GiQJ_+TL})%w0(>SYiq z%*jyZpqJcwV0Dm^a;C}m6IkZK1m+-sg$Qu>paiZ0q_Yq;_E4i|ThaNw04t$1Ooyg{ z0$EOO9J6wfC=Qd)<2p!*M4-gU+r936n-Dp7_wMwn^sMKcoRaJ3hQBg!xP@~fIX}~cd577?u!AbDHM89mSis*4=cL(nXX`~gFv^%IrzpPrA)p&)4`9$ zokJ_}C0^2p{!dbjv%A~|~vaa%n`)|-ga_z!Q*ic}}*W1a$I~}InJ415Ve)x#MktW0|jfG@hoK{)kerl~` z|IL6umK8e4qw9!qVL^5ffdDv!U0Lh<t+n8MZS|++ ztd#C?%Rqpo=hFh((M*Fo!FKfPi{7@`@pa@@Gfc=qG|du)YlstFJdwOltnBb%(cJW2 ze5EJq%GARDg-Gj~m zy7{kPX)*gp^%1XmdcCOzF>{s#z})rQR5@?Px@+M+mon-@@OHwR12qf0fu0rJ=$U5y z2=sO8xDmJd-&1vXK;pnc+Tz7%^Lvg7*^yc7o$r7T^eXX_?%dh(kuy z*mtdzSwq7^E7JLY8jU88zZFI|g-$UNe`+o0@KSNWJsIY#l)?Q-AA9We!98&wf9>L< zI35=1_H4sC+KEqw-iJevIFg8{!&;^h8~cbz>SyWevc0o6ED&D`$`-##pp^(l8kTmO zwd+xi#%F@#=kw5;+!~^jJesiFv0M`lVz+iO5 z-v@FYrVr6up~NU(@rZ19oX!XQ7&bSBC)akyP!iU11l(RDB5-Sg+Gl%v+rYd+G9Wki zkZ}UO8Z3W3cr8o5zEw~C+!~>+E-pJS;{g1MpIpcF*s2jmFdU;pFRfp}J(y5^;>OEVq*Mw?P{9R7mvv4gi0jY`Yn z^o>!?K;t{)1j5q?f=}4A-L^)N(^1_>GoMMFNhvzRsWm5#~jP}53%n4SENzfS-*{psU1vf6*r$C)kK*cN^w<}O+uE$cD4$wrCN%_SEo zYPkPEV3s}2B{5S%4?WaIgU|7R%#{4lsvAl98UGrkLmoxjVgGLYoTGA?QXS39@5LN) z{J*0te{a)%`Tfiy54(x!O#HyqVF^pjundVa(6V@g@=UHIm4HK@6AuisRB{(rdo z?rP$?s>%pB@CgU;v&)?3oc*#Q+7N z@}8BMMjB``4v}uDqSg@aSg)iNqR=-;YOpEe!zcFFyLa75_? zsJcXo=UzIE?#B?TcRwJZ>LC1&eAXqwPuJV4;{`0;qg3Y(1o z?|MJI2V-oWrj_^jA;`mqGkCW=G0=EoDf|l7%1XkwVmQ*>!9D_yTIknd(f?nW zoqtk4fo5e>6Z4U2&Mi88mVx@ugXaA2gI0_xqpU#ANN3YE-p*7cHBA31QZjVt?BT!i zOaty>zsejPC_|FsUC%m54QFfQo_IH6zHYMSEYT)D+F7ZA3o_`?kM7w?Rr|KISCse;2u3{v#I>Z^oC{J zFVFrwkd+NeStr_mX-Zd6#!XRRz|iIGo;x(80~E`s;Mr?ggN9|JM!OqfVY_9Z`_jRZ z(()1EwEj<+bl|&z$rcwEFV?@p5F5^#Z#%DJiiV+j>$^Z;VGj(G7v#8D?EXD_ZA~qF zNvdUb;^QGp`cgyA!EQaNVlHic!;#Wx(1w;SV}0$O+4Lo~Z_aHKq_Z6lR7TWX)tu~# zy~`w+Z#DMH+!21y3EwrIeIDh(5%7S6Bf7D2`uzFPJ=VvxzMF{ci81;arCizty(B44 zBF+$=)3lybtJsOg$+aY;i1(A9cf%4%E{8al05(KQ9ciX;v@ALnB~*(06*yM zEQ;CM@cljh?{!U=L)yh}qzp*nu?U1ryc@(wPfrgH$a6>L`mSeRR(d*Y<0f!sQHEQ` zcI=9i)1phV{`}*Ip~1WAAC9&4^&DzCP+&?~m_3Eet7!naT(Hfz^dH4?=Qz^>`|lb; zD10|UDc7BK)#2nhljRd`bVFmOS5~jme~Dt(KzP-z$H>UN)R@hkxHaVyjBr#|^uHUp znz8k~uJUYSyAsEe$#zBbyTrfxBG$}UCl893ENI?1g;Vbc+n7vJ=eF1rZ2Y`Uq+fR_ ze;&PI=HGOkTI`(WTf&F5-U9~_(i8#4mxjr7N~y4Db+*v;a<*S=qj^)KN3Q>?IA=Bw6{sYb{YLkDi@xfaC`h~DK~&QEnXY5Ie!cR) zW(K&r|Cp_*Mp+;TmG8-Z0E1${ElC-fJeb*e9DYG=-ruil&boQ2VU)3L@YfAL(g93l zSC)0494=e>=om?}9V2PFg;r|n1Wxwe_v%TM6rTfXZ%VOGd?@-nwEBh|DIVBNKRm~C zD~@qs-TAU&0JqB4W$~7%$>kj6Z3*0vSMds~?eEO>HNgXWW{syGC^kNk4{($uj_t31 zJDo9ec$l?8;jr_wT!u3p&ivP7!rNQQ)C(6HU7KcX2c+kOsMXJ?C21|_^f<;mp(%E~ z^K#veuWyI!gicA*HQZU09nqh3t1!lS^5=&!TLbKBPfGaopIEUf^K)i@d{!Hgc}2xE zT#@?!D_Ab0{AEz!wgg~wJhB!_Xizub^AA%O@F1uF-WioZ{rwMRSNI2CMyN+y8i~s3+fref}>h-2aAkTl<6^{mqjbxpU9|^*J^jZYwgC0xm9MVS{J&WD2X&3qz~| z>T;RLb8%anvld!({3*Qyk`pW2&ZM5pB)Um#k$|)K8IG3|t)x$McXvD17<)RezuJ&# zFe`(Evn~^xnVAWLgolFz?iW}cS(p2zPs93jmPEjp;A;eKdy4tbRD<{OOT-D*N14Rk z{soETS{n_+s*yqeIlhR0$M@)`hrEyU^E0%)>ux>k&U5UnGz%?WIm@+IdyvaVl+kF5 z1l&99dg(mnmF=w4gj%QfiNK635t`REd}{2p5Ou;Ie>QK^*+R9I2+9u>`wv4aMRn6I zGh^p2-s>Ow z`2tSlZ6eevgaF{|fn$JiX^=)t8{fxJ#B5o)j@Gdd6`PffDis>&y+s{nY7y`B&fbYn z5xUjToAoL(9)^X$<3GVRH3|pC+~(h4pE}?M7zWsW@)Y@-A8Wj-*UfhK7}^57cZ>eT zP4?r`4fu}}Z4aGa$MT+i{>nVIDmjM-YRaSqi%!iM)1VVN{KoAk}I4(W@b# zP31#)UeKe3j4iFx+`%Lr_XHns-{c%{rP&|bFx8qKseKq;G!iJ?xca%}XOxN3w?IbU zd2+h}_5q9Wb-yWRo%=DT#$rAxc2u+5t6Dlx(^|b}r$OB|z29@8V?;vecG8LX0wead z35KXu0kPXYMEQ;Gng*KmUvz&mQ+$lB!9|ACM}2%NDZs{IU%mU6U;#@q@Z%rB*$}u7 zFBs16zokuP?aE|4hdC(_V+d$U0g)em1Am!(o){GC8fBqAh0|)$JH}191okCa~eLF>>HUwcB zm?P8t<;43J*d*CH3?_n9#=}lTDhi2^s>d-R(oT-9niN;jJNuoTxMR}PG?#<)jdE8k z<@QSc6kwe7cNDGZy7%@B#ZEP%;%uIY#qw44GeYvSCMyZvRH&mIjiigisdnzc-;GJy z#4c9vWNgj6M>bx}!bs#aN}v)i^qkdw%ec__)5yG8BJyV|lgUW?*{)~X0rbI-uE8yY z0%Ww9Fyx-zAk(^WcEsc0w%ziiwQ>-j`0|qDl{>e@`%rj8&u& z&@EY6k@2GsgxLq((E5@`%#LVS!U<;w(`nYTPkCe>(=TM?skR_#^q#|eJ_|^PfGLX^XD!80671@;>w{JqdAOT8p8u-f(Mrs7Kx7qJWQ&CF|U)4nx+P2p(z(szy0GE{G6_--sI zRCPI(y7sHf%l%F$t3ljO@n11XIgQccLv}RDolQdT9-{kw<)%hVlNt$&G0zVwm=wW}zH(*u~xFXT2q`(k7S-YUj0HG1;CCfoDf$|904A2Bcvgc)ee*4&a?^{sE!~DiJNoB)i6H`;q7dJpb_42xvn%C&J zt3ESI5j9okTkt9rD?RZ?n=sB=1&_j7LAb~SuthwPCE_<-9fn|#_``^`d|3~9c zhDA|zyIro1h~2K=!dcVA+fpqk<;IrclIPAbzW|l%5zU32rVE#FbQuo;)WVV-ITc07 zY!(&w{5O@}UmMuCag+C>khx1OS8tc$?mFF_$-k4k{oWrkwge~HaV8S4XN45^5$pK` z%R5b?Z5O%Qz@e?UI?>B|%#95f%jbagL}yxrJU~c?<8h9+ZPE< z65fHNLCW~PW&(Dh21&#>_?V$3^pn^U3kz#&YhT-^mJWH}V8y`HVb66^=(0f(_$`(a zUbrunA$%;@_n|NXVuo3}D3s3B0;HCj$GO8oIRDiF9TY|q>~&dzf1|CO)Pjb#4aK;i$Ic1GdJjC0KWJ=Q?RQo=BF;O7P&d{9z&F5t+mM|s&ee#w8BsWJIIVVb+ig?%!&r~lx{s*H*fJN~3- z!cnYvbcJ#2ujj7R6pIgIRf(J0(y9Gh4Q9L1o#c!0-P;T6&gSJz6BpIO$0EANDo;cx zQ_W|ilLWKDu;4?WOe2<{t)jThZ)G6lepWBNqUT@r^ZK5{4@WWnlsmuxY0&}RgX#52 z*6&!lW3~us!giq_1+EsbAoIS{8N1eo92`=VW7l^j%ay{w)eZ7b!Ahz`{P0)5i#NWT z2KxI$rHz`OS7gBuw@&#!)YGeBc&5QkYt|B|mWeVkH-{p#wz+v^P@K3UAOkHIM!C5m z_a`Ef<+u0HX4`(P!}+n2M)K3AU$2DVQdhYC6_7W~Gbqvj^#X_^Q%t@;^%+fI_#f#~skFIP zbJ&;5=5yiu`4biGB3xQkouV(+?Pe}L8XUE{xOe1Z%R(PfqEf)gK^#$PajTtA*zsE& zH{PZxv90cRD2)$-WBxL>63pN{Xy92vdlelYR;Aw&2*|*;0uIFXvE^iMV{n0_6pkon zU`CWTfqVNq%=e~Q zWP2$g%fV*lNCIl#K=RAFGqJOG&jl-}DZx49z$GU#<2i{$*LpWB4vBE74Xw?{Ec`hp zD+J|^1x>c7i+L2M34zW!0sjYP>p;N(v9Z%K`$~^FQ-gdJFfHTVUZIx)Yigj=W6ZPX zvWk3ao~iErmlDWQ+BJu6TJBNyLUX}Vo~-th#?;BJr|mLVMduudJ4B-@Z$#(>f)w!8 zmBRjEfvSnlkVN_IQTr?@)Es8+jJV847F^)Db}q5gq_k+78w zd5|5yPx#B(+t+pDBzzUlk*R@{7*Ad=M#B@nn?K~teizVBR@TaFIat@NXa;bxvE*Q!9CTOL(17hMczU%h znA_$C#ebT}Lhx(nfPlo8-a+sA!F46IE=AS0|32;S+xY$Vg;FasMLf+Jsqjq%E!Dg2 z!y>jT`9*6q;h3rb59RjNsTmdO0Xy*+9hd&!ibID;dx;zgM;&OsxR}V zDu>O$^NEn>rbCr=$VL@1drHRqz>3dSPu2D<+fKft`fNNZ3XC>>M5nHU9NhvjcRFrm zI~9Y$I0r9iAP!+o#+v1K6vo#;Id_#3WpcR@2fMSPZeQ+e2|P@F&reOA;mtzw%O8TH zX-pibd?}{g2Mylqz?VVC572G zhF@0^06w070qg!MS^mdg%whXC2Bo!R{%9=cZeJrk=~-J&=Aq??<&>Ci=iG8{>z@+X z4^Zk`zcqTn%DE}tym3N~Xttvp*&U5TTDy=ulTa>uVua+U_A^MT36i@;!>$$bGOF9e zvEqVN%kFD`+vkr$rzTx>UUcjSg>&Aceq=1{sQ)L2AmYq1!LzioCrdi}#j62?V`z&$ zHj}6I-#R{>#pZa-n>TMtt&X7W)fD}#nQ}Gj=gXQAFMDf{<)*NuQofYrP`&cEVU2Ge zf~_qboLA?cz%!mo*Lpf?QMuwc)1*(YjrGdFY`9VPyOU1+5~c3~2Frl@%|9GblXENw zQFfH-2$;B%CuVF|$7PqU45++eW^HiW%ti%>$2gfYGPQBi?&V1gO_5;NEp|5}ejfxN zMr@UgS}LOtyy>s+#t`yRi|y?_#zvK$i)8G)&^jAsqA;Qx<@8LMY(QL=l8HdH+y1HLmTknmjz@IlsDzZF(lNp*p z-jl4m6b&zr_)P(q1*8E;17LwT0pVzL&a-uuY~&Zp^=_#9G?PNIbr3=@YbdzcPpwUI zlxyHWq+iLg$7+j^T7N0x_jp4{Ueq&dL&mDNER~VbQ669I+?X$Mh^SS1N6xMFtgrv* zl2P1mc)A<;JAtxRzo*KqXF=K5ggB&=d{_vS!S1dY@+mrdOuTRy6TjlFI;+! zV!m`RcSUiBuP3&|qDhef_33f2v{X*Kj_S~x3S-v+L5XXpQ?^}0g&qWaX<;K)x&86g zAPPbQ^>^w zQldw^LqHo3^JG9w0esPNuti>G-eMzi-m|811e~RBK3^mrP#D;UG?w+N`qfX#hKZIB z4uPYM8|_SI@oan3f3WARD7qGn?`NogeH1EV=Jw8*vsl=3KH1hR5vDRb)lFVw-Yp2- z>ZPup1fFkm4l;i{c~KT*L^RPghOlXAY-b;!sXIN#-+xJR;g^;F;hP(I^;;naSY+6c zxf|l}ZU$!(cjtJ>n4V&(e4K3R++zikafR=^$Y&yI?Uofk;Xwev2B#*Z@Z&1d8g*Ki zZlT+HwBlyg;H%?y+v~6HewaHTh4coq=8Q2{JuLk#;+Xvs{beD6Rsf z5Hj29YMh9g@9tU#cW5K<76ZUr-21>*Y8-Yx8AZ3qwwwwKI7$-s<&JvR{FGgJgFgt< zV-kJ;0;fb`d!bndCo^ldh73&k)9dtVIJ9{4#fwdFk33aR@9<)o8nIeIWK6Hf^x#>P9_S#3f_&lgRAt;Z+h~;FcpQ{H8ZxK^$X3aHLHPc&iLe6I3@`#pFN#`FC9K0(-x zHb#M4=lfSDQRy#pcm^KK@P+Mh$y6LJ^fIrHaugq=UAzck@5zL^7Pg*|%_zJd<2Lz}Acu>>%FychaZqD@LaLNs%@~6IZ;vD9v z{zZ$x`xeS6!T6S3^HkAw@;`cdz^^y>%sZYWmM38k6o>U>##K9c4PjNpkp`Ka?TpcAreJ8;{lO7M&GXwsZ>DId58=n!GWn z_?5X_S@sh_W}>?${j)NyeKLc2I?t|%DD86`wo45O6-B(EFZI&pnLgj$zqGKM<(pYk zvMimUKG8hRI6v=a9)&^CPFOHiqk|GTf6dP3u-N`ePdxm1-7mFqr}BBg$HlEJZJR!} z>~*g440pJekDJW=)H$N}=YC0t@-xILXPgMI1zV?&kI#LXEX>BnMQj6Y`OM~5#+D~S zPOm$jS{AR=U-fUf<@(F7axsyUJtjxl34Q3cUw4{6j7t8%34D2BR4&g(>YHR+j7lKR zmmNOqU^P$QIkj(PCxo=q$XfU1T%flL6{h|jl)_6Lo07w<#y34OcCm~5QaOE68mfsc zHN?LyIA$x;K}t%KA!(#ynBc82C&lAx%URVCZi@?Dx^5$VFDP>s*V9*R|M>66eg^`H zzn7#PT*8AOg*KV>?lx1o1epi9`}s{UgkMfnF@8DYDCQKS5u-b}zO=&D?S}n($MR@z zpQu`}5iW)q4Mw@RkdGDi71hmkF~JRm3J`E6$X^yrkMKWa(Yk@9?2xmb%@d`wB_p@4 zvmB^}8>-$C{ET40WooNdz1g3YIQrp9@k$i``=`+@gj3C)-9oP%Mu#9&sJh#k6sSbZ zhmOMjm}rdq%b7Vm(O&+Fxw(WYKFim4aqUgcnGe2bWzNjRBCSrc5<*>JM+URsCo+AJ zg+Z;7mZ^l^rv?Mr&JvHzIzI7?KOe4??dD;kG{caacPo;*6dB#H7sXdyUh9;wGh6Vl z9%H~my7;*rjy(T$@=dY5`Sr(5i;Ih=tmNud&#z2Z6dJ0wQ$ETQ1W=LF|<@AaKie7{{AP9HMAQd z(Q8jl0~lj3l8jex26DbJAH$uG_CT0VduMMxb-}sy6vNzgs*6haKWBgMovad4qaMvF z&$wRVnZ~r`^jG7ENY9?6GVi_vM*+FdqVL@7wuJGU7_QT?BLs>~p_5OuF0-u$vI_H- zL7Rciw2%F3ZL;u7kLcg^Mw>(npRTu>>{On#j4&E}%YzI%IHQMP9AyfH8wgVtec7ie zvM!z)cVjr-p#$T>VIN_YQb;0VM@n9Uw$aEz0Jd{=G-?;B8J6l_;r+(^YMpEG(9#mc z3?;q{LV0!xrN#?Wz4KrZnG&@db4}&q+o6w38`w{Uh2!&$>nG+I)8*U`8epWal2+M^ zm$;F+KiMze^Rt=mKHJTrl5f1J4U#Vjd;FK0@zJam(lqn1jSoD?zo|Rhc7&es6Ed=O zC%q{K(db9AXTM7%m5>ykw7NpKcE9&3-D}B>6JhnYN*Ko?jrE(TE3aAQoJo=Wtx7XN zw;(EaT}MXMO^!(Q^ZkfRx}&0){d6d`VbTo@QoeR($*X}=Wy@}@kZQIOm}vOufBgyu zt40DR@M{1<3ku1s&cG@!x^VvYkDalk(}P(E!v2c2K+EaD3tj`C`&KSt?nL_{P=8@A z>ejv_jRwMH#0XN)>}&`ur-L!Oe(G0Q_|$ukwh3?!4o=2Nlp!ZdMBSJP`$Z#0Rr`=D zqbdnh5wI@$!@I|ZoLAsUB;ucheAK1c*rDe8j|MvT0-CSkJXj|U%SB7?ecWL+aPqSE zb$d*wexdlAE{|#}PdJ6P?la3!CdRyi@=)#b3(P-LeOCs=Fes$L53_(dFRJR0{*&S@ z)>XcP#S_-0@_cW9LkGbkQK{m)6G;TLBIN4xmfy6tD&xQ-4Ask~4-|4Rfg2=LH)b8W za8BWHAB7!hJLrpmne7lMZys%hE33q_cJ0z&+?d_n+~hJ*XrT?8%IAle=f0^gVR7;$ z2n#$h<1<-3&r0Qj zNzDRA8mp?W_VmhAv4{CI9H$N24$0BJlhY;VlS2=Na*|+?^sGdnZjxZ{mgA6cvl{Nm zq-&_sLFegd$DvF!`=n?sxij1k15c|YChC*D_0Z|_V6b&?t?Eld7^%rmpCT1w{rOEO zoK&bslUPVE>G|cGTNghLOA7Q|>!i_HwtbPA!NG0Wit<1 zOwLb`pWy1?WvR@D{rM`~-OoFIHv?NzP?ErGh^T=X`XQq(Fkdw+%VKHxaJwz?e65|L zIWfGd`mpb>lZoDNtm*X$jUB(T=aUd=+?fA!mPWk~t7eamGJzeD{DhEG<&6_^y7INK zaKP(%II`4&DRal)%1P7WG`F)&w}G+lv)A9K3*Dn*uo6QiRIhuq#$UJ5-6ir2?oFxn zkH2D&kc*I)VRxA$5IdLCPFF-&{EcUd4)ub;+&b8~a(qw?8ZV}X5f8yl@4!~XguS3PqDgT0xhyJLFB zKP3jHm;;jpv%{de_~Cqcbt!%4J%99EEjk`T*9j#pu&n?(7aV7oEA1y`58L?9!IlxV zK;mpNt06t(CguN#nbliH;`_q@BoZr*oQceA%1h!PIf>s$6{3v(tKmQpa+>x{jzB3{ zDu?xVB~O8`KddphP?91Kog{H~zP0RjBI9D$WpZ7~q_ojMj+VqW-Y0tJYY?_3?@Y7D zSG9*D)8y8Cj)){xf8C8Ezy5{b`-1ak7{~qCQgRO3`$=6d97529^*wBZNuvY;eXhd{ z-~Wo=JVTf}@bwMvCzR?v=XTM2>S5dQ5k; zk3ON1Pxpwln7iRBCU8okPie_V&2(f5PEJo(pW27nLJW)IX=jzRZeM;vh<)2}a1_G# zg95CwJJ-8lYY%i8K_4C{A=kQYcZXh@t4YJ%4Y&Ao99BcXF8cq#sEqjh%EjLIoW1Y8 z{B@YSb@e(eD_WU`ypqPv8`&p}N!UBGRbVhE`#==p)rM2ueAw)V8%_&rwx8J^cGYVX zt}}K81b3B*Am&%A4s#n@?DX&<81WF{eXuIP&L$F$dJq*OOrnz%ttm(3`JHYppvdp7 zn`iiy5l#N=fixs4O!BpUgtn3{Uu&J|=X<;)941M!RHC?m0&Kp@bHvKU6DUp3_yM-p zCfQ!NYC;ZTm6zosshYu4lhpi(H!W4IZTbaLE-`;vo@ZS}K6`t%VP|{ZLASY$UQ#Ke zf;~r*fFPz-lA|?@y@NOGd0!IZQFG`3tnQGOmWsEE6JoM5!~P;=Hw#9XL$AKmuP;pP z9#UMr!axqfzM5|;bFC0-TVQ)0`R(^C@uNpOSUl=t6+cE@PX~%}=RR(ZWr-r)-9tyt zTitD#f|sB|Gb@p7h>x}PN|~q|H*VaIvuH9)%ma*975fzmp)zmy;-?)3d6G?z|G;y> zgTG=+vp#kuZ1i0LT1UHo^*N>o%Xdreyy4*>NmU>;f42J+`sFgEC0lSZe;8G&C(s`m zPBMp;xGj`&`QET2+mZ^ZZyQ#+p5Gwg6^?D>RW&e9FL6yf=Nu4QB-Ze1D}OHS`X^Ez zz1vDbnAkH(&M})>G30Hb3~mmu=Y3U$1XKLZGA8Z@O-0@C&aIb%_wWtGuqFKMkn zX_$QwCj|R4f!NvFO1MY@hG4srcPptpF%SI6A)Qg<(|eTor<$`*=l1@fe6y%q?#ONn6jte5RWxaJ_$p`E`$;&Y6)bB$oUX zdi4E$uxU4sXR!3XqXUmYL&yOsw{4(UXk(iwmof9QmewTilcC3>JxA9lyYok{4oN_a?QTqlMc9C%RK>GkWY8D1flF)6jCfe|Nm2m~$`8$N0eV6WE5@+X;cO z;Z%X61yjM}sW{{3^FJ*Dt_YPSSstq!km)ay)HXFap)6wOHk;y!1I_kfrB3wRy@XNa z#U-yRy$Q}W6Ws5>DJT5u#3wIli$H0t6QsTY$?6HG1_@6I=5I?L|ISqC_)M?Qrvp(9 zEiL#G_hS}!?wo|Pt#9mTl{x2bQB{_Ea^pzqMG}A+0MkOSM}C%w7whQ`Gnc!Vdfw;q z#O%1;OgRiW_&mY2_)aV+_wZ&)&H;7NO1+a6Y{$fRvERA`9f7`?y?vJK)7M&%klp}T9mBAf zz%n%mj!*FNFeOH6l1_c<)?l`D1!7Mm=CNZV{L$S3%x0AnZJFv6ZnfK^` z-oJ%~tW|s1CV#nUMDkF}*a|DxG>hzuHz6kt7S!aL1CNNdi#D%+iand;TiJU5>Bq0` zqE^OQIfio-MlZcZF!QlfgDF0j>n_(Q=nUM|iinF3csddPJ{X81*vd zM68#nYIy(MeV)!!)I6T8f13B2mg{YRlmO$nSG9lHs1>ZM_V&JfJvQ8@{osf_h6CF5 zRA~MS3nsY9-@fUx*jGdW1qW3O&s!f@43}1YdJkxN0ARUzRI8qkK6r@C#Oz~i|8tZj zRZcabc+&?n#XngSdKw&CXtzE5QmlV?@uuJ9cCs|H>4#S?!FkO1oa5_F5HxQFpFUVy z{P#A3KR=KM7AYpjHcdw$Gg7;-iRyd=`+#Ijj!*TE0mt z@2UR56ace-(&6boMMq)8`f<$-QswFwUL5euw7I6S<0Y`B1R zh%4K-hjhEfNH!z(58Kh`t5DCLQZ&btBXmmaETU$&4U_RH-)SY0(?aBY6}fk84$we% z9${|ZRO@pnfpM3dDm36!#Rgmf%4ohOYi9H~(c4I6K!*sdAqcbJnOMJjV`_S6>5na* zAbPG&3e|7si(^9MjG+U_K36mK@vI|0bOyG}WZv$H?r_sottwfl8bL>A3g#k+%{39+ zGF-S1Jc8S1Fl_al2TgyDBnlw_YPAOg6k$dyYBO|xI9bgCBjPi%r zRcLZ}5=tfI8!ZBH4&)mU|FV|YfPC5-yaTq973DYb-ppg zG*9Gus8T^DPM=?XMJ1mu)Us8>e`o6kOg?ahiZj{zgmB^p$sX+sO~ zrP!fh_3u_go=4xkqWP+S@~b;Alc68V^H*Gnj%&-k388*;DZ5WDg)GYU{Y*4KkdTWP z@x89jw6gCh8D^axOAXzK;ecWpv^bzm;jUO4s>*MKfA{QvSY-**syOj<_E)>_Yx!L7 z{3e^ltz_b@pn~v(L2sJ{ zlji0VE4vWb3k52@{p(tgCjF=82?wGR@w-h+feMt4i*-0q*`{ zuW+2u1H%#SYt}X&s9Z*m?qWbRrhZF@U#|6UWYXiN)6c?wl0)|2_dl}x1^H}Yc2+)N zrAyw?|>jt!v=lDW)V0%5)1dwvH-gA;I7KJ7@m&7_H%kBY)| znOcKD4&mqa|2i8V!h_;ZH}FD%6L~483d~{pCVcRM=PeMP67duCqa)*$8hn4f4lS5y zh~$iu5YnpINvGdxHAt?Y)aS0<`xB_|FYY%P{?#J3M)jB7w-t)i*{wU8=Zh2^spjr} zVwWbk(Zn(zm>yc#N`HZeoL{rxSxG#v-tFIf^`$neeEMPYMmj9zgdsj=*w4L?k6a~k zVTy{c?`N-u7q7m`M|tJdK_Ragck4}cVxswm-&%K3S$|f`{^*!wHza$=dBSN2#!07X zv+thawmX_&b8nvQwXCutyEqHIISF@N;&?(88jsoH1)o>H5ztr8A-xUB6Se!WV-YfUtt^a?@AcTB|2vJR8okoit|Cs; zl-4Z)hadlUfjdgaXZ^;KjGpQ>N&2NWY9_*u!O|C_Y!?z!;FE{xC7>3D7>s6FA{Cd1XlpiH%DW`-mMJZ2GlzIixpplrUCrrT2_cmFab&Zw z()p8QY|*31$F~BoWn(|gT|1Yn*oN14MC8!B$Ppt@sivF_5{7Jl`%N_Q_bPwhhk>wn zxx*}OAG_w;+e7~y>g|7rx<3zr+$r(L?81KCGWPnZ!{V9u{DbwO!6Wsiapg13N5wp+ zLJ3T{?J-Nx$g&u?pXdTYTO|bi5xsuml8OE z-uouvl$at z)J%VreZ@3|3-ZNjy!^_hxpYEPZ8wWAvi`(w3`$@1`Gx)x3ZF3|kL4hHhU@Cxe`cCO zwUjh!RTz~#zyiG3 zZlALv30Yhjt7#}&`CClBm1+L$=g?`}-Nxb4xI)MPeX&~-kzNdQtFiqa$exp;4S)Uy zulJ(Yio6(1Qxx^ooqF@ozk}CwzS7O=yjHH%<%y|t7PpYCCI>8h1LgZ<4SQjxQ$LflUQaeJ zD-^$WV$@S)|6HK4YuWL7CO@(Bft-rAV69=F&r89A44I=`|7Wl34Sr8clU&zbKkvRx zdE$E(Zo!cTlc{kBYB69Qf^5uv;cWAV>`{H8aI%--WL;{EfrW|Th-m-yX15iuRp8^n z4Cg-`f_^X8hl+@4D3{G&?&#{+I@Ql~2iv4fz4~r6clt#AzOTUG%I$sME&4%|+@o-8 zQBaShhbfJLIoaW(F8;4;#t`d&O8Nn^zM5UjM zi;1a6CUOq_Ko+_&-ytSE@m9+sCdTjn8JHVX(OS}M>2h>o8-@Jn#Ab%os#fx4Q7XQr zpkL(hcfE9pQrV;UQt{e5MqDiVDMA~p)>Su`bx2&`jonx&cr9!VbWV;B|H0 z%0-~@eg5&+W-mwnYAt_a8ZuLq?iE|p*b8YKsdsu|qDOCSm^m6<=&t!ft+!9r=rLRB zscO}V`zfr5jTLl|DzEBAuVkul3aQ!$QF>&i#hN?Ul*kaqX6*!*$E3@X$BmMCZ20aM z{$I6&AdFg(S0GCE9ia^OCRmsM4Iws6wuocz6^7zTNvm-x_bpYhL18M-q*=yj4w>3sK^=3FSsS)#Gg{7x;j^gZ=CObQYtVj2ej;Ys2bMQ3$ez$!?%FCtE|S zCrpZ8TT@TK08BoCfAV2eg6h0VOc5P!cbOv4{GV!)?0#hNnvZV#axd5?bd^quMb9y2 zRveAoOSSYb$NK)3BXPq1okBX4XvswkpSOinNgPN-yvSTwT5kQh(5vrcyGgjNYGQrr zmlsS1Z*;$y5Q)pVQ|pgsWrfw38kXpTsQ`2%Kyx6U!mXP?>nD`SM_?~YE6i#dukxs(2K9$kF2Bj61xRk%W$XmOJoJgds(mAPy))5#tyIy~< zNnj?r&E*0N`~~uWnPMV*{POj*Nh6aw`-DwT(tEm-3g(B(L6vHKSTyX?{x97<3&VY3 zKXYoHT}j2rd%)ckmy}y>cFuIHryN#Pj(~qmB_UU>7b~O{*uuX~h*uBbpm0l7Y@n== zY$n^4MCbhedd9pZq@E|Hvc<cephC5K{;BX3H zI5{%~Q=)Uf$GYtGya49u-JT508_h0AC!nRnG=!;B`TR7ab*wnnTn3C-jV0rvh= z?utVZ`wZ)IY>2>lP-sBZ+VS7?p~aBBCH%r}7g}^@b(Yra$mKWsCQtYpvb7PHzqs3b zl|S%C>L{-6Ci;OzoIN7N+VGLL_pTlF{HBw}rr+vd>ZlRSnSgi-at^Fs1~T%P{kCJA zI)?kxtpA>WS?l1!q|40O5RJ=M!wmn2p=8&iumwC0Mvuui@6z=X_ydRM`Z*GUtLCCw z&SyzxvV6MK)Yb(igPac`JRjehnk3~UL9PkTqR&A28kcYKW**8*^`hOn@`F+OG|&Bj9Wy0RW9w`Qz?1CA|4txABTWn2&`F7b}sRA3=Y9r}>tUk6=Ix zmUkbc`e~i#tVM)s#QmH+rM!~oueN3-VH}cwn*|Wjk_BWY6~XUYB_s7B$j%PXXv0E= z+ma#Iy135?#BuQ=E%9Slpf?FBWLVrgvkpBg<6`ylBm@Yq$1W}|U}Zf9$W9j1Pc0r- zeqJ>I9s~mZcTY7cB8cFy&K&*^GXxpDWTmmEynK{jRGt#dbveG1IKC-@ZtKv z;m)7%I_L=+THpO@^d<>Beeo|PW6?+>OY?`9`)oFkuxqy}yQ!z$$p$4eN`5O8ZsfE2xCnJIE)p z-cj^-GG@j3MCan256jqCX~B;(E_6!JCqKXuu!KUoO38LMadWx!+IU%4IL2Vs&ScKe zc8ln+riN_4OiANqTeImYD(KZGb~FvYqEDR0yMBT^sny@R=sSTbCa@!dw7i|y#$Qc5 z=67A{cet4qqNG=*-hN@%d)1zT3qCqv{JwLLpn>8e2@zw@;v|)$0vo=xK_G}~j7i~C zZGxQJESdfU5+oCi}lUS+CFN`;GJn|yV`Pp{pjQZ znP&fHP07V54a=@N7i%=5Q@7h>o@406RwF-=2^}TVzP-WUM}Dh+Ph%GlR_i##MhUt@-`hwN>`}QZx7qps>20PcU1Y9O^xN5XgJrO0OCNA1yx5z&b+Bta7;aIrl z>3u&n-P|6h9m5j?=og*CvrY{Bg-gP*&BF}ueA-W{Z7KKtG`n}i?Dvnc@b&nHVjIj> zKk-7FNKO{gx>DPr06~7s`N_eAr&@B8eTik&nogx#Z%Pkq5iGPXv^h)GRef28FS6yxvzNCWG`LEWX0;KM=ejXx6h9Ovb-aUv(kL< z=;($D4Lp6kgd(Yow_RdtQd*12C%0&;1P?Ml#bNTJ_n)#Mgz*FPiQdv#8wzI)K1I1# z`(>b4&E0x6`Yj)%DmG>uzV!_tusYgT<6b=E_=EQ9g+=8PXefNgPl=8gCHF3DI%>F4 z0Y=xz*8yr8jPXteXO68?s5=S&F6mbz+6Z=)glBoYK=prqk;6mb^}fnHYIhe+D-x(z zE%>edmr)P)L6F90tgfD6GP-9oQRc^Y0=_=Y407FFvW)oDlckmSIdq?ioYFPO(6c-$ z;atd|DA$Tmi>R%A8e3mmK(3X-vuv3|kyhI)+*43>ivTumAW$JhbUen{f!+AyC3{;t zGu5L&ukQ3DmS%N0>&yDl-OHbUH^j&_ae7LI#~8k3b!Vw8yt=)`+SI5_KVidgNFa48 z3bmkIZ~|)eWNW*U3H{UrA9{KJSdE~+;co+R)Jpy0>&CZj*wPN4-wSkmvEKJK>0zui zDz)_>Pz{IFV}sx%Tt&w@8`s^aIo^imp> ze`@N*Pxqzf`d1zHNBeGrPm(uve``SUVQS}z;ZmKTk2LjUp-uvYUfs2^Pis5RRAnmY zG4Fkip6MNo%Ivp+{0=u5@X5PTiFn?a*&oes!l+Q~mwijBj$4HjAM9M&!n)&(uvq|V z@eF47%<373tofsnIClrPiBkh3%Hqz;_LfJHY=N+8b*r5c@u3B&8@<2ovl8u#+wa4q z|8Rt6IB1Qls_YyRabh&udo>&QYe>k&U=zDH@2{sPdtHBdsn{1ebsLZC-DEgeToA^MekRNCRK&u}h!2 z(O}A9c3DB!Hm;|u;6a#rz1nluNHSVos$Vfm*LA2P$+UHo#NIu75Tr`1_I`SGYw~jH zYeaRfKS^8=yV}E}A7rE4t(^gm-%lB57oJtO_jvYfIp`CSV~#*?L1>j|eQCK|*c0t^ zQtw!CuULul77*`(9;GC-NI%eKz4+PH0NJ62BTFx7`bW)b3mspE)j0C@6 zjD2c@7tU}g?I-@!c_9;wlCIn9Gz$FnlG7uMN&|G4qocVJ&dR6HHF~finQScd-J3rK z%a7oeW1{yjUmqBvR_86aWAXwg;?#ajy*wH$RS z_}0YM35@3onQKf%7_)l%9S{|jT7<)E`GKX#@1l(EdUbLyu6We7MVwQ$PomJ0&^66* zbblidXhePAdy2**i2S-q)v2l@HA)3^rp{01Z0#_S%7p;iAX`*wY(X{uJtJkiGvwB; z6544)MFzRt3bf)=m+qFYaI#l^(ul?n<>`fm5ukg5TKMD^xQn2ha}Xoec`1wv3&Y1i z{yKIy!@m$_eac3EPQPe4nq?)U)P-wtrUf|&Lbg;!b;kPvfCgR}#Rq8VZg#{SM{}tC z-3f+Tx?fya-6@q+mlmE;?XxxP0x&hsk-@pB5vg$-i*d9%14cPu`#~{VT#Nu=u&K$q z$qd|Xy8c7EHvL$2GN1*l&cLjfDQ7nNKMRLYtmZ4=sX#y#!d;M>(;jY|+CoW1Z!IyI z`|tAZwb-=iH3=qT&qYMeraL4`<$Gp-6ytsBA79BOKtk}OP0UF!G*_kN$`fH~zEzQ> z$EepPbIT`Dj+k}b221}8aop8Fad1jkCPijA#cYC>Em=68<1{?!5k#i#K}BPCD$Ors zm=UZ84UBb+l`ZJDOSxLy;#>9X zMsqh!l71!#@WptWUg~(~Q$MqdzTQ121RB;c=#2uaqTZ+|ESq!^=R{oE2ZNy6fh20Y zEkS}G>EHCj5rkWa?oJ7uq$w#W=*>gaV3x0sj~#ha{$1X1GArG5QH1v!ufVS1TFXr=o#|h&=OscMwW~l@RM51ZuvR+ zWr+KwN7=l6=7)qQfb_8^+wH8O*+qR6%!RRaAl|+;r9&KhL!7*uK!&QTlS~_YwLElI8CAkH4vEn%awH-t?SB-}S9A<|yCwMpFKdKZzxe zXB{jzBWvU6EBxmp!P>`u;(w~VpyZqb-XH5GvpQaG%tL4|eBrN8#@?YL^9nfJ2?peU zt=)L_QrryW6&je`X*wV*R3^d~rKOd>WVvm?K>W8u%riLVdfz-!nJYlo_B(&h&2PEY z8hzMJbC^B$215MNA=b;WgSU?}rNe*D-qP%U9KT=RP@l5hl%#Lz*-gOwAGW?boa^@e z86W?=4$K$S5N_*;yfEuZ)lRoFDhy_xt>Q&vP92 zasN^M!F9c_>pIWZ`5IpIN>NOJ*Z|M(S|4!HT)pAD501!e0Nla$$#Lbhr-E0L&slP6 zeb8C*{?f?t=+BQr7!7Zy9w^Wl>NwR26sZX|W2maX;2JISY#x?Yci_^lwR3c+WN#~- zO(gpheimn?cG!2XSZy^kfz&WIpGTI~h3Qp>K>Vn%I-ie?EtzJl%8Nw8D@G5B(b%cQ zKQX_=Xpdzrrc-$N{Mxk~R{5?pk_*v#eZ3HXVu0wte29=0o_Z0{gnwb#14@`!-s}d( z3ZT%69ii9u9qJEFHkTa~s5;E!S|`8p2xt;fHTd1J4Y!S^fvRy|&erj`j_w>x+A0=Xwi?fPJ-D(ca!X!}dfpy~4I# zxJ;H7##?Y|X%oM&cd#ZPpW{h@Nj!A1;W9n)#%Jr>n^&8f z+kpe84qmuYFz>vaqjBt7TBtD10v}fP1!qfwY7AaZ7JNfvv*Yq{<<3jywR9Qs-ym|1 zc(CLabh9Z<`+mf8HRWVG_bl$oE>M=~CtDz8ksL}*O{2F0X9=U` zi_eL!C7NuVwtA#4SrP3%J=pD=E2PpcN;0uI;OH-Z5!!uiOmpZh8xOYIi8)$&BZ5md zY3R)IPN%0cug~}kr-lhlqTOcY2?%t)U&SL16KBK|RK{O;4F}FDeL-+zxPkb_*-j(8yqI zkiW+oO+Z1CTrx(2KwO{KYUXM)YLh7Ap2q?9L(U&F_?8P5&9Z}&+=W>qU{lv~|$ zvkcXIxIOjrcU@xndmX|k%ZE8vf2bHzMWji)J3GtPOjvPU=8EgCer6wYZ7+a8_RFR$ zFj3{Bz+7r#gYvkzhPmaS0)Wx*`FK#%?g-n2cZUl+Iu+>?c$_f5qq)0lD21t@y6`w*Dt z$ct)pwaVMt+x=*Q&C{UGrc%t(!17@f6O^GyEV*CJ4iFtr0L}9pQWbs>ZPP-g4&Itps!@{_9T5f+gK&*Ab$n{@17E`ZClrpnDEj2zi#-u1ec-0dIOen{GAQy<*c z_70~xMXhOUnLgtv(K&nV-FdInCdH4lWjH_oP1miYG?;0h6WRnW&DG?kv2E0hpM7*l z%!N*a{B?NyT=1@Wu~n1gsd?Q^#p((0Jjsf&s2>7|7u1Z;6RV%QyQaY#vKpQJ&l}R1 zlKz7k^F+9|CMM>f|6Gp^QL}Y2!w|~oaIc<Yu{DgVp~K%K}$!uUlHCPo4_@sfSr# zUM5=%ANKy2raaPKV;^)ZfycM>1u!*Vaqy~;)wiM0>rty0MtqGWze!J4d_@ZTRv+C4 zRRg21i{V8wwzdG2-~VmoW8T9N%ma0*X0+r1XNuj(bnmiC>b#E^l_=7Cf~7;7e;b`gGR%mL?- z;*-XD&8A(6-+TxR=^M@XdGXu#9+3>zkS0tK)KjTID`d?;b5o-`(9cM&BVuayee*fS6laj?2(fU3_mp{g@Uv9xj>#I5U<=TrfsYR zuvS}|>Nq+80&An^OMEvLMC5zKs%93N1!PI2fy;ftrJ;ISA2K-GWO?dHdX6|qu{gn! zK37LRE!#)`u4ROBASFzgf2u0>SF%f;qveo@6A-*MI;LodUAi@Wxu%{ik>Qha4{g*x zLaep36(X{ld{*(^CgX13EBcFq#>HrEeUU$s4L&j4yZ*!fTiVZD@77`(m836@$fa2l zg;^|Ap;%~eK*Q#vlkeU1cX1Wv_C^+Q7%b7)&lBw++db^In|<&a<1F#J#;?~pxM4Xj z1buU0iM{?gn6Ij7hIx?_KLy`5Wm{R^>Yr9!<=W4%()_(ottU@z(;=zQ*0}aC!*pgb zOR=xz=~#HbxOC@}HWT+b6o(Y(;uEu24P-DQC!uN z2p_-pjenZT`}@RmXHT#9xx71ahFU+ygQ^2v+{b=nAY`Lb5IZLO#6V5d__^R@;s^OI zuFV1GG!^&{Q>p8!4}PF>7Y9g~xan_E8)e~zkiOVVV(Nc&nC+24a!{}58k8-3SN`C3 z`$Mnhhv%1WEoa7LZEE4Ig?wv)@lZT|4SR0B#gJ2g?qu@`M`6#^-P+a`zzu<}*3E;Q zWPJhE`6mOUh)FMipee*KXyxEKgh-h_(z`F%CbciHJ<)EH20*%}=(p-}v4B2Dqg8|Z{oDK_^zt%Mz$dT||>_2D{e?%U(txJ97(1Bhq zBKu@q)H_E-!S6e3P7s=OB`ejl&^PLjM{E|my76|RLFIN4J1bK&0W2DLHIcNtj#9Y_O{{Ip z!(TM8J{cE|gHT1i?En?RS5YD_v#OcA^Q|vefvw#UPCH>7YRJF+uDZWJ>c{AL(8lBD z;d5+$3%$9K8kXqzQC*-l$wOv)p8B7S!?m&K;i!1;HTM*PIV3;%E@K`)+*0`6&V@i? zq|VXNBn3^=f5$jseA17>=pd`-{%BWc}3Tdc+LX zrri^VtbdHJwzy-dy}Vb#u5^PN2x{%|P9(kd%5ov}uMvg|k-HgC!DoN^sWd;d4 zJ$sO?_}IyTUOI`^^A+t4{GUEVtiV*`+TO4*>k@jPZ(NvMcq?h>5EX&gYZv&S#uXK# z?HIs*?!7;~_A!#V|NHTzh}IekYE*)2oNlh0OtE!Bc6m8>G|eCH)knDl-ETYH+;a7% zG^eVjk~*1MFf3neh>4&x5OsDnaI_3J@jTWri@Hz8>))|$uk@;dl<2h%sagTnS1f(; zo6Lj~1paa{Yx~}tG2S6}@sprZ1@qrN0We>h*^JJ8zFM~HBAiOA5Z%n3)(^3=K!tyH zcW$+`sU3-+gQj|k@6m2>*=D?raXA1CM&xM1XX{xc&vs{RWk)kZ)hYGT=WdDHgk1Ly z&=632@p6JAyKCduC;V5=Jz~n%&Vc~ayx@h}4mm;RuC@;ww%9Z7K}l5}T;p2Zqd?AY z?I7f-v$NBXe<_rkf9Y#QQOex|oqk-J@Qz&#FazwE-*yqklwjLaec^s*wRSn$o9$AP zOvI>e4WCzH!g0TyPo9%q0q@=}F5v)UNO1zSnrC0uBvAX|&@wNcWVi@p7> z%Rg%^U7DtBdfR|7rjR%FFzR^?{;4r zV4{FF1CXi<8SJEWxa?}a76oZ*e!d^hoRIPgxW0Ivhs!m#dZ=cwG|4!IefxC1k4*04 zxc;%268>Vmn2JQp(pDHEe0&oh#7RsKk>2;Zm=4j_zmhHc-%lgf5XtsuhlfC>lgt|w zw*;#$kdJO`ryhvVgf9ipNxLE!#Rb3B3LF;gH>o>(`23!|p$zRq4VNllTyTl#PcYM&ADL-h?nofW1Xl12#* zn5q+w91LeCJNG@<2hvAZZ5PBwMT+$KG-FIGw#2#bx{6{*M{{yy24@O%e$x z#~YivEobF+tQ{vUL^z_y;teKVX{RpR!u@)D9(UTUqvYVzg@X3NYBv0Um9iM9=xKg8sr>%qQjW2YhQDYPT^ffYfvQ39eNDPHvMw}C5_YCR?i`%p zYzap43y!4RWB_m^HE41B_v5`A*Mx4kBV$|taj3CsyTg^}3a3$Wehq@cis{6XdI4bv z1W1)+-7!=7SFN`-3q=qX(rAUBN^}R`4%IfOk`A-`3Yy+5uXcVfY0DZP`lsio8wi}5 zRN6(6O@chqH|))v>>8!5e@F+j6?w?H?};QYtLERLoK`ihqCBnF%30}CNx>GRo)wHf z>W9Kd;|Cpr!ueEI;~@UY7R9~OE9}>O)Z`iq4>0uB_5MVO{vx#P{w#Q~h;*0qG0mORnt+fr=9 z_>VUv-)boUS?ph3W;psbsQ1Ilj^UbGDjN~q%tj%UqEet@;9_Z<-hFv@dk^!d z$Kb^C>q_3iI*J);)$F+{sDuO|%(l!Kw)wXuF023gjjIvaVuv5QS>a)EH>?xMra1lx z7j?n|aFvF+{7%NT0k{mfDa@CE3-3|`O)3t>tL*FJBvGBp~qdIlf1S|)i&F@|bcM11H?|c3J^mv^HbF-p``Q{Sz7M!;tD$=tR zb0rltJ1At-A{CUFn7hb-Ka9xYidbN_sNBjtAb6C(yErpijxbJZ_kUdc2=n!U_}eIQ4nq0#veOWqCbMrd1fLR z)aAg@NMVa7A5JjN^$v)cI6kK8O8<=Bb)}0mzc!HO9L@fOW_K84B=57^V`kg?kr_OCqWC zn6%s-^ygI3;4|}C2k5o#3xK(EOu7v8%x|BNQUrtNdo(GX{Z?DZalsU&BsT{)H=JfrBG8^4?g`_Fj@~nT#|&t= zW1q7i^=9$`6eejc-3@}U+VIgduN~BW2^`z6C(AlW*?#!=tZ}PxQ^n?X`-fX+6*t*J zGE>;R<9t7=tz=<&<_ztU%u~j^E_s6Ama|EmnbLujtjoI^8ltlnG* zJccUE#;$^*oNplt!wD#_H2l?`v}S5x-SEHtnht$|8IkuES^R)O$+{E3v4E?)2m@_3 z!j!8&U~$`Jn9&1cJNl;eLeDRW|xS~ z9B}lFQVXg*+B1C<^hD!+J`q}MdTdK@PSjg99x75C>2x&-_=D+QZUU-zYCP-(SqoQC zGnBA2-sXCxNL0sEv;|AEJXr`z{;GL{YzJ%;(lf5r7*$7NBumZcK)1v z`7mp-wfp8qsR&(JsoZ%Pb??20xqc#lZePYj4|H{s@Oi8hSUhj^5OFIgZF<`23QQEUFT>{I<5zomk?WRv=-ipRGA=UHzpiL>{DA0zOyZntsyA?x^a z5L_-hzz`9bY$%(}?sV2d)){9?W6nK%&)FGvo<^yok#b`xUB@)!!BQF^ztuIfU2-VP zQ*-hr%?2GIbu}TN$&BJGN-ifx(A28wNqNA+5#{6pEqOQL;Fh*OI|e#Th&uVXnr0hL zuCd1vuOk2W!RPCd8!EL|v=^AK4R4Ouap2KMZ^b>xI&w_bL6_ao>gm2y@?MM)i~5cc zkykH&JmGu%j}tEq8kZVQ%z0|)zER(pZ89QL!qNb4GE#T*ZBQdUnS9)Q|IJk^p=C zt1@-2aL!bj*k;s^>mJq?YcL4CLHzyh0@9@O@+Fv20GgeYl*D3B<&NJCwN&Wr)4LQf z8anp80{N{QO{K^J(|yai16fJU3!vz(jucoIg9l&5&HCM-LzzRH%MW^gA_8%kjw6qH zEvHO3PtV+*CGRMEkNi>c(5CH7&!;>4`Lzr~L+_;~rwscgInHnH2Pfi$E0q4E9_>qi z?x^AnpjHqk#15%7#FLvdB;ykh(~IL33ba4|v|c41BOWaMai!0i#6r|zjCPvs>Y8i)KN;pUSzSdl=ofZ$(kXp zMX^}n*JmX;X;H+-AGZZM0BeGDBrvJ(6OhVYC--WYkT=qhlMPRJ-L&}Tmp6kNbr0{a ziWA1`X#@+g^dp|HTR6h9n&uq;jJDP(5|Ud#PJ5~UgsY#e&$}P1H%W?+Jv4_&MTK8B zwf|$Emn>bF5o=FoaNosO_%5lqC-)$#qxJz?HWud2i>gmm1T54^gAaX|5~G4>`EG>)rg3QlZ(R%+~*= zj2!R6pI`oPSH0jpes;6w@vTjVOhn2YRYejVl&l*sCr_#1hK4&02?e)+4KRp|;P(ab z3o=6nPjYeBm7_BdM)|5?Zx6emrnG*Ghwdv7mBtXPf|W~_Bgb)X#l1H_3#E>PRk=EIkBMZK8cSq zU5=b1?)Z@Kk)wmA*F3#_1!Vx0m)dBaKK)yDQOfL%%m*?ts@FcWv%Rct{)nSpqFUYD zCh}seEyl8EpTg9;(eFO$Yr$LR22X8lLB~vby_%ivbNu6g7(uioLb+FwL>NKX5w|5C zY|YI}rU}9~aB`9ir4~Gxc#=S^myh}|;|$;LuF3PdZg8K5HU-IH2bX6+6W~&-xan@E zw6@f~M70anz@#RL*t+mf!d-;eNcNnyZdq1u;P`~mME^$B^*rKzo=y(4s6{2xqZ0fQc#7MqUlXlcBi)?S+f2Gnj!XhcQQ~eVkS4U5X*7k` z%Olg|Y&O!ZXF;J=^Dy`u?cfk0XI!_I@V)li5L=8KgI-vStx@->kLc4_NhfWujiv3+L4-X@vRS)N$cI}YtYUuc|CywP>NefdxA)SVeW zp8Wj46(w<5EHnmI;>XZhb?nC`lup9C*0o zHAs@`4LM;*zgA>mr&i5JR~2|g(yB%@i}gX~1L~=5q5snI0RN*>FvY$|Tge*)6KW{^ zpnT3`P2K-E1swxxuPX@MYkW^27Wg3~1F=b~3e&Uf?=DoE05#zvxD(~W#4m0emVnQ} zrkW}C8AM9&y=4vi8+V;0Nbg`bE%G11El-OuIWrs^<8YhBZsNwy+qW4f6Cu0BWYX!1 z(9;?g7#*%5CnYMt4|ox*5f{BRV@GkS*VpAeXIOK7mBU@U{{cetsA-%1h&IUKTAYyG zqaEIJo1!V^k9q@l)CJud-sFS};53<$oh2T$iEVRDoF`SK4BjL5iae8Td~jxNS3lQq zLd~~N?cH^bOX(acVM}%P+Gs08P}eZ)+t-Z{gp*xB(1+6ju%w4HGPRX2Ug@WMQ|iCe zJGOxy0He<6%tZ80!xjrEeW~Hk`iNn4R&@gzzzF6#pgVw~zOWETF#blrQ;;8mJ?`H^ zS@u~mR8fFIwsd5q%!Ui#H$vy3eyOm~!epOz)y|tsK{7sbt_5>epDLb!)Jeq%Qx&J2 zRAJpUP9G&$5+#gJVnvI;BAOd18u$*TLsKJL+ z1i`TY!GQ8-ZZ0e>_9Bg^PU5rG#jK|SA8?jeu>F4eOYgl4tv5EBc{LK_Y>lxBxOyw$r2TW2sk*vqy=(os!jGP zEAMPN?0ZPrr#|aj2d8N-udu3jfAKZJlrZN$fJgdS{&T$j|I=d*=&EaKuCBONF#PF% zB6cr5A$jXp$_^)5Nzw6q1{sZ`PW>-R%n$Dg%Ih~?qEZiKdd5nA^ekgOIB}7>4wv?g zODYu6oZLyc4&|)@`Z2+`#eKQy$p~zNI8{pug?`7%1V7m!t(zQ)JaG0oYMqZ@)ow8h z)=kdh#eFKAgC)U(oTI9+yBQ}uc|_UE8&Yn2Z4MuOz?!IAU2NZw_hHkW`=BxDFacSL zYijfoB8%7%eviRS+m}c=6@0lcQH4w0XXN=(Ki}2vCBa46ELA-{jPL>2S^S#lC~7D~ zyp`QzC5V6f>+E4Ue3$uoiJwy^>;5n?mwioUly47bIY|)z%aAcVxjzw7SD_Bqx;$*~ zalIYqe!8(lEQ1bDO?JdRhA@e0bZdfs~q#q>jkMw+YXq(Vu&zGtkJd!vPVw=ngv@QePZF-fle z!JkgDF7Hg&(UWFhj?vWg324376yhG7AI}>P2VA_J9LhI<5~8D{n_l)I2{4hS9i58m5{Pn@*o(t{<%m`#x^Qv z+fBH6b1Yd1PwQavlETg0$6t=nRDRpNx%DoeU9ui0>n;V>;iY2ynvZaIHodP_azzf7vTAf`wUMyX-6sqp2p+OM5`T-A`*q-2K7-!^ zRT#G{$zLu&VaJ&G3WEMF-vIn>tNzfGLsbd_NL}p|XedrJC@_(D&i}9Lg&pm&%Cow2 zSrFox?oyx%8+V*wV(U4bAJY%n)ga^|Y|f`EDA52JquWyC3^6==c_gEvLIqA~$AjvEHbRTVRX`2} zBmwALU?te+6TCRBiZ@qs@E|Jz*9F7x&xmHqF*`KZ z;79B71|e&#sMDva>Z|*h&Qx4J?m=Koecfe0#uyww$pjQPVgTTtx(5Ha*}!`44^lzU z9XB)p01Re>z!n6nlc--=*w2wgg8j2TK43dB$=_}VXE*q~0T1#J^*)M~>-TA=XJfFs zwg)Y@FwLmaiX;mq>y;Z4Z6a6zRAPP(Zc_-3)*F3^X5s9K>8na#uEwuztf^YRra9GS z%~nQIoAS-;IKW@`wzFDB41)@{OaOm5JgNknUhVXAPID)XWw)^Q?8siQJ$*y0r_8Ey zIp?knM*YIL$LHtg+{aS`P{@J1R2f9K%)Q}S-Vbb``6EuN{*;>+@0+SzEarjOnI;8k zZoY#G3mMf*F_*B(={}hE*x7v-OabCK%XsOi<;;~0gp%k|vKZuqUC^af6rgPYzR(w> z1K`eaG;AXGe>SldoMF({)2o7g-8)rnjx$dxbuby~U5?y%Yks4|T1rtS<*;v|l#SQxuLepYQ4DwlE5{G5U-ml#d;y{NU<>~2E(7S> z&d`6J9v^sl!?+9xXa7zJWbfLp_x64brDQHNqo+1WSgDq!6#o>=a_v zA1P*##;UPW6?898+$&hl3>Hri6qlgpU@hud5 z0XR@=wNuZpINBhLWzd>Lisd20tNC^KC6@&d`VPV~Fa95Yq z?`dqe9ZQEzlAIjG6(Iki@?^*sGzjaiIkHPq;^ES+0IPv0r< zsNF&LFG8Vb8~CtIjFQB*;Ob5c9>_6+QP}$Gt1%8^$@X$3eCZJ>-xB zjSHv*?*>s8+Uv!b`_jLxJL&jyEW=p4lSAvx=1V#!aY8fRhZD@p^r`@eiHT*0eW(%85MXDGU@tvigBYdPD!4mZ zY{^(@mKzP-2NT}H=nrd7GQ=!H|1SjU_9X^ebhV7O%ovGGba}UY)_vPd<>Yqx*d+nb zR{}aq)d3zJAORAlQP&)1T*cpq5me+v%82eNFO7&i5k$Md+}QCa0ydF>0a|kKY=pcI zP6lKiJ%oZ#(bB3T`3{qwELGnLmsalDKdV~;{MEGT#W*A(tmeV`#mWHFW6uV&d-}blMW&@ zF?T1YMe4rP&Ft|ssC1T=mOz%8m<#vU2qQAd`JdT{JRX2LVF=vibO2@HM+rr21n#3>URE&d-s zQgI}|bls&Op`St>X&4Vjci~$D10s0H;N_~)ja)*^*7=Fh^uNin?df0I)rv^#HM?*q z%mLRsia{ZJ+SGRWDJ(WaF9d+!;mG>#^Zx+-IXDX`WbP&&dwHN%QwHV%0iF{pdM@_j)pFl-edlmcIf!E^@pWX}|@z`Nf_0+T; ztBwY>kPD7GaC?6G5w-{|ip+FCPQ*welRUqG0J128*-_I>ULiZ^is2An)IQaJpUt#j zq){`-52%HOZOjjyD>q~K+J&2x5dE3W{`t4XyRI~LZy9}Df811xbsQ+6YB&ZS{vsY) z|9?0rhg1qXYCnRtn5D!eRT%aXX!7vpffUUN(@ zE0%akx6N7!E|}Wl8#p*D;HXhy@OYrPCfh3eZ0WeDANr32?FSBJ+ zC5^Ta zf)}#K=^LG^3a@xsi5VJ&j-|g#Eq=jVI`YiO$3XbIlPtX9w5a!Gkc`554^G;s*E2YR za+uU42-<72-}sk1cZm^GEUiEc7Eo}Or~ttujQL?>4lqQ=U3?)z@FI+2G7_eNR1Xwg zmK5a`7pgVq9!&9X)}=T0>j*bC`w*-@Z!!$u`g}H6y8M!)qUA?aas6V^ALCJ_6=*4Xyxqz0T8`?okMtW;zi%&{cJUp(ha*xq>m%skQl zvth2#$vQ9E`jY65CVaM@lP2;OeH$q*E>Hxb7|}3>3+)Y|LzL&3q$tY z)~NxwS?c`HRq4}C-N+@?fJJ{K^sH{lx&tAm_tg2$w|75ZoSOH)5zo)sQM52Rn>POC z%t}W>wvX!be{o^x%Svx({VGCH(ZZU-@q5o=9wNzo`Oz@(^LHef)4^Qv+ARwr}n=C5jd(f-~2O<3WFR#%!K zV;QCl!l^9b*A`$f0`Pdk-8uVR6kWojoRFR4)y(Atj_#d=Qesp+2Gh&czwGg;`*)=d zzv*+K$-v4sW_RW)i~dZV)}|s6VAsnCDN6Oox)O_1rjS(*1f-S<-b5>MqlZ6y}$uGV3VFX0zTKRh& zOM_YR3SGO&P*8rqdzw$|ahn|arjLz{K>2U_BqA2lFR&CI9=_}#2rE@hyyG#7Y+t+n zUg1K`$j;|kv29<~fVJtP##&Sf#;=ye6Tf^43scXpsQp6#=@VKoqu41u(W9=stM6tlxyFM=$Pnok<)bFVa(dc+Uor1Jqg-5Fih@II0;G;HWp<(5hodT9q7?BRC@OU1vmp`EEdxD=o0Sb~_7 z9`DP@t0X3D2vA$krX$=AroQ?B7RI_}-C2UM^}tO8=KeyWwUodjGGfr!BoRUIcY zjzE-=<&Zjql&DSaho?apLr!Gb8^v}x0`XXN0mbr(Day!6TOHNL;1WKDVxjZ&F`{?& z8Zqf)*W_YNmQ`7$b4YOLqe3+77}!*A__W{&oMBWnid$VXi1EIB7ys-3rraKj{Dc6p|oM8(rALbWIr?Hqk{8_v)NOz8~-~ z?+|9F2%=DrVC&SB2-^tdSB*e*2=@0q`&xwtVT-dJMh9K%>sOE(FOuj*uU2(|Mv?G0 z|B!Y50mq{Len@FS{}za!4ri_{Tz$ycih1Gl@rB&aJ`5O9ufRX?fF|eaj%ONGQ z;asnMK0oV>`r|Sjs%TWi=8%#S}^v^;KD<&1Bl9eNOG*> zV`F};*K7m|@^em^4PlXeDA#);lxQ7(Rx+ichF;Ya$K17d1@5QA(u$r{tN`a zfVG&s1=&DnCy=CmW?A;b9l9Cs{RGHJ;JN!02-`4=a-IbHzL?i^ukta)@r;|!ol}W* zvoc9i@aP^y>P2sfF2pD3)Ri3MyizV7{<%vF(a!r3kSy~_(X3w4YtI2_7R4}!%?nSgU0^0#&g{_$h0MtrP=#nH{)LQo?~HBQ&Rk>e zs%Y57J?$5mPm%?%Lz5q`N`lg>tW!W6Rkf`j__A+PnPe>d=Du&k569;J-ePCu*D&(`O#ocyg_hNKy z6r@bQTP(p%-`uwNC&<^v@HKR3wn^0X5|!A}q8?>CXwPSH68?K^3;IPp{cv-O}m*+zsM! z=VFeWAFu8+cFk1%EJo@VM=(BcwQdRx+L*k3K6Mgm-?;2huh{aKZCHsM%Qs!0h3oP- zq5>%6hTqM-vvtycHA*2m{ASPU)(G#TF9225x1}&bp^cv~Mvk+G14A5LH3U7w`L@WN zqN<`%q-Gf~8!$qFAM--)-5@zUzfF}~aTD%K{v~LWV9-X@0TdgMi32cRaWgG>_voXY zGyclv2CtZ~TK#kmT6sR5#MLG`m(!+9_d7Azs+}mLxmEKbdUVyT#r=^U0UCNeYo%D; zd*10$sA|@$<^KHHI`d>R3?-jU6~A7CSvyUmxN}(9sJCw~v&QveR_ff}vzC9hu526u z)m$8dd+~Q%{CrdU1Hf=;UVVo>pE@Z>m3WRjxgruzE^>r+=Lp9g;Xb)vcXqn19Y5IA zMs*s36Z+!Xo_ok8J&E$dI7v~FGm!?9MkTU{sXF&Z+GpW$iw()hB)_edVGh_TcsGkc z8PMMk6$Zj%8Yk!MWDQa7(I?;yshcAf3$D}c<6i=^FE=#-9Xhc2-`Ug&9>tQ|ol73) zw%Th#zmg6t=9ZGa*3f?Tdg?j<40GdVqvZ@+)8?2rchG&!5$6 z0vOs4RJs^3{ku^&$_qa(Ph*Ke*8dASBgM>Q{KeM&!G1Kf9&+$Y%GvD z@0u6doa3_7q({@YbQ)&K7}Bi@43B$vnDPmUpY*FN235*6O7X^xwI_rPZEu^t{*G$) zhuQj0X=(juk~#gjQ`u-LO=?5h-27U@j_wYToSaIL^~dgSgP%wnbk6POg_ug8qA>H zor_?X4e1U1>e=r%m>d_^ZJK0k{1$W*+!Ud@l>kV>t8~0uxx}*l7Xp8B8?3Uwfz87p z(o?;*cI!9^D)`%f0aN9tGoMPTM4$0#5=)jMJ<{6y&vj<&ZQJ<<_IvGS_Uw55HsT2N zOIOaMseR-;8Na@B32avsA2#0I*#2fw`5*jyRvKaa=0{2TSGwR;$5#?>m|F=I<^37I zQ4E-kvTSN1mZSy=Jv=>u{R|48C?+^1FtxqN4BLG92b45`5kcJ!;2`jnpmB`u%oaHp z9xmBg>N*g}Pbyb_^bUg7n}GED@k>+b#K{x>gBDc77m+W5r+RGTnlP!;k6E7JzU5z= zXv#XwJFg7$x~7M_VH8rdG`8#gdCEg_Z=;D}Jd;MxADf*9j-JCNIm)=fY1x7rg)ez* z*g$mYKo(co()okEz;pkJ$Llxb*d2IUlh3ZW9bWDnl`AjuHl)7{}6E9`3$kA)oW)6dPX8scP<^!bn7e#Ik2BQ7CD zZ0ODPy~aMmMr9R)9WIjad#}|3bWE|bjp>+)3s@a{1m8CM@AW?EugqA+0zFP>p$!$= zv2Xmvwgk58c3%VyU5x*tnK}nI*}Zd52rwOYrx+O04w2j8=#wA#rnDnA=)Hxrdv$(* zBZ_V9I%)1Ckh5#s^d{#frZO$Rp^jxbb(Qw7)*h|jL+7ru*Er}=FU_O9Q>}7C$~o8P zGWCe{ev+8UwHbya#l%|o&NzZrxyJnCW#`N~9HIDm??4(aY~xjfW9RcL?x!6`l?k;5 zG`1>ca*c0F&l{^8Svwl;P8c0*&6mlxt*>uDoXIY4?^B>e9H^Wi#&_+X@7F+s4=fN( z%_@8ZfRc&1|A5Ow`#pw$PM`M8Z%XZ*@n zY6UdN?xpoG4T{gV*r~I8No>974l-46K$03X;BIVRS;Mh$uwMofqa-DSA0vJURcx_} zv{r{kVZ;MuMpR5lz;D#Idm+Q2WmvwR|trZ_( z8REbxX@RoPgj_-~rRWV(6DfL5&z2t zIBpT>FfLCoWDm&%F*Lbg7-~n!>0PUGIerOfVKCmddeE?>N>cA%LLd1C{w}o z{({HPgeUo7WLn^y`p|K9dy@L^uE~Oh0UjvhkPRMN6YUl6QQ-jc!^O*A&z=Sp7P10H zbM+ahn;dlN^^=`nHQsdE-uv;PeEnTrhd$~nESUm#;>CLem-OkzPZ8;N`he1B5;JJ`Lrxqa&JmCFEtNZk-s7-I3zI8du>EXybNtZ zV7B}QIJf?76M#-VwQ=4*U4O5pJbT$q*=z(g;123mI&*>Y;NV30mxA}T8f!+zD#|NUr#(#^NGGn%QH#)GQ}%nk`2+RXtI*vJVJPF9#;_%f?X9~ z@@Q(_PfPrj!t}Y{zw^(oTo3PPI+|=Xt3@2RC(XR>WtcA&m9_k%OA@Gns~t3=ee^?{ z^V3+ZlEiA&lNaB_{jE2QUVGnn4*QmpW%oFTq@qr0ktN4oG$~`pbU9r+M2gMp5}uDq z&fz0VGKDOSkD@sb*-GlEYIMW}#TRhz+L<0J;$pvOkLzWo;u;t znA!mjOHgpFG9*D!1uh(*v_(e^mGOhQQTu$k^DTF;c;Wul@)iKFkx}3m5j7d(FLpMj zgrGbF>>J_HheYoBY_^CN8ExirtZU2<{zBKzQf!*C##)&Tv}>_1_G3yXPlYyPN+Z=G zoLvPH7TvqVI2Gt)O6Xq|e=Nsf9jQUVVhcc6Jv@7!PA~CBEqQb+Ux{9GkGS_;ggHN< zovF@p#N*iLj7SouC?feV9#n^eNWU5SUBw~0IcWqnP}2c`6Q&uouEF+2F?ry*$!NWs!9(xSY^52_#9k&v>K`JS+a@w(d1r*l<1cMNo?cXV?3^imDOT%CK>5 z3R3j=+R$aHchZgP^!X^_FPFqjtU{8!W!{;yYNz|6Do_#;Z&6wu3Kb*XjPz8^R^qcl z5{P&`S`k`YR;+|Cxi6L}-W+eMMUJYOzRuh9FXYh<1Ge=yacU1aC<1>RU+G&2(xXq% zYw`|N#rYtUwBk7x+C`|Z&tg#wd6%FGoSiii@gg8x+(l^Pe$sq$Til12o*nDuE5yqF zVfokHCsn$`*w@#clG416g86Kw%W7)0lW0GTfWnt!*&XCMAGwARFp4vJTc9^VMMX8# zX%K5K8p4n+tn?oJ>lAOIM^c>N%*W@cJ1!evOsIwaUIsK8-0n#OZl$LT<%!P<_utrW zI9~B>qeoCZ(tj5g&Dm<^)~LiBX1;oCMg0nmL?QAG!F|t(#Xp9mhUdR;xuPUxnVAfY zbG`iIUWO5NxjOl?G`)Y+;7dzYgATdMH?YHIm=0xo8>OioSwt;L%F4iIg4sMp=w+xa zWwN&QBfr3`3BP(lqnK*9qobp$j1S@|90V^S+n-bCoJ6>=Y=lFa9E>}mJqK1g6%}M7 zt^R^!d-$UwhqpYJvsx7J{|{GR9TnyFhASnFAg#0@LrX|^2vSmlG=hlI-6ev+&{!-i_y+-@WVl2W#nC>dd$IxA*%#?-S9>CHQ1}Bi&})<~NCUo6|-= zU&Kud!sL;ttcnEI`ls2NNJ=YOUMss*csJ;`E)zkCxy~QUQ!tzV_>6jT>(5NmeZ{Tz z4#M>Nskp3?VoW3|tqoQibwvv*0pnX~b~JOR@M`4PVimi`wLq;zQN=G|d9mh&%9&U3 zz^*FvX5xMsIoGwn-i=?3dEp= zQMt^T!rSuZJqD{&_7WC{=7@9A{|Z_W*Vu*;o0jA2vc!Uwt=RiS%pcPHsvYBrSRmgr zO$^Y}aA-2c_vaA0GQLUZL;#<4^xd#OE0De?;fJB9LiONjGa5kvOSg1TG6PYdrm045 zP#V=azY5

(zQ5f1Tlm9OdUkD1-KhllJaL>Rp_w&W#2a4 z%t#3?I&ZqVVYk#=u;C1z8Re|6>m|08<_}JR2R1NV93rkD?wXke-zj4F0Bq?YhsuURa zR5aMK8CRHH-~JCnG;819P4*Vzl{rtIB?a-TB>shm3l@RF(7GVZ7Gk+bPXejr0MGDM zhXot&KK|bMz1E1nMHq_Za95{@_z$b_hk@9}dXtih{@A*c@1#kx$h0EgIkXxFpyGm{ zA4}-KdXB6p9?lxg?cPm^M@e`wqkh`30K39>?JlymPh4-BgVH*Fw8st=siM4`mWzo| zemXdyq7da zp?}#kzCD;9YFCH*H6CyDNV`sqLrw+vq)v#2j~22Fk{h%jt9pw3WEmxcuv-(gVL_6s z{YP(UR(P`@zFayUHG0z%*&r=KH9{^c>cwSV`*S3Z3y$hdPUfIz$yE?a*hP~pI%ZkD zxMetWCMPFsm1TB^o7WKde;pEoe|Qa5NTh|BB(T+SA#LH-#d5So-&;J^-1B?*d&)g@ z%3p~SBQmO^xfbB`Z!uD#4g?1!V2T)!%LX}+5y{8CR2uj4@^C(RbR3}WwHF&=AkELu zpEhO=luFmtYI*F7e_XBmCOTgy!lU{%?{c$1rEo_Ec|-km?BH~|$i&%A??TTFdT=Q9 z=OH$KW2ecZf&U#6)$>Bv6+&x#*u;6*>&d}IT6vBQ+rzkp8otnJ{J5bRa0m{`cIhV# z2lcDS$nWO3kPPD!$wkE$xs`&-(^w^lx0`U+Fa1_FuVCo)xj7?TunX1|i~6MTcQn4U@VYiwpSb6EOe zz)&$;otFL0CV*2Um@yP;hCrZ`GczWMBIRtJ&JIx4VBhhC&6?BnvjwVmPqgnOqCLQteY1-Qjk2dl{9zc2c;q{W_)9{0l3G z-DW7=V5G1VTlTXXY-O}aWjk0&yjuG!c)=kwV>xr*3O#Nj)I0ZgGt8E1E!b+4JBvWc5X#} z4cd)x6FrJ)fx>L@+dHK$Dx69{M4~}M2WE`NELgu^*qq1(xU##&H*s`BRlkgM6KZT9ozhiUtt{z*zJ@_4!zuWo>z z^MZP85`_?ED;FizDBb>}HG^oQ?FG4hs&bU4b|bqv2zUSpbX61`n_*mky~9la&GaIS zgnjEC)>mcP55BxQzQWck7yn|C3OhW zawlj6tO_F6(M94s5x^S1EZoYjJ;pt@{A6BcE|@&tKrWPw2gbq(ghS`bfx69dvfD;a zKvzP+WbDgGn^G%yxBA|oRakmTFJ^-h?~}-MNM8C*VA~QOW%cP>v(9FVl*4O{j=?cA zM!I^R+Z2#R2ByTk%I8Tq)z6T=6DG|JR0<+VJYg1(>BOu)_MX;jQh*bs-lAJO1t)qo zXCe;w=`z(t4UIW`T1>g$*@YA355G)hD~0=XWUd|iv2xf>J;dKRAI!k`_!}~VQ3F%l zPoPNu*^+X@Vr}UR@2GMZnMVtZ1Tf<2i5&SCvj(k&jP^O{`cjghFU(rh2scT57(Ss z_f#P!{#(faLlCkrph5#2ra5cG$SX0xhXMK+5bgpX8$dHIuAHccALK-n8!X#Q73oEY zu3!F#+PExcZCog+-aLoJc{6aqI-5k0VP| zmGv?SyW@;n%WhpKrO}i$M*U%-+3nw8H%00AN7D@Yy!;cU?!M#oWY0C3+S~ElH$1gZ zmT_jPUr;Mz2(pGek6~xz55dthQ2u?Na{yJP;Mpc>9LKoGnhQQb44aDEmol`!{yRAs zZwP8b-`LYpd@6#H8~nCgta%y2g^W|O=|jY)x_4UgOWBcPXE#GpG$2KBcK+f}bRz;vf7IlA z=_gDioHd$6TW)JAFB_Y^Z_IYi#L~JWJ)dyC%m@un_4J*Bt9f$t%2}6^Tf5_gl&dwn zpp{WcO&<(S_H;Q-|JGTQ{o$w*u8Tm6X1gZ=#o;@Da}vzA?N4X7R;`qHc>a2*giZWY z-4$9^>iCR0)@5`*ljse~)~aC?oy_xEr^g)Q+g@^cntX|{E3l`5xT&qJZMs2+2o0>9 zXsY(nmuQXE z6wby?L2UZFA)IOgYsoSJO7tIqodGeg>Qnap6?RzLFcWnX^cTfZys~7#$lSqt|mCEuEHxroX=G||2~s@UV8CjGAE#CJ$?nh8$CGo4p>O_3``fo?eH z)j`iv2L;5$K#>U|2rLL#p>&~~$NL>7HiJ@seh=(e)i-4a-S>eWTZdS^g6>{ir1+Uz z*1ll{F-#63;bQ#!Iq6a0$^!Mj_q>Ho`9V?+MQHidPOptZ)yPuw&zDZp1mswmuA0eN z$uh%C8HVR|{Pc!%SFWXgkMSgWu)5cqysvcon%+|KiBY%DsqpV$y>kk-#Z)0-o~f^| zwCniHC=rbDH#mOVG1=Txr6MKA+eOs#tl7=n)_RWW*Hj_Bx*JslGt65wb>cQfIs2cI z8=wV15(Fq?031&p{I2-)rheBAKhLDdz6tJTP*n)z?jTMee+&j-gOgp|i|fX_aq8op zi{~9ui~llBt$Ung`Oh{kunK`qmtbQfv&Llb^)mQ;pWc-l9>-|K{-I*P=TTAhg9@4Q ztk!1N6S2rK%DLM~y*i(hp+!~0m;XXgcWkgMsePhyPpm9EwtU0V;KYv<$u4t7#PHi5 zEbUXy@Ij##;jd-X*9929Z-{XHXSIJ?-XeHoK6^>ka8Mm5ZeYDp9*WEEUS!OeYay5V zfm|^Bfz_%Mr{q`Id-9ISYBalYVRp-#9Y&SZM3pOi;Vcwkr4e_(QGvjJQ=4C;OMEls z%lah@4>}9H5%B;N_Uwzfx$g^CX8sFt5mLJa`lpHGI^|7GucGO}d<)!=bKebS-Mj%~ z`5o8N*%_G$PQx{Oa=Y#CP`MdQ?eb3rt-AumGQGw#miIgIDBw-V((hOXjuI&l_dGm2 za01(En+H=0-?Vco@6W&4eXj0x^DzM!s{`RJ=mPK_JOFGWutb0=1`;u(RolVI&GzeZ zL1j>?bTf&s6O7u?(b13X{z?$xMgJA@y7physSE<^HhA?&#hl+a1;zONV9QUIK{uqD zxZjEzJPjdyGW9Umy;qAL`~2$oI5KXSv9ROEIAP4p4#S>rteWB{2BUp1*4|>uy~l(_ zFdo0fpG+nfR$rLaVlZ@2+b#;3D_(0=-+!1Ur5#_g+65(S48b50SY?`|2sF+$$;y(M zVGEjriu>nGGfIRy%69*uWY%ptDzL;o@D;A2S}g8IvMyv8bO23iKp_MQx_yvuG>xQ% zX)@uKvk(E_TJ$bh=+3^_1rOeHa6nyP5#XMn7 zG<5id0&Gx0PXPugvQ_G$j8g1=f3j?m2C*|Qu0mimcedsE)aZb6SYaV>XY9DXy4o%j zEApV%3GSJYb!_t2AZ73Ke+L;#Vz_Nuc(Kne;gAqZ_kzD}*A%IOxWuR=>?u1&)X_uj zBswiR1_hVnBB7Pk$Kh&0c;lxL>$+cKy zcB1M-0?2+J7Z3pg%nS%U|K`pE@H0$#H1OuyH4JZW;>bWGJQ%~0bvcm!60`7W@h?{a}m<9zpO4ZFqt?&UW@ z*K6~AJJrJpcYfCysN{1ram?jvL%V;%RAwGKcvN;BXM6=2^ zH?Aj%2@1mg#uI_A7r3Q_a)Q^$Q}nbey=x`+e+Xp8L#e#2N#^y#3cM1&4vs>nx$<&o z$%4o#bVc7%<%G-y&DfzmYdhs2C0iOIvq2qJd@E|6e9vf$?6Uv3u7b?4qg&V8Gg@V? z)u}j^P6cY~Rm?PpFw~uoz^=#BjO$)wJUa9fr|3oH$81I=Q~lY!S)Nh&(6}%X(#fNf z^8$q!5Uj6Stj<~;_KCFf{RW@)QP_)J`l*?j6)-<7FE2L~Sfkbv_p$N=oWB~% zF@A4QCV+@qpd_BM9R9!qdhmBOda#Q1ot*+_GxwB~?SV}?{vTt>BijKxe3v*U4}NzL z`L3+2fF}$6>=}@;4fvPow$~0-<6Ozg;J*R%wV{n$X%6#ec1YT3J+bcfetLsnOTRlF zf~YEYPj6dW@qcP`DumVA<-S|2XTN}9|EJ?iFF%^JDa*2^rU#3J6o7e3{9j+kmg}Dn z_Lq4D-5`RJIL)T(y`OK;XlaM2OfzB>lBq(M8RRu%a)5_ipq4hldHv|zK0J+RH5o&P ziH-)YP<&Ze1m6-Q-V(yIt?*76uO(WIZS}Np6Jr&`W@TSmeqwGH{tY>sD1ev0kP|Cm z)zS2&0+%FZQ~>SM@S(Rj68CDnIr08nHl9=nG?%lk0A}XMh&tGasziXf33elYIFfZ} zvCqJM&&t6L$+!+Mcn4fE(A)#a8dN6>Hz!q2(_Qbl4)ChXUaTbzu(N;fS1Y4SqvRvw z{R@7+6qx7qz|B;Zz>z@7L=lhl3?S;O%XH5@E>jFLcl_Niq9-bQNZh>=+h(xO>Fv(@ zJ{DUxOse&TxENkfBCcL}4_%mn)6x~Y!yL%C0_pVNW2Fyaq@@6zy3e4AI%P!cTQkwr z5%Y>5*c~tjiY6V41q+~59R2SU7Baf?`}#S~4=D)Na2M0Ctjr(b_tpz3s zTtmH!CY|}un2X3VUox=i2O&w%)W2{ezaV=-CvA+W_sN+=^--K-=^Oz)Wel&=P`iSy zuUN-6wTD}Tgenm@G=clqhpHLS<$`BzM?qNhl_2HP^=W*=LfWJ2vg6<9 zgOlZAan`rG>jF&UexAcm$gVNV1jeN&4}1z{Tt%!S&hxrlX}=gPmmq?a8M9*Pr2{V= zzwMtFXo+qb%T77|qNb)^Ndk@oV3GeSD7Q}JKxF0#c;e}5lo5z?3WB#lYC?|*&a{RG zk?Gya{X2?j(f>-2mkgp>U!4aff|};Lu9>P#xFwne;K_%@zT2AwYq*oPLKCgk#$M_l zj{k&j6kF*sC|VF4u|;$UQr#rZWQ#wh2NM^^Qt>(>D zme6sbOFGkKZykNoG}r=i#$Vb9 zyiOm7CIhYJ*PeEvb(ffJytOrZ?bEn@N5SSei^4Vgm#Rd^0&~<4QUc#|_kaNC^dT^U z1n0?Ll_v!12Lvtns6ldGl&cX65pbua|1?M948Ph&>WE_1Duf!g439@=)Jywd)9eT7 zt**rB>^j9A`}vX$FASY5S)PGuMJH;@=M(&3A(B&rE1K5c0 zDuiX>*d=KEfhD4{8iU2w6R5}i@Y&$~dQv31Ou6yadX>)2h5DSp^CBol5yV#eOTStM zL@qW`!A)5u+GGc7%|3~wfHMeFwUJ$F{GYipTe5umZ^r+)wmc>!MUlJQ~dDo{Ua=F3FW-&y$3V}fK; zFyjM*!Z4Wxs{p}Ca8iN%c2iGPH=kVkSWh;z=Hf5dgy*#J7W!Rs8U_+ z+qNkOLa10sLFwDaq%NvcI1RNx(x@rvajmZxvRoEkT-^Bm@CiIZx1L=E`i1$lMjdLU zC?RAPMfbS^!tug3W?xs~lO5Ca+P0ToBd*p>wsWtC^VhtJ;0lsL5K|vF^g$y;-}_-N zcy$K6HPdt0s*3Yc27&9NzZ{ zG$zH{zjb5@LPBg2#LVU}Ss(hdejg5*bI*W=tH&ohgQiJd4!-i)&o1l7s%&K9-;-3x z1;2SnEC9enkgPb7>J=NaNSRyLl_dqX8OY%b3=F&@R{Z0q#+ztoZ!byqB`G<13^_*( zPdGv*b`|uRoH&bP;s0>~{;l^ZsHi~hJP z0nz~*ONs$+FU$TPHn7vH%YM=}1~+}&7RejhSH+3S|#^U?G@&gJDLXgXjJ*w6={A_MckVqSr^a>_jVz%8>$1zf*QR!fWvLE2916=JS-06*Nio&F zj-Lzq?ET@B0h3dv%Azck*q|(3uMnF)Ml+MF__^_~*ok>leX-hPmo?dl1;J>q!u-4o zReV&fx$*E1+98#lwYoy-J{gpfcyHk5b~lxt``?WzNTiDBq`z}f`K(-z7L$I;GeQFr zol;f4*~-@1ElGjEhk-^V%=8nSt)VyJi`Tc|zh0HVeI%-0fV*%K2acsNEAc#VWBs04x!P|V+(^$ay2_E3;g%xT zIjjTSTI6PoU95vQ(8oMy{WjiGRWq3*n_$W;AS&8PwnE6^oU|oukc=Lq23mgi1_QQU z3lI%Gj)`@{|3{d2B0>Q){RYK1UU@it^0^mR8pMfbE5MM1?SG~A{`&D$wAA z8?;=f5R4)JU{Vhf!BG?80QC)zh?s~FI5|E2$eReRp|K_bv1r#cK$PZWwvIi0^=zQd z4^QPK_1L`Z8umLo=&x6e{A(jGH{Vsc3227sfSM9^dh1Wb)WLDfx3`)a>1j|qi(t4z z(!C|W!E>H5UAAi(d*h?foR<+Dl?&uOr{AD39(+izOXD0OG7IPn4-+{`5ekPP4vIS7 z%Am&wkevZRLo=hn4%e8QCqkHp?v5i-_%hF;58&JTiYJx<{VRtE_#lzYLB0V3Nb@qm z*U|%h#d|Oc@$qyQ77F^W*GEgFvt1J(L|m!nZL^ft*~2xAJsH}y!jJYFoJVT#gwHB9 z56%;#E)utMZoD5?ETnqi}Y4W#mdz52*~!!27P!gZe=OfP7Sgv-oSs;O)Bx# zW8i6F9dCE(uVwl8Q7y+xT`y&bNd!v?ghU%&E^JR;9N$iC&s3^xACnXORMU0r71F4b zW;2T{Oe1(AzY_C8V>8+&#MIZ+nx_xa*~u1^h%dd}W4w<#`8>}c6>ue-{B41MoBD@k z{*&RwHG(j00Ytp!|Z^-nsp~^((qXvFD z>^+l8KBKayY97>fVI4&Qz)$V&pHBXInYDmlLo@@gvYj`gEQygd6(Rr$zq?8N-^h zGvzk4?u_LG0aEN>drZZ;>Goc9a#73QNGE&H-+4m?u8Kh+3&IA#>pHx7GT+1^X#AEL|;t(KP7bL*Yu5Tzs71 zgILD}XA4-_NVov_%D|nAkWx5>vi)CfwP#@e*mYTE5KlAr|ykjMboUR1@#gBbTrq;eDDL&R9)6yyM5^7tUMZDb-cL$p@K z)@@US=-cfx!FqkFRIJl&Qy1vU5UQJLODFtBr52-ieS=PBj)opPl1YYH@?JaLs(e)G zkorwjuK#)AGDQaVsHdNNT+p_W5;?*!=N_BDCyXeJ`zrqrW`+Z06U-OZ{c%CrSGFT> zu7HpF^DhBH`z-nr6^DOdchA~OCq`h&)$_x|8jn)NzmTfVOLbae%`3+QJO zUG>ap)>h+wSKM-*xzh|a6g}^|53eR(1<%BPzQyFeAY}eP^EF};kqYKf5}I*2B>_Y% z^vTP^poNGWGZit9dslox${#{R9z77{8I1K+ZRgdAc%ZJwOybPvJ_0Qo;Il*yh6SEy ze~<`r(Tbhxu8o2*Q{er_2=Ns79V^k27obp}^PF$+0O2s67e~Qh^OgNF40NT614|cZ zf3vr^=<8gkMCL6JaUqQ!VOI5TscP`Niol<5Wwqk2mp)Q%D$cp8Fj!0UTIRbfU+CCu zVEUz5?6UzmS2}25ev@<3wZ2@tn?+w7xmY@U+WTBljKQ1WsPs8XIa#JrP|YW2){TXI!P4FYZi>>; zCbqyi*A_x3?%|8GKs&-|&Upa43Rkc2xyyvg0{Oy^!a(uTC|eE|#`zya7@Q{+b@tE5 zMhA5EjXdTx!lmzoKOoNoOraYZ)btvgOmup?9nJbm2S>h4sAoGfsW0Ty+^3A0d5R3^ zzTwX{D+o(
7S5-yr0)?VhgckCl(ya3z zeUV~j`s&?n>upHY_&6VgQIwhS-P&H$uCujNj1O3Zg7nF#veerAr&+>-$TdqR&(s69 zK{(NFR?nNRv9pWp_^eTJWJd@#;kTF$%!n@q$?}!=N->~{XsoXlvyhF`med5TC6*uk zDcCo&`e%LyF=)+*lQVcq#CFesOZ(F%6fwxJMNQoHI)2ve;cP18Gu(@(I3{Z#k$F=Da?05m;ZD z?QAx^Wu%T8d*`)#=h`R~2%5b}%TLyhs!O!BPQHn$G#yw~{B8O-e&*rgtnv4LGU;zk z)ra=_Y+aXT$=3s0(c|Y;4&m3=UO@0Bqv!I}Ok0x?i;9Bcw|RvtIIY0V+F`u(cMT>U zQsx;TK$Cx(aO&!e^N*AYF5!kny0KnsW1q6H{(RxWgP~U|{Lhx1$*(XNB0{h|zXxW6 zdALCMjW7SEsWQdJ?y;gF@s_gI%Qw-xHRXyMOh0+q=8npo8!SG96ykJU!PRt1gnM}9iK3W+%}_`yytXh%M*jt_z8{M?yu6? z_b;)~GaKznDN17tm`tEX7GuQ6_>5l!O? zjav&pr}nP}BZlg(iY!g$bhZU0(x$21QkuA2KKb@Xc~&?F)PFm@wtr(rF1*8-PGl^p zho9bGOgSG5F)X+(lzCQ6n=rTjOhifscXah<(rl(u7Ey;gOmAtN4;UwBggDB|m4D`1 z&t3QgC&;D91{h35x`u`R>3P`7q|hh;i^^APN1Pq}Jb4~PnQDvNoWe`lU`Mf&&ZEE( zqiHRkG^$q1CLzn^p=s&wGv@Xj-@0#-z+W#(Qq5kQc2?9*u}q*N`}V=}8}gq9 z52U&2lfPXrTZI=qt)8;e7Ecooz&zfVBo1tn_Y{2x$9I+?Z zl~PQ1O!&%CO6sF;NXXW^4YNvf+}wFpo94IgeKXIwKecMnB^4W_)-T~ETLx#U_V$Eg z>^eU#e4ea~e#WJ><gJ=)RreIE(2pI ztCy^&nd-!r8nCPP3m5u6`&#%C<6a#yo}SkZCh8Pb!Wqw+!iy)?6AzB9uf0_MtW8du z^8FEPOmX}q53go5eNSnEgWkJ%?}@+<1>|*1JZ$zTl%j;)&2UPSUI8`HBY|s zsn+Oe#n_z;_$ftMHio-3eW@;EtnYv87Os>HQLiL>XqP#;cWCcM7pbgpFh{aoDdX_Y z&ERRERYhw3Uvst5iIr`ZdXxF`p5v7k0T9ju+SkAQ!<>|fKjChJl{Ma;@3mh<)3@6x z-f>1A-rcWmKmN`L>UEq;PtT>;wgn%o2{+v&fk%Er79`hD%sWSz*m`C09`VNgwPZb9 zMzy0`tN_9Rv4fbY9xjSrp{H+|HXWaNG7-}2rEoe(en5W8oT2h)m-WZH_GrQ-3`gx* z-+B4wMmV`jFdZ=LVD0;@1Ja8@o_B#}zK{?RI4I0?H3pvFl_G$M{ZBLQ>mgJqa+(=x zKx#H&{Aah*WP%bQ&osTu3rYqs8*~-Uf?ypAH;p|HS0$hvfh!$}Ignk8G%Vu&u%5lp z=eJueGm7?Ew$Xl|+M01Dw@$)u&5nHg+%%(cHNQ-}%v~{qovw48k5pX#xc*qQAPLbi zePFP!3qly6(?-3gj516oHinT+mDjuhmYUWGmr4M2izI4vNsU2mDs)Q0(E!rbz+K@g ztik7_=Sr2>Z-CIT0H6LJ7%j^h{To~W)Sr#Obps*!w{V;yH*nZTC>i)6uGk0b_7T+3 zJXe^#AKY!gyrT9Pwco->JqFnSA!hL#+b6^}cz*m-uTNb~J*9{ABKe^DTdE(D*sjsn zI7zsK3w^#_#2DWxO_fWv`i8QkRbFTrpH02@H^xxb?V zw0bF4ssa;0e+&p#1%wsgEC#cyF>@!5>*m%$0Stp+ z`1#&d#;linhdf`Tk0-fp$iFmYQ#aCT^z1HlPBSfVqSH%6X!5R#job#lnz}Vw%c?RM zASJl@a{Z^G%SP{)pvBh3AKoC<-6uzj5jiIW8#%0~IU#f@_W^mx+wbwMkhQa37K-Qg z`Q7P|CP)Po2eA&Gz#{_`rNHlO$5UtFmwZ>0cz5eLfeK3Pk@+53j+}bn9S^- zdKJ4xzytmwR0yM;1cWET?LkGswr~c@bteBHpBpCf-f_w%U=vw5_h-8g3rFw~dPcXG|>Rpk`{U^nB2#hhK?P{hs(U5N)Q zfu;rc)zy`#CG$9SNLI#%28kM-Nc$5Ek2)-Y5 zNPPD=+wVlRfII-$3E;(X*`Gi7TWeE+-+<2z918x1dud`LZmR!ShHUrX0RavW*+tX; zKO6U)dEU)CcAxFE6kK`RK60uzxoGEc%~=Xm)pWv5&JvYvnSV8jt+j-Pk` z1zLM;K%RzaA9xcWcQB zUOuexNsM#rsy9O+$nEF@40!~|F`{d2X+Z)~IB@*mi77l%lagFz%gpliUO9tINHCuV z2Uml^;9VtcaPLm(VsP&jC+GR-0HTh)e3{83)dPNRtr~m~t3Z|0aW>JI8mk7p@$O6t zfsqFALGN&BMmSSP;6C75VZ#>8w0ODToeK+vzhSP8BHY76We zcem#6AiG|boO}5^^73x;i@!1A?@gn;JHz`Pt{MVdCtTutgB`&Yn|TywPRrQG_4I47OO6PM{3lG6w|?>$8{-=WyHGuf z^0W^A=h8CL#Z#FcznAoXw*0P7PCVbUrgvf<{Sv!ZiD|6CBWdstg|i@$;K$klb8e#>2II zX_%wce zTZh7?*Iq~WT#HakQ-s=<8wNsf+ zdqnAY%f=jv6uH)s9GCvt*EGN9W4UaW`%#7rA0Ea7t}iVfhXYJ4jx9XpM9L~JQx~(r z!0(oX*gsQ6ui#C9SLf0`#@M~Xd*9IJGHI0+-riJ_5&!1#*hv&qiCCjfOUjZL)98nGMsp@#cMmDbE3nE z5r_+l=#Q1p6WzAQV5f|y`PSv?VhhG8TXjdiKAj0TW|(VRE(T` z%&?Iph6zUNuJn#aN|JdQh;IjQla2*|roliRgy<$@d6#vAX`lsj_VgV|u9qbf1Th1x zgrSs%YWe*4lV(U57p>r?6rj~(Ya3kY{JP$=C(0d4+Vt%+ZT^nSZ^_61;benij}V7- zh;9YJYFa7Jq=+JNCX#h||0g@PYKO$=dvl#2H10&gmlE+peg(nnC)X3iSm}}p@0$}> zeQ39Cg40sz3W?Rr>EnnG!xZn?k@S$r)moPVvOB)1JHK_hQe1Bn+gf9IZ=<|mW7-45h5vpi?xKaI=Zqy zJ&Ne)L|-<4zJ~_I36QZ;a`gVd>(Lo!7q4aaRx)ZQim#T2u&CVe7QcAJJ7YH_?mxDL4ce>Ub(GM#x0qq zAFqh7l|K3LX@l9R?La9&-4&nmB!Y1HJCZsX4#;Eyx=^v>r|zKV;>%4k2i_-NzY^YY zYk<%NSmu0bd#nGBo(`<@?@5a9sVh%YRr(3y$$HkS4^pEny|ZPARkS$XtIC-aE13P1 zEnmovs`V4j z07-(NEYl})GZ|mW&yCRzgAvPOJ*Ef8afU9v=tDrOocO#e3TTxh>bepx{Q_vTUpJgO zQhyxy5DqwCBM~DuU)deg(@he%6ZTS4_O^6ttMAF(tLfOf*`(w0qk#gkGDf7onCV9& zr0(u+Ia&X}riDxIoOz15)O0xl@m?kMW);?`TFdq`*Lyt}ilbM*G~=%q($Fs_%Wdqk zZ$G^w4Z|06^_73R(SqWaejAEQH@m!DCAi0|$a&e+p$PnJd_sgSNw}{cidnKCoNloEnEsrx!^l*p9};OGW#Znv<4S5uXrd8Nj4jf@|x` zR`o{fhcw2ght<=xh|djd2^$yU{whq<3`-AgE-L-Tn4~caUJ>Z3vdH8TRhX9{Bj;jf zwg*{JXl-JU@6tBV_RgAPeu9UWjF(MWzF{TN|7Dzz^_St>FkTNbQCvmu7YQ;|jDzRwKZ`?*tTv#{t zvE3AT+3tQy9IexrQGrP;FxhuK5|a>qq1<%e%9{1#W_A+DpNyw}2{w|4ybya{9_+4% z+{fYtoF|3*0jzyF+ta6eC$r>QgC?D1ohx=)&n6QhW7OvAGs4B7|LFeyF3Hat9thsR`2g!6NWQc1XiMvXPy)aUqSX^36C zaRB>7niRca;!RwyZx+GnWdfICPE~gGPCYs4ti8?Y+%`E4+7}+>lF-h=+ZOy!wf8>~Tp+NzZ^jaS#r8^mmEGjw}In zcd0RidQNJUxw@c<4SkUw*Zv4>sr5*~t`r{>2^>N3SB<_Og5 zUURqs4pdpkBrd=J?J`_>!XzGt6E4B@=n@IvUE@@_Pm46EaVjJq2>(3#O6AoV|BPnb zE5^Mp^UWH~Pw0=3+|XawQ<`MDB3>wlIuOSI%NBFg!&>P>;JgowVWC$X z5(H)?)wOoL6K+rZMkp+Dc{d<352$%sZ`R44$ERl-{#ZeJ?-)d+kYhjVjMRbEN;H=E zyx4*TY-u&IYc2Yw4_HPkqP2Wd9oLG?nu(cw#T!zRh;gJJb zzw{>W9EPtNYrp?2O11xWX|Q~n=&WbSo4B_Cz>B~3gdjE7blWk?i3KlE|{0s zZL53iery67rp~wgII8Z_QLk4kU72LCn?ckLr4(8)Rn!*eqc(owX-tI8X1vyyH>c!i z5BP(;rIsrB?W*(M_mOMn@g2n%(+IVV2}pZs#QTL8E!^tgjfh8>^7z_*d56y=(apdk z#l!=fWGHV?xNfyqJ`8GgU%0I#Odv5Q!vX{ACLF-s6=^<0k3HI<+`ZuJ@BsuuZ(tD9 zD@B#(=YA&B(xa)ghNg1t#zEctz2a)8{FAj9jCOW+0ig|W?>H)I5#i^TQXbxbhzR`U z6S4p;%HGj&H2DeeMh9X6F#7dy@z{$=-Fm(dKJoc82w++U8nb= zP3k!AIiX>Zlvg3+L%@!Nv0DgUJ6T%!yAvT9Z!@?=Eu|a!;KjD<19g0~$}i?2qcY`Z zgeNWjz_WQdp(Fi7K>j)Byc1GKZSZeL5=*3FZGOZolCkRAqjERpH|(4kS-qHfIBTpA zPZDktC60_a)mfEUVNdV_=LO)g`2?A&Pupo!tV@;?QV!|Jj(Ph^_+)2vZ!{Tf2x1B! zSJf9X0pUDtYU``i56Rd7p@ zv)3`E3cC&W$DN*>faw#^c>>mHNXK%K3z)=Gj0%*Av{2nXrrDU{7}~_yRI*#2`zA88 zt^Un)&TMS{6resYK8te4mJ~b>_#)pRTuw?+L1a1S2OmrQO_sznQA*l+b$qJyLxq`! z6J>oVE@-j{fAQxHi-n8gwP06$bryfi)Ovidxa;*Xzp3QWpL?L*z|YWok_fNfp{Np& zfI6vXSQ?j*_yMy}tQWG?h<#hq1*zn8*i)!M2Z}~=x}yI~5|}|yx*VWP=G8QDA(e@= zQQcx9X++Y<|LBT{+UmX3a3|IGL2%D%39KhOfKfkSQi1z;PB6pe*8=r4LP{u*t*`7- zd#3gs*LTMN?M9a>IQx070pfS)-8KND!nb73g9mW#2zVQ?9nozS8d(T+$pZF}bwKHg zkD3g5P*30MVc=DGzB3rO{OD~%?<3X5X+ZXL2Y^u{dMGLj_Y&yv_ zQ!s)x!!4%$^Ti!w);g*!F;0Wn{NGc^uM3{(p!nJ20f0tIPxw9|-P88ni*A<8q2*=) z4Sg8GLDBn58ABR=W#QI~{$Y{RT2nha_a_>cmu+}Eh9{zdfPpkyua z_eeA4W&^9yB}T7yz4qW_59q+MuevE~fBR4fz}>rd17712<1U=?3V43gmMWpYe zfO#{pzx}QVQg^nat3@wsj@W2khwFNVjiO0Jroo$}clG8*1=Q9iTmlT2^Gv875tvl- zWl@u7y%dk?oaA|%7${~>q8aU==`(@3t`h*s{Oog_B&)T>V1@P1^vMy^WsTfaTgCZ*3B*G@A@kY#UjYNcBJc1gA z9td3J$`A_seGL%a>Zm^#)GL&TlnFa0&z}KrRt~BO*DA)nJzYhyio&%%s2KrVh3k8L z4F1T|Zxs*3tVL21TS5-^gTbPk)dH7l&*~jur=J$%o;wL|Of_VuP8~mX;0O=PkGjH{ zIEgCef=tLI^Wm9O0v%%LNB@i6mm@-ry9|b=Vb2WB8UwE=X?R3N`{pK6DRSu`x_hX{ z3Jc>BPa07+K!v9_+7^J>NupHX75h0~b?p9YQ>A^k1P0B98E^x*5F7fqU{uc;=MqZS zHoM{uC8sVs671Zr;&4npT(C2Ce2|6aaOHfmF z|0Kh-3-tJFA936h72_6dJ?C-$m2{+0hF*I7h@rQBF%~;pnAQ%%)w}w0KW}>3ZMWgo z#<;zpwTTRUOxqNeOBy(erpC+k-sF**Rr7akqf@4bUm)+=Hp9Q|i{YTnqD{ zpeFaeb(^vDdYD}#9t=3%xs!8RiJj-e5c)$Y zmmG#D(_ZE_S2hlY2C?*irerVc9`y`H8P8ocRd;@Tf|qN#(ysgh|EXLJ;aYw{@B)e3 z!R0);4>3_LqznT1%FQCwF zhFhajJff+Y;+ilmfeH?)mW7wqR+I>^HNZ3~azHK}cgU#o#&aOeGt@3I)v>iQ+^q#< zD|W8a{*agZwHW=(=b9X*Nh<>4ctwrX#NHXLk4CG%yqTUq-1j#>wPIXHS0xmq&QQXN zN6w=FUFFHn<6ler&pevUquZu0Uq=n(J`l(M5g54P2-UqJ?g6}^srJ#Chq;IA`7<)R zF8iBnEA-20%#p^QH9F95A0Gn1YWs|-%Tu>{h>i~E%~NBRYt)NQ6829og~8^PjiBPB ziU9sWAhH-tSU^H4kg6%ipRSCrxQU4hsLl(GG;sfI)p&NF!-yMohtAng+Q>#Qmv)zv zD=N4D4_kj7Rn_+Xfx?2I2q@hhN=bJ&0@5K!N`sVihjf=HN_R?%bVw_;>Dn~H1~%Qj z@5Jx z=u2cQTse6AlRnlpBJ8V-=Mh~+dV)(YuWs#XnBD)~>2^Y#f`~a#J4!DkK@OjPzKx^O z`o$d%_TmOyAH+GT4d6{!$H{1Z=h9-%eS@UO3=-OLg7~Jy?~A9Xkx%*VI3Yz*KfeI~ z{o&z#I6Y9RgTs8)53&5Af_?bxDL^2ZOv=}RpNs>uIVcY(x`3k;#QxO0R9EzZ{e4PP z_lp$~7j;$a8IkJyG4&QXBZFT-6kenTb8KJ8F!OI-aQ5|$L6LrO2qEdiB00S}IX@qD z)BJVK%wPxqY7EsJhEoZYwJ~Uj2C{&U_=qANoHB1Yp=-0=ZkGgo=$MZPi?8nv#Fi5B^n+P$i$`HQ$-dHkQF?q@S;ff! z@>V#% z(S?2`levD*SzNBeO$`e4_5eB%A9b;Yp=l3ZbC#2yCtN-en0?8T@)c&x1h@*J9XN`y z9lL|NkCaAg0~C?iC1W+ve|@Z~~J2ETS4@C)de6@ad=^dGtbMbhP3=M5<9Y#>TMcWBHq#%&AnSEUE`Z%@E zty$2yf; zcXNNe2+%v^WjE1dw2D0riUX7)#u_+!C)o-Vus(l%9a3b0S-a{jldlouO}3OQm4l|;$tcjRD7(S- zdjXeOx7qBySK{CNP84ngs`nj>t78-w=hrGPRkygmujj9bnfP@U4~CK21s$%M*#jg> zSy#7TJhkx*QS4Qo@Xg>y_OE{L?{Q0B^7>@Q3dQ)g^7lr=mTWuxmaPZ1#*ljbD)a&S zvl6a+UB2C42IE|q(35XP^S&dChtoa(JwZD@!?Yw2eIl2q4igar&f95t^@79OfBUky ziik)5`WK;;>1%)$1LXYn_SRtmk~J-oc}~|5m#~+ywfJohBsFFUmp>Fi3sOmT?76^N zNp9bXaim*;zGCSPH<=L}V>hOQ!fQASqvIjRE&3dyUe_kUr4rWz%qWXc**AkM&I&*T1(}LO(ytzXI z6%X<=44OEwg6EC8IJ4XvB`u>&_64T9an;(Io;cWvsW^Vz&#AqEg-?;hbioQ=WSRQv zX(&{7TBph_nn-j*dAw_32T`c-Ozle6sSw0BAfx*n-bPRBpxcG&i}$g$^_FMR%nCYO zK6E%G=k|}Gq(BOSX7WKlGza18uT1qdoN{X+9=M!jIaw`H_XQwZB|66f=(g0J?qpw2 zGO|2jmuc@t*xYCCKK|qZ(HZh+FDoGqgI0jH`s~b zKNXPAbBk`$W&}SLu#vv1%HrR_#t$NlF5G?Mb^{6A2OCMSI z2oSH=yaW>-`}05dZFWWd+E(^H;vYOce_Qi-+px9jz63qWel`?~0}L}oh#EZDD*#?% z@NJuAA*v&d0`!$aNJS)u{6pbXNpE`&dyt#2D21ObZ6*_fh1Wd2x)>psO&iuh`RRZr zQDv#AzC|iWOTzTgU>7?Qs4|v`_cXfQl8yJ$Uws2vzNB(eNA!`^5I8hjUp4L1o=Wm2 zA{YX~ZgQR4h{}4EjZ*}wV|_%?a{8U%uy<*9GaB|)5X21r!<}2gg{5%okZr2mH>yr$ zR8X(U*o>{Jt-7rGD1QjW6rQ2ssaDW1{H zfwEF>1zSM@fprro;5Fw zAZkw+k)-?G7uv4Wg!wqRnO8MhQQAv8x>VAf@ti%EDRs z4}`Q+W09{u_5n>2iWqBtiVi;olcRwsh`@|s4V5iqM~v1wiggdrAHY zmq7f&0xtt**Pgdmd!-=wQ)(8vWk<@VJOZ|OF!MfG5S54ab{+f6|FlQBaF#xpM1*-A zi1VqO-ynOeq+T`~ApBLop@|B}K>Q;qMSewXtlk9O%wqi(YN*p}avOxtaa6<;>tLx9 zds`|M<0f-CJ|89{;6gh?(~>HEMemJrklW{L_)ZlOr7z~?W}9t@92oUje!|wfrTGQd zBHLY9>xJ-4ji6CrEiJ-*R7A(%*hPOg&SxrOZ&uLz64T|t=j4L({f8Nm;r5>L_ztm; zP1fXxffJ~Et3JA-4|QnVo}jJ1X<&Xx!6W-nGA21qt|7i}$Y*53U5~pJ89ZQv$KYnp z!rk>;u;U{(10j9@zyKQ_Xv+XY$p7J7zqht*7zVGM;D;@l*{#@~_dD&O=N@-?)xsj$ z&*?lYH^cWC7x(R@hDx{1BSKT+<~T?rjentQ6Kte)oQU(YE7qV0=}6mL{C&97g*;B` z%++~Zr3ay51!++WYXybZT${gsg^4xo-+g4%`KBUkB4gERSpqVHw^em1GN^+y~FlnutbKRTaPz|Lc}=A_rkp-&BeW9WB}4fVg|r#Ho*UdgY!+ ze-%8ifS&_+`Dq|7V5|q#tRAgpS&xVJywj=ZKxQqv=pC*LXxhG~w5ZP211J=w6C`*7 zspYygQl3w~ANuj#$;Y^lX+da%e=nI~y*-!Hd@l&hN-;swrVFoH!66NOp~fj{*0gxi zsNV)|tNEJ~AMHm3FJjFo)g*%k*i#8*w1?yS^?G>OE`0Obf-k z1_QM;=b63PN31xWNZbnMx56|$NUsSrSYqA3s41G3MBv0c`Jf)veOp-Ri_IJ7 z6A*W~W8>q<(TaS2$D|CW?S0g-XK3+Qot#{pQ@e_`_> zAnl^!ViHpA_(0z@MOB?>DX%Y{^A(~2UeG25est4Iw5VIJ(&~AM(&{~ay-V0>v6QWL2NYjUe1xa_FthXFaB?QPFTd`75Mcvz~QQ^ef*FpfBs$8t-hvtHm3Jo*|2OtiYG%YOsJ*8>fD?Q z$>@7~ZD?_uRXwbtQOE%r)OqMRA9+;n)t9v-k~wYG$#JuEOBM0IL(==TqKO+*S|$XH zg*7oXFU5-mme8U6hZkzH?)Fi?*3os#-H5o;VV95HHUY`-fZ$YJa_ps%c3OQ@$IV2d zYoN~s%ions8j2+Oo`=nUC0pqeQw>5zFnUFJrO}Jjpcp4VDn}vhk_1qFCZ_X*lUS}ykdWjz2ZW_(XIFnG)`oya}n&s^-IS<_w6f<7ndp}%LUng|gpC@KmO zvLRotoXy&}B>0)!>`~&*c9W#1$Xst>AOE(|YT^j5;>^KpY`#kXqs|(gcHw#$zd*2} z;!%m@OJ>sSF{a!JeJVtST*qv$I(rZ$WzHB$&5iKhUx<98fBdaqz})IxJ;~$D>%Mg- z4SZCva1B`oPo;t-Q62C!+lw(s{v!`K={95R5SM?NWEpWy_?e?P|*S$OKZINMq&4Yh6xdbdJU+%V!o#ZO6I)28EZ2HecV0#Z!u|9AHEx|AMw8sP6x*3TImk(X9v z52oJbn*?QJ^90GQpvgqYpt<9G55bXP!j(}z9I)RlgAIe`bptj*K|vF)Z@@4wOeBXd zyT5SMb5Ge5e*bx|bqNEg84!yC%moA{fTR|Sx4FqjqIye2PHM2<|8~5Bi0Ce7_1jdZ4>H*rJYi}KGR%@p$EN%r zGBg(zCvS!8Uk~q`lj{U*blwGih7b^n|ryiW}iuqs|4kX$xM6f(XDEOjl zL%L_$mc@2YEuJaFFvda)UNa&E(g>?% zD#zLScyn9+zRn*cb-KXa-}$<9`gLi}g)N9-FenSBL@X?@8#D6sK^`0Xx+0N@@yydk zeX|nA`Bd3kewFR^DmRSMte6U&Y+l93*xlJ(hJ)?48^(;q(S|D>pVxAEtjB8)&~rBg z9nM7x(rD52`4SP5K{M!pkwy@f92H8O90UM%f!D^Yu6x~4{-qizfy|J96RF#RVD4D+ zZHz~j@j^bxjznK2T51<+Pcgg^LzWEUqS07a{@B60dUg+X@qyk2&|hHj*4-W-cHDUX z02v!oPrwxbNJ~S>KR~vst?lIQ4#G11=e76Fv*B285n}|Rkg@d67WfW^gDUoCNG~=VJo8P7aiAvp;9j+^`uWVae!&6Q-{ov~DSlEVO;xvowg-|3K<$3yLOR=Of0u>8 zVR|z?tHw>_N-!2xmlALlr(zRc@WJ-GmO!=L4sssI$(AoL%(|r7jpgAyD=-&$`9_g% zFXX3i;g{8-rLd`DYS{w3!3)k(@mKD&Epd;*d^hVcGmh|V)M*}jhpffbs}vAMNgi6Ei&n@NM7b7;O8;Zb`mkGvyQRMOjKtg&)G1qU7;&|VnGN!IR+#Ey8X9GGG`Gpop z2a@|C@98H*++QL`U&H(T>S>Dp7sdkYM28k2XT7`gXRy3FTy3zM2&{X`J19MbQbJ`7dcQ%>E-th8w*MJT3oq$(GCa&A%ljYi$$^Qpn0JV2lwi>Z^zFY48w$@awXH6M4=V0KNI>Uq4BJ2% zS~r;xrGmA~A0h-oUMwz*b}0=g8%CuA`m{?&pz^rePkWxayhouMLa3*rP@;_GbU0$pGQW+w;Oqof84B9JdbK06T3 zPwb;U?NXskNvy@6CEuuy=7oRlT6*}bUi4wU(|NcbcC?{yaI$UCD+H>`1y-@+9sACf zapm*=_I-hadDV(Iq5}MXbMGL4i1gqN_Lj{Hrscbo{_~!DQSdnZ`=}}2a{U|6(|OJR z?65w{PwOzOk7_=5etKmqYVkn)ZsPJpPG4Vc^^t5b?x30X!IRPUe=`+WPEO(sVDjbT${s zKdYp=OBFjXXkE8}9Iqf0pR=bmqW1nGLQ!xN) zjQaB?TD27ArODFnNHr$u3Tb8wY<$x2&YXmebaEN&0(tDKiz^?%8Cd6;R4-S7J%gj>zRc}1fT0EFW`Y{(_~^i2H_t@`=G;P|9`qg?+}kk6JEt_-i_K*h;t z8_A>75|ZpEm=I)+0G+Wg(jx!QAD^im0_Z zWO)_>{jF$E#vMU{^xzH%-azGXa0!|rWqR|wf?6V;lIBz8JAA(Cv-P?yH$3?v=S|iIMk3+1@T(AJF>2Fq31z3ycS^n>+ z#d3yGqZvhoyo~C6#blW4_NPAAm&|bAr{72Hd5By>z2b_DKiAE%Hbe`+h(Dvh2h<-+ zO>6p}H{JIW=@V@b3_X=V37I!F2`mR~UfU-=o(IP-_`aYte_EB~(7e@YU2JgqnW-(a6BYYH2?<3UrXBe*TaoGu{n#ITG0ge3hG!H!1lKGH;6fQPS4Yowv zgZpO~8*laKd6VwPa*1!f6nmwX8fDV10aT)w$o0N+_?&i-2eIZv@@;k-{z4L4RSHqg zybYvE6C%lBO}~H`rlbz#6(S-Nfol+}FY4$Gsm$a>#oPLB!<5ZqTK3{@@k=0&R4ekV zNRj{9WAo-;7BC@0N}^O>MlJ z^egspb!e^iB|qocPYSdxeH_U3t@0sG+;iNnQ{xHp?c9w%`mUm`9;BB^?e@_^0%&=g z==)zwz9hhjlYqa-kT7l!={)ut{YTV+L#K|93S`TSQ9|`S?#<63OU4{vEy;|J{7)V; z{c|s3twH#lHRW~C^0D5S?LL#k>7tYkzOB~bL&;NOGs@+{aNSE$mFWnkMAOUF=}$-} z-b21GFgrr!Q>lZ+a9bJ$lx#tEBFG}}ZY?Zj26s0PsoQzc?tE2io!{>eu1PrFiQJ}Z z%wFtBtC+^AnnKW2kUN;W6*LVNx+YO0q#2$_I)-cwW%CEocMxzgqmT6G8pcggI|W73 z#_-8wXXj$OjwtO`sj(%Vo)_CFU|;ks1-u_$Is{$eH7l@~`gwLT2EPfxKk^L2`nkxvLnwez(?|~uNFgwR?2W%OM9JRa3tcu zZSsWoI}3Y%K>lwQ%4zrhXgKBm_{g!d_+@iUC6-KtjROikkID(w5L;WOX*4rmL(MyT z3Jl;K-oZr)QM(t(C@2@0@tL5!Xvy$9@pY}8POEuo%=~3s4=>C_N6Q1+!+K8u<>27- z*X)p+|1baU9mg_QU-NAg)$tt{M;N4hsN8i>+nKlX7zjVJRj;HsopWooOF+nz*=4+l z;uw34HJ)N|NGjEkK$`bZTDlaB=_Kgj=z$rkE-itqMq#V!`}yegQ6O<^>c#xQVH2{(ldGzbG)6Th(d7BJ8&Jlws`!Oap`S|qZhHIt2R@wRDIo(`#(1XY?$$!4~D{wgt7)2c4*X=a_)5>XB{mXN(%Viy|pVRMUg6aaJ$W5n@|5peHEHZ0WaY}i&Cus*f70K% zMpR614rw|+$L?mVMsWz;8%pSqp0LKE==nMd;lT0_!wokS&5Oz|g=7mzm+QzIN|7RW zRPbtqW>>wCTjg9C-A6kQ2rb3;3!k2_V|h5bFsUWPk10# z9E>gW3V>y?E;s&`K5|5ZhcAXY#~XPqacudc(JA}vIJ9}m*Z|PfDG_@b zjcd^Yt?ASqw&+ulOsxM(wO#iA$><(jP;ON&A2~I(P(N_(!SHv+jGz`K`WX>liI~SO z`0%1T?1>i5QJmj$XknHgtCT!l#8M<6rh?}5EB6)g_ zmK0be)G-12-ZbE1LVI{&qE)<31h{Em1@_G7eUC9(R&Q&2EbT`dIK$`_glH-l(W7#I z2~IC$Eoe#V;lyNDJ_$}&U#fz{?B@R3xw^W}jb=KR@PO3JFO)5!CUlYm2) z!54n}YfEE<=Ag<08%0Ka!mk&+D0*V9L7jcW>wnv>5AMo;0&TuZv9IPBScySEUhco4 z8$>*5e7U>(<5F)xQNMd?&zA-wlL7V2feDfTL5d@YQUkL6&ED3&W5NHDV&`AiPO%H_ z%%LmoCkJ#)%6uF+Jf(av+3;Qor3nN1+_xL;;0);mee@Bh$@tO@g*dFP$hXynb^f!a zVe6_>85(tvbF&m7=9^G0q24`mOVSQtyG5aiIZF)AqDjNhsyoTO5zRM@F?dM`gpsQP zFBEVAgYj=p7nbZd&I4Oj_$r%*V7iO>+unQA_P9!njv|gM&XnGfh}BO$x6a+`%*T$$ zes#GmQ-waYDvcZ0+ppS}=nIIG-(!@)Gt^G+R?{^JK0jfS4$Xi3)jCUFFvvT$qE1&^ zEe-t%Dh}iO=w#(e7uNkLm26fXYiLdFd2x#2iM?>}*>NjVeGB1ht@I>a<$NwzF1ZrQ zVlh*10ULCtSkCTXro_0BicWOvA2jZL-HB!#J`#*BF?*j-!tvkBup4mJlE@}iJ(V6a z>X(nj=J`f~t0)B_q5Z=&m=J9g|5N=WD9R>@TLup`sys8{M|c_;ZrWk?6~?Pm4-_F< z47u-JViwp5{iqKGWnV{Pkk?F0V+F{*t4B$$#9x2Cutx7YD0`9cn^DeN+4O10OR3q% zj5;O;Dkayx{4=jsDc5Gx!>?fZlNY^rZ|1J|-XuF>u+RMs0sYpIkaB7OG4Q{byKP|q zBdHUuE#?74_W&0>K0Z$AJ{_o79kP^u`vp9VF`j~H`2CP={`=*CgKL%pG<&pd(H?T_ z$eozuSI%$PCtl~1QNNHi#c8bl|5F|TRi~?v1=qJKfcJ`tfd*4hCuqzpf4^@1-`eo1 z`M@Mb($;UEWhfv@=Q;ZPrp)2OG(7&Dq+oOnL4WH4 zxA9M`lr{K%6nOvY;{>z}CBI1;(*B1!n>^`BYKT&MsYsU3FC}*^?}#RJu+DytZEIgI z0IZ4kvG(4gU@iu#r|8R574-YL!+M`;PwM17>g+vNc3!FxwelfCBdX@5Fi@db?C*YU z|KoWAZ+Wxk%a0-{L);5uh_ORLOk}V_*b8zDz&IpOT58^G_{oCoyC34X9k`!Ws}5bh zA}F~pk15H3GdWykGjSO>jt*!JZtSZ$F2Mze&49uVEL5rLo!N*R7t8H`D(rb zwF^P%9Ii%!yc7ZI-xW&JUdH#GM=`YmG!iQ@FR*wT<7PMtT_3Tc%2}K!$&%Vf7z7e7 z6XdpFTqRJd)3+Cnkix%&B;iG%I)$)V>D~oalSqz`A2Xr@g$HIq+aaOQu7EXSf$%-Z zS6Q|Q_a)oCp~1x$bJy$JbxS|W>T2rIF1pdy^KkN61Z6WgTTvn}KK+RmT8BD$>W6(9 zX#L~p(pq6Z>!}}!Ii*+g(r4GLguhg7v=g*^o1&E?E3+}x*?#uLB!>m}YIu#P8$$DlvP7i51h6Gyo4 zS2SU5ykC)cfb#(N<%3%pYP8ioO9z9~d6&IvIPbpa8v*sjl@9{s>`4PMUek29F7EYs z>G78VhfoFi1K|kIkOR{g_lF@xDo>L^GL0kokv!Jhlmzxf3-6MF4gF5JX%@4D`j}OO zEO9KOhD=isZ7`z@hU{~Z_cVt}%I}y>KjD4FWkOaWHWLC&Z%Z^&K%#DkpHK!U#{+^H zdWE^-uF3b4LWSv!`=00`b&N;E0|7hxzDv5J@ahmR8Wg~0=|A9j z-hRLPQ*d_x*obfx$&h{iRbTv`5R+QvouqP~#WO{=fgm2kY6F$GY%r}!3Xy1xkCKun zNZ**u38-%$R7Z|jJ@-Dvc}qdv%A3o^IUfJ@Q~R$Q)vwOC(RD~8XH!4VYe0#RzQg%G zP{pPVZ4CE*e-uebDMU*13_ zR{uyvMvwA`BILkTVclXvT_Hn$n-O_EaWYC7NzwLAsd# z0O}FjZUWW2Z>0je!-8A+$;`duNXU~dixRr8U!kP zTm9L@WO+0^Cz>>%!X z|MThv%r5KbO6;eb&wIFw@&CP*anUMX!r6=iW3se{oqG>#b&@@J4o~IVBP*v>(7gL~ zQ<@gs+E0DUg+fWI+-p`7H9Rr@g6t$YJ-*YVTKgIr*Yya%*EL~+u*I`54cAwsz zbaX@WfZuNm(W&!!AZP>rV@d2dPClw*twj!^rbp{6 z4{nQePtnM613hJ?jp@}!?7wS<7W|iTr6Lem1(M2lk4R!lEK*86qX%8IzL-w+P3$8m zL~rpdT^^n8uEISIMfT_YC%_g-1AepW32+)fT2Fmk$2-)5U*9#9MC3Nn3B|ik&Liy5 znM1Au=!h`Jj$+oYRDZt@euE?1k}n@u5`@%geX~Q?am8xX80e{lGgQ)oRED$%nj7B-!$Jit z-l{6-X!cKX=IX9ZvwWF+r81zI%+^p!Ua#>a`a>`64aH|noQW!KqUEg^<-0F&MNIw| znFbEUkm28mi^rWe7Y5Pw*VJgpfMEvl4@J=3x<60eegRqIoq(kB$`to0YJqu`OITqf zeMeiMw=(dDKr_0koDdL`w!T8f8L8NXzkve@8gs#tTiA07NZF~g_l;7yTv+n>$jh|w#-P0fG>W(p!3g}893f6VkRSE~c0n+pM;ll_ z(mQW2a?TWAuN^IV^ZjIE3MS^1+tLLtMI(IokvidbBYO3@H}$%1UReg|p7Xm->vf;j z-qO+c?q_!))fmtnqvrP4;haH&7l?g^*q>~)i%IEJy`?4Wix>*hqpCWgQ_)UwXr(Wi zz9^)gAjxFH(U8D4&3)F31$bJgXH3uko^EX3$lJJfGSRu9d5r~5W@ ze5pRI@XOi`IX9wM)7JX@_i1-~rH8a#N82fVHnLDa^64`y&bUCNljB9y>Xhsfnk4VQ zdU}tkqWZiT$+BY9Qzb-Ti8Gq%%(bl&PoO8VBvzhn|N7(pPfNKe`;sXsy?IOcEaaAN zr_c!j0|5}x4+3`M3pFpB^*>gBr$(rLy(6K!?PW4rS1V9nsh*LztNd`Yk6&o2ZH1P{ zDP{VXQ|~UTP@Y7(;*7r(@g(MIVZ3-4wvuMJ%d&DiGaV>m%Hu*><6Xo$}Fp3|nE=Q#WfiKuo+11Kc)dS=6nx@awj2D=A-2sTQ!bM!GonSAo$go9|6nYk zH!lrD9z6pske-}7Vt+5&;;~l^>~3F|{BCADLz*Y#(#`CbPU~{2L>pCNW2REXZn8sJ zw+ccr&3>#U0W1~)`&t%szXNU_?zHEW2AH!6`zGMfZE+(Z8)8S`s}iAM#ZXBQ2UGFb z(~-xqy5|n6Ec%w2?wbjgW#nDmeL2M^pTruH7AM;yj1>D@lhw~%HI)inFK^6&q!aW{ z0!#~dTFcwRi~dgw&{W|#DSg4DJc5iiDg)(fP4r8Czxpk9)ckGJ?(+auRSvJPVrFIn znjcTOC_7gIg7+BpBxc!cjJ zpIFIQ8pUO(Uam5F?D5skeeJXbeI;~r4{44n*EZO|H#|2l>Kby( z1ubrHUf|CFI_E^#<)_BBg)fFhH*T5Sxs0ZOhX4sTSGWGn<#t>krVso#VA^nSyP2=o zyn8*+YTeMt;-0m#Qx}yRp;G_4XxyeQN8>^=&?DH&=3%n-WbMM7U2*$}`v4`xU3_WU zrJxmNe6v%zI}NRfzh^4ud}jAxyi9^am$nF1MTMeqq*UZj{_RUf=Y`{2R_7f>SLAoB zMDgM%s^#*(oOR&Nht0sS^luP+B*>1_)gLXoo;CMyY;B}_3WI=0 ze9SgPibm2Kjo_V9Yph_v7Id5G$1VxGIo&Th4rr7IHZi+|4~^dCawwX(&DB>@vXFK^ z(b#MK&25AEb&DAfzSppo>&E@;z;5D463_6ZL}D0?Q>sK{QE*J1qznnaW2Ya}YVz}ZaRXCJUx zS_;&8rKNl9N&50Lab6CZ#5U#;zcuBF(AXv80y>jP3Ylq){qDR`LKC!}qm3GLg^YMk zriX}Q+erVk`rRz9RuVGDZ>=%tM_{jrh4Yk})bxnp^iP24MnK1ehZfo)0T`pivVIs< zsw<9exq9AS@q+pz8%-_%1PEoUUW>UI0y$l#tjskV_$Q-Eh4I>qlqyI7uo{k9PZ&Mk zJx8EF|28I&i~sn&hj!J`DUDPNs;uLi|U+aTMZFSp89_fd z7+zH7Jem#v7r{OGK6EM-@X4pB42$(2H%7OMeukCG448F$&xr)nqp$T5vs>py?30r1 zHyf})oyw+wW_*8l_a|*PNXP+(+w--AH)6Ri5u21jL<<+YwDKGs4-5&>*aP1M65pVM zJ?xv&Wm`0zavuI$;yhU;Lx*T(Av_tYAl)pQv1XUPEaODo0mqF)Ark)6`CMB5FlYHxJfGE z9C6S!b%#)In&+1KDD6z>Dn*)NH|y-?X=QlwY(nc)q}Q!f%t#%>;YL42gcr#$A9X|R z?XE{Er)`f!95ECDcno3%6v*4-KS#JzWX@e2mwbObzjQG#HvWHCTU0dvM4$Ui`u?}# zxdvXcN=KGP4;FDM4ea&{>>9FjgfD{x8H0#vpRE1DXfKaSVpY8S8L7!)Jck>qTjYT- zwHDn=(%8|-qI0sRkUx^_GI+a`-OJ%(K{ zUP-WCwwqPJ$*3=iKtoIYC{cBLy9_r`av4rWEi9EF;lX81&3k3C2~U#FNZbxIVD8@| z{&7zFLqyt+FrKY{>6Ox|=0!~N-wKLlzTpGYQC(~l08@bW&JuW&8-OERa?LEd!VfcFhs51@}EDPMVJi+xEw| zTtWLCC$65^Q~I9 z&et>tb)6pqINouPk8Pc%>Ry*y?_7#8h7u}|En5CCY194S?5)^zCBkW*(nsh*rBQV| z*T5V_3x1-Pch~zM8|;6Xf&g-3{aOrfvOhN&H-A~z0OO2XE8>$|T4$<+nmJD&6BEh$ zGxQ6SKMP;$sUq{R%~-N{n*{UHx40dFn`Im}o3;>81oE-g^z*9n*;iAu?!B#`-*eO)W-X>FAPMkFj}%Yx$lXBsRdK&YLe< zQkEZ_w^&{@LEYsd3K8!-$e0=dCdigz>?*Y|c?++gn2D$PE&S?d*P*>>)&PInQ$X(T z&h!eEFnm%FHu8)co(=ES67;^~J`I1ywVnGSAeg+R<9Y?rX&&uk>`#f3e)=d|ZqPM_ zIIF=7?bf)O3c+j2weI@4=H+{4zwl{6aVgjMgatZl44nXy_P;jS_7B%zDU-Xlbr1T> zW!*jYK3&-}TaR@>xp;-U!fuL(PZ%vr2ER#yT$hobxcm2=-@3QKo-^Fec83Cz9bCI3 zdZ4ZiIR8O77nl+il4?g0btAR{uF=9~b^P1xjj0_s^lV3Djudoni$gIQ#Qw ztOH4xzITj$)noy_J~KW$enaQ~2bDw_T4lKTS-m}bCv|QyeDRLVivUFu3iq!M(7=~X zwwUdWdpnIWpVehwAJ}1TO&bf(!*gFgG}8O)BBhLBa)PV!&`h$cax8MK+C=B8=<*-=rPvmS z#kap=6NuTRt_=@z3w0$@B1&ZeCEGhi?INH5kMXVLYkxA6hUWQZ z_xIwDAJ@5P36n4Jr3h00ubvImio1mVo|4@d4%Js9`a0=T8z=<6opdc|f_G*1=u@|* zA@A0`%nQQn)w)0SnJ}2P|9~`{hh0?B&g1(UtbeabuVLo&pc#f{9%=AK8moqK$+9n+ z96g_G4v-AE;UC-<6;Z1^@7q}QVh?!-ZmlpH@TQbMk+d^xtowRckdDv;AFm=%|DsCj z+ds3`OUOL48VY#AqVbO77Cu^$dy|VgJY7fer|F%UP+S)6nJ3U*1IRSfClfZh>xz~a z(ZcvUI;d)#CW7|Oz10?qGfb=p|+sJk4wXwp}Y&AL~_7L4MJR&h$B)GEE|g&b&y zjRPN!C)=K!oPRxa!ZSulH4I*+!vy~=l=qaS2{9KjCh*XKpfC`99W8{&z(xq3H2|Ju zH;X756%6&Dd>fb?oXG3_T0aAggG4>lA|QZj=^XmEx6heeTzgKiCu5hUApd0)Uv>nOn7|6EmH1B_E(Luj(Ee79DqRt=E=}3pv))X>sd?(teDFyB*%1wMs>tH%<|}mx=ZPPB4t_2HT98@j>-2Mdj<_ z)IX|F%|)%*<1GfPSg4;Dx+F^3_{P348fL%N#R~?W=SZZgiZNQ$kkCT$mxXfpELxv) zLkzJVjupj)ZF;s4Y<%h^(ISdyl6b>Zs!Ki2-EF}}ZiX$#e~k!|Z)TZ8ucM_@E|;T5 zc@DL{Ha==~z=7>yNIpQ(Sbg$wb%lJn_n4z8f0%!hnU1>q6K(ajMyZj5+bPI$+8h1}`3Iu)?B*RcH!Ao;p)T(;wEeZlqfGu?0*~`Z9 z@|ye|__X(#y`wOH0CK?Lr*pciU|mct1Q@xBjIcvE6ZgsN{%Ev^^2)BXnd~JaEtEWQ zvU2qCW6)S4MT4fRQ4~NgdWSb@+Qz!*-+Rue$!}JBw2pSvY~U&el|KS(BhWp8bS=QA zf#=z_@8az}hkm>_yS}b5&6_q9CIS%@7GC@NH-yJt=@AGWB1nwRm9SMN4g~iX+9<)WDk{RFtAIN}*OI{Wo_QlzCv<8aodFz1DcItY?k zHgmRo&LI1xQLO$VKd+xA7au_Z=G$wiJfhE;i0omZ)MnJekHz1(jfM;qPdWW#`csOP zYBHE8H z48MtIJV!@ z_5OVS`CYf$)zx*~T$S^BJs;1<<9@$C?)THfF%~1c`9-<@-_mmNr(zDW5;W`xoG-c$ zEcW(_yA8%PvG0KFNcZHpON;PBYoW0PFWrJl_cr5#N)X=gTyAbH@W%h^KnR#FJWif$ z4j}F5?nLB0dKH4C@{Elw6b(SWc466QFAd4Vx(R7q1*3)J>xQsk%zqi$*-m=7%4W}_ zVB%BcS@5QdCyayb&I(@1pT;$(3UAb_s3FdO@6pIUW3u;%sKW4+kl^)o1N2G8%vNQJzyIN-JO=@m3i;94VFnKFgtr;I6@DuaqE z_Aj=%DXr^bgeEDToY;J|aBCX2km78ZK5wO6_FOQXgTA!G6c<#gRuLbXQjgKeIbXh-)Ca&HJsPD9k zB0M$tN?$tX zCnLE=R42e`|G0wFpPJQUeE5_%?O%p=zU*VQzr?2oBTQ(4^?Pp#;fW@2^50D_wLKy{ z;-;vEuCX`8Ufm4%eBoh7;njy58coP)+Mah^ts$`^RTChJrQGmm?ervWd8JaxFYcsg zGs*A%t%7rcHJ0v!RdiKGB{$3FVQ-`U(waubZ=-$2>$8ageMn?pQ zENhA?L86ZgC$V}C zX-4soM9KUL2Uy~i+rM{z<_o{LwZFu+9fc*Id7;pYDlE&gT2`-Y^s{MnMJVg2{_yw| znsQ{+NxVKWWml#^;Heb71Dg{e-H8cXo)NB&;!*@>P87Y`u?b&vPFQ~(eiOVhMzYkb zf=uag)AAQ8K^aM+{sh*aL=3!~{Ojy8@MOKsas;XwU_lH!Jf8{|yn61~rD%H)Rho_jN6?FKPIpx6k;(dm0Bpm>91Ww#lj3R7Nhy)f-x8oLC)xr9Pew9D$1OE+xBz0{m zVmiaY35d|q4_Wh$BhJWynWWiCkftP2skLuj4|7XIQ- zZ>Gaha($jBU8n<+?h!16*)0BQ37kYZQH;C9g9oy7G`sc9aCy#MVr^Ib8R&)7Fee3oGb95;W-OZ3z!jB<6az1X>l3=H#st zOpIR$h&Gx$Z!!#;!;|)9fZFz-{XF{QycPRSTDTSc*Zcp@3#i7XpFUH?adgccrhKe^ z@%1oX*e5VE&4-7|xuQzEmpz-Pyz9KHc$xoQ_^U7BY-zhQ%NyriH*O#PE>RaydqXtj zR=iVYSxG~{2Dz6iCZ+$9iaO}~vE5|I>Co~&xuKisR3B@$d8X;XKRhudvh9Ku^w{+g$Z&zhDdgQ0aV~5Glsfs*w^|{W3KA z8`5~`0W_XD-IPCr+9;UFL0_A7vG z296p4&RPok7jyJHrSsW_EwK_pLthVkPD-qIiw!}O9Tvh?nvA;usTMY9Gmgil*l^?2qQh0Lpo!wpdF0%0n=J?tS^`qGZ>~8wnHr9H+w|J=@7_D8$^o z_+y(o+4f$XZalw3QX8){0YdlbJEp-sk>)l~tdM*CUnB*QoiNvA$e0}O9CNh~Y#ia>qY5YQix4En%ut{(t>oh|WEckmpcMzk z3YV63oFFa);Ds06kA&q^RGujmH>o>y&pih_v;R>;?xs4qPR=#OS%18@td-KnrJUrL zn-CfRHn8hB-?UW?z_@|rc3}hXZNdCTf#DhJR{PhbrZ>w?gJ=JOTYNF7{{P)OUP^a8 z)+xK!_hr^4lQ=`?JZIwDYY${;+dY{0E@)Vm2N<|tQvRMc&f}^4w&fnw4)6BVIfBeS zZ-U_!5Tj0!GK}R=9Eu@jO!q~$s2b9_>O&Tl!{LoAn0?TV{WHAyr%0Md41LZgc;7h< zLBG+SLzXK~Rdljl#RJ4va|J!H|4$3Rs6slIPR-I??{=;KUV5b$$1={{x0_*PBW9nKcO-mfhv;5xt+_csZ%`$9Gah;1sDM5=_6DDVJabxJOsANK3=@!QfuaVqhQ04VUc|Hd*9J5} zypOJOK*s$`r+3DI*u^HY{o)@p4pExinVVeZ%=O)_GkAj6aI@{6YUtrSbBS0{GAXl@ zW!)oTu!sSw7*H<)T`PYQkaoWO`E2~gA;?p!5H&asQYFtq@WmWlQHo9@7lJSROst-a`X-)g5Hzwdb$fe8%#UsHE$ z@Ma4c@v+$14{Ycxq-gnJ;w%t>jXkwzXj;rYJ7p&s*?-?Y;^QAN7xR9VpMF5&0c}}z zRZ^5BL_#aLe7{`;zsBFabJAq^+;ZhxwdQxm#8xY33l+b?{7z*4@*RhIXNMnKcOYDH zA*i`h7Fu>IgM z5TDqs6F+olI2U2J$DVJozLx zV)}swhwrgJ9|>4b1u0p@?0#j@K*y5!8~QW2a|K*cojS)|M&JaW)8~?Q2_6Mt~lV@J;sOOnU%uH>neLte*lCH~1j`J*|-jf0E6w#g%KtatSOz#3kS7 z4>P?SHSw+^6+lltU9toAwZKDd+MX(ua*;eZexBDo<@Ny^?5ZU3lQ}j+SKyVtY4)}8 zslB_zotO~N-~Ufv1YLV>dD-0nv1{SaX^W7ieRSgrN9?_zpP}%{g0{A872k73LSzZr zPl@?|NNha1;BOA$*`lk*;*|>?&J##&ZwQT6%@rUy2X29a*ALs2hv17<@z1vTW^y)9y zr0YNsq`BHozeR3Lrsi~?=?*+l$=;TLV|3~~e0v{2u{p+16RNL3!*5n(1e#I>vo`XP zhO$j;_B|ocV|(pBV)OBh0Kciea-hML!L#zlXPvfpfz$JSUgsLps4M@;b%E#c6|e}S zMhTQLAn|NJ_p(bb0b5eSbeBTC8cROp$A|EOCJp^Y^{&&*}D{^Tzii7}caA;jEid#7c5EbB4`QMF@LJ>W8PF#whY+Au9e-GEH ze8v`D+@{Jl1lXdTQQU%EdW@ng9(D_OB3dmvS?8j z2(A4UB@q|i9RZA)mC`}}p*Ps6epb&hTxSszUzrgs&hRFi6EZIIbGgbo-b3LcpzsKm zoaVJGkbN5L9i%AQAl5#gHp{{kKH*naT-xe($8?Cvop2atz$9wP2D2^oR}8G4A@=^w z9e8YeSM{|Yb*5aag=EQFJ*#0{5%5;_X>>D-OsbxD^PeQa=>zY>ov>1H3uSWKgXEA$ zqKw`uGgl~MuId$0ex>Tdl(riZkW4Y7P4$M_G=CFByCjkJ0*#`H>Dxx$VM#ETz8@bq z@;(Zso`n01+D)6yj*{#&y3CeC%rf3cJDHd!?VjFE_Wi9Y_2e*4)!}+cUJx#glo-y!bBwgN?PF?DskE$j= z+&i2p@;x^ztF~^8cz+#lX2BPdP(4MxVDI+LTjv|C&xk$g5j{=2%`jC(m}q!f=QGWF zZ=|~<4pDe1bzWn4kS8)Ey2aCN1AB0zRz$O9!)o*aziZ0mYFpQXd`~nsVA9MEcNfLx zSm6Ga<`=F2PY|qV|4j6@vsfrG*rulBzV`^30KWEjr<<_{%WeARkjFD!ckgw|dASj< zs2kJX@#(y`#H4#lW*}qz$Kj3AHbKfR>>;!Fcl;k^8Gk9OnmMhJRsI~bg`kF=VteIh;iQCT zdb~I}s&=-yqY4w%t_JZkKT^S+8xeL{K4d_yDNm$A6vpk&$2LN2JRbhEta%d)zz25F+rtC z%lkpk{Va2qEN2z^x_|qdl0?#!BGmYeUiIs>8~Nwqc|K7BFWfGa(TsLegm>73yS6$n zGjE7(8<%jV6b21>zzz7iX2YkTLwv1B62{)uk` z!dSXtE$lNfEVa2zETKImbVc%1NyVKg+VVL*RlmCMq(XY|WtH{Ua|F*<-447B*&gLLm z2PZxSb~F=F>~D}*FxK1?8iHF0jf{+dT&!j~_+P@=yBZ|hp-&kWbvRxLtS02E6d22> zw^3!@(=0l=T0ewwqcYZ1Y27m6kDa}>5=(j5WduZgCJ7Li&sqKcy~YAsmbqY3mH7vQ zVJ+PD!%F#+rn`Q1&5;zaa2$>>95nJ)yZTw0uE;yt8fX6``Z&hp@GzU6fP-fUztcyl zs<&NELQ9m|(g`hTcJQ?^qrc{qYf>R#USgK#B$P?k6b(UW908K=SEA#6hQ-ZLUbkiE znlW=NbD9T1hOeC-SZdptlW>rPD3|rTWKZj1*j>*2>8AbKDfM2+!s$VI0=phbyUl}4 zV<9bL^P-=a!}>dmnc;P&`XG%CiET8A2F)#KPyQ7?Bj^xV2cRx^?f8#oTd z9LtH?evCS)xsd13F!-JayM=kEUonk(fa(Tbq)&_Q0P1tiPdAeYkcsGT+TWB9xXYmf zvV(OxG(7#@@!}~v(JOMf`emVsd)xyIyPVJEOY4h%^7{vmD+gdswcK8%L4Brhv$nFm z;(p4$0Q^ZFP(z)*04L`}9fe*vI-sV3w+eB9Z#kFZ7_RcK?*^Kj=Bn=;l3xhmAq)pqN*{ppW!%B3u zZ!80l9`nSQ=ALVOa`#N=epKF#p-kO&`#MtNcvQE%snAQP>O9i8lfa(>>#&%Dl7S|} zNhk^ly?OnGO%}a;;eOm#hcSgdF%PD~rsrQB1SVR81Lp8+c;b{ejZ8y~b#jXk#-SP6 zZH27aQFER7gm~8X;z*!!X4U9qWAUIhpPfDC9@9*Wl*hFYuKP?B7mbd8o`}EYFmyOJ zFI94#eBNr6St(%Ux{@r9TV|fa-Pt4FNX4(>kI6ID&?)Jhh6uygBb85Gv|rI@Px#Mj zx?vb&0+x?S#^hFp>)ihJ94Lo#eZz-9dSfO_%MO$guE|gQyOUx2Ik$oZoNh<7_?85g z;McYS=0C*0FP1tKnb!=u)SnN?5g(8Hys_IaC`>?6EK5=JWsDs3gft&dS+uA$IWGq) zkX$Xv){HdjzFo_9!&XNk{#7M9g7LSUQ6p9xHM|9uk3v;2n9_)q=I%2Q&$%w1;X2+C;ma*?ux{_=s1sT!+i$an(XE0j7JQgn5&sLM0K#mahFqdg3ukf?U#)rQnD0JA;Pk_r0#S(a(OVlBKg`c9K*#SSA4`tGkN#PEqn4o@Tc86-?sz5 zqEYQsk*}f9-21z%ch4u_e@=FEj_1PS^{G`v={|ukIYM6?+kJXgkAU5^XV_hz5DGtD z$$Ccwat#Cn5o8D!alg9Wm^0Vwp&QuyH?eC#euHv|Q1!~zv0;$Vw*Une;MaS&5YKk_uYIea8viw_G~)cV z>iJH3N5sXs$+ZNdk;4Rb64Jf|e*J{981XdH@(l4CB)wO}jQQcOPhb2M^j!ft1E54b z>wDH2elT*B{DREsaJyW}EWA1FkG!hY_e4 zEOTFBtohcdr%>cq!+!{jFWB55lS&Ih zp{IBs^x!slMBj0fJC^Zl55X0M#p()M8rruCmtr!@z6m64eCOl0?pLrxVxcD((0Msa zz0f)WG)|?f5-ndnI?vmTuf+*T)m7MVrO5XOiopHxHu@y|agoi0xfzk^Qnoo4f&SQ! zYmeg3!2enNqbBQN#H`9f+sO7u=7r6JmU(gtu!!`Ouhg^DCZP6RwIB#N``2H?_4mf- zJR1s8g!a=>$*LORF^)t%!>`}b60&^NwIKx0A zfkkePRX=0V}ardu^UY(Pr{zzrdpBDEd4k4$F!S4 z{h(2OODW|G@4}!%RKPHv;!uSx*nbxGF1pKRg+9qRJh7bh@PV<3UAb};+Vp?mL-UfT z)*7ngpsf_cylONUd2V2fGq8;?`xNLj^R-=K;h+6*Z89YR50A;4KSl&yY|z8nxdo*1 zcl$D30(j^39Nk+f2rT4#=_4F!pXx$Fc?mz>%uFv}ncHYsb9u-kP6s2F;1|d6HGr5! zT$BJtjhg5xaE0p#-cOQC3%WR0_GYdJxR|oCmMdVfmI2IvSs3gtj*&Gjb6c_#_%2HB z0ZP}@4}wYi1OX`lsBaCxg{cNHr1J&*+G1lVI>CC4qvKtqBxBIrb z`8M_eZ&Ew{-s&N(c}dm?=ErQ;@*ch$gN`^QK3$-2Tk*Yb&XKJSZ70&v*$dwnQcyj; zcX}-SeSu@=$!Nl^dQrgl=XVOHQof$xi%$OqFkk!&_;G&voLoE<7bkmhiU_^HM*xib zbSL86sP1c2XlJEh60R(ia#UGve%13L*X|6b>U(H+AvEUotsU(co|}1rK}0-jyCgS4 zx=?4k$NR45gBOQvr)br4E`5RZwv{S_7e|TPM`Ap?NAggZG_SqZglWBkPMKaEt z8%;A+0!c-6KOXDsHBWz87aR;_9t0J?VX@B_9AKhYxql5cH&sdrkJL{;)96->B$`0p z8t4^xJc85zhEDJbgu4Feo%)|D2Ba?mJ>||Bey&ugsnO-x-0{xNyQ8|9)=x8GX9g+U zcD}nF7hdOEs0dfMhT=c0jW^u#OJ4DOJJz18dJruExIgwo5J3!p9^k@N#jR!g#CgD< zEnQW{0W-p!scZqn5+Oey2ONf~c&d~OKk}TsQj@_vC~-o3@?iPBzl+7F=gjxf8~c_e zwSa3!U;xdWw213vh;%NR050t{jzIup1|a5=EcVvi4A3X;Hjee{-47V$nW=!h@@wNj z>{{es6mWHXD&Qn`yl?i2MXK{VLTfPD2!{1P@}KjJAeQ`s>+~Jj-hT#G1)tXIq2zBZ zyT=}|JD+#qY&MS~F(!4=cU_`sQr}$4S!{fxu7BnwQjBoE|M(4C9EZ92E6n5f$3CQ9 z9&C2f2v?LVP>k~KK^0hlbK3Y?1G)!ZTq;w%Q@vmNl{b00EU}P2>XLSou3^}KKIzIg zv*6LPZSb`Oa5k3kXXgZKKwb^ZW-|E-8-F$d37$-c0`jiB4OSG6uKaQ z>{8;_NH7f=1rRz7q*+%@GP!HUhfA8<%dingVi&R9C+*$nhuz13<^512YAZ}!)N?QyPf0iivZh;aaGV!+&fZ% zTAI4aK%_b)ApM<~g=<$k`!q6l^3NAI)H0>ena!Txam=r|4?+KNw#GLQfs-Y->*i%l ze}%gG5R3vrX;p%h1j{G$ztG(93VOv$a4lbeSMGW=dQ=9U6OCd=;onBo-;z?^q|Vl?E+x6H_a^TX_-m-66x&M5ds`p5 zynP&e5=|bP!_GvSkm;w+Mm0()hZV*le-q+xG9j$+aAD-e6mkA#*tSJ&& zICiVyfCx~Lw(!BFRo1iTe1G^P8rLN1g$ssS)ZMlYhsfUQ|JjW-3atFs||y_JY{@@i#8g|7;u z2B6Blp9i1FJ(Xjms80cb$JdPWiuX*h$p^gn*Ydg7M{)x|73W&s#P0u>3Y(E%e z+8w7cWv0wWk+6|p2XI(i-&<<5f;TNGtQ_VVb-Cb>;be)W6@B-#_>;V{>bqArwJgP% z$w{N$(B31Cj$9`sD!~Y-sidK{+?=y(+iV|qnhe)DJM(|ctggyXk5Uu*(S(VHwC;*rcy;pGD;{Y1s4X_rxwKO* znCd6h-K!`&yVYl`vLu^1UtE!5;kO(`j$~cQbuyWdrZ%VU5*cVTw(&6hVJ z!|IP@^67f(#D&Q;_??=oTw|Q;Zd$k}*l|U|+^o zcD-4~Yo66Ohz)Ilm+A25*Lcl00c=k_l9VIE+XLB1_wWKuVHph6~7+Hf^iL*$-nPmXpU{8Hs-j4eNiIa%X50iXj=on)^s;KnzI9_#otouTdqU-oZ zLELgO{f|-=r~O@?BP)?E^6~!7{Z$rLNja5D+2X~U*R!>H6q3G?NAp5z2OR$zslL1T zns;C2f(wXaV#FVb(Fq$GT3(!Hx~Y_pNRn&JAFC`l_s`ENcPwO#MH5Ro=_!<&J-wsF zTpzp>wRBqaMEncet(=#t%nqwJbALKa``C1Zvw4c&dqn4y>rS^w7rl_tx0a0&vu$u% z@H_efXlwH8?vnwT+)phlhdxfp0N%hz^h9v`d7*fu*|By>TNz57o`?y~4JE zQ}A!@evzsh^hoAU$?=KwgpJg--KFoh&rdO` zxIxwPSKxaBKB04Ac$T?P+|A2>g0#XsL81<gH*&u6yr23dr>Xd1dpeY9SH>v8Tim$qlEO3z!1%xI=Uuq<6H$EWmK zW3%)W6coT%BAR=J*5!4RR6FKc3yfHfMa;!F`Hif?iI|t#FM|T@FvAkQ3YYu2U%L~3 z?Kjut2hMb*!akTFp(n573!eultN2lOv$82vAse#4KzSm=&9Y!PlDStzTj39pT%qkE zO^$aN1rc7TCPmK*+F#a#U+Y9BRLxVxi7LH!f@++nXhWI{K74&50uyX|WKD@=S`0%m zS;rrcASX&1*!(kj9xQ9Q>=o*Iu@sOXqe3aK=jm72=|tHTvFgF+98C?s`Iz@AT50v` z{SEd7^q>jdW__FOxMJEagg)+zH_J+LYuWc?X2p7Yv#a;X-sL*kzh+tpFk76FoH%ZJ z>w^4v+!*Kb#EQ4cy}2I;A@aw!>ZD8ExR=$XrH*aOp_=uEze$#TNJAz%NnT4&i5#I!nnFNB5n?) z?32p*T4K*0sl6x|pVY=b^lg0te}>y_cIQRmfNtw|r|LbtEU&ut_gqXulV z=LS^{b_$ayUfn~&r?kG!-d;U96p0Cc^qY(X@@sWB=ft;_;*AJGx;W*~O<~a}>m_=0 zz}W|I5UQ#XBQMa66H+(-utHS(SSJ3K?#X+(u`0C~F`vD{Ai@{p*}~a}CFgsSN9sOJ zb{mlNfXHXn^TV4039kQ73%~_N48X?pY%9#?SpkBVx(92AOpc351)ZO!Q zd^avV;#4Dt*T_ue1>=oDj)MF7NOy~wIHSkCHxf(SHKZI>RdConlo$smdw!eJnjUk=@US|z>n`Jh z>UsY57*{X)Pd)dLA>NN6AZa|m$U55=MOi~VeJ6G%H{LIUA zYkj)Ecx}gRpl6Ux$mD!hIckB@muo2brZ*7qRo@!Ln&k29OuZfoY<7=}zWU#+rU5{j zY22sIMdIkIU0cB45_i;LBNbAD%!OU7mZz_RgjhN<0LDaY|CF8EUi?Z1?pc^C^Ps&H z;|{1xZYU6(?7j7*cQB|=6|o>pK&Iv{_gkG^vE7P5JjXg+T$m*8+X5AlhPbWGVPn6bP(z; zJZ_8%fIw1z{hCm2e`|6vwTh+I$alY^|Gb`qC@C9|q}*van9$tLyb_#^k=h*om1z_A z?NN^mpb2j(i$=?V9t(7EmkW_&$KfF54!mo%>FuPQN1e8C)N>(}MfO~02wr!brcc~z z;UMhBzEV(-nH}6|sO}FXLSHv9=gmV+Q1rO<`d>)%CDA>#tmAmAnlg%sXtZh!p({u@ z7f%do<(THN92m%CM=5FiagU1A|Mgh{5@NP;D7o+SPs*zf&gZAzfhDe4X6FIc+~xq7y{YyiMhr?($aKsCq^SM%}){cpHEBb*i~ zeWz=as!ND;_Mk6U=dg+WSpjeO{O!Z5aX}nS9$C9__SVxBRfUX1e{yG3B3=wxoJ0qp zso#o-Qr~WSum-8v-PY8P?i2553}`ic$!_r=yr{o;TzQzg+K{_SUL4w&G(_*DtYQ3Og9_L4@ldtfRzbs zTX=kbLA$zD?vz_wFB}xjpm8-R$5@lP#YwD4yg=o9mX9IU`^ua z$o0hT)Q}8sSz>~0tfTdQz?0O>vkG5l+D}(DiO8#^U&hy_&)NTNlncxAeoPRSM?7Lz zcyH^*ZU{jb+m?p2Nf%ZC&ZdbkJLMJlCMCf_JPxI7f;cf|cfezB%nAE_-#x*n1xm8u zOy>G--yDYiNFKj?nR(M-ZJiBowjTP>tIzF}YkI&!ph0~Q3|`@))cDtF9zMFj-P1xS z{BVJ|>-^X?{B%c$j;wKhj7bW}=zxpIWdaINdDRJnUu&d!E_@hi7x7c|;>ZZpN)Jm; zEF(hd`*B$25ka57_c7ruR#k_<&>xqForQ&}xX76H+PRnR#VSdJ91;8LpK=!q#J0fA z<_7?~96Bv9v*MqX(&v{iXPJg-29@ypS0C6Xv;?G>Psp9A%pP8WtA05M@FTk|mxWMKC2zq`%i>Zr{zOVktA$?PP+jQ}X6c2~!M%ZWp4i&Eu50rV`CA%>kzh`zUAU61rMAPG%N<8XrRM3@Y3ft&0&F~hz3!!HVrQ-? zPDv?$Rhzdm(4aavgWN5t9x0$oL<{mopkGu+9m9o zG(2fl;zQgmSUEFzisEV0l=^`AfKSZt7P)ha-AN;tXY+*C-4z|AQo<(aJ!>(ke!%N( znp{%t=C5Uwmu+r1LzAD&E`A2gKJCtyks0%wS7%B{keZd^L}{Dii~%IuOokIpI*0H4 z-HE1wzqz8SYiE9ZpS>%^JN(TCepgF6@QB6&W3Vms$N~lpa&C0#Yadk81 z`Ev&(c%?1%{H>0&9K^4)ZmLlyuD6x6bsu-j3i92js(-XOHF9>^GrBXihvZTRnN;a} ztzjO9;lHM5>$HHm^>3gt`p8!32MpP4KoS&7GIzQYc9HXZ9U04;((YSj&rrkux`NcD zQa=QXdoN^RnL9E4i`HrE#%q)2UnLcd&Evo8Mch9-pFG4j3W&iX#wB;cx*;10S^2=s z%$48-)-jB#CW9Gd@&dJGLFH4+gXw*YzoOeP@76Lsu0fnKw?%4pucg)F{If`-$JQ*W zUa6da=%64uE8ih2)JgtU8rDHxvwY> zv0SpGGIqr7%@+Fx%!a#e__!2pknO|+h?WU$e^s5!hjo2(HF1&Ph1jjLcFt8ewq4nz zJ7h!aC~N~AKo_7_b}>zK?CxOn28@U8@wQJ_Q=Ti2_zN8EhmiD1?L=oh@q2k!Ub9VO z(Whrx{7_j>G5GGv`HpfL#Q?cdVI9Bx!0jXNj zydV5?{Jl}Fdtn*>;m#o25umjK&rgruK|=e)6CAaeFXupOQJ_vkK-XF`M~7&0#u#)9 z3_=p(+_L$_-U$|B@EHzKdk}F^vwOKtz}^IGaD?tpJUrcpM=YP8ozQ6YP^g}Mk(~?e zyR7ZW^kR={EV>D%DwK51N&gm0!!LVQGjA`?DY@<1+ z8cWGWF3>3g^Sr$mtg1N_Ck6S2+lb~|YSy?7d}<58110Eq*nf)3T-ZF)Hl<;A;s2QO zx8b`F)3DEHcVh6vkJJxtk!*4dlP}r*#ARZ5wr{L;uz*%W!NVZNHL@OwwO5o$tND}y z4nPVTxus=;p@Mxi5ec7!{uH#b&%f?X4Z57OlDdw-!!eCs+dmd1bu3J(+c{4>p-R;d z;KE+hJYl2W7$P||6l0r0FG z7L?01rx`@GTMMTbWZ3Q6nZcl+mT4R%0lBz@9o1e8CAVJPZOc#P1~CCHXEu7X9_?)t zn+?SldB*8zhR8QnIe`kyf~7$a3GCAKadA}Gd(f%;x}REpb7$j^A(?U`x=Kd$Taf*{ zJS%Kd5PsBF=4XBs)QAo;U_xj0UZ6VgJbTUD<7-dq~*H}Le{m-ACF@klo*?PJ77QP zv@T&yZiv;;xx3!EfvfG?kaYzd#A%(LcSeOul?8lRr7q@$0>2Z_lmDRy`%oXJa_ zSnT_`d<;aqKGv1NW<7hbmEc+i^61Vrs;n_elvLtwCXU~!)$n`r?ry#d2QUJ?Oh95OMc{lJvY;Q9NtuLC)(@Pe1ha&ljq+`%jZHrUWW zxcg41;3mYHFejVFNv{cT@2bzCKKidJ$YoTvtwu-65+sMel_y9-c7l~p!A;c{ugS-k zZK=Hx^uS5a-I6j+oH;XuHMyEMaWbK!toKbOJ2{yp*?QeuLBaLvUMNfGoTK>aT>z5b zk@{Hztfuto@8IMmZfDs?KREPHVWjvMPvJ~Bk)A)OnYAc4L68(}= z&MKRY{Igpjr{1Hp)B2&V+3bc=L*5jbC4+#g3e2~_JYAz&O7~lO-wXKdMgZ=v*=Y;d z?WUn8RX?97*)wRji~nv&aLJde{36Yrn&CG5i778gn335MeIs)D_z8IiOp}rRHSn8k zes{nI05;ICJXAT`GXtJP29puEpR$)=)TYGgFH)U{K{K`rwj7UO&)i*RuMmdi`A zU&KE_EJN4^EuyUE0}mqyzmQN8Fax;jLD+)3(e~zOlruFSnEG(|FOC94od>%&^-CuZooFv$k*H?`Jq}r$d&I! zDAx4E$y~7XXob_>f=#E{uhs48$o0s~o_LfznNX+LQVT%+*NIw&lYpyYQH8`E>7F z$muM%YmSzoe#I8#&K&GyGL z&E#w5N8v%9v%L4mxyd!ae19h1FL^Ubl1pDQv*Qh{dBucO>ZX&8SC@W}f3UXqE@9F6 zJtajR$hhnGS+JiZng=oxeo2MJZcCGw^Rxl;!^gI6jaF1zCXZLTIs@J?YZtav3Jd-E z^sLxm_eO=iLkOz}1NfoNXo$ElM2dDO8s<7vXjkK4_mgIqQE*@q2{TY0nLelp#M8`~c9F*eEX_FP$d?~A} zz*~tFHGcK zy_EJ0*)BuDTxBO&q+tlh(XG48siI?KYLviWgQV}X&0cY7Y4frH^!sBDA|NY;v!rV0 z$*{H+4gjcH^=!=uj77k~&&9%CTG}EKdM5G>k)#Iyf?bF( zR&uA!FKCAU>a`vw(uFr^eUh~H%r)f(q|>rmc_eVAoJTZq_Cj%+1#hN!O7{CewVnb&)_4^gGDkE&dC| zqa&fo+OqtJs_fXLet)9&I7}N-qs|V_#h;FI4wnSz14@7Y= zIrydkO@hOGu&DBsYj;H64e~g9
5gxg6w#ed6BMIzQbz!xilw4`?TbL9C_I?wb{x z4SG+D2BjzmV#69VHn^BII`Uzsg)O}LZts_!DWYo&&4?f>Fw{ct$egp%K zvg($3TQN(rkO@^(&NYj%>c*F&I|jG+9SlQ%4S^ z7$#-np!%UI@mXdCfmL-uBG_Nb`kvOS5T)Wfvu7Kk66N%Fzr3qUekkfDyV&uGX^3&x z%J}zs$j#wipBy7AGjmNbJD**A_uZBNiU_630Ix5rJ%pzV8PP^693?*=l@?PKmr(!2 ze8Lq~yvmN#GM~r>wujQXq^TU=+zaK>9?4uAuI&H5b({4*!{M#-9ge9M0RQ%XOmObv zzG1_Ou-}~SkJ~Lppkovuza^w@nwwA}o(bD^JUJcHaesZhJ%0s0$CvI{l*;ef3KN9n zaaRoUK+LIFnJEq56Ls1?t`3(eZT@~My624ziH=FXPpg}3|DLj~X96o58x8;*0Fec2 zNWS{`pl|pvK>LEB?E%t?)iGOMJ9jkuPD0#2*oQ0RRhmcMW?n`s71#4ClN&S@Z-Mn( zJs9wT>5HcT4Gf5G4nIG7evXMakAH7edcGcYsxm9uhJQE4n^i zGWI+ofccWG{4={@=ZrcoyKPH>LA z+xp{1u%(Ib;-WsKKI_tojO28ObN0izdZ4Wfg}s#5U2=V76#I65E1S)EZq2moP!heU zxAjtM?_A0F*yg|jw-hn&bt`x$1;tH6jy^h|xc=_{weXU;>5Hj|ZiD5RM{m_x)mUZj zwE6PI{4vhC2{ALB%q(l*A0kt*&AZ(-bo(?1fy$WAbr)Eup5sbGH~o6h9zI1GB^#@m zSur%IDCUz?_vRsfTR8&b3roids_71W>}&zQHEoR*L0h$ub{`cCOHFwNtn)aTHw})x z>j~ib+#VB5&)D+a)k-H%99FGw-iUgT^6P}PIku`P@i~X4E4f|9VL}eUQjk_@Fjd zA(FZ`V8RH6K5nwbS&dF?ey_W4DfNKX>5*-9$D2)=y+=|NW!d}C-`^^0I62FInOjDs8y2vPQpKp_{Nj)#cH{9Kb`d4_GyU&&9T(2GRC&7yIV2YkI zVZ2Cat$RD||Hso?htv7^|KqyjFmc4hrkklvGp5eew4<5M>F$o{F+FAsV-wTe9HtpZ zH%A}sd++uBeSZGnx?DCK_p=|-3E%LYoDKsTR>Z&7f(pvSX3L2$@%F-fQhQyIm0P|zOY`KLC{ zkAaj-H+j;)nMv}y&G1KfbH9sd%R4mD*k=I1Z2!V{`};XksDALu7_d$kv=*hC+$TQ1 z2X*g;ZB9BUTN~Dg*%IRzrFS}0p}~n2pQH;l8;t1lX4(~=hJ+h`D36G*(`QgAZz^@F z;*oM1BCYsVzyl~d3-W^WBiV*M&E^R28J0$=+wCSwL=?`g6G|I~YyIyP!qWyyWhmI0 zI0v3sLZ1`J`3yKyJij*YoR@lx*%SrJ`s(|9{+1y6AW_S^9g^ZGV)m49hdRw3|Loeg zS~_RUaj9BcQmv-Ibo1$(W<X9_V-dt0|DU4(QGP zgWg=94)gi|?E*lWyZWaKp3=||NVLPVN7x-)8Yv+6g`{YpgFo2uk5YOyLWBzYBHNv* zgii(>O^7N%OQg*{y8G**Yg*DL(yZlAMnFq`VXEi(ZwwxiW9epoKo|hvNtPs?8x>Z( z1T-s9N%Q|Vmsl6}RjI=rz*{NvDEH_5!Pqto8nf+4YSix-<1z`ZDzloNFNevgIG z>+)|-s$(|U3O>1F$~}oi(JgaKi^9zaVn@GlzqMy4XTkxF2G)iYOEpjZVepR~Iyny> z(2rK^vPMi67!CvWW(R2wwjRZiR+;LlLX_*ML>y1KMzXHso9qM=IRpGuvi>p z{mCerT61W|@a1tjAFtMY)%Gt?y~=6A!}8%DWWBo#1$;xOQVw6$_o=2%tTi&=apv`v z@X6l*m}BcwNd0+hUQigHjeIxs_RZsjlEgwq;H>M1C;E57>xww8F*pEy#^z}q9KV|M ztVuSf{_Ui!Pe%C{qs4mOT#+3nO~-+2ptm|J#`GVq#qlf57P~KaDrInP(!c+|RIucF z&tiP$%RP12U0xoYdPV9}xj5-NsuD5*J`^uWU2MugTOsc$Qg2QI7qKl{%|UjRHQ09vntl91U)y+YEd|ZzUAbiRAp>`1H}25RWvDf{le~(OH?i|G?w~7Rd zP10bmc_GDX`ZBiaBN~c4#EWcNzL&4e#a~*A(vmvZm@L-w5#%UHbJN%;V-U(x;LMvE zvV<8&ThTtb^o!jvlAp@}Ok9~V&}q<3uGGlg8NJs(q`aWe3I$(%(ee z-Hg}WQCw2DX%F-d9mlC^J5T93rMwqA4>99!7%x7^`XZ7yy`|ZxzdIx-T4amM&j>-F zz%hm^Uy3yswwkJTjD>#l<_*R=zqZE8eAp&piZ)5u63eJN;}V8Ti;OfKU{VmM?n4#G-wY>@T; ztpw&HM7Ou7G?-k>eC()Sn-l0Y^kwn8)h!{r_PBT9W}8PEVqlvt!3R z`(~PfE>Nbh0khkC=i`4m2=6(3Y6lEum2oC~E01cwZoJ|tKKUoaBR*>nFAmqO`)V#G zT(xdaJ1RErU3JrozEs5F;pqmn*=AjZz%x#TRjs1Ztn^iC4wb{5{lfR%cAaHUJ#ihl)onwz zOPRt{HZBz2?WD9d%ukZZvdILk+rwEb4io`2?0)$kiI>bP^vrUroids_lY&L|aOD*j z+VtZBB-`0qk>ibzgRZQ$)b^*+`B=z8mBVb{0!w@IER)Z|H*{m?c{&Gjy>ClR9Y8;_ha$-!06w>^L#Yw^Na#FKd^ zLVcR8>5{%7pniN?j@5p*wGGOV??8Wc`@fX&*XILkugG<4;AoY|6;yKF@r9Q$WxKpU zfZCUTt*UqGII-*Ee5>zCxzZ-Fkm_X7EIps3sHH%zKsN0-Jps>-GGl>LSxyRGsxp{C zm4N!oh^=K}vXJ6@Y*^L4xuI}vRpGanQW6$VE6d7>!?H4I{|{#Xk122SnOHdUJ`KtIxT=bNyINUhYt0sOuJO_@)l)_|r6pk$#^4mb_zq*dFe ze|tDym20~@Rr!Zy`$v3(&H_7wctF-Mk3Q(`BVd7-@qJc_0@z8EmjgG~x%x`ssvIo+ z*)$=t1R3q(s@$fTdAjJ*zADldfv$=GJTxvwzFzq{j4w!{Q01N+14bGDX`TUkD*qHB z*hqmZ1V33_jY?JF~03re$&Sn!lCk<~aoRmW;tpK1CR|Y;a*kPz-->uTMsOKXT zX~Z=QaG-!A$d9MZkb|iYh^jCC`WZM{jvMv{##$e5z@8Ib(Ei>FBXJX-SN6{yNZH#- zRE)jiy&$2w9uco`O%wNxltq`A1#z9SVzXO^X#8i#+s1zWZqgM#4MlN?c|WPXIc)M% zXG#{eV4;4Va;hZTD}Z6oH{5>h5E65&V=7&CM(Fr#7ZS4rJ#F$c{*WHF7<(#bKcTd8EcR2^)DShnq~QiPR~@SuUM?$hmB(aQ%V|8>$7`vV&4#sC@YT zH5)_=VD$k)7ZWZ$ravER9o-8aO){9Zp{;8|LDO^@E$Xui^<|Gk!_N@biC(nWv#tPw zM z<+1#7$6iZLvEiljlBWkJepcyq>}-n}*t=@)anL(-+xLsUa(3zK{j#UJH-Vbkc0AL} zr>mDhH^R8xaBHg@y6l>E5lgY@L298Tav1O-bNnoi4&Lz1zcyfGj~+q!Z)%WAZXE6I zf(Fd&FF!WrxFcouny$EkDMIX18|4OY>Ii62a(EwcBtRULv|UvNp^%j?n> zUn-+RuB}n_#}X38*ujq>OgcZMtiFWz^P6inb$;Z6AgDg!ds?y`ZV3KdS=Z)`w`xZU zDdlmaf6~vAo^;X*ThmE8)Vb1__xe|*G0tFRjC4|B7Zfcp4(n?y3j*h0+h%a~lnr%u zZFqTC@@Y}DueOE)NgUVnz=zLTux?y5-~zI|%GixfoFyJO0${rOfXPAZ)!GhmP{-f2 zsfv_vbKx*9d-|^Z+Amq7HaeWOU)2UBh@ayCBLdJK#M4Rsn@rY|q^yAt58fjH_RJ!S z#UtY*Y+KM(wf4F>Yjj}Sy_~DtleTLx9N-;jr;O7io%l(V*`M}?n%5P@Sd>r4`U@B9 zRTgmVUQ6~zMSUNG0oH5)&^8d1{FVLW`em+0-4%PwLt=J9#BM~dG*`27*wT!%@n4{qnXi|3vq zOakPa^pf-Q*Ee4d+R4`y?(veK83w_v6bnd0Un`R`Uh&x{wJeV3umafy0AW2_0d%nz zlzA7nwX`l4!i=8;y;6BZy0kC;2Ry6j5`;MP>j<7H*fh|_alru8ifH0wYz>h7PApYF za}=7-{+@KDWx;+@8l?reJ=O9Kwc8muQ#v1)m#3AP;sMlU=CvDP5od^^u7~{doD9C{ zE^#9YNY!C;GfSs_{f6l{##~|m=Za;{ioMihM$h-erYhd~EUGRW?l2%PC{`t()*&?+ zd#pNr&jh$f5U&!CQgB2F&=+fVC$yMz=X0|Vcx*S1HxkhNHIthbsLHG7i#@4OWK{Lp zhuOp3%a1I;J@FZ@8({weXo&4plpE%41Nd)1Av#T4iCqPwi2P?D{{0uJM@LTHoxnf# zz_w|;nPsZ^cB_FgwqbFSyW%MZY6$&`?@?t-WA(GHR3^qm3!VLR(#;{+(OyUxU=|ZO zQLm-dfAe$9`h8`=Jb5MnrO(9ib(M+Vm*DHy*3s);{Q&`w7Zo1Cs?@6y`qj^;gOsYT z56>=3F&;e*n<`GGrtOZp7VkMy+H?3k7V*%X_YbQoaLBJCq=S4h zpVXA2^hm7f%}v>h@Je4F=`2EiRbzfaq|`|O_G`^gtR zkX7iwb~0}vyYaPAE1M!P{%gIxhK7fb<~XwR2Zp$l3li$&X|dvJXUI*i;NV0sRdbee z6%VH9E^nt3raoK$I5H@X&rhrVDaB3>iy)*e&0EvFu*X|X8B5b`TrdqHH}g_bMY*fV zT0JAnRynm)uSx~(D*6GM_!Qd~+@r~%VXUm6Ng5kl5PfpW%t+T}zuw4GYWu7L?^9`X zQO8G8TL6@S!k8xd*(zF80jFLbBuos7+hw^>VPj%o{F)?ScC+{-YwtMOvThB4p$?qs@lZ7Wq$=(WP5P6jp)VjnAW5He zeE_UL!%#PUAt!e)ui=l0cSmA(`GK;1C!2U!rGtV5FVj*A_etl3i`b|(`H?#B!z<9> zCsbR)A!2<>TJez3@Z4>TiP*twTw(wv!~N1T@_e7)S{wMKxq#m#6S$R}tt~na{v>ez zZE2ION++>a?1#MC2N>0#^Ive|ja9^cFSn`R5)El8{a`)-jd<;Iz}yi7BFlM1ta}!U zbT&w=2f%|Of@iBIEdkXyM}1XCFJReXQ1~cUh4T~WRxIdeBlyCf<+mgx{VpsMoD>`! z{%rND2N_^A>nH&uCL&@33>)0uW|xYM=KG@SKI7+p0@K=@uRc?4=OLIZP-|aOob9@E z42M1i7KXriQMie4!uNQYE(Xa*AR_fHs5OQ!NEetDw$MWjpPWI>+HUr|?7qJ*ud;FT;GRt{w*#^AhdoI97&X&H@(sj&E_zp_^^uZW z=+XXCOJuqHw5v4VVLSB0aym+@itIh4rL)>Di9)naI@gNI479uuXV|XLU_x&JgqFO5 zkk;(Pf9O@<9#vUZmLwAt>D0ioRaY_%xt}VrM5UfERYaHLc=c3n6rQ+mnuVpUU#El- z_7KbkGiLnk;aBy1dNuPb8a}{f%zRyUAKd2YWN5a+)3S6iXaA)s zFud^fWfu<)SNfd!C(7Cb^WQf8TDnsKi)UWiQmu)ftM~TOM`IjAjgv5EJ$54`(xsmh zIGoio$Gi=luYWT~lzV5I%~EQ%Ci>P-VqfSEihH(4@2obZ@-46`=#u62y>VL5aO3F4 zMScEB6SBS1t0~bWRvo~cwtL71sFnU3Pp(>DBUgu(lUp5ySFrbGjR#1JrKnB`@BDL-?ao?l6Sv|nCYh0r;kSS!Ro|H70;x=-22N?4A^ zn+SxG2d$j;ldRAf?qp5Jh3OOO`QI@7?hdDwnlh?$M`{EP|4Fo(F==kDh7}c~3j?#n zHym$l9Ffqw0QQ;^CWL>f#;mt?FVnC~QS__WW3IT5h_eFtdpeB9#BKu|4tCcsmd}`r zOS^b2y4-r_vIXYGX(H2-OF{jj`U+||p?p1fXyH~e`m(g$zJ%JCRxxGv@q#6JF#UFK znfvvmfiw5e&fteIYyi5IdW(FSrK;D&lLtWXh}yPS^(m}1)JxbsGgjY`*FB7I6=%cr z0fg<@0hI!o8S1iWFmRx85j6jU&}!nz00G%Bc^mwbs&_aOplX9KR7 z$hU1*GhO^%OW+!q=;hY+p{8Tly}ZfkkPsj-T?P=nc`o@h=_NJ6&aLD#CGa*bve>=o z3}^8aoX*(V7L&7`4hAi7lKf-LdjlYs|0`A&IE5{9j=Id-orzd&7Z zgh5kQd?6<3+J44Pa;N(b6XsvHeHyEVUuh0lCJ1$R-MavejCalt*m`*SDyuRH0-DNs7+ONv|b{oO)Bd%MNY%T4X@$~ zZEiY<0dB-QtKL_}4NZ}kteKkHN>j^ch#`ApdYGfc6g+YTF6rEyGTZ!1rD2t)bqO-* zFzW%R<~4P7K>eES$CauLBS3owo=}Buja#~0)$z(6m#2f(sTD`DpJ&fPN|$)kui-2^ zBHAnf*+QI_Q>+VuNddj+sO3)I=(6S^*G=7B^4zsJ_pc`3C}#6r-%c074WM&+ws+ww zq&>-^`8VSq(88HyN$C_~0<upeu#zdGtStbX7akiU^T_jc3Q81dG#5L zL_ZQWb|8NgINMl(z3U-1i{~O_LF@o<-u!dER;xFl3DF1~RCdYUDBlfY^w$o=qS?3h zsgdrL7uiv_)b<$h*p7`ID?IPJmt4Eb>hYku^wskq+!sL1LLukoL>4n`N%Tr&m%qD zD&L#>{>C%@v~?Lu;e&nqNqs6*%+a4tsGwC5G2sho)nlN<&%VgU@!k~$%sKac&byP} z2p`5c#XyOg$di?q^Yarc8_sI1T8mDWQQ;#-rtl zxiLn^1+Z@nC=M9PDgDi~uoQ`M2+;HukE^7iI-4}WmjAOyggfNa*kk!unU>Bbr}3Zl z3B6pu!ZC?Yq=CyBS(LJW7vh>1)x6}(_5*zld5@Z(O(D8yj2h$`Adjm3IY!Ql8+H3l z$|Fup6R$L%?J@vzp7j>maVM{?XIyF5_)6Kdg}y)I9njqDZ?%_l42xKr%>X+3--qN=gxbD55gEh4N&Jj{Xl5*(ZV7$ZVW(ZmhM(^613nu zdv)`rDaO5XcllUh_c~*+K+1-b-)K{)J>a3dyh+Q=7=~SHYpmS1YtU#UKfd4dvxu#V zX{Vdv-Pv!e=LChMON}TF%}Sq}pt3kzlSQ6;D)!eRKE^(iHn+z@uO%D=m5MuU;xj(C z6KXsz$DTSrH-~QtiL^dC;$FZ*y?l{g|9^l76(Zih!hgs6>H>XE@_IKrSz4ybUzwy1_rY-Wv=7kds!t|e zUAlu;PTpYT`-h5sN`AxnP-omN_0Z`i*^d>eN%B~gHW$px9FV5Y8{)JOZbSXO{Fx%@ z#yr(EOse~XvMAUEu@ikzob#s=ue&56st|OwP~Kd{0$dC8G>N>#qILl{}7gbueU} z&tU$-uA{$(AMykPW0E}#CdJy~MGUMd5bgaBCvU!|K8a*_!=i7d1Q*~U`!i~1y*%uZ>VXEK}D z6ugq?z1n%+5{3@MDpH&l{&moO2*QjeywQZA%5E$CrTsgH>Tnl6nr|5Du4ynE-d+)a zR?pZbQDvd^zhUnWx_f@VOV%w|XiFx85N*thv(+C^;9exKRH?8p{EJ4*6!M)vCp4HE zA4Hmt@<)*4rL^);5d)A2#~`ULg3o9ZM6V8B+(bpu23%70`d59&`;%s=RU)l?{Z?XA zej5frEY7hCd0fAW^Z~Jqu+0{X|L^qSB)dNnnHehvt64XiXqJ``BC6>9fnw%uD&l(*70`7k>6!Cl6CnD9@ceYL;V36) z=H4gp{IEG=$#Ikn8)N}_*>^7STH#%h9vCl7QOUmMXii%^ZAxkxddh#z?Dk=dI$j)9_*_8P?wbBzXDAz}BX?(j#i3 zp4c_=#5?}P#vwht-g~s!r^kYCd+AnmyX^-6JzVm>cQPLzj;T|@?OORW_wC!IDYEoc z4Da0hGDCQ0((Ip3;dDhe>V|F5)D3$aB>GYvm}To=*FHy25PsgNSd>OEo9Pf0gIkAxqY`6SdUcW+>cLec zQfk0U8TUngvA17%?|y?`E|g&?5}X)i3Jbz+yP~xsli|u7*EIO?YB*UuAod^*Mj{nN zuBp{}9RSQ(2-WCwI_cfp4?c3mKJelSd zSf04dWiKVe=jTs}Nc#B8MVuKZ@OPRn?N9_0N#3%6{ZBBlV0j^!s6FN(dpkI5ceGz@ zJD&1Ap0h`q1mbcqueC~y-v=D)R;$Cd$06v&b-6qJ{6+TxmOxZu!Sci8N#5njjaiQm zGplQxI{nm9F1w~3ZT3nYX4V5S&=QgK@c&A)85=9m<;)Vt&h8T!Uxe+>6P#Xw*;IOL zV_gJg)0jY3F?UzsX@^Mby3i{74zM9G3GH3eUJv4?3}Tq2nBE;w5j`AZcYvAJ`QJ?j zW1<#K;LJ~c1-E;Locw&RbL1xcGeYL`bE>3|hlpZ5TtRsYSimstV#ryc#!50y^abPd zG_;{PbF5jlw9xPN8?3CNw_7w!lkA~Po##Jcd^a0U#P28b88TD^<1jx=78vl*dxX3( zMa=dm_dRk)qA&9D@U)1uEGhzb(0>Za*;pP>iyFO^jSUR_4E;~7o@bskKimHI*pMy} zst;8yzj0S(?@#tTXa^oyCZ)SA$E7*K$EM%e6H}O5OV(oBv>1!1#W|;5G{Z_M(m1RA z_t15I@ELM+KeHn%A3Act@}XJhLx*?_m;LXL37Dk~-&vtz5i&bg#fa=#If1SFfQe9? zCC@fOK6tCs5ga+VEx{s6{KIHz>@4ub*C^9dgzwVdD-CUO>$6Xfx$j4axr%GcIritd zl}${4tB6UYQ6lB|rkZ`0w%hzvBX6Lmt`n{Bqb`8*j}YFf;>VIV!{=-QhjSJkreNYS zDz0I~3&1+Khe>_%;Gam2B;T;hgCo=zC{VQ&CZhW&G0=5NIAfl?HVbdvrTZgzAzfa_ zYedPS#9U)g=`RLP_X(iKjEuU>4k~M*3!OlmqPp0M&!rE-dtpZO&CXJYg>tI7wiSoT zF22`f3bVeWCev>L-^=EcVD}>gXXd`gEP@5A71Wj5mcn!*?2bz8e-iAM(I^YnC0NhX zfHEgQtKcy5s(@@|@yki(nqe4p zbjbKh6h*Xu?|@(%9+Y%lpX+WmD@6vd9jtFFEMYK>MObZs(*&)tHArttwm z86imu41Rtq?YB>}$N1T|_buAIL$18q!zQSwCrE~7tGNxOU}g)LxgSZ*f4>g!#QJT3 ziUKg>1!KpJjHJ_) zZZW58Xrp$R(}KaNIZx1h7LNu$078FHIMp829>e*Dlj-T@X6m$+zzLwFejIFckn+d; z&(dU=@iU4nPrms1fu({HYe9OsM!_`|`okIW)t!Z%yS|PE!bke(!+DfeF~DmJ{4*dy z6s>}Q|9ba*eqlCD<8yxTpnG&vWX7L{VYw*m%>-0O%Bz6C5}!v_udjb2BfUrm03CV& zW>r>>2Vkk$V$momDFN3Fz)UN!JCuJ*1V4poUjMT3zu?ZKOFSH6Yt|`$@o2oVeP{h#Gxn*_Q8&` zk{4O3fh&9a^$Gk^bO|KA6!C5aM-O~IE#T?Hy)BWH@RX^#NhAHYx0%t7GNXJ&dQ z;W4{EYc;N=Omd8}%g}2h*kvPndWK&8t4lOZhv84)R~G8nIa;=we6_WnF)G7pz$dlN z-I$)kNX$uK&kJo+M69PO$P4lNh|zU1svpw-8{$tuaFO?E`3-%*`9yyd5$nAWEl~jT zvmb$h0V7X7zrh`n4n+kKaEZ2)FeyqG@hc{W4q!3Sb^mbT_JXi=pxx?MqG)spa)Lh^ z9zW=k_JIL#;cvZ_yHT-YXOqy^xaU97ElJ+|YER-DE)dH*6~sXqV@#KQxDk5Weoyfx z=$_MB>cNI;&Wl}I5DP2VjyjE!vhiw{JaiCMRj}u3a$B($wH7Y%MlerShxr%CH2fLC z^VfqYGAYvb37Zq_01&aeH|f1zu8@r#Q8BoyTmh*3I*(^kD@tg^WO^wK_xA`AdOCw+ zBW1tD@L(4riv9vu0_dz>;JuIz+&^p{xZ$xGw}y_mgT^%S^NPH$Nmp$!TD(IThLZzt z*h9anIg$jYQCyXhrMZu@p~YE%*)<-{pPbSM^_(Jt-rOHOwan`l-3p(f@HXKBx`VP> zj0JPl&-rp(nV_@Z*qck+1!V6uq(`hDyt!gQinx_zkoD_@`%h18Eyy`seJGIgU z%xtaJ(ACXDZc#O}<7GuFF8AdC#NF3?m!|e4Z^5oqsYfcHgto$@-gvl%*h#*5nIof< z?wI)oV~c*F;-P`sX>y7mC-=QS@J!E*`1Cd-wY4`zbeFKaKo~%&20+;1Gt_6-e}9_% zm-z!nCon&=mxxGyj;{$U8#@y;v^I9N1Z?%hsf*e0H{^+8_P1N1^&Vc%h^mnfec&~= zJ{Qq&eyrh5CslJwC<`NF#-{_}dN0%tdV%VsY<>iI{HG8)^$*M+sKlU%kIuuTwx(0l znwP|*D~EjnWW=;Ni<^y{XE%l5yDGl$U}>7>OSWM*R>X&uldQX(_VyTlgmlfs_yUe= z-$z0L#I$4FiV(p_C8C{2XWYu%ICIv+5kovL%9pm^*torF-_Y=RunXv%Ox1n?;}496UlZm??%aPsM{kEbZts&q(I$ zNfR0@T-|o#UpyW}7te9H)m?JA(iS_}EpDMA4^CAYC%Cis+GY`j)r)eQ)1wIfbZ}Ep zyS-F9zFfc=GEEa~-7jKAmZpJYvl8N?P?<1fS0}5V!B%maLOLPGK>(_!6Ip^a8?{5Q z0_12Etp<(dH5ee8CItCRxLpkA+h}N)wefu)KxreB`yZ2A#a=D`=_p~zX;3V7}Fwvfb*jJ(y-5fXvPZE z_(*gy5ndVDJX-NDQ3EBO?o}7xKPiV)RyDxRiKM><$>&BRwY|L!2#vQBCWpEu+n}W! zg@k{y>N~>;@4qB3Ef@qdji9i>QoMrRWQ8(mjeDbE)L4z!V-_(RIQC;hGEo&#;}>Q- z{>tF((wVVEsVacXuqstKV|YmT@aQ5;T?sNuO*JsOz?M)8AbQ`nKT!Y63(NP&APXQ* zWa}97L|XtoC)Vw4bfg@(AM@ zNGCS>@hYg(1t-tSR0&O%{hfZ1{~6YB`{UEI_6PD|AWWy5z0~DVpNC(>Q=*mGgG!{S z&1_qO|)&{KI-QDR@+Y1;m1Vj>V7 zZEytRJMBW>Gpq{dw$6XuMT;+Hoq-R+7gU=8f82O-{8g24rA|ybz}0C~@ZD#Ux#;C1$_?a_QwSYMYm^Y1R^?EGRPNvt0Z-d7jMWJF~SX!VF9x|t4tFw z*E54VpwT+SKyXR6dNI07SQ_W#H}lY=bM7wzexD(~EHH~RCbIj!A$L9fwi6+Dj5pVE z7py^t25>(SVrGWruq)x)M;`hpA)7iKx}8v|2Gq5t>kr#~^m1Y^X=C`Y7$e@R`NfxE z)-@xGbrn}aw2jB{JhY3y(L^g;$>NIyE`QB$b{#cSg-kN=x&c%bE=msD{(N6et$k*^&rdn*waqjT{oAQA_r-MU?yow}U`XxSh1)4M*5is%9I-*z>@b|RGW+GZa9@&8KYg6_HgTpH%Mi`NcPU)FBatOH52;sx&{ELI&LhDc#9fx7ptE zsGD#xauRmGz}S^k#4RvJbxtgZkbaT>+y^NA50c*5p%@_-0?v!wY?w=e$v%lU=Tk!? z?LJ{QS91d65y6ZYZZ*=^d*q7H?h)(cYLl>o!%hOMU@;cgS}(k&Dn?yS!T0aW5);*1 z1NNEsAp3qcT0aiCDDnU01HstjAmme<;W3i{WUkdgwa)m`?E<*0Ng=>9auUcD8=u1t z5pp;o*ZZ^o#%z2&=N|)gX=NEIBPOkAg=C{{F$c$>2^)-=&>{nz=-Ssp`4%3&vAz4V zdQa))RQ`<#ec*RzFV{}Mnu;Uv+yYU_-e7QAn(4`5L$W-oEc;#@ei|z)u!*Q7v(zt; ze2Im_VA2Ngv3gEK;02;DLtK70d6EF5MnrFp2t%6ejF2_2Nf$T_NP28<)p)<5oSzKi z_FKE*`=S`Ou9c)UHZ~sPUvmw>uzNyBenh{o@<@_L4@s$*b~lgW~VXBbn~)X8UQ% zm&nV)x;`q2Zu8&4$+MIfl1!;tnz0N7$#U^41tbO zhNo}u|6Wi+7wp~_w?Q8C!{vQuIT*wZ0M$)2ukplm_O zz^|LJrVQj1L(0o%4kq(IDg7PYXIvay^1}jl6=4FgwY8X2HPI528T_6~^8iIml{G^n zzl18b_ITv7*}KW>tcm-{UlM~fO`Oa^UKSj5`yBE&{NCdf{+J&sbu3m&hMu-<-qnjB z_JM#V?o|znZxQ~q;xx({er(^mNTGM&c3&kyRDxo~7cNZ|rl6RnP1uLdM;BZ#g;>SzB1=#nX*92=XM#p|=*c1R*oyx})Y^%lk&WX2?j`t_YC0=me;$2Sexd*wS$ zSI`S&#anO6nTDK}B@e9w;rzvtKmXSe1XkAk<~yJm_}3rCOK#zg7Kcyp)na9n7hp>N z?HNaDvJF_Hk=~F_t#19TZzJPf9Aby6HHu>W=~6+Z0DVR39UBUoG2`Agp~WX6Z4I+P zVRZd5nIy6g1ti$Npg+`M@0`lL2CdJe*}k z;riSmRD@En=UemvC)SU-;eOhYEMe*kY^W3|1>hdYUT&Y1AfX`K&AGk?FPk`PXr6_ z*~Y&XW`HEDjnV{zfVA-Ol|s@XbMUt$C68Qa1Z8pBW#+A%6*M+P!U089wvxHU#qQPBLS6!3aCW8j za~ZsTcWK}GUrUITvrlOHCZmI)VWV#}MrtqcDOl5vDt2@M`=W1MA~@5J^2bQBzIwIQ z;<8nk&VJOHTM%#cm=8i3%XgrKuG_+RuMSr62XFr0IvdAlCkcTP?daD-oStcKg1siH z9tB#9yY$4|Mx@Tx2OcFhS0L+~$B4Lgk9OfRXAk_RZkT999j+_i?em>Xyw;tWT+2z;`x-a>hvoDZBb+?3~|BA7(jniPH~W;OD1pcyjfrAyqMoq zPBX@N%P0Zd8&IzNora$+&%7n#g7-f8JGxC}p*T5(=BsJ;i8nxsp72fH;QkC6k#~ZH z{nNFyA7eaYRp;65hZpXLA5wL%nVlVLbzZoV-cAlqp;ei!#HrJ|w*i95ebQ{G&tfvq zJ-K#y-ZuE$H?8+n1L0ZWkXy?Bhe@97P3BSO;>ORzn@Szdiepyhb3Yghnk{aPhw(;O5FI!jPcUc8^jic!|mN z&qc+w-FweLUP&CxRT7Xs%>Eb!1rwKa{D57t7F+of=1~P^0Y>~ph8e7jg4Pj5U%#(4 zBe*;S39Uwu<4MclY@ravU(bj5SfCUWru|{#MAcFG!bVaY{%i>C)TyXi=nJSU7H!m@ zNS{o-a$DSVmPJ{4s)GDAG%PQF5i=@HT~->}eZ!y-Cd~O`njZ%zEu-vP$O1qwU^2!3|AyUArv->4SUqQ2Dq~}pUoQ0?RI3#TA?yuim*e`)ISv_7K zcHW@+QNwAWAs|f+GjsGYER51IWBf{8f{UA!Fziz|rH6d|9Og-(St?QQbf%lTZo^)f zjWz90Gz2EFQZK*>1M(;9_@WssWJg$iQzy2aex(E?wmL1uUxHv^0$ zm3DF(!F4nkO%h(ruZag9(SZ09hq=1Ch5$Dez&EWuL9j2xMR54#4IZPo;Sq=Q6(e|z$onv` z-;{6e6aOQ~M}p}^E56&(^uH)=!f+xD#{T;gETVnYM4;?N+-Sd|M~sX3Nk=kN`%ESi2nygUR(*;iN9zyz>mrHFfymuS_3ikAx66=@#j_ z+7U9Zq+k6AJ`2cNF(WfeCS3H9vsbAUl71x|aOk(I5Q0`h#)V_b7BPjTj@N?u(Y8a{ z8>RS=E|JyFfo~^)e|akcyw>R_d*}-6@FT=f_;O%XmLtx_ZyM_F^|H>6d?ulB%|^}l z@iu5N9x}N<`CTJ;(lmhz9*i9=Yaf(S^2ua>)+0f?ZDHXpy@2l%qw@KRcZcMJ;M z!*F|Cn>ws@d0gp53n^0@6wF|s+cUXcDlobt`qV;!2AXCjNWmB_6BWNnEaS|t_cIZg zqU)xw8Rm&ERgJb;hr;{b^nw%xm7h8sB@z^@4*oOLiHUoD?8SG2@k8QLD() zvp?^D)srG<4tJ#59Sf(>4ob@l!lmVKs8PyWdFEP-bKtDu$P7e1L?q~^50SD={p{aO zTWRTH9FDbd2p$CYLj%M}@(?L&Z&Lz{u#S%bRuiF|ARDRY6?=bPp6@4_ST}A@19H2i zlkC9oX+@_IJ7E(Jn4=!s<&yk&T`H`8?RQfZDhg`DflO$|^oS?& z7iO@G@G;7j2f^ zlQ|Dn@z)TR_I+Kdns^^a6~F$qYajz720A z72yCg9~)kpm5+Ty2qe;1KO zINAz-OlEQ%X7CsE;YP>#mU3v$tBdcumUznSZ((ZuIitxUFHgmzYR?c&Yk38ii(%=7wV0!Y zQS(}@6Jv*m^53OEZS8bz_3?VX%_>!wG10XiiV=Mp7?u^Zn1mGTM;jvE#J7*sE?|8% z_6<%5nhZDQ7k-?0R5qCo!w8%pV^6hkMO^L}W~9SGs_0e=iQ_HyaW4U|)LZ8&nL=Mx zZgqA)b{E)&KBg$&{2p~oqmo7$yJE(Vbux~mX0wynUJ{%pC)Afm+r!6PW4qjDr4A`# z0~yb4`%enCsk{7Cduf%=*}sq|+sorR-8d?`{n)Rq<$*m7nYjb#A^%;+fOko(fY&%+ zOeG1B)tQvmSk1JxS9f-B0LLzQeaV)Mn>RE>s#AE$6oq18Bl&W6Xb!zb~M^HV^Lo zp@~;i#b~hg!1McPsva3n-GR#}%8YT5s2T>8rWxuq&7K-)bTgixGJBe)@z9u(0nl*3 zw}lg+4sGrKosF7yYOk8OTA@<#y3~bBx`x%Aw(X|OMWaIjWIbldOz{hxNDCY0#)HDWmRh4&HMck$f_lZ#a zn7b@_-bMUn3a#C(>bm6xHRl}I*3UuIp3m+mbH8(&<|YG9-4IAA+=!49rpY6?k(6gX zAsQ$4Tj`by?McCUmxK2$feSW>3ht8dc2!BM%?k+a3L$=03>bpjvqz zQM@@Z2zZ9$NThk~GjDC^!M}1_KfC2|u>Akn`pT#(yQo`0kd^};S_$crM!FjjI7oMQ zcZYjf6;&ulEl=(Kr}h!^4VYzfzYPGFH@LkDf2@Y?WDf`MD;@ zl=;XYO`veNe9E&WBXZd5sjFD_Ty6fpc((7u8hzYrvI?Go)6{2eHREWKoBoXOkfG|@ zViNROWI8ziK_XtE;EX3k7OmSZkUITq#{6dw_FU~=cm<)TCs&GL30S)D`CVewx$XN5{mbC^F`9*w@lsv~h7?W?L zZvUXxWsY7zu#W6A0zYjAKCh)Ww$BoeRJ`b{`W(HnV)70!cbkGH2Z!MEE%sX!q`I&N zi-IOqGdRL2##9H@c+TEj^SBtr!IMa_0;>hdjjv0)E|Iy!A*MEmrj{yd8Q8r9U4|9) zlof+KegB4!9HQ;dh9o(*1x%qi7{C>p*cbpVpqs+?L#5LcGHN2UD<9kPmM-q?o;Pz& z0cPTC?`eR^S6E}&+rqd8d1pE*qKOid+8&buw;6mCa_LFLsW6p`q64C+ddvm~-yj_DHx565h8(&+HU&fmLfps|Kb0zaa44`Uh=k3PHAM6u5rImt2)~7 zx2)TAxyj7i5Ya4JbUjF3&9X+rI+y@)Vf^jTUo8(kXev|e!KJBpm?qdL)k^D$G{ST0 z{aUriK3p@uWTlG|(4h}!oDl_5J@^ujV;c@W8I?&! zSVnpfu2MCjS_WR$%A6uA@(c;zHiMH;K~V)4Ot%P(d$6 zJ-2wG3EW{?!2)t!jqU`tzx~cbLdJo|fBJhWoA13XFr|Co~FK z0*$%MY;*Yg6?H|lAk>&he_Htd%lC}}JSb&4g1I_a zQU<{!^0NF1H_E^@hg_VX7o}@gfI46rO+`hNK7dv}#*{FS1x!gn3+G+oe~-)F_8Nt1 zYd(p?*(W<8AL&rk>wl?E2K*#RqW9mP2>csh8^x0T z;dIGuWepe;{B!kfc0Q8N^aBPqkAFgiRtMr}xP^rJ!0z1$;19pHzK$SE2d?)$Fsthj z0>f@2?pJ@K9!5MGiFc}NebYfa0nQS@Z1SIp1o$#VmEWFD@$I%`RZFwBso!fPH4?xg zLa^vNIXR3}0hQ|Cdc7;GtJ8}CWr!$C>d2oXx0Us#leR8zLBI0!MhPSpoeqLeU0q`L zd&NSaJJP=(df)P^^~baOMpp>t8Gqm093j}-b$_lenCazj&O)%Np!Wd0$pAgYfUB7U zd9JtMOLqTV1(A{BZ%)-AD${c$;CXT89o(C){7yi$z5d~zrK;T*hh{bH&WY=Fp$`@A zex78;4iLq2w{iCYpMtk<-RmV9RAvQSChl6V{9bV6 zbmQgK4^1O+Hcc?muG~MoUEb5tZyg$JilDg>+swV}@`x7_7hE`N{Nh%1XDe!Zl5QKB zAT(Xm>P%X4hFd8TLiwQthJ?v9r9MCmA6x8*u)1)a*9?}-2)RAEI^Zj~A%9@+ZGU$B zn;CE}+xNL120gf}N>8?^j@oYzny1|M)KWc`W~P?ltvCz6NBQ72jPcoPqYR0=p{W}X z81jC5gCPcbcQ7!DNCpw!?c!UI; zk96inzOFKtU+5z%vOJ~M?W_KXeG-28+=zpKl?;l)Ed}lSJoW3XZ|?n{VEpUIx9l0L z(cB-t<`Kpk`?Eyy6WB#s5aKbQs8A4pVO?GkOUqM)t*>t)A`0sy*7`L>!83pRds-L2 zP(N2YXA}vKrMbdWLij0?^@M^@;_FIKc@bLGEk;BS0!WeJ6ygS(9f<%Z0`9?0w{Q6L zu^aBwZR7r%zS;n3KBzN*br#R#(aIwxvu<9xPOLJ@)J zSE#E?sxe$Q9Mz9Ly8yTMX6Na04A4*ttQf+WQ-*fzcF>ck)P9Fr0%I;4`&hk2E`4z z(=Ig$38#^aCE(7F92!qg9*lqiZw61Wl{H#-Gi^YUo8GuQa%~W}!o~cqOq%X1K9A`+ zA@v3-n6j}FDnO`9eS*mRt>?a)8u7aafhc72-u|81Vz5ke)WC_b^SjoS3u}kI3E3Qa zhLtg3cUL1rmdGPND=9d0Lv3e8bG@?AJY{D|(`Wr65N>0F;QG|rO_ub%?0qk=U*{}}Q-Qb@_jD61?|tkFGJRqCLhw8%Yd`K^g$E=s0F=j<09DavAd zm-M+^EB8}-z>Nr8CqX>K-#C$V zV~UAiR{|dl$f6DPyniFL>Qv-F*3VA+Jq0aR%+FvRqNga|OaCtwgnlxJRTd|S_F zPSRo%suUa~1edbAj~6xBk0SWrC0u(d{>Od>_tQ6L4NoOiCC9d+(q?^Jic}D#qVh7b z&j0>OV#F)b)X27m@N{*L2$R~80Pf?atHUQ^6$MgqZ1nC=PBCO~sA9V;LF=#P34~E% z^57SX6Qu7-gGHL^PmADFAEZBZwi7f#RQ2_P{9#eF7+NBT+onK7Q55(7hxNK9gESLDkec=N6>HAgdkKaPwV7s8{ewKlZo!4$vJ9)F7eMce z(#s%!vw4?_10ryr9rYpsI|0VewziW9ou$RUT&dT#!@v?345G+Yi+_7Xc98vC-CJHJ zsh;Mx>Co$Ab6cB@Jaz{$%1XxYne0rZ~mad#zvm;s2 z1u;TFVI+;57`BI2wYY7cu>hjjj;q<(qi|B9z8 zP(1A^gAc%?>vO=9@6d+hz-o!lg2+A?dOO}AX12OV=Z7k=61@;X6``QqZxm6{ApPA~ zSQ6h755C?aWpzqHsHe(o%>L#A5_gK|_mtVT(U&A-2uMLO`DIoty(}bAA}FV@z6CUc z*ZLgb%-$_^frH75qvHm|EPQvj`_X47shQ6}JUhHgh>HM>^Bw#h$eCkBw^yWx5tXw6 zoUt%ek|gbphwxm-Pe=5#S)6JAG2-w_e3FgRi%|qb5ya72_IHFv{%eY{!gTY|NUtt> zwM#B)SE-frXX`k*V!6&sDj0s{ znD{(E2cY-V3^oG0Iv+;Y^9G3gNO^^mu^DoXg_UOBmSIV71cpU1;{g`#R@TL8UDL_= zo3`%yW8Jn;*rff@1XDr8#;lN8x=r9+bl=DDKO2&6u+5TXG4#z|rN}&!AuZ0#dCeEN zRI-}>_y(c=h60;BJEh$Mb`P68>O-PCX%sRxPnA|)2stiISfX!Rv;#72Gj$RwRT-5C zZnHnN>}9BI5Q3==5-?939UJ{R!z1ogV@P5GbjLy}CmPGokQMY*{NypgZtCLxmtoj?3Kw~fg`x>@?`Had#w zskbk%smQY_MWIqCVnffzWesBT2o$Jkiw12sp-ADs(S{<>8F!pGT#oQ>QipGg3HBF? zI?K7!uZw2u9x@;d8+~(kB@9!Qt;@wRp_kwoY+uY?WsQ#?^;Vz0|CO(h+1ajsB29Og zmj?wc&9szV4E(DMhvXM9j7s=P{+bd@n)5?0&0ujA)r@byh1mZcPG5AMg}t|TB(N!e z>i%bTuyM3dw@liE{{El9^mZ%h2B_ww?t%YYH!$KwrOP$J8rdNk_T3eg!4j?U{~CuP zI4cB4j<{pCvl?I$h8Zdbt~l!GC}X{Ep|t*ndz3jpgI$I8>SgMT`|Xt6D^k*&B8I2O zx8@{&;JVfzW0?Yd5j)JF-vh18U}g2$iOOD|-Sy&xtP#ki;FoUvo=%?D?EIdHw}Cu! z#WlqJIxYD_-amWO(;cA)!b~8=115n8r2&=J;~Ydl*^Eh$3-+N*4Is8XU9fwf_LwC{ z_Ko-IyRvqjp3;quzGcy4jM-s;ngsCci86$((RQ7iwRP=e`bC5DGvp_ska;Oh#q{$R z8?V|e8h#ZzxOCD~GrnDsw`RYnX}h`4Cnut*258U8R0x7HOgwKp;r=aGJp}R}Y2AC}7l5Z(AmQ#(Kqm$CTK-tbWmMzi^Mc zS=}N5CzcyN7b=q`967xYXUn+7e*AP-WREmh#v(=^#yF&3t@8<6_U#dm>x}Qxn;2XB zQ5!uhivHos`tvt+W64q%wE6J}+h>1&F+6u>wBa@(d*wfAUL8ExMtRH-{&r`pM9J-QfWp zIzSG*MZ#F~{$C6NBy-k@gh__DDW6D)eSa-?|3m9@4 z+w~H(7*>3^LwJ@tC3mew&;0@10;&q~)d0Utqq3#$c(+t(1A;*0MYU69Spnr%OL~rM zcnjF?_P3)ZffeQ>-$1*`xB zivZsFPK);BrY4?XLTJi3SYJ0RZ4JDn z=G(xa`ScRRh>t2^WUDt_q>rB`%>UKH5pxI;5-((+on+n1&Vf5)exW;K83w%HGSg6gDB>;Z{E#rBH|uubp|ZY*n$rW+koc-TH&n-b&qdtCG!&dkiQAhMECR0Bl~ zD9wD8xuY3VYb;8BmBbyp5D&eG58EJ!G9Mo%W`3DUZB@HLZI!4L0*s*7u=F0`bJqGl z0W%C$*b`_)sRpmhhNyb)Cq0L~$o8KBLDIQnBKG`ZChN(!ZhrGS86+c)c&NEF!|6)k zIbJ~v#s#+Q_k;j*C<+vTMX}Wa-W1+l%e}&vr+cT-`xT^7&Y7@asUFMdvDSkpB(I9h zvCV0D^+lSU_$SR@F;R#n7mprGUr`^&-y51$bkm9zh@NyDCh+&CptjTyOusHh0#0UM zkmD7bZma@0OrVrs)dmL}ycfrGny237cs(`vHPy?tIo@*T)lZ^DSqp=i<}-1n&EMib z4&kmX_HBe;{d|`?RuWpRyEK;5JXL<&1-Fu?J%My7V6?1gZkhQlUi%o!_kOih9GD!F zfLV(`x4AUA&+Mpdt!2E*9=Z~vK4Z)et1E|BbC*z~;T;ttp%`1-1GQtu6;`AKf#-nsB}dz9}U4|JGvku(7?K*-U24e zaWIe)1N~Y|Hmv9lPuz;}M<_Vlc0|S!FLF*mPt?^-QGmeWe9G?4dCJ_$1L-4^ zK}g9XlQASbkJPyJQ{z#fqcsvHfOkNPLrX3Se2bn%>)#ltR15pdntYDPL~9pmvd+Id zK}rKfp(H@zKoISqMKUW%2(GerJVz($TkI5&fnhwi5?=NgnIBR0SA34gA}$kT%q^Uf zD?Lddg5Dc9ddVJ1My7M+gOSVm17@D54E2ZxYXs+dc(!-&`|;7GC)D#MI5AxM*z_3j z3Q|1}@_5F-$}PhAqI_Oqp$H-ir{MSb3k?ko^<{^ue>(0ZU>W4k`A)2ph?M*5)0rq5 z;v#}@&MC_I)~l)>447OSp_*#$h@aTm^6hx&_Zqm}zwrpF+g}`-PThz@xTvxpF;rpE9wrh;do`hPedWF489A1 z(rJ2WIkadPumc)d)L@QDIYh0e*-5)&w{QAEkdG$8Dy^bAGyi%f@U7AQ$kJ0NN(BBe z1XvD}h3*kCnirfWeF8#ZQAs59*{l z9VMvx7K5>dX~*AMmXV5fPc6YKyoxK;#I;}&`$S97*0^VRqkU6&QXuI z9hOXRn%+D^Hb>VG>wn%{NS5#uPxUG;eO>Nuaz4v~GA%j*IeOPK+8AApG9GVSv-<3E zd)^zR;n1c<&R|W9ecNrsirC1PpJ?H6nawFdmBiYCadshNMU1th+>mP}7eQMm(g51v0w-% zyE0hUw(R=;)(L?5z+VDfi;KzAi0oY^IlIp`?>+TPWw*AO%6u{feZt95npL7;Xd?O% z{*{c+a-l9dUKS4|@hATvPf+cznAb~WX%W=Rguu`MiuX^)RI19SHuj|Xi7lFzm}2;f zybBtYI1anWx|bpeVcTW-^dc0`z6?+Q4f4d7#d1^)uf96R%O45FG)l&x^Q-gc|EY>? z?$cRN6N`xYCYcNYl_HropinM(zH(dsfqU44S?47B4!deZ{%$fzI6x#oW9&BZH;y=V z5KK|@{*AxK4mqg=DtBG#Gg!Fl@h^ngNLECp&y*x&B;9zCq}`u4;L?;75wehu7moO< zJ>$uKS|UU)V8TBW?qhvkSb9hjB}JRbFQNj4xM2PsMAGYvS9p#Z%W*oKXOnP^2sV2; z-d^iy@b66Fg^*`+pS>sTi(hf+5~gS9AUGR;hGjtTcSKgd#bINUGy&%Oa{BiDi^%|! zKO9MfjL{;$RhW0*asE5CzUUG8RU0Q4ns45op5bwEFG058_c%lBS{s*5sM|=q7VycE z@=>#(9AX1tthf>)9Tm8+f4YW9=c7yv1%~sL|3xydDFMc$A%<_JOHS9mjloRPy9m9h zYr+C*)`$L|xudazu{+7cQ}X&lzA-(|>HehsAwYu8C6_4joJNpO2n?U3R8;ioYLsaV z(cK9tK#ZLlAn@{fDX!%IhS}cx>_z!XbLZ&*E1)37$fM`c6Xa-xFe7hZ0K&~uliTX> z-<}UN%3#>+ecO}74a%$HnerI?29uG@%(dO62`VgO;Nrb#+u5|zw38iYtW%cAEx?CF zjtKtK-42H$9(}9MSqsi=J-~}S5EK{&Y~O@swgO5=8ah>GPVqaE-_^(U)!g}xwIZGd z`y8~=GUc>XhD&A_LJ+?v)nEmpL@E(%sLxbB*nJ{XTulpvJbQ-TZ?)o9MjLauEq3S~ ziM%)je^L~C9TR!0b3Si8%=gEQ;}y9K4xe2V)4?3>ICpN8j{j|_exRKZ*GdxVvdN?_ zQTdNEwhaUOId(7N-JS5~@h}#a12cpiJ}{!?YkYF`TiFt9F2=uc@o*XARO10NG^iws z`)VHp-4C^QaH~f$K-p)`EvlqxUxtnOKgvdyFK1*Z?e#hejESmy-SC4m0cUT6ATgrZ zjIu*;3WgY=s;y~N*WZOiOFYqxhRb^v{m?DGNDy9Tx=6^x!~A?oUWdZxFOJczb6*`4 zuwY;Ze`UUZS>s<2EM%KR=Qj{yFvRJ6M3cZ|2oV+LK#*UuzLb7aB-xtjJHCUw=q??^ zX>NI*bY(JMA%PZ!UpvF?^^5&k;iWp1e+)t^F%j-rdcwtmNyK zSJl<+Wb8>%Ol_K_yJWxu9&=Z@s9J(;HnkY>KD@?aJU}&&&Y$|eWV_*!(IjOfbIVja zYZ$>)do!q5vsi)FZn@KTgi@WDq{l?3CkU5}to%iDHoN66P4a{%3@v$d+qh66W122D z&Cu%7&kV)h<1=acF)j(O`S$}GW3Ik0%%_z|qCT6*SmeU8V*T$@rRDl(EJI3?CS#Um zlPo>eC)ZR_#cp-6){u8SKYt+J?OCMV2^Q`9gvPqjbdyW$V z7yL&WW%wkQvfwvLs(dBC)Yk25St12~ZL2Eg?m=`iNMPg1)E|M$!LFK}+aQBD7VE@@ zQ=C%tGwlR=dLxH?V-cNSUpWIX;Ly%E^7>;PU(4~fzKW!~r&pe@K(ZdYM*Y!VJX44S ze^g)+o(OzcsEuU~%WOXE>E2G$mqyz7<^+)5kj*CZxa+iTC9I$;JAa9rr5%^ML|x2a zuZzB1R2XBgEl}k#LYKR0(MbH-9af>ncoI>g8C8Hgape5kqD^$L$~xX%7G?#`d3K#{ zwM1oOwosO-kluLjsHf{F8(d3?UOolO6x`V50Z)gsdGFXmzUS!@!=V$X+mJxCgFPKK&!jmLQXx))#lt7GcE27p;H=KIs!>zinhlo( z!|AK2`1SNB8lPG3&r;pW>HZc&hLG0>s6=mUt+lWF_3`UFFOx^_oVD;f3)Aqc#Gh6P zXw8<&uEleP%0JUZJ;IW$%RD&yCMTL>@FbEW>eNRD0vssCW#tx`#xfUrjdply z>5O>4H98%(YOEd%n%*s;-LImt{{6L48SY{A{dFH8y@VFvHss+1dFUmY%wz}wt0E)% zjw8=wCtW5X^X+U+BE#j_M2`%QU+8vb$|n z$hR5Ir<70rkPnJ8C!S{G*!K{WxRoV~sp$D=>*8Z9x?Be~+Jr3z%BHt<8Uf5c2tvYd z=-8aTR7IP(iSU0};ytM0eGtj?ZEIV%uYEOJ$x3AJz>KgaZCCuKX2rm3c_BoIcm#q7 zf2o=7IZ_ay6B($^6`)S@fmlKRs^&JOxW9pE~?ii?_Rzz*FqgZsFO{Oz7vqys=E1{8 z;$I&HDP2wOs;5Kvk$)!ci^dD(k}n4bC16y=x=&L*FbV|ih%t#kN7)eqXw#pKY zMaTMnIVctxDrqTC&F`ormQ^4pR=`DsImt~Ov5^pYk>4H_ENPH%RLQs>FK#bm>6Ovv zOJR%?;>^%PJa&#kEZ_NaEgV;sJb@Bb1}7=85q-TO^h6|MxUA-*4ud=&gZS9BYP_T9 zAWQ-)gXYvknC$yDp_f?huiosK>3L`-$M810_ln=gj!wLHJLk8u$45qq`SAl9mw&Wd zZHo=U?No1VBP6EwoF!0q?j#>3EZlHTjH`fG^*E7f|YHmCn$fwKOR>6C=c?$%1? z`sCKY*=_a$d$)DruZZl=Z4GeB!;c-(h!6efA8F(5175Nt!wzjAo962eL zMTiZl#-ix$*)j-vly3Q}Y*{UdziN%(MFB~8+4R*iS2|DSKFRf~rhCcRtSK&f+8kL0 z!l)1oDg5DWqm&Um5qTKaGw&6niez>oOu{cxjD|)Ue(9ABDK<7Mz-*$Sxp@O9z@zHH`z|2$)2&$(dc;D^SbGnb3%C`d3~ z`ZXFI=lt2UhGu4=x^+^s>Rgp39<|jTZ5uL|Qi{V1ep>wEbJk(EdFBW+bRACdgK}~^ zfs`8DTg{}uMw|jwp%Txbzq*Jd@F+ni4lZ_`dAHqfhc;Z6Zk-nDSN9TDRTi(CHD6?%c^`Rw9#+53uZo|u zHYI{tNroMHwcbT*;;h7uOBftJp1(m3@QQ9MW@~8_ny#AaV$mLeEsH;vF8oo;q%pqb zhiwKc3oqoQTPpu59p|=s{I_1-EKj7+ItZM=+m#1LcNryUbqdpr^`=LL@)Ywn=$2VG zCX(lzB_|bjuNn~_VRTkwxWzYmW0d8#O*NI}^p&MckLg_UOqu6+tqw8Y#Saw4LKSV3CVbg)bwiiC*jQerTz3i|H?S!qZOk`1 zMmQ*mxBRSj&YL&g5tx90&9&+26V_aNu1x@9K`|tr(SMy_Yw0*^$bR_PYP&LLwQN|S zK9IK(d!}Vw(SxUDeVWjLr~Ld=K-GAFNm4GAek*SY!^Q#mk?xn};}=UEFVdG^M2!lH z%!-lA#1TfwM9D1d{CbClcj_Ho$(2M(escFEtQc*lNM}Dk>!4FBaI2k#iUOcrhA z+0r>C>xoSD1!VGBp`0O!a7pACeVP)IIb<@FO#GKzu0WQ|G~0HR&aKgCN0IH5a^^rt zyq;;_Oi+ai)L$V$;R7Q-o45CoQc|oYWE?{*mW5J-aZ#*^ovPkeN43U(HX)bRe^rz;k)A(MD>-;dd_Iolr`UvsC7)D)!sUyjeR8w>DjB?5HQM}9N z$1>Vh${5kv<{Bm1bhQam+RO<-Gld-5r@#D&(B0$)neou;NJ%7ylQ1zQl(>iff}6Bt z8}}njxfQ=izk;QQbD=~Zz0-gIr-mXWj=F=pz9^CTH`Q;^BUO{1;8?w7x!H#FbPrNT zs5K9~UfQ|^Ur?5sM);O1G%e*}r>H}%;yk^*hkLe=B6@)A2gr?A*E{cydv|x|JpUT8^D7-NG9C0R8mbKUD}KXy z9<72@FhcTpwO}{5v_yr102EVzDVLVwx2kFNMioGw+xlJG-ZegS1t@`>w9jTtewTh~u_EG17U;`%G;IU*a zXvCJDTwZl^T+UF&Hw!_Htp=jnfEg_&F5hFZoV(pWg6RE}I1wDGr!TIweEr;jl2;mT{8 zxpK(I9AOD%T&JpzgYN_#H)Ha7EMj>pXSlT7TX#M#*JWpy)NPhSV}Ft~nkSK=s58Fr znz83_9wh_&%q4R~%B|LU@v4H!H_h1b&XGJUNADO0oelao57-8l-WC*8y#DI5^l6v# z=Skh>l`((AOoL6I!SCaP8Kt||)vCK!p0#1KWu^%Wy+xLv)GqB3hqP-G3GR>^j4z_{mx8 zngs?4ywVzme*W(5lP}ROCf>hnr}nOPFaC#3#DXRcka74A+ z-F?8D*MKWMmJv^(Z1{n~Fs@VMY)?BwzL93LT}psA5mMe7&$jQ5hH=`;NQ!btsHEig z@kve%dakN*f~<%xf)b?n>5bHaVUDVzF_!8$`ujy4|2YMu>mpQdsCnYtX-L`(O6i|! z@~sK@hCj4}st7CBg-P^Z7>E9_Z^V!>So$*@jHh(siihL&NaB{6+m|Y~QlffidbWV~ z7>1sRSXG9^kt#o*&gENLTdBRm-cxV+y_EJnRU@tABqO=}%Sw*#{Z+_?RX!_HbWR^@ zU_VXk>MIp&dCoq-t8RBJh>nYqY?pePSE$!V_R`P!>CH-3F^(;=5k>XlZZ*NeC7Sg) zNO-*7%N-($=zspE>P)4zY}<4(*o(N*WSH9aU!?Tvq@O2>dj8;>c>-LP0FW4>TMo#X zAmS3Hp08W{Hkd}D1~7IClM(rA2}F^0Yr&1pi=Z`o>6AQ5i%xU?^^3!JP;UVu$t>aF z&!#H5U*TZ*dCco&a>p-IHD~N*mXyS-OLSn$p~R3qVa*L2!nqzXjZ5!%0os7-1slM; z0vM0BwzhTTUgek!c>BP|fhptM(ws{)>s5vo>NIUQ_pH!rs$J{a>Z(6?G!HNDI+y@A zKmEzz4zu7Ql3ZdO_8}i)$2(mg9n(sLs||Ld%O#ILL$Fd=G$)cMo=&0U^4Q%tP3Dfa z;7WaUNNRs`90Pc!>)g~Mus}`W`~}uNb1o-LVh~C9tYy`)!m|74Rz6ik+Dh4g9HJ~E z*gMg?ZbY}u^o`&KK5nmDV{!#q;ahrZ8DjaUohsA3O2cvUM<=3KT`P%321jlI8;I@4)%+^qPkSAKcaHNlm&fY2AgimxvwdJ5E@HNmPf9j&6}h>g}{%K4Vh1 zrWty>m0`N} zqe#@>I;P}7i&%Dy5}Qna6d`Euv8nO1e_Kqw`nr=~?9t#ON-XCjXI@?`n{IN8Ic2sd z6D!f_%&#-R(^d@AMPYx=f;k4V0s3FSK)kxX9yyn)68ROaPKgfSSPe_ZX&WxLwv~50 z#~z~w`o=q@%pGRKVjkL(rTx+&I0Jr$~tW{g3M~m1y zH{L3wYAi0%xo#&`$1c&N48H%ZS;UCCn*G8-T#M=KxsRRQ*u(M7jr;%S(u>vnRQ9p2 z!wRX5II$vw9*U)1`0N`q?+(T%Xt&~-=4A(1#sNEc>!o4Tr99l!Hxv~si8+chR z6~lL`{^LV0E(Z?=S8M1|ug|<=Cn0B(VmpLTBvGsJJn2wc67OY?)fC!~4W4QQjo7D3QVZ^%EL|7pL)F3+8?B`wCQgACMKSIu{KA&O3en|k{KC5k0pu&6$g(EPv&PF5 zX>;3~@@`BkpC_HZE^;Smu&$aEP{6qn3^>{F%2*(Up&7l@!=qi?8SG4+R7>!hmUI-% zqzIzzyZ(71{~fKnneihse2wRk(zni9`+0K?ZIN4Yt}B(hUdj*BvBna?ZYNs?B|Ij! zzf1#23AVhT*wKmd|4iFc$C5|$006HBZDi8Y{mkaa{s+|(UUQER-}t{MdyFnebba^l z`A0<^8^V_q)$ygj0DRL`X1`nXe?5DYg0n%NiQIZp#qxlFZn;XcRC@ zwM}iXyi6IWXF5MBbrc$bjgF1o+TRBZt!;&~H8uKmHPXSJ_Ckf$?pl?PwP3B51Jst#YGIDXtHJxdLSmK z94I=?uc8}~j03PB>n_$GpOvrHQ9nhROg{cpeVzHESI~p)n_~HlyqIRrR)0Aein#<+ zv^$*Hd%vI+Dvj->P4{-LG~b{~gl4%AZMY?X%>j7$c+ixnR~hTrb*OqVVdhkGW=ZA+9 zU>ro4QfC9AjkI5)#wh<@^?qDo=fvfEDy4TnarB+Lb!`5OJvp2U9)`v{C)YiO1zTbi z7Q!P9&r4p5MLagM^9;(cA)0roDs!q)UMy8@%JYYD>fJxW!fwWcb(Q?_2P1DAsqx7% z!%pr5VbUDi-ty}~?%3>^gxLMKi?u_DfUUg~vd-3b;$Eb7;&gTQhNVnh!<5L~&CM-} z*Vhc698roin&69kPRx!6D54-C}G_=|*slU3HbA!A(zE!7Vz+yhW6|Gm2Bq4AWKH!H~n_V_5kN zsO`WmBUocz&ynxF`|STK<8cjJ*hv%PHi~}#O2VL{@-3B|wZ?Jbb@udWdA6&(nk$ZuMMWh`ARkRrtt2IT4u>5dqyeqjyZ9R!B9^x?p;n&ehFC?5w6S#(47m{z zRxFRhMUqH-DC@pIF*MLq>W?$o&1PYA`S!XzS6o`l8he(+PsKy0X%TI%T*aW|G@|o< zfqv_E7pe!kl^zzAfi@RRT0vJC4*SEzn;+_u(9gM^+9*nz2ZX;x68vj}T1juD>C(c* zETa^W0;@T$nG+M^%=vX7MFiiKEukopXFYMTKN&q!5ZWw4VjRzJY9?xZwO#N z`Xg*k|AR}-L8II3eH;69D)fj9p6!QpGlQ@x+VI(>r7e(cJM`O~dABYPX72CL$I{Z$ z2oSQX-P;Ckx41r5ZQivArrU=4wkfo&xYh0gU$Te@kTkw|^#TK`oDB-yr>hiTdD`l6 zi3zeguu~eC8>k5vZE9Ug*ZC3S?4=`>_bZU-avXB1%83DNd;rTqTU*!O({pg*bfN~Y zw6^g3%+cxDmRwSBNxY~I%Gl)vBVyl$@w#I^XDWBaC4C zzw7R@7Okn^Em1ohv}vO(j+)*WNFFd2t()4?Ur9qY5TGoi;YjU;r^XOlr!?i~;u^L{ z;k`RaPfyPsoWs&K(khd$+b?MAY!QXT|m+PSjujn6-3#FfrU6m6?Eh@T77)p?yW8P3QVzD~)+zQ{ypcXW5c zq5$sr8-`?sZ3ZWY{CI^ahNy11*hvZ5GA>;89`{63=xx{jn;xk@jaAnWmcB0fb+_ky zy;NiS8nIE}=HULn4*x$4X+Mj$q@!CkRZA4{o|=lj&r&LfN{0?aDd$GWEI zz}DG?hnuf|Ldmv#$R<tD$a*4(++WW2$T6C># z&mRz8sl*?RJm0IU0uwZqm>v0Z|G@oVk;f8+#7kJMuyc7y;yR4zGQCFUFmX7C-#>Jr z&FxPRrLP(O-bRzQwD;1qu6*ISW<+~vR?%iTy%`C+pp`;$UZJuAzq7{gyObS5;sx+n zt)T%4)*e=*mMc{<26{`rW9RSLW&Zv&YW{}-@VI}Lt@(RS{mYW`?}K2*4%k(;l6XB) z{6Sm=$BLii{Ghz;?2F(1Cq2K11ke{KFP6<rPbKK6j&S(h3iIMaZS_7rEGwa`-mw&Kxo?AYJt1p`UH;{f zD=~;!3i(T{lz+AY!CwMeHV4Cgtb-T&OURupKWNe1?5eLir;PVe20@>N&HRV|i>h(| zJ;3&u%4oOc0>?}Z?{qarr{BdzUfn@{A-s8Grt{E1w@sR|=SwxzV$D%VKWyjJQP4}( zaptvT&avn?#nIv+q$8$pRf>t4N~m?w+;35%S!R)ya^O2erW4XoV}_5i!COHWp5rY< zRM}l0_TEexP);pA?qj9l2*@krq{o=?ocAn3dL`Bb+fZd0q-2Xkl?poVhtbbC+8lLS zU8}0|`q9I^Eq)86jxM@*Y*aWU8p+jM=N;9Z>s>FYv%=TUQ7^xFNobMA7Mt@s1$$n? zTgUBw+6ejZ$~QXv^Z?oo>Oc_FLBn{m+_G_Y7Q1F|t__nlbO*TThdz#+^o$G~M0n89 zl~o*C6%?0l2+IE5KUY_RmeCEI^MeHf4u>hPfgvP#2aa6BvOoK_oe0Xq#~nrmCPcYOznj~GhSq@<+0HSbi;C#64gac2m-<|BS| zJ%02O`IJ>NxE~leCCL?qsS%x4ak%jUDah*)^F(7*1+|`C)og3!-h8lnQJtr%F{bks zwWC0Lj2U(&iGnBm@qHkhai%!%X8(Tpq`f|N@Ze0{>>9P1#Xyg>F*(P z7#An%h>C;Or%b`fd|1!~HJ6OfkljliO2nHCr6sT2za$Ow7aH?_m7t2g`Ijztjq#2L zu+TC@X?XZRA`?~)mfC9HQd8;MgZMMUTSr+B_1l)W8?W9g4c#y3It}k6&QR6GDQ1lj zpmU(#WYDIrCS;kz)iL8667BpI&YwqecD_tYdOOw3IGl=b-<7z9Hlz@< zWZSnL4)F*;`}L`6fhho7;KI;ewplz!QnuFp*^ExKR?Xy#KZy-}QHc#F33EMMTE1-G zz>`*E+%H$2U1(ddzCF+;_;;Gj_y;3GZ%Ot9dFm1l%3Da5oFAN3ySBV${De|RxOsRC z{?wI-98dfkE~JR_3d z?YUk75+^8489Wzy13<}9oKzm^+*6_8}jT zFJilCH$Xkl$Hxb1|0~z)&)F#c6Ykxor>x-Gm~*tAuxE~?qcvf30rbC@w;p!_h1h-4 zNHDXhvlSN39R|`eC9@+D<~d=LA8B#&J16!%$0Dnml%aZ6O{Lufrmo^{@3`%q!el@3 zJTK0nCEK>?6v>>m(XR(t6VV@QyGtpw6I`PxH2171;)+JGX2{2e(>O<9>k{uvb;WS^ zk1>gJvllhH^DR7klvW!Zz8h?hB+HvoMj$Gr^hUcj*$|xytnldmkQp>L?-yU__gbnv zx^HM4LsyB(oeS5wA4$zkAGzPr^txR{x%d(QB1ThFlQZvY&lVE@FmdJZf8&abpscCA z`fHFuKpfRAck=Z7`MDfK7oPnK@5TJ{|e9Kg0x1MsLPs((U zMNm$C_-MGcp;A`7KqK;-{P^LZRTOm;5iu*@Unx(;v^S}+3;0~l3LW3z_^|+Sl)QEm znLlkW1I5VQnGtu|e^}GcQsZjp8TS4!7r^#^1{08vrC2lUTN~W2Na4%^FJ}%z{WT%} zlg3p%J=W3FgW+~+s1+EtkvEz}*#W zNu;vzMqxw8-uV9y^+tgZ_377Es}4h z^~(>}O44iK9LxxMIHZR`CHmv%ft&id% zH=0!Z!XF{vLLksndKRUyfxll~t4i~I^I!Zb{amOoWOd=*fu#(ASg@{j6JcC)H6oY3 z@Ba|>)=^PMTmP^KNGYJwAP54|-Klga-Q6K2-5^LwDlMsWcc*j-LwDBzLys^tzr(%H zecwM=%f(_4hVR*D?@w*Ili}qWNp{tpc!hNP6=&VyA#R+-n>xXcIo<8X0mrk06E7m$ zwe!lkgQ=4_Dr==?|0mY2dWlArKRc&;&nrJ7m(5?*a6EWj%5RGP4Mbz1#&itTJr+X^e`Aaw8UlwPJPH3M^% zmXm>eFF?CS1H44N|Nhw`kC3D?$~-PPBtzI)qo~SdT6^Vg*JY5k{jPK6{?6U+a*Hsp zx^OOu2>&{Qko6*_{T59Oz3uv3(0!$3>eC4RszB8+k7c@H8hm@0^Z~w*u8HY01w-Fc zaf4Q`V3qLu3z&a{omEg2V-(T!wkNw`gYVIGo8vYE-0cX{y9^u`lHZhi#dTX#x4N6X zv|fB<9GMW}e`o+i1-OlDT>RHtKpWk8&bcY)LfeR&}@ke{$@Woo$Ou2_^D z!~3$6G~Jh>Xd5l&sX*GzU z3s1{M^z=LsPHxQyCMHcwho^U%4DI!p8^sMDWhqbsB02!*J2Jm)@Ww7KHQj%XWZRY} zd+O8LwFsbC58RgEvw0S7@(O?&<27uKa=D9*Ka*5$um}OOEc93j4;7TJvVqDg9~)A_ zwx9zv&LsQ=cp`Uw>SiSIiBm$qS{N3nfBr`8ZOvXgO?#Rqg1y znlSye<^kwHx-XBv(O`MogM05Jwv6 zXBHhWU;`wbFSsx1X(_j7N>#GLFS=x)5J_q*quZELI(wz|owAyqgFlpNsbMioY16#y zb4oX!Y!!!M>dkCnZq(A{M)mV7AxyDt#1_HMN7R#Wn;e9CE*PzE}&! zr7QihSkWHz`C~jfQii3$7Fx})+lou%s{vo(u@>7$+!9{oD0sDxwmcQ+70uhM`ly8< zvl9zXzA~)Y&*%~qyC^3+ma$rPxy|1qTVya*;xOd~H^pDXxborl_AbMHbJWFGs)W9= zqxRSS%+yWwZ|=}AHapNw7?mk}j*oh0XI4nFkts)yQ)gt2l^)ZKEoAN{$TVdTGi)C^ zb$hMU(;93;KnG`l3mH}(`1hZNXT2Wctbb}VtW!Mo9Zo~9qHY4Xdoct3{EG5JTS?3y-E-J%XCUZrc;0@bGg+Y zS~AM}@tqLF+3i?^xxKkrzIdu>{PUxbwCV*n{+3NZrtG@x-5C^5$yDR5Akx>1$E=QT z=A12uGR%nuRz9T6^|pPgyK><%f6f{fH@goMmbrMKNbNuUaClX};xh!!0&tapAhUio zd4`y`rWO;#o{29nkcRUHTI-`s+#5A#EgLMVW$`3Oyqf1xER$6KgGNT*x|raFl!k#4 z626GH2;+Xq$_5gB8n~!cOYKPrrMjL^?8bA+V|0B_Pk+_PMqQGcG@Sw{)=(S@BE??D z%`h4r^3;!q(bCG_yD_rI`WpmgObuC5$GK}z7#b3Cd>MLLXbiCQ8)zS?C+mG)aH(_@ zJmo;X2{A2ApdI3@nk@J*K}|DsRQ3T69ng(&C*6gz4r#n|c|AocZ5$#CHMnn2qU0`{ zE#l?rzd_km26LJ3j&kT&>5^gmfDbOaqztEWAO2Lo&^st18%8L_o!M>Z#&bbXtfh%- zsom=#WWh%C`SWK0K{#W-mZN83Wz}XP@VPkdFdq&z?q6Qc5LEoXiUBIF&E_XAk{KR8 z9ZBC-0|CRyPi5?*0!dne-U|g*P-~-YigQlTywxlmkRBl$rc|}fmpp3NFeb$TMOc6G zU8_Om@8+H5dJUgIRL?}MA^bU z1f$QkOcMSvBA4wyjvC=q+s+m~^5R(by(y|%YSY;7_RUmrxkqQh@Y5!bOYMCtC+Mr) zCTk7XspPL1^iZ}?_++ZdB4_!8GSat&fVWt4GiCi!;q;1B$yLRJNm!RA4k(;j@!UxJ z@-kVPm&D{Q=^igd55?-q+NR*xzTbYIBQ!sEeU;%5?@EJFS7>x_E}w=wEnd&8K|F6? zFFW2%zt4=)X-)dfunVa(Vd$7BKrHp3cu_(}Rz=87q z?rNs}p$}eKFn4f|0iB5%hodPkV$=NPY+mxCQf_d70Vs>T^6C_*F+j)B15B-YJa&ne zj1U1>G*aC_dC`aZ`*Wd~IhS4^cId@sGWhZbD;pdjJb;kp7Z#*6<6@|xckD%x1%H2|B1o4nm%G4z8z#6N zTedgFhdn2*_q%(7PT4=P$ep$5o>4O(ydg5G!};^Wv2P}*et^JwvKn7ohcV$d1A#z5 zA<@l+3m;1_D#A<+G;zU~RBAC@95x?;X6B!lFx2W~tqToAvl#*E_s_pv#z;}xqU-xS zsH{BE(ZNBZ6z}yNlP-^jZfH6j4o{%%eU1L`!fW681D*`%5>b1dtakh1qiT_5(b%eG z0U|ZnpIg5b?rm3rR{(zli@Z?Yug0Hc-kv$O)`@GAB78e7;wt8HG^SCQ_#KXvB{QvE4$BpWcS<=v0hE7Zf>sSxPW^+7m=dRt2ws@h&P}H1 z+m&n}=Uyn&w;_+juYbk$p~F9b86G_4d)^yzr%9QN>G)Q~z&PxJzt=>>ko7SBNIM>O z7mC}GFkZMvllS`4ALY~MsH}5V?vpEV=0i`)q86aSLt#LbtIW<=YOkK#XyV`V zeuJ{RC2!GT>uZAw<{3KG5&?$I`-At|HJZKonLN!)v4lM2G|{}gEK9Doo*6ISp2X2z z&Lrry9jTVv)g{$AvH%Ip&jno`Qh*K!9AH;pM$Y+28ThK;tzL%2v!22t1RgYQUCK1_ zqFYx7u3ZSe^-;U!bJoSS+Bt|AQ^I(FL;R(-j`9MAo@p0I zGjmvO`#l2#(H{^1!2>tS@KAA&C#n4UNI6IQ;)|uJjn!+BBBkgX|GOLhubRkh*N1{E z(n%wG-U2^U><9oW1iBfrR}{}fC_yCz#F2u6qD=Lqc8x<*`NB?$LO!s@L-_gle!Z&w z7MBd7hG?rX9^_rb#mk_NLjQJYGUCIYuY`KgpJp@tm=EI25}E{TZ*i`Me)+MJn+-8i zZ-CemeCzlAt4vc!;NPH3?%M7xzTWq(qsuH6f{4FX;+7=emO4u}=UpgV5Q5u`5DHq3 zeVQv-PeCH6bmp#zqMIqpS1Z$1clklM)7%?1w{9;hL5PEolQh*ykhHarKMX4IQ#4oU&_jp-7RBoC!iUIVa)xtV-_|V{k)$)+GvujwX>=wI6v2UDE2^?@`iyq;3xG!xXGQo29dvQ31dTfmwxr`fnNT~ zQ8`m}ioRi#xwht{ZV4kyx0Jy8)1ghB=V))5x*hzUZqQ4&K20GXL>~?v;{DE@s5o`nbquUu4-Z z;06j)f_ilK_SjJF#4^_kvqJ)1#A;a27XE)au?A8hU|{(EH2{VZte(1B{_R}_YMP+n z;|r3t;rBDIe`XUp_a8~|2}@ucOMj`5vy0Rh(y5fiVIdeRK*%ZrcF3B?|Y(IV0 znxDaP{+_6jB$ir(MEPS}T+Y|~++6m;qwR>~IeE=+!mWlH`84^wz?;Q}7JTk2Q+090 zge3#@)4qs{X`zwk$l-Zd=-IKdoL|z}H#ZdZQUm8k2#2mkH(}9dw=RIx1Ke*?_5YW1 zYAFvbz#=FvJbps)^bLo6&s5i)RTTVpFD4gu%f80AoO%4cDrSYi$-wRs#||ql5JhlY z-+mi4G$ao?=E4~m7%R5Zrf4&vkW6?Nj_C1v57r|E1qCn&IV!8P9W@K7Cm|d9E#H-D z6ffD_WI&%!KK=b_GEnfjy?XG?@*(-P_qBv_(9vb|BkZp4ZuuWGpk$e3aBw|>%0i4C zIW$j($OMr< zrU9__BF!+_w7$Jrv3%yuQ*qh}4C@pQ@)&-8eh>^9cw(l9J%2Zv@VL&2r>AI^%(%iS z!+K5aY|1;IMv%n#YX$lG<#zM0coUIK&K5EbGGfi(KTpbBQdXBI{G6amcY@(Zq{J_z}FOU*~Q^Vx-M`DjD7 zI7%ulBSWQlDh*lu%;#zxQXEt1E2#|D&;5izNuhb~aYtciY4go9u+kRDNT_X>q%xi+ z-r1DphR!foALv|ChVyLHsw?D9DZQCm8tpt+uVzK+z++eE!5lp zlc&a8+P=gyjC1^)+Xfb5tuQFp@ie=@zD(TZ^VcyliPIuOz?U-te0&#z*CKTGBrYO2aJiUHZ!AJ`?($Nk^2X0aGP?a84fKK^Bbjj z5T)iXX{wI}SaGf2HY0$Xg)I{zTMc8>0Baj@Bj1_=a3|uj^B@TfWP8Tx zyS84nzpTF*);6AS%f0~oj;E@B*IgUsmb<$f@zW9r$AA{?7Jk zZan$)ewaV~l@KTKxsDCMiTXgeNO!yc6)zx#x*b0xT5f7bYcw%EAp{255d{dJurN0} z#uB;TDkn)as4zF@+q@z^7eK6|?^yps#mU8```Z1;^KPI28trENWcXj5ot>5gS`7^3LbuK8BJ)+=gTA@05ZyZVJ(gW~2}elR3pN^ULH>p2*Ac|c>og(hG&3X#SL`R zSNWI2M)RFGF0^2^knmKcVL6XN?dl>nbn4MPU*=5@X{W%_$*_34GH3Ol@- zk7(z$AeL^s(T!9TybqU`m$iNCs$w=D6Z5*^m*FbQx)Bv|=Heffic8VI>cOSvh;%QJ z#pHw{N6`mUGE^>VNuua{;oE^Rr%w|2Rbi)BJf!sf8Z*%z;zGm*?eaCi4Ck zeb?+N1yZ}r08)i6p3p=}k`BCeI?Z~RNT&W}&3|Vb`vCPP^8?$Mb3dVs1opbNUvO8^ z(A({++C0;WBR{%B$) znP^wY(%)bFXxwmwKc2%(=i`u7b8*L&w@yKGi*a^<6 zi2+Ct1fxumHnk)V*t^Te%DjGkzhc$jPmm-_A4R=EYn#lv%3m&neB{6N{`IN)mj1X< zHcN5$-5TB>{2|>^?(DHJP#dD?!hvY*=C}(7JUpi>cMJX-bJdmrP!SlPAUJh*bJP3n z#zk@h@xO}$)bY^`Fpq%b;QHu~QNmM>YD)t4f-H|K$6YK4+`6vidpxSga#oJ2>zhHA z6gs_DcZ7L{C-bi{TQHZz?FJ#Fj~W|VUJq51CLP6_!Gl!=jt&p2IA?#)@HV!Jp~oBW zsMD7!1v{}*riM?0HP!98n;@qP5R~BMOZG_}M(+?MLoOEK%TwEC&7$zd+0q5O5^{%Y z1hs7ccqFgGic^g1-d;VF(~qfpGw=_J~%zxP)dtAkrSdU;~C1rls0xyut6Qpv_4C@Sv7I zKK|Y+yzzO|iVH~dL2I(y<~cML`i6F6py;+FBrf|U(DhzUWZt2WfQI9n=tEoLe+xIf z$@IUWFlhH11`WqanlrqzDqvlKXWs^DO%wtK!)C!|0RIGW5f6h2qQ&<*5r;wq6jaTT zAI%>cL=ezrMPL8sXPMV`x}mL7I#jIDrum0@n$l0+zXRa2ey1NIQ$YMu-dXKx79RJ> zwnvrk`Lbn+7&<}31A=|%ZGE%`$rOG2R9rz(FiP5uGB!3g5vaURkabE4z$0YE z1#$x1DtX)c_$x&GFI$hj`RHr|)$;&(ZQ9jHvtE3;doEzSfmKu{QD^KUL>`y78=lg3 zb?Uo956h;b3a831srN*vn}f?y+d?E$5P|J&Sa#UHCoqjT$ZN>y6Ql0|AX-$`c?)>r zCAqXLAHnEOiN^l8dhArit58RvYR8sv5tO5Qv*q~AS}C#G9Wn>uUetM-v@UB-E0lI+ z{Sy*e$;U^LIN(7KV8D#+32cZ|s2vVBvC0L&)6uJ zT=nls46YEkRnW61XDN;-gB&E2cK|n#Ai^7 zs)w+===U8JAt#}C4k{>$lG|!|(jEH4<-_>8~;SiMC&FI zo8`W^t-Kx;*_rti14*p!MyQ(Cm%oHNl8JixjP$ayDg}5|#I7{pF+q&wf0fS?Bz+G4 z(US(;8=z%e0b0Y!@G$SnIfoOItvmV;mi?F~$D0B|uVenwS2LtAr!*IPX_ z*(d!y%T~EjdxG+MiMM7#lu@cW!vx^&1=1MAiZ28d0YC3sQfu32MXDD7oOms>9u!fH zWzgdDzI-No&bF$(`N(z-)x@(z{e4PKi?36srxVECl=HmQY0qtpLu=Z zFO!y*2IOeN_VV5}7#5xHkTdpunixg;U;}-f`XrBSCnKWrDuWt)32Ii9NnMRMFo2CJ zN;z3Y4pCyC0G&?nV%UlRR3eAF!Gd?DerPL?c5HJ|1wshoyUc^dLXh|4*pzNRj(Y9% z^u-Ed0G0oTUTg_kj4J0$-Xa}TnZ_H72jJoeOlAdLhtI>@DSGbwJKt0m?>gBB*s$XTbH zFMlDM@xF4QOk)sbG5k53M(=O9iIXukPGthBpHnPq=G+ve|fZCY|U8t&7{88dv2=AQHM**I=|u*S>hz&HU9A* zkSkp)cSoz#Y$RJfSCv;aGY+%LK2P9NZq$l)kqyE+?JW2d%SF>n6QL}FAy)e16gA_~ zdnA>Wk~%`S$Bf7SECO#SN73VtM?1v}@P0=BxLh<_ZblrNox|SA4vH#ghtQ1JsRm8Q z7?!!Bcyu-d=g<18Fxk1k`svq)Y7=SFHoBdUmmv0RO47PUBjn3W-FMUKEeCsv7aH{b zkiXYa8&kA??=5=o4l7>*ldIs6AiYO_m-Jc6mYRQV&x&tvRdi8n8#Bq`^gq`L;ejIj z(@wlMhY|w%oGk7cG6DZSz~3oh@x-XE;=vExQp5VW$$%%X$ukL1C>|UJl^eCex|G4N zx;nYbm_o9v$?h8seqTgyZ{L1-z7m=6xt1{9*UN9y`aQlg_w3Vl{$MAP%;4JR{$_Vz zFYlwc1RtIN+yr6;sq6r#Cy<~4Mg6~j@$N^6`ic;YB=o~HmZ@Jj3^}w$B(EX=wU`gnkXjA9mGat3zY3i3&wk0zgd~H*CLeZwtG0{K7 z#*faeC7I`yNxyNOA5PGB4N+Qw8+E(u8VCHCfZOHc7g^i?7kOf~FXO46EQML@f=qNJ z9?J)W`Tvz=Zr?%CSX7s|9X7*pjzrmBDe{X5Y=b=yKGz5JK0s9mY=J<=7GxZT8<@p5 zj1+hBU<_EkIS=7=SpMwe^w)~dq%Aql@^ae})27|f3X~0gAMgHDUI#va=>nadhldq9 zVgNKmWn9tPlE;^Gjg^)D_Za}u1~UmLDo;bZ@K4tZjUdvg_sz{VRA{y#<%0JiVA_W) zxsQy5wn_MuLH1)BaeU-volEF2d5>zL_g-BIuGR%oFXtfhy@h?Y_f4=tidPiXNK>6G z_w*_7!zm&I?HHQPgH{qFpi>1VtBvo&F93lD2F8Z7XHSsbeXF@Cy-OkRo8F@-RW8?+ zTF3Q5=v3w&{}u}jPprWz5V)Lk-7FzC4-9@Q5X|qol(z<9?Bz2#&zcZDCA#1w=)I`7 z!}+F+y@mIk$R9$MN@*z;^-r=(O^70H3+IFRS)q^j_YT55OLnf!Q#6G%>I|G59Huz- zZ6FDV@7>$4W^9Rr3Hgx;KcBm}H@pn$a%^+P-Y&bNe7ydJR&@#0-2IKIfwu(}Ck}Ir zWPgQbp2W|`=JMUO{TzRIick=0Be+g5R-DC{4_Hqk-tWNIJCD7c&0qwhBuW}&`M^A(U-@` zP_KxheDQdNyFQB_zll&bXV%$AN2E5D{ro`7$zSV!U^&(p6zrzz?etcoc%@q3Sebj4 z{p~#CyDl-1x`o#ib~K}7njUqYXDoz+v*4-^9PYB!le%0Gu9WSyMPr+071Vm1GYv*Kb_)`wk-6T?Eo+lcq2A#Eq4SkmI<1?y3fAhPnaG z=MuT@g04uPwPIOITSO+S+>g`+(S0Huju_V~-Y{?Nu_ zGoiJv0kqF-WZ1w1yw$afww&2w$wj7&kAHvHexJTJ{Qbo2??Z_Y70zd|aY(O5nbroO zB1ekL51=$#1Mw&f0kk+RzVO6{nnd=rFg)D8G4w47mjOg9P8*}Z4I1t4Bd1<@*Yxeb=x(t`XL53HHgiykV?*~}6t6RUn_1FrS zyu7@in>fC^^?txzjM%~=;O@R?U#adM%u)cl;sg{*j`bk;zWyL{6-+G?7hk7uXSAiY z;{kSh%6fmw3UDo;4w#vlx!G0pU;p>dWxMS{O-T-f^8(S?gEJnWT~*D^qywSF#f+e$ z0Z|_aQW28Evdyp&73uU{m6uQ|uS3Q9&BjTm{q>EyplMq=zAxy9jMzMCsJK5)uvRs! zscx8#@OQO-y7MspAUDCq5DNaNfG~SUFIm43HO6he+ox*Od)2&fP*q>wH#LP1ey_#F zMF8bG2=fXhaP~9>-KYximFS`$PonpE7j1khC64I>WjBHN%vdBbkG|D_wfC4>_J!!o zx$Cpwr1!EE+kwA#nCZ3_P$legTb!c-%#%Oy4FQovZ8`7{HMtqHs;Ova7N>iSv~rL3 z6$wabD!;Jc{R(k}gG(_rHB~w$PVp?wGZQMQJh(8;J68VwS!Pb5dzLMJml$XJNL4{B zjGCc$iNtS811gOoe~& ztSQ`mLTX#l@ni)(u&7Cx{i)XZuanBpNn#uYBuUSCBFOx!*3jj8X6lLjoI|>aNAG4xc)Y2 zq_o6Mzz{o#Yha4?l6=ogze9~tSV@<=;aQGX8e!C)==unXYok;rR?_(K_=(shM)g=G z<`2C(f=Yt@mrOiCat5BswQYY}f6;%cnC^Qcl&EJdyqdi8x{{nA!B57yOfK)|33kP_ z@l?sMFSSzV&tZKVnq?iPmVIQI_Dh?Wq8oX8S8eCFCuF4K)R5BxsdiTS0v&7;yQ!QP z<;Mn=0lH$9kVQ{ASUq=dcS(!KvqZJLa-9;4O*id?$-E32q(nT{T7;lKS*ZJ|jEh+N z3L-rJB&@^gv&{$e%Tsk>eRPZ&Ae^fbdLz#{nA75VTWf<^SJULoe!w1~Zdl}W1=UK^ zMOoZkgc`DTIY9|?# zMR##~fLUpt$aMAIrH!t07Kt!$2$C$nI`I5?JXYiyQgSJ3&YwlAL3`w>W1h+ zw^u-3j_Ca*1hA}qw`inuY&>5*jWozRg!Jq6ty2=)Bz>e>UghJm7n z)mNXdf>}N>lQG}1)`pF#=xOLVXc`RhW+N&gyY9SY@@WIKQTD{{ck?-wDj_~b6iHv* z7EZ<0P(R!Z<~V9&z>}47-};F*kqk4gLuD^lrBJ$E2kOH8$1a0!QTu+4ws+~}>wkVh zwNk|t;T#nT)cjL7w;~%L|Es1l3x_JUWr60%rR7(SE5+~H#I>bUi}csty1I9Qi!Euj zh6MDP>ll|S0@9zJ-oNfl)^`0+QFgCw2(GNZOPB0NF zX2L4uiid<3Pdyg)zrJlMY|4A)TFe|+KZkRb@r-BI=<72cEwnYHnpQd@+5kyqq22Yt zrep?lLdycQT(6W|tJ-(!wB5FUKigBP7MA$rdTV{w|6g)N8%nHBVqou8AE z$krode}$5X#h)FY>5w5~>#jdTZ7rs*iD%wniYrrHI4>(*d|)NmBq#8%R;(L3SUgEc z!*tb>SulQH_#9d@B1v;*y7V0dsnk(6aFWE50FPl2smEo++M2+ll%{f8cSE$uw|XPi zj$H3hY-0@f0Jg9qs2pe&j571&dD>_TwFosm6btKyl>mW;O0B&OsWpGua()@iE-l9X zF%YEB)9z5y$d1e8Em~%N(d1?LrtQ9F?EVVtpn&Yp%Si@2jv(0Tv}Vl{^V_F*JKd~h zXeuJO$i-zVMMvh!cwqoNhzT|ynkQubL3mS^NE@Sw$Drv*hT8sGIdQAhF5aVgQI`E@ z<(?~F`|9@`I_3B&+x<}XkoifX1tzg%FG|mU%nbRWXC`;~O8Yf2x3jQYJi80EhM3`d zh~qx1_74wF&&E@PjW3$Hz&5qOdu#lNc;L}bZ|TzTk7!*IcB^xjnTQ`S>pVLH=!{s84hO@)7uAITfB#Ec{$o<>&Lk#zu$PHy4f0^GjFp_#^I0H>=N*?gmfo2O(TI@D{WAJkhp@fYN zeGq)h_pWF#!Y@!xM79D1GRCFUKB?Wj6uv7tOQSGq=TZ^rU|jXLX4a*;Y4r&9`tqpI z+2th12QyOQ;&rE@+zHxqKc#Srg!K8YqXi*VVvm6m^36ksU`20>8uRbjDmkJKUvC$F{;aX6z*_G{^ z#Cry{U-{YsG~2pIGlQCW?%=OulF6U(S4VoaKcD@jc5FMCpuK|8$`$PGb#xCsDSpkDU=)X~kvmJ%lO#G* zNue9bFIw(hwfq}pj3gm%wkgn?VEMvNm}XnwS-;fgU-z?tTP5^gaX~ee{ngVZJ@wi( zO}Y%VlBQH2HI8C3mc$n~FAC(SUc}92SpFeZ^6m%{?8n@uz_^Pu0c3Rw5}~_rkmR<0^jEHwBrv zITKb(UxQMEZGDxg3n+!`T;G&D zA@B1@&}4&<6?B#_G9Dq1b7J@%?$ofcGruBts=kiI@0ha6ShN?U2r9WcI5)m1W<+HpmW{)n8*9jN*jMnnT5S3r2}!hw{zuNGlh(V*ZdH|EKCTW2yM z`qgnOm`TzyGZkm-Nb|oKl=p$4c3?#UmE?=Z$LUwB(DEfykvK_6bMZNGTFM{)x3<+5 zxv59e3(J1ne9Wl6*U)hW+N&%XPpl6T4R~wm7q%C_*qtxpcE5ez$@7FI{ZXX4NmaQC zMfbNuzr+}V-q9Ru1c5PrhU)1F!&xqF$Kzmh!d1k|%|89>;YRa|EM()NG()rY_KyGd zxOSk2cfJHfl*31{NNzxGmz6)vo@3F%@8Tg(MoyVx^(f(VX7pD++vXn-dp$?gvO5l* zskxGp$ado*v2W|UPoq>s##V16AY-#8IuXjWvGNGt1|^-i9AfLlxLizg8zHph&zZQy zmieD1CFkIzLf8s4lj-_JK7?<>a~i1W9a@5KAsEjkkmShCa71Hx=>2ENSQ#p2-mibB z4%ohC^+QwcXl)UGf#HeDmy25}+>uUQfVwhw{VuJ`dZ~ewPS5nRC|+!f7+hs}J3`X& zodT5HVkY=h*l)3wu}j}=e8w)}4&x4Er!)QInd)29YrQq#r%XM6|Ci|A07~$8IsNTn zT<@zt%WvR*ZoJH=3p(*^zL2e; z|KzJ(#dx^Hwe;>%`VukP7q_i;*F>SAU9(r=C1DG!0__gU{I|@Ed7^|WcdD-tpj(6S zx%nKR6Rd$Y|zP_WcuWy7;dt2LfD23lD z_z2_A24f7%IG4GNO$4yagUtR8AXEoZs1E*zRj^(DZgfbo$5FT(&BZ$;~;rA$O@3D;u+=a>1xq&Su5?}riuE#xsiccwTJ>B;%p@p{{} z-Q$FcAq2$7m?k2?s}Pf8R^7##Ro3g*_x)oXmRXEgYf(w(q}o@%&#HkE*<<@$kMjN1Kte!{}h73p-?V^bDJY^Usoo1Ha zu(*)pdBMebPDh8KfPvdE|eV9$}Oz6+w+OZX`v*|{5?cz0&BS4KkP)F zRapqSuKftRXyUbIe8IUOZjhjGZRUEOwxbpflP%7kDS@tdHxCeueu-vjG#69hoO&!J$PMU_8$=tF%a3M*eo zCVEATny9d8n3m|YwX5@du`~DaSZTpu)W1%l+)DM10>QyUb4$y)eE%X|0@7{%10lu> z;aaSxm_fhHFc>c8FT5ch9OwMQQI99hLWG87<0dVcSSe9N31iPqYmBp#@BUrH`yQyS ztNKAi2!nzr0HNoHXkIx{1S^w;{O{7JWo0H@q+ZR?qITN&JrxA*bw0AwKGC}$pp8^? z)lm$jUt5!Z)1_70G4Y0J6D{J{@MfJ5tU3gCjml{!ptXd}lzZM@af1_d-V4i0Sf<gSIrFaP| zqxnet5?BpD8~fuIPUAXIAQ72np$l}-b>Ge*?Fwz=S z$iBH>T*AZ=;-fnseEU1h&c=o@b}3>RbQDK!&6O0v&`-xFpUt&3 zv;}L;OZIA$q0l{`3gy$nLj?qfK{=t_{@1{^l_O_2H-dDX1&!-9AHqf~A+ESK--87! zL4uM>_7S4Ntgy!^ZcKlQHi8ZoL~p^J)-|bf$4Yf$Kwp-u;0J%2}?ePij+W`5h z$?Q&_Z?4Bpm}fxH>|ad5$N+_JN@9SJ!)&Ou?Sbvm{KtN>!K$aZt=u<8Y_D5Sh~w-` z{Imr%=_f%gpE!#fRH%pV$X41-=Bv+XQ85n+wh^K*VrZz851tjyBbFn&iUn;{MTwsS zw}NckmhTQ@VEr2has#oc-J4B9!)=r3$6`+l%_JF#tYxOcgfgkCtIWXqI&CXN#<{kD;044>pX^OB zfJDTqKKV-y-`^WPup!=S!qXuD7ZyZ;L>kz70-GVHGegbCAY7aY<| zQex`03+�KW+?_9#!mkHE>B*J*_X(F(5&Nj^5Wwabp@J=o=95GHeiZY6HkS-NscPQoH(Htrl^Zo$GSxn&?=pV=KX?TQ^`w};} zHYAHk887>1=!{Yc-XZ~YS~0rLB{~v{B2WGLheIqI=GqIigNkykXZ|r&>uh_yC#`ga z0_rsj&6=qsGhYfS91Soi2w39jipGmE*H0u(p6k3t>^(YGU|kdHT9>O3E#2ESDdAqG zsvsg{Ctr1b<0%rHaGBo?ZA%7cL-g(A%e(Uf-MbCZyRYEUFEC00lM6Ug_C>i<~rZaM4P?;K%$NpUl@Sy z*9WoWegj;J7XLv2ftU}>dH*pjfzasT;bGqQwnc1jTcsVhmk{Mq6J1o)vYlW&d`O=J zNt9t4LzFoDxO>JQskK5^q}eHCaz_1moueEGBd!#cIz|2OgwB%yr_K(P^&%qC3x`KX zz)9tCzE2F!_=DRLFg4>`Q9sWNQ{Qw!55F82#xPPnee$(->XwoNV3H2M-`S8;ihW)l z5qVwEDV;s`;kpaTW4KS2QCeSD=W((w>0{1_%ZMEkyQno+y9qjEQ1UG z%&Z9x5@UPEJ*S=t%yZ@rlwyeMd#W_jVGYt?_We3+mj6v&L|Dz$%s9nU-1CVQ8q`jz^XZ)dAJET*iLj4YNlqvbiEOnoocSB3)H2ybO z)+c<0BI_Q!qDqOR?OcNIr!^Ehhdc5kjRh?ZFSq3(Z)@o3?h~G*zl*yTDVIQ?H2gdi ztQjbsi`yg7Ri7;i)KExX(UcEh9j`GD5NOgibDH*2Z+1Ot(ah3cWxFrl7OFv)U8bxh zuqH54kIfp#OV1T)7Lgsrb~%vw#6~B9l|?2ec+|b}9X6t)==PR-;+XEbPYJ)&pRl}_4Y@D6 zyur5l$Vn>@kD1wwz#IKWJHQe9S9Eh)T~a+>Ezg3F2m09q&uWULb@5cI|S)cKynBP8M>RZdEW21{HtqV&EEUIuiTCRUv8j_ z>Nb3v#iGUBi)h{eeTklbk?jrB>AR$+juwrt!2K z97AzPevV@ed_T9Ypd1>~V>Enbd)|^Y{y~e4Y9m-D*#R70Fp3h3aN8c(vmivo(EXg9 zIe!^|R}eT{vP+l%)-pRcw+d(k;2CsqcPD{$9}8~wgkl@y)Akftp8dlq`#V&fH@~|i z`!cjWg$^Bj&!O7 zRJu~l5%w*(mMwaFZ8v`p7ef=lmOAVs0UuX=T_hyYZ&-H+EPNG_cl8j`tExwL-#DeGqAk&IqPo7QyBFcy9Pc8gxKRw6k#nFHzYS;d{12TJezm74 zTuyL-!9THO%JmOY+kZ_uwN)mrZ*^}^eB^S(!Z1?sElOV2Y3lFXXdSI-J+|#r0Nr-F zHwD~|%3N+-0K_0%p(W=qJGqW(e)~+V>pe0`v{(y9T?mHxzjj?Ig2N6}98V;F$%v%t zLHx|FrQ77A>ro$pL^ZabAN;l6vIeStmzYM|E9bnbjVFi;72sB+656W;&s1%w6-0ouv113{oRfO z?Hrw#`qfyrzWoHGACNKbdpW7**8xv!&rH3K9p$+8kQI{VM+01ZjT#mESg)|&Y-=f| z8MkN>KJWjHLfuN6UMHglL69r8u8BI+Y1dcS`+OCBY^jLxTQ08Tlg#OpjLlzK@rE!7 z=1qNEx(@<4W)paP9)9I@XPURRpYSUrvnL5;In;mIq5xcGZ4H$u8mc;DN<)(W)@4`f zbaZvcTBTf*$4{JZZ zY>;|1$WQ;vssn{suX?E0R^pnu6(WGkiah~#hr_#Bl!n;0S9dvu%=6)9w#>X*|2n(z zdJ#3CM~vz}<$USPrt8+~OJz$DTx zwfX>?iMdk(-WKSuq=ot;b6fg4hf&N*N)tzy$};rN^_ni+ z;El`ZlFC=oh%p5xSO9*%wR8y^VM4eY{@a3r@{Tt&W~AaBh*M9n9X^;iy1K;ZHUp3L z0W}U3QwM;$Oc}Vf5gq5J9^!Xy@u_ApkR5I*sH`a0Vy=unRFX{?Kr@*O{tPb&5I*UN z3taf;Ok?EYZ@~+*larBtr=mH+v|KrD=KUy#_PRT z)NMK&+)pwH=wN}-%L6=n-rwy<*}f?Ne(~`>yrb~fKM)LZF;(G9NI2%7h+VSs_M`9X zTWDZmAX~_UrKAeMx#o1}!g*3msN%$cyI>4rI9n#~_SR)o3QtfQ%(y0Hb%0L%!NzG# zwUL*7!BPu#bK{9W+}#)Z?8eK~Dq*13iPx^Bq0zf9d*P)Wi?;U8i~L*1$Dzct*vloK zq&)8_NdJ8aL5E|^KCo~%OgkcZx#Te)f?WeE#=?*>HBzfeg z9&xW8VS@XV#vqFD{y(r&0$1jQPBDkw=JaVP^EC38a@#NV$1PT2Zd~%dW6TdLV8@h& zn+4Ata$VAq{M3cxb@tP&5R1qAif-kWPB6E`+QVI6(rdk_~XNEsme(F}_l! z78C2(Y1@Sgy+2~MQ(=`QBfP3Yqmfk(mrk^;o+o^B7;##!-&$ADWIl@Dy~k~}rH{EW zXAw1)G(*DBOn5iicM?W|68SJpKsXgcR^wGDHV~VBtCElou z`YBPEkP7RHeSKA}UD=_8hd<%FUGnmB2i@GndrE$2l}m7OX|U_fG>Nr};ZS^YNo982 zk8+6|xb!Z0!bI4Bdyq;)_+|c#>T!5uyJseP68F zn#7Lly%rg?M6-c^|Ez}hvCgs$pys>myr?cVG_%ENyxA=cX}Xgy);6u~+Ew2j2^Fo~ zW}@`{_P$%ncpo^v4|qQ?KcWDhg9BszLCP~a3M{iL;0XltXNA&b6WOQ$*SBVB*A`Qq z_LEuoc|%Lm(X{Sh^_VGp4&>Eu7sBg*4Mkblw+EoX$YBTn%ND^A$PfdHpsz6=2&Ro5 zK`qHu@jk+(2E1k zud<^fHVlL_@`;GV&K`mhpw;8}Db$7~58=!YuC(5LzpxJ%^?f7Hr^WR6+Ogv4!si#> z>11y5{g1Hu>7}OktsLy}h0uxYEeB4rFLdZ&$e-x_2Xdni-4!%6stiJ1H8cn_ujjAz zoZD^ky)7+BGLuv%CjBzb-l)xqxPHIUh(CHt5@wHlBgNS67DKUlvBY=RQU~VZti-Wo zgYhO#HPxGZG@+aB+2$gDwznTeQ=Tn3y3F%^=lh96!exUcmqE^JNpN&;`5OF%3v~2f zXysqrC$7H39X%wv%iOoI00Y&Z>E*SL% zjomUA4ZkoJmV62!BlKB)y{iwgwJe9#^f7lS=K9*PR~J%^*celo*wbj|+iR=?y}OTF z?wlW4)yvP)<9KME?+3kF?m|Qjq&fLDiS#9(5O%P&!$z4`gmgZd4B<_XK`9Dqf7j&_ zJ=aySf+QWg&?wGy@muSwO>-GP$3V~$JaWJaG^~^6flDA*Tr?DkU)ynwsS=}{g6~mM z%A7(j3gz1;$nJu=_6HFYh1bCOYEEN)5umC4Lu7Pd;jlAhB=+i zDr{RVSdM@n%ql$V=bPkhN}<*8!g8kcn)dphxvk$gxjcIwlQiNF#J;|C?nExeNH-VL zP(1kFGVK2tZo1y171VwKRi1`(G*j3?brVrEgwk$pVfm0}A#2nL#_Tl^Py(bl$;%ze z(tgHe$*Ni(nf$-|;!RLaHlXN1@%sR)?_s2j9C*uspS{AMV*^M7RT!_hAn^TX?~RF~ zeo9oc#LkvRZiJ{wdB0p!q?3D$YcQi>q9tM^NU2J&R-}DL#J)~^+S1e0L-LiI94lA+ z5?mS_qyum~?*&C!6-e{qM+xmG?1r-+tnMy-w#RXYlu`k8?p=q64z*YvrT4Jh6l}S1V%Cq6NB^KI!=d{w_GD;(H3;&9-23R7 zq^9BdS=h%%B_)uEfE-A2U*W}JvneN;l;fSeXbV-4Q&~wwTbmGIbZ8h!tJfZj?eEhs zeex1c5MC(kzGzZv?S1-!rCW^=(c|f=J%rUOcszKP10lf*h2%dd-8|dA`N9$-E>D-A z9r=GNnv|*v+~rzv6#&H1TB>}q8MJ}tMwmdePXB5n1IZSK{YIMu^L(`;KGE$W{gio` zm4=+DH!>vdp720#lh-Zg*<;e zcvNuk;T$Iap&FvpWaQF#%`@8?%jeptB2vG~1G&3e6wYXMN{jnxRF+-B9K{8-NDn;| z>T4I)z2u&j&`HitYELNAkunw_(TP~6q~bRZI>~y{@nq3DEO3sb zWH8~Vm_u>FzvCm(;o-CJ$a?cpl6&1mW-5%Q={=+dkY!3X;WVIqq2wUJYRmBDcvT)E zUHpU|T{j;hi_^+aNiO%#vX@j}vsSvWxFd9fQ8qb8En1FKm)Rgp0-tN8lPehG)sV5n zb47TyOSBb{*M~3_ZTu=Zp^@pka+tVw)Qi}kC)c;A@JR75Vi$WsWfK{@6rk1=&`h4T zSy<dy7jrQG!P1}tWX2jS%h2* z%Mb`#078Lx;@d|@N2SV+!UUr_gO1&noG-^fl5Shb_y=pFPf^(=gVIPMhbUeJA7#eB znjMZXCVV|@sb-=Wr)yXUU40$Zv}ew-nGf0U2&xVjmbSBupPGn4on$?e*rpA24OlO~ejv z=&J8%o5n}G(!jVnyV6o2a1eT{_$&DMZ&t|dBu0PtDUc%_?t^gxjQJoTBr<>Y5I}tZ zyy!&`u>b4H1lndGoR$o}Z4mqpAOpdq>bp1V9$v!-PQ^?yk-NTaKuu!Ln+J&?mGbJZ zG-$|#=hqr&G1|eRaUqfENCDyoP>RT4BD49>Ge6wCR{U%nBS?1<^(6F5z8YGnR&1=4 z`{NU-i+nUz$*o7MWJ#WIzVb911&Nqg$)Z&FJu8$na_qZ-Tl4DY^O1lHs9|TVjNt;# zzxmO_K|VYvDThXLDEZ|AU-bqY>;2KaEaM%F`tLnWcM=+0T7T_l8OM38Y)|I}$19}d2FqU0`rwL~ z04abk`*b~?Zrx&uC2|FwEo5lJ$h}>+Y8E$3G(XOnda>I~AWOhdKJWWW-gwCbH^(F2 z%(9O6le1#b&_9^zhn&fIyc1zC2XkasWFl`qc$x7>zPbY==R1yAjlWKrP`Vg0W;0q~ z%Dw3}gmDonb31)4Q_1;h@+AK#V%u2_AZ^{6by^G!19|Sdx+2QaNzI2uE4JTqBuqbD zQhpruWY>ju=oRL~lXezAsm6MP2;6%)oo(Y^M8-g<#1!S4Lf4yz!7im6+do1$M;P`= z`0*wMrb4{Y)pg3~8&%@|zjzK3l2b*$@xMY(H?y?u7zcXzO6a;?g^TcXHc69awLNd! zDmL>;>vA3S=$=vP2<@s~3UH%Ao8fk5Cay*Vu8A(*%q!e4QOcL~5~8@WcM+oeK6O;R zn>G++w0jh|Z(teB&NZjqulhcNAB@L`m)0-XpW%*UvR| zSlYEa88;2s+Y0JkNlb8|-zn?Kgm^qdp1vQe;^Ys3(IQ4_D)obv zsBXTinx}~(F~y%sswGSC^sc+9rqxG(8n;NkUsR#YCa@Ez4?^7vUb{`b#@KCSej#id zcq}E>*B5$jA5)rmCcbu;P{4b9X<=v!NK6CD?f?sS8ylO$MK}0isln~TJDaEqNMNux zT+GAoTv^3GZSY=jmHy_N+}KA%b*|W&Sgu--;SS$elBClmOtVoQ1rf$*aQ(zUc#-uV zAnY)3OmMW~qJwRh^1r&>?$>s}by2xu2KhfhQ`G4bjECI?O$900zeQEKZoiy%rM=cn zJj@!0F?yr2Do#-oKVL8{9s@JAFQ;aa{FSuNYXPhqIh%7 zj&hxI76K2YsTd#i$oJ{5e*fz?@jmN7Jyq;a-?po8;m}M%dSTSN4l>p2Hnhju#UHUH z!Sz!ib>Wu3^;lq3ua8zdAahx-HTVV<_l_w*GoqHS+{{DWEIjiyZl0>R0(k09(6+7g=$HLrv3356=>x# z$1(ebT4#7zkNMqQ*O7(CXUx0B!e)YN3sZeBX~_j;ZnajV-Vn!uHzSu{Xz~uLq$OIu zg`{H>HL z$@^kltSYCwgzLJDc`CNUA23w1I*nSdLMCpp1O5rDO zE6%w1M>@#reA5!$kf+JY2;Wyn0>hVaeRNNkbrmM$Tb~UJv#rjx^S3vm1F4yTPFRRf zb|d@Z7aAA&a4nrAg5Ed>m6y5+4El+`EWc)DTsUK`bzWYFJokYRq}6)5Kz^v?7}G_m zV&vj0zV_@2KXtUG%4MDzeqhvLxGp3+O!-j0=c4Kmrtq!UE)3>;E`|bSJ=~IeL1MakK_< z?X|@Q#+nH_FReSw@Wl)CafA~8AaEBOrne7|%}kFqR~NT_=^v}P~%&lDNZ2%@Rh?>CQ1569nCP;N}@at;i-7O zl-cmzy}iDuzW|PuqMrrgZUxtySC2i2hSJF-38-nZGf?)?2hgS1x^x4_A}Y9VtGZgn z?*P2<*TZ*+8jvR2VuPn1y{&c0KpGDG4dCp9VXd)#0&%)3=pf8-Bd^XGdN(7TGWHaY zsgW9Z)&SZ|m-34Nb&gB%nODzs#}D5n;aJfPl(Zd<|K^#5goLe=%DTE< zAbkDGw8OKu^QkshIM=@DbU&14hk1uKZl-7DAo9AsqT46w6v-wSB!s1?jBk2Snvg%F zeay|}%piIjF%C#)+!_AA7GOq=k#LhZa_*OA*_cHavD9G}0Omi`^^-2Y$@kX2SNfF* zimJxa60x70lU&FKeVxJdUYX zCs(}#n-t!ck4B~Y!y{a4?EYg=X#uY&2mRm8F;F3P5gM$voX05Hh_g>nNvgyH3=b8! zyJ_mv0|isHS5{1fR8#eY-wv`Dsqt^CY@TnsfYDtvxxQ3!=?$-SN}`*9{t-*2N{-$y zoCsvO_YK72XBPqWTo}9c6gst`9TsBZmFUyD?={l4V?JDN^m#}AuqAu(FOSrrGJ5yB z?RebG8zeQF#E)DR92MkK0h8!};zQVeIc<<_*2{9LL>blO)#Is%qb4B8T~6=jJNyBK zda!8|zC+v_Vz--CS54x6wmNmsDg0)Gkx2zZMqkiuxr!EID^FzjxhZog$v~3NCbxno zbRNh2B?U@iI?nh8Azm0bR&RgqhX*R*G@z0Cd`~Bxhg^w^-$V^e%Zu;3De|D5X zKFNIEB+t{kuFl1)@huf^x%*ZLZKg3tsFE@^{1>pHiHExQg zOO;9d{$1cV(Mm=TmiBS89$!LPha{3Pl(;*1X9PtF&1u&wqGj^8r*lbx-V!Rs=r{A5 zqLhy5yAPOV8gCg4k9myGHE# zT%(*xU$4j|#n==643(juyOU4!6^Utie%w6F&e~7vj4Ni=fIbK4P=Pjwh7a2w=u3fD z-u--UF_)tifAf!9OoyBB_d_q}fR3xk_q*Xo__*Z>Mz~xnzA`#y+4}F_ zIyYL{jDdjQg3iV^5AJoAXCqUi} zM6VB7gJ5m}S49yrm=z3K1L|P}&k^8?3AJr_A-h@+xR^}2;w|qfUrNi;gZX1m01Q2h zIIWkgxBxY>3^bcP6jdJvq={q@(8^nK>XuaU^hsKTur~SKrlVn*8^Jh-*!eR?qiTA5 zW(4L(bCxxhS6bS;9D{ut``SL*6=X3<`UmA?0%2ZcMz^PW<9!_=LMM6TM)<~CKiG%F zAjf@lE@|{pB*E3LFFrXk`0;OeFOEMf6$bXqx8Lh9J{>hWNU9~KQLkR;7VcbSw!eQG zm1O*^qth9E3AtV8p!Lb!pUw1>TWh==3awC*Xp5UvcNh`#%{Dm zB-RRF+ zs!5`AncwhM(RFwKgZ@Ljg^aY|w>;gdksKat<8x^#W0P-`uU_r0!7Zw(2oj813~6gI zIQ|CL3R4l)dPuosbZ6xu7vlmJkj_(K>EGml7oA6DS&L!?5a`3jH|N7fRo=Xt31CLi z<5$pM7)(BMO(Sz)ELo?)!JwYQ{_av|C?;nvl3*qiPp7GSr4`V3DNMVx_u==^n2GOU zrO@n&kAv8{$1X9IL%GV}i^_n6C*!;tw8+wWQLaS=7QBd>&fq>pnIEhq-{MpjA?uqm z9``!LMT7BlCKZoZe+m<~6+H^h^U2KqZbQ8W{eAGbKeNW@`}x>0)-?I=L-Rd7#CWG<~?XN9<t6;dOu0VZ4Z%qlZzAx1k@k>D8ee*err3$agl9V z@1OV_2qeNdT9f6SfSxc*(E@5VPB}MMpHdQ^n^{ljIpeq6R%E`1SmABEiT%@CWaAp2 zop=7@?@tsQ`u>l&OUwo_E)U*lkkJRm6Wwc?lC-oJz?trTefAn;<;A{|#y3Q*;J(kO zyXn)#6GU%^AgiX@h%1}1v_@utYTGt9{(gV-(2x86P4bQ(X$TG7 zv?Gk*Crwa`B*tbjD2fkNH!=wkXPugzgAl3XOE32ECnfl z9%IYRiZX@LL@IYG&pZU8fu9~+8Ct*2Gn@cFb$aS@GulwImMP>#Gv{RzGER;ZYmpVor;3!}vulH->=F%_h4j60DzDLP*<;ej}@xWW}V zkjCcb)uW@yisE6$X$gO+ut0RgDz?U-P>1cV-ZH1zGlM6LB1i^&L+Y}W)mhVG!3>9X zDH|WAM5ju+DZ<_&2?w1E8dr_1%AOu1m44m)ags|^`dE8?e;hw+l;ol5&~;a@fFdul%KfgJbvY+IAz=OC`ji%m8lFB^FImb zpE>on&Q0ZLL@N>MTI6K}DN$X`Gv4k}94%2=S)_4}sK`E*#o~V#DX#Z8sf&oq#p>;P zVi>);3_sGObTofPoF25eIznkFyZqC(X_s|hT_P59^7-8C$>BOHU1Qv7yS6{sPUrkg zAAe}^^8zNe1oTty(JayG>$&K}i^?{cMDYSa*Xh}VN( z8A}rh=pc4u+8S>uyYeK{#jAyz>l>YA_=Oo>v`c6t6o|0UL{jip#MHm({S?hHr}smI z2>fPAp-!8!s#@1$xfE0{$3|GU+U)Jmr%IS&*R~c&Akp*UFMq;Bce85aP}#iy&_&hB zV|ds_XO6HX;U%_ZycU6jqO@Bd9Ll>0B1S3#T5Pejohi9&dje{Us**}GAf~#7Z=&fU ziYMuZ#%1l7?Gc2zZP_!_J$zNCFF`QAowniu2$t-da76_~fZtiHH}uG6{?vL2?)^mKcmGEe#z z>)(w(e;u8AyPs}CBR*ROs|!DV>xa`SlaK05mUIi}=_UzuLoGRg8e;Sx{z z3NawghB$h8r2(tiXjGsW^*vy3LE_kpq@MTTSvTnhZkEg&J#HYk8=iXa`#Rzh zgD)%?Mm4D!QPrad8Iy!|g!rCm*IrwFR%J3zd0~=cEDWjG&&{$Uj`dR<#S-D!=s_0juH zBxwmg!oUwWT*OP2^5%y}fL4~slWdHJ4^=)dul%rr$}Tj1!XM1j7eu%WJkO~!*I}|s z(0&3_8|VciU(;&a>(e9sYmA=;MUpe<8MYS5i5-EMjq>4?whOz%hb@)E$ZbOYn0x~% z1!T2lkjVH!bvND35GWZ2eK*}ZsG{+$I*s{no}fQb0Y2#QoZ);X8LjvXP3P2V;syK) zuT=P$`v9;z6wq4E4CDxu%CtE3 zLh(D^I%mE+tmIiQsQ-{XCYWyqWeJ&VW_+6x3LLOHfnjcsDzTz2L<+C{C12w2Z|^H> zw|eyqFLlT56ns0oyBMloFWgN)f#=puSR<}G?%RKQ^+-g%(v3tO<=ZaF;l?i+2pS+e zFO&ju#a-uBWSxfjwz@bH0zE{%3dmhu@@q8+Ix~I;p=_LYSmw@AlW}5w7Fk67!uKuN z4=;n%0%rmJYEC`(%x94?)W1AHL63)vtcJSp{RoL&S@fF{7~_y* zwkjVBw+Kq2Q=WT({tEgra5uU=XM-0Q5PnD7=lfai)cVMGw-x2?zA_ozcVwr4dQk$` zaFyJn=H3l|mj{F5d<@`sCvLrkreUpO)HEu6?5<5@91@?(@Q?*E@yQwM8G~Y+5Xx*FiQO6A8^X*yIIv zd$E6$3=o2-&2wLfmEq;!1Fst$yq!A;%0Yq&L?TEjDi|P7xOWx4wzekI&#Lw(R0MFO zO^uDqS68V(oLy0pDMWO9Tcj^Y^!r#vW||;*On{HYtKj*q%Ucp}jsH928X7>n&7Z&p zU_&6$xVhhHn{}ccNL{?V7Syz+Yt%5;Se$pEugfDHpyLo4?zy>V&DF`Psv=Ej)@$A_ zA0AA4*7zuF%7;>L0rwFS9^IF33g+q1)-pO|+?dbr8bdSp(>W+(eUxsjx%HYmzM3`V zDcF^+YoVXG$a!q0Ebq-I8FkoKF#3Fu_3GF?T;AB|GqBs+$AY6U!m}kpu_!2GezG|4 z%bB$kuE2gI%vrIX2Hm_m@<~HEy9Ve(GsQxMq@7+^gDfI{t&U@?K|QB}c70#Bu_MW6 zLE&ll+mkcHavNRfgNI}&U%}lk>UsI2J`$$ln~sc0AMh0Ob$qJX?T{b|nf}gFzum_h zgC2O$1&?+$jl;*`xtxvBKHhv%i&amUQPhkGE&QM*HFt#Y3 z&B#GfP=ppz5VmxL^y^EGuHLgV*7*NB-Q=Kta-pS0>==vrNS6e%pM@IK1m%Nzs}kf|=ZZY;!#Z+r?DR zhsBT8q|>lkKM|{Jk9`rv8erMLgDF0qr5wkt#2fC?9iD@hyZhLuNWA-_OvemEI6nMr zs{1)EwM_(RHzcq8Q#Fg8qbOV7g?0iK1;4X9q+TVY-RJtOlrf28IaBf?R_+ik+4|h) z1xBeL)r%g3s1?77)cf&2KkxNmmvr4C5iZ|8v_-bu-rLdK1gZj0=Y`L>_ECGMw0wDe zaksSeokq|-E!u^jRO8W@)H7pW?2B2FyQV7F+YYOdioUGcvulXq?xrug{Vgnm;{Mlr z5nwK8E3pRi`@dfd`~Bm%A{6Zeb1~1wa6o>-<@#5Hiy?!%Zg;^~XvpR@v&35c6~-CH zOR%&ua|VH&!rjT=?Y19t;+tSHHVOTE9?(-4ZSR>ka)@`zzA3hrYJ1pA8qL@9HgBZk+E$b#GU^z#o@A#XCZ5u& z;ypjfI8~I4mqZSPTAA8dbcRqhP@3f*1LriHG-S@)nTM{Vu1ozTHJ&Bfi}{O5<+PHj z3xhv|8ZPUlZ-<(_C%ZpGbaV|}{uXhQsl8BuQ56{4G6pYpWIjXcKv!ylIfs{2!w8P# zEr}Ps2gc@bj+iiCGg38v@Q^18q@Cg7?1tuIN;B2sy`>Jyb|Y;(C7r(cc>gWx9-b>Q zxLu_e$vBsi@fQ}z%%Xc7aQ&gr(1h&Mr~IO5<%-7C+Fi#}3LgIXyXNpTZPTGh)(Gv{ zLft=Kp&qTlZMVE<*{_G#??vwkAo*b?X-FcOV{NMu?;PJwGL3?++uts?%L`|E*VcUk z4Ph&L;pfpm-T1;F`Cxg@{;osehxsw%Bhfkxr43R$b%wh37^@F;NmrdwN`GqD!pWS6 zBc9jDuXcY?U((d-#_d_?-Z8yHz)R3&|9!n-1K)OMdmP-lp~iYumsGaDVUzP&(f?A#y*xq*r{cKUGw@@3MJ(4c-xn;n81-r$- z35z4^`G#iEXFoxH@5dgJ8NFga+Vc+fjnRx_-;I;lQ%QRyMueBwkdrJs5u}eC9Im|s zqD29E^Uw<9cjFJl8wn;L-fnJ=$ADM>CxrUfzmrnPU#+T=6t`o?cR3&xa|R{-v#}s0 z>j>PSx#x#Zl_KJ!n+{y5>uNImFVHUomml~)fV=!Cm}2*O&s*3)l?Xdj!a&f)+1WHx zk?iOo|GcKqSYPCWi|3!bEI0cqWY($K75SbF=*&AFvk?K*aNxfCi+TFnBTTJbp!cQ( z&o@DJ=`8kl3%%1m_1OGodxphk_z720-AH-|!hc}> zl)!9-q26}#7^l(Xw~LLN{VQm~-?b zeGbAxRdktPztk@|BuK0MqMzjXY0gMr+v2P4+}^n%X#QJ=02xea7+j>G;@3tjv>tku zueK?&+$xK(IQ=t6+%M=*rbiaJcjU;UsPZ`)X75q8_v@m*8R1fV3OnB0v#OJhl$NBn zZ8ceB{M0w|>X)yF9d_tM>f~$%L$Q{>AQ4T=m~}--1dRa;Q;?WDRKZ1w(R_WumZ{be zyGj@%d!4Deomx>LV#$7=vz~p4up&vLiIeys`A}oTTbN;p9ZCg%89{?}hW)mVIvl^l z9m7?jd?=NMS+Hrp45RDK_+O7bCyqtquS4_C)eR$&>at5p>zoq5wm1F(XQR+0f&BzD zG#uxRdJErg4~~a+e>um;RjQ)9ULf%l9V5Bw!{ITxa{AmgT{rT=?2aG>(p!gi+q?lM zg__;7Mz8!P5ss{zzF(TCUw7gA({XbYITiz|SN=5|JHx^C%OEiU@z4M@r$TI^SpT2kVRW)WHuJcSUGOeQ!6$<^17w?!N5xva#)vzy&2XSTaPXM9{IY9bZfeHJ;` zPXig?#NIAvG3@h5nY$?#e6xZz!L(i7u1nGSyH!6H_qR(vYS%Xi>uP8K*@Bakk3_Or zqS-93ul1{qeI`p){~Q+i0v@&Z?G=$*mdxw(f8Eo6(5b8rxOD27VLg2eG!#0?m$$Vx z=NUr!-!~tD0G%AjQC_Q>quIA;*5ct~n*N8Oz-Rf5SrJ>vfN6E&`fXieHg<3Zj~=~u zZ+CzGu5Az227XHr?FPuh$R?nkPVFFEVWrt2?J=m`sGzx7eUCy+jFWrPVmyKU2{>&QDo$z^7 zg+Wmbz`{39sxxDhAvOdjyEgjXI^bw8p2ltR0T3Cq2!PXJl{&e9-saS$MozupbCWHl zZ$xrcUp`d5pZG8mxu3cBiyxKuZ|;kQx4)jfBLR?vjwO`^4B1JsWzN2SZ~V`cybMWj zk+O$NEB95h4I(4cW_>(uwD)!0RmeUfn{><9FItsd7B3`_8lWX~vSeoKj-X52w0XXK znoG)R*DW$fn;$+88KYQ*NPE^BtC7*n>D&>S86De2q*pT$_oC}%l|zAEl27OREYk#o zX-*4zX_&k5UGdD3zMQiOriMz~SizG=8nPKb>J7^I%8SrssTBzL*~6HWRcq#CF{9%r ziBZ&lH&-_u!JL-+OG`eyCfcfeEt%)=HmoQ*2TN`Htu!Ih`FKNG)zE5Kfe%#MAgbO0 z`Fv@uDssxWEOqgT|1CQ0X2#u#D-(*?BkY~fbEfsoCH6TvX9b`0MiWfqs+I)k zhYeImfo#VP2yj-mHQU?S#R3&knpb88t2yFf98%OS#1sNI=U>52Q}zdI#zUZ@j)jN7 zsu1$iPBao^>g0pb-i>OlXg%c@7&87oCcHQZCiNwbP$yGQYVpxFmu0=|ryJV&_rQAa zx#Lj>Nlz8qk223AZz^pUWBb|Oj=L*RC_rY?Up>q`0X&hwbz#Au;TohA${JBmb_&`C zZZ6Z6@-P0s7GTWpL5K+oL`Xsiqz+m31C?gcFLIbRL;h$ge1d_(9N&(8j(C5ifdwS( zliX?+5IBG7-ToJ6rT zgn-42oh;gW;!|n?d>FTzac6(9nx|kWaeq9!hoiS%?j#g4Y!HEWE9}_Xrhk22|I^j< zv)4-l`puax<{3Ts*K50c0wV%lLfr(a{j(NZkv<{8H*B(1x8N?uno+(t?#6;W}|x=t;`)D~?Qn$a%upXn=2 z>Fw<+(R*?*mLuY;`<0E05CJch5xu-(5tBmVq@O3Ah>5*K$SMe|a4WLOMYAEsVBB-W z;?CIo*ntiB*tE4LjEZs;Shyz21si8ayF_pM@P4&;E6;7!x8DlQGLPj~rOfoTyy<`Q z+r+jb)&ucLFItReMjz+Nlj;>uPtjlLs!Q>;(TE?Z2vU79okvJP+)6pz0Yo)ei&c;u$F)dRP29b`!llc6GlP56+KAQGYQaf)Y+GA}G8dcOF)f+PGw*?DdXMjF zf6qSZZzv*7dloc1TsG=uzoAi=>b2&tX|nV`%Db7CyCkZemXC00$P{?JvoCi0q-L$T zO%X4;+4e=`gB$1j<@KaqPQ>DuASj zywXg{R>CEC;_pUrd2vV!6nn?hb@0?MUDU3Pfx^B@>>IG*_L2CqhoChQ86kfNk82?R zL~guX$9AJ<@@FQMv23Kw%{~Z3t?VbRw(az3F75I>ev?0tX(#-P66ZxAo(^L9IK687 z$MRMB3+%|8<(r#@(oxr>*}3c^6@1R0uq1{#{%&stvmx*xy?6*Too?qxJG_@G@V!C_Mv?1s9h( zdtRuSLkk?>)ZoRqu)f-Ky!C#+)qh?QsyHLzwRH5Ff;xR`RoMBzL0zytgxzOG?!<;* z3kzO~=aYc!vsl%j5e=Ujb)DBNZQ{lqL$tHLt9+;O_joOrS9ixrks}@1=NBR}`SdX1VH>t$OzYn>BTd}j)q9j2LiOGB3d{S!? z=pGH&g@bBWDS=YUs2m{ySyLV*JXp>2v zLC;x?44FBI-gIcf%cLxC@>gH(*kvt|NDL7Yg<4Xb!!kI3?rXKd z8m9HVVw7Gz%iGoi20fy&@Z?zE*a)%y{>9?5?{G3>&5LlGQ_h)~q9)#8d2B5C+ff<; z0=~WUk4Op>BDb*%%i`H_G&eMCzTUaM6$XPPovb%oK+R;D!Yex2>cd;vc=!ClSbinv zt#KoPGA4CF1+{zmAo=k%biGvZLENHU<9|CW2ObAqItU_X7Z- zVY`8`k(2b0yFY6sToDf{o2`%jL*k2c*EW6Q@oc^2DF(kE6|4IbAm^HTqR570J zZVo|kOrbe3+9(WyXI59ciTi+x!?SH^&R1>bRF#OQ6U6^nrCxd6nX(_wp1dDf-5Xzl z8lHOE-?}Ey2B{8q>`nJ}nBDKmT!P*6(R&baDR;6Pdy7MV^$O+c)sb(Kq(P`nN8!}k zQs|lR;^wp5I7m#`YS`OKiBX@;`jV39=^Ct3qS|>wMhV}MJIXvs3$gx}LmpeP{tUyB z!6*l6gj;fqId6}G@s`LgVsc_^&Jfm~8EyM&<8LbX#!Hz$ z^%sfB%mmDTrC4`bCQd^*i%Dp73~-FYJ)3w|I~$#B$n-p`s$ThH+(64IHdK#mZQAvb3=VE|jBPq? z%%+!=?NQ#>s~3q#h2Jf#^fd^MJ)rvA+k<-JKOKhcd4VKaZKh6(hmQw!({U}`cF*&E zWhL7{bc+B2Cd0;Oh{WvjN{b9*58+I|U)OR}7c+|4vwn{pSsZqyKX$zlebp&!Z-^P% zr~KHDa7Bc%*U#qn5q$$O^J7C(Oc9|POBmJ%x6`MGCKEDcNf`V)-2=jccy}!`_)}(f6cJ z2jd_n8UqG+1=540Vh-UY=Ga<;H7`5dY}u~*hh1l0!HG;*5{w!jg8qirIr+Bd(+ZVG2trj}$EP9%WacbF55ZY8Pl z84{(McvoD%Hpuu=omN*zGw(Utv^Mbc2F)jC6+#oxjWTyzjSu-&)^4uB8}&_uPBV-uvur zrrW)_$zYE}csavXiOz<|PPS5T6?>nPNVBJ{c783!-#0SFxt z@w)h;2>gCJ65HYa9l#7Z(a3udaNv)?33-K;H1u)gM5G?O^c8AnXOL+n9%4ugcrgCA zZ_PQARTF5%@jrd}@`qtfXfCvpd4DL}rS=%?2^n&TrYU3leQo>j(}s5$z%HgfJ{cef zNB-PCrfWX4L;Y{%+N6L4SV;!(J80v9#a0&m#oBe#>s6sIXWg!FiEFB|Iv>%a>)9oJ z`rrGIA40;?cjMap!a8gG2Hv@Ht(tZn>E?dBshk^nJH6BrokeYh>*?0&W!%P^ck222 zJ%1`Jv<$w>m2FJLjX2G7dWa!|G~pY=hD17sYr_m~dF+lr$u59h5c`T09lA#I{-b-WAAb-#(^CdLt z4Zr3AM%+7UmDj_%R%5Y4H%~}B3@%sx!7rVkS3Be!*(EgRsuc*)Hq!rFsrs;LMN zj2K3a?=S6%LMk13Q33+ATrAoj313G$x#LwgJR?~@hnITtdf=ne2;L`BtKTSdDoGyU zT&pUq`NNk|$;beUt(=SYh?;gCDUnt;p|@5t$F0%9P*Ni@)16=_Y$f;}3nI5hz}#O( zhT9PhzUA2Ne6l;2JpgF<0|;o zx4!!qAij-0_m|$~d3W95-OI~hDcfK3f(qaPcMBo=`v67@&5{-yt=mD~-FOd>T7?T* z5>4V?#+*+H)=wG6_g^E@v)6*BsG?`-z3z|+HDmFsvN`WUaGd^v*jCh;x|->b>~*y))2Aqu#Y zGx<|Xe(Fe5dkb^CBhR?G-S#+xE{z?%KDG~i&0?8|`W+8a{P6mh>F;pt9rzV_8K`XI z`sLMsmb;r-$^Ff*?tMi@{6jNbi%Moc`maU4#QuEy{A~^9^%oDji#}Hp>Y#6fEQ3BukXwB7_y9z9;&ON4& z&TFuoFlzKxh8qLx^JTKWxC--{5A-!VxgU; z@8B1mFs1%qci<&Bn(+f5d*BL$X@P{`VJ46Cr#LorSGUH?4M(Gv;ER}Z{N7kx+-&MPFN642rrPxRq74 z;w?PPUqSc$Cr;5LGOG_A0wQLh1|~BV1TSn!IUHY00eB<5YelYuweN*wap>-4grjJK ziq-za_MGcq3Wi4S$;F0t1H55^Ead*B+lb@V-Cy$L-++flRqj$K)j9z47;~PDK5Zg5n~{DjZppRMK`(_7wy*yD+Ea_x z8Dl!FDM0eFu`!C@rT@%u1{FWv(e}&YTcEGkkBBTwH4Z3uO~ux*z0zP)@ScIdV}4I; z+SWI(rdjS^(SAU;&ZYPNDyV97rB4#Tu9{;kCaRj#&#F2hgO8h8Ye56ZxsUhbIMU-Lxf9AUVQ?B|Mb$8h zlcw(Hw%o_oF^1VXlTJgP>1vZaEoK#ebEHDr@vRohq^8jra@n&A2#7Gvzl0@`s=_2p z>@?m5qLr`{Cv8%E8@c+|!CnpXA<*FJQ3JtCR#|MYEZ1KQM!~Bdh_2Jx@-xE4kdtwn zb9z_;d~0@?xyboQ4|>a2_cJ$cs}ejL8|5S}43ZHXz{Cw;F)g3Z0qCyFIDzxmAL}*) za`g?XD(Jh`RAA3j)81`z0^@MaWTs+TufA(F3G$@->(ri@bUMdZbzeV-j{PJ%Njab9 z`Bb%Pah{^HYXtNmh8%R%cVhw&wgW8b;$p_a(PddZxGb~@uv~4U&YxUMPunj4#(f9S zJiw$t79!yMz%6{2RDw2K84e_!3oRa#ckg7FW+402dd&Z!xg?~(gAA5~FE4Lwc$?I% z_PzJ__Z=M^Dvl6#o*M`67fTDVB7(eXUlc4a^o}GQ&N9p{b*#5sr`vQ#X=}$7%97TMK7c^Ua z%^}{T$`3>twJtLWGJ&zALZPgApuLw(E>_1^ZrDZ_fmH!kYG7}>Son`l#$bwK_w#@3 zqtS=|?rYM9Afz@wzv*|-udjS1=Q8?c)q&(BawmaD^rmXzG?}kuPHto#p^^QQ&&i{i zGsG%x4SH&d6;5SoSankEoF21|k%d<6%Z}w0(D!-bA}h3%P`51l@Sffz5ehdvbL%v5 z?Xem@KD`AA6PcPu)-QT!pS^V)5-GuB1pk^0W1zWLNRX{+{@Cre)B`fO%zYN>PGh-I zBD_FxvA=U_aWl!9KEdnQi7YJWnR9>>mi0=W@OeZu4Hzr| zr2~2=gId5Kin8-ENE&pP>(k#JZ9WA?9&3|#nfP>^?!36TmCR|KMY>PvWQKFgrN243JID&xc{0$F3k zUf@`KTR*QFS=&3{ET2(H%Q{u@xp)dDT#yF+158kzS%F97_7zx4&E zWQee|lx@4bKs=mFN7R6n7qyY`+AdIuN!mOlnalQP4T?r5QntC z_kt7LtF@*s9&KGnGqlrFD?u)-qPRoVj4f@2B2>x6#7zbvUjjM0;ngqC)1ITVP{|O% z>#5Sc>3Z4JE;hqBZFw$CLyl-ez7k3?eCi_5k9;^v|LX;IS;|Xo?ynqjC0^p)yLg|2 zyIMF@Cx1XMYyOabTbDEZ0PlLx@7HPQ)A~un)e?8KV1-G{T2W(CQ(9z%++%-M;Y`|N z#}%>ZWQyygNx-Y+QG^jV3`fZHV$)+`;dWYTc~PTr`xX-5*3dIzivCH^{ zuRTQy4;0V4#;OW(YB3ZgC=>QK=CKY$Ci%2|YG`zz7z5mhEim@;RyIh;eKW3oS*|Wv z6Ms_rp>%SagFNC&1YCLtrY7GwiT(mF!LhNieTC$YWNy z1kqujqd5pI0i8V{LGM8ObY~)I1pW$WO%b=n9~}Un4>pP47^yaIdI28ZqS%nMNEZd} zSx{gvX%A~ITx9!i|4w~0zLM20D6<=*tJc2t&S-B=%k?($m}v1iu5rql@KQMLq5qQs zKe$~0BLVHCOCh~?xSoI>onR9B}B=$+1-&^_`tZ=U%f=7Qrie)Yui^QiPM^FTEW6ET6{ zP-p+=?F$SDd-3P*G$k}=JQ8@L%?p};{sH&(iwLO)_a(l*ZLTXTgMQIeBf+4?`RBpz zlHT7`ieZW?PH{O=Jx_w`>;V78{`%F^%r_|-y^amlJ^fo+(p_Qao`x-ip@_%Cmw^qyXhHi1Y(X z9J`Q{?bG7-yi@N_MZc;BWZaoG`f^+`nevaPsECV2(w=1K_oaT=Jux+%dI+HG8z;&B z{GSj1mMQ!b-y3eYrMA`24i^PX&Q^EZhp&)+{f{bicW!+3_4ONZ|6U*j-}~(T$6oKk zF9$5vw?=}vJ+L?q82SHXk~%t~mM#iYEz;A{VrW7~uAG$_0PYM%0!I*v1%g|_Nxlaq zMwRLufddch_m1?;f_MMI%HH3v@W^x8`U|Xja=q6nNWYsbm^-EWV@OOaI zs?uMFynEI?@#>kNHvqZ;q`XSMPsGi9%%Ldzo;n9(D_6LwWOQ-f z#Sj-G+YNemL#W{W=svLo{@WQ?^W*i9^1`zv4%Jbj4$r{OOWHusGL@8^0`@FU3CzI= z)#oATXu5PRkCg-WG^V2L%V>+BKP1%mqseNd8bfF&hFCu9ClGISa|blF&~;W^bc^X4 z!wJ=KhZ8}nD? zOA)90NZ`$XLOr4#9Nfm>pFdW3yARMpBP>T(*WOS3Qc@Fwto%-&)QAeYYxdSNeAd9K zCeR-W2>ct7N>i5%-pAO}yF0wllYRDRtU%54XSn1Myu{txY7{#XIkDx_=^ro2ZLJ5Z zip;$hTzk<5>mYDsuBuDDN+Ciq@WML59pp}2ej@g78ie>1OL!gETvDLT^vndKH#J)}GY%_Sv<3^pF-NhNig0YkDI&qrL5J@q~CcE6BjSzfQg>ZT=;? z6h;URf%#8QUD<&3aPz=s+LaFW9L}KP(!S2M>0q=%&Q22&igjyG3CR^fzozT!GSN4@ zT<;adBHFvYDQ4H(?_W|~yH~jQ!h=Q`d*cazk?S&u5tQS6(*BY8SOe@2FfY!3e{-*& z@Y{McX;NkNtO>qtan}_lWFdo{B*zo&6>)AzO*^vN>VrB`@4AVJ+4Y{;>UvnmR6g$f zpnja=6U&`5yN`~rA2bS&v)ZN2zS@_m4@!p6ai;v3&R4sS?n}FB|6)RQoX1>KZJfs# zA77TBg_~B9a83M!{LFCsjdVMM?ie?%l6u)^m($b}ev%$%WeuXhH+!=Rm;U|_fQznN zY^T0V<29Z9QalVfmUKse?^eLg42P7#jydxH0POBE-a!=80u!YXA?_oS8<*TOp}*x+ z4Yz?D-^n`$$v%qJtWAsEfADvT%rG<>ZS}!kDi8a^HEPA8M4S-cOb&|sW#q?AP+#rd z=gY*0w=&QhGh7TUs#`pO2Nh%7CbCX8DL&f|NvL;t_8GPetVRAUc061|orkGYxSWan zg%PG19Do&CK)mn(NG8BoF2Vc`f&{u-070%0FR|^4)Z^sOp?f++IBE!rh@4Dr0c>ZI zaSe1xc?{H*InjG-@h|33a_Q@!FLngh<(?uvWXlFWzc2gEB1&*s2S!QV>({?)=3~}T zZsD}N&)B^%3SN&KFLonXJUg2r6>hjGi8J9%J@1`1C|M19%R{I6IxfIcJ!bp)XD=ly zSde8MQ@$T{Y?9P&OaYYwnzefDHWYls945;Wa1&Cml8I=XXVk4IX}=PnA9pEKH8MbV zlo~b&xJvAWAOj`5X0!YZ%<}CaaQh*%8zKs|A>+ zZgIq#8ed0h&@2-jE?;x>$o5c#*F5Jm1|MGMAvXq(i%6b$$UZ;PW(1^gD2-| zl-^3qn@=?hOXI^x*zb*?X1h}k$*)hSamL@g&MSDFSF9R=GjAF3TmMAK(PIbqIg}BG z=D^CYXIgDnym6hZvsV@QYXZE;b%sUI95{Of;XME7f{kj0z2Iqgx~%V;*_(YroF=(z z&Czmc)vuo&E%<^*Q#eQZ^3+4Df$;Gc1AZp0*z1Ds#swk#55+Yt_oa-p&`0kR(rWP_ z{n)Y?6mNf!1W|=nQSKiXL~K^B8qv=vOaLGHP+&bv7UZqGW3wTfO#n^|@Lm2DSnOaNb=7^*bg2Yz#>!@K{3X!?VJ=QD87G6|)B zKt%0{b`y-%8hQ}MaaGK7`=lOSIiA|S`-T_tm#^g9$k*p1uA{EmguOrX@4obzM{ZJW zx~PPW!_QWBOoPcQ=Jw)b$7wWqNxUhppr@v1ePmC{yTxuL8E#Z^&)5_k=p+ylXFk|A zkUMS=EVF*~QWh366-@i==(wzT$W~+I^u@1TKEiPlIs}sOIhg!~&4}+57pR zZxJ1A?j^|he*g&*!>GBZaNDjcP(^pzKnjYp^>|QcPO$SQKP!8Ob*IW0k>6;*S$8cl zSs;^CBLa{GODJWUy8mShh@0r@>cVrmc0NNa?zOT)4WUZu>i~iO4b(H=#$AOCQ&e^p z1YVwuQ@yQGc}0*Ct4fF-xB*r8mYGUhA_sx+WWA(tC2Zxz@Rh=nD7B|oy4fK{A^jy< zfPi##32Iho4=E^n9XH7^=u)C;|8&b1a?N^q%@&_~Llo%#+@(;^B~#UYf1Aq3sBZpL z>Xp+JixdyeIZZ8N8UF`qTCE1kprT@SCpd!LgZN1esHNpS6iR7^+Pr(LfKjs?SBeWNMb-JRbx(_O++yw=J4nc z^|B1VF5y5WNQhw3Z^Me|`}$LGs5I^uO6A~CuaZFK&#mM3$cjFHRO8+#s&tyKFPz=l zIytq}c$XZoLPyK=*xc9CsLSD zV3c-SEw`F$o3?x9axar=HG;~LWXQ!yQMYDQTLFx=#zga<$3Iz{8N{P25G2F!Bku9Q z^w9k1B)xyzNq&_v7Q?1fh|aO^b5m19X1-ZPea~W+PqnF_$CV$At47v2R`0XxFBrO< z=+D}&^qk^pd#+ce-(IbYI{rtOalpYPANy(`=r+q?=mnLsX=9s)x2MAl~+R&LLh@c=%xPHc^QWL=?!;v&csDp>ueRM{om-)68&N$vdE?XI*67-Jgtcd9<7iVLE6FI+tfYWjsDi5<@4` zD9ke&i9#a#uM8i^3Ew_+{|Pmf3twb2aa=UGZ!#BsSjZtYWP!N9K;PwK?Y$7fZaZ_7 zyM|t*V45EeJ{@r1`E|FggL(G9=GgjqW1F#+MUuf~7%sPt!>&MjVB~!s*m|DY3KAZo z*l`QD?*@(i*4w?R zwHZHOZCZBxZW`r5XP8g#to#^|BH*vdSIGd?Syfe)E3x|IMLO5alhnQ)&<6_&%hduJ4=|5eI&Li{wyI)HorU#sRhVePBWXKUY`V>e{{=l%HW5=6qHk43G}e$rM;`A@2Ifu z(Go_|Fz*(?EQ73#sgs+_x9uN()#Sm8<_msFi$_avOZim`Sg?JoA7#RD)-+JJQkp;N zVTZ|$EyPM7iWxtmo}rj!!>GeeA?9+#^u((0d+(IY7@x?f$yG)T{gX475A#V-%OUd_nu`a+%W1Q)SH3m! ziR=OF@2BRVw&OR__cf0V2vK&v7ln_0XAy}L5pbVs<;K;7?H>b3?&pYXCb2((w3M10 z1*3#{$!-bV!gakKjiimWdn3&w>dz9<_p;mbZdrW7y2;>`G^r!WJsb|-ZcC)(mXf^7 zWY1rG9AE-?B;YO!w_$KbK@&uvlkP|)Xz?@mj=}aVk@Q_?0idD)kb8CIY2~wBxjIkL zUbw@?%4*kA1|(NV(YfoD|377=L#+a`dd`6Q3cz6iR$gm@a8CZjJ!5Vc4gHi$l#v}E zC?DzMg7l@wfkYwywdmZk{#<;Xd-Br z<}YD+ySD}mPf~qI|Bj!Qc1d&fG+57gQMCh8F|~kJDAxHl+q>Ql+uREE?z+n{K&j}? zflS#nNNoq7f75M)Tp%D=!6TCW8_N_Iyc`BTwrvI-{{fCXGlv@8J|>te_78*R59}I& zVgb5?jN2=Vc6Kw)WcD;=kZ80OH}K-#o+bh;UZ3@jfX&@&=TuBvl`0wcVJe@(Y=P&t>x?T#kI32!;pjGNlWa<&jO1_J8@xs7^w5_@KVpF zJtmTJv)IGrLp(cck2$wWkLxvu6At!|b;+k8?c6!S;(on}ntk?O8TN5IPxNLH>YBvn zy3|fe1w7`u7ylH;$75@5wfcLIsOdeVvwBYKm zq*fq|rGFJFfkq4|2!I6UMi`fUpO@Cn1NlLdsKZisFb_A0M^X z@)z~H<@lN_g%n+9RvUxar)axE8G9e}yVP=o?fkW;db!1#p0TeKViIfbF+@@~z03_+ zN~)%kS>~7V!)Lj#iFy#!t0P^{iJzSEC$2M3LVl|JILvWA=yysZbDytn_EAhwG+1{q zOo`2BnD&gcTbph26J?`bz+T$CB;6N|&U>)Lp9xo}w2?8;wzT~<;}y9+)`K9~Q|~nb zJ^p{K&CfUUGdwlk{UM6H+Y=&>kc&0jwmENFm;|%RK3-A(FJOpsCstu=y}A=}wHSg> z@v+T6B-7~`C~yjCrKeBPWi?s}s5D?PIIbCa8vbub*)g-RVd2cF*~g#%rQD+p!s|W& zLUozvm}JVS6>QyvhZsSQrf2)zs#Z!0*$6(oFn`XUQl0SC)Yc(iAHv032<)w1=XJ`d zmKf%H*e4uM{KapO_a{!f8KYA%|8{S_xVv9;m^mPWp6;X5ucmWoue;(9-`RqGI?7)QAfc% zb8RP*0X$th7Z%bZ=50!ka~zUp=N~5rK?^NZ5;x9UaaS<^jGoDh@j>$hhEH{GODOdGl4#pVq44G{ z!=K4r3(Z1=eCC2k*>L|y{oD&j?E;{`C`3e*czQJ1jgBtLN;DPFVLfQ4uf{p=WnA&m z;9M~6(cQpYep6?R&q+QtIP?2c=kLrC8a%(RKtb2F;x|^MPM7$!>611a$=+O+5|OM6 z)7fN+lFis~kj|%X{|x4ymgsTOs5WhC@BTaNOFq3v_!WnMTY)rWBzJ+OdH13g<;$BK z!JaYH@T3grqU8eS$lj?%&&}bFeC&*`p%~MQD76kZq*~S0>fg?L!H8QT?bs@tG7}8X zDx^#s`eh~7dfeaH1Z|doh#aQg?fW*}N^=Ox^=h=g zqt(bF+xRZ0piyWhnRFzbiZ}XP zezXs2?J>{}n~G#S1$$~&Uoad%R55rFfB??tM=P8DP3b8>aThN;;GEUSeGjLIkh9`( z&=LWIK9{l&#ZvX?-VaNqHiD^uXBy?sZ$)<+v}>x@ZCNz4khBbgithY<=2+5ss zDnprIb*nm;&+XiQmN=S`j>9*yd3@37Ab~Gcm(DRXV-k5OB^0)PY+ezS_kJ1uUv@je zKfo7&jgNi8&#ta=6g@!1`zQtwuRdotjW~QpK%5K$(WlF3tYL0SxTRUQ*uJ!?izMo!fr_K;ATygaez*Opxui5hSphCp|a=dG~Qq_Ht;Qw8U4 zRmt>5Uh>u4($fE#y>#zIPTEcq9KP@-3JDpC!YeU|832oC_{7ccW>LW=lQ{PIA4mcW zXH0*+WZ!t4PI7yy>Jli`G|JE6x2A-@lYGc6u)M&?)eD5S+dcMp$M1{+I-*fR&x({XII5 z_mW@ZzI2rw=r|Y-zw^s)9A6x{KWML)B{-?qdRwZYfYFJr)Oh+L<59vIx-tH*?Nicz zFH`!krAw?Q^(xO^>Md!%&uiW`vYR~-=^wp$8~IyJ>IM3VUMW-~A@e!u{ctyD-J>YA z_BTo^K@%y>^u1wzjhm#JYN~u@F0nKL;$p2-5^2_k821&>X?{dUL**MF3^nxVLt;!4 z8B9pdnz|R1PlJ-!CH#70kC+r3N_eExk&VM0bo$-}wkjD6($m(Lc~D!2$`m&bGQyho zmKtQSC+;*YlnM+@VlIx72AWEG?x8d zV(pNX!>u)xTOtckXu1R_^`8Mk zEh!`4UmyysDD{1@5}M!hX%gW6naH#BfRv4pSWe9!KLDDQz!2=_6L!SON_sXe?VR45?Rea*92ZK z@rxIp%oJFCm(uQY8so;i z@9S~}qQI5`5D9j1+L#{stlTtWE4SgEQ3vx!%8$i??~Bhc1qZz5BX86{*uAa_^3aeBYs7wbr3vLB{OM>ia<>FdeYJpHS_WtN8WGR`0VYlM|`N8 zz{0Tdz?{?ufZa_$U&?sn!mWiCot6_JFfoh(aXBKX4?iYmkrp+-6UY|SDq>^vdiS2; zAJ)Zfq2a4Og=p}g+{6v$D1~OF&5Cfo{IqCZ)!j?O%o}3>?b0{a8_xwtg|{3?>wE}| zlPy`vB7~6o2Pgh^imo9i)1%uL9=TU9kZC~h@lGz)`pUa3*c$8HxoMdOhy(zHfV~tT zAw4HISfh|sh{bVXD6x={k@bUF(QmC0mK`GAx*xhWJ@mMy0hzg;3Kq_<8ZV_&J4q{A zYifO<8b{7bzh3FR7XRAG0nr>`4Ks|Bcq@**&v=q1>BkY&=r(V8Sqw>_)iihtptlZu zt0j`d#wGHOc*r|!@c;=41? zflwU~Cy%P6;lsQRu;7TO$r(xSbKHws02QYlKo-Q|@I9KQg|-dS)LQeh*(RdMka~M| zJ4{-}OE6A((P ztGO;8$)5y=%Vc+5NT{>#l=|@52V#@~A+J;{4L}50UMzcP3^wubpT2Ln*f(e=UaCi3 z5vIHF8hNAvbXzZ?QJcO#$pAY&Jq2q`I*>UZmFu#OsL=84Y-U9OXoBc^ zu#YAp02Pt4LQ|tBCd8!jg@lL|NSJKK^#1zjnIe$X*k_8%K`&7;TXc__8p3r?T|MhJ zvxX<0X0fPDA;LZUvhq)zT0zHQ1ah_92JWh(2^W>hTv+Hajo&(rSpcHVJE#P#NL}Ud zR-UZOr{MQgX!ihJG+L<~6HW>BHA6rp+Zm+oc4Q&>ZCy;R_Kl1E-c&CG=!m@ z1_)G|<1dA$vNbcM!{enaHnfu7npAAR((@*FE1Iel%Vr&8XyXfe!@gHCL$kgejG_(U zvDZ>A+ZuDsF-JM5cZ~0{iIw!r7!WRR8`amIw_1xNHYhgQDVZlUKI2PA(d9O>P@yX% z4RIZr$ow!wa+8_%qMB=Y^c-)%dy%FL%GqvLHJK-^jjuVU%sh{&SJTi4Pc!552bScD zm2OoHr#ufwf>PQQfA*ZQ?ceq`53|{GiWv{-xQZEJGnI(3LdW(vy0Qs%%0==+W%nTf)mSu_@ zP6?G7Rmn}8HZ*s$);LnX;J862DUyYJ$w9t5K1||W z|7F+Og#VNEg|fvj{KJ~hhEQqUc-M5{xtMh`tF05(-2vqF>|@oXpG>)ZTW%wm~15RRge2MW{` zu!fou$mz`$@Cy6j`rZhNZvrtxoqUlGGVKL5^~JS?8q8MC{orub;MaLd@es2iRcY8pMzSI$BBnP}t>(V&$++RE4Idfadz%Ug>4p zg!?AyOvifPWS!0LsRRCjmydkRHE+Q@n*#Wn6&OzUU3|yA_JRYHU~X3A3rM7q`xSh- zeG3I9)n~{5-E09j50>BG?B?6rGf%41QyX4KWtrWen_8}baPgu@_U%1KQ3Z)OrE++? z`hCRVzj&1&5)#A&g;=VtwH1!sm?cCBGj ztXo~RI3^+)LQH;2J<|bA!;scU_67#4R?PzYimvqsxzuko2>%lM#8@(*uRD_-2Uht> z%3IFM6M34*{A-nCQXuIMM#xnf^Y?g2jR_J@wV-DI@z0cF8fT&Q++Juq{{R&au-vzhKVUURMVEL+4$gSjpwJ|6nTvO{A);k@aq)n+8I>Wm<% zVaPzLCqxh0PVXKOP1>%*+>!n2lawQ<#`Q;^MXADg97m#qw`6e6b5V5@1m9JQf|u#3 zBdNm=bzI+mSdG_xyktJqxOtiNht>*M{79^2Ys?3z zCe$25QTsCv214c{5uejfGrv!glk0oyDV*7n5z?>jytgk3K%)0$;gRz+5SgqbnQO)j zufJ!;Sxbwi<|KQBDV>M5#z><|i(vd$B5eu+Q>ud?Jhq*BeA9=|DISxPnU+g0W|6{$ z^W_MaXs9d+s(tslPQ6B_i|uBthF(ZC7QOl*O2J7M(c3hidrEitf~ryIT146~N?bR^ zq?Am>+JuG%*R-9TI#TH9QZhD2wp_enY5^K*4FD&hG|KprUx@A~iL0MIDX?Y-bRA}r zoT}-X_2W!XklqzK2Ot$bUBs(@AdxNk9i3v@9_L=G)mpx=O7Sk}58&`_J3g>E)o^JM z#!`F6UXhY4Oosa%(v4~!(duK?U6|kd%CDS2-a2FX?K@9{?$b1L-RSjXbxNa&;&)?n zG}}QcOdTE`qAfnmO(}+Yzb8+1_x46oz8GSVjZ%U%X8qdgHPMQ1z68rZK0$+D_UDyk32*7 zF39#16YE&TPLE>TMAOBZBko$lLk!(fELWf+1omZ|H zIVwVr5XzYg-gC2z<7KZE><%wks9L*7G9Kn&y$qr$Ce{J={_F%KH%Rw z{fUR=|4Vl2fMSffsXMCz+4pguEn7ttM{3l*Q zr0F9?^P+)|{C^-FzB;bhF`vd7OvX%wN3xj}4w>_rw=n&jQ0WyPrzs89ibPukqbQj- zh0R4Wnv}q<=IgZlIL&NjW+ph)X7+_+33;GZZrjM$XJI=OYqF{=yojEnxU=K3ICUH! zOC8PLQ}?$^d2QL&3yJHOGy^;BTviV;eEt9 zLDvhvf?(~=vrRNs<=@h<#@CRWh!F(USQ@9H+!-A1Q|g*-oeo_boiT*&z~Bpvnm~MR zIa@tekg(daKUr2IFVK3_o$`F+OVRrOY5@-6BZVb9_J)%Yj(U5h?UV&?`14GC3rxb9#LFGlZ`L z<+;@P8fN;_FJIOBg;UJ+h55bGt=R(QlMNoL^8-Ff*)V zfEul`7%8>sM6jZ&m=zC&EqGH~WVY7bhD|C!F0XddmUELbORElZt7f+O_K)IdHyjlno=zdRI+|rJNN4{88(SA zc{ly;St51%!1`)Z;_Fg`SzerSMJRixpygu6d#BgNI^mkQ+sOcg_Sm8M#f^M~P z=g>PqWn08k-KM9_=wX(pDCqD(S~bO!e_j~{p$J0gKYG~vY>U}s`AS4oR1_Fk!Pv<~ z9&z{PMw(7yUF1FMZ6z@qnM6cYPvk^6CVGw-D58P|NBdfxEak1XEUS0rs+n6@d9&>LkA-yg}D&3zqU{;i5tSx;{=qLa*@0mmkx-6RO->49gs zR(1H+>I+p5Z{0YIxNb~>P6G}6`3*;+rD-{{AdaN9@6Co~kzaq4m#JkFb@RLUHl7b< zW1%&_`e|=NHYtvisYWr0{FWy<+YU|M<6P);067Gp%HO~QhZf8h}G8@yLT(<#uevkP^NwY$33{OV9ReqX>JmSC$uvmcq`;2qG z`Nci=v!vh}pSky%+g{v}Etx5xF#61vu##RCOrrlcQ^sYkB+Dj@#oM4b@;T6l|F&Eq z3Iq0}0F~LaYVk%gO4yF|>YEJaW*NkFWwDY-R4akdl#{lSZ%7`k{Wr;MG(P&UX25GY zU5#7#h|ZHhv{_PXqMU|ax*^VXD4s2l%sL!Q`r_a1)_`z3{)e$Z7S_a*9laybSr@A2 zV8IA$CnzEu|FeDky@R@07xS zO@ljz9=7CPR#U3p%trDEKtmwffeJb-4kzC|Nm z%%?~aeJox9Nl>NZH8FOH{E;sboBN)%m*LRc$eSw)6KOrrQ!B)QlKv21o}|Wpo@py5 ztrq5AE&D?fjaV%V9kfG{A1Je2xAjSDQG z1J;E^-^O85wNb5C_L!Ox%b$hH=dp$)QUB770sf(}YEcYI*a8^v9gZvBt)%2DorD+i z4(r1PrtXsp{Ba_^9$l&^axu z`r$};5`%786tSy zN;vmxqor+jv~n!4-;|Sm4bki4W{#AS>FaC!PCQrarj%FFTwR zJ~C8Vl>lxHFo}2RYhk2p-_iCQH3BA}-F{uvU8t+P+61B1f9533^owkhoJEXlD%gB# z-5%-dST%r10t}0Vg@u0LKNi(8E=Cyjn*j(M{-x72Avb3;oIB0yFcQ~3Y&-5>R+6Sd zjQO-PMYAc9bQ}0n-DLUPB%EI?EP{bqNLI{5$@A6oL!l8AD9Fs&UC=CVO!U1hGSTg2 zw-NzYlVO=`nN@58KP%OS@1&eNfo#9Z?hRoB5?QOvcueGwdX-cTcTFVE?DPs{bp5v6 z4mb6u4=jSav-sh)`ev11?bcD4Hr5Q4pnO z@JAZ#dQ=p=&?%`oo43SbrvG;kx&fzp!Gneo-!HyyiSc5VmYX2vvAjUrhM#IrCtNbi z-HZf>2ouk?V`jno!GcBw>l=@!kef!Nk@QTN_hzoX=CC#4YeM_sayo*HN^PQ@m zfV37_AiD8^mex+jqlxKGk+(vNeJtHCv&?vJRAy&>-Tp5}sSlnlbjGw+)cB4$o z=_nWdlHdTRQnwg;X0gn5xb%6^o^iSNCT;NvP!j^z$^413ejI2q6V{N0V>pN1GBs+! zQ_$t)So_gxnRY>9*D)$jy}PGIPz1J|!fj7-+nv;Xq0d$I6gIsRfpaghCn_;=zsCTl ztRw57w?CR%rI*1_JPNsrUcX%R&j*aW}2-oNr<%HZMm*NWqHm`ZFK2(=GwKVHo z7t(FPH2j#4C`cb8ew4`4Gq<9~|73OFig^>}_l4IHS=Jj?Aump(*Uta*#H5m%CM{9B zu>*-&dyM+1(%k(7@wlR?u9mJ>T6}?0rSk%zv;ZSCgtB)FJS~2Uuw$NzckaBPeP-Jh z@FCXyz1s2jax>kLTtdo%kqWhsrYXWsYK!`hqZuQ7*T0vsYar-7LY&X+QY321-Ka<%V2*OX4Q z@yjiz=yBLJR3&2FR@xy3s)15XU^cA2mQR$rhH9vCA@cY=-V^pf1$ZsFxFiCLnnZ#| zaEzKo=cM|WwSHQq0B|r(@W@fiwU3+>EH6+XPw5A?sTYe6;2(RnLnv7h&X(WlZsCg{hO-l0YtOn$AYSj2;wukF@?*fGq@&R3#L)( zd1z?1geZ+MAbcVra0cA@h|h+lrk9r`HQjhg9 zX4a?El6FH*4K$6E_LcOUR+xwOp%fuiJZpc?|2`~uC52IAV(8|Ct9kuOEbLP18mRz1 zAg6AGm+J-%Rq0)`^}F^J>#@K|o4MN=j)-r5mKB8$?P$YUoC~JER*#q)QPPdguX$ z9$;vG&)oO-v)1nq*1GFnuQS8Ep7ZRp&pvxYmNilacoC1{KRV~LB=n329Wy^{=aZ`c zRVa~7xp|2{|7h|J-)O?J^u%0JIs=_8NJu{?H?`LD>ohBVNcAL;PFiw+ zEq_1YOLdW{^!T*S)x6I`Ro^;OAHH>V>^qi99W^y8>_X-NbM_Tt!osE^G%fTxEuUP~ z$_6jvJwJGOz>=@x^{Uf#pxoD8?UvP-bu!#42U7aaS+V9PBE=)W?`!%|<1q=;#f(Cj2NakIfvmprvNvj6SnIHYBL?>VQ9J zJh`5Z@0{OsZS=bl`~Q){A58C~Nd}{xgyo395ihxED;4S(_eY6%*e`kTEf^IlI;=GJ zwuYfOmA%HK;4)qYY^!a&75P@U<7gj(d%I#ujfCWdm)iLI``qev)D;n2WX`FvGdR*J zaeFdnN3K#?&9393tnysAHs0$N1LNT~2^0?-{^-a$!)2wU5wr=UBVzc?XZQF71!YX=AeIQ zRnPQ4*8DW-Hpt8hv-`BVxe8C_DA=i50Q73WY1eKHJFlPYGainh9v1OkAGDx4zjzoFWrjM0EkKYKzQ68I< z^?q|w{83F_J-N)saob$weF7tMol0nv969ZC9OKx=m0ZdA-K?B1KZB<@u>(@f00E;# z^BPLjJWrE8^2NSEHr5rVtFhm?)Goi<^LeDOQu`7$3xcv*wIXIRZr!L;}z2%=(U-9^vIze{Mj}d>Zg|(^# zU5gP7$wG?RqD6&m`Yw)jJ{CCh5)0Ja>x#Iw)D!%kedn)=xoQ;7z2~b>e$o zN2fHBd7yMkg6;nW{GYqr}cX0c-L)WAGAMtG>I08og1!ywqkN1ai9 zSV2^mBsWYRE_U7psiW!CXT254q_wFh(tRq4jO}|Zv?^`Tiz;l@+DSJ&Efsdrg{Fvl z$WcyX2djV6eC=Ts;h|&GsNBCJK7soxLtveC(YhB)Wuel-5!g-un=0T)4c<$kw)N-<|04`xBOB{*c`jnv3c=ag~Z|FI=>TmB;=#Gdm5RF z>buIuXYv;+(MI^w|L{_XH4QFDutzJXUIhb-|qM|?56 zS?VG5zo($%Lvp3u|F)8wUKQrl54PFWp9jYmFYJCuc=V>|b-aDUEM$uF!L;28=)r9d z=)_qx5dIg2^Y}Any)gIcj!1*6x|Iv4#Fdg?$H6H{p-9K!ekx>3qulmg07NnUZmwSa z&xB&_yoZM(mBK^92DM{+G<6t||qeIEW6Y&=gK&J^r%zJdySu-)xl5BOx;M z)pqwIkSP9#G_c@JVwA4Qc#m)Fk-)R?_zqg={cIreX%G7Iy{~s(KR-fpsL!)+4~Xsd}w2B@ZRg>SfD;N2H?ZSl!r?nDRVqmHj`m5cu3%K1mm`|YyYxjntkv#GeX^O%%g z%f{OVC!6UmB^x7MrBFnQ28;9pvsWQ0=}>`M61iV0yW_;4y=J-n_7|-AIve*SqnIBI z#s41qsa|0t%89!khBbpqj7K#{3#(m^e6UmMaj4E9{TOlBnqua_vrvuzY{i+_3>vxe zHbXQkhb#ePZ+R;%vvvHfq+GG5wNX_1HCv$Zi_BI>T*Cy_s<~%*mLJ&OR6Ex3u*iZc zIzp|`$?^QdcJ>{^hSYD7SR)fUtLPV{h8ak>zznqZZjg{;2{DB(=;X{iN}yY#*C8{w zF7YXL8jq;$RswPa#}O{8)s-L=S{GSMYOH_ZbLs_fC{02ub!1gczEJ0O48MrA}xW0QS{H0-Dc_j5j9 z$!zyKBBFdU-NB#e0}3{_ay};rVW@##jZ;UmV)DB}hjKx!FTr#_7dx=H9aP9fpaVG^ z%KeAjq!U=0YYZ`ayD=GvCfKK0R0G>XuJ7c(m7)6h}XB>u`BAsqUSD$vYDDKV+2`b~oQ{I{$vFL_@G z$*AVN_)ihe?e28@bX#wDzLb0uDNiM`zcZWiy)56q*($hzIS#QZry3<1q1!&Y`Gd5V ziXy-WqTFP_dl8AgZ&N%FOFzh59nOQ-fBRW|ltYu@kMThAIK;gS*@l0e{8-;g+bdJ6 zmwe!r^ADCkg?`CYF0@~1)n-p?%Yel1HGg3rc8cp?b>`qs`W{+}%b@a>1|%nd$qXFs z;Wdy3GGX7xTPRfbxR8}TuYufO2D!P$xc{u?wMrD$1RbgkuORUQ4!X43=udPZTEs`j zWJ2fxes0c-C}4qRQgzC#acEb@y522{>Dj@`Ke(|06Zdl%f>MndLZt!P3>Yo~6VI4S zP;4q_E{f-ZJ+SCP*2D%;m%72h?%_KcQ0KE&Z}@X4{r!MW%K1SU%jB&4v9rET>foz} z%;y)EIm{tBeK@aX2976s2%E$jiXYSlPVJyyz=KT!{$%Z_vnic`UB8iZ&F%fG+-?uP zst?3`#3m`3xRSZ!KZqal(FweSNJ#06wfpJ^F0Ig*EkJZ_Vi}s8f(F4Y3z)$#YSj0| z#K{P{3B}0-*<2cRRoY`99k(^y07cCdcs{mAd2y=LQ8_R;gc^SSX-DrPO}%%9Jjqm*ys*;s5Cm20JO^)Z~cN5--6GR_<=A(O^y5vdo&_SGv5$`-FdarT!Z)s(cT|6In zT4+2oR6y31dc^R|y&tQdLEH&yH3cmk{Ks?D07lmRayYJN6IhnDL$t(0Fl zZbrIB$k&Vc5_~27FnDKxijm=(qPtc1tZ907GU;`OEI}_Hu!@o@KVY}p?*4a{#;!Dv zU`6QbAf0FHRFxFp{uaUh8 zu15Ji8A>a`VfU?}hpJTG|Msl)oNBb$=ct}~K@BSrA&CO7>LHfW()sbaHeF5U8TV2R z6;AMpT-;!+Z>Dc*`yb~+r2qY?*Jigj!{5FTYcm{`4yqk(xwTBU*xQ+pmmWwtoDd7C=KmJ zlNB?3dY9PM$wBRZOxv>r9=BdSr#mt?da>8wV=t}J$W)`WT&FbUdNoVmpwwX_aIde` z3kX|Cjl4U7#fq=yu)Ql$!i%CQ_xxHq${&DF%*9Ir9Ggj4OOR@v0f<(*XAJz--DJwf zV9M(@379doUX&LoDngi|GQ5t^)6Ki0elb=t^94FQ0{%)+A?;0V!s(RMKxO7MY+VG8 z2ncFlXztP%ngMwvAkF3;z7u^a>n45M?o?@dg}F}qWcKIh>0>2Tv1pO^B}_z=fyLZ> zF(>@9-a1pELSopG%M987_MY(J-!io6EKVqqV;=27i^QM&V14t%|FAPYx#XvM68WNA zR~UgNt~s%sKEZwN^gLNePera8iRq-FLx2HiWPruNra)L@2@CUuV&Ri9R~d~27;C$X z?h_@ZDUm|!_}_$ddo9fed8m#uHNB%R^Z&(IO=xzE!L`edx7$%&* zenck3x?O;8{MOA`=1o6X30zel7GRmNDyObGzJT9kV79*j;A}ncWf;W}W1r5CSb%fw zGvMk8a-zU;yWjc0%+r6F*Q?`l4ysuO>?D{{0+zeMz6EHvWus^gK(gQ1rfVWii?z*X z4en3;sR#2O@B>)Kbpr5aNb2^|ioO~Rc<}i299ijkv_YtAgK=osySa8~zdF$asY?mJ zTUS3{Z@%+ej`F+ARl93cF#(G^RAtCeE*zm&qklUimHazOnEGDK!U1ei&`G@9?|Qs@USV^oDgSrJ{cL{Ew|CDMEsS6| z2j2IGI}LD<-LOodubGK38Pb*dDRk#Um`8vHAc_AO3sQ}Nsd>noW#9UN)5oMa@5O|K z!0Jeo=L}twAZoc=Cj@I#KQP>y82wx&v zCe$+MalTmt@5I4sn<(0#>@c%vCJ{QbwS~mGoGm8_$fEb^i%e zi+t0y&5)(@i(4?>r>_Mb-=13Lt96kE@*o3PmbR03NdOp$0O642*OOYL|D>T(4;Xhb z?98ycdDTg@T{U`StHa~7eOKTe2yQJt++nbB3hciy-!P~ypo?nwgYmWl5C!BqgWuYr zW*{3J4ceQf&H#*02dp^7oE*@F0!(XIsvAj&Fn>RT`eb%@VBKV&*JJch&yp@_I45t& z<*+-4sR@1?$1H+wl&7THRbIbCCE|lk*m_EzE%ug0_MXauWs!kT=1fnj=qQq|IDphVLA$Bfk#bVOD}U1#{u;`#grjfG#-2Umg0D zBaB6p{h2UUt{Rj(vO?>q1D!QQY$XedP{R^hW4 znS|x^r;*lOQu-R%thZdNZPwkZ%b{B)L2BfK9@c-YB`)Z{XN{iNI=ei>}%Z<7{8d z1m)-q=69t9uq-889|HC2_0`c6x!C{59(iVfAfhu==FQN}W#&zs7kc*0XBlXz-XYrrz;#?mkP-cL^32;qJ`tF%z z>PT=8_|%~q{4N?U2Rkkw`k_7iWXXasdr#nD1%GdviNn0*b0lF?#?6Y~cShupkjVRyicS5+nQ{*v5!0Uk1huyc+6M<dn1eR zn=APDQG^2e&lZC2w*tXEh3}O_bf1w|>m)y|%~JLtpY6k`=q_5by2lHV*z_M`$1 zr9nAfCJhMs+E14s$|}!)OPT^D>QU;+yPdYJ!dv7>fCuJJ=`Nc2S!S;r8oTDq@T@8& ze;-R*&%|nRvTnUwOR4|s-X3%ORS^4a+vG&-!mZL_2Z^!Dk(QlI4H&hjlFqwYbZ#}1 z72Et;d(suM8D-A~TWhJQAatF-NLZ;<+cYZFzo|piOdPl?40JHgd<%D#=vQjkVV*My zd$AzQo?N1mO|DQpC}h2g8`$i%bwB@H1NV3^sm&|@JUHYjHprq}0YydR(>{j&6-s|( zuHy`>TYy7m`j|1#cR|XISqX@nNyKBfhIt^OPxo^e>zrfqxP{i&seM~`1msA148WT; z4Lsih^;a<~Bqlm@?0EUw`xWf5=G-jQNkDPF>Nzh?BYm7HeoOql9;=>$js{t|O7pKz zGzkbboq!iE>N+_CL~0O7#AmnS(~oa-0yQb>WH@bib~;FtdI8K!~9iVqVo{) zp;=YI9X(kE6+Y-$14Yt~4X&qnYVzYR@+{$#8=9KlWcN-pf)N+@j6>iA!#Z)M95x8B z7YQ3FPkt zbDHSoHyMaX{j+G|1DLVKS9J(x6GTDB8F&>mGBB@tu`03u56zI<$L{!ed+Yb+dUWHU2gYyO?XJ84r`|J!8 zX~#|yW`j5ZJM`eeF!&A5eyjIcEUoY9R{)i0o}aYj)YCi)t|&eQ{$_;S{$O7l>|Z2? zY_|9_9{}Cjr^{1rBkuz&aJfmTNa-YEjxeZ8O-P@K%cn3Du>4_=`vrVZ!2ixCtfrIH zZ#lc;4z4?6VC@0FTo?H7#r!T~Fh?BVBEb0p4IZcg1J$k(_*N;0KzA?eTtQ>>HiQ`p zK#TYBgx2=<_75N%C%9K({02Iws!01N7*hx?52E~5L5$QocukIT3?2fuJZ5m#$^!sp z!0=-fRNS+ZS%))B-16hsmy65lGXu&_HfLvu%=xy4&#&3?)0z*!Z%4%Q@Ehi>0fNT& z`pgnkde7@i;7-3VvxqcQr z?(qAzDL7(SE|oBlpt2b8DHOOV?i{eh?4>Sx(#+c@VT1u@bME(}b+e1g%+rZ`4=BqC zXO!mbh^8yX&&2r3Sl4Dz#;J;lSBG|g?S13?25p8dURJZa9Ai(X%A>NPw|CrrTC2$j zSFcNIRNSO!Q#&-|UE=@UozhNXWXGxnCmv`zQt!PkOtr!6BplO0-PFi&HT3UaEjZ3s z%Z2);1GI9U$)lMd2sD@%z-1Mkhrr(Fl6g(=JEWI5{^D$`ZEEbZIHkS`O639{UzV!z?t z7fm{DD0!OjYtxLUQ+Lpiz!98G=J?x z?u0+$9x!1pwv`Jl*r&&RosF&Fj1{)v1MPfP@*|9c^yAKoC*fq}s!4Wy0S}aYSY`4{ z`TH-V_kO280>DBL8j_0*Cv#0S4!HHt^+brchC8|Xw>mMIWHyBHy^bCtuL0+1z0N9r zcQ?-717&TXHx{;RVB<xN%`oV+ zj#BK-nBKbNPlZ*AftW^ciZB@G27PmF)PA;32_T1|8l*gD{%Ldpi>?h2BZ8S3kl3OH zLnlvn9Q=?Kn?T@y`uYZOvkw|7V6#*!#cHY3gV{#~CPY=*bL8Z77obV%0_`2J>HCz? z3ld43sMItPYU=zzR_MyXsSJNp&eJPQ9q_w?`5g>$b~GZNDVbEmiOd%*w{MTn4I@Vraue?583Z_jS<}j5sFH3>}iT+w?W&1Mb z=WnhosIjse3M&CtbJ-vvq~mPZ;S>NBuj|ds>rilfOv^EIKulj1$s2d3w!VNlfg69H zfgy|M={{!U#~|m=-9y|B;_`s!FQy*DuXa8D7c&B`4^UNIg$$Y_GY~NhIKXFP$#EmC zg<&%L%D`3<5)ZTx4<6G99#)p$y1&r;{mP|_sW%#w97Il59nf^VCd4jwb9R;}{0H>N zutgwL=!l>2iQD_D1VQcne&rMvMO4ih^GbYf?p~=1L+asA2YO+ zec<*TJ;h?%Ks)E}CN`lI#BK!lKB;_z?~EOY@YwWIUU;ZMR#&*Y&t9#*dX+@J`L)h% z(yQ{pe1%$lX^@$g62l#HojBxs_`8VtR=$Gv-T@*FNYZLk8Gb45?DYuLzqu_YTT_oM z>%s4zcN%ZaH4GaP?N|D7)vG`$%i3D@4Aw4&K8ucZekpX#qL9!?HNZakvOFB+h2~G8)U4_;&GN1E@s}Ajn z4S$$Xl}u|ci?!@cMXWP5QW*$l4O!#2_C^h}V8gUfkl+rh(m%Zj;0*Si*1R>=rA?WT z^K3Zw)kU$}$Y5(Ti-PhxtX|`({>*Lrnze?hWuj8#K7*WoVnw*Xa;z($Lwb@lu!<0# zk>5Tic@+TG7g*E=)A}w}`duL-(6{YU58TdXd&tIk*FZl`3s4BA3ef^W8n$~Tb;Z!F zo(}F z;|pMc{;P-X?&}pURJ{PdbS%-{9MEFg#qF|X;3uwk4GK^y255n+Aof z$F$e`53bi8u7dz^wR9mC*6k0}pO&P4zybGP;X4dj4uF+~AQfh>5I}?NIqaFtsKyT9 zjRWRJN@}2Hzn8D7spi{Hbr0v}D`qV1f7;++FKBo** zg7DwgxBiao6BDO!0*4v69tybYHY;=ARHQv=I2EMBkCuyN-`T0~8fk&RTahb1eIF|y z_O5UPYCorhH7WbLzSltG$KbUd1>P+GxwMLRb=B<-lGSE=xid-$b>`UPhFyiHzr7*S z4p-9CpkD&g%Pw)f;wq3LfGb(OsUhD~)`@8;!Jw$+(Xz+cdG!*JFmn|Vkyn?821IWs zKJk})ECV29!0iaW58(GmaF15KM|*Zlo~P*Zl~}rR6tnU^2ytPR4z$*O`B>rGK{HuL z)PYSxJ-y^ouIrul&M18D6#3w~ExmUv@@g(Q1z$=&I+wvr+vqc3Jj-zmO)3S>ElO5sH;cW%|${RP0#Z7M65bYBO?-=B>T6vn~O)K*FNpD_Di`jz*Tog+l zLh9|KIZk((*Im}7JCBzA!@$;8Zun@Kxhqw0h#pjBbbff-v+Ye-hSOcKKpJZPz zW2szyhu=Z+tZC6f&nI+DG<4D#aL~K+F79nRWO3E(fGcpMM4)3t{pJPvsUFRXyx_@Iy*hPWkh=%*UBMSnq7uDdn#XWy_3c8p7IvQZT zTQ^MNESg{SW=?mtS>dHVSrEthB8Y%PL~SKuY8k7yVy z%)vH>eS?CA1{km$9S0M$rz8COgp|qB==A*x@FY-p%Y;;3kd?tnYr2DtE-Dt|c7=G9g>OQk9ptS$4ZZf^`GB=JsyN_$>`(K{g9o_$!Y z%a2A?;2tBZ9l_@ZE$dv1M-+HEEVDUL%fZpyOj4~y1ya&ag1Ap{0%5uDhsP|fgtR`~ zQ7q=p_{IDuU!0VMQt{Y4Q<7m>_ZB*B{O)DeUu zBb)SztHwD0vApE>oJ;J{s6U3^pt9On=KR@1mSk!|!XA|+Z{z7zpi{a;rexbd8WgF#trnNmKLZx#S!4z325W#AM4N z1weDfcN5}PLXbr(!CxKjmZMA>_Gk7(LVS{ml`ss&FFodVFHP`4$jjAcSaax$%a$Oi zK)FdEM8=$qVFCE!g_wp0P#Fmd3Igfp1F#p^6NtuYI8e8SM{!$o%KcQVr26v5DP(ou#Vn4sNgV^eI& z8~KC!`u_F#BiU2w)~c(|7UQW5^2@k)ejDnoU*tN*VTF`R$>&fM28i?F+$k!N(p(os zr-7|~aPj}*s?F72jW(*^1HT{5HBKii%sT=TDe#eI zs60Y@C?aIkOEoAPRKrE0FXBWp_bxQ&eH|UY>|G>MCHB=VyCukYgnrf2(|ZP`FPUHk z{fut;Nz5en!l?dbG5(vx0cvlf)*hHiZzsHA~GA-yhS8l|fK& zvc&X3jsU^GbL#JPi`7ZCqS@GiTd~E0dgw2e5lcc;4;f|POJH|1Z1FHs8Xc+;H=NW3 zjqi}ukI!uUh09j<<5yRpVAeR&t-hfFgZk2yduNCvdrgD7=)izRv(A~8(qI(zu}&8d zQrg{LS1&^7mpJ4+JF87q+JoB^@5gkohk3D|UI@@$=ohHts#M5A6=GRk zuWvb;o#omIu#vqr<>l7B5R?ml8TMvW;Cs&(+`hEvvemDYPreb#cx^C9Q{vZ%aZJlL z4LI9#463&)6Fv_6KA>x(mxXi{vbD3TYHE@zofvq@ANTEwca1snRhsfE>ZtFGI4N`1 z*SpH~!8oNG=R!IzlpSruGOmGEuK%Y6D89ED{Z!eBD1e8<)FVR8A^oe?1Jx3pKns%h z5!8xuOC=#k?B;)HUrrKN*D8{vXFq>V5JlSXviPpm7d7j}_^rk@3gtx;@4)Zme>Qu+ zPwE7{q*CP$nwQ6#vD*S9s;A%@k8xoDX|I`_f2gTRxg7O_aPcUaya4eE_jg2!9Z|1@ zyRiFp)LX-(eX2rTbm(qyuoW|&WsY+7dxW=z0EY>bEf z?G4EtiImyN$w@#XXn~fJmaE$%XiQo=Wqc881_!t@`E+r6%Y^! zN&zt20S_>Y-|Dv$FxsT+xIBCaX4IBI3#M7xje+;G4Gx~D^@zH5+W(>+C?f8I&&98& zyQ?9s>T73*|5F!EOGAU99(2nShiTlYdfQ)DwHX;1HNfoc?1pIqr0$kkmxMKjx`dQH z$ziTmxdoaVck0Fz(hi_59dn|Z&4UEd<*SB**8@tHzHjY2C=OxaeoHNE`0HkqYmm%R z&DlJXan;;QZVFtAWO9uW3t=?RVCqur0^e=SIh}JYSWFLvx?7b^pvOdgHh9v#y`#1H zuRXT8Pi{C%Vpl7d^u011&Ogs==u^MG`OZ&a#~bNv>(YS=t$eN|FviuSTH=?f9dqar zvetcF^069ocK3gPHU z9-DVtQ1#Xq(Iaw`xtYGl8`V59g2>;Jvv}`Iyu(_(d9Mra7oU0~e-a&Mj9SI*C&sFe z6QsDlOK5Ify6cDU1(0T8zhU9QlabAOso$HeS~5ko@f4fH*`M>jquPN7N0X*ePQqYT zycDPH@2Gmg(##`e<ZKu#4L|?|-2sOMHJScK>F2+S&W^ z{>q!JmhdZF$+aBCK8vmD6=n%oufQXlSr)rWWs;;<3f}YrZyxYDDlDF@TJ1RlL(AJ0 zNEI9^34!0`W!b8`%sn$N)VK({;bXUemGZ z@UmIyQHv&4Uy+{h-hHgzIt68Y%8{3QESKBYhEviSrGgRnOEkM!l3YN{!TU9yzNP`5 z*v>E0AKo~KtbgFm5vE$0MRYXE5fkS?`hZ03NdHoY){;M{hr|rA*O|p7Namd1YC|L; zYN{mbswe>+oqEg_;iib-X3gmQ@o*ES_Jw`4>yFBwu*02-YDDE=(2crf6fsFvnber> z%hchisi_~DKQj>1+XhvehA|M#X;ad??Cpt3-^||bd1iL_!2x5=pPHLn1$-M7EiIU!z8(roifuCJxW&H z>4sUm&ut44HET(k9{I@~6q%)poIMeqE`NWTf4k6#ii6vflP-59(s^xcx>_4BIh4dF zCC9R=uLDCC0*o8d^(*&-BQ8M>?-JC=oBc8lC$nSqTs2bkSC6ntG#7*8UAFBE& za%HJmtOB{>o%1ZC)i9QkK}VuQ?MUC`LwIL2+nT}JauZEEa;4?Eoca_xjAWCzzUao> zoe;S*jh>$WU7nIvcMY0vXhlE&286A)o*uA`2mX;@_5lJ#K%UBe49{izLXviDC{`9T zVPNtZ5eOKvZ~TTG7hVOv8tXa=@Wp^REZE?3d~`~*r&2~Qy_PeFO)NwpnEVOaPp{4> zZvKdjOQM#=vR(WS^Yc4TR&^Htku!y@TW{!#uO#xczDMZ%lUdpN#-kSQu)n2|QdiBW zo>#*5^@%aZ3iqYSv7XA(Uf||EKTm9 z+&jM=mU1MZUz1L=!zU>j*(YJ zPfQxxtExJ8cR3Q|*K}hgcFn8BT8oO`tQ$-}j2|>-O&F*PoI#l!dtP5iehH7Vt{VW_ z2|)LEqeQ?4gW#)I#v(LNdbz=n5*%Cr)j$EgW2bE0Rj4Pe`7o0^fZNJ7ADZG_`QFGE^3Z+w#g(U8tp64|;FjPsj(IMP zjAU85KXCns`FJZrCgAwk4Lo={i8_V#e?PjeIB{|a1$6#w#;=>TQ`nd9l1Mane@!Y) z2>zsIsdUTy`o>0|P&StM2bWUI8ggKMy)xh8!LORLLE!G}Y=ZMF)O;2k?QhkMkNRLG ziRV@Wr(m=RKANqM#3T-z_f22*5WmSi@i%RT&+#O|0yuypJeID`FN`k(mApA zBk9p6A4pYo62&dvTVOlk>3r)qiJvUW`yjWMq~hylZ3QH29*SpLYWi7w)8_ zsH0RIXtiLDWR`E2-OzLtnr&>BV;qX2{lS`&ldy#_W91YU2q^)HXU+2*AZoF`kDm;W zWeH!3(>ZhXRYWymx{Rl_F zxSd>HjfzJkZqY(5o}c-yF59x8g$T{;u(S%x>613Qoo@_oEzqQ zaPAzrLNkWBRN@gmkAsaAxjCl~r{}7#E%bWdy%8th8@E1#=`%(lO{&9fd4DMuCJXlb z=Kd_iNEz`b;P$kcM6CI5`551?Zu`~csdX2cS!4Hda9AmFms!kkW>gf@i6k53mEK_= zK}Z86gB*D7G~-&RF`wGI;wgJ zi%t4+{!PWoCz1NZ_?&NXNM?Kz5Yc*41-zIHE78(>m272>T8)Ya)3*GirNpn*I+h8fuvd?FkxQmcebPfaa?zI5EW&fgr_ zO@MU@OzQYkMU$Cm=vHAcSoupWFfRw;fuQWSBqnBpNh5$w({poXE-rBvH8^j`g6dzD z&)cH_S_P-&KhI0{n0SUz1GdCL^Og=^qUGGA2$=d_TEA7$ZGxT{*Z^R3FhGJwYRDN% zO}Kp4ANPE6nR~kbA z__8m#HR|HX$GiYe;*qb|VUvI9rioDXYqs^FkNmjY%7m!;`|*9TI)~dfPfs)xPJh}r zm|Se!K~6lU)H!)*or}Ryt1;D2e1A%|b<~Q|+t?6>(6?$h7lRXrJ?sOd;r;9Q!xqo3tWC}9-uqWUIf*usdh!=}l!IXQqbD0}!0Ue}*k(Lw49 zqg7EPUR*fc_gF-)%@BLH)U#XhE8%_v~(P97|0}@D{z_5BElGFMETr|Lpv@Z5YWR&%p6gdO* zyMs74(|a-q4hP}ag98<*oDQ-@Yk9JsB zeLgG@ifi#?*o-J{SRi|u8btoSTImF^yfOCjN(J{EI9YPBzb!_?h-T3~rCEd% zDZFUcmidP}@3f$&Edd14;4I(nPyk zpaT|Zd4pa#3Fx*gYOHFO^ABptnw)^L^+WY?z*FEkKst&7(im99UofR{bbOO&4%llR zsz%XkBXDWF-#?)qPt z1W0We<56fu24cNpoX3`-nt!5b0m;lw z3Ht=f0zd)anY{Sv8q1>Q=rfJD4!w&ph0|( zQ(jMvNIiZ}o|%rlLnhniZAb+h{v)jpLx`+mE{h6D%*MTPUKvBn%~AZI@l{g^b6n2j zzV%9-!*z}aT6lvdaos+sHPxEce@a6{>3O#Xr0t_D z62eAeF56f{f_1Dv@_n@Ht9D(eJus)7(F8&#$Lp`JIn~Smt1|ohP6?{A)w5unvfQ&mgJN{rw3d;F~mkY^h&U6aPzbo^D+(TLs3hE=TZ zSLIx;S<3%UMV(#Z5;&r=Ps#czyq8%?{g#qZU7Te?#S=#qyWFd0ad7WBbId(D<5&4P zcX=v*^`$#Ir_rvgZvWPuHZ1V&C`bL|Nn@r5{q$yht^SDI8P`zFxDB6rzQ0=K3V*8E z1glPNOx&TI|0eqHm9M?0UoSy^D^-jo-Y%l3L7LF0GMC}`0vfeaK0y+HaK4QvN|q&? zduhYf_=oQ2ZIOJ(j;CK=j8FqvonRz)&(sECY1$tO*ZVU=qq&kfB0N;H!h2*&MbEZA zOXz@zgs9^2zc$FmwevaYmD%2EXT$hMCQi&G%{d`SKKLJqoew?zT>{N3Vc?GRsTmmG z!;(e>gUDlm*kF}KiJT?2`mp?I+luNst<&|Y)`djo`zp0n$1k#@h*ld9@Js_#AztF|uB-<=bEvwdlv$?{jHy7#WFWP~ad z)3!hCAp?aH{LXdDdoa2~up+SyuhV^@TTYT7->qAD*F8=C?g(u}az}B%Tkeu=1>v#s z{hgfT7o3l9#{>aVD*t7$OWn{`2{qA8$yyUL@W!X>RLCc))7>%LA{zU{aBtZ>dOdem z%6slUzy~+_>}<1GnOl$_-oD*`8S%OvQc{%#dQ-(o5n4fjA1gfIA>Am^js6GS2=2ZK zZk?bJo=a66bgTtbdhqbf2y!5g#h} zaU`OLb|&VBx)ntA*Op64sc)}}v2!G&^A{350ZH$*BdyM8)F9p->F7uWi_G+<_3~{! zqgY+33%eA#nLpFjrt!MoN5%QJXPkZ7Nvn(@>3;wJarKo^QAge0(h3MjBb_pIcSuS| zcO%^?NFyoTok};-UD7QgARr+%DxJds!aegm_kMWawOo914a3a;oW1w2wxO++fx{9h zeD>@*j7_;?+ilG8l&k8s8QJjo)hGR+|2^E?5{$WrK*=p2+MAVp$p{vV0X7X_l{$EG z8djpoedrKQW)|KEE+8Q&v3FQFD+*1qh-cel+`n_Q+A2sy!5y7ecR-f^^g4z|Ct%`x z;P3FS4%cauwDw!cvb4R&%UgLB&ySU)I>jVd(=k_9SAlS2r3`yh8g1D}thX(6%6i!% z-1>1qoa5NoiDCt*Tr`6o#pDJ`?|8*;(prj%5vgK#736t{ZSgbhs&)=Ou}r@OjQSWy zI@K=Uf--$kv(kXR8Q)DqD>56g8J%CAXdNCD+8uFSEfHN!Ve<~3zTmAmYm@HjI=RQ; z4E{`T77=f=?V?BPp?$HVbr#Wu3l-QGl+qwGn~FJptG?i%Ix*|HmgTw!WTw}oYx{3( zn(pqVbWX9<)Kn+Bm}a{lG@H8#cRmb$nhr{zwyM-FB1HAUe4S(7NN9RuDD;qgsIjqDUmc@n!Mu8*$gtM%(&*HaE`kAmHx^Xh zE~S<-#Dc!tP|bFJ8%B5x*z8K(YHb#xYNcnx-GqvNFGWC6F=e$!Cy-Whiq~6mjNpve z^@^KPk;41xBmks=pg09uX@I}OtN@&7a1RtQTYy*tgq&q-I#-aS4mXolr67fxqi|tM z+%)ZVx>5vSa}@XXCFXZM5S)&_1>C6ZaptL3r8Yuq2g)|+@BLj<1LZo5TP?CRE3NX) z!XE*|9IT)&024&y;3sF}nC%}TfzhGOb9Rr|j9+vFPng<>?rM$veSO-PTKM9cL)Ak0}u^d2o~ZXOkxeQAnLyPqfNTMH}?{}tYacG z-xls~@4?&&iQ3L=4@{r577!3%lQL#W2h9Tj8Gb}!z|R6V>efJS1R!_BdsSOqUoQi_ z$qRnkU)I5_;rE#{-v7R}SMr$dO`Q5TS)u_8R$rFq2BsNCVNO2BGm>wcbeHVz|B^Z? zDy;fcE1jo&z5S{e=&)tdG=aGd5K#%+`W8RV#d57V-3{LT*<|of+h1(i`uMI;g|$() zW8Bi}sP}It$1ya+k(%V+9S`)qnirjO15D7CO(V6kf2~X8P z7E3OBB@xM2>pzE8I$YKd`mE;ay;R3W-DPt|NK*;Ul*qUry3*1F(bFcLnAK{1d#g(d zq8oxPQ>9hJ_r+5zVCj{+Z)?D*1e+=|45^Zx#DpOv zF$%sbGN@B1UYgfE^EXQWOViMuaJCDzc(AHQ&3;F2NYX(h8|&h2Og+P8-(AkcZHhZx z-DCJ{b71`4c~*g-@eps3oyEeL89rj<&~ME(dGlXv;nyeYrf44dv~ShT8yjM`f3S3wR?rZ~gU`%*V@afs2WMzS6El4Ri#uH<@3UNgTngF8x376bIm5@E zzpNWHVQJ48E#F~R(p`Nk@{eV?YI51R^}N$qj^9E38!7+DEP9PK)uEHDoSJ(ao5S?a z#wjih4)NVoD>4=hp+VG#x3bo{MSry2Ss)=;E~H5_3vU-3(#NelTq*a6&sAs*SL2J2 zzB^?+a43E)FBf_f^#qwY-9uUw+dcGA+wxQsw3zut{jq|S>w9eozU4`O(3+2bprWo= zy3+lfdmI(coJJbKkwIj^be;AHr%V)_Gn#Gkfa04=8_qeVHiC^bpYYmyCW;F`D= zE7Q_1ZEM4wSeCqZSyAfde3(GzrGT?Ec#Sl2*=ulnv+E1u!>X$|_7-k>)iSJs?}a;e z`XGRoT%)#y@r5iI?T{;Y?jDDt?XF}pd;CkLWoZW@GUXM*de)t%?kN~faSbu54X&mD zzncF8tUbER=d1x5Z1t8_E-AwDJglXaoKb)aBoWc#1eH4q~)z zIW#HvSNJ;D>+1#1y4{$m^Yu15*l<$LY%7edvC;k^l zyboZVz#wDV?K7~l^4!o7a9cp;Mvj=^R}WXRa+zb;eu+~3r}$oj0t~ieSc&AXz%)2A z5q3Pp4i=vvkf5SgC=&HG|@HN;tT{falOTYyuXy z%Dmk-a_<^ZAFDR4ni-fR>lI}bH8k>)s)bJJ%A)B|$6z-lpF_noX-Ot#$D>q}_Azpo zH`weBO3f8Z@KJi77UHbYjz9G_9#v&Rgos4ORzxlKL+(n zhn<50oPV zg_)BM+J<4OzJ@R-c>?(U!R+aDRf{+6PO;J95!7+s?xV&*2Tsd-fPxETFlkA2c1K*1 zmuwTHNM$xHgKQYaQT&1zMrMR^SvVm#a#~i`tw%zM;aFFwC2o_wRsP9S}v&5-K zI}C#ax(LvETI%&M_lE9#3%RLTf0e521)x3uKP`aq=50j_f1WBv+rpRHC1>3L0jgsE zp7WY(hH-Md=3Z^GU?Sts$HzZqkAl<>XfmY}3IFV0isai*pbozMNuP~9{+v?2YN&FX zTU{dBqt?*$6Vwb|M)hhpnRsSv>g;XK(n4Pl{EH9V+_c;S3h@ae%*L#Weip*AdV3_`^=n$lpoMw0oV|5(=51h zl>kZvd14?NX`;aF*Sg!BNZEozU~@vUu;Q3{^!l?`A3l^t^!`fB=yVEw+p@v9g%- ze^};KY)}sjjEpP;1M|WE0CY#if&)M!04NENlYEm65YC2xEbEtU%c7dQ`k~C*!(@m4 zIh=j`0aZNzB-FLbuxS0}EUmB=QWLuCw@hggEW3j7=s?FYvD?@qIQFigz>Mh~=cMX8 ziqUmTo2KmeQiuS2Lce!1@UEQsyCjjIM(YOp5@eNef9<>*&7=EAfW{r%dIqU*Ue-jc zkB17tqOV}$yskJ3TS9u{T@^Chr4-a#U*8_Y&X8JL`#S>(KRH{kpUz`P4sg+T|q% zF~xa~O}l-BJDwakzFR4JPIc+C7jkzMQ?E3!6y~vMzZ5ewsqh9!(qLDkNGnb&}^}0ai2;){Q?$21PMk_ zNLEDuZ7qnGT|?5yrU&j9BHe2TAG?X`UD%pK3!D9c(99R6J0rFdPFASgDR1`clfaF= zsrvf*jabCJ^25s{Hys;lu=5R#!_4ATAmQn9O*jYS+nd6j3sTC&P9ORj=v|kn( zmrdB#1dRB+o@*Z&7NipKazm##PSsQjP*R~T&v^GsFjpmxyY+`#;c_&55u2y<>&TBI z7me{$26#%4s-37tI3#n9#A=pxDMD2H>*}4S$L&po&R!$F1a|FH@gzaCsoW=S6mKa8 zpEhl|qF^wiczIO+gSZv$e%ZP)j*$bLTI{M}trDqky8*I6Z;+aX>;$8xL^MlsCF!VD zJJZ0D236(9vHAw;_xr*8rFYin*@T;=AB|Yjosiz~J!dC$Dpg>52wo7=Wt#%McJ8~b znvag(iuQXz>sPY_lEDefu?Dla^FT<0x}?J_?|x% z5EKOF$_C6^u#k3tsUAKmc|YJL)I5#hfzw;wfuuWe?Mhi#1^5Iu*7@N%3o@Pu5cE=A z#L-Lb-U${&3!L}?B-G4uDs*z#O9?)i_Gh@pH#=BRP|zL#sfyZHwD=FOq^l?3L`w=b znb5#|qa(U2HSZhuJ@qcDi}HQvTCnVy@}T|uY`LQJ>lBki-H%b&+$ZqcoEaR&2D9=m zdZu5w)wwcD&<{_Y8m9-|8}itsGSJR17fIg};Cxn?vNeeG<{RP8H2e{4ui(l2nQI34 z7U9^&42Gr&`6=f)f)NhJOO^t;fwDu;OM^l#HUd;%`aLMi#ynpTp5qSU7~0j=O7B$F z)fK7ie6eczuab{sKt^YTv)Ina40JhLuZa1FrKj8CiaboCcr^Zwd9}xT+>0=F|8P`< zHthV&RATJ1OYO^4aiSPyu%B37PP%7cWDjF`^?UA_!SUnN*GDz;hU(gvgbOc=lH4dp ziAxcvE?9HCrcRXptWBpIMOTq6Mt>O(9TfIYyuCg_8Z3Rp1{u|#DL?Q{DtyDM__I)lIUbcU z1=^ycZQi70f(bIc9}UV^cTO3sm6?su{ArcPGHKfZIiaQ_1`Wfj?p$&$%>f^bJNjB9 zn|c%GowjtV;TzM1O9)CqO0C?=Gu96TN9Ga*8@0b&CjGk;9#HbVC*>^E+F!82u11IT zdwS7Kd2M6?#&JTC=6IbvMtl$bt+4|s{cRUb*KQm=YX@-pM+*z#ss`*^^j zLyH}FMmDwBW{5<;mCr+fC4VIi>q#?3pVxvI6XszNk@cL?wI|U9w4SxYedAsp?q~rI z;v`P@FmvR44&(%&Dml%md`|^WvXhI;%59BtJ>7C2qOJ?*o0^$r5^-8p@L@j5?$-3H zb0aDVu>(AYch^${oQ`Pw?Q`%WKk3*nYuq*crrMUL(8@00)Au>nDI-1gf#?%wRYP&~#5%1L@oq zKjNGM1@6wy&`9{<(NQB1Hh?L{wdCcc*sMr3U@`C_X~EWK;Iac#yrf@(P=c_8#2!F4 z!~$>9fIH_$;3~i{_xJY&PH}|T439SvFSYbHrKj@e={LjnWvQoYamW>;(~5VsP*YBzN1FCP~_P8W3XbO6QH6X zZ@_TUI{Qqob~W}EJv!h2>VOQu+#&@E0r7m#Hei0|b%aN-{AG?LUr#R5B!+0`W<&4D zj^9uclftgIn0RQxr}|IzZ~aVs;%DKq`uL^^$6rnxvRLnhsRumqO=qB6!YWPQ@z30ZY*0859mp&tTuN6&X}q!RfTV-#vv7Y;Cz_L3IIfaP8`+6T8p*!*qH# zi2p+mjvt6%-R=(j@4?I*L>x?+n4=;-{37ib9x(oRqg=6D8VGZGD>N-1q^6xOL4F}A zla4#8m22frGM9*%M}tv!EY2dOp8@NuJGx&uS)#``{`jN2ZUqe|@MVLR9dwK0Od1OR z4Xv!#j@-~b<;Y*~_-UV`S*KmG=m58*#27vA_nK>re3p9v|B>n(^X%4&(PragyiB-S znKUxd7DOT4b{u9LQa9#yu<_`lahe%=-|GzdxL3CniTEi^_@n7b4lNGsoP%6emX?Fw znXyU-9E5hro&!q})xxy1ScQESSKS5E9+N&x!;o~B`j6DuXOvsU%XJhOhqooA_=jc|!{Yfbg%&??I6y@s=B!_c40Erfn&z!j934(>d z$Sm(Zj*}60taEjT**5Ilv^Bcjke_;N5oGu)5orSk_$eqL)j{?7#%Imzb7JP* zRyWNl{~J=o%nPtV&sVwte_bBOLjtrcK3ldWh3Y|9<;{ymu3&?0M@;~D3=5l zEufDxR{ynuj?ap4j(|G03~;jrhlZAxmXkZMfLMSxQJx-fYY6%e;Rh9=MC|56^y;~S zt|0Y)$wmM}%G_)lNDb1I7!j8P~tMdX>!g1Lp6!Bjt+`>LuX!1NT$sTAf#567-Q%(=RXIIb0-G>$~ZbTITPZ zT3nplT1}moZ95l=)JJrKk=KoyGtoI3Jl3Mxz6Ck(&0Jg|b z|NL`H&8@NPdis}ty}YYvu-z#il6Efq#+Nsa&q&?m{_TWr1g5dO7T$<`8*P~CNb2;f zbCJ~RHS;FR4Av_-BYrUP5r^KHJhwczTnMS`yX*&kH)I9R zuKg~hp$r_$h5&rVZSb)jdgm&YT8#d-<7+h82QCQW=V3J0b{f4uJJ@rlXdZj)Ugep; zGa-?D?3QN1lg*X=y5Id|FWB<^5NTt_7dc1-@55^d?JktqqA_d^9+K=3r8y|%r4X++ z?PFJ5C+-FJ_f)SdT-~(g{?o23NyaUrqk9Ue$^myh%YT6U)(Y_SictmcRGhTXET6~8 z!*Ra4dsy@u4ll2KSzeKjcyr&Ri)CwxLOBYx@+C~Bq$;}Wu=eW+C?GOpNlu>}O2<^~ zh%0#YgtU}c0p=t$wE$b==v*?IiprF(9_L+^&?D=^w#R?h@x^+RiUxHDH05YzG>F$EZMVS)Ox^>8Zyqg_}+fWDBxZ|O5RTSzLGU#IdwwFPxceYCKZ{w z`QnMvPk0LLYiox~lJJTYQt5OXM7!p04!iiHMJ4Vh3sg8j zR|9l=o?z)Sp`0MonQVhNDK=smJ$Nnv18dqFFb*CP1gQs*5ip!blvUyJplnd`K zULaoh=0-$=u&E7}06d=QgM;+n_y*mLW$iPp$^N^PgPiuOOB=`n1`mtaEJ*4I*pa7! zaoXnrzZ&qRfcI}@Vhm(C2(b!We+wmMKj(w@u`lz)b(ebC;y1guyS={yS`-MYqXPH{ra3F6qk^yYApvX}!og&D}udCJSsB=6#2T8zRWzaL}EZ`+0WABDrzN4}WQ zm_c7FrsSmsS4_ZirT5zY|C4WZzu>_Cg==;px+n@z5TbT{yRcxgI;|NDsh3@AKme`3 zC4wy@l0So7Y073roPIL740bZxbbJg@pOAsrt_N0==p7UyX^a3_a;|4bYpYGyNNEzI z1CPe7w@5w~@9@ED??+D~lzDiErstOUNw=pS`^G41=J{pc_D3vYZJYa_@|AgS1<}0* zkoAd2AYAgiac}ZOm=84#bayjNZdMKoF*(U=P9uegHC>*l^+#;FPv?W4X;r#nS? zJVDC&$g69pZJ*~C;}^i%h?<$~9-OwMX|?HmB_Ue&n1cUY&n7UKay~APlec6_h1lnO z@)~gxV2mmIz3+tl@F>Z`x^2~jSyx#$2kHw-5D=_^uoeIfZ*Je#ynOsE*Jd`D_xvxW z8Cq~Nm~L4>4@pcoDxCdi`<5|4GRx@Lp_*-~5xjQ1Uyov?Hq&FJnp%DUesgOO&b!pF zwoK9eG2e^Wl_N^S8weZN#MOvPcL%Q_Up$BKso%k8gKcbWF%X%7h$Ni*dsv?lvhkK- z%=VO*Nf9&P2tk6~7dyTpAjty~o}h<+?-02{fHz(6C!o6nLOuk01~ynWH8e zApo3u!1c*M-Kr~Av=1KtJpiSE4W>x5@&qUd0pg9&;H8caiTKCM(}N~mrN^{fo8=T3 zL;(yRxh({m={UgQ1LQng)z&keOemp98`F;Ouam3md1hbt&TbE0`jKpF^T00#jSIf#fK-Rg+Nm37vblI|o-&{ME%z4P||0s4&jKjyEg zWW0QQ6zZ3nd>3&kaplM!Iwmf*I!}tQ&vGSHgC07T|GbM>W%=HBd7DR(*d7#x*75i` z=yJgG;oBtfbJK{=qb!_t{SE6t@opA7=JeSsW?@wR1 zH6-GD`RRwIr%WW+18ApTQ5;oo-|kG;1*biKKjjLVY$_VLry6Ym&Xdvqfw_;-G9m9k z{uh`8h%+fi8*)QFe2gO*I~|X#G_2KRNoRY*>M;DlL#?B3(7=iL_8(AxPqeuIM?nmT zV9*Pa^Jx%8-Pj3Htdzyl*$1*(XXr=?oAdofeLLd3kdq0ql>7A$OfbsC6Ag)@mSAM^ z!cKy54wD-w8#j{~AN`zZW{R=2aepl^OO3-y^hF8nU9Y{4k^xa*gU*ks4ap*_tcUv| z-j6Lz(UwdQ>~8!(GhP)U#@c>6IyX{3M6TP zCX@{1Vr{_s^yMkdn|2H&Y(3s5RsWo{&U4^@0TwJ=S&{kOuT|=5q+`zfj9IVL^(5*t zhISZ*sA_3vyfMzyhBPk6If*dtUjhyesO(;BZT~P_+-SkS7h(30me`pDftz2S4ZEc< z2n>EEPW$1`Yb+i<1^o^|;%LyK(~x-1uLpCS5Gg8%hji&sC~e+sX7-;;I^=S$C&m=| zW^aVjd}bkpJSU1x;E_}~t*Qv`8(ZEsnk4LbEyWpg0HmKvrQh-n96mQRL~|!G7=%ob z&m;=csu0K*BNflR7fRS8KR?IrJg$|w7a4;CM@vi0HGqI;?YWJ5jXBJ!uOKYHV-wgj zt!F_ipGzs6uS$Zc3-B;l*sj+lH9xDV)BFRdpFsA<_T;Y+hZG)uWIFu*OD+Kvp-dyg zMh}0Z(6dg5J(;HD%QkOzf2Ibm2eSB)A$Pud4EDN>Gt$Jjzo5l)Sxfc7ZOQl>JL>qf7&NdC8DnDfzJXPV_R3)(&~S%bix<&~8!VA<&o zyv+bD!Rcwk8dlKt$s36Wy~l$*h(I9_mS_g_{gB&RjJyIwf&_!2#4BjxG|?(K`F^t@ zJH@Cq2pQ}9cWArbv-(02yHpcxW0riNiH$ynNp>!cO?jMWdU+XPG0B-`0t`J!;20l| zcAiKMygGvu#NL2&3mgOhJ_k%4n8-)w=H|lQ1`+(!CNqn}OJ$0TO*@5UYjLz=S$Fc) zfTnmmmgC0B1lHa)q1vbXGeY{GQCQ7Gnx;UjLf!t&O{Z7e1T?x(#6PW5Y6j3h9KS!}ge|IR|183QnfdMJ|m$sy}lIug$xi}z%63m4lBkA7sb-3-42A%!6-;zR7x+@tW;fDlt!2&hy~! zIW8XRpqcb&Tt7D-Z%p(R5I1`xQ~zj|RB0#17cJ9&e2vyB52V4|9uJs!hJC0930 z{I1yciLW6nE+}fk3==POsca-x(#IFh3KZR6M|v2)E=@2s8f9M^F!(7j4mGJ+Wi&EL zo6`LFG_>Dlkcjse8kj)$p&v@P5En(f<<|R@RF3`T)qQYYE7N8lIvihS+jvgTT+Z94 zj#~}630a60OvTziai<7uGw{finyIfK#0WzIO0xv+@eGm|q5CoDlbARAjZh$QN~98R zobaW^=?!<@$27yKuDPZFV>-~-J|cgXLb7TCXpqMqrD8iAw69*7nD*R62)bVFog0vW z0bvkdRJ4nE7gTCb<;QHSTOo;QXCtHuiE4o08XO!vPD$%?qFw?Lg!OeB0L~fK0?#W2 z1;q&n*h2VTfo7;S=bY#9uWyIm!eU~eR@(y50Q5A#H3w4IjZ)9#hM^$h#wB_Yk!AyG zJ~{6tkm_tNDh2okWorck(H`LVFa7dCekh_{03iRrxM6pvTs0UB_Zs9jOW}pfY9JzO z9uHz7t_T1CU}1Iz1VF@Q(Fg~B0SCkAYMcMTVW2r*&NEc&zn7lFZ+meo@#VC>@zG*e zzb=2ab_4a(4v9oxmBV)An^cT7)t3Da)hc{%9}#kAGYjEk$wy0KKw`}l2yeP^3+ zkC{JMWpr3$W>^WnyJRfUAA67PmL3b;d3wvLdOx}4nQw7)7KkbZDDq>J6#E4y0kXu= zDVwJHe;EjpoQR5{PHTijup6i{nwpv-*d|>~z~H;&1?cbA-}G2$1|_j3Crf}|PdU^X z^4RMT8aHkwOW95ft>2lLwc$m~r20T$jWyi(iI8<+*~#0Vu~2h!x@o$Yb_m6ockpzr zBl7A_D0bO;5^l{SkvqL7z1NfEtpp(#SD$*6;m*PkP58TnD`0M)Xg1pmL;ogt$%`9J zv<*%3KJ-fo?~C2F(qY@=nk5j2UXJZ2KEuS#Ya;c|#q9NDR|2JW#$G(0frmZ8kR0Z$ z#bN;I-bC}3KH>0;Gr574jL&XyI`V87*A(xTa_RZ8bgwe;-A`}R4i}eKVA_LAJRox^ zra&iVb&hOQzfNxF(~K2rIcn!@J#rx}a^#P)Y~Hu{@^xh~SD4#Xmiqy14|_ZnwztuD zLDf|8lbGn+Tan?9c10E1Z^-2qNNrTfB4}j{G<$t0s3QB_nbWI<94YT?FzQV)W{3`? z@bpWQW#b7IeKnpdhRB^|#Acs_#-;`15*cK0Q{VuPw@`v|B_X~Xdad~4;`6jg=x~dN zaEW29etH74(aa3`#jWl6meP?VD4Lo;sI>lqJu_kUV|*MH8xK7aD?_`2A7*bJSl4|r%n zsn@Jta0&?fvCooD@ThKox!cFyiW~h3hU+}9lVgMZ!Sd!G(yoU>af5t^af5E2&3Z)^ zNyz2aO6|*u+n}S*Tb*!QV~KL$v>I}EQe5d0+2EntSx+y6fRknu9vjg|0WJUdyQHx@ zF?B@A9SKO4eg6QDd$&I<;g_4;!&Rpx_Xrm$HrTfU-Q0X+dB(O6FpByHV;C4)mqvFz z;1k=PCYd0&24H|b7r&F8v59hhecA2VGUDFa*Rf|#W(shR+x`JzdLRO8Tm-DAww={V z7E1U3()A7mo)<2&Sqo8s2VACWt;n?A@Kt(%WEyvFv~<_(z`!%mV^B~RemyQsW+3aO z-t08}<(a?yJCZN{wEI1fKZ8r9dG!#kuXqh03Sl9k&k1IevMJ2F8{NKx;OzkSG9qIg zXqskfug*^c%uv4vGH+#2CR^R7fwW%D24JwEViC}>tJP3iW~$ij*$J%LJ=V=ieQl@6EK2@e*?E_(bTYv;$6bqo-*{|6Kh$25Z^O+bK zHBA?ub$%OaybGcjZSZvJ+c2w0Rk$mbbr^RXzeRGg{OY`yxAmjPj)Jq^oznlAaK2)Py=S8Y$5QaMCam*tr(8<;M*`W6y}I1M zI@$^fFrd5=(63YDv|NVB{}r7)wqK@o_jPGM5}$wu%S~*c#Kcx^eegqQ`rbsW{$iT& zfdqhXRg7{zWBFt&;%{U#u^vUp_lBcal@ss&xDlgWTUSNxCcuk2%>{Cw$t5$kTcbd# z@O?QOlRMH=)FAyKz6IT3W%wBqBC5;%9IQ*Fo}$=;5it5;5{-LsNmb{ha2mLoz5Q7z znh?J@#YE7^*FtRG*wC&pz$T~l%4s<>h$D8BAt5_Xeu_uV@D>$oy8|uj8#*t!c_c=b z0q(`{s9*LMt=^#^U%&<=Xh7Q6Z6vr}qL-W>XHune3;RmszG=ixweCn+gV8?r!0*u< z09N{UNCs)MeXmo@_vASE`-p9#UkZA@Lr!I=VE*D`>Jn0DUD1IRy6>AMkMiO%mwQ}- z<%L~170$Ua{14v)jASaKFgT@GY5rY9J8isp!uCgv11p@vL!M8(Ok6qHMvPiGj0D@C z^|Rc$zrP-dRIGr+lb~x0iiD4Qk_tLMGy6_`W*yg%F(WOD33(8QD7hjR6AE!8>~FUt zjW8E6Tk}K%X~d}TZ0JRx{V%u2$cZ##YiJ%VR$_$@AagObqx3u+kj!>`cSp1I=I6GF ziHV4U5JltvdIMIQ|9SCd1lF_btD`Nfk))=H%D#@f>v{d^`7!Pj09jm5 z;*D|xL;#_|K@f9@jL;TKa*qY=4&!3YXG<(3r7s;V$v-3{sAf%{Rm8i%(!k-x0N0Tx zvS_{_Yl){^CiAb00Mpwa@WCvxc^Js1vJ{x4rw7tlknv~cJU9)qHhqEC#rfqwV?y3F zU`XP7ehNZ`b5S@N$hJ1UjK*#ZzQ=y6FnlYV!e8G$0w|+LfE)mEQUc~1;j+oTe*lVs zkm|ev(+lACnim&C4ghiS0KASZ%NIb>2|&ss=FT&*h&NG-IRGgUrM~hL52Y~&2LGxO zuw?lf@kaqQC5Q{4$Cd$EGJr~_7I&R{W(`(CfINWv{l5EHU@ZVz?TurEH{o`D2cSKN zyna0r$LoPKlOIsMa{bLdW7ND9av;Gu@pej2+`{W;8G z_-eiRzUd$iFY;6ED&g939Je-0I$9?82F#g0O2~EW{!f{~QNs3*j%ENB^Bj71kX06r z1=TCeu&0*C;xGoJVf7wZ(4B|g8Rcc{p2OG$i=s5wbC($M;DIZIQNEQ}k2!Mw)Y3>p zC}szrh8i4=U~j_XW>$C1F8qOIth`bF1Bn7J+_b zld9Z2iR^vHbjP<3%eUY5TGJU;wXg(2bD5Vr#l`C_?;nn{6Mjc$M<*n}ZdwDKosE&c zUr7))>W8;0r8zH);h?ie4;fZWOr^d^9Z`i{U#*G8JTp^((|^_Jyko;1Mk6tH8%PXw z7H3Ctx@i7c7WZOz26W9`N7jloEiJeeR-Z12A(Cdw6UUS4VrebEf1Xpl9c9_DKNO2( zJFfZ=<-=GCffz~z-9<_M`=gem8M!{Kn1U)3lV)1d|J&y8Xm&;tnomJ!DL#i9trPB` z>DlXFYNZtrH)RKmn_SN6g9QkoHrNAAPDGJY=DYX#P~>ZtV*n~9o7{P}&H5+_RDUp`&l+jg2s zVzw?Xlo;Qp`wbr>C!c}a^LlmTo;cLuk)gFu$m#X-;yM1a?#Cr!@dkx#+HC^)!ybPo z%O1cz>5Nj<+g!DXsig75AH$LVuiwJe-=HA&76E+@l24Ra$!CbGiSpS~;<@ zwShDw0t`{qh~7lz8%|}g+4DPwzR1v=hM26XRduW?5HSBzS67E9YQ|DWgRr@_3N!fO zc7wJQd;io&ED{e{O-&8)=Fs~SQT%YO@~Iiil_1=Ov!{Izw|yZ2)^WcOxNc3$uj62_ zFedZ?7{5<5`|hmwuPlSF0FVPXmFwAuJGDE+4?A)x>zpp=F-l*5K=06TU+|ZudYJP| zA7`i*T@-h#Gg|S={vp9mv+ki!jbZTQ$2z@=Dx#XT=Ip|Pqmw`LeJ5rQmx2t@*h`!o z^lO*A_V*890}T+IpMcd8{CP_r9oW|2Eh(z|CBmJ9_FHEU_Vd^CUs;+ZB_xhX&|zBQ zC!4Ot*ma$-uM8Te{psVdQ!TniO0!p zg8FIa(hl$*Wz9mb0lihhhu?NXfAGAJkn?X4aevvCa8BXY?AvFva)ho$C3)>EhIfG? z>p~$88?&cDTbSAm3UG~=LB}KA6p-DBv?N7jxpS(;@PH{JlvSd026;UD7=~HeR$VWK z)2R1&_?k@WF?-ALTuP4h&XOe5n6wcAF%09hvdAL>FcMf$rZiphlRR&AT_ha0MRDAK z17?hV3KUz4N`>SX!aUg#XO||W0k0x)UFMyQc4#8%J*UQNEpgda>xC75&gw4z#W=gz}h!Mu{eCxezUwg z6T_Wx&C`H2LAJZ1noiHeFg|kxz9Ji_cmMXznwd)TagzIwLn)Z%?yd3>37S-h3gZSS zhUzm~9Xy&>8l1+O%UXNhdZ#XVk768YD6jv1Cz4_L$s6%t(eN0Z1QN6rsI}?VVZ3#8 zgk#nl;G1l5o9CmPJ3LMw?*XN$m3re4NBhfMogB$Fz238+{IlHg@AWzN)_)+rHH^R? z_ySm%hhShakQ?WfxTL!zFV=PAx%Cs>j9vzDXzxWpbtLXkH{Qz(B!j)^oDtgR(5p1zeSMK$#Di^? ziRr!GpMl+GABvCDVItLu-tC;*ze$rP?V?ATi~1AEGo#49sUUq(e+mjN(}58B(D1P; zPwjS}`prCgR?G_w8SD`~(zp@kGyKX67A^gL7L<8((#4QB7_>quveHUO5QyE#Nb5#> z7Ai3wQx!_Iz3G6p<3N5fONDwS08K`9b#;%@YUY*4+HRY-d&RrXG@gr?#3jM1v6tt& zZ$+LSMpsnH1^iRhsd%V4KSJ9e`Hmj0;MREA$Oa+{aT}h~ee%Ba-XMBdzP$4ul^o6o zkpwQTt}?@2?Py#&Ji`1(LR-zjE zT(mrk z{7E}S()P?ScZ84;GfrD}ZmTp7BaG5%v(U91F;2Jg@Ee-C*jtU4Dy zCj4ri4>SOyZ$;!Z2m#$Cqt2@S=;-Q-SV!lLMBxW~bN6GVku2Pi@0jvw<~$$faawuQ zFAWV;#04sM3=5#2M(NY7=!@&BSj5D{!1ANJ7ZQOt7d370`p4)mg~Fx;NTowXW7CPh zs)m)4{W!ryf3BkSsVZZZP~`M>MarF4U*%td9w@zk6cPd{Pz6R%Q6#-Th6vE2zeIo8 zYEUhvLOWvl`Sb@Y$rhV!vj6;NX2lE5bzyx=t<#+U>v6Y`@m7^6%1P=@@ajH*ura2i$Z|i9h z&-o1re|W8R0VG>YOQa?$T%-v}B;pFm{bU#>f)yH4_L|B1zca9Z=njYfWUDVxOR|3Q z?R)BFkLfc7Ia)CT`2jCYJA#2{7~|_rJh_kGw=Xe3yqL2Tb-bB1b||2)g4|4&L>Dkh zN1Fg`b<}eMoxcjKYPIt7>rjL;OQAQV180`OpVz%(&~Sgt*@aVA!l57$zE_?XYtpc zo+&&r!VG40OSkd(W3wg{yQWmYph|_fQbUK8Ph}xN?dHx<(jJ-9%a; z(w0P?6{w_v61v^<=gWLgbIP80Ub_i}d*aAxpi0{txxxZZ3r*5FI=2fwsjdcvH!6Hy z&5FSf%c~-y@pwm^j0qstc7^z{kXFc&qN1{c^$JI&nWC)BUthm+&-Ip(x3l!?nf2%b zuF(=`BSPUqwT-11aP@td*0bXxWCx;c zB4=AGG-4}O3#@w;q@@wJVK(Z99k5E?7gX;CUJtV#mQJl$-BW04#ulyJrb^Q(FFo;o z&C6UZ#(n&AZ@fje`yn|bOvWSnwau7Sq&Ag=q~FN7*eipK*@8b>CySVumQtP=jGazh z=(2Y8y4AJkSkq5WFF#s-imAMKxbE(ZxpEi^P_mRir6U^!%S0SQ+k3r zME}#v5z5QdI}Pj`EDq2Ez`|vEwz{&nzT2MIYK;(-qydLZdr!}>70)uwvuzSfY#x>5 z-HzFdX`T%u!^dM+a*nC-6K8mxWHBEIk;6^M?l)M9gY`IhHM_MU-wCp&ghseie-vU? z5Z9unf~tQ*f}rFGPi^5;8H$OTP1GffR(oltg+!mp} zzZV$=_Ir$it%nJTBRT4H`%Qh^#XWugehZxe?b`*5KIEtaD-RK#s9IS?a6|kRamO721>v*Pg7K!GuHBzLnBTkdHxs+S=OuiGF=}8QlsRw@KJ1OQj0PFwMu26yc!-Lpl*uMZu+uCYaE4?p%7T>anC^FB2}dsmQH4HM$U8>9ws)c)oh|%5xBm0`A2e5VgKoOE=lZIsT7IqKYZk zq|&0t8WcxaaMr!-j7diDuc`{k65syDc&?l2RVvE1T4hd~MY+)|B2oI?K_`y>>`CRt5&5aik@&}3!bx7V0@(&H! zYaa;jt!hTZ*O9_syNr;6#H}AxmQ$=(E9PD_c81b0cM%yzf_5*mnX5R5rB z)H7?>JtDqc89K<#Fj9|zsP<7G-I2h}h6Xk4HL7ezSVvGvxEV%wkEgYHZ5TIZ z>@ap-)747dXpH9b#6-1EMIqeino7oIW`Kux{b3D*!9Y|Zc%;)R@ug|h@YCXGcPUaP z-U+vHh^nzj*UG?Qwn{#Z;sY+Pf0I98$NBCCX29R|6Py{|N?eKdH|Q3Rl0ie#%9~Gw zl>4S%VkBSMV-}Qc_D~JE{Z4(F7Rrn6-EpCau^7s)qQL#`P}n(dso-PXBXyw1UhxlXH~{!;^RwKGB+gOp1YEs9!L+MbdV-+?i%(n(_N7`tNkcv(_)lDP@~+@I|DjkEEmoQQWZH zP)47|xv2AFO_3z3vyUItM6`TYpgZ_XIWkL>pv?$k5r6&ti)n3u9w7j?FA4WOR`NTO zv28M-!L#5G!$ThYg$FD<!{oA%C_$4vmVJ5;Pz0AeM1t@L> zQj7rGG+?SpFDW5$-`ulhhQng}7m8KSQnyNDeR)K9vVp0Ih<&;n4Zg#;`F9`NCWHE< zMdMoM0IJ_2cRKuU*Bb4t`(?)EN{h0)YBIN@{w#o=ybt#b@|QjlBp~Y1&hBM> z7LfbxN;~gNOw&Rs!y1UR-$;};UN)EmydKT^&YG%cli#OyD^Slke2k55_m6E%s=5w- zsrF~+pZxoWi;Hjsg7Hbo{7x*tx(G$5yZF#aYieFtD-pi*!^@p9;X3DdW$)Z8sHs`V z`IS-!?a#PWhNzwWmEi`nM%BLtA>1Jh<4I*6mTW%c5ql2-mK+;<BUiK+6K6OWrS6iXbKWdJ0-N_C}aA(9?-8nH}**I zy&<#)C!>975b{L4~A5Xn|A!SHtuhI3N3xKFWd7w$4 z=#D~B^=5X3HHhT*4fy`zMz>!wJJmq)=qEh`uCJfixjeg$udcZVa(vIG+5OrWkr}4rs0@QzM5s-be-&?vCEbDU2-3s2n1< z?1(W(g&LjbU4EbM9kwrr&EH#7L@JVI^z%GnVhewZ7wWrPt)E-s=&{}!-u*-g&Nr=2 zXe}#LQISa+hF4HRkE{%dXk-Hvr_63R2>A$acop+)!6Cvy;+1op-icNUR`R0C_D1dH z4&0)_=t=P78TfInZo#G*N5hhli&RPXOFJ#%$MBw`m(^MS!_!wrMb(CDlY^vmi2@Q* zQUU_fB_%1H64DYwcS@(UbazU3BaKK%4Lu++zyJdbaklUI&bQWH{$!0X`+4sBN-GUC zjs6lFmcFNpS7lsEbpLNxRgG_5tZ&`u4->S6mM8Ne-rcui;u8QxjzVY z6pg411Vi3+A0cM#puekFq`1S3lfaDqJ*|X+8>TFD*WO*fhS}9JHf9v_%MZV$l!)a| zJ31OngEM;|9Z5N3p6hFC4#~8!4s3s4Kc1cj0<5T`w{I!S-|eDaO|r{10ly zttRL{Q4@k1(Ycu>Rgpz^d&h({k;)jSofNBd7acKf?XP;4^WOV}{Epzubx%2y8P=S> zj^=#`25&V*A*7uXPY~@<2#)b!{cN)r$rHBKLoRKDX7!$p@K?kRV!7Ku76OU@863z^ zd%~0Vk7WV+CvYRhxrW;D*AL^fn@QMD&Ci=x26B$pz7(7S9JpD%HMUcv8)j>fLk9h( zQq8N;1{%FoX~mZ-i;&k5PPG@*PYF6!~>I*;%v-7nMvWtY4Ksd-dea zFkKbCxq{vC%8A}H8O*9KIVnZ1P-}w_8l{WjA}8M*snG>4?o+$XcBbX_U&_>xLvaw3 zPRNGUuLsk&$>+hfu*eO&myb*ELX0H9s;ySP)dY;ki_rEO1T*$<(X~>9m$yLsiomdG zlm7D`n%!vy_tj3o4I8L|t~x1&wJ#q6rFB zGca_IuEeY!KBaZK=NVePs#8NN0~fW2E4Rn)2)`uC$;mkdHlWz`Aecj^zn$lKdSCE> zR4)&~Fjcyfsc#y1gdQXKS2#_DaV?ge5%P%;--phN;hUI2F&Ngf|Rs?DxjoFEuZDnZP?VG}bu&D8~QDEBVC{MvAz zemIKa1ns3-q1%1hX8o+fYfouq&R;Jz2(s=iC8p5JOcEi2H4WCS_T##(2+p1kVmzaQ zIiF_ND15i?jX?zypeLuu2DsOf4~Wn zQ7lpj{(*mbc9p~YD=o9sl#~ftti7co;KL=_No+YjD)IMn% zq7nH4>J<9CJ`2|b?Cm{etag0luZok)v>CskKMZ_LqY8X7&N8LKO zyNTogmhQJ~h?z{eipnqX<~X|9N`KB8`>?L4DGTeUitgR^ZZtPHX39V&J^o<=)HcMI zgjVXR^9=Sh#lJy6+wL=BBGDha>!qtA_Zx>HS+MYDM?IHu3qD^`0!Eg>Mxjy0?~*_9 z+!^++NQ0|yn`}q+uV5#Kr~r}y&+>)cSQ!*2{(GGlw|rRFpAN~kBM;fu=bEtuwHz3q zWmL!k%*4Fy<(~U5&LQ90#R12j`>&lJ$V;cYw0Q!)4C36ScOGBWl?u{Mt|YHY7dIWO z3qoN}wcZl-<39EEoo@=pTpt#-SXm!WYkK9w&0N@lbH9{ZzYxg7Hr;dL>=+}b_4@SU zf~<1BfoWI#q>I3rHxN9f15wh{g_=&bKmT-{MY!Rhyv3iQz6G6rmE7t+v23M<(>{+i zRo~-ao|yQ&f8kL)Ea6qa9-!m;$63@Haz2f_ae%8KU>DsV=v81{#*Pf@zl;`b>^;IP zMz#_P{DiZ=Vx$>C&xmD_&5C=6Rwu|mHxwEV7&ALU08ep!9Ra-d32l(c^ZnG*{~+z_ z3}<`Q@uj}|jO2GCpM}3k(k-u7q9l-E0;z4FLZUJ4p-B{$YIS~mZMRsJUEAG82a^m1-#ECR&1XbC&ZG3UtbAkvM$i}VZM z`ABb@D)-E?4x!pV9Q)`1TZ1+Cci?@cv8P0501EKxI&5a_nf?UL+ zim9K`=w-pLd2Mgj_o=tVP!u~l$SBx`;DC=eZA*+K9eQpM4IXQ1rIu8$-8X!t6UP`} z>hW?mvuerL1nb(SCrgQDj^V16q_~-lyhIC0zfAjbh=!>qTWaE)$=MCuiX&~Df@a+Y zr`5zyY=5ef!txFi+KbTc?76rR7~TNlgBV32Kxt-wHHQ)~aM2ZcjXU=!@dWtzL^p6a zySb4)K>~$<_Z(3-VDs;2Ju3rZ-HX59``7E{*(~@MnIL`VU*vvVw@=P5y{^!ipm1<> z{rfGaS^U+kdKJln?}XX_WVGFomFy0z2Ow_tZ0kvm65aXv?&oz^)>r< zM2mT-blZRM20NWdWo=Y@wwZ2sN-DiO_XAco>+x3oY6AcGEkmO)Wd2xD$6ZAMOaFE3 zh`^-g+B&>63nC`#qowtX%njT5*NBh=oZwFmSGCNkzM=dLMIdM#Flnmo4^k=oha-!# zt7r|*NvZB&Uq(I7ro5}wavIKXfb`d(Irgh z97?^#A@U^hIa0tR0RS!KhY2E5e%|Hbx;fBik`Ip6S-#=`9UI3(Ih=>$l>2s7n6K!D zc_eZ`Clb*^5-h0*V)Ys&RV9A(f%&SJ)C{=%k+36+x&LENemgTOatWv~eDAJ_Li$ip z(9}!4MSpAbqspiLgM*LGx_(1Q9r6}=Kr7uLJlxP;`L=+fhF08C{-bRM?p&;0vF%kv zE^T}tGs$VgMW|mbmN98JjsN%OC!;|&)ae`{7;1d@w=wxoO=p?ky1u#em}KbSt!>eo z0L}p5vCafqA-4Yh1?lL3Y%;?eTtCG+(`fS(e!x$4lK(`P<&#R$pC$X5o!bhajJ~3E zC2#xB3~2rtdC6s}JeTx9t{?Eu?8+yQ2lBU&MTyihvUAY@i!e4Qh)Y^tro#d+7|Hus zQ+?HdAI!63gY&0izJUYIC{~R=oM&?!y0~Ge=q()AUL(!k*k04qmXvchgGBmV7<2^X zP}v?xDBiZ$KpX=0q!F*1-|s(ky_dbOkGj4Vo4ae#ZRL~ zqTyKL8E^pq;JyGLM{0H?`EO|moWWocGg?T0+-gZW7U8lF;p}xG+g?Wm*~Q0SVn9Vo zh`&zmsoU<0dwZ2rbIq6IIHa z#{UsC%%WRKhw-#}Yb#anRld=i4v)XpfG$=Y_8I}#&RgOvA1c=vq<7t(4K;Gsr}n95 zd3lwFQfplMuKQXjX%4}vg)B>h%V97 z|K7mTjgPW-K3XT8+IJoT16&7X&*R_) z>Uo#QA=fC|CgEi&|JsbTj@~wyo8g7Gd?TJ-$tbccmdDuTcv5{71UH_lL?Mu*BnyM9q=W4aYprvhiDWi6Gxm;-k1ed zRrIPJ6+bX1{}(L_!!OpB0i^nL3$H(K+M>1c4%V6TW~f$gBKfw zTvWP&l6YbBT>?>^aP4W;$kXA^qt8(FKKan()oa~K*?+$AI1XVK#+=(;VQ zH*%iSoit3CWU@g&ErL15<1(MNpIP?<*OgJgfe*sE)WXIV{2r`9Qz{m&pELE1_^5{h z5H8?KP+0;C8$Eg)&sShZ=NL!H>iNZ zl3Hw2QN7k!uOCtg$3GC*UIaRAwmPjk;@<-y`(@g%$Y+;3e3ME;qt`XC{lK(^Eifzy2E$Q zT^d5PrqwVe$Jcebp&M_Ot>TJVmpqShdl*rt!KXhlwr-cP$f!b$Iq1@qoLJE}6{ckk zIb$mPW^RE4q*?4Oa__0#z2Qf#@l=k|v6t(8zZLKeR1&MTS$r_daL$m2}wYF*_x+2bAXM=f7>00?WBF^pw5 zF(gEQI`)g&A@vxWwRP(iM9x1G-c0L3L-3_bb&AdjhX=Ni71V??%s0~xG6g=0IlEHhY^}lhiw(m-FjWMy%f}9?X@{pgC-D})N<)l(PCvH_H}pz+%0x|f>Jv)tk&?hK zqA0KP>LkX4WSZ^`rlpdYQg_aOi~0|R9hH9=v^JN3h)XDY<>Cx zYl({P#8}Y(s1rb_a^+q|s^iE)^6PCk;Wmug6Z zNH@$(V+{KS08mpL_2QZ*-)8z)(b@I#9>f&^Plc1-w4Lde7NL57RVlaba0D*3qt5!* z1dsnaiN+-Cx!v;A`NXwzVOi~rN&CB>;}Eib!?$tKdG_#=AT{vNJFb9$`Xq0f z=!J-1`i1H^ER9S- zCZ{fF)Q>IhoW?97%KvChmh~XJ;sGu@rYcgsbw4I&*iI>QjZ-WUG+e#jK@FvwQP;# zu}$f!rJh-n33A1~-v+HN5#C)+Tr3RKOFtS_y}nfOmsK$Ny1b_mJXL)6?aCDSbbm58 zZ+xP%JM3;PnLOnx1Y$0ny>)QFYLW6-ubj zR7V~RmY;g7IDaUwaBZfG`-j;X#Tfg;^r69puTOPS&VuYPC1C6WzJx%c%jsuDZ=Cfs zODe^W?vD>IyvK8KVY2Ey_2%Ngl9Aa(5oy0(F`nQq zpSvA$%xdE#S$sbhQY|J0ltus~*g;(?&Q_F6@0A%L>pknO(B*A21qfiO=24`$R;207 zwrCjXM5kpYMxyK*zC+A>XM_fKFsdC_7PQW94&ZC%1@OG-2bR3cv?Ilr&lFI5Dw8Nu zsKvF;RIZKB5;Zs3C+F$=>KB{KZ;jn8ba+%1(1Ce_UN4yEYXOVEUA?1Uc8B{KCrw4G z*OQLqi8JTx&`;~y34iXoA*Jz+2}TO$>C53m-Jv`nAik1u6bRk~f;nhk-oSMN7l4_K z6gXqV%7dp68qGbJqbAWq0W!niOvrUoy$;}HBl!f?yUqql;HX-zqC57w*CEk7U;9i6 zLBrAi4>#@P*-}2&ZIY(iEu3Yc46xJ#6z?HCF9EGXYE5^&b9yujrj^6z2Lx#JTa7}nPuhzDfWc4a$kQ0dT>S*y-VDD|D6mC8-=;} z>BA3#zzv#$Md`$n!-pv!391O!=?IkjoG3(EpmQ9@^eim_4<&&*K{(|Fa=*#JlG1#% zSSE*&FxfDlw4y|^nv{AwPZxFI`Hwkn{l0P`-A0V6p6Pa*I+VP>)RjYM(Fde*tcI%0 zlAk_|4FdnU;pyqTJV^0Tq1A|`D4psiW5_3ROgx;*gf`GG*&-2|&^Ijhm?yS)=~4q2 z)CT$L{2w(3nn2F03?gzgcfyOF4DY_oR`imf=wwOn3N4Mq%R4&K-}=?@VfJ)`a+Q4_ zFK<>!W@5a~zmpzJq3ZV-O472=Qo)hW3HshMsQR`9ZO*8^IE72(3>35K>Vc%zaZnFe zg>3?xV;6)fL33P_6%GonJ1k+toG^C zYrlF4?bNagwzA{~4%{gcOx_6PqGq*@OGO@JiGrpzpp2FY%wI4!epN&7%)!h80E%8KOBP>hCmCE8*%dlG-(GIDI z4Uc1u*~H`Q5}W<-wKWx*gjg+EnY&r)EJg)7j+R86nri)`*spU0Uu&WCQ-ZzA#_;LJ zmAe~Z5SzZ;r%$FRaUo3YqCzF6)jET?efmuuPjGJ1(;cMBdG<8#q^xRmGwCPWSEln?OS=jXf9tz5W&xcPhZbyb$GDHCTyiGoHcNu(k*>T{;2x!gy<+=7puru` z01rr`NdOhrThiuUucO}%{w#GJ;fQ7!tP(hD)&wonT-S;dPF|o7>6QJ;OD49|6H{X2 z9u8&Hgwp&|BOC^rOU#3Fv}QkbN2z!QFtx7)H1}BNLVqL<+z3$+lMLK+x&#bU0t?FK zKcV2~#y>VAm(P=r9WgTV1& z0sC{%7Z3$L;aEG82#xH&?RllHQir^}7LYdYytGXDhL%JAUIW%?Svz@h_F`pQ^kKc( z7zT(>-lAV-DLP@9OmW-bL$0rp_hQW3Jhzrq3;5=EF$;vNX}?s2CE5FgOkXR{^)?q} z@`EaOiGgP?VjHQ)%PIsNU1mf5c4&w9p5daPA=J&te4bBD%9E^=M@+q6pHIJVR$?+R z)0uBrY7w_}UQ|uIH=}9pI4eXQ=Yx@XlVQIte)UH+UCk2bsv0B}=|xAf-|vbMZd5Vq zpr@Fw1$3*#B$bK6$02FenmZ_bG3LW0%58&5rPh?;!NJD-+#U$0#tzsoB~@0k6GF6|fgz zA(!6k2UTp3nbVugJE*$2R(QJaRNLCWma|!#=fy}i8Jf-VrR!*^QG2AYp1}cg(pbZ4 zCEt3r@@3a{xrGBoqz!j34($>e35S{>>Q{_R%W8B7`YbdL&?=Q6rAQsAhf4%K0uGmF zrey4%eo>vFm%0g<4aD!@chvS60fOQE!t$~iM~;}@Dhhwjs-3Hd-!-R2q_371sU}%C za!nX*i>RPQH(r{DQ5+**`;0%bjO~Nj3J#DTc}6Kog3DaHUBx4NODkxLJbT*Ouy?$C z{r3HnEvb%_GjYr9IhZ_95W7iVDCq z!JVz5-sH|Q*;sq_W{ZDwl}v(%wn@CCt;|J%qmrT%Y5?;lHHBsXo*uBAe! z@8zY68BsEO%AbN$ErTpdFTd3oi8yLtKF{>qgL>jreLAEOU3w0E6shqkA!!f;swKncHaB)Bn<_YY4$mHnfCd&u2c z4LamVE%D+i@n@$aFY(IYwB5_q)a$n!Jq`2fLSI8g9N66Hj(to}^iO|8-cA z^;U?$eWkhRB;Rj%C0_?|y`6V!!3(7G;@t-aH$KU;MjDPl=lJj|wB0_aDQ=ce-ifD@ zdaGt6*Ke^-38>DI7H$%5ZxR;z(^}?8J3$alw%G)WN%Z=5*5cCy z$trHpe;>U$+ByWWKBb0Dg;jv+`!kIJ@fUEZ8jxLB49GPoD9s?MnaVk zp)e-%YiUy5Q@nm5fc;x0v&b}GeL;)KMhPe5*^1&7FXWPdlcu;nl4F?C{9f4;%vHiB z>FL2pZl%QfY%NyIFZN+hjrwAyEddP)#M80-0Ctssgkp#!OD$*U5+%%e3j)Y4zYcto zZx*5OC$)67r_D0w_|+~SRqueo!5U`cSGs7;w=7s9NU7}34!k+-Xispw*kZ>iaevku z$(nm)dE|z}gdj&6IPUe6v`d$5i(-q;5}u1ZBsN`@Cbl97!uq-ABqPkyM@X8<(vQzS zrBUXOsri=)>^dyc(H7wOTK14?d90kx@20F zVZP}RYfDF|b?g1Gnne7GO6C8w0E*o;>{Z%e%DEpU(YVZW0#fS%9uA*xJP3wK1sCNt zqxp`TTl7pGKQ~Er8TRwVs#g6Vr&*%gYsvoX+aA}%Ur-e4OaPMjRngM?oO=@UH_l1$ zaUPUII|=IbV(d5YkAAx#6zvSipafkpey(#qvu9E@_J01Fa=XYls#@)wD5X4J;U?X;)J|@Y;?K$1 zWkfA&HJPQ}!;JfV{huXkR$$G{pOF}ADh1ah4@l*`Rg-!F^=fYycx-5+l*gw_^ z_*0b$@Mb6nzm`RSX;}mIy=NQWE7;3y3_(gEuxAwdc0f=@_Rp1(nDQ^a&MN}VLzm5d z%qlD|4NSi~D4Z!(Ot`VM(fcj}yhxtIca$BDs>Y3~*ODip0nR4Q;XGH$dj9*Fp{;ry zPZuBHXRM8qW8mS$2#iSi;7LiO2>GX~A4NURpk-^m_88ifDv> zi+@WO(~o0JXo#F{*MEX+P{C!Tg3wXgBLLvO@$$YaeuV(xMo;4Y)2#R^(fq|$-3Q@i zgYySjg(|hQy4u6xHQU142P(rgO)EaRv}1zDpW|Nmyx95eHZJsB_{1m*d2*)7oz~EH z@NP$hD^2O2OXK9^3j=oxJIPfS>#8bdEG?Vp`|UQLTtGrWeq32|xDoShdoxRiqHzIb zdjip{oG!DhOW6@>OKuI=_|~gUF%~LHC@sp|$S&%g9)h;(LbUFDs3 z%`wD}z1OT85DEuGV1MlQVm~qWzNZmsnURxvDT#xBLj7bh_0fvTc0qd5*@*DK-+uZ8SP7HWyNtP5G`CSK41WSC zrU3H`jLG5<|K9L3lrE9*Buuer`WG^hL7J`eZ;DR06ZAQExaCnMJmY#AQNm=hy^tlLz-9n*L-j8?7+z88{!-gKqRLgh=AzDgHI+I%STn=_P9 zr~&MY3Bf|i5;CZty}y=e$m8J%YivY}h6$F*2=F%P(KTEdZ0m--NKq0kwz^e%l6S4^ zj#>9Jbv@1At{PBwJ^9<~pm<{rjggjYzxF?oS`=qU5LL#&jD6MqRi<@yZ4Hxn3>e=- z%c|gw_jQG0mZ#N>Lx~2UEOkj5y&RV{r7qIR;&hpg>7U> zxoI_ySES4s^03W>6&COrg_QEm@uN_C*Dh+Vmq80b>ALxFdT{|}zorGiur>%-8Pkt=%COEOmC42)foO*N@v9uUw?+5VLmhkRk>6_K-wX^bRy zkPPELQ%FfZ<}}Zs?^3S%LuZUQ7kZ=iSmTG{&KWdpRWu>mR~Uw;-u6B@@me!)h6Qrg zG!Y$@i=tYve5>N`KU!WVF6;Zy?@nXClm(W$ki=64jLQG4An^`kNngl$$_1M*tBP_? z>*u5-sa|5Tmb0ATL--@CzeLxM+Z?{oscJ2zyQQD^dK>ZQ*iWTsq<-v~Fa__v$0wcm zGU<`$->zhMXZhpeb7>}O>J|P}JOvO4V1NA2{{=m&QC>198{VWI8hPxW_zPy3;yq#m zQm1(U^ckpWMxT`!CPb;yW(PWA0E8jjzdkuZ3Q=sw{f5&|!7)*iGLF&BlokCKM&x0eD#BsR#04ilgTibEEJ#Dp!VX!X z!-_S*`8b%uyp;pvWDjD-WXD^QF%87fvB&&O7CKi)IKvTQCaTLw=(I6S?bn4)iQb~y zt3BTieFrs_MRoSUeK=!CfacJ}lU=-Kb%g$ZVnsZ)>T=~L7|;m}`l|z=asp${4%D|= zDvem4SalQ~1rxo6hI5<7`Z;Q|6Au{9#iZFT0Y*O_5H|vOFsCq}G(lSyIM8bwQ#}mh9eFets+yX~eREf?zqK%xpa(SYnx+0G zP)(xuHX zZTpB(SEGS(5`TP`*efSIXOnb-euY=8R*)wpxcx^!L%{xH(eHx58`eC(Z1Zj*_b-Pz zjub^|J`N3&HQV{l&(dmFLB${UC7-kFc8quv4B8Ee&3NV^Rk!O|aDXZO!%H?K<%piFy8f520HVZF`sk;K)9?f!eP`?3AokRPD+)m8hC z0h?KlF|d)5_r3sO47?X*6@N1zu2b95kRD94j)D$|-;P$5>G8uC+9|IuMgjaPwh@wu zcQqhFgg+MHg61tyZ;kWQx;|IY&g|&Dt4Xi7nCM&9TXI2CSk$+-#%517Y5ty_@er;h zr>h>*mkkm8SzjSWG1Ks0aUN6vYIXDw;ABETHaE+MA64+Ah-WB#ztJLm)>Dw|Oa#MT zCx`ZpyLH!zw!SC(J7L1z+SM$3Uh8cTz((O*k|keYzo@PyC`y;I)fD`3Mg4B7C+0rb=(R>W{I=Ya3%t%Ms4c0w zn4ILM(nT<+>guzm#47#Ebk##l?np;-^)DcrCnB}ZSLk4gGQ~6gC*kb`btLaO(`BO7 z|8D$639ou3f{CT7)t_5I17oAM zr1|2T%L~*@-h2E5z5tt)m6pEC6#d*qhFOR=>tBJq$1bO;m)$;(Kg;s%o+IL;eRRaZ zX3_~p5=F!f@_lZRA6;0g^YsflYuHShA5bD%PuAbCg&1gQ(do&5c#n$y($pV${1*7K z#=`%y1srrfoy0YADL*0PPp;G4iw;d3ZM)j_ z-066Y&K^>{2LcKd(D7L{ioH*iS%WvNJ8&R5s|0nniu=_rhJXqFSMvaXmxOw8`g>{x zDCVq;Br_Z%!D;(vWEud)734%9TFO(0AKIvUM(QRYlTEOB^1!8S@<^NH{o+bV#q)pE}^5OPygJ4rw8)UNlNqC?h5tnj4R3nGf=086m$z?ONG zg10`RstJ(AU;oR9$X5AxAOc;!VZ{5EdRsuFEX(-0sm7DZ``=LCwDa57WMZXT1~gcI z=w-^j`AH$Q6~m%5ogrJTXk?REd?tg6y$;h}_UMBO;0qcLpM#|K<7A95&j(ScZzHaS z39Vv5{leEgqyeMh(K%Q9wK}`H0;}}R31DrY#N&Pu4_sT)mw1Yvg+;-DkP$d|4qT~+ zNtpaxb8}5~DnYTf!Mu3A%+hO?)dQdc;K*^GLZr-3RE}3QP5*X2G|r{&e$|O<(a}_z zQrkjaw}8s+ls{69ZtftlqQ4}NF>QV9;Ab~buIBdOhl$!=dO)aU7{z93uQ}#HlE--} z=*&Yr>F z-#H!3!;RdW@$6nFYu8Ok@z(x;#vz-9S9qbqfb&&KUK~q-UK;zp+QgY)*qb*;55z2* zpBpg(j@B9JB{b!yT6xgd9$WCY6Kh$;>>Ycog=xBQodIsVae4C%cpNF z*GB-vIVZ<72FTQt*_rE(Dp+do{qLL@?uat@8!2yL8dHwTD&-xZEqJz{Bsu4&sm5(9r(Y64_=$IyN3mgEY_NwLB$`1mcR?Q-3k9Br0$?f8{Zip8axjIo2!-Pjg4^NmpDgkCDzT!JjS*$gle2mk5t? zGqWKqrZ?Tm>97jImbFKtD>sT#W}YsLk%?!}ObX-ZnzbxTDxjwTF!M=~l>m-}-O$#Q zG2kOP2L$va(z&qcs`gnsEW6zDAblh9*W3HHr{=!1k}r4@uf3`{c{u7mc75#j2Nj$> zF(DhLYMkwc#;St1J^h>Wu9fN>eKp0+6)j$FrT7*&Y$JWdYkP3Ekj-2Rtqa#MKI^Ynx8zusRm6U>lV2F(F8< zpKidr_ooGfHP0S&eP0`ITMhSrU%Z~GRX^x)&n>kFxN73U?eu{*Hbp|S09%OnjOZ1B z5X&X>scDhDc=4i6zdGj<*$${s{2gd2J;i^oWRR{z551&(eTE1;&KOuB6<)c59NTzS zxZIHrd9H3>7_hH+Z0d$RC`q#Iwf?|oU6)tbrIgktHAo?=uaEt5+A95fq{14S#g)$z zsx#7}Qfo_1S&ew#Iu%j#GN%STrHtWxLO;5qW>!X2^QS^pCMX8HQ++Nn4&EW6dc9&d zfrw!kf3sf|NJJG#Izz?LBEMoqr$AgM(9mK{=ETLbO28V#>a(K%>=t7VE`Kk^`W?)h zVb8LwprAnTN@zUU>$&**QteSeAaD_Hf_O30yceHQUjq~v6!?i41>J*u^^e;Rc$egp zx&{n(CDj7Bo2q9jWB%KBf>=@g->!x|Q-n9>FJf*U&O(A7X$a-PrKGE_ILM0~Z18aB za)s8yyW(K8oJr^gTqu2^yXgKIRuHyY)Yn#4vE!EIaeFX+;g9T{GD zUUL8O@$s;j{Je_f44@_4b)l*_Pk3Hu$O+g0pw&_Ie|Pm$E!D!_K@&<2hHqz@U|Z*Z z>(^usasN<>3(FfdDgAu!u9L)=&x^`5o*3--z3W58l#yWb*2hK8Qsn&MWxq$urD;oI zb&H+IFT^(QZ7C?S14&;z3g9`dk1(VBhpw5X?+QY|DHR-heew9mXYN?Qo!P+2d^GZ# zyh8I)ZN-Vv+Wo`y?@Gt{vm0Og4_Pi!X!qz;bWc9JB(NAXQyJ?wF!H`a3z9fmdY6-1 zuggL6J$WI6bMLgzt@y*2H=eSZujr@VKh$i?a-mitjsJ$g^}mzvmwp!hK3MfGmq&a@ z!0+_zJsD@0)!{P;{TqL=T$A)O*yuhOzU$p_uGftrS}x_vDs&4s%hgz!Zl4zWdaDH2 z;cAPk@ui^J#gWI~EtcC5|M^DKkS%QI@(OXnDk%bAugapR8hR$+Z!IT za@5;F5EtI%a)tQSZ08h4WG3eaemL5ro!&dZsjB3!C~0uHWYh|fHycK7#T1hBf2>ZB zV@+cDgI1GmqQ)OpA)%L67L!s16E(43zri4pmqA;zP9LR9b$(^gJ&Qk9G1&g(B;MRW zZe-kUwhEHc<}I(Wp(noFD>RAC3Jm;+-Le-DIpg9 zUtCq2SEmKuQK&uO$51-^(-uY>9hvonA6F)eGM{3z8zL!TeqGr%s7!kAaoUkfyZ*b} zC?lsruKqafz7lCk)~+1OPP<;~R6Ac4B*ha|t6u*tKM;q|P6AuS1n1X>djISeWu2av z@i_-hg23I}?<6Rb#K_&d09O4)DiW7yLFGBJ7taGy_%1%xM}S zJSx1r6$_tqO7T6R(1{LCh~!V^TXCkLSRMj^2p+k-Z1U;mySlG%Guxl-ytL$z?m5jA z40|KN9TLM&naTfknQoS5!kW^_nt7HR8z1$aME%Hr@55nhQyqM zFu)B{?7LoIHkg~WFA1YFCFfPS=M&UyD7RMFSNMm|OOz{5#m0{gn^H=xtanx5G`D9& z%+qft+=V|QGpNn8lEu=9gL$3|U%d+cLtp=+kall&#D+4&0#6-jkKOH$3-Z)8l+(!g zy%5USmp0Dyf?ViaI84EA^dkdtV6p_p*9dGG4k>&4_;*fma@H*Qbm{$+y=+7?+w@D5 z{JLW;HPTN2Np6_Pw8w(aRNJ>%9mTdB#PsyE!Teu(Yd6lGyXBjQ<*~b&DXnst2}J0K zX2eT@>5;y$s1~9_69|7SdMU}nfC~P2Z57jJ+td%l0oUnrxQo5lPqS*w_$FDJbNO&6 z#l+b2Di`wo`xe*m((GB9xSZ;9s}b%$cRr_7eu0+3lb_!JsFz2;;0{BEBb#sG3qXK0 z4Iq@Rm_85fnT*)LFaR`|Xg^hXG(ON9a_*c%Z-xnlBa}F#y{A5H#ic((M&TT^Q<<|w zZOMw-4EXhTUnA8%#fuYIXFb~V7Mpa+VWxK{kv4h0G(Ehzp#oOiw+}Z^+8wX%H)$%D zNW9eDX8zn}g}s$#fV+cGGCWYeW7+;oV1B#%x5J;pp9hrS+w~mwecPelXGQlfUdzFi z=!xAS^;<>V0JECY{+IxWI~%&c!1uN+5bB)&3fc1XE#7qji!jxxe_{;JXC?KSc)!tg zbm{xzn@Y`UE{LoEHCYd|$77J)kC?22Cucmi) zbb#xX=lFni4<^^VGCh|yXRIIke0Vmwuvn-?)ASDu#{w<~oXJ)b9WPaKs=j;}X8O(X zb^36_BD;1zG1 zF*`*i)_UU$ZT;>-+GQMYO-grqSO(&xFOdcC|!@i|4f1bEd*6O(#O^K-A>ET0J$uNFVuL+Qnq+6&FNSQSK_Dy zCVN;Ad1DGJyF>s!gpA-}7h{#RdhiCS&$L;k$v z=TLPF8KNS>(dGWE&ri9hjq9DkBY8!Jd84yd#M%x16O@WeUIyEDcutD@Nwrk5aw`2| z3dAEcUjF{W_xGYFX-qiEfj0Q4s6RCW-;cURE!_&b)VNy=gOyTSkS#`mgn7w0Q3_wFpeG)H}@`IfD zFXp&Ae$r4Z{UH&i_g}KwHqeQ94HTH4USIDo#NPOx5SNQ-zW$*3w)w6#LO*YY2f6h} z4CFET)jUQhb&}_dA{HxYO^pA`yFm+hEd+u5@c^`)o_WTcc^>&P1s&-li8NOQi73?c>Yo_Q4hoVqia#s*&j#9!LEY^L4cZVF0rjgZ?kZe+r zKe|eCd{j-kCrB;@{4Sp%R%TV0NuXTg4TCOiG63<)m}@>6@Te4b z_Dh5y8>WUV^1IRq3q(}mIic=yxz|VECoT+?9aLZtJl|LHNkhhvC$Sb_1^|YGQDq|Y zuowZ(!OXnS2Tu`qyk`|ESKmA~&6Kp@8 zNJ*nK5+YsF&4RRmbk~A(vn=r)@15_?IQzq49AG@}dEO@_8VH@CRX_rfD9~KEcfSXR zz5M0%bXNs#fP2^LcPU0Q0?`*VeYRn~^{+D!<3`$RI^;G}+g|_g1-K#Lq>v7mZj@pj z_nfYwXHPE%sVL&j@y2RTGCH#Uwc|0dt;5d8jUtI`-79EXn>~)v2OHbm+He& z%(DrZZ|2G~pmuu3$N%h67Qac~v+MPzN?T%MsTEP%=#HNlZi3BD8Cak)_rZyDm}EB! zM2a=xuU04lrTJ6ew6FXm8NlHK-4m|%f~RPJJyL#hO1n0x%tk*|%>ST1H{Bdtx3#NS z-jtI@UaqJn*SC)sL^z=}4mJ^f#$Z~KIJ6}j1&aPIdnIQ&l5QJG-CQ9wx2}xccm&U-4*A8q;B$Xw70Di~^tg(cp;N*)u!56d z7}0che~!tQgW(oCV6S)knPk8~23JO+3MS!E|5Nx6)oQXx9OMxrj1U73wm;He+ajO# z8+@WpCZZ$$JpmYy!DUh-!#Wl3H>>X4*mwrqCXcmjlU=ZrD8bQPj4~mZ8K#l6LHgxg z^}#{m>vUhrVymMZY3uVI>CTibTR&OuK0UW$yUvM_$-lamcOKz}t|EDZ$; zfW*hLFrloMwqwOP1g-ufkkJuPfaw*B?h^!;H>d#@a?=@gLMaqaSLcH(rh6S1mo z|EmZHodF-%vZ0#>zh1OK{_&rcX>X{=GO3PbR zRT_BJ&m{Y@R01O#0(ktd|5GUNJk1XOOh3;UdzFk<8Z}Avx8G<;;?Gyt%{F!@68MU* zUuieJ4z>E_b-qSNtzfXLPWPqfs1$#ABKGMj1YmKhOKC{9f;#==OO7Kn^b?B7DSRkGQ z&QjW~r{w~r^QB(N+IWB1-+df!4=4t8wgga4Vs>Fp5=L`4jWERorqTo-ZTFR2X9XgG zK8xb1dOfZNvIHYdmIs;uq(+}~z@67F(zul5I6DQ6JNLGa+r1h(@mf}SAafU1)SA4e zEa{zU0TRrmH;hPjaReQ_a7x(sYV^v(3XxRppc%31)79QG@Aai{nzc)aJ2IwpNJgc< z>Yw+4HRLSCSp1mL#-f%1zhq~qSNO{{)F7Aur%HB9h!$v^;$RF$FUDi$OklBc0j7TLLY&A|c> z#E9If=Rd4#xLZb(sN#M2_KFGE36>Kmn5fH=N)B<<{XvdTAtf_2Ui*BY&4eA`RZ zsZ7+vPl#iiWP%nh_Y{T~i;W@K*Vzhsw}?^dGCaqx4Di*N#>a(1Ujg^=Vv)_FfuhXE zx*}kR4Gq|f9HB~}M7hO8M+35b=vWRECis;p4z}qPceK*6@o!rl=%djsjx>wu0*V}g z>kgp5)8)!_-UAoL7iuRXH!^S0s#lktoiQ$Qirpfnc?+jfF)fWx;a4-tlfu6|ZOdEX&9QM`7)@Z_fxjUUQ;c`Z91eJ>&=GVN`l1;KhHfghX-Z&4=1$3L`!1(!4-x3z zUMVk!yT?;kk>_^smre+T+D35m!NVn6I>jAlVD0o@>UY|C31ykmO%S2?iC0xuFO7mSm-ymzA>Buh9tg!cI*2LU3d*|g^8hmDtE(p1-UCY=uC4-WA!3Kp=A3xo=o{G|lKJHQN)m9{ypEivMAc33slI zr2s$5kQBP@>b5^NXy05PZ)66G<@CuRo^>wbBvQdDJc`G{cg-3#k6z-ZM=nWAieYK7 zXe%O$O-gOPyhM)pDdn_BufqO4{w-z=IdgT>YTETF5MG04kI}86#pRGcHGOG&0CO{s zUhF66!~Uw$AnL4?or_OmEbmXz5kJ}=$G%X&b?uBtZq^*8V2|Dnz~pK@?ykZ&f^^I( zkKZ^Gau;GODcmau4x?`h;F=j1nNrFvUVq9~gh+$6o@}P#B zR1Zx1a}o9Uxf9RUG^EOXh#m%i{NH9c@E_Ax!h=gxv>obxiM&?V6*xI)n;f_gubj zy(mcjvxN3J3>4l|-sI0;kO=`72KLK|35EqejSc*T3Dg%GNTO$k5Ji}jdq-K*MAl&1 z-L+$z{G}OimBgij+jmLY!Ku>S{iz0Zgklfg1}KKrL&mkkib_T2uJbrR?{U0O9r<;0 zek&cCyg{!Za_Ld0i863~(~KR0E-XDlBTf*-BY#3q=#~^*Nj-ZdG7Aj|N_hdG4PZj; zpTHWIrR3Vn6Jz%U&ML0+BSo_-5Arq)`Wm-ilvyU`!n-Ynq-~(%p`)Cn<0cNcR~^Mx0pPw*qUMD z-be8APrACA!vN;dH!vou( zi++#E-WuwB#4u^a(bjwP)QnK`-SaQ~-!fnC&BdD$^4TXQ1QX!0ji(DDRiqcvoGut- zh`mP$UHjL|eC$csRs9DjaHzqSbd41k;jAkcq$G^0D+gHkU^e%R(`7GegvsmK^*+Id ze2+=7xJKplhTQbeAMY4&hXL}Hr?#S1C+DJ#ZI}t^&#CYj;DG=Mtc6*F^JAf(7!8;# z@fHY_=2yKMwc_hl4{a;FLVOrpTcs6I9Ahhp~7e@7Unelkl7QMuEYcd6!thy&r@+}=VcS`pfTBhy9xgg_biR|HJzgW@IL{Do8aNL% zTr*5ggd~(IB-=h~f-#2TF`Aj)$bd3kt)CWZ5*}>av(qZXAJjCX zVv=0&vK0~SUQnS{v|Z6B`*@BCKxN|icfiYC8;DJE!?cc%*!n{17ZVa;SR@$oCE zYQHXi^MSe}1p(?V+1Wbg<&B8TncO>p-@N0tmegkvF@gLB9#N#KSdgiLC8I=V-V^@H zlG*&9iLH>%4c(pdhp=X(D!<1ArIKyH5>+@HYz<2yA*2DjYZ}pp)6u=foeG!c2feVX zx}Yi3%PZw{8l}H}Lh%b3V-)?uSDQ9RJ+r}A~gmF`dbzqYuZXM~`q{zgd0XP@PU5eud`sP;NwDiLqHu zYXi)?2b=V2~u41LY@ZS+25mq&R zlPrI;t}>s)rVtEBQ)^B;(=t%iHVyDLLlk3PBC}t%O5WrP6;=^1 z^z;SerwzKR@Oz_-Ah+Ooxva6Ix;)rE`0NgK_Tavg9I@#tPbz7LbBTKCJ77#H69n+F zWHNxcCAy_W43O!EE&1eRb8kBV@aI2xy~Htf9eYszzxxG)Es8Tx)j~^+*MT>~L^P{; z^BL>8g3HiKjG7E1nt?<}@MfI65ydP^M6=!(mI$TQ_o)^tM&VQnS{(aV`QK3IPXdz5 zSOnD=da~|~y>bhTn-)^OUA=g2JampUd=a!V7zwF-XSvC!z(^(im)xGcP^~U^!bL(( zJvB9J;X^cV%UHe)zsfiUHK4;`R3|8^lJ>0bP-E`2I6Q{SK%%*2{-0lTEV?SUtzx8P zNyC%y!Z#pq$hzuiG5;u@3Mz+8Xkt1c&={}7vqsvY?18gh!JJlJ`&EoE{ZPx9Mc*qM%`Ka<^$0^P0o11yRQI<4C ziC94k7FJ*2!~`q`S6rY*AD|HAU)j37d+eGu0Mo#add!?YOP!K^wjudSlZnUQ9Te^INA<1*-qrSZh&k%u4VpkmGG}RwYy%QnFO>7Q3|{?b^ScJfIt{Pt&98Z)|Ue z18*BTM%Az!7DxHYlcc;lotr4PjxCIfX{E`ja&msT{fjeq?&#EN&MqXk$ud6;AR==O zUAC2BZ3@NcbV`25{?s>dkzQ!Wk~;t|Fvu@SF#?(dwzu!s8Pw{oS4 zhEaYLk^bl7-P-M8t@O#ch0%wY$F~;x?Y0tGKl=TsBCf;G``M)K^pev{$&8=yWk)mL zrLrCcL58X2Se|{We)&{r(4KF5SN)LdcouzAWFt~0hHEeZ&auuOzH|J7f5l;+UP{q` zA?1wHFt^q3NRXWv3}$1rh!Iv{vcQCUB9PybBa?coH&d$drNLjP9=JRF_XHhGSrH`8 zG3-P3KPnph=8hf>KKvcNcIBNi#?bkAp+=lhB>@R_k?AZ7ORJ2LJqacrOnS%{o)9va z@fFCZ@SPM%c|tsQ1Xo*$$$3;Cm+f3XwnH6?^%()4pK%&>_VbGc9_X}{%n?gKU;&JC zOBbon3-+#Hi&wqrP(dC!ic8<(#&G;54(>eUAqtH-N=v(*Z+fToT#QC@vyvG8U8|l# z@fY15g}idH9|p#PKTi+ay%62}jzi~Htp2~EmBeM5_T9~6{lNiiC?ju)s*O(j!sHQ(eX<9#zqRGxc@+;MeE!zR$FI8ZZO{n~FEHpvfU z3B@`IgY0`%aQ4^bQgY5|@RK78DRj6Za?L0QWPd>wF?F=J1Vu1;k;4WIjYnpU#+=~+ zuL^SAg{fAzZ)kLrqJCHwmbQqGReSowCjnyn-L7f}Vz2K`EHP@dV$ zrp&{hKwu#Nr--KcO&rWFt@(-}gQ^19xq{e=ijo}1HJCMo%4AY*tRKH&(#8T|_KPy@ zVsOD{3;%jT-#P{Bg5u(;mebJTbVcRdd?ZZdy zV=X)%I(qk(wxKICvrXQMNr~tOd^V5hhZ>)Es2FdKDXdA^#Uc<^&vg|c7e1zhd~lLq zxNOe)u3DwR6Si`P^=EhCK_So9KU@6j$1|HF8bBdfwjR++L#Et*mwH%x)Kpz2fV@yL zgh(pqOs`yDp&glxkVk`{mKjDYG5Z7xb=d+xoS01L)yEsW?99C>j!AZ!{Y4s@~v2 z!3s`QEI*fGT-3&~rGMM~bl&3d1 zD}tC|(dz64hs164W$OPf1V#(GBDY_Rg8Z?-^h1@`r(+B?Hs6EOB&iwFnG=A@9%s|W3( z4zZyraW|Uu0u6;)0afsLb;a+|_HW3)TusRd?x*xy1W)wpl~UQ!7ffR->NC1soQDEb zOF5GIgO2YsD6kwor($e_gq?Vm-K(Je3h7@{iQD-g2I>bAe!r1;WyM5!P@_6ijr7LIPCN_lAa7JG2392ehj1wWkWg`2I%Vryravc&GG&W2c`1mez zgUVMBqoWCpAvTa5otCh(b{PHAnGoKT(pbq!F!+S1ydp2{En{>pb#2Yg%!4o@4 z*@W#UIHdZet#H>RM5@OVXZ8^7@7qMz(a#pt@Qv!X**8beEV2NRA>CSg1rgx@-nY`3 z&-qj>OTn3buD|l?s;}G-!4f|IRx&-oMqcA=<7Ae+|0M+hPz3>uOo^#UoM%Xcl-tk% zaV+#e404-W>+*l=gn+3N0Pb-#7Sg@W>($#LR3ZJ*9<}s=;gHxY9XKd5 zq3D^@Q?aV$8h3oMJ^&O*+x>;A?)|oWy8r2&?{`;DCH-<8PhjQ|Sa2WpT={84H&ixl z(87{Ynf}L$=^aDWMrv}o_0j3$7Vt4D_I6*ydvVONwj8-4z}=19`yob>E{nxq*Z%wc z-Tj>y@Pz%vXZyaRWOwlR*l;`G-tnSo(ytG`LW&?FvoVaiD0T9L^dr}+kF^zBvDs{RaUod0mN+se+mZF_NW z`uQ)}hI=9G&7PBc4NLL9Q(DQI6@Px|wxjlzX)lJd6&y=c|A`+~-$#Gv=dUOYtZ>VU z-Qp!ZX{>S*Z`eJL7K; z8}?up5A_n^%^{QC_vo*yKJchvetzB*(Fvy>tdPB3va@A@aa> zv8)fllV2qyKJ^Ao=y3pc`8QzEKYCpVBgJ-6A3%Az+dkd+FN|2QLzp$7`p;ej-fgIZ z9|xb-A({GRE6*~r%zHg~h9;^>Z@4eaztfjCUQk<+4L?COu}9Z}*Zc~Q-eoztdjxkxtiJL(%PU;! zt8_Qy-t=uN#A;p`?51~-{Mhg*lV6D$>)Z`*Yf>Ydy zN#NJtxIONfcOF%zhrX(3O-y3qpH#lMv!0Lq0 z_G`rt>WU#iXI70-<m2TfmdKGtNl zc|^n&hxK`1d7gSTJ8Pe+fZ3)-reu3&XA5A>sxoqk)n!sF|*M zw=Ii2LZE9G0;J;lZ16jMLCG(VC67WL-`Ca$wqZ>Y3gZZ;MdtUuLqu{wZI23U`uU~F z@OrC11}?TYS^$R(+p6703M}JKG4B>CJw674z%gDQ<3`2Y$&MlFWjBI5E8Cq(M~zSW z@+J})YSn*xB(ebY)D@j)=_lm=_m0RW541D7#b2{OWSf8y6z9NbI}xj-%-k}nRN__9=i}wANZ5@L6qEY{ARgBd^H&~{eNncxMC$V=oQSH^`ex#ez2Sh z`dDkseH}w^Gpr_MF1J*o)MJoN505#8!kH(D8~@)6u%|ZQTP*IDo_2QBGd9-t@eYyM za^0nSdQzDJ*>>6Obm#sA!RFZC+bfb?nmP!MbQr%O0Ux1FW9kg)qS~@^BQ`f32lcItwn+1(s z;z#$41FZkEpyP3Of3%AvMI~)hj2uQxWvAavU(h&fqeb)XUWt&^kIY?LXVnx;sB$h6K8 z?VF<4`2_NsKsX{3?fopm>*Hi=nm$8q_AUDb?!ztejAB)>&jj<($k0&a;%QFP+xwvO z4opdhSEbLWt&f7Lx1UQ3y^3^*KOdQKKk6kySuY$d9JQarJXOEe=amj7Mbq4xaiC)c z#-8G{N&#wTX=yiLqA(7)3+s5e2YyQoBPIoI_iJltfWN9|ZJc$vWHwgs>i+H>h*8c^ z_oeVt82=X&{?gAD1uwUKg}D!CdX_GnK7iyM4~kFLen_Kfxb#*_CccS;?H=~=6tPNn z$G@{KzdE|pf;!{Z-Uy)Bjhn2&RE!FV1ql3DJ81Y~uk@w&XjkXe(OG%M?9tK<9P0q$ zR|JL)v#v!h;dhd21L&o{`%FrfgB8G_KJb2aNGLwx`3($u#r>zzj{^M+lft$@{SP^r zy|GOfmfnw#OzBHW{p!B_((QY#{EoQED}n0dG3xJ}`CyAdMiiKzpL4K;c8V_*zsSdh zL!YsR3WuLZgX5GNb0++EGaGmu$qXnb`Ql(e0{5k*IQap(Qz>hFykNGEukRamvJW|L zMZPhNs2$aE%Or6x=(bWF4z;8oo1bSUvPhB1#O;j+SyA(3OPT$FvLeWE*uy*S z--l{?ny6d5=6xjK*O8GqBl8$vcCM|QkMZHypEvqJlTvE(k#=U1#C%ydhgAMixcnP= z^L0s=75CA8BPR)BHLKxlo>+}H%r$+X_sGr$m^fQ*?6UmqAZ;{U=IMCT5RrI z1$XZW3kVdk;mok6e|PAsR+s;ZKC>EF@%aolmZLKqZ|dM>_E4Xy z)y};l1x5H#fb)>~k^ZE+i7ZD~-LmO)#J2aJcv*^8hFC^8Ed64>X1oa$BgG=z>lw4= zNw^eek!be5az>9^_dvL!T5tH@R0jf4{L?t19{b1JDl;t26gBnWri5!aY|$wyzM{A_ ze2UyGRr)W!5_$rFNl3GXlc9eeLH0Nx?`8x5ixQZM5C{?dQ~TyU#+xMxd2Dgi0LMro zU={-c2U)M`t~fA0w^739*^q4`$&{~|m1|RXv#{+FuwmFS`XcU%P6jLXVGO05N}l>~ zq3Yyl=6;tZVeiGn_^c62fMSAZl(5I>t@dJ$ozVfrx>(x;F?BV02Y~wk%6nnq9c2M= zgft+`;m~|A{@Dgqyw%W<`%bfWVaDSs@xF5ZMh=Cka3LAFQF525PumX$TaLZc?xWbq zBI8?*#`EO1bhAeMb@;GC`EyM4LsA$7JA|s2j-q=sZ3cY&%b(>5>eaiI#$)PsLnYJE zCRj64$&{v}Qrisoj)i`2*61pkKU1Yxe)3~wCF@y`7iTgA&KNh}JtFw|ApLas()?f$ zht5vIL=sVaCVSw8HlGCAw8D)EP+0$iv%TbJmd3HtKAWwY?Jg1Ee;4yQO*7*?(f{GH}4DIDv+7{e=XJnkZ7lL5DiFehiF0x$5zEuPP73`*?VF$h8U zj2m8|APXbR45z`-S7WN7KcTAJ12p6W9bvFPrA~o$FE~5CyGyn>v25EQrtbT^((cy- z#2^0rNf{FQ*XyvfBxQGZcy$s%b=E5!w?XyKi4GWp4a-`2h~>`yjPoSt z-+(B$SccK2Ayr=Z`={BL>T7n-s6}$;s9-^M=!4X8*niNh5stsRWT6?VxMb9mpb zVpskrYW%DiZ$AY%j3a-e>>;BcbsnR8vy?OJg^TUkXP^R-y4*saD zW@-##Ju)O8?_^WUHRsYk&|rK`?x$rj(`Svd8azm}H_#aSBExt|uJX!fE0l}9Lw8z2 zL}%sowhralMP^Fh;n_auY0Kl(k1N+*v}d3G1p@NBLqC2gY6LW~j{6H9Kr{dFD;h=a z^6zdua*beA%Mpa~=WwhRuVy@E__*I(VOaQ5VN%1<6ZFCVhWsMal@L25%T|vUI``(R z^+kG~IR=s*|L-oH1UmyZr&i39;N4y=W}S|sx3|k*=cxjnsc;?J`JRu&Hq0fb62@+p zbd8s}q$8gwwV^A0b&@`oC_pO*1}Q|KSI7%+USqrzXXwGCic5I1eSWB>wSPVT-D2Ol zFw0xzoDAbXud-CixwfohesAI{2nL#>?`f><+5|nEK_B1&53ccBtJuotJl5}-NN29o zB0ul2vZaTpuc+d7g5MN%)p2}I#|~4;)x&^L=OI5vG#WHteBToZBOLgtVv;C2M|=g( z#K?4H*|HI*hV@%c&MqIo?SoFOmNcx1CMkAJ>T6(Ms4ngKcmT&0HOA*6lMRSxDq2z$ zR!bq~lgHLH@(zse$Z?(t$DoxqfAEQ^01VcfW>MnC^)YYa_(#Mq`@==n7c3vO1~QrP z>!pNjz0KtuCxq+q2H|j5o1jn0q;^SCVcBrv7I00yU}hXONn}bO1W{us`%T>VRYZS) zbMc)5uN0t%28hF#0PBRln1gcao4yigGJrFwuYg~fUUGj-D!T7Bw7F7ivsUhPU#uTQ zXGL6s5;g*T8gy#-YJ&R7hcCZT`(GyPUttt-NggriasYhjg1L8G5#*(bqH`k_k~&Ds zx3)d8yX&6-Per)Ea%9=&3^)dhQ5nJ=e0^qhAsFEr+gIB^a#lwOaXdoL0zDe?vQey6t z4Q?{gEK#OC7)uo!=n9Eze{J#0rMDsuuVH6G(CPZVuXV&IP3r5-V(IA@eF{K3QDbwn zOPI12?pp`48*gijN=-A|tGkcNrj;m(B#mYYUO)R=zp)S_M-!5-p2dpeMgOA&io_JG*^7?Do_uzyL=SmaO3}WuJJ_Dzo(*0LTzjwW`D{3QDP{PhaRMw zmjcR29nBrW*6@I5N91N3~gui6Bp{LcC-O^Z`XUXde}GSFEc+%uzeoDw8>;n zT#^BGvQ;YBD)^m=n-BBB=@=PgNP!Afiu+0aSWO%6Pr@iVWQ=RsMy2+$NE&^#UCABI z_e~>7BygF+S*VV=OryJ+H9Dx{06f+gKiLp(9U@ZcnjKWy!nD3*tWUgUiMQ+TJJ6?}P9qtvj z1*-}?CtmS?Fa@I_D0W79Q7J_fghJS|9O?Oi`sF4D-*=na1W~PHzVv{LfAFo1&)84D zEq$^%yNP+Wg6B_;PpHaL*7*&3*s&}@(^TmOQo2O8d1|^eY;mBjyjW~l18$*>V9td# zf2hV}`Pfo$w#C=$V+2tjQR;VJUe`Bvx$i^Dw@oY_6$p?~af11EzAaOSpa~HP?`}dK zy}=vaq}bkuc9o**En@s_WR_Yz;A~b%rR$`KRB?@Vjr(Q3e#?(^H}g%*Y&iP#YbG(q zAE0tP*|p^JU6FQKev9+uF-RGmysWR)4PJ5RZcBAxxL=>{DkKK|+{1!!#iGT`nHvbl zGqSEUGY}~9le~T%iR&!xRCYRI_i=ABko_^R5n}VDQRkVUAXOJti1^RbX%=U{itIrD z#0W{9XaS%X9_XR?2OlFMBBbT!hce^;k)(_YxL}opB8(XgEN~?A8ddM5H_en=oVamI zC~5gs$6M7m-uJ~{Vz1V9{sd+3fz*@hOEDkAajn}-afOJ`LK^%eTYT%BH75PT9B4r0 z3WqCo3J6^FI*!(FZEHCLozJ1l&f?WZzZ^B*mnC;!9j(w$rX*J_+tPLD1a+k?Kn2je zA0^zeUKWg@QV|7r%xF@;=~v;wbA0pkZ-kLYC9`FTt6d>9D*k3>r7T7`sYRFZoAHZ64#9n4}lBszR|v!4s1a>LYWS zOkauk@=-k>iONEibpy?F%GOC?h>>ir#sPBNSz@CtZFFYv@OgF0HgVyp-%XpkC4MQ+~$GHs5HW=b6D)mg`)#Fh#vtOW-MG zi(Wjv=E)Ns_|ww;YVBklxE){-@z?ms)sg?JBd!WvY?0-0?g8KY?$!B{RR#&wcI}54 z$h%+K`0VUKw4#bGyyy3>;CWQ~XTM56J6W;0WzK-<=~JwLjn|BToy#H6Hl~`($mG*+ zrK{q3&Y{v2%7>(bbd~`~OepLLM}JL<_2;V}i@T2ge_F;EmHs)BrqE8cI8}++1zzen{duxuav-UP*r`SA-uUKh z^3mUPQaud)RCDeLAg03bH1{#CMWbTSA14ICqVB$aN1FnD>g=UTcvfW|BkxodiJ@#k z-CYWz!Ft-a%8NaTUu4i##*piZH<|pXq5vVSJ!NXa#%fvOv7VP5VQR6(6z-Geh8#(l zBaNG5Q2-Lat?dcYg#AxgLhxu(P1X6zW<;_Pu8UBKwG$-u4>zJd%_?gUn;9PFs6z>p%E?b5BzY z;2A=fseY}${o!!jbH(0%q+%tSCB`OqPk=^S(hdv8|M*9J^_e(z;D9xuQi#C|@F*i( zmxSQ~qbxHd1Ha_70DAMYbf;+M322C_$Ggq_UeWI0+k}nle*dS<9C_Z9#DQcGKr|n= zC5K+3@)D8uss=*0-fJ=Q#u3U3m}a+KKO zUcNo)m3U~>ILdqI$y}%wT@s7)$=;ZrX18B<&eyY-aWG&fU=1)}kr$~m@gkQ1`?47j zQC=5i#u{%g`GG*?i7!?PcHCLb%Iz@iOX8w+VX2{&1i|?qy?<^gV!xms@G@`2>JsC|yxk zSBYm?w)_k!8jT$t{U%_^>;-Ym*n^gqmhv&4u`|m4W52y?yEE#3xIhHgaKYu=+tVLB zO{p;Fvi~qp7qfZMIhxc7T9ATz_Znf$;fa&ivSL*St-fp%OtNBG@rmD(uaAZBH|t7@ z1(tpWyf3}o6J0q1rj=d4@;cT=Gm;=Ok6P1yo{HAIY_*pEYs_(cDN@=jyENGHw@8XU zP$?k)_q9aI=jE#_Snx}z6ZBm4%b8XX0*{fF;R5+nW zfxp-9sJHYG)_04yCmvx-!${vb^(3^~lBHX#zUUiW--+A*rv-JIfZiAm% zv>FnGwT**;@?q+X35sH-V#>5H%^owIwi{B!5p*eSXLy2cFDyRbDWnYBI^DG@4`N48 zG(T&p3DxH|Es5;(F_wnT2qICoU) z-asrjsDAUtV&z9l<6<-IA5mjO=XZNMP_OS@l)iM=Yvs_4OV*8Cdy@mqvULMX;Xp9x z-NIECG*hlFPOnqY4q?AY@f7sqkBc2WL5ibM%c#03K(}2%jQ#5z@PWy0uP_-l_X8n7 z5bs&T4e7!R>B3b=tbb+a@rmhfeC$4eGI?g66H3*SD}bT!mu9jqj91`qGrGbqMITM( zLdvlgwtLQJhU2RaGO?@)g0``n%Yx##$^>eL%joAhl$XG!sgiE<%1k774sM&tb-VBe#5j!^M?j^HS2T@%pW zDhpbJNzi4~f$htD_QfNP3f3?ZP8OEJK&XYpleHq%?N_(xpht(2E)I1`0f>Y9>~9-| zb-br>;2NBSBT)v#BKmE8-AUaX7`1zpuU(z+`ZfOUsE<8q0r7CsQKfdQ!Cbx|><7{N z-)LEygK1euWChomr_JhQP1jQtfsO_=cuZirNAzMSGAMw_=xb(xvuB@#Tjp~4`1`+8 zX9a$f{2bnP#&iGC+J%%|lZY-7n zjXTsZ{=2A#-B$`eY$Ddx7^wm>EtFSs_WQQ6eIGk9Ov#AKi;g3ok?Q_=t6myhi{CAA zTa=&9>Gu*QWc099`yb_e9=k4(%vx6cwOaL)jJ4(EndfRL0?$6+ze(}qg9V{s#2I}( zo_9Hq&>l)8;A!^y3VV?93@zKc*f|zcps=gvr$p_p8qW%t`rzTP@IH5Jtkx43(iW0_ z&jZHTS;zBk3f2k3S||GXSEK9zO9duo%BKRrcX znI=3Fl{MnjQZ>%Yz7OZr9goFU!sww%7sb&e*C+>13xt=wv3HTzl*~mZ%mp-dvI(u# zmsg9OxjH~Vm!bOpl=6DAV@Y7rjl^}*80T&|SQEu|Y}WN`cf%gEO>*vE2@uxtrKv)<*lz2vXsq)s0z-2a}%E zapjPrVl$ML&c}!-B3RivPEhR>M#?Q0tA%XA=dZBjs>;22h}Dgxm)SZgiIO5O%IxW> zai{D}%5-TOdqil=9Fc4LqQQfQPvLX!hD$3dm{ye)_0Tz2Sk;D*@-r5NQ1!w#waj_Lpk8WC>Ucf$GviEl+!-c7bV~DrkKL2T6-Dr~I#SC%uuWqkik^cYm{Me>o z3EIB*Yjg2)x}n>9PbR}n`c`4um9^s$WU1$9&GYPt4|C10p0}lP0~~G&rUH^XB9hBB zdyTZNelunrf`nq_LVuqb(DKI`cb309&Xt|i!)`m!UdSy~oN`;k*Bkw;^i3kIuCfU6 z2DJKs-4-Gr&@Fa({>N0Dj)qsKlXo!G}5u+nWFP0*GXW z;B^?3)7fm*5ApMm(Giu;0(GT z^N4nVGDqY6-+q|Z@mtqFj&h!EZd>b*2k-ivV~VQFsqQjwj%?2t?}ESiRX&pyF(u`0 zpBd5dhs2r9jAij@l=T@&w(t4!KVr7&vi<{al*ow0$NzThJ>7Ba`|&QBpgiTk=Ew-g z@)KxtXjJY>`tK7h$)%sm5uW6xN?LTXfv>jmiYIp|=00g1KiXo7(_Z#cme`nW+)kk1 zkPE<;s2}?miuR}7gEau7qR_HyCL9Gua>#%mV(qO^lIFJ=66r$X@*I!8LulX~u!4tCU^s=e}nl z+27J&W)7F~gRwvH<&lNe9{aw>ANU1l~ZaL z@VuHd$yOa(0}s&YbNsd`mjT}K`I&+Ygr5iSbp9*vxxET_5CTfP4WY;ipW~zkt&AhS zCDjwhJmX0NV3XwleA0uSb2UNxV`i)$gQb>Z-Dcr=lcHLs=2X~$@<>=H8G0gywJm#3 zLcfspIz+>W86v>!#2=ogA(89eG|1@-S2cBc!+0i~`Wd%-Zr zz7pu%C3r(Wb*=-?l=@KPaA3Gr7<+=uS2#37iE-M_x==0YOBjU2ACi^)XkQ3^St$2H z`vV0*E<0E4EAv607>@#=1?Iq_!vKxP%Lsc_Eup(J8$OGkp_9~!uKabHp_ey~dDp+; zel#`z9n`+CH>^ry?*Djt%cv+HH(Hw(>5^`w5g0m$lrLIgxQq#NmuL1_>j zQb0hubVOn(X&B->zyEp9yB3R2NC?>VzL$N*b+jM$tvBFv$D^JJ+q0X865&I2HE-A9@afZ%~Y*74r{5hsHr8 z{1ZQEmj$G#$(f|llXrI;Jl$^X))cXj_S>g#d^Yqm5;JUo?GZoaB|Z%}LTxbx7O=tQ}k-Q``PLr~ocEU|U+%iwdR#)H-8;d4LafK686{m;|cE{gWyeX*+U^tMzOR(AU0DUB*OezcoTZ91_z^}Z$K>$VP;BWirE%kl}5qeN>Mx=HI z)_-R?O#U3rKOqq<-%nb{rH|Q5{?#vIXALY7e*#yropfu24;Z|o4h)!Vp%SrH{XBR* zSU~J<=#;Zbo-6-PW?G-(TejiHt9aQJ@q`@hX}318bJ%F{1#i-5NL->qu-wCRSw*<_ z2gPPFIP*v4!snxLO3z;ek6E0ox!en4Bq+_~g-meXmypkO-Y2$BDvR6ny0`oFsr1{h z**5BhXk9n%coSglY&Fs!^y_ctB%M8aW0uJGf3BE4FyrWsJX#c*y)A*0g86Yzx=fJFaQRjv= zT#Tad2K?>V`iP2@9w9xf0XO8K?4h=czk_$(Lv5#7IarnRt0OeK3eva-3zu%hLe9gcC07Jio*1#=P7&g<1hn^>aZbn@7X zr3%&`58mPkI(a{iK12}T^X$|fc)wy55D<|4UEoBqt5y!`H>D$!heWNQ!7;?f%T#h^ zDl}`BTBE)C0=qdF71&-nvVApSX=|eVq<~f7K>e)3fX4kpxe5U$_9s!{D50aiYIo_K zpMG88Z9)Fvv@sx3=1wJFLB_nGcmN5RpK!^BH7`-`)?w7Sm)!Ruulw>3PeY;v7^}1J zGpJ(mvrT3wqopa=!+N}>?3Qh|02r3m(_B0dE%h@< zy{eja0+yvK8X*Ox6ud+~x=YCH`~#z_JYUX_SebKwEWP=!TBzmATkR^Ol9(C6gjfbEphKn$+} z4g?t-%phm7)NkkwXEzXLdzv&fD>J87e#c*3o?pezf|!KX%{w^*OfIZfVTs%6tbcBB z+n2FVdryY0tA5d^Prkm2Tr9qyByQ06(26+>O8)NrB8qe2(WKKQa^PAlNj62!9JA=u zLMz;j$zXBrsbsK0nl!-pdiDj~p=cA3MW@br0Zh>X?6|!f-AqTs zxgaEfF>rBlDW;k36I7^|lNJWkKMLt#^n%GBU_t|T>tC0R69gJLFAP2(OB?^W)!w`9 zITr5X*XYs4aF-B&c!gdict)1@r+s-cr!doF8?VWnLK(KXcyA_t?|%HQ4eNl{iWm-p^drEcX08+X%Gz z6?)qH3wi_~hAy%UiXIxu2m&i9I#*w0PgJ^$&vCv$7+ZLFiqQckcSx%ly<>NL#4kN? zh8)5r(^lce_Vnmwf5@FFs0x zR&A{tG)Z-z1Y2i=sY{+=m;V@jg2)Ss5UAmcIe#L6Xqr2@Srny(%ydladgSDbdSTX; z1q;ekbZv#}Mp|@~#|`qW8=`#tZ(~{&(8fED*={Rm78+=H02) z2!T57=B#V_AvmCfMNkE2or#I5L~vwVG=5T(M%kt3W3d_jWVitD)<5Evte=>R9?-#c@@nS zeVi(RzAx;$YUj8h;c*1|q4_lkA0M;cflK7wA!VyJX~i2w!cyPqT5ZVmJhIHE{Rfpi zB(0h6zsx6kr^`#w{&1iL02YVa8Dy&+AC-E0TiZRjjU4~R9>&(^I9R9C!10r}H_KDpo%mLtRY_$PeEjK0 zJN62RUxjmhYz_L1XUyu(7`-At%=$8BNo=Mi!qXiMn|AWo0bV^p2A0|^wbZhcm>`k62m% z&k$V5i4*xYLOG6k1mV~97R2ub#;htlriXZc3&@#jWl7N%2Oj8dfT$#G2OEx{0Zi(H zq>y5vB~Dk#^C!0a^#6|b3ASKH}qYj6&pZYbT)+|J-v~@jbM|#N> zs2hV&U5lTO!qz!Uq%qZ+UqETvbGg4!#{lkaz(sT0H&hB8dXfW~T(Q-ZR$ zZk}~FL%(-7{R75PK+g|Mn|--uI?}meT>!8!F%h5GW;?vHug9X%rcrA{fQEnI&FR2L zQ=5WcxPwp1-)U)MBi`3^@J$qB%?)pfirb(1?~P`TURAk;Ta=MJr4d^0Vj(W-G9WeB z^UZvq6d(`7vT{Y${!=1}f=U1FQAYDS5QWuW zcr?D8lOlEEz^SCjuT!)()`icfp>@kV%mm}74@1eOnwuWdZdHnrY5l+Gzn_JdNJ1US z7Z-~murT(Oeq`aiJ%B>U9Q#@kzl?L41HuU@4vTBXB8-KYFPuE}$dRjFXbFGtGh7+r z%Jh;nKE49zbVsk%R(nXwnwS`U9#58Dy*HY0_YH4h$i(KCr`Z`i7_d*&T>ANXsppZn zCcDLF@&sN7Jrdig2!zesZ>T;7H4a-7nBW-k^Ye!j8Z|{9wEy4!8>-Tqy9vNcs^Zqy zhO+VH_Za-8O5~@T(#qhIO+K$g;LiBTv?g8PB(GRpOGhz9hs4gRUbla<0!kmQKw<2= zL{To6WaiT$8gV${4+r&Cb!oIQ4($qesNO%T(Wem z`|6Ue&8nnL)&M$AzG=%5skCxMcawKo1!zMSA3K#Dt@HiS-r4)S`gAS#mlWTyJQ`b1 z5lN;`uq%S@`IoxBfKba?X((Av*skc#+!42;SkV%tr;)Wbz&3N5Ue-9X@mw%j+VoU0Ue ziLk+F-4nN4P8k^)nVO`W=d`b?Yno(;zvDFcv-13cDKE#^Sl0fJ0TC(A^^_LX>_ax< z!x@`nP%L@kK0u1XO=apxc9*ZESgB^y3ZU)A-XpUz%*t&Q`ie#N@|mAgpizdau| z7}C2@B!f$Vwi>Jl&T8by`v>nogq~8rDFMPYU=<^afgSe_{r*-LAVe1qknn}L+Ke0l ze(HpaP}y+XlNk0w7r$4S!@015+!HyQ+Xb&T+#e%z!@9wnf{%ZD!ky(`|1C(n;WsR3 zU(+j*CBeCV)FE@W*{^>wEjcf)%Wc){`1gHF@1!1%%r^U3_7&AiWbZV<#CyzJSjj1u z`6|N5gGHgKx5o%5pw%J~t*z=MTu^2>b+fH)hW<`YA;0$A7NFvLyqS&!^ntir+XR7m zA@+b(8^|BN2C^U$fX@X$&;TIXaq^37BZl9bkL=BC|9_q0B0XK3A201Cm<<4}IoTD` zJ-d-Kk8~{eXzcTSftfv$d%!Zhe{556->2+hir?Sd8O9|-`MYx=Y<`=XQpJ{jgbNNy zfMxSl)arj`e2X z9pKkAYK&R5od#>ijGJ07>gJx#3Nmz$GD`L1yRE$@>RNspd(dTgp)KdX0;;qb4?cF^ zVd+ydLI%sgf#{MxVZF{oQ4?hM1}1hOXhZ4kAIqOX$34v_4>qaG5wyc4r|zNRjb(G9 z0ll%yuk1Q`OT#VZ?o>5D6U9%nIAZwAq=SNm*nr}Roj>09c9-L2*^9pka2a+k!{mwty;UG~Tq~7bJDYx9r8-6!Ri#CzDr@t+P?HCi>L_z zf*PD8@xJs7)HX&bX(57&z03)YC? zXlK|-F)CRmj+Es3Qfh4WA~PX0F94-_SCAmrLZEhMyxVIUTu%RNh3)=}#0wNIwO!Qn z6ht30P0MO#8q4&VWsm+%w|@yNq^Phg&XAp}Ue#6JHe zfMwQ7n=nd&rQF-W#AwqKS{gs8l{+2-8HKM}G10OD6TJFf{``y-?Od+cum2GD zs$-z}qdE}wWuC#3fRlao<&~VJH~{ol^xCh!szqDM+2kyV1cJyz)Jbql=C}!d`9vx^ z2Qvvj0531VjapqNhrM=B>c~a@K;3>xMgB0Nx!JAlr&+uM4h+UEJ-|pGy}0WW+PqtT zd;8bS>jr3Fh;5Mh)f7#pYoElm5r-jroT1G(JXgQ0Eh_(blc74s_I-= zYt$bq8A1)KUUx*ki!^ytR;f487Vy*K!|n}xeC#yPKSN-l(1GU)D&bI|;sXD2u3GmY zuif*{bRqZ7|E7=UDM$ z^si}8WT{REOdEy8)eS#>;r?>_3Cz{>dhg(~`q|WGw~DoKO)SVE6HA?bxT+Q+jsgDG z=Y{$F0o)kNj;Mp)yibY-b%?)mJh8%>zvn1(o0%7_6T8+B91ZG&2em5phQ2e;1T+F88%2yMSX^W$Fx2v;xD9lqgzohd0+q z?q)y~uxJJhMST$0EjgfRT!{`pf+k(1{R3Jl4yBSq*|?g6jD8f}>c8&E%VC1ZDcdoQ zHwG;ZXI@E~SF%>eJo2h~Qqi-Z?#!xzqJYLtsn4p*x{ibXe6iEfI`)k))ntGFi<1){ zDYggYgpMy<+8_ZxErVEP(VBqhMjg^s+F0{rhGw*{Eu(fbW|-K_@7cb(?eBj;h@jY& zr!ikm#u9)or5~$=3#Pn^RRLf7j@6<%MqtE|%KKMyGr~0~lnp;c1fBNYOk3gCjo&l* zpzqcBB?Ue7W4}F2FjESR`L_Vt@IqmrIlah&5tWKDR*dKF>XFVxg)!Sv z_vUw;8JYv-YeD0e1vek&>VD$^N3CkdLd`yH>IA!cWlOC`PHk1^=mPsG&O2j3CM^hK zCo>XM>AFQj6Cr4WfACZDBFI@|Y#A?2fQW>k*FVdzd#g?+;`ZJVJi;}d-qHEw!n&lG zXlLIRz3jna@)jH?jS6fvyWXN?=$=n@!mrz#ePJbSZfm{r3XDiM0PDd;wS_D~WH$3C zZJLfxZc1*ah$w@rBt0t^LLELTjPN?{AAz}1>Aio!-7Usops{Kgig4u z<&AG1ulxpk{u!0KxqE)9=Y(W>t-_9v$3~IlU7KkLxe1~F7AL??fr^R>kWTk|5<*F_ za4(#QFp7^bufxR(zV}a3TQIi(P7-pqhp9QI^+s+jS>!wz(&Kj@7Tm)W=hVwZ(5G1IAPWjI0t%ycCr(_x$ zkFUbH(m^0TzK2Dp`(aa8(*p3pO(S1azsk{WH#gEHTl7#|Md25Z=ob)frG58a?Qhid ztZ&3b&)wgHS_p!^B_3z?^MN5aXtkek$)x{!BZPC5vw*M+##C7ec3|B^34MH6uO6vP zjYdQv{>=An==BA7%4S~ugf+EV&+3LGJ&jBG*N0W;nY!c-CwC zw_u<;&GQsMvSWUJsUN(63hlczcP9GzCTBW*O9JP@HWNLv?rl;?=h@vIeMm9l_wO$; zo45_qCIzT8pOPUh!g+JF-u0PQ}_NH%= zB*eYv0s4F`CN>O8v$H?@0;{~&c+>YD5&pvh0sLYBm*am?Ux2glQ}Ub$^d|wyz(?B% z?CnTJNfWk%t|YkL^I6OC;YQf#S+8&n|I1fopQHb%7?<}dv4j?B&8BhF3M~&$bF(<) zp5mjUx>;kCeKVL@F?rsnIn&H8sQtq?qR#b}OI<+=V=~+j@DmZUh>vx|4#t$H)`44? z9`_LrHjC2@N@&T&Y-&C6P8w3-_7taUpu|^htyj`+k*6Q&_o8HogW5emT?4Q828zb~ zNBhkdJQPg^feBmXbXPm8+-5o+1t!QY(kW`_ujJhSIogGCA&Sn-7N8$!xKluNso&2I zgOD^H-j;LW@gh#$Mq?S(Q>&h0|D80MBJWz`qYmaYSrFn`;J*PSHZm9eUr=EJ&eFmz zAI;-x`UWJ_ODjgd#~xB5f8zZNLQbd>kTEE*Lu&5mc^EKnq3HwA$=A+iTmBVF+Sz)) z{u+ayfW6T+Zcd7|h%4C~zfmLh=qqGiHt+(XUyYqn&xA?O%VQ==a*=CKUeAVT1Dx(r zQfnKu1j!H^zgN%IfA8c5h)sl$3#EKivXweQGkuT6{0{A1#@EU`@0fo!pE?x+JPuPN zbvgQA#owm_$1LzI7X|A-K&l0D2K`HP=?YC3SmP`+b6ty&#f^2t3OC(x*8H{$Ddd$4 zw3P-+{exfz9)r{wa6&mQ@QdQb^DfyHiEVq9{~aSp1U-Y)z0%&Ibd!h+z2vaWgw#Yo zPQ}ga*)W{W42Cv|)7bzZMAH}4PU$N;!5kiWS9@;z6D85<;qTRY9N(RTkUc2~aIAtj zMqX5PUW=l0txRge3t;w^@iBe#cKGbPvE547)?y;URizM;q%fANJvaZvIlpRXdwbi) zU5n9n5vIF`5>6!0h*0+R5-xhG9WiGAR9HSu9o}FGY!s{a|K3h%g*f)iEr-7^mUVXV zf54P*6`+Fv!6=v1WlBTCO1Y<}pZR;h!K`j&53d*wf(~cVP1uZZlVdR1IZ_mkIjQKavVxm zoKU320!Hu$1K@fNC>o0k&wxs>NYVwwDSg}Fy7D@`23Oq)RH0Vi6IA*4v5}nHKHlaC z94qSSZOVK=pGeKhQ$Lyj90W5Wgn(Dk$JaMnz_x$u_iqPcJ2bTaq6$bMHYxXlnmHZF z9yNk829gMVFU%=A^U%!DLR9@tI8h^v6H2hxJaE=q0Ued4T6FZVmhAZE@B?2Ay-?tI zTJDj4esP)IBzqW2A0Z@EKzVjD zMYn@M)VKD8fe7o;?-66V@a6(|WubQr%<=lwqKD@qQWj{V{1%`1tvxAfK=Fqp*vNhy z>89@c6xV>dORb043vPkQewjg>-P zfL}>`RG1VK3iR7Oa1K*)o~k7XqM4WZrp}tY+thkixN>p2rgSby(}=bAr-JnTKWaBR zHMP|n(?!vRMC|j!7Y!gT^JA~kTvJ*#xZVv736)oe*OoVN(Isw044Ly=J&nV27Zd^e zL@b|fn|XJ!k_5ashF)$xLSIjVtzZgNTx>5>%&Hr$=7qM}VT?e>p6lmh6&dx6#czM< z5Uuf2ukLL=g`O=KbIwzMaBZekMx2m-*#0C5VzE)-*gJbO`T$!{#2iJZI1DS#BA#ro z>LCsy$Au39N%Bs4_2MN}DGZw;E#sBB-gS6EeJVf~_vm@C4``t~)wU9X2nx*b)T z_cfWv+|U`_T+#1`xH z+F>(mv{#yr9I5tCQ|Usb0UJkBQHKQ--B*Pj%L$( za=-t=bn2!g&whGKuzeg*EJu3(l2Qzd@ifDT+e0Im7#^K{<_E2Mg|?+I1Y|pGxXtc3 zN;y6utaaMtoSi}oLJA0@1vK*d*{a3;aTNL&Cb<9UBJ>bbek~F79UK!lKLo&T0XFA6 zVlSt+q_>hu`N;c*QRp|I@UXcz?u^$0OI_1k&s&s;2yDyJx3#A(&r#(4sQ0j8%HY4W zTm;)5frbeb&wo(7{INRK7Zpxd)6{@F8n5{=oC^JRWkDWO8CE~k^dZiqTiW~sc9LjK zK3;))OdxE7coey1F|t5CUf@;`zKL$6p=|(^K)prU`e(7bQ z0%2fTh(9*O3H#5xavb@%nq%^(dv<&ASAS}$m((e{tyo)uwtD^cpCu@8Sv{pji7m3-8c;5yHZ15+;WjK?oPiOiID1ioh`Q5 zeDUv4Stx!O#9GPQB=|@2A>$Rz{$gn(*O0shH-PJm1h_e$KYu;}3plqNPMH1J&bj~b z5K8msRX)7>@;{+J2#y&I#IFOFn%{vOheX8)y2lTOLd-QodoJ+4{?*g{o&T>)*NaYgMTEqpT7p(UR6!@rpTQ;}fDEj1zIXa>A=7!Ar@bOI&&6>A@# z@?Nn8tow(fQQ(B1YT)Dy0x@8udf4zLTJ7k?VI4=|Adc^*TcvAVDlT;7Gt%;7AO(vh--%CT>c_x8sxMATof~;@ zZnlpr70eU!(_R=pP$TYD)k_$Wkn=bl_kB*OkQC4cD)*E^YEiW!UEGt%dH@-*QC`&r zf-m+~Lf&%2oyI*wn6R{fn6L2L^QW0(e|9f)oLb~^xF0Jn+FUyRO3sQ!Wv8l)T3kZD zqG?WKrJgq}T%P{>5o48-=ywpz@JZ`0Sxr6FlkHTHlw-cWNJU zuLx+U&iJMT+&(=6yrC1KLe?y;qC!32mKxIX$ZD6F+n!PI8T1TwgvdM6B?ZLc(2h5i zs*w5wKFw+(x@W1@%$aHBEP~KaE3?o2SRN@P+|k6dBih2~fpMomOcCq38yzPapY{${ zsZ!$&^eRYagnZMV&&+W*7_`I}v&~HiQ1%#IE6VUPPU$kh?tkZSq-`f^oBu@W~d$4MUV@M9Z)E4R4Wq6g5ExOc^)->{|5 zStP>6YLe>Jnf7Wv{q1%fU(`-s>DWWCD>245yV=_};7``8u+*(0zwM6&UPV3eTEAVH z?}-Yh+A7t|!aWklJTgR6qp6`aP!dxoqj>p?CLfpw&TiHgb!;0=7!QWp(yI?JOD3{* z`XwgXbRIu?%3&V(ZSq9p_@!vh5VX(uMvPrZPY4lb=OC|YPxW_>H_gH20|(9gO82yW z8)R6@mc@AzKo4_*Ivzj(tLJKe9Tx^U)R>Qw0M zoWGhvx)Y!3FKMGeT~&X>qB+q)2q0eSbE8*o}|9 zLVja4s69F&_=E;+b|J(Z=Jjt#9vyeLyI=0_v-F<$^Hu+Ii_yvKIEH1LfZ(|wyvHwD zK?#F@-sqf%)`+_f0-6P_>bbuB)A<5|wF$xjk=xr_1u2>(TQs81om?{yC|+%vm*R*- zva_W4l1w{m!@8cHasd zuVl_h)QbBh$Z&Ma#S8AUHcA*oKQg0_SM*m zxR$4e<4jGN-jHG~t~}v~=klQF*{E8LdE<}_^7MBODcZFoKup&9dXer+hJBo6rZ56p zG)v^{7tRINwkF2zYu_sgk42HnH%S8O7|^wn1qC3Pn>t4HU(l8$;43zK&fH4z)4ERIuXr1@bq!-b)#71~xun;oVjRCAtm^jjF(z zmN@`+NHHO2Ntsp*_Z6stWdijJuXWMBre?x%u z@ZsTMb(FLec;~F^$sZ82?rKb!*2*`uyVf;KKU>Z#{{WSLjGq~QD0~wmbG+W011_mT zJ<9@dTO%1)r~dSrhQiVp32V)>d%7mPJN3_*PBzxeg8c6QEE4d|)YKK}l+N8y$id6R z7~9%)omTqeMUv~2dzL**vmip0FQb9m?UZaBjK3(%90oiCm4Q>=Ypg%RgS~_sAMmpl ztKgl>tgjq$bQpD!y%U2$kb(%6h|zK4rWcrJ#@1yhT@YTN;c!jL{GC0W z;&}x|>FQY?t&=rt0{O>XXUN$KbSTY-(Wej~i38^o1k>Ynysr7QZ=V?-0DO)AFP;J@ zIe%6<=%=gEAU8b{DbPB|(~~VJ?MHG zhie2e0M@we3irIHb6C`~ao?o3m_{AY?!y3BCAt=tY2?i*HgJdAf&J_B*VCnsAI*aLspn95({J~Sdj1q203wmnuFGroR}y0(l~=vV+i zao|J@;ZN-9zlFO2ndL*m_ByDWdHQOvYzt{+p&k^17;GMI_414-cqgAmx-kY38ne9|3j_x1k_9pS3U4 z1U8FY^zHdc+xAHz*vd~yzRCARTW=0#<14Q?WD!r33^9j|uC2T#>Jb^z>fxkW=EL-F zaBfkyCC=MqsYp`v(Ox<_k!q-=PhoHJX8c*0YCq>cKSonmGe}8mX)OPZjhbONmj4-< zC944;1)qD7Lz(KeaPjXRMo2v?S5I`C=5F$v?uaPpU5a!2!!H^}S|Hn?wT+V8L!ZP) zRIiwxZY0HeU|sPUHpvKT=)%N^UP+r{FaWQpNCilOYm{wI>ZC;XC@grXzjb%FmiqcB z0l}g0K6V=ibs_ZFA`0vNZD48bW)0>Z76D3CXnz;Ys?nqm#-qexXZshU&6}oIC&ST4 z``eBqe<@=&l291CwK1IY?CRIAp`5Ao!)gZ3i->HejiGTc&>iW{QUFMkWwLJS0Bk+h(~jOAKg3I6{^FdR~K_fkTo7Qz_7?tz#1Z9H}QyK{2)#%A@s^+@wt zBKlDX>EIkbzbocyvR4rLDgV>>4+L3>%wmRL7rRx+#iciKE)Rcp2f^0stNa32P)pbL zb~ZSZ%MsM`{}BdVwPI%S+n0VSHx+co-RULj+URyPg9v$yjzVSoWpT_Maj3Wp7qyZn z2VWNN0J|LE6&PWwqX%>oR+yXq;S-Z02E=1ff<^N;OWWP>KFKQ`t=HOiP+RBv#cW7u z5}DA0Tt59Olm0`~?a49!yuc(_p+^{NS`hQe;c;DE_-)WWpL6LC3y4(F7it8}7XlOA zYC~^gV)Rz}b`LHAn0K7eJn9^M86H*O@9CfMyivRDoOwtIRlnoBRYuH1FwR>klc(s+ z$QGQ4e#1}pHw^bUX4!hz1ClL#>uEdj>I0fLIPp`jcV*U-NHRyA)k{FU-To(1NjC#PPUn>wIQ2Xbe=XzgN%Q3I)Z_OPHW?M5Jf9GGP~if z7XD7p`I4TItimrEIMMxfp$R9HRln4ZhiooJ5S}SW8RsIr(NWjN6KcW}53SgJg5ptJIK?|-%r{UM&_VxsfRH?Kd z7PH}1y^ANeWxvKAbThuvVY4VzYXbMJk2$40w7U&nBieXHF6Qf(lk+(!1)}VL6BK?W{I;#{SkjB zK`W6dLcoh^g}97#>`FviKM7uw@l=efrRG_7vO?{M>u+w)Eap~G{?ha%yw=7t&lrR4 z;CDOMy5Vt;oW*vP4qWYTn~q6jMf3)2mF{l_T9DtyCW{w~nJDG4OTRXmpb|g2+2v^F zeurbvqu?(2iX|mVIqZT(ij~|(8S*71fGlZYroqd0Q7@3No`SZLr|tgCk>eDHbOw=2;Uw z+XV~n7@#2bd!biKvfXBU;kP&a&^*uh210?kV@zod<`~z+Zy3PE z_Zl!M*>I3_+AjRw28%a%39RxKH3gId6tS?81K{a8sqDNf8DI-#y||d3nnAW9lqCO7 zQ#c+=w1y{j{N(sh=|O}s!Ltu|J1BS9X-WjnAJcl#x;hnWQ?7{@bsD#t zL1)}4vt;k(jRZJ9zdWEDg-Y*{}?r6B?_(U?@ zR_$d<16$**$rddF=t{?<8Bq+)u7u4;@5VYF;P4CRa!ag_fkW2g?c%^)IFo_LeOAad z8OoVUsn45{^tq0pU1DP5eu{so zZMvUrjEuL(tQzd6?%xy4`rpMpAXvySDmO9T4PG1ow)_~&>ux|^9Om-I3jDsft_}~_ z2y#u#q6nLtnt)8flU45ld#R$|Kr8#d7+4D6eHhxcq0=b%{psxeJP7I^5pi^(y?I^w z_~DYaq~N(PXp4W$^z>>nf3Q>r?Q6XILvOZT^t^GhACmDEZS^R8ITKq^?6Pu{T1OsY zmCUAtI~G(yI=V$Fy{D%K)4ioW$VwZFARrAq=>HOb_gYoTPyeAtD=?%mJjai(<$=B` zG+2wuP(#Wc^%ikd>1NWgz*Ud8`W^n$C6$$`6n7Avsq6CAqk~h~F*ek@CSq5~XM8h$ z=#vtS^k>|;+^p!M?xy>TKZ+O!=X5lOA;l1(yZ~pS^hLr8P&4l|Z*ydg+%^Wydk{|j z&;4c5=XvnN11uc*a;{Ui6X2|?m(31H_f7!*`Q|Y}D2ch2^5Les&3F>=OYT^S_i5}; zPoFCkSB++3A;+*=FN}M!Sk`XVc>0zmi7TEbbnzjUZ%KUT7y`nX?)1jxYEQ-_*^GXyYBmLsd@n6R>L=mMlC1{aO3P zo=7H|X6Fa74eoooBiqPJC{mMVfBFJ50EQ5y-WT`)e#BxA-^ftl%^S3a{eBv;ZB=cU zx3{EjvgE0e<#gyJEFN^mEYaE?O>|t4dYDQav(hM9Q+N8*@X>`d5vsSC9&<%?o)U1{ z(m0L&g6mn(v4pMW#%H@A$P#7Mo6=p9g_rAW{-Hd3~@&R;wKnwfH zc8bb5v-D8o1g<(`*Z~4gbC;fffXkd6pl6o-?J9CQy$wi)rk(EwOjME}XV*(tYXej- zTd91G{AF!C_&Ea*uc90Ot9MZWZ`{IbfNVQ(P~-qTH<3 zV0jOrK!7;rxZjU`6-Hz}{|8$O3~Ml8DZx5A+geknU`b)+Leti_v!JM%AR{GgCX)3E zc+b-%Pp(ZOik-m|BetE%oMol^5v05N#y_2pA4Bn@f@GeSV9E5oHxUa*Nz6<(B>VEE z>0v-fllAM%W|)kQ(2{F7Cf))@K^q)u_w6rgpo>{^*sm`U{vU=$X)>^vY zOot@h2BpY%9SBQJkl0!eeFbUdf1!-6x0Nfx&`|iK0QDg7H1942+;zr+iLsi=&7uu! zTINGFIVE{HAf%HX7@kTz?(Z)L#LEH2^zKUTF}gnFJvU>z2sfVyPf?k|+xb^%G%=%M z@9aRLqWs#}bnIq(SYj_ocF3QbM@y)a=AGAQqn=BUpm7Yp-p6tC9v_rxnFu1s`57W} z#RUK#00|8+Foo@5IMFUQi6mHS`QS{39!ee@<6jq7aRZbr8N8C(mA&3lFU6vXFt(mI zVNGc_L!EN3<&-U*d)A3?-lI$R9045xa7xEy1oUUpS42IfzxcPbNA~XT`)q}A@7RPB zy#8#O_hh%F;wom*P!X-GW;-#?d_%(%?lSj))`fdCZmP;vJ9~dF?o-j;fS}&?qauzT zEXP3{rc4!z5s|L=e$-3fZf*qW@`u+`XqpSIP&8 zj3(?Dgq2&IJF%2$+j}A?zELN00FHkBjsl2&RvDs=RtbOGp#jg8VP{{}GV1Py@~v#~Bze#3YWg8m5EuO14ytzW>WA!=?yfWfA<610*!gN5EVILMpBUZ= zX!TKCOR48j!TUP|qT&BxPin61n_<4M`V=>!HW?w#?KBO5{$_2&nYwWQEHdDR zPKhPARDg@?N&~th=}b)2nz<|f+&`B9Au|otezm;u>GJ9L4foErUFo_s{s^n^$jLX^ zP&Eg-@zO_qd8{TjpylaLiZZ|h{t~9gfIjh%lz-7HXzS|a8Pj|36V!L-7$nkz_%|>P z-WS(BybHkeaFTOVermK`#rR{s7!|D|1^aI+~JwDW{Y#Lx*_X{^^0&B!xDvXRd zkwArzM$tAA7ZDsMV~0MAiY9kCiJshBC7NRB7lcHvVnvn?L2YR* z?(U4+YrTj6rv(T}VF~6@yldteA<>flcw0L8Krsm!{W#k=`Ck?m1Ta^ao*A+{ni6$iiKj zzF0*j^dIiW@9f&LMvqNq!iyUkzlqqIXWwK+J0e>;b*vXRTz?%e*+NAzAL|sI!!xS% zyh?OjgeRw`^pZwWXf|=8GbDn59Zj|BlZ7WQ&Oc#F~WKrv8yPks7GR3zR>1g5%nan90TEhI1>TV26omLt;SU>HjFyNp<>WYmFy6 zRYOO1aR@0IX4O8tK~OwqWPT-boL41H1C%Yp7=nR>?aQA-&jJZ8vjv@= z8usL$wY)H7jG|30g+ofYta$E3VvDAWnm;>jg{eT7noR8$cs;I=V~_Ij&cKs#dguCd z8~*_irT;#w=ADE~I(X^T<9f)#HBx_YCHq#S<-TAQdDrl5bRjpNOk8S2gVQzRY3DM* z9M|x?nQM32VpPwbdvG>sA|Y%+q5{u*-wk zgiy))TPW7n*qMD;NdZfg6Zyv?)*>!r<6l7Hu!~}7lN_@nxUYlbxb>nn)%>3g!39|5 zo5!b$W~Q|pL#}7`J&pEBZ(walTvt!Mku@L5xu-{60jb^|+x?N%NU?%vovTVicR7jY z^?~2rsxq!pUgCVn1FN--pv+Ej!AvA}o0uO7)s5$izS-+c0}SL)i${UW~vAoxW_GA*OWQy^2VX{r1N=n1>zs|g2nXcPOGObwai~pqUC=Y z+{C+w`Jd*6JG?h7K94wTM*Lp^Gq5SzoLg+R-K@;MRwd|X%4q7;AOVsn=ASB2pTnt3 z?A`io1}r1>&tS7B%XMlf8^qI2i(-@oe%!$7%ko@EYJ<=#dWMfe}-KkbzM zHZ7S|HYKZItCEx>w9S3I{raaxSOJ$h*;lvUl%Hj$K|CsIzyBmSRJL+aDS6uwkyKUG z)zc!s)2=4t;{?7C6S+&s`sFga=SPsB8b@c?s`lh55EM|0eJ;$co34azz2_L_A^EmN znj(uRHDu~)gc=Eyk3C@8vSOm$&TTskBcgZl{%#}}u(qMnu_GRtQ@Y{5O>&BqeD^o) z2mds?aOjLYGe+XjUp*$@ySHaiiG%|=SIk8}%Y4Y639SZu?VpgaaE!DDz=@Z!4kX=_ z2Q>du5Y`yxAq7Y!AA8`@umyoz3Y^v9m3l20XACZ23JBUuke#w_U29P1? zBm#ow%I@`(5D;8-?va!|3-59X6&s3CRkmF&MS!>R-8uLB4nG~10xOon*H*|w=b=Ly zBfZOEtNujNl>*bghX*O=(-|q2FKALFAr%xntEKM=W<+KJV@Hp~^sHiBTYSN>TT}_9 z^y6l7Z~s?nDlcQ_RoC9xT3H3-&>3nfjeNG9zYZOMFMeY?(nt=ZADY~m?miNbR0x6#2b(jw#XA>vsi+m+VhYSuQ`0<7Xx*` z(j8OR`AGbH489%uywL>PQEMUOj!cz?zqM_?hA`+5t_cdw=|J{(4b-SBWHB3Zs~yJ)_nV^Vv`Iyic`u^9&S z$nAS;6&ndt;fZL2dIfZ;yh@5&$#>v#YN8R=imO`$HN#IMPXl!s`9Lpy?;a9kS-t-G%U|sGY+Tsa4N8K34R;lzq zR=?&3+`oRL1PST+(gX-2!8bZ)m-dfCKZ#@>v@~$T)Aj+4hsPcMxa4oh`RJ zoSJkkrHfBk(dRywa$UPCzkPiO*77{c@|?Cj13rLkZle{ly`|_$-Yw{MslH(}hHCpC zWG!#JAVKCgtT`Yj($=I>?zz#RE*dpF&acyc18D}&gf z?2-Y4EFWLU9Mk1cWrwe8kQHP4Sw zit=|=`F>Y-Oa?hY>4L&F%Rdd%yQGWUfd3IuLbI;xa{lRuA;FY68G{?}K45_B8`9$3 z{WGqbdQ*~cJh~RT^fb8So3_hGg%?d;RhW{++;l%F@CmMxM$QrBf}T+`Q*T>?>n18- zfiReLTid(kq~{#F78q4shX)7$({l7x@K&4kv155Ex$o`3n?{t2goaOPjZG7rE`wi` z5{^zjnE^)>5s_1OXxO##YNRaiQj2#gg_iRSOJn{9W6~h)Kdy{_w~HB)RN9rz-zkpQ zVK|dbYPqkUC!-~?uG1>kClREIQ<3qjHLN&3?^)fA=vk`kEfTOl!I;quIpe*B6%zd@ z7sj5TkQgg~L$-bo1Q$^_P0E=N+EijTv*K%}wRoM|;I}RH{_~3S=~_^9+ICFL*Y0@_ zr$j@hAQF+<`aoV`9Y}SuZzLcvL$4Z5$?beS;nZhYJC}c5HUw~JE2eB3?$U~8td?i3 z1qMYa8!*Fe)NJv32{`7>x6KBdbSC@-TBhS%mcRYx1up zo2L4liinmuCv$0jhN`@VXT8*|SezbfL;%@vM~%o#LNcnVDcQZJAw2rsEXmT7m6a7B zdj@5kp}zmFf3k=T^&swpnIi|hGPrS9?b=q|zb(+Z6Fya)zV`{Z^0!YvZLjd86*Xqqt}-G%?a}ee!;L^#hoC;8!g477yCV!e5w{eFq7}`bK2AE<|y2dh4?X& zyT-M`)U77PuxtJSne~7k@5dBx=~zBI`k{BrDmEG#{GC~tlyk2QVjX*3v*ayU1S^C-%0rmgc;Q8&&~DzKFX>0#n`}p?d#c>@0n)zewb7PqbA=@sfK@x+eIt8_7X*BhfYnSV z!(XwB(Cc*T8wsDqaS$uKd884`X1Eb}#s9rKhrz%Pj}gEtoUsNO91mCArB^V;%yTWi zR;YJl=+W-;3N8le{Snc^bmYko6&AlG?Wq4jZCKC1vrj1KEijJuB-G~PY5`txXXuQs z(uRf&-rFNxH{<(dXTxx!A7Q8ODwAT=W+K-=HAEd4y|>YoR=Pc&S9ctH4a(c7?GCVz zWiYwr6uuyto~36F#(@`jg76dXldU}Pk^*8{*iaTwZ6+2)<}N>8+xbNJ1!;;=-fs!( zTn+1@_SYqZ+ZDC|e9Ex@R2OxV*m6Sc1+XBaJdu@|yTJe$y-5*1SnDqL?K{WEj+9U* z+{xACCAb~@K3_m9iHEDvf-^n$(;UVu{a2gJvX4CV>HJd`t(^n+;*ydJm=W)p3ieV7dS`e%K5SyuoqML6)@cb)cA#dqRv!omm%6+=MSyR z-SAKt0}871n6MkI1pRhgQlD2yCcfZfFZQ1oEG1t<)%Bm0BryAafw>$gks0JF7IRMd z?Y$eUMpPXH4Sx~!_3d8DL202R9qh_j-D7X+u!{7bBqH0Tx+|hz=D>C?F+69OF?Bg2 z^-y!VwmaKPO|qk<`k%gb118&Ji-&UyfTg04W>Zo|Fg)~ErT>cM!*R$OS?9KZh+b5w zUh_+QuE#x%^f$9Js!ksUL?nX?Spc6E{e<|tQ}&NP$@O5zF$A_-F^uf2B{y`rh5gOe0AVLTg0VON}?Qr8MOO2$St*9K%Adw z;-F3QX%VP9@Lv&uzdM8vLREMmh zE@e9~tE$T1G?n|@>B~|*YI~?3frHkLDfCjhZP49H56zCCPx6tjtgA71n=|6!C@sf+ zmm2eDHO9O_tv7dBC$icGfegkD_F_d%uo(I9vceo=jvpPlIezHH3TvC`-ha^f1*l}-PBr?R@8x0Q;2l096DCeyNC|{iQ2{y` z;2NeQsHA!~wDR7Aps&_7_;Y@vZolWDaTTU zUtZo0@J+kOT}*&luWT^Ml5`=>=lV*zKiI;Rr+%rymH!BBO-hlvCodmbLgjvEehGJ{9(L13+ zJi30|afVHJJb0JUW|N#WAAzeB7fk@v6Dk7;odfjdp)g8^tblHs9(X~nxB*S@mV5t< zjyjkjQ4W`!Mke^?J&-El*z3tdX4q_Aoo5}lyW5nv)OBO};l($yWC{14i`QAL$EtdR z6ZTm+3opm_NEq!k+j`1&2()05{k6EipW8Q+cEKi~yh+((iiBn{>-e$>Uk9caiAEn$ zcbOs234>{UaaXqA?>o|%uI4xs%0Di0(0%iGXvV&=hc&(5R}FD_>ooBG?x*3ywGGF& z4wCK1Q0=ocYmVb~LHmK9H-)M*`rkD!=}bVGOzU8MWQxdbEM5a-O{wT=hZ@(qd-C@X z^&1MR6d*(Pa;)^O0Co{8D7e9v><@^MK?KjNN-hN^6~(chqWgeUi?nwZ8tUnksC~s9 zz8|C^MB$e8=7$29idGLK%5R6q+TcR{guj756|lt>KCd|@Fix;~&7HA*1UG8b1XLa@!b#X-b+FDm4TcV&c~5zTMw13+>#o1!SBD!*=j# z`DZY+BECAfS@Fig45xt@`(VvpcWq(c{|RYoX8vAW03dJ-lER+gd;F#+0xsVOrQ#{L z9y95YHFC)p3JRCK4maeB+9JdR=V@@YUvM812D zW1|+;Tz(!@k>(=?9k5N=ZN`EL(A_yA#y8G;HDw#HXOTgL!x>15s@oLTYT`6;q1lxfoI=>;k zG2w(|Z|~0EN^aiuRcb`WAN7`oeRoZy-FuFSm^C~#a+YCo)(_&JmRq3_j+bV46!=_6h}?g1n0%wXH! z2Eu42gdc_7n5p6IP>DVhnRO9$^WG`tZsHjJr5Aj*{56HpmR&7;$e?6r$Dzjf!-KCH zX-PawkKvm#Aw~v=CyWUOSd;gsVb=u{WUL7F%eooZL=3FW7BYVq1HTWZZ-x5hS#R#H zb;{v0r(Il}3MqjewZyBTVs>SO{?!HC2Z5FMNIwiWxAsJFYTGm^7+r&8^AqtD0sH#7t7OuOgi-&inSi$?q+U%+E|(Wi zfI?R@6M%YkfC&T+0-dHvb`$S3Mmxi4yUvMJ|Gziz-#uR>``S*MPGjaaut{`E^z8bv z^6};>HgKu42qYp!b2hvYX?X$EknW#9f7T-h1ww56OjmB%e}4$(6KW%uV>a3xTY5n! z>9Qp;*%Ysu%n+jEcI703S;Jy#@Cx8bUT>~8=NY{nJDF_rQnU(CcI4$*L^E-n>Ev@s z4^KQ_E3fPIsaJkQEXvhNN?!dTR*Z5a?eNb^G?XRs)31W89d*vFncDh({&nAdCG`mk zHG8LzkX9v}_HSY;w2V%zDIbHHD!)<80M0cBYKzZPjbm?35QfeovsH*d&7U12F>=s1 zk|>!#Vhq5ZR7tB)mm99M(b5Xumr6JNVxy}oVIe-o8jv#jGTxn8*d|AaYCIj})5xtf ze}VoHU9B0FGgO|*{I5t5>$rFJLe(s6~{p#KaMT+GY437=y z1_J5j6M1F<(ILLmt%M7N-L7T!iD;4{23bWiX5|%DI{nS>N?GiYppzrAt3scqsc`QyTlj(s>J3bFD=)&gaS(-?!@;N){}? zzS=3t+pm85MHKKG06e{`v+YTFTPd49h*Mku3)| zTLvw5c9mzF`Xb`(H8=k4Hzr@3HRKH$rA;>({!-DWSnH_>pi?rkc@7gdMz#DMX zaa-$olCmZT(|%w7I?gN07`) zc@jalD+Ms?x&g^83*M3E*93(*1z&DAH6Vr@!a!LP61I&Pc&*F7uhFQ7&K0glRtC=p z#LptT9T%NZAS2g}0CoJ#!#$R|^bhMKh~J%>f(7R3W0i-{whW?^rFlBcFPdId25Et; zEg=L52Iv6>@gtse#|i{MXbuyIFKAt=>M@=NdayHPPOLQ~0TO8kj@uG$gtogAnE?Uw zL8hyln*r5PE>Cn@hO4&fKZW-BkfJ^lKant6Z^ql7Y^}NkgQaAh)282TP$_Fx1F5-o zfFZz@@VyPzy637PlV`c3#Tdd<$ol=-?o@D0O5z{v)$hg)X3o19OPy?<`WMktaVIy$ zf_?0tGpk_-8E5#WW;b95YL+qmSQYU)p5tNpvSW za3Aru>>p=fwjNxd6S63Wrt#k4xP*%VF>xLc z_y3&7ko)UmJ9sqJTrM~Hcj+H8eQ4^v|Pcv{iV*#eaGVgo+TkVNsx=y2DQFjwXOlCs8-OXy2&=|#sa65cu8YYSf)*P zwmN!GY`dJXSSmU3Cq3}IOL8nB(8pC)P=S8-cocCppBXsk;i|GED|JZVS& zBb7Rw{A!_sk-Xg2QSB`=R4ecz^b{~H&S6-qa3)8u&-(9QTzpvk=H|*K^g`-QJS^|t z6JrBlIz?|z7ObsP&j`n@i~-bz^D2{qJYkBKE{Q41@MIE!+0>Un0FAk;UbWWKM_t9= z<6Bx<{Qt@ZyL5Rioz}W9JYmRZkh6`ImX+jyW1vfThXG{QfO+~xNTe?SB23lkkfM+9p9Dsf zQ$wN&$?w~JDF8vu&Q6x3r#yp!P~2luQLA7 zx;+K|1F_AkZIbhHg%U#?=F&|iiEYO(#vu&T8 zOpML(*|xt}b#1gaAWnT86MdD#51(I&>8M@Ph| z{$VnK?^Rr?h6Bmq7eEWf_Int~%rBDmSqZ{2$8{GrGEMGaKBmzGkE5AMmf6iPBf(Vyg5j65hG=4dB#3m#n zB*OmG4Is~c<7`!igotQcO=4?;dyM5e&=q%Kf&)j*utvnQ=!`?xj;cpanMi+>w52Qo?us)fa|W z)A>Av2Cs~^}$9UBc3c%bi=aRp~x{sW;^&D@LuiP)uDhq%BhZ|IBgZQNEhV25`{<4wQixcHg(s z?v>*E)1`2OT~UH^M^ZO7(NIl?Xl-oI{?Tt8JtV^gdo;!R(3e9RcZG^-lYq}KH20tI zNGnkUe7X9S<7xG2{rlbNfDSltYy_HX0A=^=%P!&nv;a{6QShI?2RKJYfM!W}Hg2K? zy14&bE*whYw7@1gzsA`A?ooASfCTTLid=M4r+=eg3#>1a`ai!|>f9yT0OO#>)tDmA z0B2H4dQaD~|NOKSLO#^1wmYa+E`=3ud%&{QpHCCSL7Y2n{K*!pfa_sJk>zCWDwu|c z!0Qcz;WVs1vm){p-_Mdr!V)m_$6>Ze4b@M9aQV>TM#8thi(q9Bn(Yi+9-h?k3lK72 z$N-n1+JI^D<@}rSU_6&UIJ}~_wa>$yEo)+8?Mg#E`@Sit!mGc~EXHo&NQ+ps$Q(hv z#IyzG0hU`oGh)4C*pJOR+P9Bhc?}LD1fZNM)@g{p)aU7d7J&Q_62@_ zJt($@;Y!mZXsA|jQC8d>xR82O?R`c9)$A>;=a-jB7JTWs+rLsuJ$TyA!Yhr%5tK7ylq!KqMc&_PN=g^A~GldJN6j(o2A5FU;x8k z?hz0#0YpGwCmSZm+4fGMYY%}+)CD>pS4{8^+02H*@SGwBC{>*ze~92&{kA8{9ff4=exFHvB9-?gy?CH=1gCm%aXkQ|8M^VspP0pBl+9ce6vm2Q zYy8XIf4fdT(rSE^DLhwPri>Ew7hYt76x$3f^QgE25>x*US~9P)5C0np2kKyU$-~}A zX~98G2o>IJdhnf}M8rTKMOBhKX)~k$R$b_;q8*HxZkKN3@A)rv%|cBjF9Io40x`qX zVW2w>m1zS2VldON+cVn{b?HoXV(jq4D%MC!G3$HGH*nZ;NA;x*qY8xj0a~{C-p6=j zfrcx+^40a>ciVDAvI%W0kU1>4!`7zOU`!yst zfL}gtjFQ`WF-H?NDP&!u=h2QK^#>41IZBak3KZEa9b{RkYk+ zo^o=5;rzNPRrc*ez=!dWnmMQ2`Q{}Tt4d%pjbyJJbZ=R52@LodXgCIKe6Q(S_Y6&& ziqKf27B22{!uY~$W}yCdEA$o|Vdmlj>A&PW9kZ%QIPWnGHTwvnjk}BL0hAP^0vv@D z21dQ_;_@rm$lwCW!ph{ze5wpsxzAS!E81xMHkA2@WwtmvccnkMJE(26oVY?_J%>&X zTcaG(PT6RQvh^vV&58Rd`eVxy<^|SmH1xA_glm z6*}E93*T~Kru3aF;W+spkS>W>H{{J9{E_Bhh#S=Q2a+_6{7{KWrs-m~&98@defF|O zdpK4?0I}V6+nAmli#?b>eW)D77rRdbSu;K`G5GrZubLfte-3T5;4D8pC0#zH_Apxe z4iX!dAYmTed(3V`4;a*GMD%w}NTYQBfYirAS7}@ENmB_auE|Y=%vAnZB$;#0G3QgNad}a+3zya2q02izH zTjGbWDJO6-gp<)lRD6QAddWHO)UOAe`{M^Rt^K?%U`BlW?KRU|4h}=5#-7YdH=B1U ztv$w^8Dfz+yjE*eQ;g30ZVv$5T;pks)!^JmIxjw91(?o zts)wlD4g{Ll!Bdv0j&nJ`kD)ffCOX5v8ZB~?uf_GOekk@TB1#{8-FFGU>=RcVXOY(i#RzMyGYmN^f^O5 zWmfTo8EJ3c3fCV%&=pVO9aG1VguEUl>Q9;E#6iiBb~_5qdJpey3&_XH_gStEu!>;J z35g6!2k_yA@_TJdz%DgS(bmCjlqf&0_EHxlk*_W+igJLCm6KnfaTs9U+tX2PJH9m`^>bJZ-6 zEfhgf{B;Fou#m00GL2C&C>9Yuq{7kqqeuMEytezA88`|9*5rz~*aj2?Tcgm3{YRT;yq>1y)C z5AIPb4>t{JN|x$ufldj@5Z66a0d2${boclsjTu2(6!J|m0_UiQB1l~kn={-kk~NEk zU(WbfQo5b4)?UG&wilwQxEq{4@QT z#nD*E{Ucz(1<1K{)xBX2hX+Ud|C*I$W>>vyO1VW0e18iiPfKrfSi9S04b7}!50-!v zc@Gvrs-XRN_bg7WGwDshLI}p?3pG+Sy>JeWR|e|&8^1|XCr}_gde;j zY?gSB8{crbj(HR)1QAq>t*XD{C zyw+UaIIO_to>A@~vPwk42aZ4Adg3zXzFop;1!jzA3F#U=emAePq|Lq1`5DK1DWSTa);O^`!7H*6)h?Ix|D6|CNm~Pp&V6fFkcNDtCs~gFr7+&WF9*R3J5sS z-e5{}Z(dQ>o2u7Hc`0MaDr7x?7LFCCYL>W7?q5ZVjHbQW%Wkr@-GjJwKK1-eH8NX0 zv6&ouTOiGZFoLo=>Rhy(^#O9m-TC^fW@1Uwl#%5WAX}CUI28DsqmSQHDmrff{by4LSdG9}T9SX>WnoD}GhF{g?Y|YQL<#{0U z=C!LHU0z=1iu=TZkWZ24)k85M&T~kM0x92|w9Y4p!%)KSzQ`Z$Q>T5pM2A(sYd=LW zDuGq*jb}t&Y`$~)kL`+0zSwS%vV`u znmiKKnjCIWlVd`*?%}ExK_pk&9)c`viwZb4hNN6XXsRuMm6CtQHx2?IC}n9k_0Zpf z0bU&cTQ++4!wj`U7DgzpNL>oeT{&<-1zPkDN0NxGmnE1U`x(@-C(CF)ax7>;sH;l@ z{x87-KFi||l5D8kvuZ1y6QkwqycCe<&E}-=IkXLExd0sYzkFSw8h&$6y5s^Bzkt-O z3svOsZx;*v`#<~?utocS;mKby_^)4aBqJg3FFI1+0}DLKk7bKa-`)O3%FiyuQm@g{ z_^0(z?^66>?Rf{=VPg3H$Y~F%$U4B^%xc5a&9^~;69}ZO^^FV6&23)zYSC=vX02BI z>U90;Sak9kk-p-%uRnwEj;rGc%JIdgP9# z<1Dci#gJD`UT=?l&xJ6-AwLEkfwXa2s`6tpn13=cx zgC#aP9dv0hvCt>xKz8ZrhOu!P)Dp+!=Q|GyLMU9X4*6!@g0wd^jZsDwx?`ct9D2;r zwdjA6fMsKD8cD1w~w>F@4o@$is4LM#8@n2~BxB!_mD%4s$O zbtAITi>^_q@x*Oy|7{tT^9UrMH~BOtXLdpQ=wr_U&oH2RmiqPvW3=$TTUusVP)b_* zoE9AtU{}m8mXsx7jWKV-tLpPq)b1a8@pR3Qg`{M9JV_ewDo^PdaZ<%xP{!72W z6}H1CQS42h*Rn&8ARE4rA6<=_*KaubZ~jD0T#re1V_gQejOmYMjRCLYVUW%r*Sy?D zj*ql9nJDjzjMbknfSN^~S-bI~Ml~8LbddMO*P|1_eVSLJH?K|sef_gb#g%alb%Sg$Np*E~4hEN5Q5odN%aTxxBXy1kAZN>@P1(hB>easJ z;Lo?U--KhaH;O6aIe!eLoW?QJz1IIkHa_E%_lqC%ix7W2S=07fA!f(j?*s22^@l;j zkUi09z>D-f&`WGpbWd=M4A1WS1hqVv+3CS0R)b-zyX`q#`V%NOEB@I0&EvAPQcl#T z*h{Hl%bj`I!~jGIg^>&2}M=xRPA2E$xN&f zD?s9|0i(Z`OOR9DM3_yqZimZw=K{-sLCbo`-WpqNuraTWiSKN+j;7q~g0 zw73veXYtN{(&ar3iH+#z)6s&ouHAm3>(z}5*M{&mb^zV zJG43buMn-ntN8|9qf()G-RhjTsjMZ>`0}6eh5CRdYo#bt?1ruZdOEPrI*%1AwHUag z3bosLS6ORZ*)HJc??0El3&M&1w@Xn1F=qK6kKM77G zgZle_0QSHf9|J(BQuiO;a;2AJHFhCiddFEwZ??BfMIXf9*t3koHIu*l(mSin`)eu( z0uZR|Y?>~5fR%*MN$V-tR|_GOS7@LT^Zmx51Xl0&MsrjgL2iEsq=lHP=Yjrw8pg*R zorSa~Ivvw~ehJLT&ok6|`+{~;yfGyLl`Hc2Zf0Pn@!r?3w@|bR%?y`>pS?2Az_IC2 zBJ$|TSv&V?vb{TIeJ4hSG-4RZ@^3+VP3qVz_uM=#4#PSCH# z;*Yl{i|Jz$jb>%kQRXJS)9+yQe&Tkn*{`P$T9SAkX<3=2 z5;YCZ-%=2kRg9O+3yExWw}|%Af4PBm-g`+_?7M@CTq`UNy$}4$2>_j=K}Vo-Yv6Ni zQZQnph+EW8LfO6{PTj9`}veu zMlzG&8=T?HO?yxSQ)(Aec+z3e04Xvs6^#fV>&P)}|DD=N$2M8S07~-bJ6fA?ZJb`DEQcS()LGzfsD<`D%3gDO(qY* zH}UtU-nx7MsMoR5%s=ll$FWr zNfpd57tAfnBTO!?RfxLltUPn2HcJ zw#Ayy59oz57Mnh^$_r-~OyDTP!t@B9YU*y|6@Jt$?XD)G#wi`luZ+}V0%1@X7mQOr zB`C1vRG1X7uYk#z?Hlrca9m7j7yVb7)=dO>iZaxBQuQe!?M{pxgXjC19_6;4cv4Lo z<8llW0AQYYrfO0wretg2Ry4g6!4xi+#->}-h(5lp(>H%a=jk%Dv(z1w%NUQzlg?ST zmaf0Cs2J{{Ft&*s*B=v1ajsEX4sJEf*M@K;EaN=!R={;BRomdCXC$DJi=(_SRD6)ylH{f^NLBV?^`&j!2V5ouTnAQY`s|OjJG9u}jVeGG#tOIA_n<_Y$$E;bQs&1q1;F*i@efq+I_ z5O2DMj*1l=yJfUXv}=pOKX<&*s2TyVQTzM)6rY_g00*5qp40br3B4T1Ad70m)y+9~ zSy^wB>q-rP#rwB|2Tn~brZ;z#Xu$R0#%lg@o_r#VJJsgXXwt~)kZxvTMZ~Xwh~j?s zio8Vy0T`awXv`hx0uryGGBV{#T)-3S9(!6;rRUT%AVPzr6*Y54Sk}~_c87LNc4@ER zem+LPV7D)wbL9Q$UD-nD>x5Dn!|xl?eH^`i_dur`V+=o|8#!na zQ^DI;Y8nZv`|ZFolb!yJu0c5;V3 z6pl8$K@NPDmw)4XX=-Ck$pG}v`uA(PX@6IZ5kmCuA)vDI!cpTrkUEXMu!O>+ALB)# zb>cj2}(`6;`#H0u@eNRXm#F3Xg>A z;E{BdfxS5Yt^hJH^Ve>gXXHzs47_DyUWdfxG7%Q{3|nVbtV{-os@JQPK;$e%z)l!Eb_5 z*-~_o#~aUrB|nQ(m4|!dZe#h*;1zyak~^YSmn#$|mzzFt+Ph0>1!nsA_Pv#?K8^mg zZ*WmQg|{UAZqv619=hw1?MC8;bYzv+FCSFQzR#(XR6`~hAgnPg32O0 zAM^yDCkb@TIR!oShLiElJLTueh8$E1@StvHsD_q5zkfKDeZX|Y2@@epNzeZDuxu<0 z)9_5Q6K~9}RD6w$e6g>IJ&|Bl^PnmKM}z01-+ooXZNw&RLVtrz`^yhE9#X+DY=Ce+ zs<3y|%Dq8Zn3)e*rz4o^<>Fs;Pcs879M$A?dlkt@b&Rpkcp`-hCi450e(C zMaXe(Lw8Q5ydocL&kH@eE?Radi0)0yhkQ^7-?( zhPHpnD;u`#^X~~ZJLrQq8=NWUN?OwQ2xBR`uTX-<=kQo;YYig z-+8dvHv+{U`%t!s6K}~kyCSpNW|UP8SBenkC-2O2F6?v)|E$l+%K1fq4xJ|s}*NnEB=3fTTK4~g9h;I$XMQ|wT_NIm3(cUZ8Zk{ zrfFs;mJpx$%&SpNI(N+y9J4MoG0M0VIFJI6s4Bd}9c@;n0BV*`VvoG-TC&J9I!9oz z0EEa#v2udDE%a(Lcb=IQL9WVrw5cEVU>hC$=g}Va!S_iQGmhAud7di_{$ou}?03}v zUObELbAOoeKEG$)a7_BmPtRNSKJU?OL#D4KEQMn5_S3Zaq~urXEylZ5Uw%R#G{I3| z9aNQ7C8WS)722C+sgL^?XM9D)oMp+67=p&D( zroR}BOHCiJBwM~`p*p<4gSX24raLu#Me|3vf-P({6dSV&Uxtd_qtCL+t_#e{E7|}&C8rl!9HGK zj*2ml`q@b)VCVRASv*<~=^vXC@1iFET=Kf8CVeClATj5KBYkyQmlaI&zs}Mm;u<3z zCiBTu48Bu1fthP4vm8}d-@#cxq>SN>WDQG1rmfcRwQqB^rrHKVAy{u=vo2<&xx3ds zyJzUND&tmFfN)qj#-v#2@)>gv%;&jD`Y>Dg3{`PMRH>u2f4uW%MrxKkw?tg32l};7 zB^7k1%wxmly*?BWiPW2ad&(Fapt0a%NT}pl@(DY|*)og#*Cw&gDO%eSn${m$>sQ#2 zIt-xg^&cDsp|-3@u;@PnY07)pfC z5#zi^KLt4$qQ>>syV1RgKHKomwB`pJ^~y+fFR!%ax5G+O6*7xBM#uDW^ZEc|XGJ;u zE~St=t7v-~K_e-Hh3*+#^e8(vlH=no^{-@Jb(Z<@)RTZF8(m6*6{4*LQ>@b^$8%|0vd=#^ak~))r1MjMJQ}I zANf$Iy$~FGXou5yIc+Md9Hj}7kTxO)qSah4_aImT%^ErBq4*fK1Iw$kK_4{Z5b0N- z{}vPwD!~WcO-!*zH)^ihFSZfs=4|{$(D-eA`JIq; zZ&o}EKt-|!yie>WQZK+!<`3y|G&tS>M24N}n3W)w?ArxG_t5&IgG8fF^Qq)g->(<@ zm#~7ap5Q~nts)Iof}&5pm-_rF1w1qcuOiAkEJdM61DzHZO!m!i3^`fT2&wAYrOjEF zJOFB?mu6J%h!yh{OHI%*43{|e4Pt4Y^8fgH%b+OVKkR$yaA|&Yi%7>3(hUmIA>A$A zEL{R3-65%fbc1vWOD{?{2(pq(cRZK>d+wR%#WT+g!wZHN#C4w6H;&_TMB&9HFRBO_ zD+lksMLhkK3<*hS3u<<1#CJ)up>}F@+`b`Gl?%;;UW(p!jMm@o036?cQBi+97RS)# zSSqUUq|VEfBvR$cHg4{IF-q+^j@Ivo1-1l%y+-R*yi5}VDEqzxaIui5hgSd+%pLd} z0mH|qyLt1kXKS$YvwB2VX_tJLonH??gaXpZ_CKN3)FxVtKP4wV4}AJpz;xEnEx{z- zRsIJQIYI1q^eCf$=NjvwPvR0i73?c3D}L1F4phLn2r#MtBeY|^t4yEw{w@6IJOtH$ zMeCWHyTJITvw~g6=0jQ8%WZ>%(np0~xJ?O{4Xkxgf7xjPlMS_Ua{e{5TjK%JE2K%j zk>{NbCXX9UY91mrjJFdXjoEPDbP+T7?}5$UPXv>%Uk{t&VA?(B&`CMc{ou}OjYCS@ z^*c9FpEB0WjOgG#Ui#}xF$1rGaSSW)>1Mkk){I-=8%%V=Xvpz_0ZjA)=l3OvB9T{BXkipCMOsdcd-)U( zAJdg@0cDv@)x7trRX4!}3PeYrI3lukjE9;vh-zCOiYF(`t?sBn+vj!_f~IjMG81@o*;C;`H^Tt>MfzUotmmvZK7+Bg zf9k=Ejn(S&T2-^vn5UGQ_CiDCd#bN8AZ8q$9N99q@t9ynlw`2DyQ!vB(%p+hlKVFq z5numUtwbrPd>Lk>kf(fB^>ei z*KB#dI$6}3iheAVW-k|5R7hL`6JY*VI5};do#>&om^bARK~uBa;ON_%ddOfM{b=1& zsEgEkW|6t_->eJ=giRha+e2?jMOu$8qRKBEvpi9`rBe$R*na+VeFaLsrh!T1+IN{g zAA>lxF4Jp$@n@}-pjS&Tn3$mt$PfBIXMT<&{SWcuaAGPi*!R-2TdpQz#*F#fdtoX3 z>aA(PnLEg!fP`1j?aFXk0q$r=VMk@InmM84^z;pKs7P^IUmzZZ^70^hp5lwDl?Lg5 z4NjjXc5rehNKOOyDR(CchC?~#L6j?a_nz&KIED?c4`eW1*3+dcdRqs=xEx6p5)OUh z4=-_``41LDJt;JmuBQP<7c}!TVwAj03kjf7Ht12e8z=u=^Y+3;s7Fkgnn*J(P`dpd zTwKg1koP$30B9yMd+UA35g%KFsO9D5HDBxTklXVSBo;ua0g#kE&Ui;=s@IRL%UpoK zdJauyn%vFDC+Z(2`0+8=F0Qj>_#r#M0q?VY^z9FRw*CgPiRTgEnHDV5NbDyAh&-_} zwEXwm*WuQnQ{mdN4~mcvQQ*xYE%m5It%^)Kby1hHtOKuKbKZv$Ejl#ThImxJtw#t7 zEaJifE5OOV9``C;NC|sr$Qua0^2a_5 z6y7D}p?iIMmq4A*PeZN^S1Qpdb)bRBg-U9j=|tTw1l(wNSnpDt`27JhjY!+t$3-8f*ufO`4VzVN?-#&jGqXn;Bb*Yv*f(4TH8JiY& zcSgoD={58jX3|;;MPz`lgrj1a7TS+~O#GUo0T%^I#?nnGMH!-&Nkc3wz;9 zhlO7_oRqcJg9lZM@gMMnq+7zOl}Rs@w^S8n$v=y%c) zq-vIJ*^`qb-+`)Zu8)2qGDKZg@pslE+;?luGad#jTRY)9o{HC<7pA)pOjSn$**EMwk$ z=?x1}=-yWdKXu-Q452yDm;m?5IuG0vSmFXc3VeW03Imvz1PU3nQ1_935OO;nR@Sym|)sscMqvwlFweIxL!=P@RV47^^a4Y#`p)B1Z&PuXQ zyTDLiNi&96OF+YSapXM=@2A@9kZB06_OzmM5?UsDB3pkQ!X=2BBsMbuEWK^oJwJ1; z&XywIP`OvieJAFf~2=Z70!n(+r;)9|Fzx2ZjVlN~XZ*&Z@x63bnc ze`h2*G+ktufAVnhtU;IAkkO1jU$>(8BPWt!@n{HfxKbJB`&S7(+7;5LA;f@u3;^qf zx4*er6hwc%uYSiB{2#yw7z(6;NlNqJ$N)RpMC1wDCX<_&gs=#$4xi994hJxZ+<+hu!kUL)*%7b*eZ-BT`UAb!+w1X91I@z z{5fw_zv{P9dULLFV;>bPrC9hMbh0g_dq`2Zrw>O2 z{6K-c>A5`d*e=B>N}T(D@p{VonelSvRD48*OS4X4kok40kFf55>LoK6q@gU!2rOOd zuwP>5mImF2pJqD239I>o}pjR$WY4a5n!J_G5s3i-%X#Z8#@2hnaH;Z z%t8kUKP`d{53J-c#pg+~F(MB*3`kB18!x6ri<=cSGqC%oB#@3a2R~7CnnIO%LK&i* z*%w5ya)^0;q?%K|j0@kCAr#%j~|9UV6fS z{$CUb?LoP(#rwPh1zRm#XINiEH$M-m7%hE|-cfD-iz7`B$PMs9w-Ia+m8sFzVNpbf zbbqEf(s2o4FH*in%~|!m;_%|vySi^%v;Z}UO3#LyiJEKCywv9=*XPVQ zY_~7eLF;YG(wWUiE?lWe9M1hXx-*%|c}6FIEoUzDsptZL@d`}+S@027v|t9kQ?XM& zj=nh5zy+ve?p1sRFR{b_$s0!gl~b!QixAQW5DB;Kpnpp9DgKqP#;=C_IYOrMHiqK6Sa06&ieONW5g*AriCjB(_PlmdJZ6`M}%w!0{(H0wle zr&EPX09@CO7mza|Ii&I1Qo!0o9ixHG`lcu9K+aDs@8$ITn*rCDtPH_-(LI?6zVv+x zv^-oU*iaG?yyu0!tg^0dKyqqetCkW?H-~8ZX-2&$&6Aa2K@`M#3NP`@6vpdXx~(Vk z{xR8|vEwiB4g-dhwaH$_k`fY(V-03Y=GWMkaWbozbLmHWgCu2S<~ZCcs~pzUSi^2+iO`kD z&^RGx?~2qV(y*!1#RT}JC1I?98^C<)M}1WYUp*-9thf!-l4Po}M7v^j+Geq}hWT`@I>RsTaAi!;Y;bJip82=_!3%U-@mVA* zOyiL1wUT|UkutcBx#DahXP{@b_Wm$o-W&GWt^ggyD|fQ{N+ROwu zLdn*xe$-GJjipN*a-SP5a&^bP=FwH>>2(AZE}MYze~k10utL&|AVQG-5~f~D|B}#f zTGU691uqop7cV1pfrs%*r?hKsY2S0e4m4FMIO&A|A85kFqHuU*T6;PqUu2)i5HhJE zvfzL;nv5#~0BjdgaewGu0n7=ANrx0fHg@rWZTiO3D(u=F;KxJ*Wh&zsgkHMr0r1Qm z1M#QSxf46vEqIi@+FRbjYA^n(F5xv0-wsngC;L^sd4~?@$YSfZeNWF=r{*E*JL5*Zc=z^&R(1gRfWj(6&X~ z@fBG4nRLTB$CkD#Y^+~N{yorXm~?GiR%}=XVRcs&HJ?`GH3#|l68>P)=i#^Uo(B(5 z%tgf%4-V&Z7~G4@?Sl+^z@5Kuc|x_wl-rv7Br?P2o_%$QVZ}Al&BFM4E!MJrsB1XT zc#~#H%)YAKv1kj(k@cU0?Xut`3wp|T&}sznL$ zfEEPp^9~xqV!gw<`7{=Ur!SLOOOg;TTwIav!NEXp!12R9oBb*-H2P)^Q`;Ho_s7@RCPycj+{d6zdkW zmhBun=g(!BYS-nD`iwy%yTBEao&vowYM>Mi>&M!neQ%SCCZWd$0eT@GsD%FwhLR z(FOC+I>?oxydoX3rl;c9hTpwY@fq2GelnDamJg?3Hgv1<`AH};dG-exjr?#B%}5fw z_kgDWnZx#{aC~Acy=Ba%!aBVx$nM)nyeI0Nm~HA@PF1D@o_Eo z=7t4CSQ2KB`5%w*M$5Q)WpOn<4;+nidVW8c{nAW^GZa&r7TuognYpBI-_ARH$g+aJ zACyK}W&+Xcu}iVtX-b_o56-8Wwrbe-DR`&sJ+GsdN&xyR^u{F|RH~|uMB5umH8jq^Fb`rC=B{KU*m&aIFn1I(Z&`aVn|}emX+OKr?sbI@+T$+oxI-TbXxmP)v2z z$P{tX9$l?`LWvtM`6lFERf@@y1q~wByEWH0UtV;$I>0GAUpfl-9lv zMEbmM?spQ}uivBxu+8Qt1SF5bl#s1dW`&%|goxrT0fs{(~esflj|n6ejU3(B<|r621IsR17*ZC(RQ$-}QEfD=e| zX>*8TWqtkbF+*@w#MQcI_|ftXs7WQhg`rS7j5)U&0h(S5fKUU*0w3|my8hvB3|Ladg03l$tR4vvD6qtEtCk~ z1}CN~*77oX;%p+VNh!+fH0jJu@3z;zy~ZC(cYk%Kph$8l3y+D}3ZqC{_4p#L>B8qa zRG`&dX}CnN-EB#&d0^#mta6qK+9{p8+Z3icM44S&)17S!$hMxW%nNo~L}3SE8deJR z3LjntP&3wnuuf2luxe;b_(3?x15XEE zTD+J2c$*n=W;SBIenmGtlSGL&v^J)b(-;(kv`UImW^+vgfS#s z+;vMtkySE#37#iJ%U(ylc5=P?Yd=)60)0>jS^Ow}x9t1(t654g}d8cj@8^hJt&a zhay2kvi?#*-TKc2{?pNI_az$qrW0!X`kT(i?RoEH&i<{5m=ZD2h@*xQ2y0|Y0xd?Ey6Ddr%6YdXUMZrsWB>Sm zKnhlex~HTHUOUg(405P$6&9yHE%L8PVUTg6eCYz%=}W$N zj!0_i+HW5Mzy?4hs@RO)dTGQM0Ruj(($sdnBJw3u`}3_v9fB(_3Gxw>p`!cA{T0UHf&7O zag-#1y#3}o|Ffk7;XZklK&e)0ggs|#mlTQ;kpJ?j@zV6F`*3 z%63L>N?3dN9`2Ws(j(FK`|uPr@#hrgOD}m&D!HGHBbhw9J!=5qdDmFss$2faVm6=L zoL8pLcTW1@DhRMH_!o?Qd0iiTomqu+b*QDWJUAjj^r!)MIl9c>+RZslaxa?jFW<2) z=i?kYpq<7rcknGQm{5T~%_gFuDyg(yecCy$v8LD_Pui*x>i=%z`1z;t&wzAz|D%)) z;dPvK2*nv}gl*hcPdn)I$kC*CVTM}f%Mr+V!13|Ys`$^xd)~N0ohdPOVj-}N;@S(X1OnLDaAGVpSS!tPgY7Yh=bfPBWtIb7}&%jxhlaL)7Lxvd~Oq9`JO zaJ2u{oTgrwomDEWqQcG7bIZB<|IeVLNd+NpVoPIs{|H7|t}VBVcW?e~RylMbMpWHwXPnHY z9&Pu}|8ihL)zMRV9dvh3{PTwLJn*9%iabL4Yi=I+g>|fZ7c*M$_io~<^D&5Idib*o z!@{M07grPWwQinOWSjrujHIv^w>&5VG`XB+coKNzUt)q7PSewDqKjP1;x!K-0kXi?ZHW@r>KL#m(6Wy|tmj;|1vLD?K$V?ESu@;9C#8ODBOJYe4rJfa0v7~|V zYd^?epQ@m~jn27J@`bW$nV|@4%3n9CcN$A+0J;$9T=T<%MgySEn8)?wcL?Jv3e3lu z$Nn2{AD^HO-)}VSh)@Wi3w&IE|LWUhWq@}L;|W&oz_`( zVCj5>>ym4zC-`&;fITZber3BmZ`+rD^@JU`3*qO@($jsBP@R4A{eSp z*aG`oF~vVmOjqr$PPTtSkyP}9OaWDxEqDiLUH@%6;h)$_@7*4M`3^!k8>N+_j;7T7 zxGX@0&%Va<{kc<-I->NN^BwQ*rGI`#2a0oNJIS*Wm&dQ?^bFELIy6}{|$62r=&W6Omj?Cmhb?po0I+Y`lVYq&;# z*+4%s#k2mRi!0MXarC6nZf4l0>d3ZqqK-t~E29ets(KUtV4n{w7f!Ldj!s3;Ja2mS zucYi8`+pgFhynK+z!pGz{?F922@CKG30aq7x`k6j0LE&&w#w+7Of0l9DLFL-O!|Nc zzOQ$6bH4PN)3qmD$(`VQ;t??~m!CupwPa%2A<5+oXy+;Al7r?*GSF=0h#KWwKV`sV zP)H)(oP(}V0O71-yb z#ApuV42X;GC){<4vKES%=`CGq~`eooqAnQCIq)Q4HRHik7{r0!5Tfae~oN*lc^6t6Wx5ND_`{#11v*{)hcFO#4d0TXjcGYd(2 zt07-ON0<|bZx#ID#j}1|roXMbp;z927D>EKaCm)RQOENE#zQpTz4l9=T|j0EY}dQG zPWkgT;3K5&al>)%0YRxz-XE%eB2DCA+W?|yVz?`sEi!CUElns$lT<_brVt(0HSYBi zu{b!0@ehy-6vh8cyl!|K$_St-1{_A4z*_L1n+F9<`HfjW1n6&s#yGvL&g3DZWi(!z zq!*AUcN+GRB?f>h;94#CdjITzx;((K`t|%rs~=s{BDReme18b3a;>RHh{KZ*%d{r0 z_6_dc&Fd}eNCK754GHld$NhLSZW4q4OGw-dkZ9sAXmCkw6TRd%(+V(HtMmkh5vADS z(!;ju)1=DfbX!RQnV-pt(*&&dJm{_5l1jvAv^zTJ{^c(G4VyR9^nv|4688#%02)zg zOo<3ga2DU6s_Bnt73KM~1qdVSMa<p zLO<}g00ikTU5Er&WH2CdFA+$Mo&aY`h;!Lx&k5f{=hA*c{qn>XV%V+5({;Q-aBd%K z#=8~YakZKn-F|dE-XvG%rpWbl!Ejdf3ktxJj^zBbsVo)=AY9L&;hb*?Vdr0-Oo4An zQc^Jy!w%0|TJEJEy02kHmx*Cr;vxViS&z6MoiDR8r3Ss~m24){c(q7-g*)yxT^(RT znHS7pba81}_L^0{(n2Lv056#tC0v>@7FF2vO?>-gvdxx1`BdUWn?$#~foNUxvq}ER z4l&cH2Y!!>cQ1MPI7=>RfZXPN;h^TG_`hG0(AyHl*W^m>A`~Ez6&14Gz;a4_?B@(} z5c)GSlPLl=NiWy_b|>1pj=ti=x%vWeXw`7lKr++OyinczuNPDtC)K(p49`-0BsA|^ zFLl_9Cs=%(w=5ldO!E$mmT|nC*5Ngx%5+MkDHtfcITjxQ(^JoTWdNimx4#kZ$q?LULy%jC1>xha(n@^-_;&m^1OclL)_g@=3`kIh4c<&FZVUo920PG|YE zPFwI!?>3exH;kjpT z4(c<++QrzC+yBO3M`vvSFRU<0uP&F}aF>66#2+6AGEh|U9NBwmTtYyfN}Szn966mM zLN7=xh>C~C$-cW7OBYLnvhbQl3CF?xJ(EPhu=AV$yb?!5EaVOEyHs*%b(lrFCj0qJ zV=3fjc$`0<&6R5h#N=2c-y780G2~b^hFp&=QsY-P*pE2Z*bBmF`;fFKg;s|eD0=6M z;aEQu4}+lX5yz|6&!M>JM#9;T;T4>O`VmueQ!Tr~=gJ*9rzc>cII*M^f{aa3D)g{d zwhoO+nr}3;baesQ)HzuC$kik7vnBHfi@!aY2bQDtabs55Bhd$Vxbq*bhQ4}Sj)MW9 z@!1XK&e@9;>m15;l-AWM-vsK2((+~Xf<>{a7wZ@wzoG?P`KGAWo7Ms|{RkielVEMi z&(=(IO|BqXNOnqHST~q0GLgMtyxc;(zypN+5*gxkYz7Q&=R8>%Abj3O;~ zuY)34D_-{=DD2OORlx}wF+C(GYDi$X5m^qRuSo|%0(mqwRdjR>y_^y()7Ywvy*rWi7A|+D4mYQ^s%m#WLBzE`3^(x&aq4@89 z>*>u^H5zHSo>>J4p;w1#?Fo=BL1C4I5CPsM|NgtoN`SkjD<3QH;DipSNS~tLQCZCJ zH8*k&+`7k?y5#?tv<`DSyAmg6Wc&FN1}X6~$YrkqK8vbjc0r{QB!U-ewPid(-Kqng+ZO}82eay#>zO1nauBkZZkhzzk5iv3 zJ_*s-X+u85NnxVgn_)&wbz$#ew2uxr@b$s?XKG60+RlS2q{-sC%| zi-3w0BR1pVcn;Hm5Pj{Y)3DmV{0no$LE?a=@#QYs9R+e_-C$qG77u4&3VCRK#LEir z8LNJcyUF@GW||tXEJN z1&6(0jVqpGOv0`O>GL@}oYLow4)519!8Hw>$*9*(T#pW1+$iJK3R5*9+LkvDGa{GH z6nkVTnOA(@(NRLPoAvuJwx5-(nQ3&77d8lL?AY&cROyBq(f-zK_WtuRCE7viw2NID zBZ03rV&vczPx@vc^0UQJaLVo&w8@ye9(ZWhRF@GNonITGv|1Tkr~gtg)-62w?kJqmQ0%hL zvcBH~8g>&niz!Cys98$=*|KxG?KcHdH`j834_E>?(lUQGm@|_D%*>OIl5e7R4-dJx zd3b<}ESVVxNU}D71Ny@hX3Ay@sT^>2AdMVku!j%R#=yV#)fLrJ9^mcdxBGKX8GGOh z$%~G=XN?WqNIr`bWxdF6uaS5w4?*7G!`=@x=1KSLh}9LitL@~EZ6~#;6nDF9GYuS^=zhiEC}{x|nOb?>OJ%Z!+-K zo{gSvd_{!?*ij$wp*$6I`8vB8!%`GTHjIj`M|^ZI5_Uz1UQTvBJ&{jjdfK)7`lc87 zpWv(zSj!U1D>ra0dpO%heiJ|CT-{Q~hSeWsI?9&hg;Aud$+LB(OkPSzF8L%ATk)shwxZ z0`B_Ofp5)0o}6ez3Pd|+HiTeAyPe^GE{C1)J#!uQi@ik{Y_uge)kz@CEQozsG?!x>%$c!nre-8gt zWr`2ml;_h!M^Wvi4-E{>svFG&+5D;d;%8JPbG<|c^G0>CT;{}XzHg;~yD%%fo>T!P z))JM`mXOKW${q#SbP>K`)h%Kba{jelgy=HaYU`=0Ks9LDyC|p6#R45H=pjH4gv`Cp zKmok6a=`3;5@feLw||i!arxg`K!{Low%OODBvVg0YsDFFJl!5OpIu|{W%bIhcOK`Y zrKIEv9b|sw{5g{k+@*PkGk;i8dET4Mv)GTdER6rHSvoG=dU&8Z>127eY4Xq;mo$%F zxWHmQ7Ay5b-uDhxZ2`yIX2cYRuX}&iil?#EBn^OXER+&2AOThcy=BGO8GQ1bj@KLu z+<7P2&l--ni~7TTI1%4kjltfwDB{umZQ?v}i$as4pQN9cUC=yygQeGntHRKc6)v~R za^CCCenPQ|x#*m=(Vk~+#kCZxa(zitT#<8`W-}1uD`XDUWLS5~$+@UTJMUsFkq2@H zRam09Py~kh0o=&{vOqUCEwY~Z9~%yJRF_)9=e=TpRJYWTrNJ~F$3nvAX>=Oc@tvGW zT=~hh85)DPBmvt&C-3jx-cHHj5~&igu!Z+Vvod>;$?6TNCB0?)Ao`}TdsRB|MbkoW zWoSKWjn~JIqZo7syDqY}Ehk4&y&l2=>1d%R3| zniMMpJywVN=D&}dw<-?s@+?0E*l%z4po$AL+>x^>el_VbTy0H*rBb(~^zm^ZG0ssX6dD1nZn{lTw3F)*O-@`f)*-t?^aSgfqX4 zb2@9u%;ehM^ImzBIh_AwvqU#l=9&$9VH8)F;%^o^c)_+s&p52SI_SK(H$D(6OUtUia*QVym;BUOzwr-KLgO+OEqu7lG3X{MW6agtsU z_oV%H9!iJ6OIXuseo0nZ3Iu+UuQ)7G-tlsolm(@1EU6#MY3ZXF)3j_q(~7OXu*CjKaLswn z_uJ$Hc|zmt`+xompqsSlGBqo-T;-l_If1!mH>0OoUQxEt6|*W*xCFfs&j())gxxqN z-K7~GcKQBXio5$LY}AS9{P{zVom2romkoI*N%jepJ3%b7!KezWHv5JnpP)$8KUHn? zG>?%Qx4N_psP^b7&Lo6k0f+2Lgg(T--gZ(>1iEL*TRo3u(wU{nFWbB`rKZ0igfR|n z0XFBDKc_@+I8VTuN^J90b|z?P2&g_f&ww4kzfKVF7RSl{06vfBoSmPammCQ6;*Kuo zGPwv8p{$=x*v>@dv2EJECJ`El&wX*{w@m5UxV_TLMyX}}gAZ-4=BHYzj^1(ZB(2f! zEJQQq3!&)*DT9ndYtCg9R%J0sDXCl)gU7lFz>)-a(r{;z&yS=pEYjf*B3T-in=WtnYL;2 z?o;jlyI&^R`MUHfbe#m8kh`6zXY1jgAI%#}7|9r(@o~FV#k@8>KQrHs88IO~m9B5q z^VE>ss%LMVkZ%8H7mB|+%54xdcYtm9;_rMVb>U>D;v>WTa~#s79n`+|z)sNU7-H6ZzlRmiCE2~-lNQ3=-K@N1VX z^ptOx|LS->^{pf_f%xwUX^dk0;|j;dBu9r@Pmlr;+l!$sKH#v_!`jvxoLwf%FC}4W z@?^#3@O_Ar`jOa2ZEXQT=kS!T~ zg?9+HDz8_pK$k4V&~ayJzU!Is=sWK3!eUzw)rFq-KrDenj-@zVZhNrx)LENx1DCZJ z-1rV-p?Y@GFb_QC!J}deEhzr+Hmk8kdufe;e=}^Pu#-Da)#QJdinCkblvmzbbZ{8jj$of=VoyAt+EI$F5|_^+_`w%YP;x zXnt8g?OpUxS6+k9%an~qlk|aTw zLpRN|3^L$R5xC-3!0YlHy<#B@V6<*V=FrbQGYHphrJmG8bPw&PQbTP;aeRPEy-< zRS!;vzG_j@lf`C*N4R1j(&xTaO9xh`;RJqpSV2Fi7FifxJi8L&g;Sl0tLGzFIc=Un zPVltX@aFVp^ZEJ=FJ?L3&-P$^-Ut3|7Ne>4sy>@Y{LJJ|2ieEZO=<{^UFI2^n%p{w!bF^qn7+5!mYD1mX&VGr(%{ME{i?2) zet2*5@7TpOtg-IGRyU*&egRS&bgnN?mOdIrAAm4LMjDX0A?h}x1%~^N6gh}_-akQ7 z=nRG}7o|a_a4|KQC*RsSZi7b1!|ey4QUD@J8eyMRSje@F9w~(Le+jIX+c_d14o`M! zUc3ByG@7r}rs%c)U65M8pFr?CE61LaZR4g01`h{IodY+B9)E&hk(N4h&4jOC3ai9`q1**6!< zHY_If#7f)t_!J3~^FPiQo`79Cbx$mN zLwksC52m|M_SicEOWZFrZnQ?D!VEJoO#ACrRr{OAw7ropZ{N41euQts#n&l51rJ`M5%BD}cj3HhbUN;ZIS$ENO4jvRR%?t|y(ibg?khKz$Z<)&2}AA|f%w=&gI zejHf5{(|1P_#fFP03?DD%j9~MU>5Ru!G{}kHchOn^nbMg_|x1^CtFy+r3?^96u%Gw zS2N>(_dxE=@AUwwV>H%kjW1E}sHQ?gr70q@Sx`!Mz2Nnh{CMBle(y}AKeOAIeV{}8 zVUUq6+IgQ~GPa7h^2@zx(Fu?m`h>4~$=-FlhBI?VgdfHf+ee>h%r}cnn%)mH?NbHH zVvi%v^5P6zYumR^Q4X3S9)|oGj+!aJmH~&7hgOBl&A(O=gQ_gFrbp7c%9M5yd4llx z-SXy{RlJk8S$k!?V%#r0J$gZfv}H=+yBC7Qa}gm5=B9-f&AEK9qgd-mj2Xr9WuT_; zabNH^y>y&}X_>8Mr@-~se}RnCxOb!IV+L}jj;lZvc|p+xDd*d?jN6zXamOCLw3#Y) z>s-9k3Cw0eL{iXRgGNV|=SIDqbucX&!lYpvwpDK+CH!REp#4es$A;vG-N_y-nb2LY z_gT8eu;0Q$jw%KjJ0@SgoJ_>|BHB96LXZy_eDdO`#poK8q2T^X#!hVM@AI!=sGBf~ zW$U%1>=8H=40L%(%kwTFi!$Yzp+2%^a~vcnt4n*$aY?Tkg;?uuF9@uk9(iUKi?1Fp z{4jOZ3rnA{-ls_4c=i$`R}iy?IsQaH7epsz_SoD~!n|$;*Ab&cvTn>$d1y;ZO3K~0 zqc!{)tU^-7GvDiBkD~E9M%LSW;Qgb-O++kRB{*asen$NL8#8K=pvHewgP5$JqC^re zgUIOEH@}b(w;x&)NLM%-?-Rc@v3ky|Lm>mR`pd8f9MjPi@9bmn294!$3e+H@1gDg* zZQK^m2cxikqk-?RXR%;$+(&H0pE_`v1&!BYL3embY1ngTRQmuV8rsOoe>GR8V_EBY zxqh(UK5p5-bw@E6WKYAo{9tspBCuyD9Yf`9B3(`_fRc+KVZiR3^jZ9C^b)@5*G#(y zRHNcO-CqacKy3iG8U6*8E1?Tm{o}dlBqSzS?#$Bp5M0n;>K*U7gbu7FdCx{zt)Vz` zi#Gje|NRy&Z696h+Ll;%5>lHA)cZIbBlndI_am(07C98wX`H`AmJIY)%gO+^z4mD%LJ*Zrq? zn-3VOr<~TL#c|F;cgbpDi89*e z3MKPnz;|)3bdoIjK@VdyrR3c&?zmR@EpaBN_Pz6{R~EpGW9W%J63F=!#QC+}9mFrR zi4;|9U-PYQ&gTF2dq`rpghS!lf}*(QJvR26H-5zi=DH>0Lw&ZmQ^zgY^WgsFI28Oq z(P+Oo+Cl{C0i^rp_X55{K&sP1G5$bqsw8~uK#cs7r4jCK&cA)Q(G@`FvVCZdc2~~x zP2MgoFQ!-Nmu>t4tRS`gDEKJ+kotW&0mU&SDVHYB_&5^HLV7__?yLLA}r?1F#4ZLp*okZJIf+QY#;h9+a1j_M`~zU zKJQ09F-P4Q^-cTtO1u^H*=JZ13(;BiT z=j3tpZaO&JUpzXtG|A!vLl$G21CRD8g-%^O=Z&JM(5PBL+0}cF$WZ)#7B*JwpL*JlIy*IEk#?x3 zdf<7>Lh@iB+B`RPb{^Oe?%6~6FZrlmO!+6U z;!d314jW#ftD`dj!-Y$~{=$ZG|&Rn|yBp0xp0 zfExYnL3Fo!A9MKZdz(=OFTO1UNe{__+|Wtj@sBeB`2`36Q=kdu##5S^g_Vn$_u73? z@3VwtXDxu{ibOtm&awr??|(*lfWmKT%wpGz0F3y6^bPp- z_&j_NFz{ebY#bL#{V(LzcchroAh0gaQY-uSM*R*lZqbV5`4AZ%PD(6``-X8-iQq*} zsL(6hwD49+d@q%xAekNVzCw&w$wFvxx#(&OD=R<0w~}*-X=fj9UO6EMUMVl*rP?_k zm?v!YT%x(7ZTfWROD)*=`{mmSk;`JIVw>~NbZjG?eO^S6UUvD;YDvA)?n<=yIZtm= z@KBQ-hlbgS2{x?Nt1QLrM92txGFc3n%?r=?bBL@zx?sTsK{gNgVk2eg?X{J-&ZI!VW#q3dX7qaoY0*5Uu6EfK<#me7fPMMBia##=tBZ8{S5sq7jVYDg#KZO$53-`4 z+phTuAJ(oe$V$bg%*4`A=vzxW#=H>g+4cyQU5D!UNap>6C1>PlMvIhs%JxQ%^)gCi zSH3UbOjy)S7mkbOwKjT5uYCm{ZXHagHI?MxV$G)F+2)LnFC^Zf?0bn1h~g6eFp}Gr z6)qE1Ik5m`Gi{oDhVq7<>09V2j;PMJM#1y!wS5+S1I8%~aTBw^>a$uf3lTO5g(~C8 z!n8lsbmm3f_XupO7=)R0HkzS~jDQSOq~BOE3wx109)*~Sj+8m4`CR~td{*yUE%`4v zogNrrr9VQ)A`9RMAlKQJyXA^6Naec5a4ra-G-!^9Ac3`_;eMAExye~U-oXHaXl>tv zDgE^7!)jhZcX-e-@y-Kdpl$V?HYtjemjw9|A$VL{H{rc+Ukwdue@)l!kj$x-}ldjGC z{2qdJ0z*pwxmH)yzcvO8aDY1xhyn2bF1Foc!|Qh$15>pX#Q9g~)#-y%>jml# zcI)fw)VAWO*D1_>UZR865E)VhmQB~J%+|kFhq&5`mMrng8F21ge; zXKJU>^(na~4dRU$N#i-~%*^IqF0{-?{693kcR1Dm|37~0LqzChWR^rW*?X3~$vF1j zviA(xMfNUx?`*QSYz~eQ$38|JIS$`v@89opUH)=i%Bkn$@x0$}bLhaFH0g2EQ6S1MnsztYTuBf1NE(hk&?o88(L&%_Ta4uW6LT6Qid z$?nPBHsF7MM0;TQLP1|QP{H)t_iHLhWi0qf>vp5Vde2usb+;~{^J_25N>ZIUg}CzX z0q^y;Ug2SK!+=Bcs^ux|Gj*4QzY;V7iB`v}6I|ImYNi7%!G~YZz3ONo-Z_s}y~cMx z*xn0KXy1QBKh;ul5}^9&wvM~`Y;RqlOd0C-jKqb>pDooIqxkhrHvpUTX8q}=f1dbO zgMfv=`aMGab1P}TDkwNT$TYiG&^qkvYAa&xe8koQ^_?;>IO*K|SiJu0%TeQ?>gRLH z85c|)$%E<&V(=8_qK~b7T<5e+iag(bjTn!snOuqyD}KrNPJ_FRk>TOi^&rg4QGU{_J*6^O)|0z3eAYn$8_v?rtLE(y?lCA*GR_`E~*AKl#FPyY`gX;gf z;{B%n4O2kM_us!OWqu#cfrcBN>`9=3z!~$VAJvTGteDQ@y0lgTxk(DSvjh%;=8x&j z9gf)NDf2fw!^D8P>K$tc6h09QI2o8%ZqLu3066ds&`<-M6Q9)Qz=8^_!JIBZ7n!VP zc)R%7UK>|bf?F-AkaQm9{;X_M8$Ry2Ja}CSW~eiV*Uu^5y^d{$5!c_x#!xciguEnXJdldp40!2=oyB8xU%QUlVT0@Y^=d0i7X1yxdzXgrX1Ys&G^~i<%Mx* z2LrijjVs4Y<+PSfP`Jc^#tTZ%lDp@*Dr<6|ae#EHR}oV-u2|eh6iX7kjZWVNf=iFR zp<&d;siVd=^s1$ET>)Eu%L>N>JT)|?nF<9VtnG#)XRq%2m;4T72Rug3i9D|fyYBHJ>=;)YQ5B#_JYNZhuDFU< z5}Rm7kzh_zLqV-;YYd3)OqkqDYyw6N{ELleX@TD#0Rv=tEca8=?lThq-m5#@)`z19 z`Sz^m6=~qeL#v;SHpun$Tt%xE_Za*Kt(ie)e!R&%`H+3e=cDPA2O7~^46 z{$?|4P1;QT-)pGpT-r5EdQ*v)2BefFl0$NO-?FBB6S#_u&)os5! zI$NFL{fQVg2i9Ni-Ghnto*tO_3*dlwka@ng9JOghPl_z#v{E31ejVu4mgba$WfLFttC9Dmk&g7*-NellFXBE}Z9KKQexzO* zBBgWm?daarrHg{}46`?hy2K0eW_BGx#9G)-DWb;sv#fRRIuu4hmz8yqZ~Ez$t^F-_u$B4AH@D z6;FD6Ba{>8uHGqlNw;i$`+*kT<4MT3U(zfPU!om;F}!H0|0D+AzX<{`f%a^O2n;sf z`4bQy7B~p~p<*`qQG+Lyo3-f5a3`lS03fc>MMtMTQah=I{R*}}y%Y;5Vg{}KLD)35 z+y;!NhK%2j(%6n4?V<9G#^7i04$Z735I6wDLDv~c;3tp(L(@PIxWo)jT_ z4u0;N2U7&w9}~hvdSG-={%-kafgwhpo@V>@iCjlhUdlTEZ8bNWc;N4acbe3y@^U^k zNnz@{y1G)kKo>9Sgs|Chxu0x_f8es~LFzCwl^+A?pZObH!3JNKt)A(~H}6!nQXSUJ z87Z~B`Z{j8Rv`2$*k&J^*;i^6sLZN5gjA+H94H?qBD})D!p*_5npo2P=+qUJ+)(Wn zBVK~)efQwonL6qs8uC7xX4xw(nO6SopM{05D`Ly+LfJ0|VJEA^*e@TZ2yMSz%wS~K zo1|I4ay&4zvE;_BQQEg60&ZQgd(#5rYy<>wq;U~&V0%(Zzp`YAi7vRyJk$Msludmc zTFZ~gNKyb0YD!^PjV9O_spJ|J*gB8PnZ75p6lnAwx>l2v6KYo%6q5M!D{aYEQWHFV z%~;2(R7FpBc6K>!!hF}uO?^h%NpTr0kWJMwY*X~*<9Nu)bVdP16eDwrVku@)5Cpf< zzW*$@b;)N{*=l5!zi3@fl6S@#Cr2o8(!C`|(i|#O)wSOM@3?!a;{TmP9y<0FiDS0h zqq28*bwmL~^Gw`G{t;{EUgoNe9`CfJy)BtWJsnb$U-D(zpk5Zj8BV3$$gX$Ai*wo& zi3m!qZB3yV>9p3^(5tWr(X@~2lTGC5paIhCe*$YXkU!o0Ee7KlZ_Rm7P1JlxeptNj>soTSdXZQGb>Fh}*h^zf1H*R=7MrwGLPC0xBfrd8J=8tChk z627&2HR>pui0*Pf_Qhyk;qXdFrRd26|!G$ z6xS6=ZS)9URQx_Snzr=) za@e}ILm{+l#D_=h_-et+rlXGbuthfS=#(+J?I7<#r{uPjZ9bBk_r2^G&pdO)s#B;1 z`r?w%m;Q}mLnvHU*;U=fwRgM#WBw#bitPA0^2beYCmsU^H--krGKiu+_(K<^>Z|0i zP?kIrTYQVpQvP(L5Hl0k&DJVn45Gs9S9RnP_kV_#V@Rl$MdU^)fUsQoGY+Pv0KXDE-EjuCsjQxkAx`Cdckm6Q+TN zy(`T#N*huu``wH$8e>R4IC@XOY_1iRjgQqbYnEnR!ZfJii2UHDw$~Nsku;oMlvEB} zyp}MVCT-#HJ_%8L+h)VedWTmBTJA3tNxzL)FDW&Dx^mgV+V%D_Bh8!mTm^z^ zCwNMWsOb4CDp;S?C%M?TTm}-5%eTx;VQ@tlvE{}4R@iWV?yh)!cY8Hn73Xbi_P$4g zbQQa{(jnbSQ`fq7d$625|C?BLa4Q~Um4ik1p_PKmy~bwKWDsQpj_F$A?VsYh* za-wp%)~AdDQn`P$cZE?X$6QeDu*)5mlB`C{ef-49nC&JecVt!*IS`S)`Ebi8=8u0^ z5t&BXaF0_(uz8MOQSBwLDdu((S?dJL|Kg{f^D{=WNx_G9_>yPFnordrj?ONlvTDU? zNdxa11-s8pd?ccu!h{i;D*)sNcAyjOdulf7>g}CQ&8(=I<;v~!alvKqZ@=hjy z$(;;m_RV0R1T1ByG+rR{958_Y+g8p5;~y{(VX`Vg+d1)Q&b?|9i|Ai;@=rn`gW!fQ z%a7Bt07xIuQ?IzYeUM;E)dGG7RQIi^553Gv0J;_%&##f{&Sh$P&n|*4f)B6~22X_@ z*IFvhde0aNJ`F2 z6oaZ?hWE;ne>@2cFx>j4z0_~%`w3!>FqMq>yj=VqKuWw%fJaO5wWS3C*|}gg5wKAK z5udi?Y{w|7)EtS&M%L-1rSqvil9GuK<~yDrW6z>%)+c}4;um5n(b7K)YTg|Mm57i! zS7NLKm`166ECSYJDU!PlENjHX#K6ZIX>j7=xnAqWW;Wqoi5_h;rG*fDqYq;r|M%C7 zm}@ERAo75J3Sc_bx^C(E^Yv^N&11O=sEb6se*?Jdb&BJonx&(zE|Yw8Z-a_X$)N+* z&LgQ-%pel%vxjrZhkgG4aHDQPAm*Kn%&GL_wPq{}P&{9B4>bEf5!ukNBc&Eno=~ z35>75KTx^CNGAeTD83lq#~_VL(fwl#jsC{_ikTaciz|WmM)#H#X)Q}mOSx}UC$r3y zKcKo{BfZ6ZsqW#J)O6TNR2Cm^woQHl5f= zLpbH$Tw~ZZ2+3l)-YuEtr%uzDl*qb3E1Gznw2q6qY+xrM%SpuRcvw2(Pu1GHGd!YY z7ItP&J18Ve_F7ucI&w12M=#kTegII;)MKq=o?q7RA4}hY(wIJ#w<+rp&<Zn;e1!QPTyn>VD~U+=V1sA1HaR{^g;|ev;9~}weEU^KG?71)>bhr4FFi9~ zdmWUfxkZcUd09;br z=5lKb0}xW#B;eMOHHp1tFRSd_MI`U{cagxCk}xwj0Xq8JjExZIA1xaT6dC=?uDid# z?_c#+>+}v$=@{E6JrBxPD>cgmsOlC=%e;2=7E2r#(XvC&cVQb3m(!8~MCD~ z@BhX9c^?HK!Om#Ot`th#@)45WAQKDV!pb|=5frjUPvQ5l5TrV{lyXeJG3yP5s{Yth(GMwHme^@A__0x1(Co~qHd1e|JtFXRMKcMDpYPsy|q8Ot9 ziX!JE(m$!a`izE5Nlpl~KBy^Vj2~lWP3U#BSWqPLEIwqZcwxLFmcb>N9bUp$?WV}O zw{vJQx>^s%{%}WY;fa+iDO-yO<;995_9YE|(QDO~V$ZTmkhfa5!scNo6icvO*6*{c3(f4Ux8+U4QM8St9k z4?^K9?K9no3wUHl@UN9)myEI;-u!7Ex}+!azf8_lmGEB%{r37KHeFW}s-@;euacd0 z@pG7xKfFTWJGmI7A1nEgdZ~RtYiSvb|5Rb-oKhqv>kARq6sC*aju3#;mUMIHl9h_g zgiYI)kqz@APCS-J!QRmQcp-8*A@7{rwHYritF{X|yY%yprhuCelcXN#k}+rcd-nhK zT!C9BfPV?XUs!W5IgfDZ`5@uu=-7du)s1*of>moT%7T#r_ziEZo;4)xpM7`!Yp9U! zY)V?nLKKXv?a_=HipvB0fXg_SlLR}67Y*9wQ9-Gbd1#;r{h?WYV9q`6} zrBP(a9#MDGXY8~L`$)zOh0*n0f>?3FLzgUgLA!rGeqOU#KiJE(i!1~RNWqv4iL#yx zMc(d*{=Q}E`#=c$*)r03aHVwu$@Q^|Gs-*$sPY7~FaLspc{7ih{N0>5(#ORW#L(0# zS#6P_@VYz*E|A~`p}D|omuQptvycX#_7xMjY#2YKt4r!OgxY6iiPz_Xhy0{in=J)> z{=QTH*o6lalmXX;L0Xsc^DE_RFE}WohaGj57VMAzo-7F9M$2-5T5!vxmx>mFbpMW? zNr-E}(EU>PM*Y$CNfPmjW8}C7oQ@m>FbIlHR+#&CZ~nC}U!PQblNEl z;)Q-t3EP-%I5x8-ya{3`j--zQoVG=|87jC&NtTLApSWY)__Mbh1p0*(Np2**KmF}r zNlrc^lH9ye$u19X*ydlgOx2n>k*P@yuW+2#9T#h0_ADfq6Wu>-kXz^EZIRm!#lX5g zU!`UpraX=uw}MS}Qiwh_HW}WCUy0)wZkW`0m9kzV?BF_d!XWlAHNF4dMwJd_GS)Cq zYua-L&kreLA=qK}t6e?J&$WNBW)zPxBYZN=_|u&%`JV0D2{Cp@5MwyD#T^lErYt_b zW>uke-MURBHH-etE`i2^8m=1&Hpvd#K2vBKPU?nK`BP7bdDWwMU0l<261yCGOoDDs z9zCi(hjr{-U5rndvrEa}z!t$ca`5#ZKVpTkhj$98Z3v{8vH!C>$}zoBFvTkSC{@gl z`R4f2CGjVM$OmolL7!$g;L8usWA2O&V@~9k?+#$Av3}+@=>v65;|Evv&L8epzWj8$ zVRE}*oyWvpDS<`*M*+()D1|aOrC8#2KJ}Ig1}IGUq?86gb?l(Y-%c0v05QD?e38ZU z@!ctue~mXyqxv#&mHvo3Q)I8*8(zieYvGCt-eXbGHnb=ejfpdQ*fb`8G2 zIM8Ac6`j!mn(*+*L^rV-44?5Mt?`uYY_$!{>ge$T$pc}-KvNNbb$u==*UVO&n-@~d z&&wlxwqd=o=a@4eN>{S@7wf&4l*fp zs3v%{pBlLG$70SHo>V(RRQ|T>o!m9c80dkT+H8x}^c8&Bv^Rnucfw?0@T*9Yn4O!2 zOSJOVt?3T|4`WSyC9t{D-10p|4HuU#_6-Z+(aP@T3)rLXBo}ADTfB15H~G^EGIM9a zfBLN_Qq0jOP(iZZuJ(4`(R?q+vr&)L`WD1>@zHa1q4&>RT9CM)+WJ!NrGHC){HHmD zvt%712y5!kXAe%>wmQHxd? zPP-r{;%Vd)g(nIrijC*7mU7Y{^`^U4I$OayYllATAFUycRA*w*Xjc~uCcT~#^R3lc{gTc zqD2PV;KK# zrMJn&Ie+*CO%NUR-`j7)ab%8trVuLIW8hvTT^QPH5(rvr(rj_n&-|{)QC=Hd(0;3) z`e5)aT#5x-fcK|NB6s=|W*N-(HVS+qVgl01yP_@-m~7vUQ0_%9aajAE#pMKQlmGg$ zGp>#s4XmyH|!+-ocG&@tiK$=(O2C=v5U#&%u=Y;4)qsA(~G$N3q9Ca@Z@#QqdI zW=Vg?Oc#MjH2@4{%bK8ul+umyQ+G#a==85{L1vFt{(5!u(^Zu~<}a9V%hgrI$DTBR zR>%TLXW@`{8%!gcjuzpj4k7*#`-BD%J#7Mr!_7{Tq#H03S{WX!g#gvAk`I5?0Y%^( z6Bijk!}4Zs9v)USmUvM#0yEXdvI9bMd^MM%{Y;Zx^jZ4Q=BpbMx6@aNCm)@oLWT{h zIgGUfx;0}10H+LAY>`uKS3tKmbR2GrqEW{|ZJ0cA+LfSCF?k#g+Bv7Z{Cj8h(5t*^ z4eesb>F*T{rQMY*&cens8Lws)qfYStou;mfEhP9jfo~D#{@pGHMXl!kU)po6J%sRW z^d;1$Q92L47x+J_cpEV2D~NwrH@K*cv)BX$)k3sMam1fg6{? zW#ipYu1$|t=$O-ZLJx!C)kihe1Bb7Zau0jNpL)X@B%N^>p#O<@h6JjWCh{5ig`yO2 zi!mtah4WA7L+-)=yUK6BZdpBXYf0bOpRZwLqMVz|L%;H2c&DwmV;z{2S#EZ@A_E%m zu0(|wcQ@x)59jm`VL+Ke=I>b{ml%qpD{7#t1fbqaH9d}?mo!J|vZz%?mIoXLapF-CBOeyeMHAE8 zqe|WoM4X=RctO57(LR>XlWpc|&?4~C1!&&i22mC4&ssY9@t04^kEnGGiuOm`sJJ&t z&rRYv1XEVMqo8VUY~HJvYQGS4cxEZqN}KExagZv!ebvE>?g+QO_WHrl&X0{+J!$Em zoDfah8j5#k#shIDMvF}+MEC)mSDSI(t^u(x2F*|_$v^C!*ev=ok|M+K;JFH@n&D`O za!&WL6oxMT{L3ai=p~SGM&^0Fj6Km!P)0~nB9-ifb$Ei7zD=+QrNH!h40$u*^Mpz2 zjeYp#F7*h-%e;fpOjaHMU>Vw3}>$+^W+$C#0o(W=}HV}N7zY$5Aj}3<1}&F#`EmA+t@-GU!8Ng=`9L<0dFLcl-sAWo7*-H} zdAZ7$64vidhl5<{%6uhM8m0hD!R~J+u|<;^aAD?@(LCNgWjI4GCG1y})O2omwqY#b zO|PAY-e!K@7JR0C3R4vTI6UV1^FU+4A{GY=r;}SV)WZ7J$Oaib^{}q)$?^l-W~}4H z??@t3I_PxW#nqK3S55V~d{#-xl-S8EGQ%{g;Ep2H?&a^f%1S|;J^27m;GH_iv;7Nf zPM%p12=67q)Or)|Ckfuf!H^?)bAbdE@PA)aFfplA(A&UXs|IyANbUe^P6w@qu0d9T z7}l{a5N%Fib;RE=IfT7SWe2dvzmNDG9JhrA{>;2({(^xuHL4-$O^Y(6fMf=_;4<=U z9TSS-R@t-H?+H_Fds;vVx%6>U;QIts&^{N=7;o+gn}$YCv-D2p+*Jqwi3JH{UL*wo z2axg}g0{*>zTYz?mlq8hN2Fjh7;}EMUg1s(e6w26c19NCh8bxobxVXL5yNyNE*|$A>p5W(+XfX8g%W}yFuKc>vMDM~2*%$WYf@XUDWMy!qQ zL#}xc9B5^xjjBP>(O7NU6V1PrGmz4M>dByqA0`u{kXxYoiev`t^-&HE_QDVQ@wXd} zb-@2;5>`loBsqes6OHBfZ`4nFu>gheaIWenZ&!@7*QHB7o_K00{ZktWJ@M`FBshOB zxlyqA-gv~peGb10onmUs`dWGD^%J$Pd^FK zEv{3xK125D5x7%*;_7RA3Yy}F)z=<8fZ8J#bC8KRiI9MuWY@5zmL+RkVIh-~RfN1I zpwFO^47p!x^ub3Owmc72?erZLo7^!O`@SbW+p@1D^ULss;+K?EybY|DhxqBxpgCQ~ zo0t0pC6L$cw_7Cp^xx?(nm0QDGfqJ*Cy*RyYWmFYR9U6LpY1WvFXArA8p*WjzLu+# z0{c98iTaMv5WsW;7N7=psNeJo@_KFHyFIdN^G-3OuB!#vMaJ2``dF{$jbAz2kM-f@ zQ_=26HTlce5gpUx&6daLG+Le3QD(8k{I*S)uSz~-9L=83x@2pT9&2=Gv=pfD!O)cS zV-UyfNnFu>ybn$6N*mIL-R)s9h!-t${B6=EB0D=f*J>VsDG^m4;|8}`<{pYE!!Jxh zhOFd%iB8QjsZ5m3$Ja|T@9e{Gt$r#qW`+I$h_e+V%Lp>LvMV}mlh5vp_bkO4mCozP zhRL7ibzLJ3HX24@egUL~b5YIP<3&;j?0bf+sq$fm32}frTVQHXL$W1&%OGW2|7%7EbSt zXtH=9?NDc`lu-CP8JDol)=kRu|~v|8}&KjP8D2@Kp+ouP%t8cz-Mnwqq=elzSOCFC*0#T><)> zK2!O$Vs~z;Q%ba-)}v-F?J{{h^+8!$DTVA0vtDh9EWZY;y zucP#L;qa|V0(Jz@1WG!y3t6eV&MXAnL)84(X+QhBz-JI&1yyO87c(y{7O;1V^(Nw- z9mb;Zo9HoR0xPomj814#m$FCba+L&2LN5{JH93MQ3h)2AMNNO89*Oh`0^&uU?QQ=I0gBcSS1d%OJaY?h<&w|$=Vz<-wSd{gHMZ{9XVp||{w zx4-SBc!UKW|bk5)CWur zuLM<8(T#ZwOClpj1Za8s&9C;aVX%91cn0sZW>W(~G3%$}D=aAflw*dy=G<$3LRZUA~8%!5q-;tsEPZf!NOHO>_)87 zzH=|GSoJSeKb~gYFXAXY)n9Q ztmC#bejFH3Gu{A%{a|KK+GO}hP|vzL43vg|vhm8Ug2=4!stgaS@M}SmQE3+P z^Op~Aqf*JWUnuLyN zX2dW1_F5I{$#&KCAgl--z zHK#78v)1}&?wE#Ps~Ig)E6SfT3RDND5gL*cz5dG>C6dpNh)^LGEdO=#&2r_6kcE$B zKwt%-Y#I{S1i8?ovH1CjF@9Y%S8Wm{M3)4hKU6-^Lr_57?khHAGgrmm(r61%N7vVj zOn$+UDMMcIE7C-~K0s^5=h9N~F2m}&_w3gWgV1RdX+{U!Y^M8Td9c&QrYJvMQa}pk z#!q7}^H)2x9TXK-fQ*?6e#w}#s$P3CoqifIMb+dUVWvrLE|LGt232_O9ukrSXq)Cj zXpR6$;oIS*w+pfKZZr+Ly_g#=g895$UEd*a9gy#MAd(J_aSPY1nf~*n{xP?*z=}2f zg%}LKs7{setVhm1^r!^5eO&`hJ zjzr?I9cUOz;-RObm2I39$kG-KKF~hBoN;feKHm93UnJRu5Yut4Lk|8ag~nn8O-G}r zzhhk!!zHKCYsl--(ZTW*dZj)e;TZYGu|XlK#sDs%|dN?>6CllB6&x z<>L4%3%}T_!NDnFcL?8}Z`3fVZISxiF7n)J_T6@?LIwxUH0+XHc4hJRpQ;I6lWY|q zwRf>Ac_(nf)y7<`{-Dq}55AV$@O3WhvJSJNPm4yl?T&IeS;7G$quVx}=k3E8hY)`A z_Mw&f_}1FA18>fEtg1w6oSh(*|F+O*vMq}ou>`SaFt9Vh@_~LlYN>ZhvnKQ;%>i4yp)p`Klg>qzkDMv0HKddSh z{3e_r{2Bsg=qG7le>QqGi7PT4Hl5KgMrx|tB)bPUg_kK6EQ540s>yUnMm|OxW3$Ld8j>eyMJ_tynZJXM|#y!YK2iB!IRf683GUU(KxG2r_wQe29v@*fiAS#0UO_HH2dvFiCr1Q~@wp*o^y^*P&x?k^w97~Wjn1;i2PDTb9KdP!~v z%NI?eK>sM9&WUG2B0{^7C(VfI`paMWYYWpV1RuuxuEH+C$oDP8S2{K#$SPM|GZEdk zgi8;Y-+oHzHZ^i^_E~t#o0_YTQ4PX8jo0*mrS&4@w5| zR$zFPRgDoIx(nDtP=-KV-7-T~(gofnV4$P~oan4Sg`!@yepp=1dUIIeka5Bx>N$Pp z)&OfdwK>TCG=dK5E#3ApFM}@CJI?%o;koJ19VLHDeJx4@GDG|;=^-Z*BQl`f0t=D*}g)zMhMtyl%U1{}{XAbruHq!OuT zn+F7#1auBe?Q#{dB?S>0$(q>0nKC8%F|+tJf$K&QSH^^1xRpQBRz4s~=QZGMBiuoN z{?eV}N}I~21+wi&_k~G1t7MNx0Gd7AgKLb4U;vKNkih`|16#e5$#`UGWZ~p&0sF2^ zF-BC-txEbVu}cm>5zx1AUz{8UlzbffH~xOdpcLV^J#z9Ghk&AgKg?FCZv+h$q;? z!;Q0jAcrRZx;F2my86pvMjF_@Z>|!6TJhQof?RdIbmApm?SK>S{}*8^}_E zGo=O`v8B!S1Xqb6_x2U%8f`nps4eXz(c$hJ{;Hr>SSAgiaMGl!U&60$#xDSVA0Uk} z3$07>BYy|pgb$ocz$pOSQ~zhJxfw+8x|l@N+|L?X0;HfxApm>@9)55*$O{7e zbaxhyB=&9(Nt4z{BcX4g+-EqL9NClMcISHn}2-@;H8u@#TOWwkvPgJMEEQ;F#xjFu_lsf9CXu z{`x;Hz$HTH#sr(}n4rrR13C#{HgU906_>a%X@Cm&K3VUs_{Hr!HhCON{? zS|Ty*ll`RG)kl0z_>u{je5F&(?%I*fE#=S_Mxgv!7sdJ7HB@XyyOG^_XA;qVgGU>{v}Gq z2*FX88_nBz$J?`%^`(mq5-mw5BKP7zWU354vLkv5rDxOA@z_l=j|qTZss1@M8R$Ya z2hD=)Sc_R1v3j`=PeR2|`O^JiR1ba(SU|fwm=OwNZRE)P&OxlCt5E@c#k+|%oBpOr zPHWur-o=(u9}D-*jNuNTiTX#EbG+=x7~_f?v^axag$iJh9o~}2KLKS(agZSaR0KdK zRU0&5_g`8RD5IFSGEwYC^$GVObUS&&8(7^ol6SK^5&@=8Y>zZB!o&UwB@$Jl0ej7{ zeIjdSs`aPc51;fCiqoV=1@Mi1SY2s!}xX#Z4Q>xXTwMLtwsWP4eLD+~;m`Eb}RhD?BZV%iQo; z>(zOnJ`b6-XC%7l*_Pr}-BD>d%9; zem45@JfQBuIpPwqv&_qYWMm!@(=ic@gn3-j*{#5nNuLvLsWK-w8jxYPVr~x6S#cXX zf?2b9X7Xh5G2E(k@Ej)NP7Tk(of!?8J3HI#tq#9|d1Dz2bzc?olVH!tNLA}eX-ZjB z)fvl(OFR$o?G4i1qL(pq<|!0Ld>Qp2@PL!_!zmjZ(hKPZdRZb#UWWVQ)TWhL;b4U6 zJU#PTFUhk5qLGROZuC&#j{`D`BXXf4$s`A03yFxS8V%0J>21Okvbp=Br{tm!e8;4# zAH93;#Cro8vEHX|kBAOL;(329S@srbOXS&N<$yFL5>G*7Bxc3 zI^x6x;JudeTcHi%v7GHXD2%?l7FJ)GZW~6PM5x!xW*BF~+srZXq|K~OfbH+R!&M+# zoL@6Ql0#10ze>42;kEUj9Uq)bSUY|2fqQ-%m(5xcyRv2Jue@(rZ1|5{x^86|uxLUR zZAv(N0s~LaCEKD&x@Ax-7(d2pT#b zl}ZYDPXP(e{FhQqxwJde74E;rc2c?|T8w{~zA&w&SZz2F{MOw_HT_JdVZErn!Mzva z(-iOLsrU|pe_FPr!Jo^AnJd?c0d}f%(Q}c~vw8JEFK0Muh4g1KCig)Yn3sA!Bm&IzGdw-%_ zYZ7;-j0+8d_L^)*rIq=#T1O_W=XQ=UP+%wE-AYz9^8)actFQO-!~*S)H?Tp}O@j)-HUIaC7mt*(#79&s!64@6htj06s zU@;FesjxP!DQ<}ub#k7}G&=RZ9xkLW{IjNX6s?g}0$5E-XjM9GN%D4bPyxlMRHgZ7 zx%>h*_a7VKO70^W^btYV&;j*)T-)`wxQ!q~u9W8}o zpf)N0{=IxP`-VT33*I0Ii}m>X_hd&+Q^F$&0mXyHibtpReRmpr#`WJLKq5#zdb#3c za~#{iUjLpw**cT8^nBHuSgFB?Td@xp^>Uooa=gpxq=e`P5C{C{k5wvj2BA0L+y&s} zA{K^7UytfPwU4it9;P?4T?A`h7)3nWR8dWfp3wHHK-}J5qk1$R4%@w^NBh#O9Jj#* zA;}ohZ&)=2tj7hAh9*-@ERPwYq~wlivnLf^wMt4z02u?DfGZoQ!#NWp1~NHTTmS3~ zC#8JFy)6h#;))ZXa;h!=WZPhHn6WVIP?o)N+>Jo+%umv1fnuIm*yL$)XfAm*e|F{k z(9~CBSvOZ?&%1bV>zQ}RM_*B_7S?Ea@j5!=u-3ZF^fg)4Fe-wlsg$QsBa=gMAEzas)3uKta4XpirpUJ$c|65s2%s-}W=3 z2W*Fg>ALCZ#^V8%R_8hfmhdz4_jl0CUYb%KhT1qhZd~04Xyy(ukmtdZ6)~U6CszXM zE(rF>xQ8Y~ejDfV75~k`Q;ml6zjoM;LfC9rgq|F!qd^vpVaBzOm;>`GuvYR6$2!r&%aZ_yX#dpIf9fa18W3g3g1%vz5>socUYKMJN0TI)=tSo0NAI-uR>B%!(H_ zv+eVXuH_`&1Y~)){5Wed5EWzw*G8w7?wDnKv&FSf!l9U#nM~b7`r@6IU~*|S{$)1Jf}fsJbLq)ttSnUvKS@g@AG7f z?KK}sBtF8cw?6RTgL2l0(_lvQopy8+pZa|i!CIlMN*==lrCEz!OTc^G-q#%m(N{I; zHyKMnH6I%iuFGA z;9;;gV0o{xslwig_>I&_?G zqmh$Q2UN&R9@~GAVgK(DL^h9!?Lhc3PgI57ILmj#4!~ocB!00t4g2=?ndc;fAUwL= z{U_yILql{%tIp!?;h_>9VYzpS76C9f0up>+pa3>CL+L#og@-n?#gbybsJ(GnZ%j)S z#KYsRbdQCq$xCClC;ws4OMwYQj!B!?#}`%n2&|s)r9jj*Q68KTjA;yk*ze|^ zc%zD`7U6Of_?}IBKWgF_z$DmVr+nXjy?fP}taJ5$!+3vS z{>ncA`1%_dtm9q)Jd(a1IoX9K;(Ns^ULRsLH;3;yIc}Tqt9gf6->YT5B?k*imRe>} z9xAa;TD7t}POm6XX_3bl4bD$&@L}ETbv&FU52DRk;mle@_%< z4O$6h^9O+TC;N?f54uTJY{Vw}2ME3kuXvu$oe%5-{o$HZB%%@){`|LMSTyxr!sj=o1(&J8vf3duj1HJ0CZ)qiJ4GKN|hZ9x=gNb|Ls3TL_OU^Uv#X z5M!*!MGltv`*%xoS99d=zHA%+`7z((m$)!T7R-?zqYRA-{|ez*P^*9YC$OI~xu#IB z=d&xE#DMUn#}5`#er(Hvii^QZmLIR*mXQ)#hhsGMWnk_QF4|!pLG#TXDjiFD-pV%kV<+R^-1sqm?;w1|Susy`b!WCp{djPZcH>z@j4^g7> z^~EQ_8K?PsFQyi0(exEwQFqD5E!Gn6Ak^$JfHO4b5yGF)K52^%ucyXcKsr=-I7Rqupl zfTq_KAyQ>pI(6|rL2gAbO|&o}6-sT3KE1=oH&w`K7D~3OK`h0llkr$y!ZOro%J($t z3`9d}It$6xo<5gS{S7|oka;bvQ=m?Y3Knp9OU0-MF;7Q!!hHe@Dfjgh z8_eeItjeFhz#0Dx{d9G){m8I(ug>n!g&m(ZM6z{>e*VK_tlR_scX(Z*=+vkabanjN z0{$@J586>RQL81y?bEEQ>WxluhF zb;%tLcBjMuboM&Xh_I-@bX~h>gC!|p^E>j2h8o01uO4mZYqtRTt4O%2cPWtf?tCmI z!Z{H;wC%t6V7+-NH+*{x=m1RcD{hMlVPDY}4k9zS)L+VcvX%@G9c2Q1irV z%@)4Th&N;v{*Dk+3C(TE2>fkHXpCyJqI* z!${&`WSUf2N;Zct>#ZLsSJ;wWiiQT~#Yi`}?geG6^ z5#ho4dt9NA$CCqp$stEcfzO$m**Eu+N-c_eFGXF9j&_LcM9?U$Er97Uh*5Eb zX{3uZgvF}>=s7QAsDQV+90(hN*O#BWfxCx$c$h1HgK)W02T|Kz2*KG*Q#7(g zUy-mcbvwO%TY`#0-m62df2EC!-8f7TNhVmmhBOF8;zcjV#T4Qum%gG@Y*+KY^U`}#v?d>e> z4*#X)4gKFrw#gRhJKpZ@MQOo_)si=H;E`p#vuP-;c(TG6`(U_b7E65?!OoXW zcJOa?vy-c90l8`)I=yR^2q=saeRvN*g8a{p@eV|U;mRCHD#xP&s^ULMIS5MIHn1O6 zLgnfDE%c!SE|yd>AEK#7S0^Dy7NbZa7M2*I8fTE5&s`(Lq4We>w7gZf<|nGzW?l73 z*zVZj*7tXK#GBM4n7xonTUQ&GdL2TcCxtHJDpRVz4rC6qZXJuti?)^%$+`=jWywMv zjYuVHI5pE!Zfjsw zRjTZNS89Ar-64YwaQY$v=xLrbt_djQqV>X%b6ZEs5p9MdeM%Tu<4&&C8BuaSkK3X& z9aq8T@p-4~fY{jQ-Ze)DvsW1zGd2ab@#!aeFUGw;qNG=01oaq? zT{2txP+PcY5Ok%t8sxCrL%e#17cmjo7!}^= zrq(T78PZKVv8G_~y8PM9ATAu&y|kY?RF#hMYy$fyyRb!;Lsqc$L13VE6V40 znf#+ShM~8Qk9gBe1M{@~QD}SoD)ir>b(LvG>`6L7c*Ek6Nr;K-zHsBSxe!28GP{%f z3!J%`=(^+haN>p4&mqQ}S&&xl zCE0#POJFnEuX4X(7-yT+DauS`PNaO*s3qmx*aiN}-?iFXF1a z@xKKf99Jr%tHdSvX>QbP{At5gTQ{YME;!g1AFle9ik<4!Nj$cV$m?yV#2c0Y&=)zqLIa6A7 z-=E!z8;52wl<14T_DevY&cqbbmkx!8dp285MOVl6oF9BvxwK zs>O>rlU!E0WFG6$7_E-!VSuirIHp+y6{$O*C$LAIGB8NU+Sn>N7qLy}8}9B@)+%P4 zQ|Q;~&gx{bczh)AwF5VJs*BEoE~JW>cw0S6iWj|v*c=SQZ07OA7jK4t9@Z?3&D^C z;Bq&Atb6@Se>3d~R_K|-;yR$rL{s;nid6)NCG)NAe=f3mMAe6vdg(}S&rXT4d6!ADf4NKDhAB`Op7%(%Ox{jFY2(Us_5)WI3w{p=&$f^%3x_AP z$xqkGPP_sgi zCj?ItV;K1S&jSTNI=moZtv1fOP}zEx6qj!smj&e=DZ{-kUCBJ}4NEGnG{1icLZFrN8P~`y7b9(tkPxHYYyB8BZ-T&)Jh2|H4mo03 z6WjHEA*e7k`B9R6?ys)g-~Aczgr*#BZR8b;NM$S``oIvfMIGoAPux9GI82_Lwot45 zuZtFSdM34bQ7Zr1ps9+0JP}`a1BXylkA_9ZxfuN9V6+iOu5BF>^UdNQLaJ(*wwYe{ zny$CYJpUP8w;jcz(<#0X*GsNgv*ZSx;B8@T;wOZNJ^o8K96dIVWF6E-av3~YhJ~2f zV=nXhz4Nv98o9gA<0E8@{)s&0NTW!74P&RB{5_roJ&jeXxY23N0{NaGc~d&P{cYW->*xJh-1q4W6W($i5n8rb zU0Wg><=nR4;Roya95$TDKhhBOUwM+6jcf6!76dyte2jQEcYI9AY(hEb{Q5Fk1|Uq& z;<992_#1H0h~CE(-a#os#g;J4a61pX3>83s$vUQ`!f(9b*L5HUKYSyBv1>DsaDuu` z=|s8r^l;&zvF4X|68Vbuf>(p#SwqDNap~I?{E53vm;Cp15jG3jd@W#yA@qKn&S*MY zu(FUicrdOIE6@5fV?>PcP5h6u>-+h$1hV12;38BWZ2BM9s*yyXeRQI9AMgH~cCwUr z;N?B~RaGc|5IT=in58ZrI!&zH7C!&wnvUuH7hmnOjLBI#bdecV7IeQiH&q8t_6s$( z-u;P%?nb0RJ(6V*Fq?o0rO#;*E_6ty5_R=20E3$hDw1X6eGguOzvKu~Y_Hgb0}{af z0-?S%0jgJ4TW9AlMdhfPZ|lX+*R!DLb9-cmTNk6R&dvHPr!H6urfZZ}F8JT44EJ?d z`toi&u`gLND^7ZVz>vv^Pv)?RZNvmsqC>Ab3+1r6C}0aK<)e@jN_08|6LO77`wEpo zbebNiLc-XGrw&`+jXK6-lIjwok#hKcu+myuihW^3ZIGps$@OV2%#@Rh za%mqw_e;Z*4kxLsm#_mRMXAQ3%jTA6?i~ph12mC{or`^N!ckv0LDgGBEz=9rb1&w8 zSYHTz=y|mb8EI7ijTKqse~3Kn=@#<~FS`fw)1A&9eF!yQ5eW;|B2v<#npQp7;0YNc zB@_1-a&Y2OZ=7*(cvjhq%aDj4P}o1m@=6vzq(%|DWEa;Gj4J!h=V$DrDz28yKbt1O z+m4Gt`Rp=_&X655iL_&r+@*=eARdDwC!&rDe{M@USV)7oQcM;{_;SP1gy3fzUo0fk zrJe8yWF!=5*U4-;LVY~^&n_{uEsh}14QTj6aV3pmk)POxy*~|Dd#ritq=^ymgp!+G znhaFii=3k=Z^QjFmoi=SBZ6tfdcJa+s?pE(=B;c(ob?A&QF=6I6$53ub%iODdUVL0 zhjMcu_Z&yxueMeu z|2XrdF(pHutPi6kFzA>1=hAw6Z4p|(CU%7iQ2nrn z;~yaYoD_gZ%YVXRotdqbw)*q<>1HtJ?Un1^-&`l?HKOc7#a8%$4?io+j;@s&ZJ-S6 zcVX<(EohkgK*}saC9Pp&=?6zj+VnM{W&XWsmmF+^$_g=J1h`jD;_?GFI+ z$SLJDR2(~V@YPzCUi>-cm!!Zd-F$_>7q%)xJV6^A&Cg>lyx}SInYxvs*jaNdw(Xo; zl$R47`f-Yw@RZym=_qTBHZb}mq5H#p$~{}!E5*X^++;dsdpb@ zCxnhKGusl(-;6}mYqcVg=DCKS3)aj%5+eSbbApywPf(1zf?$$<+@nd}%)VT~ViskN z%VY$>jT!EtqfL_@@XxHFpN-0Tq;avVLJ`bZyt^M#n)TCso3c*NXZ*Orybwd$f74Uc z)2#ra^=rAY2OXt)5;Lb;bSA#aPL*}FLQ&YeU|8g6glXE@ATuMSVZW|ih%=H_?^*R2 zI`0TA5?n>2Mi7`R*-G$Oau{)l; zd9=Gg=U4RhU}{k2T(veH9+ok4z6ZPfxZTDyG%Dx~N$P=rOTK1O0D>}kQ&MsFD`8{S zdlrnEnnZT<_gx|`%ediP=!^*EQO$SXGrmsU4hzHWzU{VaS$zMLbQd-EGN=avgyJH_ z`mVKcsK5UgUspgxJ9eJCN>}ncE3%RpZ8@Folg*>e6n5my>$g?*VNI6fMk0g8->#T3 zk)PKIgZU-(SX;H~Q9@SgIpAD1hW-eE7TW4PE2wWZmZ)q+YxqQfT6MDR-j6B>x7y86*?T${m{{(FXDPB) zR#msb6`A*%&#Pql4qOl5(*Wsr6QzY`Nt4Mu4hsU*G&DC?$I^7c-Oer33V);s{44e#poD?Mu! zHr5}RfMs}&Qd`(jyz<$0Lz2Pcs7>lb??-T zVD(z*`hcPb`xFdVozJI#JTj-Z~+(LE$Jd6 zvb$YV*8cKDf6QMko}QJC z-Q?aW-pq3CEwI(az{4=iUb;Xi$B>Zb7QGe8A}>XtR8MH& zH%1}IkPvE9PcvF2Bzar?{X6bWwjt#tBY9~y12;a3nDw4UcYZoVyOnRf6b17wNaX-R zWnlLYp~ZZG6S0M_$oLr?CEdL(ssyYDgA2Zm!5qnoZBHQnZnfk`qhLcy$VvPek={33 zs>Qe)NH>?1*KJGod)j?|8CLSYB2tRnT>|_1{qhsr)WeSkuINbNn&s^Dd!F8h^#>!bD3&v)gXl>&&P-1Yg&utEtM|Lm`2!?rpDEmwB}u(UnHT_> zv;hgA*hJ9b4K&JBjC$`Mr9yQg7PjpPqRqVU@~@KPmBy|QQRgWHucTH8Uy%MZ92bTw zpo=~X?-9ybi~TT^+I4hX^x6{!dq|t%UAoH zUUGH!PG=$;KW0BP$)`bG;T`$uT;M8PrgMY5t8np>6Lt_f-T)KYZq>ybD*Y+`6aD6` zvx~SJmPxlM!~Vv7j@{7<40km1bZO?tadJjWZVaup-o_ciYUH=(7q9!{*eFU);tWw( zxAF+)ELZniGHJ-yXKHz)kHXY#AWvR{{bjY%tj64%N%5HG*kPNiijurISnk~0FYjxm zUyY*01<;{rhWfMwG@q5 zUR|x4qZ9Bt}|zK5hAJZ{``D8?HzE2!P^J$Iyk2GOci0@UxhJTK5z_J0k^^>(i?W53#Nx94 zhQ>TGiF31#800QJ`($sCXUpRxmKa8`OXjzSxkXu?&SbKncMu4-PO)Du7V~Q1^Q@Kh z_0uum>REXaFt`Iy858-kGZqA)>4EJW|D@I(cS2^$qW0EYZ{dE2V{txQnT9e~1(6Wo zAaAm`?MmEPneinYKOij`mr&tfZdy1{;9oA=W=aMjjgP)_qnhDr5FfB<5o9!_93M=Y z(WtD~4@VXCwS%mtG0ShZy?&=oXY+UESDqQ3m$OdxX*(aOy#&Si?rfzMOW>mH(XWR{ zwBKasH{D!JipTJ5v8~N5ej3|G-21-8v^HM&(A3=3weoE8U*U)+hKOHeC|c!jq-DK7r6xt`=zzRxlLb zsO)kf}WkAdRRQ?CZ#A31o3KS6ZI`7@wT2vx`Q zP+N9y9bdXW6H3XFKG<=_qkueHd18gTxUUq0@-iz>rAW5JW4tF!M!(mzCoe^_ZnJ;@ z4d-PfZAqeZvea{uxX-d0eAIIG=O=C64-zMt*s`obTsLLWu|$cVYzg=}XDMcn+96Wh z{(IMsne^Na3o-X=nL%s@tRi+);f&IpjKo6a@ur8;P*y6|rQiKs#AdIXqgnnkGzhOU zS3^-0B0pY*d(;IJlSl3pEL*O8{dApv!n~Z0^`MdFSd>?3M7}W7c@G#5Zc4nf<)vDV z12V8}daxE3h`+ohR29Aet_4H*wN1TRuuqzFx6%_NRg1*0&bMrCj~zv(y0EsPrx^!I z!(w4%cdo;jm3zO~6`Cu{61W929+7-T1FgVC>M`VnM!pSEy0UR8l^PcJ1}=zBGc@!T z$T-70q84YTt<@n5{TEG1p{6o=+4XQw@sGzFy(~nnGlSnLkA6fTz)M@R?q%r}t0k#G zfVg^Fw?4#4^bC~a21dm#Qr}ayw)2OQv>7^Tn0UxqZud2*KwqJVHDJo+7$L((%oO!|gGQ<`RVM0dWw{P1pTi*J%$Bq}gs;q}>@?&}M$l{jglc zw(f_?tTcf;oFRqSy%U(>;GdWSEZ!+Nirk|cMHk51Z~2^+3)=~hfiVYhMY(s@y7DUP zvC(OOja*l)O!y>!z69C@Du*{pau}EH)_d>8e#?_L)WPmyqn5AZ$*$b+vc-EIzu`Vx zj1ig{S9hdcC+5{77!EY&>=uVe_EBQ$GrdWb3Xt(XweUd~U z2}(S`tA&73=%D&?_(1uR0~^Vn{DI5jnnuJVCCX2P=FBMm!0z3t-ocB&b)j@uiqPE3 zrXjMap`?6zlF+p}KlL+GjW!K}nkuT5Z?F-mVXptRus3zbA2}^=t;`DDeIvyAu!X%~j=G%iOC?0w!CK<b-L1k{Y=KR<1o)5GE$7dAR9%ctdkb80zKfB8lV;@jm%XTrY@nZBM@2 z*I2Y3;iMX4hrEQS86$P&EnWGL-BvOn;@E6i;`ssLzO*fF)*&BDExwFVs3DaBEnRzE zzJBJlq`zJ-AHd0bqc--|Az|_>AAXI5?5^tSHF7ph58<&!=ylQ9hP!k%4~8^)O_t2d zdyK(fP{q86h?^(-Q8o_+sFTc=2M6YXSUg)8D6`-hNn}A6duB5z!xqkn^qcHm+jE;f z_d)QbXL4@kaYo=ewk*37JnNX%w%F{HGNq86 z-NF{86iUYEVU$h+M~u;|wXnU+*@GQPJ0_LKE)~tPr5atYnt3JQ3V(IyoqRUp7_KTlcZ@o%l&L1n!(iRE?pWL^K7=>3opwBTZC|rmqEymfD3p z2ZOU*#RU9i1Ds!l-p{p zy3afurss%=$ym1LLH`8SN>ZxXVJHCBDQ1CL@rL$;bsw?FJqeB8BBAlTpjVk32Ru+K2 zIlIF3>N{`InBC^;5@yKJ_0!$LFJ@0yK61`CPoaN%F0<5r1?QeAgJlitAMzb~{d+*n zf&`YQcC<$-ex}R*{KCjJHGvrO*n7Hb&v#AqUTT&kzkhX>L<}CnH1mJQgSd;qJp|`*D-KVc~J&#!)6S92? zVlX2SYFc$766sW`8`x+9+!#xsuBCp-Y&WP=TK!c1&U|YRvXSN!7XZ zGn{Wtt+%A13UmU$g#dgF#C#2-Js^NxZ$04_ZDX6s z4bN*j6a-Dk@u#TCmE<9{^FM&yP<*RR{TY)9EQ)G*yX$rQiat?i#`d>3WTg{;~q8Ba4aNy6t;M8Hv5VQW--M`Vaw5#!ak!eQVA#3vM=4*?nw{lQV z+-%0`jmm*ZI`AM2Z&=~3hKLE&QLcVQ6;-w9R%0eQ$b5>6PKFoOFlwlzSj`ylns8&` zc{71z2oin{v{MO7o!|l&_fp^o|K`XimjWoyxhZldiN7RUlsf7L(ZD!iA{S*mfXBWt zE(~1#q&(cZ)QgD~Q^+}?R93)**jk#7+jFD^MHv`=&z4G-7-$g+J3%h)Av^jmZNG-| zd$zgY*b8VS5?YFN^M#GaR)2YQ{5nfB842e43sWW$yor#Wq&mNO{p4mZ)TTkT{YebZ zI#@9kNIRQwTf{2?kU(%6L@@RBw3(Q{;a=E87ISofxl`Fd75w9lQHj~ zGQ>26uVZTJ-V}@cL0sZ0-!w^6$bHHZHxm3nW=4jK-a7VPRdGt21u1PkbgMwdtzg>| z$b_eu7`}7&ISMT*#VN$20xZAw@r$at#^|!LvIMdQd-A5jJ9}ni?S<(55A=xXHU66~ zBB!HwBT}TpHd`&mWvpARoIuY2LYmfEIp4zj!IOnVziXA4sm8wnRwYvan8f!Xby;G0 zJzl**G>G;`gk4`w(dAT4j*qJ`?>6b~Lr0b?Ss!kpaLnrt5JQ;Gqc-#_(*=_bJcHg_ zXCeLrQ~zm|uZ^xcV*%7>?_y~XI%YYwp!ZyA{kt(|%5|(x=ygll&epasvoRUPG}!b;kB*pgpuK+vqti}lKL+p0{O6>1o?77e5hxB>M{e8GBE|cqDsr77}-Rr9R4XBI`-SK9N(4`kH}OEmzy05*Mp3jvIpQoKg;I(C1UGjv=ljnG5g~yO@7oC%5)=z{(vIq52;RJiqz7=P-o!=b z8_YnY?~a%-r;BAGG;sw5QxgLznuaD5T}AqlpPx-7n=A&1dQTQLtnb{@%1kFS;$mW}Aio(H_jS`CKmbaduHp7@*PA7#qi7gzzw_@J*5`sBz1LTiN2V$o^EXv zi#Dk>81o>nW;ml%EZnIvLkG?wtD%=bUvG$=MOcBf3e2bCh-+!d^&wXyP%vmQPiKL} z#CzS}ZpF`61n(*7`9I8orVQjeK?^g!UZi=Lprm`ct(Aut-nW|3WER%{_$Cj40W)QI z0*iqH)JnVRzhOrxrfu+2BI#HI1LpLRiU#IM?dWTN(4thHyF3u1t_x8{hOR;~Sc;1< zXczucA(-|tf!sx_dd;1i#ebAu(%k<#b#JPL>`3vzrX`;5W@iU0Hdc**9^NCU#C-S?G}IWtnJKljJ&98h{1B0|HDji zubmoY2|MO~YGlgW61t7HIjW00pY5pGk zYk?~nJOf}cMWelpVo3r;_?qa~iH26AjPrtv27L~I>U?HY_*nf=HhsyFsfXty(Ff(0 zBg0$0k)<7M%t{Z=Tx!!%eAgw+I`r+2*3F&DPPbb60HD2pr%Hw2%J6QtRq{VPO})o? zHvqB-|7lx5biltcsF*Fa>Az4AM-b=H|1Ll%=3+qED6ZCv3Y!*$P#w+*F#28rC<$Oh z|K(f|%T^fF2Jar*+apQ?70!hCQl+qPUAO7x3>EL`(2W)*$_^~&U1!$AKb`_ua-sUV zjpu>VX)Q{lC7MJm*3nW9;J< z;{e&fdJW#_%F@#No2WtkuTB!~c(b4G&h*y9{=Hf*{;8$fdPkZ93(RgYad!&&?C$UV zRMR+Nyv<;0I`*So_Y$J~%L7(c8OFGF7z=)IYbz~SPClMQ9jUF~H>PUaZ)n(lX=m9r z(o=^k2E?(ryea{;#-}OB>;9X>{AG2|r>_OI+aVjU`pxlve->EF4l7ut9KMd4yxEP2 z3?`*>dEHN&_Q-;*TAGM@G#O1sM2U-+TaEX;7I$EQmFy3)FSL{BH5TKW>M=r&i0=G8 z&KCnY-MQ+c6S&whgk)v7a9;Ugv|kX^b@fbAEaDU^JomuDV+zy&W7y!1?D@qT-nBB1 zacexDrz!-Y3_>wwR4$f35(9Tb`2JqqOAc==k${uR&^do^P6Xn#!oo0~hp5=! z5r%S!ON_x1wWT7YO>zfV&RBNkd)J=$NCdApS0sq3r1rGa({}ASoC?yN#6Q{UcI~MB z>cg=mHaD5_`&kYnVSEe?F1kosxZUGgy5hcGuMR%}`819;88~^goR{4{LjpkkV%CBC zoi(!Bu;S?QG8~X*o6d7&<&}9lfwnj->}*jLx@B_xm5d58of0B3=M=<}_BX--giLSY zGgz-@%-_u?fSq}uUUqm6C{vduGzkXryeOiwm1p19aPLYydKI%*DR~!`YNwLpYfQwK zm7VhXg{I=cc4_11l6u9x7Y#IXn}xOWh%=4dJ*tJKY(SIyNny1DN2e*-ZaT31gYB3| zpaBP2=bzk`mT8v1!C)w3{MzZxKzJw&S~cK|0N3chZOB_}B@tVFrBs?Kyv%2hRxU2~ zH?xIJ@V&SI)Kx;vS^zNPf^8dUQTr6%)(Xw(GN8Ty*3giJ3Zh)~Q~3FBZhc-J!pD-U z!NNBRiG99fuS}FeqOHt;t6jO0R;1#4fxWI7;a=tSt`Az$8GU}gcP77i*P9kMmB`Ag za>keP37+?rL#k6M9Db95_C1-+-D24+EmzNv9AbN_SBHG-~n z!ZAfN3D>&7K90Uw@#lu;4r8MC_A<|33j-w)>3B!&&9Smk*>N1Koqt48KS0+#vN0g@ zo-K2BM_}zT7>E`+=6@B{H_aIrF0!DRviiSLE;Mr+vsKqY6%+hJMSS<(zXu9ZrvrPS z`6IOZ14C;r2ftWy{z%|zlK85zEszl*OCQzl%dEX#i*gJ3|5^Z$=U|YW=n4~jO{jZ= z$3=H!9~k()uyp3lckQzr?=)p*Kop2nZ+k8q8(jcv4KSwze}_?>E+*2rCxce|jtBs? z3_AkPpMkleZE4s4c72@ztZT|o#Oys%34(l_Fi4&e86h_V!QHe(3u4JXrscw3Vw{g) zsedY2`1Iv=*POS+;@#9u`QM3Ab87@bUqYU;T#JHY3Hmoyte{_iY}$llzEPb`vy6IXUpt(ojh^Q*hKdyY64Cuc z<=rKcZN0>BmIXf03&M45E3G6UGuPDf_b+V;FxG zD5xjLYSe^w@T;5vBwC?1q72JLA^xCiSp^8tKQZdXLr|(OB6c zT`1Xkae)BO{ConH`AlFaZ&Z{x@#~JzTFq!Hh3KOaQA@Z{y<85?*Q>Pr+j=- zU5idO{QNC>Paq^Hu!8ul&aEYAT^?;V`)~enMxl9B{}P<;gQL8&*+%;Vhzq5B-QxRO zl3`*rh78J+ZOiY1YfMpFW)Bjm3GXL_hZ3Ket(^E|Dy7+G$SPv3;6K````Pt*H9>2c zXw{Q5v^S60wL#a1l)q|E{n4&RcF|m}LGt?&2ki78KGd*dDduA(Q|8!qG%$G!ar#I| z5<~$YV`1avc$H(CN3y`PGrH=tDbm1D^l5T z42Lq@nu}1jwR`G|SG7A}UWQU989Gv8XrD(09!`H^Yk9>sQ`*IE6qY#^v;Lv@UUiWaQvEyajt92fmxJGM&SxM{Ro(V+l z$-p`qLq*UYf!|}ffGk=hAJ15APXVfO?^^XS^#b=al69z8*6}Qe!(8Jf+a*OFK(c~t znIO5T%h7Ej$sJqC4z)Hc{th!y%(6j4$HGAl80JnyyXn^v{=gAoyAsMr9=P2^HvcCR zX~m6_dtjIr1YTmU-N^pTDIoSKScSq8n~Lx2G-bJO)%CPWFAF6`KcJndfn|+NMypO z|2T1*u5ht8+)48BjmdWnVGiN|Bnx3#6;B6pJCGF?@)e+~3_2 zz1x?UsB>Q^{$;v11M&MMj&5Zv?a|JgBVSTevOiXN7gGFHCA#ftgRcm?xnz@el+O)_ zWkq;`QcFOw=S%*z=UOy0A6!~~+@fwV7`BFKs$cwEpQPrw!PR)U(Hj_NzIb^sLI2@z zqh}i}{sa-Ki?e48r4kOj{!hr(t2sz3ZDmSUS367yDNdiGnD&)^dnp}r2B_LJ7_(WH zqVWuyqI&iD?D8PE|D%-Aa)yrwmDB0Y#cO`E{aHB|`TB(U+vMA?yMY7Ka`m71P`X|1 z-NSuVzG|)HU%Wb;!d0E3#2`k{)ijhOU**!$C9xHwAE&1E5gjx?0_CT0vu@W61yu`%B zK;HRoj#$#il3pgX4VBtSrfW)--j_t#ubpT@wQ%?*2nKSVeye}5EZgmm}XoJ=$7%#VX=ygFL zW6nXmN+$A^1#06mu_4bYcC{~Y1lD0!B@e4Uy9_J6kCoCtZe&*RUH-e^M#;a1ucl>`g1fk1TdBBFCM?L_g_}878=cO0E7f+yADx(Nfz7(U%U9&bPozV7^>qf^p!k~A z++xwM0XDH(83`W`-P&eGHL+*iL)fR%D2eK~k#i1Sj?~5#vVoZ|w0F$_xfhnN+V)-5 ziB6IL_i?C9b7hwm%QGgrfO;d2wsyXW+}cp&fI5(F9DXV6p{m)AJCeVM4C7u0LKtb*l6`R*qq87x?hO_Xd10 zeE5m@`UecH%6oM}wIovo?gZ}L)C2q2Z!Ouk3LAB$3ox)#1XywsFqHd)*b_Ak19D^7 z)UfC+y|shxxAX;q_FMz#Gzn{r;A-_(4IH2MkOY(2(ja%?B%bn-3B+dHe=+lb~QCPh`j&Bx5Y*D zBBp7ff;sogb=qDl0B8W9*z4AY=FfH0X$aF;UR(A$g;bjr%W0rO(pxn6z zl`nRM%N`C%2dGnm1=4haWzq_^R`4yF1*x`$@Cv6&EQ{ea_;|qCk#m;|J+E1x=bj## zd!r|l#k)~eS((lB2PpV&@9!u;DrVoi8jpeIiae`g6I%Vp%4lZlp2+5JXg_n()7}+A zNm4~o5k-(Dx~b>dVFyslY?tvKWSZfIoK$~p@_glg(p7Y|2%`dvf^NFCQer)49Og)W zCM|3d)NWMGG=>PXS38X^=(i;k`Z{%SkYHqI*6{fL%9i~nx_S2$JSIuU@(6t<{%3v{ zj!b*T0^GY;nJFt)H*m`kN|Co+m?tS;chzf%Wuf=q1?38TI`D=~xXG%uXw?a^CCAA$ z2jch&wSasbIStAvfLV^z{50{@6N79;%J)V>9W3g!E(tm@s-@i#vpjf{fTZ7mMhTl7 zRl&~I>>gImFYpARgh1HO8u{WTSYXfc`JBy9J9yMSyk6~?16R>vuohD~bNRe2r+tQf z(AYwtNw~^lQgmbfSn%nS08Gti&?u>JN+;ZMIG}oy{3HqkQwe^{j`j&~ukiB-eq;SP zN`_7Qn6E{h9TTsX-6WDdp~W`!u&8+ZZ?BUWr2V7iA@Mw`R37H=HWNZzUL(6(+xhbs zMxNkVv^qB={P!G0RaVtTyb0AKe(EgVw!DYn#u-z&*UA^4pB}DUh}5u7EU=vERpCgQ zH~?d3e&K=JXE1qyssHv2ZgL627#kPt4{ooLxep&^om_{wTt8LeEH{Y9Fh1Zv7WKa~ zJn8=MRk25xk8aVNE@MUFBPH4s*7u2lJ2M**>y1r}jCMBI zy;K!#s%n=rD&YfL#n)_qUhdq?FhUf^%S6@A9$-GCmY;IghtM4<vTTkA6we!Q2~JD1h-c-Ehi@;y_H>)<{niQ32Eqi~aZMe&a$Wa)&g$rt0rUGTFj z5hi>Dp9^P#rp=Q=TFmpnlYB90Y-6J@@2xv8d`&RG*0P@$)4#^A6`dkEMz}M^PDQIZ zaQ-2mQZ=AXkg!eyihpN=g#D`vkXgZJoBT{@p2z&e*z|6v2+zePrcj^Xm?3AhPd)J+ zFo>N9HUsyExzNjX>X*4Pjc5$-1gK6iVXcRPJkxFOhP#q;RdG0(2vX&iz(@oLU&}g! z3A=}Cs4R4(Hb5*ia!Y;Zsd~z${!39Zj7-SrS?&oLyD_mnT^rVSU0Zq4UY`ADG|3%k z8_4V^iOy?m0irD-G6xf6j6lKm`%BoR#iPeOMbJ2gpv1>NRU*v=g7hUiGk*4s@4O8T z{M@bZ`0wBoTJ?c3Q?jjE=I~1G9&-uJn>&N&ULm~=+tKSbwm(wf1?dRlxD<$o!NlS) zg5KY!Cnu*pDE4t;m?o4SV}wxBoFF-xzmD4quagJo1r86IzT$UX;bwN5Q4|OV1v{lo z^kL5T$G~y*5e8vVe<*~a3wMPhIf(QoYI?QbbXLJloW0-`Q^bk1jgK}ahd1hZy3_g~ijy<~%-Fl^H^F`C<{T?{&;LL-+8Jp-aX6bCwL$(p;4bQe??GDbF z*3Q<}z{8t)F0dft7$Bp-lnqp;_wUH$3a9VA|0<2$2-i#SoBnbr^0k3q$aoz1ofXgu zTspTbdP~5F4~$(pKpz(LW}}QjmzC$Q0``jQlJ10Osf2$v7p@Gj)vN;7A;v~TfdmkB z08ie(1iHGped`n7Gr!ks2*SWo`vkLP982~4_#a6fo}8H@F$bC&xj1OS%>99dcd8ky zh8gA!^a>5?;e^urOh|EeB;M*g4%qTFE`uF$eqc<0t#Pftn%1^HWnq_xCpr zOR-(PH=)NKxc|my!ok=N^RL0Fx5&G+=E~i8z5K8DLvZm>5iBI#)s8~YC{WdZy_yRLxzMVsIlvJlJJo!PP*cP)Kq!InggzL)d|K3!9 z-2Aj0j4VLYuyAnxdsa%^Fp#I)ts9&d11Tmo^|?aKWIsCY@g7S2YH?aa$%;=hOe502 zZhu^q;$C9E$vi4|`zYiuhzAuFPMoJr!Ao?6vPA?8Ll1=J2}XN3eFIfLw=G?c*U3vqFvSnN1%VDKbV9+1-dD$%o&y|Fsl}Z z(Ooc9d@~ZRRSh+hk^DYR^g1m_7|;2GX|GY=FiJj-5~iag>xZ5OVX=(fCLzsn2n?MD z7phWNEk{&M3wd?>E;M;)kPpUJa|h&KJuFWzOv!+r?!dpWA$cDe+dTE;a~}!6hE6SQ z%TQs%iuucS^ld0vN211^p_~R)0{mk&;Yb)VB4*v1Z38qpAR-9#(PCw;DihPLwUQL6 zaDv;(dytG zjT_s|&s}e{^oyb`;l1+`qkZ_^QT*Mmt&}YYfS9=cE*$t}nx=Hr2fKT!%`}P*7l3nc z8){q4alRG7Ia(2-~`+=aL0T%DohLfc#*_89YEshZvZV?ye zdA72ll~10uYD)@fN7kwe_ud*|7+Ni$Z;l0<+Az=s8zb7Rxza^PeIZ5(zXk;mgThau zT2o=InK&v73Tz?Z|I0manjNNi`@=Z=n&3cf%BrTmG{Nt(ro|e=OA_Ea1(#)qOGD++_7Kl2vVop8! zJ6yLM*@DDT+YZYx4tI%g!aWdNjn+~;(p^RVC#29%id(0tJDf|x>l>;Y6NF;A5t9TF z#kFisku=?oT5Z-s?LrF+Hh+?^v6>Ep{T9Y-L`mZ15SuiI97CVBguzGq4lC_k@)DiypKs@CN#PbcMlE~c9tbUDXUVyxveWlpVW zZ>u#CXdeFQ6jzdoByLz>CZ|odS^njxOW*SR=EA9B+&FbHlb3vgA15wW@THOGB{4tl zyVqE0X_<(t#Lo`@rCbi&dumpsRkj0gm1jgueY69gNKOmrWHq8hNmhRaZC(Dm#V_AY zMuL1|r`yv1&8`~}=N0iSl6L$LEv6_m3{AuzWHbO#z0H1Kp8}Ze{g%Px2Vh!yC8M9p zFC-AsReO_X`5(^B3XI8%o~>Y?M90(bB&5Qp@kZ{f(Cg7dkN}bU>0`pWnLoGy9<~V= zX)Pt*jK9TMws=sx!rZoAY_6@`$8sY4rq}F(ZrR@wCfDZA{rn_0GiLHNJFCot1kRUc z#0NyJNUrnC6AS;Isk}`BDgAVq$cijrQ2|+)+qj1y#h-Ho+()V3Sn2I*tJJPJkzC5y z*5du@bsMLj6)VMjJxFf4Ro>aGJ4|5o>C`?d)|zcg5PV6M0G_ygayeE-*;#KbvUWL0 zAz?gt@azRWJYHtCUL?pfb8rrXul;!OOI(n2kp10j9_)!YyBnJh$a|zD9Lwv~XuN}~ zN>RKHfBU~pj|z927T+qrdu&b}PsBfS!~f`C!bS{bj9FBp-{({jxpzXOgV6p!+j_sS zdQYK<9ADt??QGO2C6vVN(7>k4k6}YA?XvVm52-RbHa%Pj@+yp$@+Y!@7a|Ui!dTFv zgIOG^f-ft!=aT~ub`zszZN>)P$ zO-;%_(%7NChV+ql5(9HiM^28Q;~FxY0v%pWZ3n^Z=!Lz}C9E7k9bQqQ)V!y~z!NJR z2z?>dsgK=4cwJy}ggv4tKnw%G2ap~fOx4-=6{^^iMD4n8Nse|ddX9K};r94TdYHiX zARh$MDlTZFs&h%Wr|9{H+-joXX(({#3F)kSv zi<8~{66}ql`YbQ(sSs2@^X?-!#lZqc`2z`ABPyY7qe?>ZQWJrYEx}19+9MB>L%6Z# z+_*?lNk0Q^4Mr11KS)vZ;e1hUyVQjOsi~G(YCT(V8}quiYSOvBe!Xp?Urn3}`9(GT zfjTXrXmwa4-?@Pl^|4I>w^b){QfO>|hX>Gh+f{$z>Q#xj?li%ibDQ-+QeQ#aJ<+)K zBtHHT<+s(U&^j%Cw>W%K5uI$lsml!qLGHlw9fe!9*3HEiWY`l8a;P?q67qx1vkjGf z^##5TOV%PDySV7eOI|n2^p=T25Mjn7WBY;Z&!iplrj^Pl@}Rhh4}% z1eincS&^*}-E0+@AldPp@>uSvaDErcps$)20F(zc_nPAr+?#cr)mtDMe@bHOsBn6J zt2Q~_&R?+?K6jE=t9to_L$3v=7J9lyTZ);TiR8#m3Uf4^`{tR?Ei))kwXTnLkrxu= zgkj*Rej}ruEB^ck#6`rU6CWRq?ggeODhbJ|S0%%*rt<4yFB`Tx^P+-4;^sSYtlpkD zl}!A>MtSdC?kUcKVVO~!PGM6srshjOX&Dx?Mtf?FC}v$-Xl<_|i|6zC2tN=Nx=V^u zlfZ?PQhSOEQLtT)qOpP=q4uJ{zFV)6krFymNQS?}kbpsDdMnMLL`ItY1%HE8qB}L9 z!R#nWE=4tsiXQw+Ld+17($<$OolL4}XaQUlej zI`$6V`s``4(@TKt@OQ3+)@?X6IduX%0 zcBl*;EIY1vr^fur{0t{HtvJaZWES{A!SPwp(qY0SSuqC?Mvy9+soH0bnU}MnH8&x% zkJN|G!Z%ThHwRW*(j1GQPb_PP&xgO_(vP0>3zL~` zbdB&rCyC(IsPEf8R3xqH(QcAyzL4HL<#Iti=%ksVIN%B4)t6Q-Ts=-D>lV-#i=gEV zQ=*Lc+D}?gJ8MZ%XcGZ8@K3X`6RHkJY+cOJi%!T>`Y@b7WFp%f1qieI6rxBoko4-pP>i=}0SBesyTQ#V7cAsvQ ztSM6reVdd{9m4)fWhvrpr>xE&?qip_!?A*6ok{%+SQ}5g#nxg9T~C3#7?>9e{BJ-H zZgkU;XF2(n8^1LftN^M`Bsca>Dmm4AJ)t4h=Oq0k*&Ko$N^b>PU|~Z&4ikSM6ltb` z+`v%`ru*?7b;*nx;yo7+4=W1S!c|`LCq>HF#oi^+ru~sovA)_keI6@IU_E`Gkr>kJxSfbj$5u!kldlCx&6==%Y7V z=v_F!aXy#-!+(e2Wx$-BLE<*Dd3;&pI#G-J7$s{`ZC`(`7BiLj!CxuPYVDpc97&qY$tuy;V8%##E|{lOW$ry`*uqF{jOX2F1fqt zz+L_Cn0Z5O)*w=`1l;DSonRNFGBQDr*=VP$IH`$UtjLE-rL@SBO_DNuXDR#Pr?W< z?F9L1B%h@%s^Hq_#t$P$ucbH}KBP|qKRi}a^->S140vg>KT)s{739m46mpSVurYMI zcUG5Kuu*Mys2OGH&$;<--bZ(hwv%j1O70V6f6j)mJ$btBTS$%MJeVBvbURISY@~gE z*eZIBbUCrQYr$s^%v}Ka00Az;{Kj4Z?;eid7J@cbnOnM<65CV=6$w3QZ0DE1=J9`C z@o$0t)F#eS2c~$-2Iz^kMiI74Q=Zs|UQ+>>O4a<(nw0f=IkC9(G7V*329sgMi?xaC`<>;t$ zqwk2T>*$%$z4fs<1q+>1@WZaOC*`V`8Z=-#LzM4vi%pLQYEB+MG6V@WlDdh(Gjz_~ z?_p$>k3Pk$IahkBVEd@fz28bxdQ<3x+csDeWI~hm^%=I$ShwEJNdrV1!UB8a7>yM; zGpe7-lz-KE9tZX24l^2!tw1qKn04%k;UVEZkL4!89yWjDSSy=D=$eQ#fJ$57_?yQw zL_7m=FCAtT9t?@H|9ZM#8GRt)(E&uOE(@;g|~RZ$dAOB2sZF3LT!61}v&_rrDa`e1q4Ji4Sc| ze$U=;t6bVoo1Xhfu^Q}RDzv1P;PPi4eVUKs4I;y3jeb32rG|^W?WY;&q6h+?4Ib|3 z8`dN(vX7)WIn$wsZQ{r*GihGgG-JHhBfqa{MAc+$OLEDcZuv$&p+c*t4Dj-L2sH(9 z2G4*S{huEk)eYnoKIAe#Sf^BC#QboP%7~pP97bO0Q?XTis&BL8U9fM~PmSFc9DQvm zuWtly`sMc?Y(E_c8Qc6M-r*$fyqcO8Gysc#1pTxuN&YhBudzYIbcD5>O>tg7wNg)*P|>h($w&1^aOG%X zZxLhfT)`*G5I6MAu?A7@(ti0XNi401(CRZ{cTXFNi|akYu;D(~=0UD|j?4U0XwhK)W25wtoXtx zr%pP_&!`}(S9m06MUYP7@!++TVc9m1Rubty6N;)oZ+ag)bE9Y9qs5No9HTn5*bUd# zl5Kv@a5u%=@KG;^xS;(QLQ2jnMH9yVmx}V-NdNy9-nK`{)H4JdA2I9aN(R&4BBHCD%UcE0)A?maEzxm*4OWCFJ@usj+{VdmlVaYCT|!K^X)%3& zlsCUeJO**no}Q#IQGYS$k~iZ$?TXFA??t@F;%|v(vqG7zF z*qzj}6)!&QdhZ_kMoE61?LFIzQuQjKYV?!1D)$!GSRVLusYq>?%JV!-_{qnS%F2&A z*9LQL+@#RqHw=Z~J;{$OwEP7stWC%Pv~{Z7@!VPT3Osj6ZubE}=GfM)mT&Ao%p1lQ zVa$>5y5@F47Ckz|aDNkzUPeFO?vm;-@azgH6{2?`z$7so>m2u3bw*-DDnLs?1bayT z>x2v!8(rHcITBLP{#d#mC~xgUim`oEOjIrEFv=$p`nD|uj4suu{OeJ3%o&Tt_&~=S zZ4X(T?=f0@nQ;fBKLL*Th?NExj8p zoryyVUm|M1P<;)U&1_J+|0b5b`9*V(bbJ5{aouK08|xH5sr#i5_6rV&@uW@*@0QGK zr6Yn^70wEbe|mqHcU(sDZiQs3Vve~$i1xlcaFu{J0TgtXIgdOA(`@S)Qfr<3v>4Su z5V+|*@KGw~c7KD`s)q#BhfXV_3XD0o*exNDRPZp^{73EXe^d0Rg#~83IUxKj`tRzZ zFedlqK(G8L!O~j?c=KLu!!x0d-XHA-oFH-rv}z9X>Il&dp4B#;W^!8wqkKYYv85`j zc}m&cQ&DrhUxV>_{}l&e`%fXMRDp2&%q_3<;vJ}9*smqo6^2v?;mkB;jPl(yWpnWK zfZ(GdZ5}u7z(i06#P1_GvS(+snKm0*RVR64hSTYl@&i6{*C+0jw}d68Zg0TOjIT3T zds|2PD^Thxls5Z$`e$vH1X-wq4`g^m_GP5-bKrv+O(7Lwo{(a+|PWj>$xs7gH!&0tQ3 z)SX)Pv;`g}jVbtCs|{be9xe8BB@KXpj!?ah9JuK zlT%z0e7!(hw4V`c{SYtYau0m6e zqPW+hYEy}#s><%lp0*c8PZb=A{jOX0eMds}z5noiO(IafaB^}+q1@B$JVPX=s_x1! zw^U4tj4e}2FJI92YPG||5F~rYT+rMEX#hA>%<=LNlFc#2e=_Z((%1K}fk#_2Aq4xv{~}7I6Q5a^@U7Iq9=TEH6Nx%L4&; z1A0uSc516+vd+AGGV9I{S$jni2d$km_n8+8eG;EBuX}#I4Rq~bABu8uv>LC}shC@F zINN{jhS<-s&5DqF^(){#nA8s&Ysv?7) zsi~=^X)S)(o%%KX&V1jzqCn^O(^(#o@zMGzf!2Tp@de=x{T6bgVD5iUpl;U}oak4@ z&>&}hy-@GSCnFlKlk5w9Df$?Bl6sr>l`$Z5`IrMRO$LXtnvr&;!vdGAY=;`XZBZ7S zt?M%};_yet!+ra;^K#fNq&6>iV#JM9E*X8$U{Di^UynKr@rDV;%LAP$tZzkUfUc>z zVA$7@!fNPJbr03d2Y)Toon` zJ=jQ+)ov>_MqiYIr*o)cDqa~qpRu$HUK$n`Cu^!oJ;4cutuPtU8JV91-CkQg@7Da@ zj|uCO@9j2r^S8kCkT-pzJrpzRl3v_Ny7U*`bg2JA)k7?@RepYVi&HG5ym%0Qd|gan zLZM`oiHW;af~W1G&0%tJ>Q2`ZmooCaUzv$XIhDZky`}KyIm6>NRfOo)b(Iu+$ytQ^ z9kXONuJl(Q&A|QtAPv31KMg!TvBc5E9EKR)0j8vX{`^4(eD{x*7GSHAESw73ZR#z$ z0IL6oi{$FmHWF$2t6Zdg!s+SzhDeFK3ltz-zlTlExQxdBCu$Q^qW(LF2drfW+<}(D zfG1qqeJ$UIP%TAv_u0+do9*6K?xhsA*EwGzz(o;%0Q-X?nN|=Q)c%UIYRRVI7T?EesN+5@=aPr=3kdM#${uS7z88O2P{4SX zbiQtN=m-CW((yzo|5J-?g`j@>gaaXYR@Yigy_KAjw#nkx(lvE34}7C9ap+ z*{K`icm6HwnTtSBYazc_`zVbA6)2LkwA=KGHmb1V37GW!R;{HJC)%twbEksHbp2bM zeLxX)?>DBh#*Z1?+pb|@^#JA=J<0}Mjpgq6|Jh($7%;n`9EGQXGr3Q{^Z{g49+NfW zlud9H_;? ztt5Xz|Gcyh@(g`-s_jYZvmhGXo7xY+G>QR!qQYd?3 zOlt7t}{v1C7M8SNfV+bse^B0j2A zS;ph9MQjzdq0+y(EUicBD=eaS-xXXG&uLxPu1R_{OBSLqqW+jQ@xs*>>}2Z{T5TF9 z@}y=samEtMmO;cQkZz4LacyA5akG{e*>%HWt7Cpi~1bvnKGD3Ui#J0;-B9X=Tr+Lj6q?tPUAw+Hl zP0o(buR_FhCgNKB;p!Phv(rQgGYy}xMuilJ6-LjU4=OW}F^su%{}l>toT{Z-N$b=K zT@(B#>R_1N8e&ut27p)aVUCER(8+SJNh24#Wk@+ht%eyG7_5Ggxa-*8=K$AQFm)h4 zvQk_M`J8r~DHwEWi#haaJ#o`?`4C~-hJQyUSk#UHA{gogbZ0hD%C zP8N9B`jJd(X_?=tZE!CV+9}|5;;(M#tllkdIe0nvKY{eN$v8_u*1qTaXz%E3K(r>| zlYDZZ$`xIiY{+`$6^jZNt6?AM($yXBZ-(r!j7eF6l91gd#VI0yc>v5{eo658VB#Zm zl=y+1h~@W7ANQ-21SW-@e>RfdTTCy6rT=P=ID`v7v@E<@pKg4&(8?flOM&Q?C+zKe zrJz}7eMlyW{0!?Gzz5n8PdhnOw18>@>{AeK!Q_Z>pS?)8u-0D<9R&&{Hzd$lwt zH47+vG;VxI<_XiB%&?lv(S1p)^g4Vk(P_}(&1v&rIdKOCEylMnd0}@2RRIF!H0j}?aFXT{5;=*U!0RQF~6nFdj+c8K{p zO%lDI^%$@ofSL_?uSzlb|#<>xojIeVcFBjOb_O^JoCG1 zUmi8IU;b&rV%+e&YY7ei?<1KN!Hqd(=gn)mb(Lo!8M?fE9^60GT8(lY-@!QUoeUFj zB$JSoG`UvJgSe@qbLS8mR%9pU$o#1g{yOgwH-1Drv}~6bjXuhBkksEP`tmCEuXjs% z`_R_>OAW7;cw{wDJ)^o5F4HT`^W>pMOA}29GZvkb@+$#l3&G<)1zigWDY~#!4zHu3 zcFOaVBToMa{4b)x+K*$9Db!YLNN*5SCN*KLhyx1iCS%_xG3AoOoJ)c-w+_3seB#!R z3ah{yfD1T3fR7dk0SJE^8|kN!@8i9#7%ZBs+1vHl5r)*02CKXqdtAhhBgEukk(1MC zWkpeW+T`2}x>a|EiUX{T^Y{|Ngk=VYPgu`j3l}o-GU<(0h*xJ`?u}$VnYm&=T1ckm z^AJ;fKS6vVB_*XY$4SAJ`PA{=TE)m}6+F^DxssO-Jk0^2@WIqN<1q4P*SDgEt@Pzl z7oN5Kvp6HC|Ds>(_~k3W0+7|B8$Q@!Rrsm zCiE=?R;}RE^e#)JMOAO?YJYo--`vVK!Xh>^=N7k- z=7++K-|X<}Lo7;3FQ(=7nF{?K$S#aY==DJo|C(}rjrquy3rt~we=F_cE#~zm&TpcC zSDDZ9Y%B}rj%s3VWOuO#R%)XW)kv?)=z4kz>OF*?<)wcx{UPT~bD5SgSRr+HVVC39 z1fYo6)e<|l=rwAk$G|{9uVi*+j_p2jOd*XKKTt1vHo%F~fx4|pEw?bb(DS}^H+9rW zmH6-8Qkm8r&hJ)P)y&c)!y$EtiLY{Gz>@%?OgA^t0oH9fMMuXuva!|W_8Wifn8>LG zWC5XWA?sb^cRBmpeE&G-%Oum9wNw6?OYy!zYvn!Z!HDftMsRP`i5NlHRy6zfNP1s) ziQmE3VwKd$E}or4R@jS9kOTY7=13$}Rpcc_wTVe{qDs2MeX-CeBqs_wZ~$2Hf)7lw z>d~o%MTh0!i+u;57B00Q5uqQYIl5oQBaO$0e74QeIe5E^JXsj>98tH_HKkb5^7(T3 zc=BUQPd%y?jVo%AVUKeMooIMbp&$sJC&)zT<~=H66aD+v+}%oXl=9R;+U}X0rwH?8 z8zHlpDEC0_sVce`hl{}rt3fIkF*H2&@YqRmP;0ey#l1#5mP>-O{S(=mnk2KEf z8^CDc8sDlVo~)aE`r1Ez%Xpc*DMn^tz1)9HF|{*2>`-=^RKpPs>v5zeq)H74vGI(w zS*KY;;v;=M{P9DeKr51?^~E?QAEdX^442*o#GvwE5%if1ZIG=P;XJL^h#)@c%DCmV?=!^;pls^}>2rYNP|>p=Y?Fg}nGF;+2hZr$T2C+^_kc|5Y>TXUenc@e z#V_NeR));QBIeH9y0=bC!?HL2?r71|p7Ac%eMh*!R|lPj^#w+b#cF_4Oq3Jwf`PHI z)5L`5-3dq)s@qT-!Sp?Vs<^pF6{Myb4UL(JoZ9Qt?U>S2y%yRo4Sr&0<)bmkyFAz- zwLxz<_tRJW1zGZ9N9vlSlq%?EMx9%1a&3fLe>N_AU7-D8w`to|7)-7o)&v>5r^}sW zq;%Xnh7~XiRx_Ro{mi-tOPzR}-noQDCbROn^IuZ*d0X!3PgO5*ZdvN~{xiIB*v+e6 zcA8WsR`aW9t;JLjwnZF2W>1#G-WMIK|6ps@v?Y{JHdcR7m%TGOyFRghT72U{Qkw1< zt=I-uJo#3EUyD+Dv5HC*xf|}uK9zgU50rc|*T*teY}>B5=2*3Z^@|o2Ya8xy8d=q> z5H5MMzX3}$CJKvvPIk~OP-cF3c(~A}gNs>7hOa`FaMsKlTcnA!i#;QpDl_6Q!!$+v zNMMQU(w!x|Pu>y*BK%Ad{&77pICxU1_HlUa2Mmj<6@F483XX{>p|)ZoER-B)$$ZC@ zV0h#zd?oN_=BbYtWl^QtD07~#xG71zi|&U8Wa>K3mGdjal{9rUj>0)7x=^WAG{P(* z+uM)(rGTo}=PvGm{&}|BH=X?f42_C8{p#Z=mC~IV6;~V8ErwRI0Pq4)0(let=2}%+ z3Gu#Q5-Da-l#c`&naze}yq7GB&x0++`d3gF9I3d|=%E%HRwj zctLFrUHuDnR=WE$8+EhCqQ}q3W=qc;oT~}xKF?C=6%HuA7ui)3prMQ2&uGZr$A>|0 z#mNST*n4>BDCf-wieF{FNm?r*P1Lb4FS!acCva9yUh-#+FTpAy4Ir|%=EY6tLb8`( z8^{1BAmD1c0D9fDe85YVFs}u;4B&YO!`buKZ2r2<1K~b^9eB{+gH0pAz9KsI-*zpB z|2YIKYZiFZwcl75nf-ZD_XS~Ao6L(j z;jcy(OX|}Oy>U5pAzT{P|6_1m6UFF^cl(~AFVsNFPt~Rl^xq_DwGHAqy^~)pIQ#6v zHM4&xxi(#|-&&vjvn}gDr4!9H>g1TQULM<=wop{a&L%6~@5>d7Qk>OswH)ubzdd4X zT8&S2=vF?6x^^_qXa;fKFgxAEj`QtH;!vPJ>a@j%P3BQWpbPhOy1eR)oB;pl3~!rI zVN+vNou{Vr-~}inB|k-tSw9c2rCeZNW3?`eDd668p;n1M6|>88ozgp)Q9dt-;#&%T z`_YAa>M8Fe*-|OrzS-BMExt0Rm34ndWa^{bTL|l0>E{PQcDQAl)(j(U3a5%lr0Cyn z514N`XTH*+Q|8O*mA%%F&`U+S*NZ(Q5>h@wb)oxbg!)8y+%fkEUwHg;-$GUF0_wg; zjA3-lb)YPig9M_9D%_`-@2K%BL`r5Gx+3i7kwZ+X704-$jLjKQ`|oX11)VX>{H=Ff zh7+^aintL&HY#(0;lH7~3oaaiU+#6;n_%VaX{ zSQ}ax*&fB+;gn;DhkxKM@ZkwY-g{BkW|w!tA)NABd^;0g(X#T{ zxd1F%auoSxo!2&ks!1(LqwnHXTuOPx`W!yI+d-lYu-TW%w8=$^c@7K{QvKwD{}D2Z_;jy9cA=8mdp$l)`S10-!j<5Y zut70%eVWuyRkR!)6?5IEr*#upf7gF%@gisIx7iB&uavg`OghvpB?kJpe6&5tm9RQ> z@iT*xI{AjB<&q%I4_v}<0D2|6tc!(Q^)oWXuE@Vt-1n#Rd*5iF-PET2KP>=xYagS+ zxY)OZ#AvVdY3+lxFTo{e{_hHXpT*~3tE8ZIEX|%-lMCtenLCgRost8{%X3+_8ZHC& zoF1Q4YAmc`UjU_K*sS`VryzCTXX^v3n?jEZ^d-ru(JsnT`C6{ ztE&t+XUUk3PMdRp{nUys3IW^E8Ht6h$74!<Jc4AQFDM%hQh+v`!%egKWu> z`+IvhELWmPP8?@>8sTL@nS1;TPUC}}OE#Nl7r9n#ZXed1yopFKJWIySmSl>&Uu)YH z&D@5-6w}COwQ#LN)(o1`IfJ6L^|l&s;fS)|3J}v8OysQAxScLF5g`+yhmIcPr%wd`tEfkP7rryYrx&y!5>*hb|fu|0FG+ z{hYu$m_WQ%u&ieMROk3FumJ#08&!5}%LV+Utwb#Fwy5`!URaqZo)n3RP z+*?1ox93|{NI#L$5n*vbYE3shnxXMWzrN+KdZA&$EL5{ExdK$$fDF|M$++Qg4OqHU zbk>cd2iX=2hEiw<(2EKC%*m^=jw&Vhs__+fB)%ZN8~GFzhKKXxqsdI!qPkb8ZwrrI%G{t zt-<%VI2LYRiE#J%hmP{2l|Xc(lMEuPpN8pL@@U^H%M0TradA@rf*Hc4K)_Y$)7R;j z78xQ_Dq849)B7mzF~}lgXk`l^Un*f_n8V-(+heJn-lq;M2;Bo0eQ(Zdl`4Wu@~@8Tt6=}*y%n)|9O8#ix3YeXq+ zyI!C7go>{7hb45;EmsuJd*qk74R((cf$TpiNmciXrH|Hca8@YquQ#s;jw*&bHer=v z?SV`8Xy#6Mk3tg~-*8j0xJc$wDBJ$fqg5v};OImObm}XWj7F3MUKUBmu`kY!r3%iF)GK;Cb3b1uAXv9PKb z*)Fe!PcPt=EUG8b*^P@E`{Q0^MJK)r*J$25E{RT-sy-Gsi}3TO=+ht7hoAozl(Y8& zpkrSZRspC?1QO`gsH5X~_fFwUQK$^PlBSI@kZbwr1Vq`peDg0j^u%<@3VyXCShlcE zPx)CMVzT!T?g*0Dy-BXe6r>YBd+N4pj6=&b>f20~B6qygsSjf{XJ2$i3U8dtDKE^E z=(s`iR(WU7sP|xt&$=OOR6Y&_S`RoK+e3fCKjBlCkBYqT?^d3vblIl|OS);l3g6uq$C22b!MuKvqOWgo+(bG!HqV9k;0NtV zmSrA&<3pM^6Vt@zG3$w&l((-5!7-SV1B4d#ThJC+uKYrU?31!!j4Fl@l}X~eoIyHciPS;s7|$VhXq9_uZl?!8HoI+khb24gc+H$55H@NSq%Sv%%TQjEOet z_IZCF_DA3XN(xD!3L=OdsWuonhC3*wxj%*Z@8B-2`p+pL>CBEPGSc8b;$3K0bK~$k z4DUnK`ZRx*Lf_0gYu=1NGb$iy2A|#(g;aGr7~^u}JPVK@&E%GvJ&HB`OmSO#w?J@J zJ38g&c17PQ5PjgxdLUBq$;bv?8lCDt+!PSu|5m(EbgUm!i1Ld{C=QQ1z;XTC?}t}! zDK&JSHsGq5zk2$7!r^+4p*Csp_`~`ZKyUrq9n5Xw!oZvYn>PA#EcznadC5qM9^GtY z5ti3NnUH$phNy`cF!qi0qfctBBuhX_ymXd?;|3h8t&1`hiWEMhI*lufI z2X3ygnR$~VTRWxjKVWv_c2%Ol@kW}STSN-t9 zl$8G-oQ{C71Xz=UDzv&U86P*8TAIj>t&ezzK~F2tI7-l{oY!wca4G3IW;*}rE${A_ z&0K}djJH7p?m_kW5;#4UhPGyR5U7)51MVgwGb|}JzHR#k)d6418Lnj;%Uq*dvy-F{ zO%zaFw`h(Rn)-WI1%7iYyDTASLM*#iAuD40a0`7BG!Auzv#yKJ5|vq zgQFzDL?N}~DAxjdC7`BK&M8_G)ZgG>X_g;Kk$B_=-XI6yE&tsGNWM^jNsc*U_@>%T zKArw7_Nrj8Kq{NWZ7@5s*q=Qwr)(de11p z;0g;v*{t`Fwc@$WSNemc3wx{gS|KOmQe97kOa7$|pCrq_HL6TBP3KTp>*F#Lk;!pE zyO8npMv^d=!m%Kd9XlRwx8F!j`NB84@~R-cm)~R=vuTU=9Hl3cC9W`_BOc435p`;8 zBQ!aVjnANnK14GRH4G5p&oCKcpI|jMs0-2%(!OU+_F0E=oTtTtm;*+6YDJ{IIcm}6!7TTDdfO6JPNucoq6}hvMWBf9Sr|6nfA3P z^`EuR(v;=3dC(K)R;qI&qo;m+J@GjcHz-tlJo+<%$ycCN^Cf7Fd2la+_ey+Lc2q`B zxKPih+b22xm(25hdxeMb7Gxk2!KpgdcY5~}KQuQsv425I-pQ=<;FX*q(>b5%5lXt3 z46I;y{du--mhp)nh=m6)Yfuv6-I^6kw<8)y_0XWCE#AjMhPA)NjPY7~p{k8Mi#NHo z?q;vUZO3OYp?5YY#@zKT6Ekp{R22w+$WdTqStM)cUA70Yo9EYwE1*bP|M_1VLL$Y&nsoXu>!=K*UZ|Ay}qH+KwTCUWWgMAlt$*HSm6_ zyXP^=ov!@6H~j0^xPi8h3WyEL)aiF-_4f(J!(F3em1B6&6gF2`(Lz3~l1mfqS^M06 zJ(aW#3bsdvkhf8Nof?>9zxpM(^{I@uhbT}$`RcRgKc^2Dc^#LbG>E3vWlqm_yqO(I zZ^~Ny)%AoeiZpKKUWl10vzz#)XsJm@#S*$tOEc$%HL3tPF)k1QG#iG$CozE=P(#BIjA&ZS{P9_%IPUmo7fGc%w49I-%(oilOiG1&+wL&war z-Njyr@R)#WzD?5$-T`sOA(p7*CYP0FBPHnZp(lva`*7*|e*GnOZ{B^y>r#)Q?MrLx z!Mz511|nu8A{O6${tpin2Qr`y*AC~WBc5BavcQtXij_8HAo7-ULSHmZ7q=GN=~(jL zzGA-RLL*_$2lP1z4347*(vuIf*VI!pG3jl|aOkEtH+5RwKNJ-FSb8xCc9P z@|z#f)jX8o{I}xjBhV1kl(%a{jx6G%K9kkJ)0mdRmj!2H^jfe>6+?53iyyDO9hnrF zUq0)aE`N=G_n_}+;PO2Pky{Wt8J7WDl((ON`|GeMQ^Ki(h#*|NT~)0i)5dj$vpL{W zjDG@Nx)Ql>u;6xAew{eRc8*uq@V8aNgvA2?+sWSzpK*g)c(PyAfePZYxgO02(~3og z?!i%~xH6Xc-cfp!h7fZn?1J*R_~L!{v|CWAgM0Y{3T_0Kc&(Tfrm8Z;!2w{j+7k~} zdRgwc|6+_ClMg)KxSXW#elkGddXt}e*&(k$>lJDDzHjiE8+1>2Q?%?Uk#=sKJVoE8 z5sZ?0vqq$}iZr@P9uxV9$N+(mz8X?AJ`*Od;3mrpxBZ+9zqTT?CCzGMN|bN|o1; z(cdyLS&cyxd1LFi=RTd-PJ#>!Y?_v9W!UD_Tu~NE!b!>*}vD#ZYZ*ul>?I#Zub4pL^QdF_30x*W@(nxt#)NBnB=B%et)sNr!A=7 z_0A#s6TNm|(&OV3JSZs0v`}p^(Efy?u!ttW$H$iR2oUMO^DIia2Fk2}ADS@2fh5rv1U;YV){TvgKHQmG3k?(3ivlyi@CKQ7I9aC@R&_#vpZ{OeU zFv}cKP5|hPGwxl;6Oo zm)DxablE5F`m+U5yyi0Wm+70anuE1Ly^4+PMG{8M1x*Q$;|F?L)SR<;d!cVpA+Jk` zlZLwYIj`4K3%qA@mA#gpTUn8N+gOSRW!y#nG<$YIL>;{rzaA}UajhUFk=Sz2z{RXJ`DL4s8iE4Oq1smr zJ!OQwhYLB30IJ0=+I4j!Wk)+8A;I7IZ=BOVU|R4URQ0-AHnd;yh`zPk3LFtG+0C8{ z53h(=&xb(Gh!-MI3>`4OK+>zEZuKeI&d#R=$|7s0wNd8X6G%TMT!$Ne{D{llevMIT z93b6WQ`3s^RORaY=LTjksq^=jjVj~n%dL{KV^pgNIfx=4_mS^(a+OYC#Ftr|AWCAyx z|Ka&Dqsj1ew3R6)r5u@zm465{`;M7o0?kMv$ikT2Aq{H*#vI#izA~%fnl<2J zfJOzQ8IbtiW;VXI?SH5xac)HY_906-MogS`lxG-nV-A%-`u=h>!h@mR76N_>v;ty! zb-|6s5ElKpL=2Q1pxsep!qkaSwCGR4dGu&gaMd5e1f}_ksVoj}2uwCc*lTl7m6B3e z+{O~AFV^hcb_;MJ&%fNVeCh+R?&8XUaG5cg9ZWz|3O=8-d#vB(9=#ASgxGvbGP`$v z=9AZ6FOvlo-w=-HNDGNF2ReU1O93QNl3U>F_8|%~iu+PbkU#=w&%`J#00KopfYfh5 z?(|}*9A`s^k1v1S_<4GQ?hyf=E0)xkX*`!fo8IJPH{q!=3|xv0FXK=F>2rUJ2soTG z4j^moG$Iil>$c_#o=x`#ZYN~{e&@mKHiy|fE@<{ZCy==%C5?<%XOCHqE)|CjUCE?2 z8n@wb%i@{#^NShD6AGodV6;(nozoptv{CJu^c>fb9=7cZ8>8_>H!pJn!@@sA!2MHT z$|=ZlrRcl3y?$|b4Zk-N&dh2N&p;u%AP6N8&ipLX7Goh`n=96H77JDEqakvUO*9Xu zt@F!WDyoam;tAMLFL507p$ywyJj?i8E^}r4R-CR+JTPSM>YAr-B5g9^lj`mea825) z9PN9!zEQa}Jc~Q>t{HkS-B&uh>FiUozEwbms(RW?k-qSS+Y*^_hvKL`fp>oVSm#tu zC_eGlz}*rRV)-TC@6)2=}aQ2z8&TIpr7v5bvlA z?2ZdcCGo*(DEPiWV*)tffIzX}cAaRHxzr@G=Kp9q>!>Kd{%a524HANcfPjj$ba%Ia z42>Y&Al)D>CEbm5cS^(1T}tQBLk+yQ-{<|U<=-robMEtry{{b@=m50M_{agN_JA?4 zP52}H^Kqf%A!ukLO~Ww_Lx#Uo zIA6C`_tDG%oIj+T@Cx#Sw#jYZ?oqaxQbSp>93kcyQ-C6~`EMW$$R(3Ucf!J51d~gB zPs5L#ie9$H5EDmGxPcc|gAzYjeU7IeC{^a}A9?6_Z}g)t^gez%XTb3>qvtd@j*5oF z=hvhO+|E0?y|C z_>Hu|u>yskI(5P+Af%vVLRq4Hvjzi&tSY2>NRlcpe- z%kN8Nv@sYKPwN(FH`9Iu+hL$Pm`OMW>4bMuJmpEf&1#%_)L(_r$Tn`OPWRmJ;YnTm zH@hY!=@#w(S2_$i`?H%x84r_bLzh5RBsy6L2be<|mQ-|T61~WTyL6_)^a`{tow%06 zj=3g}GOSZ*5=96Voakt0Xg(g#_oR!pm&X8=^@pLGtd)cVS4bu3!V8}kx{I1AHL*@;+#Mm%!MC|1P_FNdoP_^tno1c)89 zU!8`a#0wmeodb_8FnBM>W}GJ&7fS2;FQ4nt#*IoZVFE=je?Jv?W6w@jJ_4fjEr19N z+@8lvl}EtS=HczVI?ZV#6zf8;a!~EK$(~QTG?wD|=G97k?x=F`1^nxHff0iqX*t=W z));Sm&81)%^dXwuNh$Vc4dj(heQW^xVD+Y)J>#zT49DB|>$v@KT`es=T~F5^{xRBt z>Nn9Rkn(lCbUU}D_nj~LATwprx2%ej_t-IgJuL>1j%aYmK-ZS$ifM$aiG=TBa+}M} zx8E7XQIylXJ5*sQ7cSH&%pV&Lum*)WFKd_@2wum0isSg$n6I(j&yhA}vAJ{dST7P{ ze9NMEec|bDi5j2*XSL5@5XWlji>HbA5H29NyQ}i~c&nK0QVus4Bs-AeI0EzRSbnl)QAylU zYAqVeK;tp}IiXfI^h(TW)rJ3`kqh`hDS}v{WgwUThE>4bIDX$Z`_}1LnaulAJtrH8! z*VVs}sQBUxX+4twng#kVFQna2)g{b0@*K#AL^~bX^rt`i-7tw@V^U+X9%w90FM1Rw zh)_|1ZG8UaD!&$!Y3NWDIWP+)aj!A6`_pcQiA~8eo@S=;IY=w7wpIdo_fZvBHDEQm!UNpzbfxZ4`27UKlneV zSNm2Wm)&6!)qn75WJ2~x0zfeuqyBH+bWJ$#56YAb%5>w#PgCfTaGx|7%=jlF76gMf zLHN9a2(}5=8IvyH4XzdwA3PsR#@sp-%|?H9;reOxhG2jHZQ%ldh=Cjwn$IoG5|XHZ z-CYytKg&mna0|x`TzPp`|1c(ZsfV3@@xXi(-Ix%uO)7vs(QF-jQujQ44fuk{))M4hekeg4DX$*j6*LT9(FHuyX)4ke zMc6GxgQE|u4NYtj8gU3l(0z3d%l9<>19Ga~WmkLR6ZKtmx|0Thku_KV>R?p{(FwVPn`HT;UuqOSf3uC7%iD&tQc5x@~yW;lt5%OCsD`n zP0qD+V$mKmHE`X@8qH_5yIz^U1{P8O%L1YT%Gd+oH(A- z^&gTpx-zx1&Fq(h4n7{!7*4+_!MkY~1&rx^fCgiL{h#@4GQsESHS(WRll?Aw&TJPE z{;=s`4I?w~^J&7H5dvB{Gxa^s`T>zo;0}%cYY#a_aBNGln z27)vH6ehh?MvI2jV#_lhAACSDObTig;m^nx@oQAPeqo55xZ9{>S^7$s;QBtIqH~W? z?f&wu}#M7qj^N-S^S8V^yAYBt4Y_p&Vw>I;7A=bl52 z%p3AnId+d&{(v=j)y~Db?>>BI*JWXXH$UfFi5N{!^K`j)J5&S+_Ts$&7W ztcj?EJE9y2wtPDbWXWSaNHDf7-yiFrL5j{aF#!i;DN3sA8|e0#1ky-xpo{B`kJR=V zK~e;gRcP}kFTNfv#GHczm39bL*dcs6_#jf!kbLj)qL0)NBrJ(;Sft{KwM;?s1uv>M z5*slB(qOoCl>w*FzCWHIx-ilGvqQ#4f_86mUB}_T5wz<{z$ok=#3V~*}PjpEyyZU|dsyW1 zMaAzrc3U($$p(MBhh#bkGzW`L_<3azX>?9zqQuinQ5FwzpcFVX&4TJPaW==AuOqFHx9mSBwq|hjs&<_DM0uIWBwT(R<(R27 zsDl0B;K^*;xcQ^{gH5K3WC>%qq8D&&x+_WM zu-kOMh4?={QdWHY>V}nTkWAN-gh9ciZfJ+)+>if`&cOTtRsy!y(0Jk|KMM94yVf8( z;#uh#V8*`Yr|mlYm%`V>boShUdV{gU`c0+$mFc^zf zTf!3Gf)I1HRq^AZBsgtw=x{JX#O6^UGvy z;l>K69ups3*S?2{E~uj>0mLBS&#;*ZN3l)Ddk8F&F$aF|{(7m&AX^ye(8}|^(;mC< z>UqxUx^$6nFPJLBn^jtH*q!I)Q^!hd8Cg59dDy@91lV4@a)5LH-)0hUfzitWjh1n5 zf`Jb11S^_wms<|{HR*UXmlD9cG47wcRwAOp;#C>=urY}S zh65$SAi&+pMQp z6X%7)cuOTn#<+|&dMZ@U{cPQXF4soR3 zTAv3OBz_qu6eru;1SmDfUYmE#HG@4Cy3q8$WM7_uF82C^xq@w)S}sc;N|FH`RlHTY z^F%aw8s_t_T>#8>KrkDy=RFgI99wiRoI;%g2FCmPf`(Op^9>rY`R{!LegXebAw2uB z@ueoz8T4{D*>icn--y-l#yfQA$qbyv5Pt~DIFiylY@EqFHS|8T`co9gQRQ$3Xmt*& z{Oq~64AX1u47(y*478JNCZ%;P;wnwcpsf?qR1$Dbwi!c;Fb)cVOk7|%9mgXy!mF4w z7wHVbEj|gFGb0&25m>~N9WTq6UV5TZtc1k zI8k9Q#}$1{FD9>TrIH)JdhK=*=)1S9VxmuG|KkJc?s);FEd(&zjgCf%I|3)_cH61GqX&R~u?n zKKNKq-pgAbvF^=U=Zq!3Jw}+|Z%)WJ8gcGRe4|>#xNtr8z?j+PFowlcD5m(0wj`U$ z$c8BDm>03~?HFIoRwZYnjk+CCP<)Ep$_a0KGV7l@&Mz4C6RL9IK%_H(--4yne^32X zaQVYPFS%G&WG#xkh9pty;$@~g%jI1m2YLq=Ps1z{XL97XExQWvZy0OvW*i46`A5ig zR@#5}M#NL3VKLg7y;-hF;LX-L>zr((?sOP1hyyHcxU|SXN+l2L=+=38ber?_+dul` zBxT2lJ5iVbVGiP~QR^?tAOdh+5MBXnnaG?gfXk?#1G{}*^jav=b}F=XkSi+(^B65E z!T8|H?L_BK&(vHH?=10X zbTNz#eO=h*cw<)<@_EU*smNe4^UZb-h$@V^4>H`upn#ABCZ| zL*FjHAJfB6)cr>0==-c?G(n7ISLM?A9H?g?bRrsA5J8&ejSQlBGA*~-Xa9slP1VsB z#{vY^C^1e1gaE{2)9@qHK)!~h02tI>n&XS+d1lNV)nL(+KnEnnQOVhE*e%^SzvDUhMr(Bkpt7p9&=pUPEDM{<|o)fci9b89KSFPlST24-No> z$>%!et!)Q_L6N3s_pd-HS2x$+x?5U0nK+@OFe(pxEUb?W|D@%rihoIJ77!W(<2l$#Rw zhk0tlWib9e0Am71I8H5(9P-~6da1fLbP1qA#{;(9mCtv3)PS!4xd)Oh!k!KJc-p0$ z6!&JbeVLf-Y28wNq+&klTG4*^CVPog=FYEZ01D2#*V7 zoVpaOA3ppO8Ue}0fJ(gI(PpLF_Vse4dNS9~#5Zl@I23Qpx$m6xAELwKV#}sZnuw?* zgsYTJ8lf;Cp5krL(Q8BRC?GNrLrS$ zV7&53DihjHR&iJ#TXY}k=&U%B^NrG62OnN_=*E-6A^n$CI&l(bW;O#}GGsKUF zBXQ6xUGPFe6^q2gOd%?QPI7=N|Cf&U3YS9269H_&jD?+vfcodk1rw}glp%o@0MAml z9!u<1m49cD>p@2eR@2Y~`HF>*m!&`B+@S^S5)f8Y8&RNO(e&6p8&9IE(oPn!i6a;d z^OE89Z0007u`5`wxV-FC>u=*lYkrNU}bv zqThJ!@yy(n;ERcf+b_o&Tlc4@6Z0j4TWlT`>VV*VheL*Jq9##KbRuFH4_!dB2O z=S4j$|4kc?$^r+#X-5tE3a?;{Q93Gnr+54aP zu<j3-2@{$Bkh5A(*_ z!^Wq(&bRxi4-H%2qwKNvb;0yul???({^8>NYRJPMax_VG-UT?}A|sg12K=S;57l1A zU(iE5>|^n_N8l`lrLv8<&u92%pkR1F-Orw~Llb|7-08>h!giT58aP~cwXR)}NQ6NY zMOp0(JKsxo+s|7F$V|r}jlSdAv0@^p57+MJTquY4=Ptq(4YV6_YOKgQ@hP+C^;5)% z{OI%OK42|XDdXo*_1#;~nTjNiuLsOpK1xq@OdNw!KWHb8wh~oZ+Y0>DK;P`bePQsO z>H613)0-kfVnRZxTOBvLh-B=c0w5w@a;)ly`@K#-E~)5u0mH9#68)p8{W;L;ImD=< za*c}I+AF`Kphk;+LU%>TEi8P=wKwUAxpso&XmNdf6MQ7NR1nK z)K(dn?<4q%`WNFPxkWRL`Pk)U9RuOegyIY_+;@Y2kZJLZ^DRST?l8t7i&kl(M$-z) z-s1|>UmsPPDOSw8e;g#gXZXjWnS&-5?<_j))HM0qZLiO9T@Rg?hPL9(*+95?Lpr4J zYxd&ReWRlNwoGmZ3-iTIMaYo>Qf6e}U(5EHlwyiKr4hw@rK*P;e?RId_RpVx-lSdm zk%aA_7i27FlqJz=?uP{*)eLW|74~lL#D2`1yfp7QVN5Bh+@Q;5L3tDn$S~ zKK|e+vf+|ZKD5SwG%I6HY$>o?SH)@JtrWK=m-pfjW_M^q5gWx0jO8h!|1mj$rYXo- z?Jw@K z)fuUu`Pv*-=;a6>pB|u%RKr=vZf!gg=mGP*uy0KjM=MzZ4f%dT-FBDN(BfyC9GXg? zUOf^iy7&gD$#}YB1K(O^-!3`)`|c;_SWYk5U@|k@>Is>2G#%1OC1hQv8|98}}Z#xX<6((oexw zT^gV7xxFw7yzec4)A7A_tDt&DjFPxSPm=+8!2Qs}iNzegr?__i#818hSnd$G?aE@i3fMZ8VW8I{bD%#d8A zy~;u^TJl5=gLIb*dFK5)Z>jwS9&uzE#JEo+BYC3SsbuE-d@g+U?XP$xj~b7B5h`%b z4U@;AL}i$sJfG(Ziem-3`1bIDYAw_p{!STJ4@nDQ+qv2sRr?)CS3Clw!N_Jt>uaja z{SAk$qNf3IM!5uGOEgimnA{~Xu%p)Occr|C{F2NK<=oK?Ndt99WyZOX=nXZ>KH<5t znQF56|3EL*xQ$h-cs^2s(dM-^fF6_K_Ylt`ZiEN*1Ispmr`DzQGr5g=@a@{Ihy`57twLcyHcKoia^sPoBV4^wNEFis=3%s!Em?rgH*(Voj&T93= z8Smtx(rcW1OfQ%xOl=uj?%^IH!P+(Tf?ht`JZkCg=REqy{N>L{m-fGl_EwSU*1)|h z_{1(lsS9-q zyox)M&B;AG)^C>2E9urd8FRj2zMsDL5sgIWKMs`gk<1HX!;V8Gj8rvBHq&{*HGz z1_*Q<{cY$yfr}YkBTDxk4AEt;*kB(<^NTw~7~N8fG3+y|(qpjdr4eanDa5Tc65toL z4PRP?!q^&SbScweNgUi8efWYAzb+`*tQ^aE_lk=6V@;i-Bm#qE&uX~}_&BdmU3DvG zPo#_|Bu=`?5J4EAQf@P~97;g1(lOCgUAYfik@3RxeW=YpvloZ25AdZf7nx@fg48Rf zkg7p(oNj3af&gzg*~lCLtQ9BNors0~&7U1hjpI+rjuw2Y9?w)1A3+V1D)_^0sL#Sn z^(plhQo|)t+(LlZd?K#C+!C=|NBDHj1_?#*c#cxcCLyK~k0JeNYXe0;P(N&8Yl-dB@uI>a_ww zH9h_bfn0^Ml{76f(6A<|Yp2SPbFJ#ZSOEgWhW^U{Sw_s$T*5zTc2M+{pd-1Q{9r*cL=HhW3I;6)F# zlWF3}ECd&oPU|~}%3@+0s25GGN7?fffV}Xu^q}SaPX$3?VL&KSiPCk~c?QmE%a*hF zc^xhvub#8m*>IvF_f^GhZfh&Q!Jg?Q3W^sHva~1^O|Uj04F2N(ugdv3Sd$18U%zG^ zI(xm-|7OH|)u_xSIjS1uDZK9_I1SS-dDy$#54Y}>k=mRZ*q{zN1$;>;OHdiJN8jXS zs6EQ{2dChIuU626sCntI#H#S7DlE%a5_KTOPe!fCGYlY{9wogum0$d`{OkBqbi}I} zl3PV5xJK9zZgF&`!`z1VW7XpqMm&PS5?Pnsap!`FWt9BczYO2_ygLLy|7HFLQ906n zVtb}JEIH+?EIY0hi58#~^q%`?L`if@6mGxZtTiO9r@xQcDE8w_e>=OrcG?LjeSFjV z=M7QG0Wm)WM@*%lDe4v=S)7A$sjb;$s4LvwSrZw26w z=`r#L=C0UbeZa9r9%&Ry)ovVrt{jT>el~kOZ83!RvxpfrD1d-;*12&svf0Xm?&|BB z$I+{h`4@iUG&_PmVgD967kwmGwluZC&1Z=V!K@ zv=H44uZlw`yVrrks`OQ5fioN8=;vquK(r*s^|bmVffxj-pU9HC<6I|Mp$lHyP=W$T zfR}Dsl@IBG;KZXU;OOq@Hy~1V4KKPwI+R+TQi+ekG)ssYr6@jjbXoT|RH?dexLfy7 zN#vep9p%5SgqyAlTr7VgoPx(q)$6mWCGVum-GLLsPu;zDm!V;Zg_n7W*JihEm{^FW zWB5?Iz!$V!CLnB8!sQ|dR#0ZpC`w93`tq0<=F*QzH3Y4w?k`>47v#Npq7C|aBMONu zh^AEgGzgJxMh*OHOv6}A6^e)M?fDwX7(lgg^aPT`&e47`is*TVof$h%0yi=e^q2q8 zBk*a`7*psD<@#1+a+DopEB9$2NK4xv*q=S2W~~MO7P18B^(Y-4h}8njUADgSYRK<- ziHYlzCtDE{MP)vPHw2f=bxCeGfqo@hk&!y6<)IKM$XWa6~=(gcBADDDGcpC6Krb<*5d=3kag z!EbMywMUa2w0o&hzf9$jy0m#b<+ZA~EPLJrlB>oSg^xDW~UsR){KQUJ0ZD+7LK#>QG<7+P~ z%F$hd5M(XIBb1m68y37evaTI}%uwnSX1gb4rzaM=_^N{t%QYuls-E;^yllD)sEfvY zPixX2Y1{4v1z$^4ZwnpIJQ<^ox zUi3A>w<{L7gS;{Cm)cd@xXtw(Ie$*p6;fmN7TqNT@)aiX$VSNC^TsT26y4s`w)y3> zER!JI$=i29+XMqwV5=SUJ~8w7bUR;t=)8_+rTn*x84P{0_LxQq0aUGAe9p?r-Vc>tY$zUnE}=JDTK()Oo=;f&;+b!15DPAfKLBtke`jLfs`c{ zP>LAGms6;gW*96QhIC2Gc8>v8JXvIZ8zLX3>W%vTZ&F~pcG1Vea6eKu++b!MCu6Ij z(doGJD~*Y$!%P}+XYbXZFNjRLlXr_uhmi+|ysuKYZp5r+Z^cZAZ;dl=4CV6Y*ECkz zwNkULas&wc5ydC)H8FTG3tGFQ(`dCKxp(YK7<`BLo>cCFzYo!JhlL_Xg52i9ZZB1k zfA36jMBGBVw3(}FGaeElHmTpvn%m;_JXL`9zQ^upw(h(%Ec z7)pYG2agaq1t3L%H*$dhLUC>@8^P9XhexVi9TQk#Lm&`fR%bY3=Z*Eh$Lq;sy~yDT z7TtM~c@tY1AMI?H3DeS|l_P9BO^8-hcCC$Ga~XJAU4+7b_2M-j_ucDWw)(_NZahne6NjI-?kh2f1U{1%`?^wUWxF+_s?Qw~&A2x%8IrfswMbLS)$UyN5my zXi!$U;piGzA>5f}BmMJe#(?!ph`2Rzhq6zau#68F-MA}kp5fk?&iv~dtzFQ~8(VnX zV@bWTcW4gvU*j)zsc2Ccsz*E*zj+Y;-4<`Uji+$6G?~nYqJd?;P6GB1Re5 zax9a^)uAB$7jFoS)%2TtbeNE8`wnd%zC=gY2D>e5euuq|>SAQ)fcJ6S;L4 zHIm)P+lc$sW}a~LcR!52f`TdidA6_qVyN!$e^cHLo;M;uB1Pe)pRM<&7|)ITt(RCS zj)8+=)X0y5*YmftbVi@`%=mgPl}98_v>~`s5f$_TP#Yi?E6#~w&OcNAdVZs`ilo87 zwV>*V$e3}h7cA<8k*uG_vxDG~5g>y&i9-BY6a|w-E=On-`u>u$m$)_E-#J8fCwv=m zlaa*Ta0gurqw-S^2ocjKDLOxA{p%>ttW@F)J^7Nfs86x6MFU<5 zfpQxBE-3GJiq)E_F)2m!xLet_1<{lRN<_7~O%R1W{a-y|?HeMw^5Bp25^uR0A%k#` zCz~}d?H@r`3KYH38xRTNoU_QoS9W<_`pL+dv^s9wF6gB46694IAtrRaUAw zd7#?BvfY~PsMWsy$jup;*G^$o>Glu}!Ut)3pk>c9_mu|-dwR*+25 z9!$Xf)F^1GVS6Wm3Xk)f!Wp{ZBLennwr$p$E3G?OE8{xTlDln!SmQN`Zfo#Y*}sY# zCj5L^F;tF-zE|Wi>AikXA*ugB+jR-p)?Q$3g|)Z0OQsdw!eJY>4i)Mn%h`iWHHQWe zp2CiDquCL9Plsbx%UMZ}+{C zxp)21fn4Kq!gpi-w}@h7c|;rqi1^r(Vu(v{q%tpS9`iYDqfeqHCS+s$l}c$>)uxAY zm!K$4WaDred?P(^5=`@F)H%AqGHv>`&wCb<>@FFBznOb!5Iy|K@o2ea`c3uE@M~CU ztiTc2WEoX!(MhoI=aj2O74(OgpO9tB zc2jE5*||7`J{ICmW9>7j5_66fzbzDqCem}qB}w%iuw$DzB>uWwIvhbJ7f%->AUlJb z#}tZ>z-z(n2t}nx567;PafC5T_P$ilS}*RvPJOGTHNOX#5b#HLdW&AI7A4-lb0Cq| z;aM2{r=j#Gj%hOcs3d zj^5;Vl{U7O^Q>y>1qBZKpz!_}Vr@Al8gfyRWNkZi+<=NzwUOr=9Cdx)A_KHI*4sE> zs7XyV!Z~ofd2+f@#tpe*HE_VNhnv#E6>Xx0ii(%W0YYe{pzlUBJBI0jXB7`|rVmq~ zd>a=ik*Kww$6If|Rj(f4)!-5?SI-)dN;XFiM9)A&??ZOf=QE=S!(WY1Ze4o?XhCdW z;L`3daavZWYP}V?t%SE6bfyhVl`ab;wtQE&)S$4X?T=i(2zykfn7OjSO`_`4`a6?x zI^k#6MR$>S`g6#|{Z(E|cyp0m(?g&GgUPbbx?S9yB^Q4Skjp-fE!u<6b@Oz)g$KM| zz$$$6{(iY}3ecr{2nvtDTNW-Uj`jY#O1BLs!v;%QU!f4RCqdCA5EHrsFQpzem{;0#z1YcL zc}2|pl&p8SLih2b&;qnfmXD-anOD6EsT}>UAfzXyGxlh@;i0)kT8dg)8BB;JphE;6*yzX!pVabI;0uB5WPW z9c4(-4$XkP5fu(h=1bAWZ%}Ktb@qw-mg?xB7Eo#-%9-FMJmG(f8QvP6hfIngBQlLn zP9qg1|ahSM@$<*B&rq15r$gMiN)qHfsaCAtQsID!GJKrD=~#p zU1sbZe#ghf+}uYzS{`CJ-X(Z~8>m9Icp`N_z~0csh2>=Ef=59 zoah#C)PF^Co@ke?t{4A00bO8(r5-4mfR)GXt>s`txgC50m}5(R$s)PfAR0W&2OYV+ zI>GvG6T7v@AE#^k+#(tB_U{?h*lD|z8#loVO^f-8q|^J6RlX4R(08N1Se6;izLQyA zWOJEEEf3m@`--Wj5)FfX-K+zn6@UWR+}76Tz-yy4qp)!FMPp^B<<7eLDE11@zrBHI zw1EBz1HhdDeE;$B@iY+ybYnT3PpO9@)b6ZB*G19vu0h;skFCC_C@`;*@%=1WHF-!H zI{zVBuoC=F#iDtYw^4P|V{oo0eoB;z zo^`=j)R9fIdGMuh^@y@Av4U*rASeTmR)ohXIsH9!vqLTyx)lTBwIOLZDA7knrVf;(4>JX+Z_I zv~0D&`6#WNL6+)>!=M@K%ERnVuLO~OGR!Nm7^WR&Ns{{C!B}dbZ(J@WZhjF;3)Hv^ z;k&V@*GFKh6(XLBF3lBT?7qyzn^|iA-LxA!ze&BES z@}y^a?}h+3JJ3?2wk_TF`Id1Hm%Ks=6{=hFR zlR{MM(Dt2{9DG%ntLRlHa?Ei{FngIps+kXOEiXBU;sis9sYLr5)U#gWa3L0{)siW? z(fm;qcytQUS`$sbq5=t5`UG6C6-6T-D&>{ujD08G>9RV z?GHh7WgI8MSL-jFo)k9P%#k-sxB9|Ib z5DO_~9adVxDe<>iu|) zC?3px@M`&arap+Cz3i3-eS!G=2pO?j`OrR$7MH$Yds9D<_*xH1T+_&=&<-Q8+AS*W zf!6%5#UiyW5;I3>@|z!wV)&Fwx%F7f#OL*PfEVH@gAQ#9i0aG@&mR8*c(?W(J5Ve_ z9$^Eya3Jl#-=!eZ}u$9&YvDX!2i{XtH@SSFTYI za5ny>5BxK50R~@_n#Fq|d)?T5zB{+phtBjG|E%1Hu~oOiXL3`wY?Z1Xp0irnMBnog zYps?V{ZZ)(OOU&ZxHoX-^DZ@X>8z|T`Usex)1qRtaV-2sjcE$|P1I;0485x2M}%X{ z1VbsI>Y`c|9PD$@?t%)7xOlPjZEsgfJ~aFQXOscn`WJEWxn-&e7rQddx{%_dN2H}% zI~;2YXDzJ?^LmVjN89}iq z7WlTPER5sMKw$_*d)Lr>&i*M%p;xgd*XsDMk{0v0LnLE?&&!+q?IJhtw~cd+Z*I59 z7WHSc?t}c=AtENlG--9<1(fhColW-|4Ok z!t)hzPU2?OHz!{D1UP&%TTulo*6iX;b(5v1I`zesi;endXD=^{OA)G!WIa%6kX2`^ zd{EW1xF6d`VV#X4CxVXufS7~Ck_|8B6vhHs^V^p#4 z5Oibiha){=c+b+bb)? z-s|svBsfTn>GW;zJux4b;>0`hr1&v8(Jr5@JFd1`w!>$5g2P;LmYC_;7MM{0WWr3$ zY|rK{2PVp2k(~u`?d#4ocLDHaz@pc|YE;NVw?hZ^OQ6d_l!k1zl1n;el3Y*+`8+bW z-K!ax{*+d`>a}whk?2XPzOA^Qkj^{0bQB zfKn0>p}MLKQz-v2+F-U8mUNt+MOD!uU)lgg(#F)e2L>80U9q+2a?IzCk2VW9e)b1V zJ4M#cv9=f18S!~%$M)Y|4kdFlA4xF%R@1`N`($l8_6TmAI3ZSTt+iM<(Y(xBLQC%i zFH=*fI8xHZC{32pZY%8;CmHhps!9+;H+8nqwU0()bMvq6??@N+BNd72im4!eeqg@- zs!U6lBG1wy4?b)gHBYcK3jyyzH7I@tD>aO{rw)$R*7q2=2;O;u3w_di4XmRDA-4RN zVB(v>4A@YW;w8!Wc%odu?5d`9*8OBD)9yxu61)dZ$i7LWey+Z_(OP|eW<5f(*p9-h zwk5Rhj~eHPV-sro+DJ&j<10&zYNFL~eyWY_dgs^;nc;P5b%b$D7rLqR#3QA_wp;lK zpo5zeUZ%@m38eFGhWo$pk}p?EPpT7#M{#05o*z)mDfN3%4gv&kp6FNORc4w%rk9|I zNVauHHj`UsY!fqBCq?|KiiZE^CIcEPy&1cg>j1v`K(keNY{pM=yzV?~j%1xscBc+d zkvslYSIp<$;~)? zooalISH@$eq7G-(NUvOJbU+5$M%e{jnH-kFZbz5XonySnulv~xSsAt5G|RV5kr7Ha zhH$4GMuSoo6yM*Hv{crVQK=kwoA*6c1SV?1br&~^ii#a#wB}2{`le?uAk$~_mn84O z;X<|V>Ly;&sf33M%){>^Zn>0fHykrgmuK&!gFxi*4igypiI|C8bArx?5M@?#jH^ay`>&MyPv-OySkX~KTjEj0&)=wW{VCSE2 zFXBcrrDWXgsC7GO1=|E_6#lXjXsUI75Z;=jvZ#;gkS>Lmd3@EM<~_akY^0K{%5T#$zuH)|Ph@Ia}`e7@tQD;EPbC{p!^i)iN& zu<9NqKu^SK3bWQqCBvUT-#11*j6?8R5DK=3DK1Ui?njW z>5kAwMHD+^gB6Q4F&P5Y`h(Z`0jT8)^E0kf_7TU!m#fk`ZEA~965|tU=NL_)zTZXX z9dhT&G+Sn$E8NwG07Yx`S10T^wU4i2|8e2l+S;5e-0`67cu=R+m81jAG{@>{q^SVtA<{l;RJOHv(3nhZ{O2n-Bqa~Zr;^N|lv^C@k?pD3mafCm$Le3fQ|0z5IdoquDB*V ze+>&I5ItO7V>*aR2IG%zG{%3YsU8R9I15Wm~ zsyrJsM@rKgo#P5`$Dp#W2004|?W+B4ZcGhLN2{*|dcZP(Y!fa9DFk|Ipa|d4rhT4r zd*lhJeOObvX`63VyW3savh(~TpKux>%*4csEm6+M_<4h>ZJYXa!})&+WYq_XSfT#h2v45?6ilrg`~|l2(`6V}^+OY;G-A|h*QIoG{-zba z@f`K+4dE4x@)VG2T9KhFzHa_u&9j#)21&ioa8qCZX+9%31Y#maS&}ABJVYx`=5At_ z$@*}@UM{+D@^o&yH8!5S6Z_HBn!?bG`1iH%l-a@9C89X8EFmWh5XW2ES{WuNEpp+4 zJ3|LVXWCs$99zB$cD`{_)3mRZFetAsc5~V50MJ@A=oD}vU+PsYv9*Gf1-+H-Mqqbg zSbPI~#P58>;KmwCUQHWqTbb;kz#gvlU4<=KXfBRJF5r4o<;Z9qzExJ`D+ft&K$AcD`3Hc&te}w#9UV-4+e!kJE~$hxjBOKQJxAmBwWL zEdH1aQy0JASeX5|ziONP`t>5%My^N9r>{eKLFeXmt*2H|M~Mr-+E!Nlu3WROfma|lWdkh1A8+IZ8A~y zBSy-4hdeX1FZ<_;!`0A^XiylYJ|-K6XmXqsuGY5b4}19Sr{A3sJM?nD#3P*lA6I7? z6=l?~{UIf!K|-V(BvnAV6p(I2I-~}qa{!SNDQN^LX{5VRQW}wt0V$;h7+`=Q&h~lE zS?^l!NBIEbntSj2AJ=vL;_|t`p4EivuwHxd9`kVhv%JSAoE|LN>VB%`jP^v|=89Rj z07X-lL>9*a!$TAOdybZ>M21S6TKEEM6B;7)L1;~ghap7Hdd!;g{})4~)UE0zt;b+} zlPo5P!B^C_pL$LAI1rN=(|%MjLc&)TZAToxHY>msr8YT&7Oxx-hH z{;$WMbxMMCsRFwL^Tk((!K_h5|yV~(F)w; zp2`pp#Ys#qPT$ zjsVVE^5Ey|;8F)@j8wn0y>Sld^z*w5qB?euW}i9!rsk$uTUNO!QciD-dIvMZT6zAX zQ^jrd+4zK8W=za1&%9{IR@d{7Y%Z$(9L^tFSMG7Q{=J5!e6;zcyA3b$lq?{3Hwma$ zYQ@~W9)D00WYYY&@XrmGe{|(EEIz2%AzCbMKVM_pi@E_pW9-#$IYDXM^+HifDd%Ho z!X=wh)@8I0Bfp>An86N+M?h&5zYD(JHGiW1Yv@}C!{ifsVkopYzL%pgG~Sx)v9S0tmkRr38sH6OO7JcQ2wlEVLlvBc_Z=ge)gUb^9d$Jd~Ku{(q; z)q+A$c0gU~CSzTcA>Xix{essX=kG!gvuKE+sYe;#LNy_QvOqgO{8FDD9F94 zKw}lONbluH`cL%sj(NkQe@59a_(n=EI3EvfD#9~&lT5_qnp(n>i`g`*`gr37gF+d5 zvjJ(Ve2GVItKwI7OnYVA5RnkV5RWY5iyjN569^=dlsU{oko)obC;<%0(-jSWZ=aUN zR4(?9+k|{+gkOKob$zA1J-#i1nIeNcrldDE#p_L9chT7g?~^0t@xa3k1YeJEgh-TNnm@at!mu%AuGv6Li@f}tdGyQvQ2)~o`+LN5_r>EFNn5opY2OD?Q1{- zT^8co2I^1iIQmlC1UQ4q8$_iPSbRzlT3ciUiuoO^DbWF-tM`>`G*)@_=m5TwtK}*& z2D|=(g1Rat=_FL|w*PKg;|S)%(P{q9Y)HG8nB2y7$gNyd(HmP&^M6`^CrzZ^rGuZ! zobs~BEre-8*U$D)OT;3<+v%emgGd~WfLmGQqwD1>X|fH7b53d5a@2@vf5yeAl!=gR zV!PuE zNv7QDh9<~06fTgtqN$sN6V{AvSfDKAL%T zLu{0iel);TPmH28sGt2%U_5y%Ue{}x!T`f$6>G~5c%z=Mu z5ahs|=$jE;kvgBpzBDvu@`|$THNX+?o-jqapkRxWcc5YRG?a;l0f zLuF&rC+6$Zb-_c{U7y&JV$b6OCN_5Y%-_qAFNR!o1hvBQGS8;3B_Dpbkp+8%my^F4 zpCjLVD)J^?O6InK`}x9mnfIPDF5YO_muN7y|CTkw+{AR04E>}Q;y8IDEB$~bJ*ry~ zVmgvr>@zXUDGLjPOXFfw|M6~ZZti?WTKO}nQy&BIyewNa?EJYLRtb$l>0`|9o2=Ro zMMQcgo$vFdQ(_3tJid|hn9JXL!4*F^?e)Mf_No4pNAeFRXW4PfVJJmMx!@#|_LvM&Td2_fP`I`Qo4T(mv?(VBEZW;~o zIoa8Q^u)8$vrhz^!TG3Utz@}*b^itiIK)5=`VYVXBx`-t`uc0Yy8AB=46el7HCibH zQh8(tFwor7@z4R+I=BOjy#_PoQ!cEqTrGc`g6wN@Ede`3!nR<(3HMKFK2+vl)?j%{ zGvB*7NFME;R+6_WpO&ndhz&G1%89*pc=miEDoqPr!E4V#u(|+uUcLT6m3x0-2gMnjEsiR_23UG+zPtuZbZB8! zy+J}PrZ=BeBQz@`$aTmNpN#eH7ynM8oh}N&d)=Pe1iv@6qM65EjM%++!%sS3=S(Z4 z9pTaxnJ>6IZ6jQv0yG>qy94aiwG=C?to;G;1NvGgyHr44=)3E`VB=Hh;0Rk^beu)c znxwMd`+x(Wgi5>gQ%?0hj z8gz=%D=&U@a=Z7%Hrf;LyphXHY8*^3WmOVYGIP~c)=@kiUg$tn=@plJnY6DrtXP2} zL>u5j^mgcHgKfF?^wF#NbllxMFc=um1IaMdT(}ZMd_o`~b?_m1psv;+tvN*|%bri{ z*Wz&N*(m>~*_Rs}eE}5S+Jem=a&z8??ks4t+0YN%U$oB|94e}*8+I$sSM#aLh+%WA zQlCBf1P+6@Cme3P)@@zQ^yoAtC5*pFw&mQPz}=wSiZ+tJNNY;s&nB{%b5lG-`Grku zm`?elD>B381FtvNi>`QWk^0>^DIa*XE-%YgXs`u0&WiJVX|ci}6qv8@6y=#V>DjHL zvU)W5zl0iC^kF&+;Y71f{GB9{6Cv&sdt}{vD-Rj0@0CqUcYKdSsQrH8S8{xt?2?d2 zE}x1wtpC2n89PqF*Cz|AyV!wKtwlaB$H#o{58{h~_oWtBtcNQ8{O;*jil2txlT5d8 zD_p^07`t;bcU!spqh{@CJ6IBeNz%kVurHhH>;V(#3*7xWlHgdGLiN%h`(T2#2GvvR z`J)@@x*wW&7EqE5HvG%$&gCzYb@?H5ESrPIEk=AZXCI*raPtNRMtpU&tNfz$5+Xnr z9h7xRb?rPXyG;n=l(mugtC^v5J7gjzJr7?7?e!W94LKA|HB`Vyqd6x?2Q0@W$I zw9kZhCgphA!c)%`+d8BUz1tS``!ib)A9y~c1+BfpVyz^GkXl?;EQFOZt5G z(d$2Mz*Vm?^RlV|IO|g`H#yMh9xl^|H>VSiCvPSn`ka7a+dHNw``15Q6``^y7{D3+ zn{V_kqcJV~TtpAU7X($vttoWZ>Fe%Exs^xk*ZGL_FGhde1tBInEkn{WRcY3{t2Pdb+v2HLIHS&#n``PMTf$U?unl zLdUf|fy`sxI;HkJ)4J7T*Lp~Vf%-w__@2={?pBw$#)6mbv6je*PTbfkxjxf4!8xlu zmPX;RCN6V#t0{H|L*k=8r3Zp%ta!Ou7grm?JX|=y2{TW_XCA_BoAb^Fll_BM4Mh7| zk>(L*1(}0s8a1R_jI@8^`u?9?nQzhTf_~U#Qxzl^85T1=A{jTdVD#@R*?)cAp)T?F zDPtX94?uzkq4!0(3h7b~UCQKC-vw0?1-}H5gTR6GPyGQhN1>>G#h+lGZ(ji|s#M^e zUcBN4jur*9E*{kT`uT;fJ&b+8bMfY<6tPhulFdC0&)e|ha}*M&r<%C?7S7fxWu}%j zoAw7v&099U7v1&zWxjB!V$$}rVe;`rP#fQH!w6;4j}2Y!i%y9W#`?EgjA%mU2g?XAkrPtyh9v3_;ZmAYC|BJf^fiyV?$xgOZSCy(f~7nj z*!Te-XRz5KJd~-L{{1k#p`jeES<9!8$cFbvKHl`h=LyC1HZq|bCaB|vI_R70f&|~9 zvu}NLwIE7G&$NH}jvlzF!@FGft6;3p&h*Q$_6bx_#yY)I&$*|&oD}!@$zD-vBNtt} z)9@=S*y7dC-P4($UnZ{&^uxgb>4y#Gm^c6^_iyGvDs)Sqi~6H1+`v8 zIfiD1C&b8MS-8K2us^yJz0i+7Bk&!|oJyW@dU?MVg^eB z!Mi#pr@5P8L+hECOFdv=iMKg7R(~fiq?QDs`4U5kxG{@PxFb85YMsj{ialPtmXu(` zj-ONu&kF|w=b0rX3#1kU$Y&;!nCAim|6|2wl7WaH97{Hp)-0b4t8(uyxu+c3+$LCq z(kDp7TYH7nTYuHL?lrA7!2SY5-#OUC{i}npjQ+L&dMO_B8*usX4ZpnRMr2$dCT^0U z`(Dby(QQ>o)aMfgwA#?#^8jJdFQ2-IMf#oZ|7`a9JmP6~TdX4PbC=%gmdLqk^8nGa zNNE8@yEU2be|kH1-K9RbVOQW$7uk%4`g?;lNzsfHI#q*uachkuN0j@C!%e}BEH?3} z$;|+sMW%`$OG&zp-5i~;oNM2fsj`goZuq^G6xjFwRD{pZe_6sK%N_S#9pKw`_W7rwl~Us#;0XqKiiV46nU|3Pqd_ux z+j^<&;Ox8!2v{t$KxuB|d{zH=@a)lEnGK3+?;!T_o$~H7<({6*>KDiR5cKrTf~b{^ zd0{K#`(F{`FFLzZa z+b@)xqNKaK9+y!d_xAGr=HbCttqppt&c(=Wi+g5c`1f5F61B7X*>YuC|8F(4QFSKArgoYbc z)8G*1Iu%OJ61*Rp)b%Lf!Pxeay}vF?lL3_8Hkec^2!7zNLX1Jxa_s{Q%q3~9c+uq zThAAACQdn2Lb;-yW$DQp9X^4NKj(R-z9BxUOF5xR8$B3juUkg3AbjXtm$Vq?6u=-I z=fJ6Z$TEs5XQKV01v*_bq*IOSEmJcs4Zx0rdjx+~tYMB@zS05fxwb3+Jp7)}{&P#N z!aW<=fk&Tj=TyC9YNvy9Sl&KS(rcTocI_Q38r+#x)I$#h8Y*>{zDqU((a%{P<;1yz zJap7@q^oOd7%GWhp^$Mg;!iC5i!3{hN^?_+>f2H4b2FPrDtdLYsQQW4h8gYvOr<8# zQR;)G?WbaYY5LPUBARB@eBkf`HRjhUK+6YJm{maCS0V#tY)1rmzGE~A8A8|%EtcWk zp){@O3TcE2V_jHRelgC1=HV7j$eVMFNf2cpt~NSZAx4AwM)_o#{v&_)19BbVIDE}R z-sWyNOHTq07Y&vPSJXDn`7MfZ_3wcbHzjOZ)S6e{m%{P)=RP4L`poeulPr^bvvE7E zmkQK5!uxmLLQvy1B?ar>|Z9(j=R?N26+Hbgg(cMYC3CI|^w9V*bPIfbWj1M?v z`Q4P=1$;-o-)X7RXJqwdsR?uW_IwR2xH7sEBe^mJy*3|r=OvWUONlG+w63Xi1;bn?&XSwxr4saYpj4EWnx)?n70(*`+S1Gpd0qPzIGC=U_*HIGB_HuWLX|E!O z;K>LD?&;-q;(g7d{lL%{aYYV}DSaDP6=g#+>z+=sm%W_`P4U+^BKEBFflBn;t6#V- zlN;bZ4c7RJln3><-uh4%T2b@01A^FBg%TI8ufhW|F-Kels3Q*yDF>5n=Rb^4ZcIIh z9{}=nFw;dWHrL z%x->hxMunHGB~5^T)et`-FIz>@s1SZd%|8Kfzn5;iBlx1u82m*EXqsx)1be|3{BYT zL~G~_RhR`{4+QK5ttLs`=<~Q#DZ|5N%0N=h-m9tCtOX8Rb49kx0(uW)=-vs*4(Z?e zphq09eYt&?sdKdb5YaxSX0e!lOS^ez?!i-Nw7e4(>)tXsePxG&qSW$zm?kOqATn_D zfIZ;Tj2*!<7Iau;(%$_~3MCJI*m++l&q{k&N&I&NB}U)4;Ch3Ew%)=n2CV0QD4xkk zOD|a5X+3zP?gmP2khu$p67#ulQCU8)aMSzTe>%ia( zxQi@GcsUPiFJn;QZF3MiE4JU$`@;^O^5KYeaCO@nXQQV+u03BsBTY;Sau_W&A8%aw zjeW*44SgE~*1V#I-9vxg5Ye`-6#1o8LvLVCqbH_aky!!PLBXTGd2WCz0^QN3yR+?g z1`bF+23hEPNNc*B`t947ch#ST_=L#BYx7t%;R>w&+B+c8vNPoRc~^2TmlA)AMIHyI zkV;3N$%ZQIiQXHW2qBWA55?!t#Z>*UNtMDaIw3jZ@J%x~PWJE5WDXCoBW%v_1G=vm zv7b?`i4f~_?ZOb8iu*)g>GaQu0?x2+?GNpPTu+tXNnQ(X4` z%nxiM{=5(06ORkB(roc5aXgK!${ycn6KEDo<_wcNKgABX5;#QPLMf4tDQVc6GYc5h zu;h8MTQO(dPl-u#C8SC|+>fe%t!fHR2sKuP!hiFqD`jkWb$RUFm&h)ZzU5Twac6c;vA4NWZwFh2R*!5R48){IvoS9Xm*SbnZi|sn}5a=;S<5xjuPjfF_#;#n$_; zE06PISrmvX^f>8xbb4jB^jONr#niQWd8dQ(RnjlxGOZ**CUM#@N#}1=AOBFIDeHA3 zj09qG8}8WLjLdZMoCsC@0O`Q}daqw{eE%7ik1Ij+zla>5$z~4YmdL@P;ht?!3 z+sx3<3)H?H!W|W#moJib!pzLfDskdexND5~{zWXBcLlA1Z?Q2xXGpS5cu7+t|3+8N z3F4*d6L{>uKqP2oglmuAK`*BcY|!hX#ed-X;x<%=UIqkX;;qY-UK1@I#M|^dstJ+! zsoK`HA)wbpX_1!Q?cLQ#gy)7XsSo26j z)rV!tJmL89Ul;s8sU9K~MBL`LUFB9Q?3+|2-Yv{qw1>4%AK;L+gO-F_@CzQFO7}Vq zAKs4M!Kv5Jmih?KpGUi8p}?ErAM^yJG%%wzW@ht^<{4zG*jaR#JY6zW34iV!gUdsf z*B(M;%|)Zom#%K^O1@ZrIiM|rhw=F=4=p>tVX7KC{Leik(#={ys9zxa%^jh~(d9aH|Fd;mMA6!J-&bnndZZD1|wUteF3 zoDFiN3%C@4CIYKlRu1PH4m#HD=Znavnaj{R&uEd))}e;-R~L7Cbrn*gCePHHmbQ zEoJCIhoZyco5f$_3;lQZ|1NzxF2>7Yonwa{N~^-v2__VH4;(aDQ+7ZE`x~)(={nQ% z@WzWxDXN?tD!VMogj(!T&Bd!u=thg5-{+F?TK+_~?mi_F@aBTC$R=X1zRKg;8bsE5 z1-&{YBOuQeC&25Wkt3bIXy7AEwzV9Hz#rm<2-;UboQYqF<1Xyk^`{eQeL-DWFS)Ht zCvmi8^t0R6GP@K^{Wa1y>Vli!r&j!>b4cDW@7|(loQl`;=3$g8HF^a#t!rnZe;25 zpX{pu=TE^JLOpjz(Fc#UL!KwH{kP@xb~XNIkP|8^yG%gif&Lp6M=6o4vm9T-u}5co zy`WrQ7kV611&MaP`DfGF7k~^R>4!JTf#ndC3qXKs#GeL_qg*QDn-|r6e&1dWZ14Yx z2Q>!941+!izPxM7nI9aa8lW(6?xB?_-`C*+dD1uAIdlSxmpE%zjY!CBWeo9(y8^%b zd^;ytFhfnFtp9=1IU$+s&`tsCjto^jZW)mNzb(6RFOcl+_J#B-)O{>-SNPLG7Qnlj z)cchEhh^IL zy!)|j%@f};!z^#Ry1b%c;0Ifd!Gjh^jg$;#;E(<&nvUSdyJVm}NWg>A%$Xi(NOG)z~Xr5ski{FJrp zLa+~lf6<7p#nTwQ;0=o%?>2yuP4x}fKkYQ!>S`R(YvY-|9?{F`J3#Hj+*iPu7}ShL z^4ZG2MP_Ptn^{=0=|8G+1J7k!ygQXHp!M}!TS7DbT)jku!S?5%1U}ylPe}-v6KrWg zyZ}2yS@z%kczc8D0*a@)p?0X?H#zQ~_3yZ%nR|DWXS0&r(dVju$fem~dTw?noH9={ zk&QH!`>3}POH@u_gw_w0r&<|e4Am&|;X2|c~o*3MF%2OxHE8A&;YG?Xh6 z;mc%662`a%G}Tsl>erxcONadFn`qUXJTWx9gi;HiG38M37vn(if@oL0(6c>6qtJ75 zW>P-}NqA&EEkgY#jJL*xbM7J&?H=DD{(hO7U2*j3^Q83cR~WL?eG%_hY}3MJH~qLW zm0mJ|%x(=uE&?P#Fv^=!OS$Gnk*z)D2AgO0MjvJI0sibEzFi zsMY*0vFymQE@!12B>`8+ycm1zM~YqK`|fVb_GL}C3vL;@$(&vK{N?VRzhtCxB6Ffm zlweGzS0pId7#kU7@$k9hQOC~S0oTDdP-K=U{yBlZKIhtQ*YqyZzoSx1zfi?yJw+Uz*-JrywJ&F~gF@p}G+`Pmoj_;{32h23ZOwKga_?d9Tl+K+RtGV27n)gF|T zO-7i`qBXkZ$Y<8a1-+!7x(aW*vO{P6=~+Y{9B1y|?4P)$7c`D1dC*<~MIL`W&scD8sUhvh-*+j60z-e~r%9nw~ZxxSNtwSl6eI+Bd{lEtTwTEcOnUPmt z_@C$E!PEl=LoLF4C`@cZtm zc2w?OFYlKuug9s9Hva5(Z+SF}N~MC@bl16e-N*z~Lv7L}$Dflrryu)e=Wz*d_(eQ2 zWgh;?Ip!9xFu_*Uk^8s!>H}M00SQ@-LR_c3;`*hle{k-a7Oo^U)!qvw#>ylNxM1NN zs%$vh9$RboZkbMr=Q87clh8%P2mYb}6RphPChF2G&V}^jkI7!aKAcg3q*K?FZzzyN zA51G|y}C||w*5`4%mNsGy@_%Z3v=1}3@`~|5w$CsuSMVu5tTfD@&&i^QWl0oWN;ZE zT^HAW6O{K$2(%g~E%D!~`3@?E$Sam85^JWBPT+Zlzvq9Gr@B%59jqgQMw6=ueS*l) zv+HT!g?`#Ju&R}YBZiu-~&U(C?PBy`=rV2TRF#_8csL;XJQdGQAnz2)P%(%`C zBJN2}Z{NdqL&mpm@5qIKZanbz=7D)9>!p>S-lqcesEuyO+2r`Zhi~@3WzT@I4)}?fgoFZ3#Gxb!V5Yr({rX=vL2~}D zD~ImTN6d=r??{B``?-eKlA4hozY&2st^QR$LNz4%BX;DEhigA0j!KaUz~v;?ZdT>P zW7Ui*|6qKuawmv0&WQ>uPMn7U>91UbAKJZ_7AD8B)e?Mfj7rJ!_b+tvOQ=Ne%5Kct z22+x2!P%SY+&TU8b1v`50h0=Ye*jtpU)8%^#X`!N-N&_j?`AGX_w!s0duzT&`(G*= zPS>MF1JI3Ki|}PJY2RbY!`HAGah`V!IQjQHT z!Qf-%ME^w6)hWpOkWD4=Aw1ssPUdG~XH0YO)!_9^)F1m36}7_Rowttuy^*ei(a1`# z?$;Sr``_OK`YG1!srhYqd3ibKx9>nU)${7&fyDrpH@A9o$J&oyziF60yzf|phQFUZ zL3n@eA`K6O&>kD7T6JjT z>CHE5UH%Z-yY6BaX&b1*m-y?ewlr;qSd`kI-wB6ujg5^pcJA`fOz|gax0k0~KeuQN zG7xlWH{t^-+8VQ}k8Jpo<6ynHWxTSy>~-*k_onkh>DcX^x3Y<0ViNZsLt}rXUO!DO zbul;0-ZuI15{*7UdzZk~1Q{TuhX#Rd5&g2Xo>YkpG+LlwOeiYVHu9e;Xh&Q9G@2vctx4gE zG??2f&+>IaG%-j?vn~z!@K;0oMYZB7;3)841Op7U(|}J!9O=^rlUFZeyaJA(hR-IA z7Jk~lvOzwz$4YQVzxl#={Cwkd*yNYbm+TR;()cl}WPrQbHtAgEs1o7)U$UqLrKl&^7ce*P$rJy|_ zgu0v1`mQ|VdoJdWkZsE9M zizV`p7yYQ_Ekpy+)*BuriS#;7Q#rhM|F0hdsS?+hLAD`s)-=xU2G=B1a=kApc z_X38X^~d#LyH*kW?wWa#RdZsFBS6Fhmgtz+;ESi3eOsr#g%twBnB~*-mNfUb0zc=% zN3-B|ox4SiNY4>e(?P@1Itq7xv8FNF{io^O71#ycYO~oHWBA`o<8KA1|BxxTqFcG5 zJkEiD;`FpZ8`}|mQ@MRHqjqW?f18nFrYX*NxKcN9UU+fuEC@&$LErxfG2hpxqk`2rrcdyU>SVb8*XCx_j|=s?X64vYq}Q; zxEz|$QVKfFpcMnR=RJ;wmPgcrhR+-c)y(?Ikuy8N=-Xv}=B5XneY-DLgnod@X%fwvE>Z`Ue{c;0#vUz}51 z{?@c`$7c$S2q9-sUHd{#-s*yL2c!F)eC`Wht;~MXY?2uMT!C90sjhcMqn8C&0#PtE zuhloWcigz9uuEo%z|8A|k^>?VgJo!7aTg;X`wP4%S^iT|QAH|@pU+5ALIODEAMu65 z)b5*M%@V4e)ZiIKy?nTPbVPQGl(~I(5!l%fA$}s=a!!@LgCG+2>I%M%D=+8OUHbO; zV04t|-?$sR6TU!DycTIP_9AN_Dw@z_uY1$vG(v_g+ft-_@UHbl`nKj@KZzg<-UWUA z@JH&S3u6Y^)*p!nY{o-^r3bs6cG*ejo5rNEBSp3g#e-tAFIK+X`DXK%9~Z&Dby(A} zw;UK-@v^omtsb`Yq<_~$aF66D=e>1`m5!~ zxU1ui?)AiOFtP6P@|I!7I05`HG17*0Q!d~dWm7AvF1;}htuTC5FY(rg|2sWN(0xqG<&mKlL;nSCWsu02J`d9JTowMoU^;kx5$ zh$C`5X0`Cr{Wrq%gE!))<4d;Pv$u$Y>y@!&)cr`TKUUq00qXR;HlwJK3oK?S@C1{6 z#xTP(O_9CuW6NB==(eTd2@Y{S@5+sYzhTf58^E&3)4Jz{fw@`U>hF9VclTW3hz>(k z(~0t>!eg1o)Z5sHuqduFbTe8y>?^wWgW%U-(I5W#<=eo(WY?8u>oo48>GY>IjE`V2 z;)1_Eg6D-EqBk&@m@Ndmn?@F&3Fk1cqG+aJnWy&Q4?lJ`9a_r+A|V~#FrM&80v+C7 zo*qCFFQL(iI1LKJ4y{hDLG`F(JdZag7}syEm60h*Yxw{?vJCODBaD{li^hUS@gHrC zo#J2Pnk@P4X%$^|dSP5EnV5a7!QmOI7F_kop_ajPE;<0*V5h}eK5(nV2j8OMpnSd9 zyh`T}p4cbS49Alovl1DAmx*3=`bI1}#_clASlOZBodN=kdk4x5!uYi^H91_w#?!z z?5>9&qwbP)5a<-m?pRzI9)Q5H9;D=mU0sDYU*rZn$hPRRDr`H>q`yW~$tjQ;%f>kT zA`oYsP>`Mjkjve&AQN2C7mq8(1Ka~@)0q|V-hp*irvi`kz)o8%vV~w1E z2gTJAl0LZ%3fhzpMyh?PzLfEd*olN$+MhX5=$2a4ysUt%jvkLn^J?zjx0dMNoAk8D zp{yxC&W11Qiwk9_HQKbK=gz(aj$V7 zqE1GDVqv{&ZDSlg?KmlzJ^OrrJ1z2%={uRCFisfB25+wN{r)S7>>1+zB%%Q6+|P_) zoE+PqkR7kqYZL}gxX|t0Aqz5)`|>q|G4_gUG0F3E?(#FuAtMHzMEZQbW&7~{Jwo}Y z3h8~#s~Dz`EDh$ODIyc;yUa=0!g0)j!5=DI5WDHw2m;v>%CMQkPcW5SyY4O#)c(IrLnE%iJj#(SVhC5jC?6Vh7)05ms?ZQOKM2w)>vkE7!#v z$&9bbXCAX0HacKIrC&h!OD@S&Dtj^TR$f#N(_%o{{d{*-Qs! zfU`BwC)v^ht+z%xWgz2Rc(ZpVeOubo*_(E1Z}LU{=2s>`tEB-wh-2%v-?V#uKV&(q zDPlz4Ft&qW6;Kod*XQfs(b(41jXI1;T=jC@5f9*;ugoLB83>Ft3%K$U+D@{;hWzIU zytc^cQbmtor&PpPj^8&`Gi>7Y{&x`Cyw^C^M-C*rFX9&Gx|WeOsE*-yTyNf9hTqQ@ z)lP|2UMHoMmHi~$+(T&p{n;60D3#j#1?&JD`W+jDe=aybZxgun9=UdCJK#S#`hx1= zV0gIdC!NnFmw1;f!fpLE4!E%8!;JWZ@oGX{6bX~q7U*tI(E~p11_2eb0c4Vz-;vEl zy!Q)h?!M&ZD*U)jyM@F#K!~oN{0$69KMr3eUQ55C+aCi<8^GJaI6qusUjIBG&^0}A~ek*_Pa_q`uiDv-0ab{@~K$J+U}p`xe4rBe`T7@uS7kch+@ol z`YaBFJ{uk6&xC6}E8m{(Sh?RX;U*$uq3xZtg_%dAnl7=g+!-=ZCGO7Zqd{ zthYC`No~nha8Ik-?h=Biz6ZVgw-ES^sMhqjqC#${B6FZ#!WN92?yx?z>V>i?bYr)W zM2be?v+1`N{UIld@w4knzD`B0Xpp_m;ozsNsVwXa-jPGKOT)7N<{I<^Ci}I2G>?q# z<}aukgS3OezC|_D-yJjf+1s>s`xb(Na`%K2L3#WpIQVw!KTma9j_aKvnv$EZxz}KZ z@T~tcf_0x@k?##rrxD*>ifkUgs{K0*Jxj&d9iz{Nko15Z-@Cb&D;P}E^u@H!nyUT_ zpK|U4%qJ>-CbZp9^T~CwIRYvdfr}>E;Qf&c$*T8O|9PU<-MB=SaIPCFt@>b6HElGT z{JN5Op%F2H-|ZiL2Q_sD2pjlmow16JL-6!6>^x5@H5*sgPNIp;L}Tcs$m(+^tM69( z$G!My>!hcDu_38a)Yjg<#N*2@q^bHIh(Z852;_`QuOKrmGilA6w1^ZseaJ$YgoO}K z*IrpRl;OX+OFQ89i!vi@G%%ZWobW#$<=h6xt8(b3AvacU4V(?(l#>6=;#YNl7fm6Z zNz0YiCZUVZUYqmw``2~zb+l)u(F~mk>qljT7!Cnq`~&Mp_qfj<9*^FPj;e1*R+(~7 z>5I!n20o(8<06=Vw}$HM6_9@;x0+E)NNUtX)jZ z(?1Oe<4^5=&wjJG#opvo6zhU}HCWxbw_}ehSjVUEsi>s7+nQmuMlAtt`|zDKnsIgQ zHhhd)b565k8OGR*P=dlBqdtmJ``O1&)}`>C?0GXY<(JrX+`%YFN){dQsnE8i^-RUk z508#P6K_dO%spj@^pLtmw2Ky%VMsk9oP1SvMk0plLPR5Bg zpdwdW=EJL~%M2r)hnQs-HCw{t?=(0jl6e1oYvw;V4}UXw8RDxUFgR-_uxDN75eG+! zBe1p;VN%S)wU3nAUkNnJsaM*LjgNz=13+xn9%L0aSDpIDUIc>Z1IxsBHr*mxmLgvJ z0p|?6*tluH_o9}gge&1R-~aw2&)(5lHI^k9a`pkRdDX)re&awNA0H6yo6`@k8K50t zh4y$peTQ;U~PdpObd^wk;jq$P&5jS41;tC*vL?G707g7oz*b z>z?f-eDc+{@eTs}y=~Bdb5RJ$4Sx5nn{5Ls(`wH7Akvh8sv8~KMdZ<`F%-E-4|YH8=Jnq>16obF0Cqq1s2Ku0u3mqZTCF`dA%sx z(5v6SF;%%msONt;NjSK0e%*H}3>CgMXbX?-cyMhH0A~C4%#Poe*4OXW&9e^Gh9Z(` zB;~<{uO#Hy-@d?t_@z`X!k6YjLCA)rDajdk)F01i=R6s8x;UB}DJ-AfnL3w|(g^?b zfDxN4pUcH+QBAD;*~5sMzqQQg)ti3_{G`9z2!DT*&U6>%n;nJ_d7JYI8+JYB(O!Ev zsX&8^r@*M=kB3>MT}^BKWxzcfWE3B_JiE6#gAUboGN5+sw6t= z2ehFPW$6;h+~W`v@G_WOe^aeG3O(vRGN2ScmQ+ZsxWAqI8H_4-a6gbd52*H=Jrl@? z33%4cfQKQAIV!JQj;U4L6p8kK-I_9Ide?U-w$;0>jAx3XzKlnYMRDgdE79*yk99Un zQeTv8Vh*Npc6Bn0zeAfT>iix-eZP3DxE;9bE033z%> zH%;l!KdSc|A0HGmyynS-S?n{`Bu_hGzejYIf;7M(+y8`$bB`e{x%jp0&Ev|B4=tK@ z6QBd&395fyZ~JQY5aEnvSruSU=n%helkzZf{F*+o*GdPjv4AY-g{(GzTaE=8yEI!)nm2cO8>XkmRPlARN}<%(8gakLHhb2iC^&SN~=05 z*^MNddS6;Ueqg=ksDtLYWne5abU1mtT^Ws7NmEF)@ctevwYa}B2Q7FCCt35uC?miN z#R!F{=RXSD4u?o`;V75pHH6Ik%&H@02xWRk@04sisXS|#Dn)9g=hu5geu?ddlgaPKzWVj0)1`esAP)vwsFiK1GbM1g_!S`Dfpd=P05t45V7B@=jgcp{1LMb>9#+S{9XvbPa(#JzIibOQ(Bz zBmN$u8Y9(+m#zWXugPyg4%oR8Ul~M-Cp3FF`kv{a5Er7!PSL7KkDh{pB*c#^HJ zPpeW@+36`o+~cHo2E*>Z%p0MA*wwm7JQ-iKi)dCmtwhDoE{jZoxf?Nm(!2EvhJobi zOzVbEpvGy^yLK6#bSl2HTq9=Mht`#7HPwGbVROx4`P^hypjY!9zf8}=ow@+n&yR#X z6C+BEm_z)yfySxej@#QSb-L&94dO41ng2BROIf?!)Xq&y7jB%sJk#EaXD6bE0`s+H z6k9YYc=R9=JX&Slhn1rEVp)=8MQWnwsCdhY~Ev(XnDpsl-l)L@a=46!^#f6X8*6!0D~^7 z!LMM9=9{Qy19$8cu(>!B3Tt|YK!euc{N`Gs6HJXUEo_!xsbm8$APwT}Z)RfV;?Hp+s^Iz__CI2z9Kcel2KbPAN?xl$zCmryT=pYI> z+aw53opztw_41ef7Ah^aa+KBl3}(vc5%}PD)dAABZ6+8^v(tUEvRVJJF{>5In!)GD zdv(VG&rDxm$}(=zS@T|KqbcwBTkn;d&KWweXwd9@js5^d-2I?6yW7AWxFPNA;GLn8^*}O4WAy~+1tAdWOP6bRrIonivX}>f!p9; zRwI}pGd>YJoOIh6>Wu$xB$Mp-69_&|&V5PqQ)4ZM$xT#GfrcKS&!|D82R?D~=Jwym zDt9>X8fn=o|A(%(ii&~@_lJj}h5-c$2@x2jkw&B&q@+PYkQStr?vhZtlujv;?(UEr zL?xw#0g0h&h;RFz|G799-&$UA;aV{B?7g2~Mln)y8b?OaA!U=ZzxOfF65&BAtqxN? zUzX`%sQ2*4?#bZqxpD>+A2J=S;2&LF>*_$fX)8iZ1Gpm|gqZ1zj_cwsdubSc&Ok0( zQCp^Sm&9%zFRTi|AnlXyHJ(#X*$p7$(wrhVba0DBinV1J$msa)zBZ8JDGFeaa&gGxxt*02BJ{x!cp$m(!6LR4LheWV^}IrJMrS z&fP>S%Xd#TE$?0t32d8h_}^u|l-LuY767qDJcyL(d$+@dBqg7?oWE)vL&Dj%1ff7& zszQ_bVF@{*vS5_~vbwb8EMrv=A!eIb0E@r5JdCBbs}LUheOTku(=xH9`kLpClM2T9 zlEmFi$LQcH?m;=KTW#cUk*M&bZJii9(aJ&DHQV;mPYe`LzZX(VgMRKwfE|0zB9khv zV&$iQ2iGCSuv@3!vO zb zWUSS+c9zMP=I~3<(+gVPs$`GszObJjqSVPOgz`PEa;Hw&K~W2Zox{hg(%+e?%tqn{ zEQucoqPXvZEDROULFD*tXJ?1ID#xEtVaSL_Q-ajuN@HCKsRLd^7J-q`^(G$lq0%)K zD~^};BYrly(vUd7{MzsvMlJzU5{LI^Nq0p?gM>E@9f{m)L*q9VPYraBz=t&%S z#XbJE66Z&B_IW+J|IXwL?d$y~M;BG+;h-z`eK@}7eQDKEiip|8t+s);rjlMjt3W-m4@q0VqLE>PmF3)XPYnA% zbZjoK9#eZUQ4>5jG*(9W8$%%d)4c?o2lV#$SEk*9+UD&lh_}%VWn|lM*IC^L{QS09 z*-3)%g>cy^!VITbeer>E$`?M9kF&q~^O|4ys7ad440{ma4NyV+X+<~p&Yeyi%O!%XuwO4bL&@jaY*qBBTQV7C!l>BQR%joJV zJhl}~r+z^2Zkzl5tCsE1`_I8H+IxQ96i@s~i)Q^HA$CfXl~y{&L-#Q(J>C&xR5$p@ z$N|MBEtzSNM&LEuN;m%|vP*LA3}aJ_nuU6`D;O}3H}7I^V|K1uMNg_NMr>FM?yaxx z`u!aFU1A|x?L`6lkXJ7@-!}M6Ck|#?*(GL3;)Vag-gdC{*zVY|DDgP|dV;F`ph+&S zFzKqwg0jw=UJ@E?RelXBob9x2vDT`p_bJ_0%^nTJ|Ro zOHt~4OJ2Kq20r#k4~WJmiikY>{vw4e%5N@w!RPkEj$UPO<>-+%J>{H7Pud&M7|D;He$P(o9wFk6wyj4XfK-QRBSK3QyXNG1)&NNnVFYWzw# z>M{>{(-g9CmEaL1HEQK~vvzoA9G>?mP^`>nWXtmK4vqk0t($JvB-I9~_D6&^LPnG2 zK(-=8l3K?1hD<1OR3gThGR30f`^C~YP;hNM1hZp~5Aacgm5_HeX^8C5ixYXiw-*ScyIGQnYpO#(JU&Z~2D2?7 z>$esM{sff2yqdhuLu10EFEV_;N$iP#MGauB2=NjvvBK{R-0{smeWU&Df!r0{bXAjK zjQldKU$x^+s5WN!P`AHt-+(3NB4!Jd@mc|iDQM1u1Ugq_+qT`HS)r^|41lY z81ZSU^-0n>lxKGLG@djMFK9!`YYUO-F8a<8!X-MTszuQ=5SP z)#*Y1+4Yz6yLF=-MkA;St{lkn~J#8Z%-Bu#})E!?>Ta4qI%x-7c(2+vp zB$l2A#*LQ*>J8wFONhQMbeUHfJQY9F)UWY3>d$X`6P>rg(BHDt>7wbt?fT6SD6L3j zwsmAG7x7=R{V{wvPV>1st0@C9#@ z0Tk>hfP%9%bg*K!K7N6FYt9|wmf;|hnbvp*=^#Lp>N9LfNWgXJ=i}3&&1OOW8q;^I zHm@!KlL5+8+h)0W*;5Cy!`86&H%<3_W9O1KHi#v~#C#j~PrqwoU$JLm06 zdF-o{WWQMeyf^Dp@8U2sd6Y&o z=6DqH8AAC#pL&QEV61yye-yly{jlZ?V8h8`J^ShIB2%K%=|I6DE|GvO9Pxpks#T32M?|-xT>MT=S+WLf;Mv8+^jxlsNim1)~y)6H(c@o({<(O0kdlzcETaXJ3zkB_EfR zblVH|0P%#v=Xin=o-_5jq=wtoSLKxy@Yigko#g4hI83EnmHKDkbNu`r1}HzEH!AdK zCF!o!wYTW+a21b+VN1%{vRE)e(Buk=|nd6UQI71K&CC(bl^b zZLDw*ZMOnsnnFlSIi`kJ)B9*+->2(Y%$$Vxd%ip)k_o2W3`U$0)cZ9Cmi}5+^4IQbuAM3W1Ztq3KddI3$1J4~?b1 z5FrE#OS(f@?+`usHcTk@s}S{Q;Ne#@fa1LE-z46#XsuCauZ)j(S;Sr$Kb6MTfG9)S zSX^abSe|qYOylM%Ptpkj>v5!5am*1s_U%(v;iu<)MY{!RVg|%#h+w$~o$$Og>5mBK zFFA67B+vqw=6eVnT4$OOR-tm%95_kAr%2u%zDEiR2$qT3Yy7sqm))UJx}G`JuyxT= zUvqOUT0v|db~!VXs+8d1y%+9{XCdxzByA?)Q z%Ch#kt@=GE@DuL@fW#H(m+~^RalvQWJ?;;B4#0=U8r4LUEBn1aik?UTm@WRnMWqxV zNi9%IOyR? zp}v$>@qlJVT$6XhN9*TUJgRSJg_s|li(fps?3kCG*6Xsd$eR(7KHBv;LY%{*N-?2BE z(P*1l$)@=I+08}CY@BD{#eMaJMrsa#M9V0DXI;`6rOBUwHmmxQPVc<<9jH6d zBaICXI9K8=Je!;;hlX~gQ+B|;`-(n%i-BG9A82En2K@MNm45=uea|S6?E@AO&I9z9 ztPatIV(99uIL6mFIQ@za)4n)VT=Y6K9c0C}(X#vx_BPnsv%2OL170X#LbZR63cms7 zYw-53{4;Yg=;tJKcitE3$C-}98Z!N;grb(622kVry-}|}MtPAzlB^|!SbF|#b zIOgZ`vEz;Js~+JbJ8ioumOBZ*J{w!TnN!RAp*J@-6ZzQj6@K^c-u>JdN|r-yAs#V7 zjw7JYt(^qCM!)98#`J)%Q{r)M265!Xh7RXl!cxM}ZVsBlOVS4|@7O1S=tP}g5>DWW z6@rqb_Co3}OikVu{Bg)q)x(k1LxNJ7;_$sxs{Pfh$J_gS&=qy$-$6 z{*9nOh`|_1-s`|QAD8e1PT{;}Z5ry!9ZkwcZuPFJP@|Ed(8{||7YJM6-zP5`+u>rw z=0YJ>7`d}Y^4URB_CQ<e%%@04)kX z;w*mA=371GT>-vOz?%_~g%3e%?^P5CG@11e7>%3>sgZ;!^{|)fX00^tKFzdZtF{kS zuT(vEFy+t%sXH}l*55_n4Ru&R*L89#8bJ$fQuph};iwsE(5ovZ`b~Qs^-lSX%3?oPgge@JN>u+7_g2~UZ%@&E+ZDL@ z?S8hT7b!o%qnsJ>?Xgsw#L-C0*kie}M*cw5`Ln!ve9ZJ*Rkio^6bwq={*v+phIQ5+ zLV}f4VkG)=>v>%t6&-j0oVRe{MwIW5SBMIJ@S4pKLq3b_ow6P~6mCrlv6?e33Ei8y z*&m?qudwR+GOza+?5_F9o49@JY&4fE@89{x7}4w*+!?^iDt>P{d}mCqr%Uk<&xg;H zUjECN03DyZyN+8T=L>Is^CQshlDlG?b3`C+|HBmsI%PUuQG3(5E78PtZ}6F6SPolDhL^p@YyEph+|MWY%WVaW1^ysy68Bk!kQGwaaUYb?cE!(%^H` zHw2}Qxz;z>ncNM&L`#PwvCvUW0msJi!=Eco8}=uTO6L|?6+1N{J&3Ucl0>O)GPrVb zAk^G=Np%h8hV_LbE^}GhERRp;7c>->gUFQ&)Jpy~1U>h@)n?+z#@^JXK5sg%LIu9? zGMQ1t5c1-+A3e{7Cu|WKUnx9`XV&7AU?Dsxdh9qEso@ioVMAE)dXd`~RzV_n7qK#g z62a0d&U)R~x2SRAP$-fgwwbO^Gou6-S;UC>A{g>uaiqeKGIHNC%?pW3o)Ay$|3)Pb zOO8FKjYH=Z9lICaPV5~><2X~uBozVuD;WXVr?OJg(iUutjv=v4L|BUNZJ>9uv6pkW zPB!<=r%&Pt{f2UCocOJnjSZgjEj5id%vdP10aGY=5+`~tP7z+~TieCn`W6E0?f~c> zun~Z2V4}d84%RA#usx4k679_Hysm?WUPzMzE?M#axF9O)3&3*X8Wx%MH}I~6lJvi9 zZ*3Kb@&xYiKU&JvUoOEFSGKSxn0{0+L>F(sN`=>n6n;# zSUBx2KYpyia_?NNz}7oK?iV^r#5z8Y^&spES7rRya_a3Ymh>u%0BwQtnzn_KR8R+} z>?;v0C9~B$`pgLFK1+1cyOuU*9W%%4I~P#p5H|lKlW#~B3cY7*HJiy*C?cKSOSe~E zR_)W#A|&s0jOv}6ckq@h4Ugus=B~^{+kR?SI1f{{ca(^{{$4*}SeDV{l~o@+z&+ee zehuuiV9@!wgxkfD{HrnT_^bAv)||sYmW}gYl4o~Npfcp6t}fy2d;%4p@!7}V31|zy@}6S%v}YE`xyX*P!RV6h?@b@ zWx-`t^2F0@JJSw}jVXb#Yi5QTNH+dS)5jtueVw*1d&*DoA(sKy=S9cnGla2;7eF*K zA8}u=l0~UnmviEz&6wz;Me2dL1rUkSi7(tWR;3Y<4L?fzlNTSUxx}V@U6T`?sV>;l z&lcd5k#@d&V*OCWXYDQ&j*2tE`e>~&%oNAHcyKp^3Mz9!!WTFRXRR@8zs`KKap*=( zu>2mM_p;{?7AAIqS ztG(-w3Y~tkTHqzyaEuC1e0RK$w$k|-3jIiITFLs4b^8OmkwknG9o+tn56g) zVoQ?q+G0VGVELb835KO^$EX|H_-L68z+s=yGvW*%mavCFTDx+rhkWSrCt(p#X-z48 z|3=}M(zU;oy10*$8=q;9K*-yP>)x@sl(+>paSyatfFLQSV$+a=za1J^h#V^zJ&m%; z8DF=~#ToSO6C2OwzzRMa;|G*bJI&&2XA<&KC}Ln8G7{9 zs@|uS_=HWja`eZ)>w_piyGF}f9vd7oFLT#1?d;lPN!8!J9H`1he`Y-xKv z-S&}6<4Z)yzROOxuISww{YUlF0q)ff^xE^kGbI)lRw=u4M@)jntDb-TrI!)9%CAIv zd5+39@_G`(!hCUd-v~EJLN0;PsCu3@_C@xa-!=D_fajC5$+K0kU;O*W1{d@|k#_lS ztn#(M=xw3wWr_8}s!Fm0U^J?k+0O5Ce$))uLu(1s{eDY6>Hkmz0kjUe{6F{JPQN5P z#_Z>ze?6PQwwAK$KSgoM)n1D4&ETh-)mTXg1mxnVUpk*QxwT0i4PUNR-+t}%{OBjy zu_@0#F#0S1q}Pu#;Y=Keg5G8m(Z_P-tgNbq&)|EGCKk0Zttk<9s-!9Bpnf(GNAVjy z>MDur&T0MfZ$=$&9zim7Ti<*46tv~(c&_Op(*?vQ70uZ;^PaPx7*c?>c8ejz-n;y( z!{qj>V3NS2AO^fks=eUEN~2g^zBgSFTBqmDLwK~wFSc>t@gCW{|4qi4Qxz5%9CDY` z?hXUxod@x18S_2@x>_wq zEzgRN4P(1CoT+*|amW+-U}Tj__+5nIJ-&=jbaGTsGl=2`Dch(6+Qd954c$G6XM2ci z!aeYMKAjRixeQTb5O-M6{R|P zF^%lEM#XP}+zcRTy(1r=Iwe8+@K237rEIbi9pBhub+Rud|MkTM4OpQ588wmhEUCaKK>p#rn z)F6aT+Ah?vyhToPJ6jUqEX|Ws^zvU;+A8htt8QCJ>>56w*%r#vON7;@>}1$&GlHG` zwzhkZO_6t4%b2xHmIN&J=}EJA(X0#Nbkr?#D{^|<;K`UH{lN8(Nkinnx$?lJZr?h- z7`(s^Wc!v5xJUWNmg9*tj;LlEe4*=9kD39Axdon2L*}JG=Nn^7c~~iV3N&;6LVgzP zA-rs_=NM+;)h(&npW&xfTRXA+wE+(6VmmyEEs=dI`Kn&QZ}n%j#~uSd|ExpDAYLo4 zgdGGv5)Y&-hRaePcb;6TT8saB&`2Ls#;CO9MF*}90Dl6hAE0uggD0=9{Ol^c+mT>Q zAtRWcJgR?5;yxUBCh1lFHhrVz>DMzHZ^6S0>>N0h>8jT=F@^U%XV+jySlKmK>qW082B#aw;mx@T)usO{@&)r z&9jcnD{;NSoE;1i-VAa|SMUu-e^P2&fm#PMDP&fLKX5_mN4Lt<5yr7aR4=|G&9 z%@EKLOUoGUOR5D^c)%sDGcR_v(GuC23s#_A*?vG$H$96dOC9<%)oslf1r1K|Uv){W z!4NMJd!_{fCMIX3>;g|;!6a;$)J#{J9hZ}deeo$B4r?CFid_1!7TRC4lLLZf<@Uc? zfC%sJ_i^3_rmZ>h{?hG9da3l`g|`MoPE(p3eC;*7q}Viv=Ttg>NR^5aeU#B+>y-}^ zdin5?vtr~k#ySOkUD$9n7i4Miqs(-7lE)n#iuNM5_CmI6$pWwd(HlOMwaXa^vd4|* zL>!P8!)>^w*ckbi5oB2KJGrF7V#YF3563B(n>$0<pd2#s?fUK7NX@YC|AJeg6# z%jo72Q05kV*mv8LSKpjvkgB*kze5S2X!`W#>$x}~zA zVcl%^64+5`2h^$dYdMZGKmL=+fqx2jy}=Wk=3!Rx;A4V>e6@Cb=@6bMnnK^!L~3-f z#ghp0pKTS9%u28y*ewHd=2I6J4_S3vDVry|Z@mL0gi{pcP?mScwsjU=8 zj!u+>P5KKT(~4pD^E=|&;Hh$oJut%+SKIxEbqb!8^D1wWOG7y1Tt)I;@eci*ux4&J zu95p&zA2HdV{eX*r!U7AI!0?*dKw?8faWS-YKrlR;+ub3D_Sv_(J<%0nLPYl=^J)> za9N*u5a=>VvB2>pQ#4c5I01^1`bFvaHXRUES~NO^!io_hP$W515tcgh`bqC9cYK++|WIw22FTm+!*6sMtU2=i678PGipnn zNwq^Gju<~|djx@@Ve8%CkQ2fwq19sbG=sdi@%a&hn(kNJFmLu?qi(FE4m~+^&=#D& zxc&pzy<{1ZG}l>xC@YLl^yp)0FXuX^v^+L4dKglk+I~x$?*I7l{^qaUTP9g2GIQde zpaK0>l3(Egkg^ZX>0bbnS>8=@?i#UuK*~-O6js1RQ`meUR{9xcK>Im?bR0MX8A{;e z&7YEqWgl{*ZKLzea#SFx=v72ad_S-AV)!RgLzp6j75?6Oe}y1OpH1}u`mo>*1(O(O zpz`Ml+z74QJ>?`rDQjFgy_^uaU65-I4b7G&F!LV5*9|qxvPk0MOD9`1;fmUZAWi6tCp2U*0rlq{wol8_HJU!y$yH z+C06B*v6_M#`ZF7Oe;cyN=BG#fDM)9ueo%}Vdm%WgN&QIk)dV}t4X3q)&!nm77kcs zo^yMNE*&E!Zln5X6E;IzZh^6{p)pI zA~mv8_}9aotSZNQMExzS&yarn{?`2VYQygrcPWr>H!)aYJp>A$`56a`39d2Lb6nP! zyBJ!A2vVYO+@b0~EueIeGftRU<@{dPE}`>bw+^|bA22unbZ+sKx8As4#3AvjX^V1t z#AD3pQFWC;-bn^JVa$G=eQF94bt4tV7K=9F2+Z8t7VP)F=UwO>OGi(pDzi90Pfg&^ z|L5CmCKA=y*7ms6YlUi^dk)SU@5D0fASyNY(JIw;xo72pskZMR6=LUs-~CxBW}X(1 zvDH;8nXkB6AVlGkHD%uL#K%_p0AXV>0))umX2-z-MC!R{p!#r%BsnJK7;p)OcG^4^ z6%XGr@O<#Pt22#eAVjPRg^@tFj%T-%=gxtR*~f?DB1LHNAZ20>6zfkyB}tn{s{ebjW_##j6(W9gW+&+o*e7w?%HYs}BZNCLWv|&Y!-hla%_HT+EQWG*#+}xC0ML zAn+ih6XFv)nFkun*SrhO9Tc4Y(;uwV(!dLjMtn()C(?8CVyoUgr{Xhn#d z59u9f-rdsG1q$bs>nWnW%GrgT+>4B*kWA0@j#Z(BztmTEu~N13BKODWjUp(g8UIj^ zxO5cN3A%eWy^z58^Z0k=tN@A$9II#?>f1>UuE?5!!^*G8Vgt7*k`{u!dY1NqkPB!` zBY^Z8M1J)|ssA7cI{;9b^!(R7_pi0k#G2$(G*j&vB$M+FD@F-phWSN{Lh8kdkUCbJ zflONSUOyw)GorBoeZ86?rwMIfj2E1qv0dO5|GA0P87yH*6DF6K@aLDGlu z*27a5({yR&H_^jr7d4CSL9Xs9OkD%h;tY0LTe?GCmBbj>Du_X&iy4UPTwlin-&l}= z62_Fx_+h_5U#yWBlhRS{XG!~EP~icQEZFKTIOZEc+#lI~{neJ%IG#zkZFV6zE&9@@ z2eo-nJ53Bq&1t~RlfbJs3ZH&3tY9XDD7GP9&yjg?icNo8uWkNErAzQ{{7`BYbT3qdZM6Zk_So*kPxjUd!Akc zs&2}A{Z>;hu0GBDDj4`>hZ{1PvC&Fn*x0!9M?4)sy~6=kIsV8GRGOmmBSV;)k+Jy9b_aB6OdHM0*&9bMs)KC~CcW zH_y}B*GX>nh4u?wpoFwehJlM5OuymGL zO4%J0b+>)AjquYr__vZ$>VuMCjmMGKB;VGbE|IzEO~D_iBPMX;DuSecOhBQAimaL( z)Ed^(kht-^9EP2QWDmVGPtL}ZkB8yuV)FxmMOUsU$qSk!A)sajHLXA;Z5@TJj_Ga+ z@Zs9P4mGnOb%PjUt2u?rQllLc@}u|1^5v81yI*acAa#|+_bKglgDudJqf+L?l6Rrg zWnLy}ahLN|$ck4%y>=X?P4bAO%*&~cYmjonK@=|AICA!1K;`~wxLL(qS5y51GDOHG z8>n^)NbwlDtz0n$O5P&|1_mY<_Wn)8rCLg_H7#*G0{g@u?! zbx8rB6!9#1^w>XYp|V57JzCb3EQ&=%0tS`S{MlTA;`wD<-`tYf=ICHi@}s@wy1wj0 z-r$wb?uH@#{R82ExhS{tKB1>GQBOsKh&xMLrroW8acdHa)bpTE` z^INx7*GqEw{+OLK_1MiXx5Vm(1rIa*)*V`g8_BNRM1=?QTZbzfEIuTCfAyB@>h0b2 z1S>S12mKHKD*Y4(<1q1k8dZ!%>S2hn;vOCDOcZ8q89p&q)l~0^-k^7pOMY#-&wR+r=;~U-d^R=kONceJH8SiP{$4$b{L}*WE590@t4E4ajq~8)) z7A2E}f9NXt*`OcKnK@$G3C1aK^VUc|_dy>*-eH3@D|Gr!v-g*D^w)XuUseX)FCUQz zsCvn$d|-!ZDBP)Lm7$T>$HmfO)3m+CdJBQY#F&(nzL-^-cp#HEPV=P#!N5SVluQxa zio>p}^7+s;RbT;|2`34Kl@&fgoO4McPl8}243UqKrb2wM@YE$R(1lHL;B4t~j&=|? z+hXM$qreL}P|NM*`5Ms!6+}`=Bn?ETTNWXc)csVku(cdBG*BXy^Yxkeb>>HA6GCJ0 zG;rdZJ8xTbwjAczaZ{7z?%?b(=G>&2GQ1xoXI5Mg;SFG2o#!n7Y`k#XR-fWP-K5)cXw{WvC>1#-~jM3V5l^d z|MhbK`7|*&K~1b%TO{%H6B)bC&xL^oH9zTFH4(`D1A9prMRwul*V8bxOy*Bj9xD5U zeX|sOzT@sQQ-|sqB(8%Ll>*gm7S>@}8Cd>ib$m5?KW&319OvDhWWY5DCz9?&jO}0yN8)m$U$$U|wz?F5kAeZr<}-ET+0oigey#^ZEJX1eB5tReE$#4(xw2 z|8O6hYxp3iF?zK2)%H)T>ABOjx|EXv9@L!q0{XjJ*ddKk*i3%L;h~G1rX}3KVB`cO zRDr)led3=(j^HgtjBzV~*8M}C;Z<5R7<@_Ame7EQ5tk%xSX^+d{;?nk#SqoOe)z-)UXy_f~(r_EaH) z9>ey`NMb!I34&U?TT+ilJl(1#1|5)t5{vbywQ9-0T~t24aJv(KsSMw9zo|k!+m0O-aV}~c5SE<!-+q98F)JrOQPBzs2KEMeptuJVr*PU%Sr7` zx^bFF`3J1k>Wj4cuB;m|eDIz)yQZ6xH%nbPY0Nv2o9ZW9u&UlFJl#TtE;w;W*{=58 zX5$F(y#1yp3hC`H3mdR3?-rHEU&%rldYepdL5U*XE3kBV>cDFO$+JkwnrN1FEt(vKJ-RYfP)q9DEy zvtvw8(qt|4fasAi^^DiSfd#GbVf+CJ?qO~xgK3OKj!LhHYz`rhoV9QiRyY17$)0b{ z8l41XYZ4ZBNF|wm^K)ZCqkGuxo5K3^+_v^3hrgMhE|4BqZKqfol9?m|VeI_8)f6>) z*XP;vu?U46YrMQkWQNOdtwb%4I>87yuhTa^Z-tqY%{nz;mG`{$bmI0(M!YzUDe9#@ zPr63mTytL^X5W~$nV_xuLC4dk>%Z3-#~`}jQ<;q;=;m}WU^P47x+=6q+oy-#M+{`x zkoVO?Ni77Lx?Ok&J{Ly?p z8tm;r(QK?AHK$E(k~t>3u`2Sp3cfD`_fl)t-zO@}lx;=APobGw2hJrnnP(pMZk zZZ;SEK0tpwA zmp%r|txOx9BPe2$?yu|k{df^8Q9>~eYAM^5?;+^1#JWjX4+#hW>~iY3vR-FFw+7r7 z@zqbk5-j$e7W1TYTWfw$0?BbWbxL!Lvm*GJs>toJv1jroF_%kraL4uLJ@FanW0Sm_ z^fOlmT>Ui(-H`e*zt0|}lTrp!$bMn4iKYU!zZ5nJhZ z5ARmJxWRAz-HP%0joP2?PmvBF5~s#$$D87K?|ci7VG`GI2-ll0Xgt&{8D)sjqAqkM zC?t$Zjg9gNOxhs)U`E?X588=j;v?Erj|JC9s#MSGV>bOl=}kT<($OP6sq~_YH_TG@ z5tby<_!0-Ky*)M|=Y6=7Z=*(to2Blws7!hSY;J7lF5 z(wvpC`|*ZRMM^~j6^ti4=F9j)K=OA5{(ug8*;?em zZPlrrm%WR*Xq@g3lytrPlQH+_!l$~>nE9K^-rcBEW7Sjb9NT#vn|;3<)(WrWAi0Am zEoGk!MXfh{snd2}Ed=R^5eri){@EUv)-_$Alm4GD2k5)aB(k3fmQAMagHj?v{9|u% z7=obya40}8?;a)mGxEC3G~u_fU^)oKtJuY?L%HLLZeyYHXjpnzkOeVc(!#-9N7aJ~X1g_}_r&_Wi zMq9F;1CtneEVfj|)ZDpmZm+R z1sSz|2eeBKWB3ySxTa~hR)uyW4(|Iq*z?Z^6%9U|yFiE~FGk!M@VmE%X~!QEhh)Ii zHI!wCpdewdNx=B8m)eK?Slu_<*29Ku6MJtdw&PT zwfdVH9UdH$I7bb-YwZ(y#TVW1dR+QjMcCnxU2uyW^U1&1znEZIRv*$u}TO2 zuh=fJTQ7_D3QFPOOk6+lg2uWs%|Dx6+@&hUkx?N^kt)Paf}0u!1Nm8!w%kmg&SGDN z?UtqERgAh1T^Ea<3V(ui3V@av6_euB;4Yd2g{%C7F&xNwg3eOs#nWCVQ{vu(ND$y;Snl zN`pH4r7HJu6P{UNadBk3mX*l_9za<&11ZnPR{vsA**ZiX6uAue8S|6{@r93(<$Sy4 zLKg^??ZVO8{cNhx2Kl%WSm6Rs`>8R8A3 z+UwPD+2>b%Y~GiNU9%InKM*R)HNijRw?Nn9>47x3dJ_H7VRhXuC`&p7geLsWISY>9 zboI?+t)|N=m-7$rS>pTY;iaD~QeJ_4nAW=bA-dM20z|)rcU)f#^BuEk*2hvyg3?L8 z1o&GJRtz5ZK)nrKeDzZ2HE_zJ5KSVblHkj7mJP>(4iO|3vozu^K&Ez z>Mcw=^UWiRwrAgm{5sfn-4{JjvEe+w2xMR&0?VZ0v~)AGT%BDc&Otd{M(2mW& zh0SeY3GV2Y`PMG3&`f|R4?LI>iH6HMR)tJQJR|a)$;e>~e@t`MTs%NyNc4xnk3^~`cgJ%EHK z!R2!q3QC}!1dGJd$nazD8Qyi#%L&sc1d%LBr>e$cQmXy%_X1|JLwWM67`)K8q2r5UakV-fkUrGl_2g`OjWNGZ_!~`Fl;+ zbBftW2Hst08JzmzlKAI*mfU2^Hq8cYXbbHhnRje^4yHN##YJ%r4JCV+m+K`rO3 zrMy+%2K)f*-pSlA>+S1o+T=A&Yi2-+${nD3G*TUwrN~?0*mb`b5TiStdw%NNv`w{l zU&K|&sBuWGyg}@Xe&5?D0EJ(k%sGu4cC_%t&TYF9%~G8V{Q3GKnCS5i-RF=LD{8<& zVbNx(+nZnfcoCeo;oY`S)BVWdX{P3)&HQ;xake`9H@mX>k^z0;bgC<=r$ zXn*l`@;Nu@MdhD~b%`XvqFo8s%wl0+8nD*RnHs($&lIxcF0mBcRORv z_8yi_?V@e%r;%Q5(FL+(^2wXKUWI3lcxw1ja2?EEm@&#cx;Su6wN_U!B|VS(!!3p)VBHFo!Qpze_L{^_R{vD+^M_2E41=*1;m zUS>0s+iqfjK~h$K{hU#@`CIFjc-c!1QlTRWR@_wtA5%1<%0DPkom`mqEOtE&2oCql zQO!Akyg23A4KGto1$h_sSK>eC_Nmm5nZqt#!1LPzq_4(uW*~bqf%nwCfMksNfpMT6 z0p6`XAuT#{=CHHjdn=zXie0(Gx8%k;>7Oh~ItI}PU=KQ@5BJ;9#J6&A;&eM+iWX0r zYIKJaJ=6|aqYb5JhMko08y}(|a4^&x2&fxWMee)L|<9q7fT*L3m5L5yw(8kFn zWtneK=_+Zb!}km31o0?SL){U_+1Is0b7cJO4p*vQ+p-PT`L>>#ezE?_e?~0%Q>EpH&t+a*VLA$9XO$C-VdFe?WfQo z-~4Zo&R{vytDrNg&BRG%#SdIIU;%sj$qKlU>8oMQk!BrRO}k_KUl`hlTiT<)x0_V# zpPju2F{vN#&L1};7cN@0+1z-3bZmOPB=1v0Uo~?=DG&zmsy;Sf-7k;#6-TP+XZ)lU4Yco z3(X{evX`MMIEFmV_IMHtiqs66l~j4u?LBUfW&fEGqI6$kE^ILy`ux}5i|cS>A+Uux z&hValksy2Nujrz#=|n~zHyhhqNo!tiif$WwX*L!=HTD7BJa_vzn}BbQio_x6v=IHo zD^xo#oeJIiS0YLJ%0P6F%~rn8^L1lR;ONIh=UB2U^}e^wcnOTW)e-*0)u;DJp53V- ze><2P$&$^SJd?#Z$nUf-^7sDNBp#PU>!gfaKj)96CPO-}{E2b>HfsJ?3qW;6U-_MW z50~LU*fIc~`KC8_YA9)DK*wor5eVwIkKJEj{4Bk&zCdt^({KxUU<_swj5zGcZ)#pZ zNWltUWhU|Ik<^e7)i6Q;P<4++I|c7m3J7nn_&l{q>8>dC?+~OCXne#_{qx&2AyywG z*AJ%KnMiBKwfu2AXU7bZlCbo*iRBWZ&6fLEhHaURU<}famCGcjNvoqMNkKId!i>lB zQ=wbJnuuVeN!ZBd;mcTi>`!G~2RL!K`FoY-Q2zB*LNX(aDdRSiLUX6i$8Sx&5xj~> zo;Ac}BJbKMTYsayeL@%0%nQ@>+>-^OGvw_lg|(V@RCwHMLu7W||7q3XkkSJK@>J{X z*vaC(1@I&Z8)<%V!nW$&ox8B#JNt!y_DjyqdCI<1xb`2;g~%_v<=GKCyBF#d0ceY% z2Bk?lnt-Va+2-;Ong%bqABW!jziyoRN3>%EZfkI@`M0PPfmgpDSM2`Jce^-;Dg-9| zlSjEe4ir;><6Ja56BVV+vrQQ(&rx$lqToY2fFyr)!aJA9SoQV~LiL6@?1l?{;kOmA zg`yl?25rLg5)mrE!Q|lRnogLWvW&(x?I?<5I?7oWmmiJ)MjX3-7T}%VWJ35JVX%qt-o2LkqswBT z!F2lr?v0LXks3cg7E$YDw7icEk2U|*4cKK+#1@R@FYr6g1IF@A+4~cfDaj`U5B`G2|0=d#&;cv zy}}Y28e7^6w?h2IkTudw&+Ka_8DcFG8g2{% zH>=XvWlr6`c0Bg0c!brT<4ezu?224@#`K4pNVL7^F&CCE)|;=7o%_dHSk=d86=x`g zLARbWF$WjVD&5`EgOB(%&d1PBDHT<>ppTyvQ)0Ewq)24L{TQ~fOiWYGp22aqtrpNn zm-$uW$2J9j;Lm2ai0Wi1%>CupH<7_vlpPaqMMJ(D;PbkGI2MpY(2zpwmI-0@9#>bPCeV(p?ftNtX(Ul%#Y?rxHsyEU>~7 z!U9WtKmPaLna^PyM`whcJ$v4B&Qs#G(>B|cuQ`DI==UJcxGjb~x?9j`9fh;s{&>?L zztYDPe`=Mv7hw{A`iXyf$*D*zqUA4eDfXe$n+*h=+o@ys+Qe#D?#O3foLqj^a@19H z@!56NSr+9{NE7#yl-M?z*vOqRR+ZnJD);Zm?>9H?eC<1whxsHj*^RT2 zfyk|<)!A!tpH|OSN#QEDkuzFqv*wK<_A0tKeFOqQ7FEc~U<&R=IIKDWMFEp9etHK# z?C1S!VtZY;_C z0De6zqE`fJ`L%G`)VG^<5)dCiWWAOq_;+gaU~`qw{8Js=2F&Vwn=*k8+)b%!z0P5VPW@oHt?wxUHp|o< z-B^c(&88bX;hx)(B=voh2tk4UGu7o_SEI<9Ddc6v5pIYJ z+C#KF&9recYAt-N`&#p)J6#|6LgO#k4Dbfs@l2>uXm-9p_`EG*#mkQ!geTP;)_(PX zQ!{j{&0-xYyK(bl8R3=g5Bu#Wy+hu37M}OrFnvxj>wDNHlpZ-v@q6Bz+mD zzdgZ#q7A%!HxM1SeU8HZM?cC1-jbXqJ_R57_?3jf|Eb8p_#;q}_nemZqWQOiU$gHm zRua^#fgbQ$^`Y;)rp{-T<~p;; z59|Hk!qYR{G{Ek(YIqAhH|uwhBC(SY&L#pA_8KH_)JbP-AKY+2`&rE~iai=nw4yre z_k-#h%X?V8`^$`-WtF+FK60r*c@xhE%$|UB_jH z8QeZezRhq(c~V6Rqva}tW4UmbD_x?a47XS8%<3I;)~`l-ClLKHMQHM_5rx_cz))DJ z5Y2biafWTUs5y~f6EZ`wCDF=L+LI{`jcszK+#*~5nZy>yG2T&B^M7s!Bt%yX*tha{D+s`vc`9%s;-bCRuXuWv6!5P|_euvW8RQ+b6$C zH|dOT#5k_#4--2@$PDykU7QOUZXSu7<>s(YuH~AG-w>bK$jrS<3uD7StclQf>Ur6? zS`v30auijP@1tr5LE}bSv`Zl9lOAJv(L*cqwX-g)ax4T#VGwgu^7%IbSMV41eybCt zTB~|rqNAQ-wf-hwAHK!>SkRic2P5YS8G8{{RPbnC(p`w` zNysItQhta@&8u6w@A75lUg`?_@O_}DeiFE3wK}#ka{CS*45rp{axdF)fo3y1=fCs> zS-0)D4o=yzXH(^LQELyG+gA`qto%A!x~g;QfECrhw3Pd*^m{G(_R7@F=C*Q@Zu#j9HZIJ@pm_4-3GMKX zkIeW*il&I61V#t~H4_#~JqJ8N2dVxr(A`z=awg?IcWry@oN1DkU63|1ex2aV*Jxzf@9owQoiX|U$-&L6*e>X^2N+ryD1pHSXtEcR} zQU1sRPfDrUJG_w1l_QsJ!loOes(TFpNXQr?t9nCT#?DlN`}OAk$;#vM1{;!3VgBQ9Xs~ z?&zAZ@V>W~c{H7WenE4|o6x^XXcup3SHH;ru9s)X)~bV3;_wUeWIOEF4`uTxZCesYhe29&Qv3@xJv4^CXOZ?B91Pzu+S3mU z$=<~>>Ed;hTJndQ1u4zG#q)%?Balg#wEGk2Azc5!#TeeDc0@KPGY<0rZsf@2soE%q z7ecujPQTNW=Vjomw>pS(5L}zT@xr_h0S*s|HsuUMvRDlipYc+6N)QY~dNSVE{e5e{ zLM+u7RrpiC;xKkXCKsbKl*NYlZ~uusYW$cetNwe+`rk}smat78=mgXWe*;zc+XS7p zCiVJbZf8LS27U_DrE6KAFCO<+yJ+k;0y83+J@jOze#Vm`FguHJs78@83SiL*Q0R|^ zxw8w=L@wq`=@(+Jp3U%l8umG%m(g#HFw|5J<*v=sl95r5lj-;EgEpq5Iw~_Ujh|H5 z4mO-ZGq1mxdI7di$BPTYOUS+2_OT3oRq%lX4lq^#QGk>Cy7aY1rGo2A{Vx-0v(k)% znFl7xJZP@mWgd2t+hQy24Buij_ZHAT*eInvdW45jOTQt2D1^Q*6yg%;wEQ7YNqygt z{It0!AR3A7^`j+M8qM*TM?IzQpe~6#LUPczIpy`fr?6LU8{HU5w5Kq`{BJcipJR7m zqFCcD`Kz=LD}H8P)m+CSy)WG3pSMiJn!DOl(YEEOrd{u-2g-&aaqD_l-UPgxLh$*B z3BEKPXCbMd_kTI-v!c-`HurkJiRO4|Mk2hl`gaC>hfXSMo$Z9N9CLI!S{#ve zdclC&1Mt{$ur7msf;dJWb4RIN3;0(t9E2)8sO}=lU{Ih?**Xbme{e(GFDD^GxBQ4O ziVLCNA*1%CG|i&!DF>rwm!ATjU55Qn*};I+L#=wM5C!HbF`RedAMrn;#h|HqMRnqy zS0~AuF;Tlm74LG9Ov~2`~NC`pp{frp|vXSy9D&q*4IzJ&u z(-F3H>INZSox^R@CTAtXIge?FWXn08Hz8V1Dlg9-DY<=EpRK&E>R;pL7;M#;iL4Ix zIADq+4`U1?Wx5RPuvE-kK~pf?X2b7M9-8iHtO z?QB~6uyOOz^{+?w^G-_A_UU(KH*;z#Xkp@K(tGhS*Cr*dqd6A2dRta34Qenk{e5W4P&lmoDUlyb@bUy zO?vO1wEz4$tMlD59zc$!k0n2O+$F|?R}fj7`hMU9)M%TJ^qIZTwGjqr0W^A ztv#g;9)%D8suKIcDLYqi>H8zlIp47cT~{)xh*Ep%`zAuls9FS(UDV1Eo)4pi9LT}% zhxGMEKCgPzbAlDt*$AJS=iQqWlr>DhyWye2aiYh`4W{Jilwiw{xx(=Gfw`kj^mXdP zOjMp(AxY0aSFExO^8*qu*POCEjY87lvRa!}8zs_9v}KSG8Q3V06DHt;@sdASU5*&r z&bhFi4WFjqw|9$*SmU`y9JX^KJF8NI1PRfi`S;!H;&C#^{yGeDl0qQL^+2Q2D%UDb znk|0_Jdhc}`MQ2u3=@zv&&pQaglfP-#5bG{Tm_qpt{@?pG4*}Q4!`2pdQzuSF=~ir z{m|1{NmYxgSc{t#8SqEM2Wec{6rXi{3Fz!#F}?8TZ1@#B&)z zCoWo`2nBv9>b6aTf^qsXCyW2cUDL2j&52tVU*@gvHv32l9fMF*mU{qA0E1qI&y`^z z5PkG&j5Ruy^^c%j-dna|44o{N-M2VaBQ+a~VZ;<1yBD|fk?EI#YDi`w7-qGHie=|r zKh!VZsZP+{3SEwyTNXC;a&y9cG({=@Py{t`wkShhVmUPFQ3-_uA1r(zCT*CjhQjBf zQ%Lq7(HT`8)nbF##mgjY)*FSlwo56$sj@w#!axd>TlWu=v?d>YR zsEh=$g{k+BtE!-vC_~Sz^PXezV~3Oyf1?+*Gyz(FhEG|)Bz6IL!GEfXYeevmImbM% z&tnrFD+|3-5?>};b|swlXj>@%PPx784;800v3>us{>Uk0s_vk{JV#n{^d9-Sc2`bT z&Q74XncmM5XlYm1DbW+HkA0_qiZ<4~eRV8Kc7Ogvt#~i)<$v#}Y$BnE4`oE_!6{b@ zwT$Ht{PpfA1oSE3-_WJC-;zGD%RIFw;n}bgcbt#KVxoC`+JPYmoA8to&}Ey6pM!et zdtpGSjoCNeSCY?iutY`9P}(JYo1sLT&3A^-{Pm+3=<8gkd}C+V6vYWWv<{2aJ1^ol zF2yk2-?Mzfq(y}@Z|qSKX>A5T_L56)=G;A7DX`fnKB%u;FAP=tW-N!m1KKntVX3m%Y{GVdN<-JXtg)hJze?e+Y z9f4?W@Y&)ahL}!Wi#EbcS~68^E3M;BG*3t^2o7^(xS+HO9_4>L!>8YcPVbS~80w)) zr32}svf^Uucloy_1?&Ixm5392J(tWi%6c>@B}qv*fk3XIZXPn{k^Ak47Z+cFrpuob zH>Y8zbLgu=zr&Te&olVI>%3mpiu4>E>yDNFj@xUO?Ay<@W|UD4 zl|}UpM6r5;#i9{6E4@>d0{ciOpX{*tDpC;<6HV0d{u>8iCIf)=BDOpTRJWG5cd8}h z6n;t#2yQcfQf73=5jxtr9*MwLZqV9&%Fq7FwBogJ`d4E?*kT#Mhh!&mr5XA(>njEZ zhC78Y93Ljx;b%GjsRD`cPF%R+is*EoQ%Ei^tjB_Ndg3q0ZlLJ>+6KzBzS@V?aQ-(o z^uEn!1b0`{QXf%<;n_+bVO^$AVd8sd3(((cgHOhqPIDYBpFdLiF&&6}(;w=}xnaW) zp4$qFId0}siLRj~%y3W9xB{$ULVn~;rgBbnS^fN0iy@opsWPp2JJGU>m>j~L+r(_I zKPZI>&N;HOkJAvw`aawrT$$nF1NIJVHE_ z$F%+ERhbxbEn7EfZC-W4RGCumYo{}*-aog;Kf}Mrk6wVgD(~>G4oBuevBSd2EPp}~ zrK4!*fdgB67#nOyfI*>xR8~Q7)`YSHLXsreO~NPJ9bkv1^Db5VMU$%bjR$U9mX}%~ zF&(W|jsj7Pon@W<;RfSmx9T@ zRNSo0dA-dl|H21nOZ^@5*Qh`6SaOXM$(7^E;Cr>wiB>eh2bMo|f9J5kk_>sIHg*kl zI;0l^I_}IJF_g3&FP8e<;@RThgOm;T(Jz*)HnBA$A7S@Wlg}?t9fX2O z@p{m%gCa(4Bm4XBtJHw*1E9YhR}IluB_7%R3GgLADRFJ=*?06#$w+0CsQYZ_kRY1a zMG0srK{M*=CTZm6TBNRowZTv~JIfk@zC1otyX>sioESHaa?ejT2lOv28-BJ2I(N?e zYbU^;n2#G{AyB2yIF+5dwwG`QHaJ=n^$66{P_wWT+W1Ek*{uIIWF~s4->|c>%E-#) zp&O$;=9O6#(K(}&rXVjX3OGeEr)|RHeO630@5X{Ix z@@akwE4GO0TY|5okFcY%iH3SH_|Q7oI=^B;ssHMYaG{~ASx8S^PH)1I{3{OQ-U(-WqWe-VnGP_$WX_+==bWOwM_(D^o&)0~KZZAI>9Cr?^GUIOE zcT5QzwKY#_q|+@`h<>PbJj69Zzyx*`SK#TB7Ct6q@2UDXE0|Oi1`-i~Am;pJT&A&g zbLl*d&ofeXED}k*JBw!I!y|+3`QP zzH_Kb-+w=7gVD5bcE4EM;#1?L^j$uRaQ%;bi?V!buWkPmf$`IzBoJ`Z>j<(qOE2@| zj;&p6+G|ZbUGfoG8`ySEvufF+AW#x>29Ev5b7_9y@XvLfe}ffqyA-a!gsrsD{g3-m z57$2N~N+<&s#=m>C-z*tQ{1 z2~gaMPYr3Q`sfDk)PXCb*Qv?*eVwwnx7{CF% zyPh(|Vf=DKTfwbyTmm;M&z*_29M^X|Nb!^KiN3$3JvKGB@g)-2#1@p&C(X=HRR4=s zGAd73$h>v}b*+nJ9F%U7hC6?<$Ys~)>Sh{3bCTNv$CU`PV$8I(Rh>`{qF3o!N;sQy z{w~vNs~97Qa3!mr%V-Sh*-AQTX>zpKBvy-+U%vXp8*Ppjt>JtFjJzw~@y~T)o)$~O zG*`a2f2YEPQvX3}vSrxIqG%s9XwQzWWlk=He_`M!+t_KoC4+X(WZQrZ(u z^$MY5&K_HVerkGr;V|mRiDkSjH{~a!JNIvOXyPdq3ea(gDp@nQwb2aR7zpSw)IvkU zAxx5^Ovf0UDA^6$Xkr(2!SwYP@D~LmH&>s|-+2U*k2>LSqo3sao2e+_ zV&OtA#C)n*;s&J~Ehg`Y(KGo!FdufWX0-!Qho({8kaZ96I>N?)RWd69_^$8r(3HQG`C-l(2|OLEc`+uv0EQLLmtz`agHDzY z@mm9JfNV@rb9lNNttV;l)quB_&hom+)8 z^sK~BsGFC7e(Rs#9&W7fyj1qgC#bH{@JVMFx`8BiE8d%j6UU$3zDdwVFi%TpL~<3k z)N)1pwl?xD6GR_XQUf=f86%_o7O8_va;pI;5?0u31XEZL!{<|Kzxps!ZZeiwu94ev zsATlVA2Ly_!S37s`(m&3^9o@^6y-Zj{7~uSom<)Kx$tA2?;FFsdQ_JIu~j1q#`gSp zCf!gfc@xH|`}B1`NJynge@$30;Q5C|z@7kM7%rH^S%HHq_7}dYwHqM;|&sojp3wzxg%QJYFGYAI}^~+d8+9M|pF=ul5;T zXxYtexWCbWk0nN3vPd|%^_va&~8yV6CoVF4CNbS=i)!W8krsC|*Un}xSAVb6pg zd5YvU(9|t0ne@k0X)!?A=~>*vhCLaQ`azoo#D>>%q@A^rQ4UWH-ahjlIRivcp3)=m z5VzpZG_QYS*sTj@RNy&h&EEwq;A%bog1Pib-Dt26`;P{`eI(?w2xLx#?<)9J@pa+I zrC$nM8ao2ivYtZe1AMz&Rc%^+;9A^kZcfdeh9N2fTR=*&edX|q&U=NVO6qSQ{s04} zH40g_;MO0X`DCEPLvv3V+_$+;b{EPv+D4+ny?M!JpgVEuRAU^b7ocGJBa;J*)M4vuxvWqb^~1(U&ZVML#m zc`o_!PR^) zWJWgHVvj1{#rr6&cu*o_Fke+*%FE(g47_eB|35Ck?1eldQu1FQ!;#-+!p?7se_Q$H5PVKVsJqW`y+X7Zk$OC{$e<`CA+W#T0|!v~zd{@BV9k-2 zqW3Xdq4JK&{QIeY9;R_OBYd8ObQW^s%-AhBN$ff!P$dz!|hq;PdQ(2eG?m<~v zi3mp1qFAG-`8Jc(4WLpRfa7vEfdHBpSnK=|KFBraseUi&$(R^f=vz{(Gp~2$1qN>Q zZ=_BLE0bVgcvXlVCuy!?-+sgSaOc!7{U>=pA2$!r(Sl2doI?Wmv1vMlxL~twIi4b6%@7WrU&>zM)Jy)zl$9peu}r^5?eI1znlP%!MvZRO4{V(JV1S*fTyO35{p~qgk0~_#~WfgbHSEinbj+ z@kS2jP@pV+52cB>f7Lp4Op~!YbfWc(FOH2r(iv7ev(fgf`g_@qM!e4{MxO*`P*#`e zi*3}zwR9@!ggoW$MGe*@4>IE|8b$?~KvW)SOc)wdi6Ux2U?n?G_uyo9Urk?C?ii2F zy_yp}jyB65O@RJ5`GUbIfL5MS%wnGAo3P|8f0`&1a{*z(4p%{uS&QUH8 zKNQe`&*4=ahXCK__@N?0r*Y5r{nD>D{3Us zvciF!9(3bB&jhrNg$c8PkvUA?!(rth90f|f&1g{=nO`24BUZyHm+bg~g@Yr%S!yLn zLKCvOyX@1S|1=glMPH&Id+|{;5qwzP06+t(9RQ@W{vY^k-}iRx1^UKx-|tNZ1}%wj zXWge1E4%)ued^ByM`0d-B=5`~@^e9MCu5&Z{EE6@I}6auz(-|abK}2cg`4vYl7-Y- z(<;qAmg1jc>XUCbOzG4iy9#Z8*+~xO>9zUJwTjzXmIEPXKE{$S`c4Z)U!z+v)aH%d zV_#3+`m1Yf9d~H>y1SJ8p53T6dGq5rz7`XC>uG@`rbGpr6zu>Qgeu~&aR4H(B@m@( zsH$u~^7!lD&nro!N`=?7Tjp6~jSE_b>99{@fLVO~T03t&R5TI1#>xMN-9raUhT7|| zrlxYFj$Y3uk@Yi1xnp3i9nuYv9sWEH_F}ZCuSlJ!5ouesKpDIBm2DL>#8h!2;KY~CN42G00(2;jWpTg^5nK)67v_@emnKCnj?u&qAAp0z!( zOoH4WB#P)Pfc9+lV*lA|I;9^$TIK7$QLTQA`4Tz-!8s?>qIgv2mK@!u`%%FzA&;9+ zhsu&pq2SpjAMttU#~()=!_&x*Shu1UUyud_=d|KQJt;vIp1c|7)1gt;!Vy|YY)OG_UY7Ce(;8t`R-N$^0IJ{hc|r9GF4(s|k~mzmI8dSs z8ONO#YAEohVDIH1=l?CuZB|7M^Y}u*k>{nUMnKFW4;Rxm+1fnH{-pNL90H>c-L*iia1wXNlBo2c`Pxw{z7Xrp z`z0AnBH4TBR8bT1vI4dlhjJmDcv`-BHtj7dzjeZ1-W$uaJ{9seioI4ar$PS`QASOg zO1i3K5jPMoM_@697IXdT$2ElztsrM39tL5t?v)$l-Zn}rzN;!PQ(fso->RJfmGcLm zQ?oOf;zNn7i=8P>xFrVb2_sdsEt+6w0ol&|A7i9D7=&c|q>KTbBg~BZW zr==;mCD1-=-ZDTc@hNt7mw5)le)e z%}94NwwHRh1X!Uewr412|Bfa?A81dIzl6`l5KRW0fnqW@?uhD-r|ypvedS4_FD$W# zjW)kTLgS88MXNXr>Xtq^4ey@%y}miW`)R;onmlv1hz1eXSFS$@Wjx&Xq1uSC z@)!$s_^=X?E+zCi!#71APUsi}BaO_|&4bl&0+ugcMSa2pN~;;^pLb8-i8Y1Q`i%Xl zZ;B+=jm+bx{3VKplRcT~FJc9s^-VTt6)}Wd`{zT6DNsu+GE(HFz@$Helw-@F_^OaD z!i#oZTe<&(IA#8Q&f(UaD2}~m^I&N-$9Q|y$fzp70CYcB^0?Qoi4Fj@ewP@wtw<>rWx(~?zb@se!Z1!HU1*27%hZz*wHj!&m!J(JcU1A z`{i+GQxuF3Pi_cDTC~Jg$nXe9jrM_3A=j^$-^wmhYvTRcL8wuA+{Kh6^2@9qxolSY zKn-n9ZCnDvs95IPbsanV#F6MJPR@p1aEsepD|RDABD}{rH4Lp?rh#JDdDE$gc}m zY1)G1J0!?D7(c?^wux<#e4(RWH=psvJ704!K<42abO=s*W#{n}`7SyeuWl+#O3gQh zX(OE-v3tLLjOm}ZKzQPdiO(EB!dhNf4c=CoyF*6e>1&yYA8q4CZ3*8rkh?#IwDnlN zgtgK<&^_vX)%)0Xln=^rr?SeY5YnUUn7z1O%VvD2Io(f0ET*M~}mVK=JG<~Z1jHu4|#&NEHb+`S`w0FLYK%Ul9%89_;hg%}q zM1Zc_a4>v{G`Tmu5`-cG*0oP7tExZ&118;%W38l}}VFr=NbodWJK(8QYw)h${}GwV-_SMAZnEF&yO+9Mc4@ zC4k~4u7J6;=vG)%;p#_U*HG z;^elzXLnDWfST|=E%wQ?Aj!bxfm@G?&bsbNL#v7I@H0%iwZNRC+8#r51|Z2Szk?k> z%LNFolbV+$QJbFFv$)3r7stKAr+-k+0=t$!s@1E#a<0#h<$oTva!eb)ZH8`X@A|WZ zOXX^C!G(wULFk5{dSNP<&t|rt5h~bKR0wihywY`(R!P?M3XowYwwP&2I5AA`L}J2G z2aqT(m*m_LzbTo~xxo~A*RMxOp_yinrZX&q-p*YJY}^yn0I`kPG~beZYz*h4ZW|Cu z&zS*ZWjGm-4!T`M>r88b{`79!Jlm(aQ+rhG{48fZUuW$lnuiWCn^yEhEV24%!qeX6=!=-XofpzP_tb#vX5k4Io4bUw9oqk>$0+|jcuG%LcIlQVirJZI z|E`Q>NjyN37DSt-f76)lon7wN^RY5}mdCJO(LSyVPOIQZ5r@jo*pvB8JB>hcS!L^0 z8$TCSAz5BoVIHpOv&la>Kh_~_*#zSyWm3QY1|$nggo6o)POHESu&#Y-s#UF=ISa0R zJn7`z4%|oX{F}iY!>AbX!g|}=E^4@Rye2`w*2%wvV66~JQ?SAykGFF41^NB4G{w$R zQ`9}}#jv)@*7ewZZW}|s?36v9I2OZvE`fGp%QN*7UBc*|if*^u>#c59aj;#k1MV7l z)PqE5Sul1ZnSS&F4$#q^eau3m3q$ui=SL6nrYP8Dlm;&VzTIVxraedd8@UKGfnncm zO&-`nkz=+3pfJJ2u~7z=UWtbvFDKp}Daw%ls@9zJ{9ZYs2V?9*`bq**=O6ud4_B}i z@KUbs?Y;Z{LvWb?3V@TVIiT*Z+zI`2xs!|%m z$oQf8cdFTIvrd;=DDO79a$j{=XZ*!^H`WdwuN|IAr#@8#cOL!;7+Nfb6apAgNyJ9J z-x~dlS~X@L-5yw#K`HWy!90-4ertNvsPpc9(<-Wc>A9s29+RWhK^4ZB*t%##EXa|A zl8?8jHw9lE;ojZWG8^?ui{MWQ6&6H^&{UGme;61b-dPUj`!iMd49mt}ns~h&i#&zE zj761RCz~QUQ}QHt)pgSP>} zA&pQuHagLT6l=!)E@JW785a7*giNnn-cwR6TY5`sNZQ7|q#>Vn*(`T(#X+%)BAIOB zIA0c~1~kwarq}bMzVWWWPyb#N+x}Z~wWGO6wD>c5O^qejpNg1RV_s!d%hctYH^Cuf zy)EtBM0LkmCq!LL8Lv`z3YPQxcxoNY6~ z6hB9)o!8UG-U2?`mG?PiX{{EXGwk!pGfGTRBnY+b=B>Q%zzUE)L7{Ttul4NKwQ-{= zoK!sg?>`nZjz_q(&=A#Gd@Oq!3xg{4ircgpmZ(LTcjID4CyRMD@h$8|qIH*$P!A1hNlK_Q9kawlN$5-E<5@GD%T2V-)@G#2Y1=&n{Qr#uDoIZRlo{9UVug+sNT`UMO zn++9W%@OCLjrlZxtlM~9lor1HH!g&)9T7LH!9Ikeu20rMt-cSfGuln>)Bi8WeGQCN zuxuB5!YmBg`3^piO<0ao%3@{e3QQTnKLZ?~$S>0U*?w+COQ?k}JKeV&LnN`zQcRpwi@} znePC!CP;0Vrt^#qJpG3ciun+Weg8b4# z+?NsfQ&8RReGy=bcfPByxkp7^U`*9Beo%k&J%s)>kQ8&Q8KtuVw!{%QjDRz>H*7n+ zV9fWaWCBN?dg6zFU)b>}aR>r6*<)Gw2} z73Vl8sT3F}JaUk2>k|5fow3rmFo(0<-={0R6Fx}GNsZY>I&w1FZou{#O^apXVsHQK zvjQ%z*R}-Ta&6pE-o8ca3#CxrabT2nD0%+I>Zfs0KFb7Atm<)m(lM=e9tcUU9zp@! z?nVa>O$zPNo6jXe=PxYc^p8&mgw5xuIW^G?WeFHqHwH3f`vS;0Bdow-I=4QbB-To{#KytZ5aF>=y0bajm`Aqn7(}AtnI}La%n^WVlYFQ*2|6=9>JQm|gPnD`@faPzv#P%LL!7K zZ!b^3Czyb=(z|;F2$7w0JX_8Vn6a}8(0#CHTRUgz3#FQ7>00L7$^Pvfu=HFsZhR4f zWiHAB$y)nDNyYanEQZ$th?K5&-l8Ynm1AkiR5;9@kV&iZF)<1ktKK7 z&c|kh{Riyf;L;eE&xdzbl_C^SIG~sTPnVO6D=Lq+WidS&X*#RxjgTx6yP`!9`&h41 z<61jc&N0-%JWq*mE_uwiluwDk001W5W7iTkr?Ez}1g^f7qu3vejFKd3Smuk$Y#gt; zlXQJ87)S+nMybEj&kP4GLBM^{@VgUBy0lJhrsi0^b@s8L-|U+ z|41P^lcJ7c$={ZeiVppsh+BGSd4;CW^f$Hpqy_BcDX44aO$}vsCR?rbVM68yDtzqS zfv9Ew3a=?VwDaF(89WC;`bx}B9h4$4?X5&H#G$C8MKcXB<#I0Q`EY!maePi0wt5ur z^EGDZzRdW&x+mN(!{83!OYz9#NPnVw`Ku1m@bbut1SLYVol{m>HzTQTd)2q%4Pd$1 zgjPQLARW^u*ZvUwYkcYS{crH+-Sj(qS%uu0yIJwiYZ%6(4@d)#as9-fb3Va+l^U!Z z;B;uv2jqSWsMhI7QsJ8*mEvYdTiG-JtEfVxaq*?X_$|8|a@(Jn>qdB#5O8`%U?)O2 z?=SM=`9rmlmuXbo`$bn^Q#zjMd?R@ax(Gn`-Dq8G1{$ID*?ac2b0d&`2}uGcm&?(k z_Ul{WmWvORM=jMaKUQ8hTl^vTeg64ogW+~H|Mu!Bu+JJZQql&C5#X=C@F!*%iV;z| zY#54VucLW>6(9|}yvzbOXJDnk`F#}9B_S$$h0ive4Cd8ToiFx7fG+Mp`1#ygPhtLy zmYAf6I|}*a^X1>acaA>~!rS*%===HP@r(|g7EXd*8H z=g(g!l0e&+tD)L#5|r|PTmZ`F%5$3qG-)x`U(YBeb`>`-KAHqOw%lxIxjduF*vJ}( zIXFeH-U+zlZK@tN6Vun$3V7JQ;HoKqt)$TaI8&2#zOSI zwUYY6kEx4*%ygEV;Z-c&eb2=g-=C00KMHwW+DqXVgg*U1(o8?zm+X}3AoP*EiC`qB zjOn$^i$~xpw-y;=-TMIyGk5a{t;h13wr^Q~ zOX#7bb@HkbS)mR?;?a#>%ru|h_pqzAqc=jOX;RUD9InNvL!bYV76|QwW@(9Z?CW!} zU|BF*Aw;ZTOeXIGkLtUC29f0Sj`H9vjmX&Rz!^Cm1>T0^BRoa|OSApQ&}ZNaqV= zj{^8dIEtX>gLC7sIWG{y&ezA$;4&lz=Is`D8j(kyvH`HuxjhBM7A}a|O3qYORmm($ zUcKhs9G`RS1D2&BCWtfCb-lwJ{1hBd|( zNnmzrGf_Ljh#Tk=$nYG9IYg2&TMa9=T9 z&QxcLwb_*7v*0K~{DnTYydMV+YVX6>2wtUgGK@CMZ$4RJZI6V44u%){1-2ujV=iNs z^%eQicw}J$p3+VYRt+t!a?lDl0cA3axDWUBV!0pgTwwcoFY~TO+TmOB%l_(*@r=Q1 zAqtnKXIy9YG%5I`n-TZ|`cgmjR&BQ1ccsr$M9pKP$@B%;#RJJ@qAxSQRDZL->?RrT z4JKwuh`;Xou~}%ZSjM4f$he2^^c}nu7F9vyuc6oU=)P@l4rK{~p# z(NOEMmE1k&zBB3KOWn3L<9V0{u@TIG^lA6QyW@F!1zI^EkQdp#0x zoYCfkot+qs5(TiB)Bn^_<>+uog@Z(|m20s8Zss8A{1lr^n~Q8o=;>*FZuA1DuZWB| z=xb%A@GMY3fTZZaK4~omywDW3s_6UMh34b;&Wsy&Rh&}^aKb}hB|RHX-t~Ov@I0IF zK%MoInb@Zw2CHRc;N|s`s=pBWJ5OX73;ePxU#sIr>9*X2PqpWS@m0X=my1^ir4#o~?G#&kv06WfZ99V{ zSN(+M=jg`Rn!PXQ#!@_c!c@RXlfFRo|Db!`T#eH}4*`gKd zW0LmflEZ!vgN`MpI$SL}fh15;_Jx#Qo1(S8U0&xuA5rDM$KET}%`{QXW>CGn7xYS- zZOiZdT3>!8WrzTMOPTuOQqci}_yfBcG^UrFuSxNrCaLzHcs^M!NmVkPd-<+jwmKY^ zX_LAH_bHfdW*uK#?$kw#Q?IeMJ;%8v^W`dT?vn01|DVEQ7)tdS(#n6(=i|$t`2kE% zSdhFIjSDuSwC;g{*Teqq2bSv~mJ?XrBLfqYlALPXXcU$Ky`$=4d;2c&^#tH>0`y5s z9_y=zco~q3^YaYn#+KS|BP^9f68!4A5v10JeOp_s;4KE1dq8PC6%HJS9X7?Eg9|ap zs{pFLF@!U{x2x-Ud}-Ox!_9;Ql@#2674wtU`~cKVfpM?=)0yopUH-@7A~KV?EvAbl z?BX#%m=5^7K^KsHrg(^Mh6vnKcfiFAwdJm2m~L%on?^97kRV4o`#7j%vT$L4 z9d(nE@ej$)_Sfo9OHpf2_8R-h>DgNb_`M4Qo`Dw2*AvII3udB%*nvzDbXdYEK1$l< ze9#40?V!PmbzS55N#TfB{}(r3p1+ne8H3YmiIr>}Gz%1x^EHPU<0r9JJ-$eze3Q4W zB9Zvxs<88*>iL_cv-w`6w|@SdNVz}XGaG7-sXc^De)vPCuh6f=i66I889U^rUPjEQ zYrlc|mf@Iu7`V?$@J^`YnftSf-(`wCE;J30dd2t8FX_hn-OVEH;!e?m;?FP?KQM-2 z&56l9()BzW_|im5WJJHjyIHbAV+h$ea@LqhlEprA>3&bj0kJdTo|qF#eMu_q>)xwH zLDa*LRTPw~ko&n6jmkSa3QgwSCZbpF*k6XOjx<%4n7mzc3*|Ugnsn^VK&&knlAQcF zZeTsbko@C?w5r2Z4GR~3cXRQfUB(bChxKVhxPO)&_8d9H zKbHO`aVLM3?2lp%eHvcr;qPL$q{rG~*M856UJh?hueJkx-Bpq(pLbiqg_Bx<$HUbT^X12oc#NMomEaxwt>y-{W!c z56W^380pZpLRdgRYhoOe?TV|bAou>_1lQifYpIq(U@xGb;S9(k5k8m z0o7kPC79UTy22+o<`I)oz!`Ze9ahWPZc`I+MmZM+EOr`f}5@&pdecR`=A{c#=;bpct0Ddji?WzLZY)OL}((8Jg0!0;q$ zCLtYtgS!R|irod|Wb#_5WbX#$1+1@^AJ;o9Gj}9hj1J2BC?bbalLBUVbmmygM!wJ0 za+;}k9=e?-44j${DW@!YH~3;QKZl}HL`(adEtb&%z=;`4D>s`sBz7 z?_Re)bC`R+z|Q^v-d@SHT@iVKkf>s)TAA2}xwjZWMkaNlz6pD__YNxEUB+7T&lwf7 z&1QL4;k{9_x+kdWxN%QtL%v+tOqUVqmcNz6G0Ceh1ICzkCJnYxJs^BEu-Q|fdq-|Z zMZKw$yWV*qRWPEpZzeLfl4?7W5I@)mGAc?;EmiT{efYV}3xh7b-_I)!ekU*{53PM1 zI+taXv_~QQ)3%9LI?*q^yoqK##;pa{kB$<$&AUK!|K9EpLFlg<&$kgFrW(th@~c95 zfJ=ur*Tpd9AjN04l0bF8W9TH6RmbBtSrpp)*dn37-7HQlHt-#x;KmC$VNDs=1#Q5^ zNesAcD~4M;S!o}yc6WELdst92gD5B`Ev4yY&8Twl<>R;56jZHTbxj$vmC-5p%8M<+KA=O0qpyDUD~q^w5-g z(f3W#klj6f=%53C(mjK`I-0+=XL)H=7juF5Lil&R1Kj-AzW%7;m02ogv>?W06(Gdo zi;Ha*mv|SMcy7PCHyl~B$EjpQ7N&%$#x#=fUW$!6?(k^YXT-&4JkUDs^fUZhCyLW$2)!MWtZ*?eM^tZ&@q-xzw!HfY#kN6IbGe#3gh!*NK$ z0cMQnlC+b#dPZ{WWkjzgeht_^bAj!_=IB;Qi_?FDTlCD&Ih`=bUu(=~PM|%I)pmrB z&AE+gKtSE6oxXQHUM%)ds;a1THkuc#KF~Z|pYQN@1m1KEn7iICzzvIeIGY8`iFZ+p z&Cmdd=GO<~7%q<&-uQtvxaEGX@A^|Xc7|*P?&?maM9aV+sSFDZ4ejOb72-8DH3fJ{ z%$(oaTaeS_u?l=G8-J?ECIj51lH^^EdTlFdW0V_>$1giNIuPJLDmCdP*huuq$=+us z?EQximNXO+Sp)pHNh(TwYo|{7YaJIp3#ZjlsxFr4jR_ewlmZ@cfDJL#y?*$sf@%lh z5yYbU$6exIM`x=Cb=>I8f&clq=!iA=M62l(EwVoKDpk~c=FRcEG(;>V=HcAYW~zjVcmf?r*%d9OT~ zqmy|!c9n$`hh$d?SEhv+frFzX6Syqfqdq%OavK-`PStc~(A6>Vjnlq&fyn!S0B7T) z9Hwip_ufv9B5zzeY_GGC;)%myw?!V1VnD&v2e!mvs8j^X(ig5M9BT!xNvl49aEQSK zqmT3{KeDJ=R-}&I0H2SzxH!;Q|M>Vqw4;MAyC-+wvkeS^NtzZhp)5-086B#1WVgD| zv8cR#!XxtlumLqc7_l@05Ol}PFD##(WH4_j%l#eGwa{+1#MR#(W7?D-3+>esSWen} z2ohHxZLX0_TC6S)HZNLdIkNqrA2o7e=oN7p^4Fk2`xqFUcxzBxf%C3$!N)j7+xCwn zqBXR4r@%Bx)}%&heeX<^v@v42=u{`ob-McNk`is=lyErB)9l8mBPZqHGmQ;aA`|Yi zvfNb;vCg9CZBuz$)ogwv9)$HGX#?9M{wd4olZ`A;Qk)6_38WLch8rjy~5;t=||vI`MHJl z_*l5zQ|NysNY_mWPq=yG;dO*}RA)-l`NThC+ykuo*ZDhmt-CtvI)a6AK?k1;wacXZ zOfjjo4ZU0C@{ERp!lR9tTS#R@^NX|RyaV4bR(1-<$bCaF0$Te055mNM#(b${N){X9 zlW5@Z0h&v0x-)LpC!igLyXC0vQGa83NReR)vnT_4bYLIdByA@o^?& zN4H}i&o1^mDyUOUusMD}o*Y(ggD7-Zx1YK?dZv*p(s z`)T3^LB9!(plqb8pPvR0YPfV%crThoNNxIwb`lvGcEoI?@xSSK@8i>&sQQL1ydpeJ zm{sU*pkY#=ic~VBF3z=XSW0x?m&CB5Vbp+nibwwFSf z2~_G2#wZDYxVqFCZxO#Y)F>-0`!L6G5cKTxUlNZPj{CR?Inwi2xQn`?5#E1ZO0uu5@QAzKv9V5t8qzk^6Cj5ttuCMY*V*vj`k%Hi)XQt8eg93!1ahx8I* zc1aJVI_-aZTZ2)F-tQP@{NbLB5W8N}VA~p_OS07Hpc|dYf>uOfnb{b8B`^3yYQ#CU z46bz6mda{guFJm9N;zenrvD@6vO_ zSiWO6OsLLcy;<;XHE9{+7RtaHuE1>}rx%@myT|^=E{K8QaZ89J{@mNTAplU(5~$n! z*HdOGE*Ch{HQ@j2tRRU=7H$Ips?SVbNwOA}QqVGMrqx&^@e(|krPYi{}2foiq@wEx-? z@m1O3E|VpNTbnLBuQ3m~1HKS6+DX4!RI@&`+nkrkwUppo)5TLie!=8b6{O(EO|a)*#Gho(*9bezRD0sVt6K+eW2te%mM+!N8P{#GOIBE+fcV$w$g&*oL$M z@Vjb5ni#i>B1BH@vP&h5#4@?h7k37DRli|aTf4`+PTHbh9r)jIz}W{F-+ixwpEI$c zWhSluHD60>>o1^B`3=6TMWEvQ-Z&8yVHWw& zd$U?4R#e7LY0U%Gzhl4|AqZmqau;@P{aCkO#_IR2Tyz(N>lUMjtwErhSF|?{4o-w< zn8i63xHtf`72d<5>ZrL5Sa=cW4gTS7)kn|78{2^L@gFjhl0Ym1hCr@3rvex(8`)U; zn(Qt>EN~`s`Tqm&q2HeFfILr?1eSjt+O&f&nR@z|`TYX`0$RK$NlEa>vkk~noVvn@ z0naq>%C|!He`iD-=RS-HG?r%6|E&{`fPe`U3ROZW8C`;4dbF5>KjVIQ(4}0J_6xp$ zr-Do(N0=UUMqrwT^-m?(%&OI4QU!>S5ejX9h3}$=2_7}4wZp*ovirr~IrR`U4xZa;K<}!zbJ4Ss{k1i+yK;{94Z-wvc zJCgMSbTZ5%<`!H!ow*1@G9_ZCv&7^p?6}DrlP0n1eYMT0xM0DSkSnP?OR;&45FZ^B zm=j$+ojD=*zQhWTBbRwjq&@e$r$9OXOF4nUo(#?lTzr;CSWGO~OksFSMDn-+ zSBt~l>kt96OkkgMZ(GT6)C8R|ARyM?|5Jy!?nNRsb*n3|6aHUU1+;6n#z)X`6+%M7 zNkur@MD^sp19N#sF921*4O+H#YuUgpn`!}iI67&6gg6+u=&EkJ-1Xe)ncyZMTTC8p(T=|k2pb!Fa z*F-7uE)yQ0VtJi2JP0&KuLwk~t-Iz~%#JPrQR2VW^kB>>{7$0RdA!nDlWjS4fnld% z)%I07)E}C9&UbG@KV9^KQuIPHl_BYI4)P-6(F|S8Gp2gRX=;Wm{dH{&`beGB!q&nPMzRo{ z)XYx_796;75;~drsl%b^drn_XXIS(Ml5Lv#$?t~|OM>q>4yd9oeBaX6TZVAURZO4_ zBD1w^%3NrXh#e>G3lV*PHyW@6OmL4lY5~@wp%AY+tT$4j1kvV9sAVa4z@L14A8R}2 zmv1@Quv&0eKxHK~NxAxUxqSh?HAW^_n8>{)hbZ(bg#)g&Z(*6gAk>z0qC0)@j{ zHCbZ-#Q|bUCuDEVw6(Of%3t^cZxPZB1n%Ej?QT6VAO-UO)&d?BUkCX1*$(Z5Y9Hv^ z7@HU*Dw=CZ3fVnvglqWp=Ke=YqruC72)#x~Riy)HrNNkGMNXUhml0i=qDZG-c=~Q2 zq5|yr&b2oe7Yze)XD_DVv7m?Wv4FuWuOY;}#Zak1@&U+fQ(6yop8e-*~8 z(oYKH(qA#B0Bp-#=!4>O#7t9M&7Q#{$IrdG_<=Gdi8gnStg9#JpC zHPnFA*epK?&&BTGQp<Z9K3WPugX|R7M(E{sp?Aihi3*PG5xkHB7s?6+VWZ`wvFm zjI3bucVAMZi#bT3A0leGbbJ3#=LgUGbY??1|AFDrFF)LeP0|!DJ}Z?QZoyt#P!!sv9yIOw%_He=XPr&;1co)o91t$ck17t@>=KxgF zy>3&ji3yamG?N*Yj@d|09;^t92)@> zZ~7mb)kSU9VVV}GIdJJe=#|sc-EN#7Au#_yWX%oaiOH~uI-Z(z#?^p%2N$q;uP5_4 z+YQdJc)-_kj2;aW_#+$ke*S!4`eUxeWx!zO(aD##9a2sI6`I6{;Z0cJg3)vja)@qG+@c2-LFE|LlbfFyHyvL7%nw?Dlq2-DT8kWGV7b# z#gsZE&0BZeJbVabNh{_IRx6WkSQWhbD*=@}cmq~|aPLdmcUn7ZO20%Y(_Ng>9e%)= zRS+Nzp=YRncqU^P&LQ|rB-9emo(O}LB^=jic(#uA-T;RO#r*CQJg%aoEF2)tyAFaE782og?7R8-je*0Lir}7PdNZnL?KVW} z`uf6URLm9BV$x}^k&WJ$4Iqw4jhdaEJu^G|130a}eGHLs?{Bml$Aw-+xL+t zII6*iN?_$BMgOXZUEeS&AE<~2?Sz;|1tastyzg>E+;altce$jb|o6V*w-# zqJum{bwdr@6TWt@Ri;&9&b{ST4YgIdi3;N|^i0>Cq)w^jnXqgH*G&e-!1%Jf`(Ye; zu;PyK(uqmVw~3-wt+Hfol?%iN$;|qZE%Px+SC3(Hr;sulspPMGJJf+PDig?O)rp^- z(~h!Y7LErlKm&U_^&CnvX8TF>a#e^JPo9T07%ANUM=`?}= z8|HjsFJ%&i(2_?TmGP||iB-=iCSLqMEr3d{Gy`3j-K1=}!_S`w69Qug-~y%T|5>Rz zIu;W_$jPdjFtv01JmGhV+dGQiaDp=+$H}7-0xAG34P8H|2?wkr6=vTfD=obVgbCm6 zfK84))=Fx!fCC>Kv|v2uTPgad=^D-L?H&-l+Zu}~q!DY@UE;r5pHrTg7#q`qa(e$1 zfB;}HG2-W=Tv}>J!9NeS#3tQZSN5pgR%b2pn3$T{k#Fm$HV*&w3L-_R(8_1);IalB zbpi|UW5SPLQGUDyumCukWu4O$w6^8G8%W<{B-$L;(h*nVoKViT)i&wi54MDP&cb;m zTBu5Lp!F8m+Nj>*UEmvON>>8p^n3m=3|TpE8Ht>HG&~M9-eGwX^_vogyIp$**<=fO z`xGup{E;cNyQ}t>29Gst`Ly3d;`!7H_WFXi&*v$bqIo-}SJw+(ItsN(Bvw^}Zvx`( zlf>W0%$HM(pQCiGdv~5&Gh!`_PHt#g}FKl*ryBfZhn$6JR#4j?ki%Ch~ zie=cXxL(rmsN%pKwCXve969RFK03*8gsfRn?%2hYJM_^Ej$*|N(GB4YTg>4{($-`$ zMcU{W;*f>tdGpxFal!@+%@p-34Zr2gi*jHrmimHS3*O$(109Z{q1xyzceNA%b=wRE zK4pjcecZpmfq!}z8K6sc#S-UadA{YoO?gB}xF2K+bRdvnm&*Maq0OeX01(P_{S$oZ z&Q0pX*q(kcfbs=iBLi<^oKVf?)acuqidKe@U>HbOLF}iKTeAIxP)jTjv#7^P_chO3 zNYamF67|NjsEWzRu#F0WQ`FJ<;PF%B_*t@zYBusWM9Vk@kSO2Y+ddB;@br4>3>ifq z0w>Ll8+)i=6 z{McAbzQyg2JEvdawN88=b@+R9J{NbkICk=Yk`q+HnB^30pYMZb$m0J(;2Fc2-J<*% zQv<<4143iLT_jyfPV;elJ29p{RV^7Q%X5;S_C&_BLyn(^YTF0f)ralTKJ_;NYaWXw z<@MZr|G~kfwS{_RoTWJ3p@4yhl(}^5H>7W)qysZq=Qo&ww`B(o1=gv z&>U#(R)o#(Tb1vllh#f;Zd;0dSGsgU!kuPcnI=}tCf|JtvE_)yrq_UQo!KH*`f~i1 zb2I_aynwX#rmVj=8%b3)Z`8~{%55t<9kF{)T3Ur-CQIooLSQ*(#8DJ3aGz5@NmS3; z)^Bb8(0-LWta>b?G4-Odc_MrAJEz1|=y_BexpaLF=sQ)C-DgRQXb_d0Y$6pD89^D( z4F3v+nFR60=PUa#=3{&*=2pExEm-9w%&^UL`d2hPxqc9xKV!9FnG{l{K&GURfg{Cv zyD4?F&lIi7Iz_Q#s{EF@#(bw*AIpk_&Feh+!yH;$twu{-8kS2OqV`Gh%tt7@64za; zP@UOyqu^_}oG)e=p2W6XQV2uktTf@e+GVR<96ul7Oq0*RgGcDIOh6z3_94iLZDd718IXN)_ z(%1kTUvnLwhIZ2X?k$A?>=w`HlnJ=PHOQ2Jmnl4;a}s>}@-mYV_crz{{H#fg=mzix z6Amlg>lDhp1O#{>3OE4q*}j5fG^C7cIb>zMTVVAA;H^=^LSK{qECD` zVqPct4_CxC2EJ0tBL7sG!U9D9=Tfjg!Kna&6Z^JR8tSy)XaL8n#%MQYaLmmi?dSrw zJnq^T9QQW^X=eZ6n~AFmH>oMm4L#}TsaAtO(gR_{A)#yV|8_6~OW(`OFocP#9HBDAHWLq?2f!c$5XsBF|0 z_*2y>78r=f&eza>+pQmVF7Na!W>2R6O%UBl1}Nrj*8*}427mzYXn-v?TZ0X3-VXo| z=zR^)r! zDV@|mA6mGaJNNzTQWxpjhFBDyk(6SadNMAX4lEDsIzMfV@tRRgN3rGpm7476ATE6i|UlgTGr$+UI4pt6zMiW1vR~2;r-Yb@}=t5 z>YlGKvS0RwZ@akdc}@ zO~3G3>bk}}V`gBZ#wHqD-W)j)(CNY|cUu_4v6c@H54E?SdYC5KPyvpPXLQ;BY@Nwu zLp?$u8f>4<5Aw$39LJ4j>4cNL{yQkJC|tOIW@Tm`++tV9JBA?t%$2sF!M5eKV3t-( zd;2E1Zlj{2gq71lK@-}$-X&0o>0mg`r{O6dM0**B+U&}SVA zj8V~CCPb}$$X_&$C#@vi!tQ+F}vP*k!;l{WFN?Z|?M4TbmUW{=0Tq!g|K zE>y?a3kB7Ze7tr>!e$W44}bjQ}QLK3RK075f`7B`bd@1HsClOPcW7`!{ng8A$`jfxFUU+p5C`w%Ku)3tT)r z`5!|+E|_o+M}^F2Neh!i7L$uPL7d|NSHa5!o5c*x%-)M$@AqbAW`dLilrhR(S^m-X z)j!@UqQ9F{@`L-*x#{BJ_8m4upWWBN{R^nBe^>3a21BybJ44$cva{qk=iT3OkmX`P#f+A zHVwq=2cDi915-8pUE_Dhw>0||Wn5wL95!TpT-1XGK#3wS&I}Eg94vM9CJnR8_!#yK z_j7=`-UX8x3U#{2bF@D8l7<_KXF;u#!Y5V5{gLZRAsDJ74NFyNa9vV}mju*{>t=Lu4lj8tNNGqcuFd zo_7%Z_@{fRW7GGI7fVF$$0g@RmUU$48lnxX`xc5Efhoi7c6`>mVT% z2{x0OeafhKQxi#36TMQ6-@Lb_CI5o=m5;z=i3KOMFfWK=G|l|Na7)62_IZM?Z6Mxr z*-vHFZeGVej>`KF0EJY72b#t zfoPZ<5Q|!)WkxqY@aAkD1pF{?@p)iZ0Z25ELf>GLa+rOa7y%#_=E(d|^9dT(pc4tg zYVjG6T7Gi6U^~X}+H9nIy}&9FV9im7tJl8zQXnxpgR>O60PX)lr%#WqCQK&_L?CQK z%HA(=TfDl+6-Wm;4GiLuRFICYId0mMZWhKFAye*UapjoanJKcUXT$}gcZnWNtd82f zc~rnKO0b4n;p^6(GE?J~uIG~5oK5<}8}fr~-R8%xZ4P1|8fJebkoN13KXJe{t7(h#b-{6q-AH-677qWKB8+ruP96(9}B;`(A zB5t#6jf?iTjhC3;Yf9Eq@E5Hsl?|_iPBaDw2QxD>1=2Mf35Pem*NED-HC=$T?oBol zm?4?N%%$ibDv^YC|LlE=j3EUX9vhdJwB|8S*7(Lc?^>fv*%mzel7Gyg-4gm`GDwk2dhO|BC>x37*MpAMKlckX}vye zoT<%EJZEg{Z|s#=x;qMJpte&@g+&4X@xDzg5ghMND!!4sC&cy)F#HO3ol5pVuO~}D zg8+akhiKQtuugqi`)ijF!(J}YQ%3^>k!Gi-+tK`OoF6%)@U!A~N>!hyJWV;yRIth2 z$%$PMs;bZVasqKNBbo`C+j5_eJc9Oz`DbsVEV~*V0&+k&fcEjph5LS3>*-DIa~(5= z%_6(Wk^=nLFqJFSz8a|QozieQC%;L;eIog~pLj1jiS{aIsdWuM)ymDzjo{{U4soyR z;^mk;ug4I2PWE|ZYtD_dDs(pMqwzlEPhs3%+>|}hA>MsQ{_ZsA4JNqYK3>SJVT0-j z6#@%RkN724JhN5(ns2x^nrC!g3Mor1Q)}JEDZ{FI#H?g96OHdRJ^ir-j29n5XL3Y> z7BMa|Skv!nNmb-wT)*qsdoi#AlK`aC1UKcbO~;}adVm8Saii|{b$?gUz2{Qezb^84 z2L@du_i<#u{^l(DbKJ_4I>a_>?x7eK3QVCPw5GS+_ZFbfL$N^9|j2WxKhh%@}XKKBA?9`8f`DtzZCrpK#>3maOzJZ3Z;B60{wz)Y2ftmmQB0N z)t!W>BVfT_Ae|i@Y?CxJlRyD~TV$IH{5!}-GlW0cj|4ZU9NSF`#DZ29M8{T1Oe zSv*%F0~c8Y&7E9bYY$5GDp|7jRhghzFP?I2&oQ5^M=>((8Kv4U74Sf@G{JC*O%62S zjzG5C|MfjJ87whh%*JbX6}<<={0OAR3a*-xReaTqo;lE?+9;QS>~rTBghf8*Tu2Dp zu{tsBUJ>xqsJZnNS$)U;j6h@HGvpBJg}>;>sz3@E2oM>i`Z+zFe{g3NU;}NXiz)R> zgGPa6B|g44{Oc8!S4pkqUk`PdfoU)-f}dqB%kG4q=fA%F8y=)TN4#9Vuz!VW z*w3@qi=xV=kID7>ev^Kem4Ak}gw|C^82?2viQtw=QD@H2_%ms;Qy2k(-0Rc#$D+cZE`EUlJ_#(HVcwq-+8UedEW^|k} ze08c9`QwFzx06`^9h`{CJBhNu`gA+Uwo)7Di{7C@>|-2Qwt#T}z+*en*-Y;kPVpD` z7#Mk&N;Q85nyi}7HLGVs|Njcg!8(1i3O7nUKmN2aL{3Me+~QKS9>VzU$vVvdq)v>G zcW0$~3+j9<>8Yjf*tuio@^l{_G26F%iqm5P?P;waPO{Cb@b(_7G(C5RtHJcnp50~rm`;?dzdN%T~2N&Ukz=%pj@dX zFDESK`>JghRH0clE$tNQR3AlaU{Imj>f+PXBpdjae_B8{nWzU%Jj>DG$g*4EgnNQU zKm_2<8z4p<=>5<2rRGG}Hehpa?okf~hZFzag*M3Y)f3xs>gweey{1|Z(!u{qroh?f z8;jy*`)9RouW9J;(PZW>VJt%>*HG~gT>bBX*Pk2=68!IEn>Hgg(SPthSI6Z3#EaqY zqQH6+6pyv8T8P{@lbJpxxjrfSsZMrJ6d9cQW8UomtTO*Ggr{QFA+>gbHMe5GLlk86 zlG3)2b1aaB4X(mB(%XyZk5Iss&qjh!DT%DuWDg1ju$Sf|O%y)iP`Ip?{jp52{Ky0? z{@O5OKZtE$u-KFN*^qw5`sYEd9mNLpb?CEC7;6+9tY00B_|%VJOJ_V8mvRQ2Nu)_d z%%exiNmsplGfjH#|H=j2?v=-VL#3@mKLL^y5VRHw#(8*UK2f>=7bIxUcN?6WqV_Mo z-HXZWx9kRT%9E3n{}cr!fH`iL#a5=|}K_a~S{7 zVlCq`o8sc)a$B}x{_viV4HI`67!?uU=H07uiiXUX+u@oc_CLaeK?v{aS<8DRNW>fZ zHp+d(AeoIu@WAtdHC`Whc3<(IYc~Z=+|R&zez^L4AiZ$;Jog{2H&PB&mZ@CV?S+p^Dw{=z+F*~e{=%RUmtwpd zThBH}4Y50n0eF%QLMOG@>S0W-vL1d8HJ$=vcwZtZr|{R3KR%HiIL}od!^jw?v8!hK zcRcg1A(uWJcl;Rk9FBZ;J_IO7%N7R_D44A^ z3~Vz18!{=DO5waR8{y=a?%eMI%Z{?>4tl@o$J#4ydRXyvw;OVyL}XmNA2UKRWIiLG zgC`0ilkRYdjn_JC@%ENS0{99!HQJq}SDP9ZTQz_C=(Us5UAFADaEct3& z&P1yD)#^IhqV8+|@@R2^k3?32P5LWum;k-rvNvJk%1<+8U-uGP%LE2+8jhn}7~Vi{ zUUANv6oe9D+v^XN3vy-YFWgUwq5}4zz0utge>2q2s`mJ*oh9;>n7;C0;Q97|eH%)!Z7@JXp^uzU?9V31|27%luIzdwuO zr7Jp!`sGiF)(g>P_xW8}MBJw^m6{NXBvDg6h%P)-7wi&kYI&p^O(>OA@|AVAL+&Es zxnilb)cVF&P*9M$jcV9Isr0x&kS-&xbnt+R1JQRBb6nh^mKI4z@pmyZLxeXT+izPp za4zbpUZ+~~pwy#Lr? z0)({uenm@utRiHeK zhGX72jL&g(8QJ1ts)oec84ax)S1p7IQ@Up*H~6z|m-|HxD!# zlX}J}DNLwey-g9E-ZW8EpzGDlu*VM6MEJFF`og8nDgO{zOhDOe3zpCzQ~4EbAU7cW z%@l=%7CeDf;=Tl$HcdF`FfDN6@)s!maYBgf414q_Rr zkZTZlT+35XM$d4`X;AmNHNULa^Z!v!m+arleu4G~*f(7L{ZT(U`J+tQM+qkvA|tjQ<+>PF(5j!jMF0Yc9u!(WEsGdQ|?96>N@S z{6(q^^B+d*ARg9Fqzy*-wFHqUB|rx$1}7xgWC-q@rl0zZNz##X7yIRrnW&9UXuYj# zdON0$r#pM;ePpi$$z{j(pDftFu%0wOZzsD0Yj5{$dh~2c{kyIv9rt!@oYoybA!*c? z*^K(#@4P96t*rdKceE6`d4l>L0(sWGXIZ~uIv4|QWIz3g@WbT&_*>@QKgI7_Bhqh4 zt`anMQ>`sgmS$AxKZP_8Z)v6S$SM6wq^)3!G(R-(t#PCN*=EC`ak@E}bA0@gcF;jH z02aW{l`MHzVc!-sCyMS}|` z5`l2HYaImav-%iiMMGoE=h4lh@ia8T8;NeYIt8gxhcm;&pPeorDu5w&AVb^aTIyK* ze>ZWl`K;E9^e#s?9h0}RPTbZt$NNOVNeN=Hyfc3r%%w0=M+XHrX_iH+CH%}B)#AM* z=-~2BY!!eT13p`T_+AMGFTN7^(EyCA2M?4B;hEVQbUy6g=K2rNalXGNd9 zjDKtH=Pp9!_r8hpY4?JNT?J>uWSC4-xVGyBo$%THk-K&cjTo>iG|&Ij0<`l7Ehk6& z=@z#h5L-}up$(-FCY|=cTZ&1H3&vofCJL7_`f^Hy&k4h#B3Xi*)%vf zHj^ZUTlzBlh*f|H>lr2UFUtH+-XgvH>V@+$3$Xb{yH2M!lOOjLGel&y&E@bIv0D`c zk`kV-so-ET<7T`2RdpM+ik@+@cvDv(I0U!l3ap4Qz5nIPCDADa%Io0Qmwh)Od9G^M z^W{a7UI9yxT$oI)Zy0SRQxrkocEi-kSJh@ssbu5&&#AVSoz|)T(9hNg?G0Iqk9js4 zG{$HoIP#YfYX}+ad1{JP!PuMfXpY`UQAhp6`ep0V4$*=iec)D21zhHBY&rLv&IfD( zuXxBs*0&Et1jcVPt(=}W!Alls;#pQ6g-TR&1x&VA?G1d3*D6`#x}GPp9g~DfEsgKP zKPcOp34h);RkN|rxYe_Oe)oT^;IvS~7_gcS&&@r$MchEl3Ah~T+%5W}U)dOUoTpvT ztC3XYP5qtn@3?FBYU^hUKF;Lli=1y_2TA|7TShQYC_j;Kj1q$PgOvB4&m;wOYJ&*O zg&#Y|0AdE_RkVMEgx95-w>midp1_=#d>H=6?3FKf>|d~`_5iI+B=a}?)0DBZ)=Ct$ zofN$r1frT^V^<+ABh%<92OQyt-eaJ`kS8wh*NqeByX`s1{^33>OiHNbG2(k;xK~Ce zCBGV|b`j?p&QiVRq5|@t^+r6&G8jj( zP1$tb#o^e(i`zU5nQhnd_rBiBO08q#$0dE1mb*jS4pZi@ zl5e>?WW`v|HYHrch3AgKNArh^Bwk{MLwH%aa7%mR1tW*1lORo_weTW*#d`bKLi;%Q zMQMhQj<+~Rc^-4&=a(^$xn0&ibM&1E_kLa1<&UJm9-q`tu>Y20ggYS>cN0&_#H!C! znmv>Tu^%`NP5WuAD*aD(wgAtB<>y^HrZfkorYQn^CDW8otr(_>>ixA7#`AX{@>}!V z700T1F+>Yfcx+2$DWy!dxO50(@3nmx(bH^SM^nJzlVW|Pc#6D`0Yh{&Gi@vN3sN@c zF{{8$3(Uvq8s)Ne_S4ZDX+VF(O1SnA_3w(|<{u6yoq*gmD?H9~8Ofr$Mp#VD@bQTS zCCT7}r!tyt&vc{rJN>S6P17PO>G+FhXa>^)+0zaS;3#K0Sq(j3!-p`)DloSK_h?;q zseJ}>ST(vApvRzAL;`>V3~y%ugM_-qy&|F(UP^dZ_H^qf<7b0~_2O;UH|uzf~q!&{*9x9B_MVi~AAO zC;EU@)F|M{#=DVsrkmh(%A4)U8|&%O(KKm~K5oQm`{KK{Y)JX>Wx^m&Wi(43-Zfmq zqwe23^|3f5-Ixt>k+*x4MN_{&250bwsoO>(kYT0U^L< zAcisP+=%j3#EmyY`-;nJPk!&8eYDAdhY4`rX-!=-zpi{36$5?ia}ot&++dwZ6V4Z= zqVy{$-$lnA&d*;W{17A>A9%4x&>S0SFgUCF41%5Dt6$DdPP-RM(|WPCA?Fh;;Wa_y zPVKx|TTzAEtlrIy?997kZjYVvG6OTdJBW-^Z&{Wv$>vsF1C)m2Dz))Us-({unFnay za)k+}UX$vVjbz3(unFH2oy4n)=1~2FaO>G56`j-_D1ST7-Ee*Sy8Ph{r^+?Gx0-8_ za3Dv2DNlM5>+n+wr`UCjrrjNmCv{05-m4#4Xnbv@lVI3i3 zX*K`Cmv;8#@d6V1(a8SA>z^$5-WuocAxq)=rJH}d-5kwiQjua>ji`;x!G@D2=}6|* z6=&XQnfb4XG>)R}@MHl3hwi)H_2yb)^dk2Fz%uRJw9|}LAzbk?3aH$h;HM_Mn7}I2 zD($jtayPvaNtYR4XfbgP^30_1Or+#8PwN9E3fIx0zd0AC$E@tNyVrm!t(~Sr=kh#FQgeNwpsKvx+^3cot$g9+F4X0!@FJt& z*T4SB4a1@>qb5RZNlw{@DT^#@3(9%dm&{|Ggh0UmpOmm@X6wDHtFD&{&^G;-M1njz zs&x+cR%0)t!-12}gC$rBI{AP#PjT1q1%(Qeg*LI+R}^~)i1H(rI;2^Wg2SsMzaJZI zl`3QnPn2oVB?AFwIH8zXTF7p(S^OjP87#ZW#`xu=qHjAr%CpUL_!WC**{%DyHiyuWWwLHlwi7ghZKiL}`nsvkvW));%&byj6c?wS2 z*7=yuRbBxZ6KbRJ|z+$9PqX)84yL6Shj z**G~VN0D6<9EiZcF9miLV23E1I1|!L*I+w7hxvE3n-Q&@g5JxByRXTu)IV0`8AP5K z+k#!QrdhnJDH%wsk~TlI9OFQ8PckZI3|t{fE21;+#Ia zWW9vryes|yrC1#C2q@0KY!jbo>Zi`9D|%nAz#Tq~AFe-zoPcY3gno8Bz^2uI)2$K6_Hd{RW(oJX}R{OV&?T4%_}qYJTdFR@{#0Kavy z!pc!W+%yk~v4T%8c1G4aO_Kcoj)~mUCrg{N*1~LgVyz_q#fA)`^`*FenoM-^TlrbO zoDJ2xnxKBH*qT2VdV>up(w|~u$(GpBIsP2{UO_H<4#=>1jDg${QX93g?G-@|was|$ zR0aF!vPJ_+zr-0qypCa=7fur~8|Eg`8vE1_J#?$$*Ur9KP<$16Y^7yd`ol5Vg~D3t zJ%p}&N`^WHj0I#Nv% zGUu-gWW`Pw=+5i&sPA_59*28VyT^#*$*+GKLL(V*-_rtwbjMT7lX#JK7v4WNF0$X2 zc?5;iWmH`2m7Kq_sB?1~o#%+$UTEcrlyDnC!{~Tp$m}R+t6HVl;eV<3H^tV-AN*7M z?n$P*^|OsH`@^9cg-sbQ#-QuLYt29JS}O;y=Zhly-%e^a-hrPw&59P~G?55mxCx+gL~ zT-8bl3+Gsq%GOu1y()9$Qxm38LiN0Ff^Px=-*-Fr|5hJ3IzX#2rxja5-qHjP!x7F8tJN?=338;ohDRJnf2*(f&TuQRSQ5> zJ&@LF_XmL6P$=}RO%{I0LF1)bPyVBz4Y7bP95>5^m?e7z=Hl*Gd1uWfe+bO!(5eZu ze4C889HX@p^Mt+eo^2pFHiZ1`qC&lBa=~eR^JOp-t@)*6#o6lVa+5gHsqwtS z_~@c`E3;|;4eek!r)|@#wZ%9^f$s@nn(trGWyXkg*nLNNlJ-#W?xlIP6$Rb7#;Y!G;P9 z1Xx~MlO1{qd@%uTZBD$1H@#m2-tCG{mzVE?jT-_p9jgn0?Y!(IfIs=!y^~AUOh58K z;QwRnEr6nK-?m{T1OY*iQc|Qr5TsK;L{jPQln&{VP$UGU8-$ydW?AVFSUMz@Mp$8m zWu+vSc(3&z@AEw~-+bT9J>%Rnj>`4Bt}~AFIFIA^WF>Uvoyv1P*Ejn{ocuwD2q~e- z#k#TJc(jnH<@38Il(`C^x@Q|(S5lW@SqaL|4c}_|xe^*dy zvH^0o=#dMM1f4oMW|4O~TpPJj6~dopUhA(k zp;NrfDi;skJ``l0_*D#fi4{jYV&gU~NPYa=8gx0yr7FpAa$JUS-DaP`Kz24xYm=nU z&YN#>ULP*?Jbxpd{F23-PEIb!L76MfJ^aHNB`@!?rL1HZG+c_7a<8o;(+W6QbD z%YShJ3Rh(N*y^}O@CZyw(f(Rdx%26OjeIp67&J}cTY$2mLmI52`1%5W$fY5<;L^#^ zwE7h*c!`UCdhk)pjtI>CPu|e^7jWH>iKep9r4?toQ@f*}T;$=|l~>)*5-|k1Uys^c2+h!9Pifng)IEX1SvsQQh^e~ zfy(t}il}iU$Dk9zIz)5z8rAErJ^zt^-7q)XlZl*-CDlRH^r8*zytA|xcd2-~VPhXp+6(K%4e6X7CUY_8D%bhZo2N^6*X7_AMh6QYSb)aRU zwpXa9Su5!MO(|2fL$s6mW43laD$5z_@g3Mpj8rOwtYXxH^P*9L`Y}`K+{c%1d!P8c z>M()8$5IL+%Y#EH<#O-L{l0Gh((j+JRDnNnpNl9r*+`ohA1GIRMMPou1Zx7-FQ^&PfE6#}qZUUtcn9{aIPxhNASI zpp#dG`4{Y$khAfZUY`4+IR{4&?ii~PT4;u}Tf#*Xh+$5it)FaFaD}-#GxpeGgyXn$c}16o=kAvXdW7r`U{Dnm)&<9QqJGv5|HX_WUr2@F@WD~rXGKOy)# z#hju3{)YCU-3jsrE%`Te`3{>4&(Kyhk>5)D>;qhaP|cvWPjH34sF?2aFiEr-cpWhI zTEb3d%)e}xpFY9PKGvt@A|Ldkw3v99HFkRqD8Vkd9(NthFr0wzwzqP1u>#TuoI%Pa zgoiNPJ-78Ag-$L>T+Sk_y9T&vw*M9pbM>8uxIjoLU>-}|?c(i=jU5Wvmn}23nJA

>ri;Yv(zq#;k-AGr6!_irl+8?-+ft(&&}nYde>1xfh?-#Yv>=pqXCNg>~acm;dhHM zdy0D-r<+AHJ(@jV;MU7%K{u!&URMRtJ~f29id!n->$H3t+cU0nq23X}Y@tfLGbqJI z**sh_fif&dy6=hMlTQ&`H4ont7p1R0(qUvuQSb^dht%-@%7_~h^iTF|O2@xoxN(->F`O!tDlk`m{&R2>&j}t{^$h{-7hxxX;>o9scf~ct;0txN! z%B53bidKwXMX$S9(0JE#Y!4YJJzLT?hHV-BhPy7ax4kjej*6%1nx1J945h{t!pBaJ zjj(Uxa^(sWie0`Fi_Z(vkPX}bI<*W_XYC!rk|E~sCeuFPKO%&_FcJX69s$UPZTut&a1V3*4VpW21 zjlPa&{9qw6e+Fc7FN68-ELmGNu;0P~Yyx_`pKnIJ&h;-Db^Cs#u!U&;_(Ff#gi35Q z;w%~D*H;W1trJxi(AOzwZD|g&Pm~&@?blXoj^wS(K6nylRZRbG-nKwWaNXjicS``l zuk>)$B!S2HszOa#KfaDP^_X0QWsqvdMq?2lW)ZtrfRXgKBXsJm62Td?<2RbXKpZ5Z zGre#mnSk=XH;JZK*aROtKo?Sn*7=WHP8l5}5InWgEHM%QGV6Y1bn}2TUOW1r3WX4J zmCj8-;MdQkOF@adwEXsFgcMH!`5$6sXTTq?t1{sV1ulW-fZ|JXBO>5K=jag7U9X>0 z+ZYK4^>KwoOC6|)=g~*=e*0%<&1U+!W5^zl^M9TP^-G+}pu(fRG|Bn~yXPSmr!ze3 zAB^%X&ri6)SVVpg-h(!xkIP_-kdcj}7cNdCW-46WkA6;;yukW+gKiJ}&(>D?XeLtv z%)2%+2TA`;+>PO&vBtm2#M9fm7woNo0ShzX$@%Hyf03#HwhZKSKxt-GdmGybS~B_A zRx@o`tRVL?V*|!U%vRQuSJo|#rK(3ixh;zh34*l;tkD*jpGXGi#qKsbRK9{30j9M? z&gjhciK$Ti>+Mr|yz81R-vl2H5HdRyO1-^<@30hAaQNf01rKeSQX8eyJ+E3sDHf9A z@%s%I5sA2MhHldwL8I7;=)$=;+WNRMP8uY|69L6UEgO7WJ*(F@3v+(h)R&;7nSXJRC8E|ZC-zk|<|SGn+U zr4&`k>7D>cu#bPxr+)P|q~N1IQI;>8>I!cy@~;jad(P8m&5!mT=@6C3qx^wOew+5- zQgA(%q}Z2J_NjWiLaL6de~|@S2hHGvNjZkQmUlLUZ$wcn1#zU{z;OAm!6WQ*Il`I0 zNRD8zLhb}7nm@tdZ;J&E@8r8DlcIh>+4vQ##>3}gyBGG8AGc3C-od+{O9SR~@dt%G zDX0K%$-v6c*U<914FXnW`BXNR!My7W62=CZil-usV2}hhK4Cb%eyP9s4w<~;0v@r6u4F%>*zKs_0-!FlOR2|lV` z#amP}K-TR?VmU!hZrONAfT_(!r6MI}eQP%@WWA4?k^TS!7~eU@!u2RDfzieXd^DK4Ni}nwa+5ykXDKi40pbAS zcH>M&;}6nCfJ^kLcaY96t2OcU*H3fl`3Cd27fk%!RL@~?+N2#e%%_@@(qbSJIP^KXkq&6e?=--6x zH;oKxU)LH;6+d!X1M-iTmCen~R#J=|0a2xCyNomIA=FA&wK?Y_XhyF;`uG(Zm0dz_ z-Lvpl&^`b;1}|?Ke*otBC+$%0`{{qU0Ja0KCDy?Nk$uby4D$d6F48eqpkf$Ij<;GW z1#4Pv-4WsN^~z$8l9)|c|5raUW-XG3;i`v2Z5Lhm=G$09*X^y-9xv5_{j1hRNS@1f zd8xCW);y8&f{Xx(f>EX3QsP$G*gl`;a&B5yN)#VyrijLBQjcn)ze?i0?^1=%Huso} z?l%oZx9@Zk>9D;#WotIcr-<_ONXUretnckYwuy}%KY2B-`}-s?NmW$Q-#=}PrZ-Ts zg|REWJS8~QYQOcYO6wX?p-_=gFBNB}4r9Q|&jz({H$h5E2pz1eAs~HOn0>1tx3nFg z3a_@M?hn-kSoX(LiGY_s@R@3h>8cDv9=aQ6tSz+{0vU=Pv_XTa^?!|4m_khf(DjPTmoG zMKpHs3NrsxGwP9Z5>UD1W5`|(50*4`_7SXLx%nrP`3k!kA9TuMxQ{KA2Ed-yfDKrK zgwQUS+yR$A=wuhToL}Ev+x~5yar{VQVf~kEV^T-clJ>&asv!U?fZsDy1_UpFJdj^5 zAO@FO(|~3XEazeA!pU$xr4ED`Swk5XBFhJL;co2iJ<=l>7+(P{2UubAULw%gQAY+G z)G~S17z54TFqfEI?9j4E&wu_*3IXrio3xSXXoVjVL4PQsBlh zPyD=0*^>2eJFJ<|&Rk%Ty2yFqcdZ&D0*^9`#g}++U3&9^0ern zgn7lcxUVrpcV0Y-HCB^|(4uZJ!!P0%Sa!2CsixRmAurPE=^UoDIw{NEmrZ(PZd(xn z%3&yN1h=P7YC#Nrz1F&Fk#dUC7hJ)0&4SX_q#N*`e(b#hy$Q$K*Nxg1NU6fzHD(J| z0EHef{(+eq)h)?*1)#G9Y%Rp%6LM>tTozqnN{X8Kkg67DVYf6=1GjHv_N@^hXW0ck z7L_3}=J5@DDY;g8#|#w}f8wHZK<1{t{bDk*p#QY#*~6U()0~IAM~{tD*XQSzH7P-9 ziyeXh-4|?aB9avivI#&`@Fah?wX{^+k}*OxN4U_w16q!7R19Eb<&^fxwU zEx5LfY^fPJ&7(!G0M>T`4aJCp8bt2)k7hnFw(yxWzUaHhU%@hSJ^|SOTE^ZH!jl zde;xu9i*90tv&TqvfTGAkx>eQL9tvam77_2`sxWl25B3(G>iXfoZ-QDT~99gqzdxy z>a2%hBJ1DARCy_PeAFDs@Bt7$?pa}>y|XJFl+OBjVx*8d6GMdx!53&3C@1qF6w8Gv zgyyD=MlRvZJqO$ZA?8ZwK04ARWZ^33=Dc>GsPxqnz0|I$sDG>IWD3P=jO~4yLGtgC z9+0ZRr}JPY!p6mK@qsk4_)sYH&;U+d*j%LwT`1xmYNnm0eSq4P6+l|dF7yV;aEy6@ zaVRL;z*qr1HuWOx`y)+cy&rE4{!l<#nedq5lkVCg%tZnZ3tup`9Yv1io&N1UUV!e_ z&nXvSA^T5vzo)|ycywd~7H%_2FVl1b=ULItga%ffGIB;N?|@e{-sp=jg}MHA657I}O=_FQc~>f{gI zbazXMccLjzZal3}1%<>Ne7`3{w9S3v`10k)sPmGKw+87`wf|iB4zKTwx8UHYP-b|( zhbR?ibL%f(qorKms@^lL1gKXzDU}>ucJ z8qQoQ8P@ic5Q;G1>36f!UMTnlcE5=5L~`~MkNvr~*G#5W+9#Xx7toWgzIzw9#}00W z*ZB15qqnjcy3F*XioB=2`A8mwGuzac%4IKtTrR zM-(i%PNIGGfJ68Q=IRovEMdDdWo}GYpl$?6Xt%LfX~e}#5D`5{2h5=K zJP{Z6BW71~APmBXvw4R+(Ln)mUIQ9{?`Y;qG*;qX?B-hULVh%Lcgx5rrhr*}GJ-hR zEPUTH*{DE`uHM9IgIKMxG_QlXl|!X;9$w97`wAmf>-miE+?C`CPD`z__hBnIP?Q$e z|AyiIlPCO|l)r>eO#$loPM=+j-M9t6sFV0no73<#Q>oCqO@^OZMl6J5U3ShPfYA)( zF#wFRTUf7MGFkQ*iKa)f9WY8J(39MFEs;ZzQ@Aa5w^Z@e1z|yMXP#Hi;16I$W8(d# z-}u19ldVR0iV5A`3R3~h0IP$S46xWPaKc+FU%M=xq}l>~^ zRNd9*)+K1zy)RpZtLD(L1wSq?FBK7d6%~eE=HN-p{t&K%=XnNz9$a>+X?YQTe-4#u zZC7&@H-~Z?sNy|D+LT6F_5<0EQ>5(G0QiY3^@zs~whsDo6GXgh>5z#z;5i7?VvVIqhSSMfr{@?oX9Z+=^8?z@U_3-AgLzc6wYV%Xv9p|$?+H-~z zf)>{@!rH!iXYi@)6t>R|I0*2l>5%oYEt3^hXq$HYD`N^MQJ^^k9nse+VPe$1!gT1oUqt425Hj({VQcNX1$!yJ=qY_bX+0gl|BHZ-(=OWuCcvN_+ZJ)~) z_ZgUliU(6eU&!lz`fR5#wUoDeYW`Bkx?Y~kPK+c4rnEkO{!EuvN_+hA-85T`a$>u| z`$}Qof1K*l1;Po6{-IaCovZxVc-gLLp~>X2{;mN0%&W#_uVsnPl2#`Dju31D7NBMs z>g?0H6U9R=Wnv41dYHN$UfOWtEAAy5pKbE`w~X+?AOdWPpRCnxmQJ7UE@lU;zQi8$ zGwqL8STMak$Wn}ca6S%nJMPp51pCe+)_}$e0uNm)Se{>UJ=mP&0Gf5Fvjqd& zR(8NHsfX!t*c)Gmqh_ju?eO7^pD2*Z1#(a$sNSwiPqS}L?dV2R!>zHAmtgjCxd*<( zQ_Vn5&M#*GuN{79dDW1KTSI$z-Mi_LT~eqv9`5{nsB&@!f$8rYKFLw-`v41d$3E zb)2}VMoA0H{qY25*Q$=&i74?_)oNptJm`~(UzrBEz*fhiSprEU`EPx@y>bk%TSFVP z%oR`AX}d9^s@C*Yo6g;f^sRy-QF;vhYktb9MLo4H`qeYP?cW}a_?sNm`M0?QUl~*c z1}?jd|MJ} zYX`1g*M#|uT1WF2bx+v5bebbszKJn5ePp!_!R}wR0+fmxnR=&X{<&4zn^dwJ{-~YUnbASh4cXati3G+`j+F0*E?MZ` zDc`?VMF@aZZUa7hAQ7_WCzo2Z-=6m#6u^z2Y_VI_Sf3h@m+k5^YzDB|!Cpy|5~P8k zm1=bxpUT#0N9>B2XA`TscCr@#=r8I>YYU{pkqHn9spC~njMONp-^hmM!~+a*$raAt z4QM#Wr_P5mhTi06!vYN3uu(H;r535jH6g{97|S}oBcxrm>|yIR8Y3~=+Y}-eB{plm zW|B})%J^E!Cl4tG&w_OfRFM)yfwDIChVxr}dVLL|H(=^|b-8o34?a?!_r{>i@BNK+ zYiO*(g+5~V@j^;@cESAHb=t>mUH@p4ufJ`3^yCI_3X3VEFu*r_hyRT=34`@lp?9Ra zt_s|7Wkz%MTu-EACKpzg8Fop<&l5+D^-^&z$~<=6|>6~24V*=zI)>n91CCXg-8PrcCDfb)3LZtg2G4;?pr z>c84cKhzbnz3tsHCZrD5_Xs41L>aaLASxq1)pcotZ2rJr^H5DB_DL?vBy_8F!Mj62 zaLQ#uwPKou5a&mf({k>@Uo@`UStM}RFT92ZnLAfSnJ>qsmSG+9k0aGX!ayzgrFJv1 z7xc_Hd~x>$Z(O)8KW`%{z(6zaai3c0H$X{D0LQ&Tvr)tkPD0h*IQ zZi0u&D|3EArA~>r;8|*PtW+EO%=;??(Ko;`2jf|O3mN-M2c*DEttFDy=knH+;#R^) zL`;E&L=M>F209~Je=dl04xot&W=56X=$g=BF7wK_&UqzzJCFePV2DWKM^>=uMlE-F zYql|Umsam1h&6{2Nn%9!V20(@TV)Ppk3n0A5{RAl_=}LwD1HVe;c?^)iefyC;z;xg z2upw_g(vqCc4_2%eO(42Ouil}pNlYYTRx@)(1}g;g7wG&FqazklM3;;(PC506y-H) z7Fy-Cw5-qN{gJkv$2eHO_)L3RA6)kZJ^36Bdo-jjqFhM5sIq9+Gxe}nJHM{;Lbq~sMN(yI2O|8~aiH_N;| z1DW&B2bQRQ(Hn7G`ie_Mg!^t!4jwnDrbFX-xH7^0yS;p8<`v0pMIgdTHg@1xXbY%h zU`pg_8~RJk;I>AzbRJqvjjPw<5pxVn5Fm83$b_7KE%u-HpVl@!U>UrMq~F4#6+{57 zsDnRTvykN>q-=xJ z@xf7x()D?ryQm$ba1l1{F=kV}y9dR(rXN^z8C9u1a?@DneZFo>GOxoDauLss?O0)Z zJzUt!HA?g4$1<-J)GG&QK7&PA5D-`0{l+g%|FTG45e~jff#uov#%V3sT$zX2{0y* zF%l4W1OMLxAYTHWG4BviHZ>i}1hTTgG=c)}I>>2YfNOh687d#2(RNAMjx8rZ z*85t8d2(&>b(JU+279k;tKF8_Q+gM~?LmQe2Ci8Lw(j0(L>+llxh)^f6F(k-Lr?E5 zAbAXvx;0;xJANypWPibI{G<`@pbwDI^G%cQ=olXNF_VVK86fQ`HbRNiqE*sL*Gaz9 z7VuqTi%}ErnSY>7`mAi4&i-X`MMs}x+5ccpgitNrUkMA}WpPe6q6gb{Ml`je_3Or! zGlg#lUx1~3pbh7~bZE;U8Jd8gwH_`+qtNsUM6UR&Lfctf{Qm;V#@+}kV}sYb`|UgM zGx>_?@)o|8r6uVmQhq{YXXBUCmC!5D9|1cSEDO=_0I~NqUd)UyjqDEt`TC3g+B&%J zDmKqgXWa1Fz0^69a2F(K5rdD#dihovgCZb=Z}dpibc`mKjO-z(c&EPr)SX(_Eqa5Rrtc_&Ci(7{ZIRR14LBqPWFkDktSy%V6o zbIGf-kNc&X01Jzf%-kgb1Bw~0~yEigwv=yiLY;MbAT6YDk1f%`6T_%63Yr=e-P zvD(d7;W73p@7wRC(K74D=x})!Z58u%}JeD;cNI>UX;P(XbL z^dzfqXRZFMx<7AO0>*Un)2@=^bF^ZTQT}C5ma}2A;t1=4;Ch!fEV_9%dzj?%i9$W< z+(z&dFP4zLYHB@_H{ww&oDZb-|AoOR{_`&k&O*oU@ex3^s-s_^Z z9v&)^i3Y4GepCT7CZGgdYsu%m1-n+sI6|Bs1lWp)x%JPC3;zsu?Z`EE@+u)$f6zoe z?%a*{f-}kC%8U!%Nbo&hj4LC`j0rk4)&1}R?3VqTP;y|bX1S{-H)dm!DqhBy&J{(k z8%!1uGTpa)Sn>6fsJ~VC?tuk^Jix9%-`_0Ok@0W^v}DJa!|W@zgWZjQ$fYZ5FDYX` zCz`i5tJ=3UzBS6XwSJmLv5Z%d z^-AerO65JO3GC|w?MH{Vl>uf*f5s(O8n~C7CM*SC?j_1vIq^1!?w2{knEkNDGgjIt0Faq2HU3!x5Sw=}!nF7Wip7;V54!hdvjRs!Yz)3tls zC*bs|iIYHvo>qFUYyK~agb}31S85l>y-k-qg_)4QOCk~gc0lD8$cafPERQaMVG|JA zIJElN9{bTpy+HiRd32#+#<;#Bt9MdxlqM418#3byspO9d2hAOp&j;)kfu0or5Xsp= z3XAmpz(58f5J+ba2hB}PzCdcB?2^{Q6B5sFy209W21JF8i>AKya@2cZBC_-|UutS4 z_mVyMwXu27LlLD#1oL)ZEV1tSmhagSdiEz8tT)}pn?BK~FyiM^SJt!ns#84Qc@x0) z0H{s1XMN?FTX6n)4)lZxn-(j5Anj!(aF8BBkuR~&wYTY#aW++%i}c=VS~qR~V>N2) zIyUwfqu;vtTX|HNHDmBoI(b$ykBhlz`um6}wMI8`%@_a||&5?_6$3 zKfxDwz>!wD0h#>*&iUqz^#9dNye_|kEexc6q*@JlL8_}1u4g6$)zV4(n8hOlx+Kyl zg^8|Zam;IW0!L|;O^)WElp7Ic8=|9qiv$X<2Ag@l0kAe6p)$ltSK;Z{QcA{?GivC~ zA1dE^EJYS^U-`~=-d?hxhC&Z%s7&gY{&MT@rwQU2h_!&<07$*hzu`r{{X%-q<*%zk z$;u9*`8V!;_s4;4r?arvH48I)Sp{q0)J5Iy5MUHER!yMvTNX6PW-<5*?#Mxdf7Sef ztwc_p3Ez4!Wqi2Rp>&1b%2IZ$`zvnp_8Rn`F+^$P@!RVZ7N03^?hJWf@T}qHy}7a` z5$$`Vv$YhxueS3ttH}=Rvm@(2M5ryWEQIhQLNlI{wj;v zYNW0ZcFiHYu^3Atcjgwh#=4SOyIyVtAG=yRQAma+v;zd^Z-_tCDT|pag$lTkL}Wl zcdi#v0&#c6iFx~hK0B-?G1v+{t-2E*DgTNFeUd!C9(2#DVvuUfkH_~{6Mfol?xQEy ze^#h|5+9{gpKff&jqJ-`4Td5K-zw~fnKX^a(W!%sP6-L-9r&M zX%XuNRvee=pwU!6kq7>5qnxCFla&3pcv+fQMHe4X_W9-N`?>=|j~)+D_Aj?YB)_b! zc14MS9W)*5gx*%cHL8SPPiG9P;7AG;-R`3*|5#MBgMP#f+1==Z(vTp!O`qHN}q{6`$TNlC?l?h`iP20dN?S6p=Apf!TKHtUX>BrSxX?O`B;1`=HHvsGuWhK`N9nvPxfhRJ3|KS2~CHH+XN^(#!0w zi;1Nj1o0ByAqc4sunvUOK%F?{Zf~c2euW%gcnbKE?)3I3nL)79WWD*GjgX^rv?YSs zAT~CF38xo$003rO)`(4xCfEZyDXX=Ex3owCm2t2fNvfq6*xJ$(sHN}!V*3FePo+D9 zuTyc8cZu6V8Zz(?fB7gPtNEc$W*S56PybP88Ec_?0_{w2ql#Bw-W#PseMFiI3LRmm zN%wNA>Q<9@KkMo+be-o5!X-4=@_BR)(`N>%baKc#_I`$?ST0EMnlv2m;pXN3Ud71d z?o3zPrs|=8CPaH9-54tvj)f6nv32=EY;S?at*$BtE0=k-hnEWq`{alvy|?`TqXNmp zev~QfM``oFa?v;_8Rc&oY5)5mka4JH06^{nn350FCRW^m%f+BJ`S84`-Cak`5b|Dj z|IIH$2O6p)K=~g}jwNSrB6wg8V!<-;jX{b*92IS-180g|8E&ygmPS)2f0`I2CvH5K zhq@WGfuNj)4eB{K>AnCeJWtR&13@5PU!`g|pln?kd^8$~UO=5(pC3vBYRpKrEt*@1mYI=ywqSTMdzLkQ zBw`+0Y|S`>bg(rnApU>>j(@VV6CmTh5T8xa@}~Q_=Xc(TWx@~q1KKA(e(wfZpCu6` zj6n8w6u_XEBLCV)q6K`!;aQj^Z{q{4Y*e@S_rJ}}jEwIQ=G?yY8RaNGs{PNSH(Y|l z;xCErRVo(oBNzouaf_kMG8+f&_w)_B@q zZ>qjmRGUN;m|O_AN2HV+tzaIijlW~Yfmhd|YD>|X^9aW=|37I1MD*D4R~!Xp58Vi$M`P^$q38FVwd@Wpwjox z8rX-jS&LW$4+RYR3Qe8ufBzdW`u4Y&<`M9+#am`06ovXbn+AGiJ2M(*3GplqB+E98 zyG*WekSdjx7oCX^w6c-N-$=s+4ZHyjw-7!mK$a)%R67BRrgh0}b}~sW)+%3mhPRJ*|4B&in!hPTX(Ua_!9tt_D0q$rD~B1WI?eiOUA*L_}Wz3juVtH)rN zg)ERxTdX$ks9IW0pF>fD$px9&mcvTwK>Nr<2nh#9pdOS)eCH~&Ol7cgD66%Wn8duC zKYB3bw_>`kT6a^nX&tS{1_F(jMOxfc1oA2xE*xo zb~%ZJGCaA)505Lmf25OCtGTPq+}_Y#k3Yr%Tbo{o1l%7i1N3d-;9WRxONl5`fK861 z0h@>V6CU*c9c#A<3NhVT&Qjb-*boqruwqlL(>@0ueVwxikkdG0W@hHMTO~mNd&vRt zx^ux-|1~$}q0BX>%)*_KPA<5wr?0TD}jTah>yK^2BXPhq%rzB{%kc zf0b=d_;m0Ickj6`8)MA(u}>#H(wt|F*W^E zclHUmjYm5ivDYA66c8e8#}~6UQPc_G?(dPko`CjmDUoy8&+g`0UHW(i8vPs7%2$O- zT)$g?N&@p9k2mAls6R!$sGMX1R_Ax(^nHVGSu*-f39J+x<{!Xo{di!l(-K($_Vq>W zy*VRxO48R>4`;FGJ~**VS$#ZWv(nfmHiy6JGOJhXhIob@(>^Qw^wmD{f#m|cCFQpH zKOgfHRBdz_k`TISJJ2wQ`;Fu$B*Q5zdNEpMkHuhbUBsT?nb0cOkeu}=btYM=9R_Ez zIaO}_-vx(yA*26iKiX=fd2OtEezrxXR6%PQPtK1h>+>m~Er4Mc=&3pr{6qc=yF!no zY(tADSQtcg-^j*4w6MUwsa%R-yHEit{Ch_;V!BT=%tpOd(O=2TK*sMk(ZwJ$`fSyj7?p3BgC=O`XZ1GHzWzX+OhPn?g z$PaBeK@HPy>P8mq6156twKcWbW+k;Xp}FYMK7t*mtBWZE?P%iPwF^B1e1z2z7r8al zXCq8EFmsFvFraAmyg0{QDp{V()RsC;{3p-euaWFc-A`{kgOlm<>6r?1%DwBErINx` zlJlzgY#Th6IXg=zHgK(%T`&Q*BtN;>P32R=%SK!O)6M$Z40e6lLVe~|`Ja@3oeEZs z_4KqIML98UJqN&lA4VQPP8+tiSD^bRHlGl7sn;E@CZ(lL_WwyUQCp zsLXhx3oo;~-^nf6_PamM|Ch5qQK4F})I!~)G+H;j#SD^f&ft}*_fCgy(4RzLE`AcV zceRxc6|YR_H5T89Enpsc98*`yu%6KC)|RX-xp5rKq?jCvZHHZOV3GF+w>>wZ$k)r{4k^mHl#!!MgtP#TyC=ss>Rb3fcy?px5zRcWa zO!;)nca)W1W)awlDXs@jRO6ek0n7*RW55&w;%1lu>7lROHd*`|oXAZ+&7-~Cko%2p zlX34HfibXI@2iU^!KXOoRb5R0+AZc&v=6mXbgif~>W~iZ zMwYra`l!m)|erZ`E3o>yN_F23a7m~gG zr*ial<@==c0UIsoW8mrptYO-lizk0SVoYeFTNY?$639{KQjgZld|&EndsQJ;nJ{83 z2GCFcnw7k10We+j&yB(`UF|VBR6->_qx<}G>rJrU%mnsXIdsU}5m*1=iFT(zj|Pys zDUXyK>d({!+286ba#;wwkEN#jk<6W=pSl-yVXo!^>wiB>Wi{S;oFM)vF~h&E+->tS zTidUzE9%OS@845&P|H;^9O70n1L|aqj3nVdk_WEaocU7IkY+I7zdIs1qhRS3r@VxY4ii#}<;tYy3t+uX*vc8=i~tjETSL-OKWh^I+!fT9!@JX9I9$g| z_H6!CqBHm~yk?mUZ~5It@bM+mzk^HWHX$BP7}U_(PqP^2$ z@>SR^)mGsf7mluJ?VPiTh&Ufj$lxE{x2M)#Mjb+6X)KEFgXh(0&@dNVCSEd{m!lN5wdAo| z%4Es3c>R6skLX7`2N}5}Ua@uDF#UX##0*LpNT&TI9}Y0jQz>?ViWn$)+s-{&Gt(95 z1M)9mV+ug*5jP^D2=C5>buO%;VwTaOuJ4W^UAuQlz!7!^u0lRHy1dHraUZ0cOh}dO zbh^1eE?I)wif>%c(o+Nj@7kFa5c~|b&;o^(1 zKj!$mZsq4Y<<3t}URWHrlc6~@Yi5LL3>nNg@g<@iSc_898{B+p-ada=+xYEy;4xV^ zJC_YU>#P1`GCZ@eDiruJ)~Y)$t(r{sfkn)Z;!A-X4FHz|V@1*jRc&Elg@(ZCZo-mV ze+?<#@(pw7VgeADE*}&>m#^f{j=fAt}Yf=`da+%_Ulc6uUYcy1dLnpX3i z3=gLxM%FdecECok$t#X*G^4ZPyX0gvh3_e8EN0?>+Fx3-0+-uKPO7Jt)O{#*j zn-R7Sv&492kshgk0@~Vj?E%y#H6|`DZV55c)SZ6h%4lMW_(;Ag5F~BaW)?+)dh&y6 z592DEGYQv#VSYDP%{hw@s3#y*J7yu{rOl-NTFDW+)>Up0uxwXC~Z?ufD^V74Q3*|)L2#3$w}=x-WJGL zBJ6QJSffwd;p@kJPlu*w`@N4SRtCS>yyr*X%!@D+)2%ZP`jXseqkmlTmz(4KA1)@4 zgM(6e_E2CeXP@(v2x}wDcRSYM*uYEWccUEz=9ghpl3y=ZT}5vbo(m$>y2{Jnksq3U zjYXsb1b%aq3q+OdoSf^Tcdmk}Hnd~4+jCcM-Ld{83yy^s5q#{~)T+J9&{C9p2YnYC z;X0i@&s3@xH47lyi+^BftzoUS_tn44F&{ato(9QGRfT3>5Q68(4i4+mJ2J}~^g(;> z_GUsI?LHYK7$&K!HX6^?Z!+rIfUb|z`C6jw@blrE!>i0hT zv0~uWg@M>{l@EV&l=IOO=G~UZe5Ab8#OJjuOt7tHJBX1-NC;#0<1n}!)l_@+q*gX9 zzjAz!s~pXsMOa$*5h*H#TT;e>@6;_Ou3d)L@l!yov;NDS{Os%F_np}`25p>K?e61j zDW0Z2r0Z+P(R?u|Jm0kszs{8vw^$3Bke-Ud;P#!gmduqCu_ZeLMzvAlzRu#^#j zdW2!g7gcI~cKzXP!bRZ15;&~D{uz6d@RlQL!5)0L$Ub+$k@jx9zu`^8%v%A42}`4O zaY;!@md!`A0z2?wcERc`Ru>1;(xcyT!6XYcF*{tHb5`!0G;1|!2!8BjT%!uRv9u(q* zAZE!{X3`Z<0UrDb_hR2&`*ZiVt4YvtNOx=Wr=aMc9B;Z@M<=!@gj$if9U8aJRU@y! ze}z|wPnf(Mx_msO(sChp!bthA4)&bC(rQmnmwh&-^^yXe?)0t9 zrA!^B!eVqbz^=U2Hw)u>AGF=^g4sRtWbZAA7Rk2CiL43?cFvA|D(Zb#S=G?EY6OZc zB!?-o^U06HuWl>on|Uzo!O`VN1EUUR1v=&= zBC7Lvh2widUWHp<9*A!!M)p5t_2@p_I$NIIH)oSM-DePxr%>wA{8>Ci^fXv+&KiU! zf}OYfdmCetKcuar0_kCDpn<|&Oc*;ZTxhLWCO&G zXy@inQ#GI7snidy3S!=Mn(7S2u?;<)d+L7zR-vy&b7yc55K!m#Hr6yftGaw$bu`KV zmxxSxnw^pE6#eTc*Ah<+g3zJUo3HI1S6L}%{^T{B^~*Z`4;fy3b`{E?8V=s5K!zIU zkf-}}{4Em0)Y>IiCf+Bfn?NDsv)$vWp*RkrcbQ7ey8(;Pog+ZgJB0B3d3WK9y_4}b zbvcGby%C=4>%nhNM}3?{vQ~pOIi53k4p)E(A}cJZoY-Z`K!4EDx3iXhyoXj!e6uJO zpXM_R8|t{Ic76WY=e@8KTqpS~Wuzu|9iN+sSp`QGt2hfritS^R_d#Q!aLU@}nR1gP|L_wr*tLK_gyV2*Z%V z_GA7j#6U>Tf@dOf{)B$*y)Fw&ebx9S-ty?o`th+dz^227_JvC^t@1(3W#BD_#2C{6 zO~ln(yi1gM5%5-yh?Sy1=fzWz8yX6k+^sfV?mog{jJP*wq_jH@kj*mzW^Av&X}zB{ zmS>zKTM}?Y-yEZRBSpebhkrNd%Wb(^o<`S#$W8cQzL|VhZ*mev%->^YLEFZwG%d0* z0(Q^>@6NXpuKp^zs9PG8z@vi%+22izF{fU>2W~wA1Px+~qp<@^du}pste8kWbbI7k z+7OajG>B{zNFowUSG~G(!5>+RsAvA{%Vn1Sb`X^{lB5ApYqGHUm~XBH~t1J=UJNv9Qda@^4V_UI~i1cYYMxJ$X6 z#L}O2=rZ2Mk-YCj2f*E{K}_k z7H-C`6eeKFbnu2I=bFXy-2SjHS=zbfxl1oJ1NKz~C~^~1-nrG+JNPx}$4W{p_P7n3{f@l%uA*O{ImHvcx%;*|A93W4mgr3? zm7?zQ1zsncV4y*j%=zn%?#JX~ED!0wX=_WQ*hyhtYbUVYqdOblav}ZJ91h3z_D_eY zIcGPm%OL@P0>S%)=EH#M9=wT?Lw1|;t!iDsv<#=q-f)A(*fK?a%lA%9n@%d$nf-MZ zkZtN&$*c-vV}|ma@8X4JR*nuzmiutT399k71cuQC6er9G0KWTJ&0{=q zjd02Mm6`fRIY{z+mR0$lmni2d_d^^e$)0O<=(!W^#KuOBrX|f$*65j($xRT~sMmfQ zjntwIZvFI*sNi0j`Y0=*8uCuN&Lw_gtR%w{<&%ngG-lwIyXtJXN#6H(hwWoVAocXJ z$k-5X9)}M`LVs?WNO+Y+rCWi|i-wC3>BcDk@V`bNCO&pGg_;Zi)=CLPFDjw5xDX%5 zK`hZ7k@cNMNt!hb-OAzxflAZ_&ui^C%8F4tvA4m3d|mjc6)gz2SM3(3{> zda!=p-R_5&Y3S<}5(E2Amitb04_PS?Sih3tr3>jQ{MUY+NyZBoc{WcdrU#4cT$e+$ z8~hsJ7}ROMuVRKt{|`k$nTNOd5aKae71Hh-oBJ&0BW+y1&qDZ$6`^Bfx0~t7ND*Hd zF)c-rE<9se`!rMP*{_1%kaH!D&m`fv?>^&*5L}&#IFh&fvHLmQD4r^=K!H?>+~aoJ zkLWzBnXk7@FtBA_<)5c4-f4xao|2c3Vn8DJFHIk>;^pUQBxJlCkh`j2PN8ibGa~h z_DjRJ9en-;=Qn(k-y=jszZ8y8x+Euen>WqUAGN)iSJGv+g1(~dF<#o2o;Z6 zPQiMDvCFT#eipodf>LPlMYTJ7nO1k2SSPzGZky>B6P_?A%z2A#!^QV4MR$S!-oK=J z2@5jEgB(G;=7p678UrJqJq>ui{PvI?QuWATZ4Q~3;-Eti(%3Gen8Z@uX2J%&mhqgY zav+i#CYu9B_)LmF=mPrr9F29^d9P?gY{Zn!#u8o2Mpu{OoES9m_o8t|?kuHU9r|={ zIh>k8B%rO-TUyu&VQk1~;Gmeq)QwO6&B`_8&GhL0E7ZYnrAzoQW~iJy$QdKZLi%u6 zl~zj9&FGb>9=Tn(br1)mFaeID7N>S9!Z_r%{<2K+V7Xix!EE`T#z0m)irm|^thNvH zlWF#vtYmpA%az{0wB7l$QROhG_S6MKg+97du+(vS=c^(3F;RTxx`MZVS*N|87Ens~ zY4pRmJA%x^v#|mOaQ!PM!In$EX(f{qa21n6_!0}X=IsBg1?UR~>NNAGo>dfA<-6M> zOW6%JIjHHX^*!Ar2KuA3CN3=m&=~; zT1L%z5%livB@tQfjwr|w54BiZPI0FO2hJuc#FHY`M~qv>gTX>x+PfS_=vKzBii3buU^OIvJO%3U)nz0>v4_GZ(|n#SkzY0R3fX)G(^ zMU9w%mUI6Mj@Tv9&!3gzF1tiF$G{3a>5RBdxW6)9CWsXHL3W zx^y5Y(UWyJ*Cx(1V*hbvDK^-`eZy%1*}~B|*!p0+&14LJ?#<@6jwu`d@S~PQLHR^m znt1f`q=u=TQVrYKJ}ef$?G9PlZTew59-qMY&1{;EUob*#i*~wR?e7=U2c5Zhzt{J= z;hvK8-@A40bkZZfV*&-<;_*Obeiu}^*_+KcM z<!U&(my5D#*>@o^A!y5z_xg%r%zI*Surr8=-qr2Eu^=@`eoNa(!aOQ1+xRP5MnD9eY3Nq4Ca+n(r zC?97UMW^m61lHSdxF zsjbkmcX7izTZ#6Y{qdoWe9K1kGh^eY)k_=Q50zeMPy+qY$6s`G2WFP&0~hV@C6T9I zAj}GxShW)bPU-o=|Lx>nUzi1C_W(d<*rFOAG+#{Q-6<y*FcO_02&yu9x274g=(-!_W+K zo6e(9bb;}X$VU0S!dg%1C7R<8F;VRUPqNHw4Ibk$FVV*zn+HW|TU zJRnUr8A_>Y8-o@vBTeW0V<@5`_9@XT!X4SE0HtW4p>?=SYD5t%!4AR01e$OkSuFr_ z6i-^KV|?7BVm!&1M~?M1%h8m1r90epO?ymBt;wBp$Md4=sBF)U3(gTuS&ta19BTv3 zP$(V>pa2FZrHR*#6q2yuoMmZB4l@mB$7w*1ds2VE*UA{7{<_J4H3NId@@G%4W)>g6 z%Raw0G24YMSbD_o4Jk+7lAKJjjWo)>by8}gjV-@GVnbIf4sCq;trlOEU{>Gc<_P6c>XNF;!$kdCx{1qT_P7vw?w@W7}a3b5L)-x zvk@_AyU&JbLfgGU+~7Z_0SZ5#ME$tqLuC5yx(^;kYMHKh>68r3T2gUXyp#UzV$p>C zcVzf8rE{4)v3#UqbMV#3PBQ!7kv&V0>cPQ>U9nY2;H8KE=HevG_Zz$U5F;-PjcRaO z64Le1Sem}g!2J|yu|R6*Naw*Usp8q-1R>_-lS@Ou1kOmr{~Cx|9wVI+ zRi5-*HH^y-VAEx0njCar&5WXmY7hBU@gU7VK7$ay3b!F(32nQogqY|$+BpVxu9P@` zDG8xDeq_RsA>0PUhek89DTD9wzIsb>2^DS_XA&JKgX8pTM5FC1C$Cea`2ghEb_=ZB z=BK1{op(;gSx=1D$V-tO38O*vahJ^;goBaI-jk|f_eC5_U#0`(FW&KCF-Ji10Gyd} z^TwULI+;=`Ti&<=*~o{crq6TAGnv{%n*0M*U%yEDWpKga42@0OzU-nq3ZebNd&`u) zKi!tZDRhcy-2RqjjNPu(TU))Q_852|fD*pm(UGqoox>EGnmbeFI%hh#m#BeXpYQ z+)y1Gc~F8r^dwZ3pmP@c4}!(L<-8Ve64!F=*2CYX@-Z(3ZVeH*JPj*z(Nwts|1Cp; zgoHGw!)2x}4_62?RL4j8hjxVOrpNjhe?7`1e*dKZNY3)PD%;Gx4L}L%bg7PH6mINu6xC z_hGf3oe~#v`C}z>mF;Q0N{_l{7Rw8|MVjR7BN`y2a7(Up+9?-~iBRF^x4PsiiCjDD z%FhPn8$K;$7u~jlEj@{SKaozO#6GN%oz2AN`oI+qi>5!#`ucIo`;7i)8+8u)L%Oq}0c*aDt zs7%N2yRkOWAK|mSBC@yj#V?q<<_16KrPj`F*+acqMC}z!#k5c=< zVn;@)@s&G!K2)}e*2IXYKtxaFPfbG+pXkAy_$0G`c;yo*H_PBMB&<_UjDHy9(1Wx= zyf7cqzfzAS#r&S8zD_<~x@R26x)n{a8S%r;agdQw(#Z5G#uwS5d!(Le@b_~+TO)*- zO-NOwbI(;UsvFEt0qyC|gE7cGw*kPmQYR8d@dXKI7jhmW>E?gr0?k74yyz9{(xH@9 zaQmY|jo+qc3D+B*%C63&prV*OgxQYoxT0mFSSVPetM^$aw^}H4?W&f1Doi7N#Uttl ze~YMzaB}2CKddG}QK=)dfVpwBfWn-6_l>=qI2!mhk)! z5T0%*_8F%)Yi>=%xHIjYyP5tE_tTg9HCZ!XWHjOnIte!L(C>?LI|Zx~QcEYQ@+Ip zJfGj0OV7C29$TDtoR8GonYum~UA1{L0E!2Xa~Mw=a_P4a%zsIqSNE-w=*bLkPD{n{D^y?t3qL}hI3W)rN0nZfJr!;0w3^0hDg77Uc>cfe z4fkbBx+B#2sY!2|l>KEZ7J!=oEdp1MZZaThTlVK6fSHAN=I)*&FU?6;^Eu?ZPQI0I zWIBNt&Ew!kzq z7@!q!r3b??qoq`6)S>tY8Cic-^Q5dhh<2llK^{(&eKl%oD>B1~BwoLSUSo<`F(G$M zD{#*^z9YbUBM6v=%uH8|Db}e(8<~}Dv8SH<=AUAj`=x~PTS4dd>CS#JLVQ{m+{fQ{ z(uORKxrQ$m?G^r2Q+52xHvznasuV|VHv7NTojl9mFQV_kes(;9MQs+4>!jVw^x zaLEIa?q!1`XKm%>jny9yau|)(Yo$vBUOO!E2`YycTCjJ}QU<-fL8P2V{L3}3Sz`yI zgroYpmq2kWjuYE+87bqJ?Np-y>Zf+u+V;PDNcy8^^&7PNGO)|}L+;r_^@qaiP)6Qf zh>}XOWl-t9WKlCOlQ)?Z??=j(H6KQMp^qyafAy;0b>(cn`iyEX5B@i(uK+SZSibQRd87^H9Yj!oGjw3F}7NH)=OdSrT`wCv_w44bv$_{r9= zr|bRj@K@8PKc_BcJ^q1PB*mSmR~b zy!%@0;t6xQB&ml)Pu`_zB~8zlixHFmVuOGIlTNxL9$S=UnNP&o#zLOY7I15KTdI;8 z`-7rY0@K`gJ|+o`_ZxvF2!~b3r|~p4wHsm8+1pWT6CKBHOr)QhNRT^g38j6(u36*v zgEYQHnr*XoM5cd4;8(!zMwD+jTL4sM$T?- zJ%DR?ni|L22Wx9kNQpb0YF2T(Ooa0YuQRSKL%nzt(ZdKlhs^^!1t-~L5oyVRY6U`s zk)!%}Qu83$gMCai#T*(f?m@eM9ZHukb^h_;72Tg5Wad1mZ}WY7zOr0?@ZGD^2YV2w zCxFRypBi*nOF;~|8ATydSKCU>mh@hZ3)UF!7zOnTNGE%O<;C^ENc4Kop&iO1{t$X- zX{0Xo8oJ#{(VKN4F7=fIRQMtuwl7g_X*{nBZemYhe@B)(0SQcEA?H=rnPFHhK++uE zPlefDJYRM_#KWTPTb+nP9Om$|+uDykS3Cvl!u7gj)tKNP0DB|dYScCh8>{Gvl;(0* z^ZOAY6wt0<4rPYpB1K~=S;D#A1giy;6ptn4mGqWI`ZS>(b&qdt2xVLk*$&9;P>|_3 zQ&oEtHdIH|Ic093KvC!>^PyhWC0x%`Ke0b~W-4DXp%uy1H;R0FG9VS_g*Ppg@j&W; z3oP=+NcQ}`oM|DgT8C!;Kl+O4?AFXD%sYD?eY@vHwpl*T8m}K$E){QO%rMkdO3JZxLk4{2YJ=Y(@{ad2JflYLIS0y1boBY zyYzpp(@0{Fvo7+6B6hYdy472P_4XS)bjL~=uaehzIuJv_$Oo>2v2BPR<9QJ?#{|}T zgJa3OcUWJ+n8W+nOA*wEQs2&t2Z5K)SsUyWYuUXvBHI8T{OZ~y;yg_5opbKb3Z60N z%v0+$V2T1-hhL{A0zI!NaRF1&TjbA?jyXE|D6EL506NO2Q3{DMnKVnB)q3SKdv3Yy z_dN_{nbZvYnj%Ik7^$#RkRyzb`gBemiQ0L4`e@tymTX4QWl*_^7LE;(YI0@jkPgpX z168)Nql`l8RrIN-*~~XiRmw_Eg8oK}y4iQUys0`b4W=1;_#8fIeR=UEN&VHv8@a~2 z)*lLN!kldGI^{KUitycg#uub1IhL$r!(s<-wa_3M*93(c-Fas2OeKqayCOgjUZTK` z+%iw8$BSYcXw0L7i*qy*>>J)W_2TG}K%6o{)xfDqJC9$zm)IAD^a0=%c5TM!JU_%Xpoym=V7R;GN>-W`0?%Z|}%k11>wTo~G8Qa;a?Az8;Y8AxI!+ zg_3unoG;+}DTsxQjFD=eaG2VPxekJOr~FSBJlkool-dg1T-m;}FHYOe^kAQPE}-DSxYtD&8>m z^D+MI2|q2bV@$7*5uEOwH1545OrWx&%)d<^DsL(}SdJ*lq1k&vN9x$spn|M<4x5k* zZeBY^s(KKHT}r}2hn=RH89Q45(TQlL-n{u^Kv;iC=$E@8V)xGm#_iIE+JoMn?&w+J zxQHAdv#O!nr7vmH1pb{UKv`U%3mu(?g=i}c4?GQ-GQd|*i%*No)qSic6hd5 zHy=E@tK_2W22^I`ScnRoJ7@aSHO>Sz!(mfB7AL{`=-Z5o8t`8ux>8Xq+d^5MS;u=| z-6Y_(&0V9aw|o!r7CPPoIx+8ZMgw${d@fbHOZ!XijNk{3Omb=#E>zaIC)~+{f#x``OZCfCAvYAE7@;o>puZv^xXF6G2ugJPDztXbYq4&2uj$0ewcrTjI8twdf*QS$< zih<=>#);>^&4WF}A*#2^c1B8S%^l*s(Z2IH;|Y+^QONO4ajC*GBuB`tTNLf=aW*sUn zWED^nYHt3FVfOCE1^y={j1BZ=MDI18W)E?GKBA_5k`;^fKA(OJvXrhS^%P-2h>vAv z)*3<^)4Ue~jA_CmBKM}|GWS4FdK;A0cf*HLt|oOHA3evR`Z|H1`Ki$CajOP$HU^nJ zVGj4sl1}oETP~LB(#$+HI-lQj1Myz$=}S$|`^W6w`Aqk=<}Xn*U;285$&d2`LKW=% zQX0pJe|X?c0pSA@a5%Kh8DNn zCx$n*Zzu$i)O(4?xb=r=m~AEm3l0=lMX6>vOJrAby>wH0F->@;-Vr(4#b?7ih=6>K zT~489(s=lG?LZk5lsgB1z_n@5_Qi#zEL=D-Sc=sYOBM0TV$SJ<{)h3(gz&r9%|`hZ zjyV%7DojKUOwW%UvNiy5X5Lb7hbpnDb26Xt3xHr3q+07AXW%Z_{9LpL;Ntx>{w$V$ z)UC)u>lc&@v^m?d=R+2%;}bM6v#u=n43}Sp@8LBg;dwOLyuD%pi<5E;kF^@7+dPlb zBqH;2E4?o zbw`SKA@M&>?jVLP(acEOT8v%N*udzT&@lL=z3uwp0ibTe|LP{*AFb%XGRFVVrn-YK zy9>WP$69id4~`gov!@<$9F}ECx@H_m?LL7hwjmhxBAh?z6xp7yyUNG{k^+b-yvYx& z4FioyXR#d=U(#(Nwwf`m@SZHPq@?$l&TPtxw|TXit!Y<#r=Z$#R5N#4c`<)rnAu} zoL+_BJ~&~we)->)t<4?;gd9VRKmBiImSL5_FRc9Jr%MWmM-P%x?T{8Wf`Vo?QO*;z zK^C~8sWNX!5=n3HhPi*c$*+2B`*m;RU}lxC?JGfI-%{BB$bvG}!UF%Aowpp@2)W|W zRR~t@;Ud!;A)4g_!;2J&??sr*b^lDuvB)m0avF~m?*J*Ig|Pf5k~T(&kiEP1!$_be z8k-HQcxm7B4HY)&Uy#Ue^2-1;7>lS`PPjv3k3K4=pQ@**k;3a!X47 z{t{Eahiprd#LS2yCsBi0nv2Y<3uXy#^OVA0~Phmwnej$gCK#mLr*LU6Ok7_`9Yv7 zdLg!9>xst72g^Fo`QwBurJOk-0=@rK`1EFgM6*omV}gne=L(Bwg6M_|wn#s)ttyKC zIP-QB2MaI3Q6t+AuA{xP&5UCs$%udmE@y25vN}hIDu#LUzPW4Y50!@zwbc@XE_{#IC!?j3h<(Q z4N2Fb$^UOF%Z{yZD8Bt*7kYz!VOL6qj@?|h!==&u*X3{9I#yNZsQ6aS!Yv#6VY0o* zB(akIa!4Ypg<$rxR5gys4B^PIna_6WCflFlj z#@kn==JCwSUwWVs3i!4}Damj7m{wb_hP`4i4FTE`{3{Ro#21>!0Yv1T>wlV7TA14A z_dtDt_Qk}Y-!Fg#G)|24+1V>?XVt53|ADFIeR#KeW)Gd{o@J_~j%)x$A{c@0f4lr` zl3}+)Esq!bmF2Osu<{bSw+@h>G0hT{SNypk06L+K381~B*)tq5iZdRuFc{u2P-B}= z3Z!zHMs|;syARg){Oo(WvXxX-k!mM6Gcb@plolIs?||z3D_3oA7}eS@OhAFi$J4L0 zWPF<9x zXMTYC2DI^r0g#1IHocR3ewKuQ=p=#G0F}BMX39)5Eo#tdlMDpnn2ve}f6L1A7aA&0 z*zU_u38@M+G?cly7|Iwr%Zkh>8kltID{l>esku>)rqn9&G zm+3Y&D4FH$+Z=-RAKR|2w^*{sq&2Zr3Ymz%|AG9DW8M;h^!Q;0dxBi1K6 z=#D37oDR8vbM&uAdq)08o>iYEHtk$eLJ)&|;651ZKl0-bxQ7|s>AKB5 zpbI(AIfu98w?29qnMYH#Ra$aiGRoEP4ip6;qdN_VjgnGAafIhOj(;v{z0O9te#0@* zaHr|!u{bcciv>1Yw*9#Y)~{WdK$?41Z_erGSKyO0Sci%Q;y(>&=ga9CT@{({3qEz} z|M1jAJ6X$G8Sy*aggY>rC7fkWxTlBj!(g0)UzF}KpCiGg(6axHx6jcPv778$kZDc3 zxDU}2`kVLpl|x}wiOa;19dA#F{|B^rrZmbLQuc|JIQ8hqbJFIUsB_;B+Sw=GM|0YAHi%!Xn82kB1?783|pSEbk`A zTsf5zUrkeK(2;e=(`qu}YmisYm-F39c*Lg0lEBI~lxV`6GH34S1l>qNaHz#mJI9Xu z7F-hS*MYxU;RB5QIDgsPTzKO8f3*N6PhlgJpZ%%Gu6GWd1TYN(l{t9TX59z9ub{9KjjJ-)==txT*0T4uk&7ei8Fd8P!LJ3?q$a>Sq+Fa}{Ym-R}53 zeJHx^T~x3@dBITFHqwG>8qt8?QSJCVY?o@T^pW~;fG-aEf}42R{X@iRkd-5 zH2ahzgJ&4*y;N#wg|r<#-BExLByx1+s5ch(zu@VqX~(4bZ_yF!6&h53`ZBuA6J8?; zT1lcupWr2rBs(pXCZnqyKGfKCbfK#ZUh(N{nGxW;+Q^NqefTF$u_>LZ`G4U&nGdkH zjq0B-KZDV;07YYCMPF4EMZvL~#3Vftn?+5=;*z38#m?tMpJ>6Un-y)lEI(4F9V)%y|fDE%Dy33a{41TW5P-=?Dnb%oXVK#ab)14n-KpF<}q9ddr?tu z<2GsUvG2giMMTVqMop`KxO#@4FY9P{i`}&m582S6J7)O}B6mLIU^bou{p1q}nBsPk z`d}n-A4X`_v}{ca#WwRZwho_s-}-Fj683C1tdzbqf2rZHgO!4PSSoZcM;H35Z9{n5 zx9Fn=Wr4M*c}{dl;Xfg89*4o#1}-2Iit#euJwVLX?LFBB!C47cSF@}>)4>v0!~uNQ zC3VM|P@nvEtS}!sCN*GowlR@unWb zR#&HDDXijCr;RTa0sASdf7&g3Ziv0(`K{I!v8eEh>68RHH1S9jlI*ISX(JggnJ#m4n6+MQ6m#{1n`e4=!8a_YLA2N{nZES-NLxF8L!>9= z?>m0CaezWCO8|E<;1)0#L>sUNIz%d=y{js0{$phWDs-lPY~lHeNm`+M70mbVCg*3U z3=k&_y3l_fmMYK)yfG)>dpu3cNcd2`3iox^?{%W`H_xpK37U!N)souwd1K{BG|18( z<)^94P~p1L1#um!%btaE9TCzp=PMIVSSuS+7HG>EXiNEe^F}NSDk}LSHSdC zFXi*6|9=Lfn~;5u&@E2z0oXjfSM`e^4+#1D&z&}bqfN$a%|_HICKWIHSkdPUiW(g2 zl?9tij=DtV5?Svh7qwao3_KN@qJJ2X$V@&M>k4li7I+-dpmF3&(lla@VDTO2-+v=} zrKXwtb*!JZuEIvRUd=mb$)1#W&pN?GTA=EE3c zXyqOPx7A9Ivip@7GV?5>(>!u+GKS&9M?an@0J819c%b&L4Z8)|PQg=5bRo@biQnRk z@oW?H8oJfu?mp-|PMX5DRVq0Gz!2|!;SKl0Cnnyn)j5puINu@*?<7c1FcrYue&^HSy`+Xqw#Q;BxZ`@_awKXUYY{5#`}EzqkiKJEb03 z2lQA&4QRpPPyA1}JtBn#OYnhh_*VTToOKW`HUT%vrT#e--6^iB8QJ{qY37sk;gliE zr1v7iMp~y|GmlWRvXt*T$}<1B@o>m$^t&{^6O?!_sQ>z|<`_Rj{5^nt7qml!&!THO zHQi#>zf_cxMTFwxJ1~>PE&`j;D{ZRDc>dWIs#cPGi2h&( z(z9P-*!ijLhh(XwUOI0R%HKyA-SqYd-^ z0n}l(UQpjvx$?D-A}(@(LT_y+rfJI;4+&3dy6fS2iQn(Ozh~L^ z;|(_mg4#^M5+4%c8pmafYyiVoWL|@i80LFa2omr>QT+yXw1R?`)I*h9T_`@Ny-R(# z4a4Wx?ycY7>@S==ce7wRxX&@n_oEq^5$;We5g5Ac+M}_FsMlXv-2b|8 zv`ly0qZd`%=A+LmSJ1EZMN_-5eS9_HfjrM^hxk2$ZTh5V*F=NMy9`pJqPrf+hN>VH z^~uY7YnaDlXui?D*;tuEY3#0i_j@4ygw%ugQnmrOFIxT3%G%mNKYgHj!*C(vkJ-pq zY)u=jwr<+&ALfUbcKs2Vdw6gcIL1t<3O$M@d{EiU8?}D500}nml^57LUQu>4_1^K% zUefU2ar!J=--Ja)SI@?GNci8@eyB#?pI0z9Su9{a8{Bi##d-H3hSHh9N|{@5$; z%&f+6VDj{fO<8cq8pG+K<#Z9#DNt%1m`{iCBA%j`**~e6Nv^1n{;`|+5JUBmRZU^i%(9|d}Mw$ zc3nA=FB@z|3+2)U^x*F&K1=80taL37Gmt-2bXuW9AR`8T1ZNL7zMYhol>#0&e${8@ z*Y9-YJYLvI)B3VX&2qVc`CiuSuSFMyc5nOw4>T^?~8Sm zND2?jNxfx;@RovCETjwt*LHQBU~J6vW*pgs?qiz>oWLhYbE1dR^JPMkO8-6GHwj%^ z>ap)#{Rw3#yD`kfU+t(Vlf|aZHVCMf6eau1e-zm$*;P` zb_MD3v08e&@v)x0(RWCOyylXz8shY!P=Kso%UVtOQ4+Z`DR5h-RwcEy z9Y+3M#64+K=OW0qfvXS8<(?~`3(w?jJUgZZ!jA%)W`-j+3`4Z=(y^~g6f6S8G7BI97Vp@O@muzbK6R2zls`DPCX@e<`x~Oh_i(wz(>9jrxIs6 zD;2X>Dvp+!J=y=ec>C2diLn3WAs+aGjHZGJM5d_`i|SmRzhX8%*So1%fw|=W4jHp2 zq+nn~9kLhXad1S=BiS5bNo}pI3@o%a+VEPL(l$iEb|IR#aN0;CGm{C~J`J~W`N1mElc}*{EeWL}_{i>9i4!j?O;5dAnV=Wi+7(L63`OXdOt(#mth$m?IIrrTgQBhtInc<8@#dFLLvb>+J@bR%ygjZn@(G+M^QQ;%wwOOfW>3&U% z418UDw@m9S_pv>F>-y%m%%c|iI<2Cjj%qv43}JEA~-DQN;55eH|7AUzqyFh#$`nLDCiR54995qaN zBfV5Ntz+(L^7CX#_=x~lwm8hAWXnaA5)W}t$c>Tf)jhM`qo^(OeizYi9H0NXG4!j& z!csoIe#+^PafE5S^S;`A6h;i{4O$ zSJ+I0A6IZT3)#niKD+~stwu2EhN*feUz7|b-T6y@48|dF^v7-L&(2KCz#-RYDB<3% zwYk;O+InkgiVx1HKHp%iwM2Ju|NQ$XYGeac{4ZN$V+j|ck&9ndMuZbCi!T)h7Ar8c z3rmYB#V_>pPw%G9 ziEJovykN(V?%UiY$$ulFNbfto-$jo&l7Ya}kUDmV+# z6Ehz`DJh20abnKUl=Z?fVFoInSk*Y#9}bLPZLENqd%gfZYBjHES9`JjXAAkg5wMfk zCh9HpDdT_z-jjIdp+(V2NH2&(Crshhn4pb49;w>JTEd6wXd%CN79FnJPU=);inSa= zv8vIULL2DpjfF`XZC$baN}ft~$H&iKCD|&>kR`9)GA1e-uX+@pCwoK3W>_hss|}qJ z*1LRE&ydsO+|8=t|SKIx;|Xk1#+CU& zf1S?DW{-Mkz!D1m#=K_ehUQ&Tzx%jk|K1i_h|rfgd;bN;;oss7>%&!#ezi0`R5H|% z964?gm^uBRIxeVVHft+nsWFI3;e1DzkJ`H(iG)H3ol#2ys51+pCDa!*u^h7f&XbC3 zMvIMs9;=i)9}juE&eXQ-@$@e$=>7awqkpgzRWY8*-*~fNHiWsES-zm6DYxG=QY|Dg zMM805aZ_&1c4wY^ZZAl#Tl2Wu*2}^84Q02HAUZcsQi&Yw^d6{cv31N=_Xn0?piKmn z;UI1X*A?}2c9uLpKhIwO@Zj*3GMIP4Rv7W@Vtuy5+mfNo!jF7>3JHL@v2r@ogXXi7 z3J7uz?41>f?|w4Sex{`@kX0WOwp$^>wQ|$S0C>wIG=xzX3woxK?YadH@k4J{2e5(I zOGY(5|4-Z<+=WZm2wvLiKZQje_21|1?&`rW5b097S{mYaz0E55{XO8jbd(j-Dvqt^ zF7iU2p=rTuFzIz#?3$O&Zcz5Pp`i)n9=kMaPAF(}*$O_$UfZ|Xe?;>aqKuSzBxCgbIk!I*SY5=Hr&GKOmnUcehZHNaF@u}hs&=Y%Ct7+!o@ByYp`W& z7PSXYk zUalV_b#f4QX*{!HOHkkQmZ+E03;%)uRe4T1-DGd&i#R2$(;;<^Oli{h@-^oP_JG&` zMxSriky96a0e>nh$xa$OIj)6_fshZdba4cK)hhhcSa?jOvbVJcnA^l@uan#KIfWo` zilq6QHQ~{%At+wO1ZH>abN!~u8jmopj>zBPzaygxwF4hk(O24y)eUy;+mX%qB`e&1W`VM?iDu5#U;KWI; zwt3ZMEB%3AUU1!1lnk_0=%hvZJ5Jv1hk=!My}L?hEk}~;b%3&*^rBU&- zMGQV{7fP3m zWSN_KpLD)!>F{im>KG#n{M$Xh(KR$;*(3k4-5iR{*L|~21Lc)IWcP-bJ>lt}c9jqe z4wjD^32@&B=HEIy^}1fA{oO?gyGrmKt_(-qv+l~QA!AO|jM1@RFg^ghPQ1M_&47x||moQtTJBi)+9`>(k4)5Td<|&`w zLL#hAA1CA*AqOFUD|R-U7%0-G4N2)4dURkbm_hp`yNj$k?(aJZg?1Tw7`Y$ccMS+- z@4!Dp>gV;I$r8A}|>7+`xqEosfH=0b)^I$GY*?=^3b^I-8|RQf)x{&5OHDXa^OfZ$pP^2i2c( zDs%2vyuFss=qKt^E=X)44Mg|f7k3j^om2ebdl%0kzv7efLa#^n$KC?08KyL17J1Rh z>&Uo!Wp=#!;&+VD!p=fDgd~_aLyG{Po$Nwm;>qz@ev4H%y)sTxBVzW zd*N(<5}#*1x`ao7oKZ#x%!r&}VlXIoTVE+RbA~;%uxw7ant?{^QbTd#Ge`!GBs);! z%;>xf(bVxbmoznDFxWUEKfifCuXjHlp__!z*(uwdzcueF^Xw6g20yvx_oO$bM88SH zVO8OLy=DqJ3O^fu8)0d^u~eMYEMNswb$1l2>L`@oRa2^E@umjdAB4nv zL&@(r_p}G*s8)UbS}e7gRo6oxM$0GjtIpf#1%#IKD=0s-hS-T5J3)^57Hg-f;6RL) zW)I=*7urj%Dl6VGegzNDksalFVU4!RXg9a{Ih9xQE<##wMJIow2bx%!OU(QUOR4jdLTQtsotIU^pPbqvFEPbsp(Fy4&R>?guQ7QGDta zV|WkIDAq_8fG&eXQrL~ZC$dn41OkEZL0^0U+HlUY8#hUcB1Pb}`c|W^AJ z>m)jmx^jwjZp5b7CV9Z#yyC>?%U%5KP?k%7mdm!zkpP4Oj=^;-?xn+W48rdb4-Kpb z+M||H8Z2+BtYpplo8*B*N1okFTRtdoH`p1w~cQ$LEu#kjyU2`_}0(oMyd^fs9X1sHHgeItxXR3~0 zwZp9`7aih>(Bi>nn{)2E%6|8%!E6Cb1p<~?kVtO2ENAnJ~bZ^vq66KX(;19VSFr} zLIR43OQjL67B}mkWAQbPsM~*UX+}P&$sgK)$g9OmJ!Z5Vn|95t7Fe)HXq{N6U8OIA z_Um)Esg|7wt&edHBK9w}G0B$`&=${Yj&)XW^KfiINi-<0^3krsWxQIJcy5tE%B}AU zrW1qzl+O|QD(OzfZTSD8>b>Ks{=@(OQX&${-l1%gy|WUMoxOK<_72G=l4Os}?3uks z)**Wx9C55;a~#Lv_pJBl^SOP0f4Ws}w_eY6U61Q=-LH5`i<=7#x)ZL|Zk2K`n`B1H zE2p>$8vE;eyLXfsT(GECu5Z+=qS4%c0*x6>u@`lRl>T6B0`;O#Xnza7TqX$AF(uL; z*J3XqMZ8-t;~Dhosee+(Rg8$NJhAXGeqO6N%z^p-F}?{i5?@@pQr1!#%*oN06rsRD6og#?>t9rS2fu*WmT;yMJM2T1nFXwcV%iC83x)$??^nG06&`_{K}s#=#)2}b z-}7JrC9?o%1w0wn&1MD;OB4eqNmg6wwdO)Ejz$}#d9TqeLcRXAO-=KTf3lOD7tRXh zeZ(?o;)Up5rDk1PpluU)SWlNZJWaN)76^q%pg5<^Qv^k}LcdOxP^>T9V>qt`xH*2; zjU~@oAFBmlj~;#-M+9%zmXz=+UsS!i5Qpeh%m5m@aBt56TJ~|P&JcLA0|lGQ@s%!w zK59gPKj;1mY;oK@diJ0(1jMv-{Vpw7EV6dYnPPRm;@$W0r3;Pms^8P{t#_lPTN4_UQk>s1)5wJ}qwU)g!FrJJMh%e}Mx)*MHJ!IJMK92ad~ z(aJ{yu(X5CkZH}i-L3=S(2Ry@s&QCUp;AO*20=bU9&M}6H2o1%?~h(dJ+D*jKw3K( z^Ap8~O;?nIt~-lW^W_2610wppI~m%S?tB=-ijp5XI&s(c@<|j^)5YEVOOlYiuo*Yp zN^yy!I@ZT>Rh}jZ1$LYPL5AzzJRwyQO21ML1C1X}A7v03vVaSER>fwQJ{+iJQ!8sj`q-;wFXBA$0E^cnm_DV7fuIUtdp6`V69&Wl?4asdg zPXppnohuNkHHX1@&;9+NlF6(;87Mfl*ig6WF`(rhpIZOy9u)(mkcE zXUlOHOr5R`rMkx0K%{yh&$f=m;b4$gT3Xtn9KHPbt;ekmeLPX-svd~4F~Tn=nhThx zb7Hht=lOO`Ugk)>BcNfHl*m|UuGB`nNW^~D{L#|qqtenCjUd@tx5$K=0UU#ak%_J6@wl9)m5>Br^Qm!`>KzeBLheG%1+8f zezKwhkr`l`;C#8f%i9Z_FdwrP%t80XEMr8a^C2hW9;zfUmvg`dRdhl-b)fK*4pWjl zJ8R^MQWzv8mgcbeQ86WJwWlSLnNMk#n)&@{Q2Fqoo5<~SWs$2VG{lnX^)0=70z=~3 zN%SVyOf*>ehU(B0c)S4qzZ+lR(4(Uq;i=L9)W%V@l>OKr{jX|ZW;!Xz(Y`>3rPC!{ zH_-5nMx$Mu3*Vw=p0IAv{$0?Uo8)aod5%5Oyo>j#U35!>PWFSclY*3roy+o_4Rp@w z>GIf>x8bu094L>mh^n7U4G0lkJkQueEaNOWK!`pUR-?LS;Bbmq`kyrn2(D+vg9+1- z-v&23Xl7`^JufeB+b=HJR(~9@P`?O;zVq`#KX0WMrkf~;+EQG~y2S8a6h+ep3q`Sl zsNaau^$w<(pt)D1Xmd6o=z6^d5*cUaN-%T%u^0?!-ktofv(vr#w1+ zKThM+xLcX0>&}QyBubM%oR7Wpfu6GY64G@LxB~B`@l-0t-Oj%Z@8MV^kM2$Ryy>_B z=w?Sw_?`_ZYviH@lsl?cHB$LWLepG7&F#dK~A{n@{f7se}G=@^$zz>emM0M1Z8n#(5(R z)@VMBR3THBNc^#0rR?rUAOB^r&z70pVo*_D1b5wX{>I+^&;3=Z9Sv*Bolhhb%s`*d zjF*;nFLGhO!-?(>{;_ctBJF9rKc)+_k=ay^+~7Y(iGv_K0hyf=AB9L}R*B5Dt>ky> z7D9DW&(RO`lMs6joL+4ap(9_R)QhFQ75S~VZTY2^W=*uIHNrZc+}WU=4Q*lWZ(h%@@JJ~^z;P;UsUkRk{YQ8y+qs$Sx_C`_?Q zESQTbVcfGE_(FfLxwB5#?p_sQOf%FkpFy!|j)uBWn(g||`D$*T85x?dW)95Mfx$wg zuFgYI=8_ww9Qo-xZywz0mibJZl-q|1B2i#=g;mof^w-SIvF)}BNcf(I_?D@uyQ0~t` zPU>Gx>B#;nXN2ML(RQT<97k*4z%n*W|Muk0w09Uy{~3ebd%1H6;_>mX*O+$2>KK1P zrV+QK=?IySRX?7-0(^UEB}MbfZu1qd}~m9i*y0e?>RcXHyd@$Uj8GKW(O?kZg{5z7;UwoY*E zj$gR>wjt1gF;sxtL+_cxbnt?>Q}I`iRZ~Nqre)^#g#%ZN-Vr9;srF(lB1AYCgvY;T zS*dW-ZxIZ?|57(xD&LB<&T5kvG)dsO#=kladcIGS%sKXGGPn3~!Ivass#*jQ=OEQH z%^H5}#$RgeuJJ4(u@7ImAsY#lP&F`eJ^!1RtF)ePj}EUO1J-|?qP>aHr`RB3!6DWNhdejNUu6EFM7 zZOY?QOzz)$1l%yxiHvS>gp(rvtxZd?X7U4YoJFkQj8$ z@~=-FK|U$}$Ku#KxUZu!5hK;T@aAuq-cD+PUe65_s z%*oB2!t-^r6Ds<8f}CSB2wSXZyR4y`Ua)0fG_|RKJxZN&*((Fx$l4bND{NA`mG$Y? zdW(X4b(REAND;+?mo9Cy{P*$;{y~&1xI3?gc>JyO&WaKxA%9tbjVaxXxDWCsEy z_N}4nMa{A9HbkIpDN5x34Vmf4?_%ud`TrL9oR{0w@4*M2uT1LNXO~r;O4P0w^@vl! z9CqYc%2`dEUmv#wceoLCMvUG1m|@FyAW6i~NxGqFzuX=Wu-t_qXa4o6IVe50RX|qr z%TVI};{t8A)?&4KFL|GPjm3Ir2Ja*k=1>RLWTkON4^>3H8jsYgZDOy#9fp0~%Kb#Y zANOWwS4`K3Zpa$RLTG>IF*3O6joetm3x#-c_b|orK-OvCI+p-Biuhy240g%autP7# z5K=M8w&fRPC*Eni8=aB+dTW7mj?t`?CjFZ1QL4q+S5uf%mD?WLpY!KJ)7b)0D%Of8VAK-;TQ zxZnAkCNUk;kskk;dKeYHqsJ9~&iK6H6(r z-)R3|AUjC5%B%BDEm$*$_)Ee8*r}ScAFIX08&~P#YfciFF9s+dMNT*RUN?jIcH^A4NepA90?M{`t)I(zW#Gkyp)uK2B6{ES+R{LjrDb?E~XaI;J0 z39(ULLA!U*zS~&E4KFpDsw(382MEQIRtx<&$!Z1U>Z$Qh@4E((7tTgYRnA<$NX6T0 z|1f*kQ*ZYe z;H++i=zzH4L+00UO%zB9a1I$Phv?~}dv!y%Mxc$CMEfr`nYOeJl}1>*X8rRgAC|NI z4Oemf8K9rdf%0cvGbelp`#caW!McG;k3tPB=Wr{}H_`1gGgg#j2PH6q2qQYAgmp6< z3wprd=e+oQMUTcBqVTQez;N*=7H0R|z+Ac|q=D24``3_$WL60DI4KcolM7~{#)hGo z75lz?PV9hnT&mp?ecKBYS zjt!$qS4FBckGAjxn!DaKq-@YFko5;apRZ8rW@9T6Q`twZV1ATIQR3NHT<63sjPOyo=JSnko)au0M}`+LYgGN_Lj)k=`$u?zFpLnO}4i55uC4<0*5EgytED=L4j-*dR0)IhLM5BZ@|L!b|E9y zQZ{GxJQ{_?9I!e^KX(s=pQakJppa8}Z*PC#*xzAMV$nFC#AhSbZ>JzIdsxD2<7eDS zW=&7=#`~=Czl)PaUok7%hjsFKocX_%P=kh=8_WF@YKHwK>78+)$>z`|)Mgd_lr%3P z^qPXtvR2iH3p+rq2WNE9?96}JRPIp#TJG#J$h>))bam>0xY$`LHgi_wX6VHUX(}}doTEyAtGu~grwsh zeC*+B>Xmd^(D>sUq({c_f?q&h1{uiWA7)#Ki1aHuvAA#uocDfCTagdEO8y9(*KG8@`QND z;9rWv&3!uSDbmR{&*F{zu5uWFH5Dru z(r54nlymj%{)z*~tzDM}8pH5EL7^m=?%cx)xZh2(1Dz{(fErwiGiSP9n`!)3%)kDVq#2mB!F|3&e#JF z`P313)bMK#IO2$?sJJ0uqXI&IrePYws&z=R2bzxU2}Oj3m0UPx0{{a99<^ z^&#XgxHS23x!*BRw*^tuwP2UZ$4Hk_9uE<~qK@A7govi;}&(c-R zS4~cYAUReLzK$O}33c$4(mA;ZwVTG&p3y4P0AXZTHe*WRoSP! zg7rHtA+_LFq|`|-sgXAN3+(n;(IWLGW0`hulZyu{G zd^+0-?Nzvj8gY_YHq3?gXIRJi+0^ux9>j-5eCql2i*yqHCN69K-?c+IRGw3~pCxW` zv7=9-Kv*vDZ-d_sjBO|Zwo8~LXSpBFVixej#YloAEzT|1^$18POclboNp7)Y`Xsr zE*DmKNJ}{S#7vz75RmUb^S3js7oW~Nzw~4-m2M(S{XI9lu(%X6mS_7oR{`XDW)O6uq7rqz$Oq5D{xbVo# zTNUrEg(1JpjF)N~{8F3)gk4iC7J1QCdwf=N%5Gv$lo}z^#s4iq_rE0|v{*vh891;F zCDuE7!OQ#01#DP}{wA^v2MIpWQK)K8)CGcrQDzwlssM3O2lQ+k0j{D^j34^(e^vCl z#|YAX&XAS9pC!wCy_S1PNVlSZci~@kBinxAu$zeFFjy#FXKaT0hMYqArW04Hxso68>Dd)NsKyk6&^WN*JLEV$EsfgA$qA4uKvDJoBCQ^_P~Z~RUdiH$2FnA& zFVs#&J3x2KC8*NQd6YQ{QiGo17l4TeP>}S~qAUrTfme6J+BPZtG{OMn+KqFx9!exm z1LeaTc;9=_x|-2XtQ*SzSi>p1*tFhV=vD@9EN%wwS@wg%;4nmEH5c`QX6_;;sjEPQ z^UdZQwrldERyWb3HC`Y+Vr%cnOwg0`a-B&7r2O127{dNq*>NF`7Gpf#_7zo5$2N?= zh6tDM?|*V_+*w{%AS9u(L!}T9yhw4p;%e+B?#pde26q^AUBptS>CNLp7vp`ks1h6j zj1T6pp=FWL0-?OYOWxkdAliV>wHn)`?$)5=XY5|Z-1T{QbJ?g$a`aKuO#y2N z-}S>1=ULC_9yjJpiv`60tXIWHis)R{zWYb~DgYY`45i6K`8C+IS^%RE7p;)R7H!NX zp9u$M5cSrZd#9)5w#%0XllHW@G_>|cp&H9g`-S?t)R{Ax7e2RwZA@LU7vHhErxIRX zkw`kNNn>5I97qLYol8CUnC7}ri3x6cUhnnNh_TN!*!TlMYQ=-&!cCm}tDvfz+|#tb zwx~_QO!>CT+|y^|=t?TW`tUR5HrWmkZZ}`X>utBq9X!p$6g!;NJAz$qZcsVr#5$B% zzW+kLnUzu-uF3`rQgr1Oldr0>=6rwtBGlp?w-r~qsz}`X-`wyq^266Tr5Sts{*qF5 zod-H`H71K}_1Hcei_~;}hGhbJsk{(4AO|n)a!8lf{X+=n-RfZzE)2OyA3TKY60HE$ z;O?3F!6+$UPEQgT?d38QfM-(u!OhX@7Q;UB(?YI(2$y{&$A+ ztze;$o9x7bKNvkhQ)_X)#kI&%V7D}*bCvrVMPBO_@R6X8R9TE9b2TtR+wZb=X zV5CDLGqa-11iu13B!2XUitJ7vlJ3_>NirUZ(bg@n51P?pfTY`3PP6gl0{_I%fgi-`NuDZ-b5xNw zvt|e0Cti6`i*5xRNH>pYN5S%&>_py7C(j>sW#D4dH?Rif4y@Kx*_b$U;X%E$`c|GY z21M@}Xe~EAnFxlSxc7}wZE|hq6qGrrPCM((@fg+$AQN-cSQkF?V=LFJiaspo;dwc4 z!@iD_pS{4jQ(A3h!gj4C*gRGKei@1Rne7U^0=2q+afdUFNp%xNl+tkb* zfKfw#DHfi_t?Qh=LDC0r$=g@Nxd#3Ge$_iJPuAl|66YpZ1`n4roZ-J_8Tj%QS5c>E zjPeG#y=3NEfd}}J^e_bT+b3Pm9)2WgITSZqPCwL~&uNu1r3&-P(2n?S6 zvTm3rZHaX?S<8AYq|d>5r-{n0{$=aUxmK}<3k*ie&YTkEY|=fX>&H&rgY~5jom?V= zZ)*|1nnSexhVu7xN1vJJA?uCg&Z4*{7WyOWtT+ep(UgezIMgRAW`yh(jG^(|cI7ANXN=sFSRrR@e&krqd7~bKMV3!z;dMM1dIc ze?q?ie7x%KTCvL==5wkpr{90hpZQqIb{pG3NsCs)Oi3?qR62~9}uH|vs z(FpTW8zfy{4(#*~ z0hI;QSgV?)v3lTc3ab3;ae2OyPh$zWHAc;8P}J5a??ub>S1JFl+>lzl<~lMq-SEio z>TaM=G?;=w)PHy`kOkrGbNOdWn<`2U+R-~vCjsc(pN)-Xt;SM6pL(OO+pn+EfJeY(u^qu88{Q2<+VyHhRfh!42V^C0kZ^ifPxJvmF)b?_ku@cvLtMbXnf7#N7qZo=`m++ zBzCJUcyBuegl+SU$PSC6Csbr7_(5ar?-?kM21>ZFL{ufBM@u?D>2a0ws3PpoT(oN6 zE+efVlKM9@E&lODf9zTczjBtt_TL9g=L}sZJOjS~dTK`-<1Z;B?-!lIp1+!S-e8%d z!9`opis356zU`(7X@zjt!ORum!n6Oz86Asg0gbNzVtk{>FUa44tu>D@m~t)(n#XYsp+($fF*Eo4Ni3Bn)TTV0|hJPjX#PDA4o=y2wsV()(MyWRkOeoVF8zvQHQQ& zAht`MDA(Xv1Y3w?4gAS!xBgJ9@h?ggo1T>@)C*dYs56I(8LGfLE8S|3;yUu&paZg+riiKVLTg;VdnE{ZLYwtkvW@pa@uG<}F`? zSzrM3)L;;m>#d1*-N7PzyO61FjBFORV^_UY)~g??8(POwIrP_bDdtZpS?_^SP`Jfs zYQ@E8ua5JX&qVG>(0gs!PDOGE00zG6DSbz#?Z`=FW&{=`NpTLdmc4}C%D?8ntjBmT>k|Eyn&ZluM)hS z!f)7@+LIizG(L3bY9s+!?1T0b4C0FrND=`kT!B3H(jJw^xr3}r)6=*eqyGLC)$YH_@Oh8! z8r6e*s6Yfrs+?nT?5G772rBJ~bStLw%z-f*xWSr8`JW#pu&b*pPQ8;gW{IVSuP5Zp?G=xd zC0$;B$XT)AD&SfasaOK%<+*7G`JVs;y9-^qL8oT_^E(Qmt8Kf>4YHL=5ntZP+m?;t zC<)Qp=_JvTwab5CRsp$~p@|Wn$*^MLZ5PjzX@EjdGEWqiwp+(z>LdN$+5|P&p*>2O zAGN9Wn`-%8u5NmX2_^4sa`RYj+*i68Ql+LhOV#^Zf0&_4ld(rXFZYA}uS)j*zPpjr z<-fAa1{yv&8oV;IU9i?N^re<`mdb>S*uj#njPv!TNdLC=O+{BH6+X0fCiYLv75AhO z@(fULSj&@QX(4#*>g?+~(JV5wa^d1ITDJ@zq(VmEDyEBr7M9^;o(AyXd_U3yX-eb9 za#JzArCxgjCXlP({!OSWLW}GSKAfC2%9F=BZ=Wvu#3H>5XEYf(N(!v3v1giaiZTIp znplg7nddGe-dBc{G`s)coU?~-fPX7>+n?(>+v#&mk3`e|dI7*nt~$9Pb4dS$`-2`Q zP;SHOhgI$Rbm$kR(EtC1Yt#T(G)7~NXs7`Wd%j_&xpv0mXsC%{qNNG(pQ(HBN&wNI zV+0DE&%KThV8K>Cxg<;S0OlWuXue@ghef+i)ayoA3vteuC5VI!Ti1)bZ|t9yeWNGo z>A%~u`{Xx@6MnRvcsiA;C%F)x(@EMur#X1N?XjdE-8ZMPv-yqvEq+R;qota7bHK;@ zo0t*VPF6*8Yg7!si7Q_-Ll#d;{@o1Tq~7EW139!RWSXL>?UqH~uU&w5Yt;QaL$ayG zyiqsgX$fw7z;z!`MEUetrM?#SDfjpN;A}x0*{DD8>n|xO>6^LKO1E!^d=a=GnkcMd zoFw2BL%E!m_qkg-xh}r*r>-$DNrCu}7QNQ+_fU0$x>NL8;k*2ll66Sc@|EFk^q)fa zyXQr7N6<#t|3!~!bOm83ouHt*d7<$d+m_ti|1_l*a%ir(agx1~$^_6XQrUrs;cMWa zz`LrT^+~EvL2Ec1G$y;ey*yLUmRxA?PbdiOyUS<^h}o(lZk=fbN`f~=b+gCJiz zUep`e@OhnD03hyf>vDk$rTRPP(4ov`&1Qfk#-4Q(b9dQm0v&x&%eqf4TbL0L+@VM0 zn%pl6)uX4!pct8zh}A>WUaGSC-ND)?=Lpfp`$6j2cEN5Grt4_tV2iIqNoBtH|MK$J}4E3YE4&4m)xo13<6w}fr-_~Dl z8mc>hwgnO^Uj12mvh{$^nHt;LXGU^r?*MhK0;UM(s=K*e=%R$#82n0gW zZSPjF0`X1tex89)jsY8cW~0We9Y5O!?mZ@;5Gt2y)Yha6LU=#JGPR=w6>Sr5-#XEK zOFJ${EMZ!v`30HFnit{t-L8`~rA(e$)_CTRRoM3Y;T2(~$p>SRx)w@2bQx~OF8R8% zd{NztB*u$Q)F?av&3I@_ze9YcW#1OLBH$gFs9PFb-<3?woMFZ^V`%k$9xsga?GB9m z(xUm*euPi*J6;It*nHHNw{XulY0GZUW-*`A_Zb^q16!2QM}Wcuct|kFI?v$wgdnhn zTxoo54!XA=;?6F=Qmc4GBadpx2J1R4+!BkCRG9XD&^~+@CZadprf1D-@-%B?sS8S2 zy)LEM2ij@Cz3LQ)v|phmyM(h_4z=I!OK~kTb8G**LR~FVP@iPJA)7r4{)#+)eC&VJ z&)b2+X&S>q1PxvdezB*Z3P!TC?lU@d0pMzCxj&oR^AI8CbWr%!$G?Zv>3-5N-FW1G zn!C}4P5PtUr|S0#`p-NDGOtzWhH`b35Nw+PW|E4Dt~p{+jG!A0INQL`+LHCO0u(5V zkjMiGkusLHqkiEzRZYp*bA2fum+VOl0em;t+FB2Fw6SawLAXd&~Jj zbj=OtkNfnico=U%^wVHkC#hje8?`R#{H>&19oQZpNuCOgW*K)8Px8rOxyZP!$``nn z-U}Re-6-Llmx(#&P>U+}+@H!1+WL7tk#%9VQE{8HTy-mcGB&b!e znU}p}QW1^OguTqGeKENfcRMf9#2yS5iekF`D2ji%~cvHC4aQs^zLCW&EIfilj90bTJo z{Xgf@v)Gk^eo>dxn-*Iaak;D^=7H4``*uOH>XJmlLO6q{L+hoVyQoMkEjb1~hPlVN z4@$RW&Muvgw8$_yAs~9mW2MqQ1}72py?c(MJ|FM1Zng$21GT{I9>#Op15~O2EmDJ| zSG^j%#N@oQ^b-wx=twdGE?MbvLdvt?24%vB4!%|ntZw4v{dXkg&0Sml~EuBm_xD8$0 z-1x}WTOX|3;9XR6B1ujrdPlZk6DKmyw7JEniOF!&lOHJ?_m*!?H`hvaUv1b7C3i zS*hHhW~^PR&*uC@1}x((wxjX)%DGYPKS-~Kt&@~ImEIAT{-(e@z0)1hRg$5x5HS>w zQ~4$qz07nnEiTR!F_e9s;Y|SK6b*aDvd6^IYj`v98Ns7v%y-ms`^=FO5PKFU<#<&( zzw8ioG|av6KO;_k{3i4yYN#eIqsyy?6f?)5`~?Ljp;t2!b& z)8~zG$VRCdMi^&#c#HFOre75AP}8Eu)YL44`_ER3`pds&B?<5AwlGXwuB}51*<*#4 zls#{JG$wHkqyMUA-R5swP`CqXrlZ;`Ls(Akw5a^=15(g1R+C#R2C=kf&J_7!V;^twp^D6&z?|SrD;X8s!2?6= z*vHwMIM)>zac*w7#XQ*U6zH<4Y0zh~iiA3SD)-B_MN*`z_%St$yHb!G>QC6|_%AmH z3|Kb6CXXgwok>Qr9Vad5jRrw%F8R{b*-p_jRavj9OL3q4c6WV6zeT^%aeY$k^0`2y zvWs>iq|jd0M*G2#DV$D0>W#2|Xf5d^c0DcZQ$f4+Q`ss)YJQSz?8(kOiraj4+rp%6 zIlPLApRHBnb-jlBX{E-SV&iWK*VQqm^VrjjdbL1Mjc=3^zL&q;;cE~22*E{q&IT;! z0mMd!Ep=wTYKhWlfMm2ge_Q{b52Sra&lVH>c8JkThE2PaX?;so^YOYxbe*OSZoWw| zL&e99d_DoE|Ex=NTj9filEpo z%|p+A!;j{dIT}#RZ!xa)y+v^@YoO>SGPA_qKdA3%-Qtz~-o=I&4j;`tTl?KqZkM{j zska6fg~DBMiHH+>NbO8CN@?OX|2dRkC6L;K7n!7gc-C9lH~zk9-a@mF#C%K|5jF5FYMojkf?9*3hjRS` zM<(4GZNcSX^*w^r;2i1=w+Ea25gqnG(yE8!U4Y@?=2fOux-pc&KACw*xjTk9i=a^> zVA(AoKqa-nkHvHO_5pG^$PE~GzlTT>3E$0S7)@}G?D=MoD?0KpG%i87yB=Hmg4lb= zJKvv4CY&R#;TQ#`)#y|UDZ;8JswOWO!~&jmZpy2_AYOPm@tWR?*Q@tZ;mZ-*G*xoI zP|55Ag6;F-+$D?K`sC{^LfC+qi>jM{Q+%T+8xpsw97e?0(aBtaXurZvvGSt zq^3{I;7>hlTdRLwj*mlfmlMLBx+UtZLN?tdn0HscAT<1gMy()(hw<>lo->;}*(e@PaI8vyPCd1mL-ds#RR zNjF0dz~+0l3!ax41>NtsEwXY9Q3=BGNquKz!nqkOxJ9^;e9Z4|l^m1@rQx=z@w2+u z%5cQKsLYkN`~C8Bf0W+$&5yA6*b$4EFK@C1JT+co#(kXh)4#EYw6G8G$Xwh!to_8N z9i(U9k4Cjuy(&q7Y59dO%SR4TQ#;6DBPEC*-RYrfYAgJmIx-~yc2U`zlYnr6kH&U` z;(4z$MeXg%tf>1*6lL&rC-?}$H|1QvGB5V=l7>Do;V6wuPy4W-Xj8N%Q&^>xP)iV` zMH-;@N$c>uDQz`qvF(0E=Sn$~WHRhqmSZPrH^!b_Ntz^qRpp6H3BMf;6VA*}wkuuq z+G>O2B`RS}O5%)8fVCaX?7DZGCnX|M!)ZajZ$AOISmQhH-Q-!SCa8FjIh!i^L&9Z0 zRY}lCWp&-Uv9rt=A~4OiTguTl<$=Is$EnBzKQ_xhon{CCvRB5{671-YJ%{^rob%0_ zB;^e4CP`jrrx`rML$0L9;T70F6}^(JEY{3tJSoIb;`FOj>td@z)y&E@pV|5(7~#J% z@0^WRz*lI_FyP8)-;Nne%LG01&F#Q>a3mgNYDOrV?3D~`BE@N`^$U=r%)JI3-Yl3$ zmM9aLQGA5-ncbh*Yk;T2>nx6v+@xwUA(LiJ^(>})pIE<2k$F;)`&frJ)9%?!#b2`FR zzeAx;%nZEvO<{Jl@yhx2Z3J`26+N1GzRqGMptJrFlw*?z#Bk;q3v&E?5+E$@>;Tsj zu+Ta=J2$qr1{@d$cZ?J3B;Rz!?ymQIP1CQRqLVOG0pY$G#@1%GV=$ve;?0LUIxYI( z(R3gc}Y8Y{wadLx)iI=qu+7z;=*Y^;OP=s{-mx$ zRBhTkg?*)CIEg`Sfpo4dXZiK6_+zD<&$lxQikMwZTxD_vVl_yn)%dxzjm!p*=4h9@ zWET)G6&Sej%N^52Pm3eB-B$yB{aZ)MBJ7E7BE12*ujej+4o;33zdq0^o7s+dZRyZ+ z5EY1DOUBN@kE4VtJa~g_W%V7`Raamerf(xtOw9gboeW7?=iA!{HTeb*n{Dv=S;6ed zKNUv(M)?OGVVyQs7b^JeJk;-3J)E1k5(jl*#Y|*+KUyc9IOhK~!HF0%6}S8Kqa}f9nV*x65PT}o@S0%s|MZ=y1Pt7 zvDo`Bi|`h7*5l=2+%z-luedp4T_f>m5Y%%BNsh1f{YO?))|w!tDfIEGByR1E^cF?; z@BS59@?fMVBYo>UJ0yBg29$stTcYuMPZo2gw_hdptNM!JKyA_9LtBeikNCw?6 zKS0;5#k{mUCT}MSH&=i?PTfu^$*SiV`>+?=(D122gW7z9T_No3;fd?PbxD*aF2i0s@5 zTR|413Po=2h_A{p6iu47rBcLv^3_$`#*j`E&vguYTmMr}*iQy0gJVuOXaE73`s;Zx z6CTvWF=yz!csR?rBnM!MAL^pR0!*^cw&x1$W-qH&1Km`OX57nay2?tT{t~1@z~Hj! z_u8qMk$hNtkKc0flQpqKA3?tc`9_<%$fE+dFgq^i`u|2~T1uud?HU8?szF;IdJy0< zf3`N~&yp#qd#XlHgu{z9SHzCvTgO}m3}*LDe(7EtL3;w*pG)u7ltx!)mnx;!KSE4| zk1{GHSW!l=hsMSWzpVZn7}q` z1)*o(xCvwRbbIkZI5OTifao$%md9|ck_+9hS!oS{>Wi_j65=1VJz^Zb%v;uCxY?%A8%xnv9Lsf`m$`+ob^ z*J5s?8OB4=%;mEQLzqtk%r6z|OB3a^smH_1p2;WNxXJu1%bPKmu0LN0R|(f&iP-NR zCH~Vjw$Z%XHdW!m{DY>D@erxzC zH?uyq{T>7VAn&q}(#n=)6rh#(U!D`wOZs;>2!_IaSce|`n8KS8ngIo-O}X$6LYI2s z?p_pj!DqG*hW8qH@_MF?hOlEeYWarkI^HDTai(mZ$sFuqdK_@x+H1)ZhSL7 zj)6)32T=`fl~}|Ub6QHS6A9Bj8JBn_hTDn@j3xFKh;owJPoEs|)pdxhBEfKv8oj)x zM)?50P|undI9O#IpZ3HotyKqW7~X#^z_sR+gOlU(@N|;ne?n3A_}>@#_Ws;YW8lG& z2Bmh(2%LN9flsDI!-84!LI@FTvQpL@dMuvKGkW+{>KgmA0~V2mL8h~i?$tzpIcrBK z(d6;-)Xb#oX-Sv+LC>U*R>_(7mzmm{WPa+t&!?nP;^k5vgJg|eod&5XM^>}$w=Orm z5Mj&y{tVv)BAZ$OiZfl!KfJ*Bfg}wQtKf7qUhebvp%JN&OLB>-)+q z|A6I_2A!oo;S4kP!?YS5^_BbDYZVz)PBShZn%7!$M^Zb1?aZZay-p3??xL*?H~0N! zRtbYsL~`9GD1UOqQt+DhL=ZEz#pjr}F=a#=d?!gi&`G-{Y>98XqFf$wnLdu z=jK@ws<^nP+4=9SGu3?}eYHm0iIOzp-dENS$|@`7lavf{LWin95OvK#dC2eqNK1rz zzTOc4kGjSzC%;%VLgHxou`d&%DVd;m9Gry5sY*CTW`C2u_hr+7@>3#yogdN!;=7;@ zdn^aS)6F;d3_sla8W7}$b0t}GaQzrhFA0MLq4=&&3Z+2r9#$KiiRT?KMz0Oc z@POA096#0=7uUdGuYIT)xN>oC;XVRWP!3T;Hq3S*1@@I3o@(=-N;=FEgcTpWD%9j0 zCHvXZ(i4uPKiJ!*9UUG0WJL*MenIi^K!T9Y>Y(o9Onh&~bkP@?Igf#8tTe=(ol`1l z+v-R**1>tAR?p$KilMI>vORhNddXHP5V)|IShv5R5CN9rTQa(~x%;a2E^N|eR;{1Z z92b79xz#QZY%ds`e})|75?QT;9z3pmw5f&_P}9*V-r*VTN9Rq$l=7N5lZ(j6_z`CP z7L2f+L0AeWZAALX!%xgNk6%f04P>rVGwaNF6tPc~0(WSoenpIgPf$=Pd)`^C=UKWN z_%Hci9uPq~OW_A8u3S&D zj>hm=4Q2VZo8V11<`&^isvt&9&;gQXqW+w?uS#QSnG|r)#7r+@D0pH0tEmXF)t5du zR-ii%k8d!1@9=E!@L(T$1jgS?HY~W6rZilJ3>C1D@WRx2uZLX(@RwzyCWWI{%gqCs z*A-&U^;}HO#BY?vnnSH1e1y!Yp}xHCzIUGzHt8(J52D~W7Q<{%$I-QezA+D4U^PFe z2*TjYn~|io?Kii7dtF#AjNP&R8&pBSXDP5VJaib&ra$y&U`R?k#JZt{tbTK(FKdsT z`=x4_o?01tkK)k*rSu=Z;aeY(k>OI0?*&EPx}@ST%%_=PeZJy{&Naqvz>}CcKjg!mP(2FQK_b38^i*b9VPLZ* zGD|;TdHI>-$7vg}nQg+o#m6kanS1>u`%y3&0P6dMAH!^z;SRS5FP+o4`TXpzoDkyuk^>7f9^?t!1qIwZNY~R{Y3a2qnXAqTA zxZIOSB%~i+TN3*Khp*_}dC)s1eFNb$mRz~ZW2Lkej4!={Q+|_6@qwk?M}8I8=9b>K zbuz|(`Vx&I0*u)on=Y~zNkBq(MSDOX@QdV`N@wVeC|A}agdc<1J@F{w;f;t<2(ghN zqqtPK)VGjlcecRj;}qwXZ1p6>OpWMi?6cZyUjcsz>t^0lpgw|+APc<4%PjvNQ*Rj-Ww?D0 z(+oXy$0*2<(t>n%mw+H0(jwiBbSm8;E#2LX(hQA+bO=N9e>~^>-s}CsH!g;Gp8MWw zuf6tKN!1bVyq)zZP01#TAQWu;b?YDrBNhGHa?#rXRolevQV~cDTGhC>iN&fE58|r%HUvw7@EL=;gTc-*?rYq=g z*pMGig=!wdHHrHhL0TjX`P0qgEAX}Tv3i1vn%BDSnK-1eb=ew0j#-Vj)z{>INCcx5*YZ znWs?a{wCLwhp(oc&2CrrJI@zyxx? z0Q>#eR6NNfPQWoN#=_pd_3W_Kjr=d4uBX;yoCg;O5sI8@<=6QaB^eBsm>`pe{$)wR zeV%M~Cs1(m-*mVULIhdmVuR8KUm*C&lRxoXoj)u4K0IR#yvFCaWI~b&G%{RhWP4kr z&KyZWlt~a0-Ccl!7(jQ;xwFTw`tsr8gkWrr4VVj`|CwR*>39OXO>jm^;q+F(9XVMn z$6bKAmnlfx!nUT$sF@_7jL}Q?8L-sWXfjl`9TsBxy;e)(eR#%!&6zO?C`Lo$x_tVF z;$*VCJw3m$jwx9ZZRAT;1Y?AV<@0LDY~CVT69o@)%2|KvVOtWd&u+Rk?lwvgp!c!Q zTPA3rUGwk0ci$CB>@VgF-~xt!>5ZKCv#!RnIKmaB-NlDmP9UWjj0WowJ;N4PXHPa{`M^J1=9hT|od!A6lrpzO z6uIe>n6|2$HV%>UA>SE-XJwpMtaH`GDowJzrNloV$A{!0ql@JXFfXuuY*8Nup2xAWX%|hA+lyzcR6=t1S>t_%iQp@^b;)~h%SAX(Fx#D66FxqC;iyIfq zF_=upg2N)ke{ts1YHmXq5kVziW<*C*wmxTd{ipLtH{lyu^>LU7E9LqPfk*lOVaXxq z>vp?55NbjeWW@_?3>+)OcUwIKQjNJ*@_@nr`(g)mqLWiQMm@uYh++iVi`@d#yU0fyb>vV+2}FA$ugvL3c}(TT1Y< z%oXaqyzBfS3q@3wxXB(2nY|gdePGDHaVb0hK;Adh-#5;9Rv!Y+Vli*BkJ6X33z1<$ z%t0cIdvVR*OD9Hl145=%-*~A=Xs&lKEc^QG$9wiHtcdw#rZ2)%FqYo?V=CqY5a;Un zSK|f!m+L#lE{(S8M4@%K9~|c`6JAWb7}(WibPl>45DPy_YVi*$0;r1pH9KGiLS_YA?Z?;SVfXelQ4q=l@-)6Wq@H;aUl3N&%NH9$iqM=g?CkgG(0e`ov<@_Is&j%RZ zfyFQo)wREu6Bsbn%uqDgV`?tHU-Lx{J-x5$8Bd&-&!oeSCeE19A(o)}E_qliWAs}t ziYS^(HXciJe=7J{#>e)tNjTRHett8Tdr3)mX2~BuE<0^oH@!0szW6G4DTJ4-Hsk!dwS$=ZItFvT_u9_S^3(o$M;}n8a4=dsIGJM)$xU zNZDxC!Z{6|ZcP@>JhR*O(@Y9NJ8*MY4E*SS|F5F$^*D)GKjUQT06SCvdYt(YiewGh z$u8G{2j_9Xo8}ad|NRFek~v4b+-XNOc}f+2M*8uFzKxF7as+t6Ygtc^_X#A7>y~n% zm}(06D2RaaizF)aY;@0uCkZ`DbhUD)=`cRiIL#pG$yGge#mL z-wgh^aj-8vX&;nZoUr}T)Fo7<-L`;ZBuS2%*Uw~I**cSO)o1!hmyyVcCaN5dfT%=qQ(1JgiTs_Cw#6SQ7A_{Dl2tD+!*gR}p^ zp(z;Li;tjA2FWo0*P2y#Jw<+a-qvmRhtpgxQDwUPmj1UQ1_-}QTexsk+g9FbdS-PC zR_5}{CR=vf;bu3Q!Sdv{PH1zEY z6rPOTI54CLAyV;`XOiAPmz$X_{r!6KHAk8f@Qu5KOt=LfyG0pxO0Ld&?{pA-x4m?X z%aG}~wTlHXx`!^!s~L>uAw-F3Cc1Ckq#XmK+6AS8Vn`ZH)(A)xS$vJxapb`k09&*! zU@1uK;m^vrgt8aq0)WM>tp_CF>8KNlGlk|uf9O{NQk!6)xG4uuc-iOUdZj!lPTGc< zTfiDcQ%qNwBf`}wMWcdlwC-^p-q{6?)v{yF@aUw(f`ne}kei(~@6GNfpA0o5v6R%T zi@>zb(rrnKQfxbG;Asn=<%~019%*R4eH%<=du}IttNU&U&=G#K?cLAdtK;D|n;@LM za1iFWxcE<}X4+r3QOUGhlnlgy0z42Y7FpOP^*}o@9te_4;reNyeGu||_A9}~QGv6X zGx6W=@b@NsS`(gF24<_M#_0Y)+T1d+0n%=#L@nEseoC8mxt8`$gh%;S9eJOQx~SHR z*rm&t*(jBW3=_OnzsK+|lY>LJ z>w4Fy3CrM};}}TTymlA8`Fx-DbhU^dw@~QhjJ+#XQwt69%ZeR z7HB$sXHME&lK@_{WQ#BVu!sNCWlpoTKDT)IIITpm4{s<(PT98H7RJ!fM)EY zh@^`juCHgPv??>9LbRb1IEWy!wG_}RtQqE(W+BZcIy#%$weMZF)U`K7r2#XFzo+O`(dXEmD_#-#FRGdU z%GWs@he3yp77YUAyaF>$5-Y6lX%c)RxLi7yz0LR@EqlXxLR0EQs6cl~HFVZ&6?r3% zlu!(oN4n`TbjO4J?InZ4yMqvfBD?!Q$u8EVbjt(^m>w?zaV4Ba!J)7Agcad67(+UC zd~Zl7!Z>gyd>1b}kYTsQ4w<8?1m2l0C?)}{W7zngrmz4b_HT

5>fzo!6-_dbL1lo6IUUJ{q(0I!o&a|&H-pP9Co?}2~A{5TM|VO zTzDzVvTiyTW+KHY44*=bif_WvZ@MA)G>_X1!_NXAwpA6IxA;j?wt0;kNZ@1NCa+8J zLS5=)Ot^Cq!Z-YBTMMaKNbYgLJ6>384N=h_Sdl1Aqli_d$n!yO%@6|;5+|)TA?3rK zs`l5{0gw&1=H`eZRV}iCIEx~-EI^?wi$_;ZbwpZ8f|xM#@#80XVd08>`;B3zZaC$D2gTv(+G$w-}mxYed=R>@zpPXev@XO`J5Y6gU=@s zgrLAchGP+*UKIcWb+1)K3Gn78^;|F>zouCY01h6$`q+{C0pRY>eB}BUzrwjOnbi|0 z-e!`SJpojc?lrxF0Jc)m1AsBcmI43=4qg7((TBe9+1sCg!^^bFisr{bL=1UPE_lv$ zFC~UAef|?bCW_eeH~>(VB`ByM8*TLyFi5~F3W<*c-?io-L~Qo(OS#Q z%qXJFl;^|YV0~d}7ouS{jEn?;4#cFX>G%5pTG}#-q8Gp9)=%H@pBTYaK@eu%nkHn| zQ(Udjo5uQC5HFLJoBA|=%q9qNc7P}6L?Fy8=hn(Lr>(7K-!1lU^F(8Zhnvt8vo>ma zY$b9IGtP#G;5N=aqXiTqa;0}*cINc&ymyk)ICS|_-E!{*FMR2+zd9JKKm5Q0i;GKp z_Us0LLzi56_>xP9{gt(~l|2B1Y({Fm`Bv114K8-NWnVV^@OO8DP@HGID6 zGWenI-+4L)01h26M~@!ew{L&Hx1P2;0X#j^j^R;20s;aMKx7{&47|!wRYXMr(W?p( zA!OwVQnBhNp{ZX6RC$g@@;^Z1c_2exng;+RQU%qrw|YkBHBM5LF-t@62(JJN#H3ac zu#Rqnh*kPjBx9Vjfk-l}4n%#TrDA<`Wo}`~n_>i^x3V80L~oTt#8I3&=ZuMcFoJB@ zYf+ae1wmx29eETvPSYaGLckp$=LCs;kBl)c*y*SfON1&eicFE`QDn+8k4(&r;2a|K z2W#EVVw|)@RlqTDoV1WlVoYQRbtG8NC}Z!JuU4yhX9#N>EZrM{E30~qGk7U&!!B$D z0~3sS)s)QY*Ey66h}*L&J`vE}JZj>GjMdm~-_Gj1RpZ-&?&)QuAd-j^5fi0*_U!Fv zz3%SCI8Ll}D<{v8T5v)A6~z%CojP;UARwqJ?b*G{M6p%ZUtJvz1}d(drUNS&w_2$_ z`0#^H;aSgqK{o7V+2FAwk6v}vmCXF*FMp{&80_7DARn&x`|FE~yR%}p<;(r2PrhhJ zqp<(^2jO45W{W!i`p4n--g#bU8O05F{xzo_IJM`>J!5P0$+$>?k?|jWMI!cznP)xE zqZM^+!>!{eJ*M@nop}&_w&}{d&{H$cIlZDR*hKe-$b%IbQ_)C%LK!vQaKs684}ysE z2~oq^Fz`=m%aVwUp)q2}H&QJK02GP5@j?hN4B(taVwBK*sJM3pWMZeKRB8!8R0%>X z5lL`B3Yq{UfZR_$koHXl)1}DH=Cn}v!!I>YoDhdFo#3UlY#7)(y zi_%t{#GqjF97RCE%Wp}N0-&`P3B@`DjFZ@y2#IW&JLg=H`$apMSX_CgECIOH>CDf~ zMJ76P`gFJ3HFI;zWwCbVbZMO{i!2)w^WM4c>3neX)Z@ML9Ec6ddBu)-!>i$uqwxEG z2EX}#!2j^0kW?|te&(m(`+gWsFNd%H*I(`c9n;jN7RAt*NJPrAAgY8jL{+VgL_qZK zKKYkhHoG}lQx|J3HHdlt*8{mHK2)`tYzP|DhN>JseEE?h4*|ekpZ>`8FMfruFCxrP z(*i*`;FYUW)Z_5C^r0pQ5PUq5{5)9MO7Oyx{a z);bRq0CO-SYBEiPc=u;+d;X0#dnUriv{x19tUn_WI%f^XOhiOZER*5Lc;GEV#swU+(z2BE}?)LT!8fVJu zxY>9A#BQrU=aPbIM(FzqQf0eCF?n`B%vJ={#tAu5j?#9!-CJAB@;uLnh)7Y~ZFj6K z#o1ne6&1Xm>h*7YQ<9{^e&3emG#7L23%@T~K6TllOV`)dzkc7n))q;`MKS!+m+skj z;PBF1_wvgwd+7eJxpwE|$rD*Q!&&LXi4zA7?0@XB#}4eqo%8 zv*qA^Ja+8Z!Gi}*tqkI{rK*HfF$Tz{5myDE3Id=2AR>eW%tC^Iz@z)`7uTW|5JatW z4o7eraNCnMJ}sy?spEr4l^!*m)khT;H_ZB~+HTKUE^;Pq-^;)Oy)MvUXcm8Ga4u_`c=xS$iR zQQkA@#+WLfD*E|f))v=Na&r)^=T-$STJzWKfJ zJ2r58@@Uuyx;JK9!tV`-+>Pp7fU;@J8;RBv2W?C7e9mQS=$`IT<(sx?yE+{MZhIZt z6uQsmW=$!O6##sC4Hv~Es$`NhO^3aHUKVAMAtIWnowl4S)ww~|Gl&Ri;-uAXn>fja zLuYM192&zMwURVlAD(j7K7RUf6GsR39_aT64?lRnb7gGk$k9jgEEk2j`NcyA4;+0Y zm$bFKe5SCoot3`1w)Uex`9JSq6!!iOg$3BMgt!4ea_jGY@OPIkU#$FE0+-^$`VgD3 z2f1<-0uS!QwLnMQU~mAyhdWVFm0%1q9*VWeBWRT!$*DtZ&6T2LaCtQpB+>Lta1CF_G4%RrlQ!uR7J*QdwbzMEs5-*P7*iC5 zi1R@YJiR62>I|xrWeW_O71yWv7H|5(&iHMMUAj@F3t6_lgbRn_<9K*h3WqIW9JWJx zO|LAr*Pm^4XuCr)-I4;Jh=6kdU`z~5?YJW%!$Dt4E6yU3i4!j#6-Dl>MF2!%6DO?} zh&plQAQNYaDD89+u-9Af1FR2*S&<(&csMS~Z=HBd#2F$sY>%#s!rp!R=jZ2_PoFB7 zRORTgN76LfwR>*m%<@zxcc7dX9b*jq>c5BA`~*DXDP#Me{d9Q4t49jezy26l3+B9| z277Jl{{8zwA&Ek&kvLA93skM6t~mL=m;G2#=27I6G?OYS2qG$Y^&pAUzrSM(JJB2e z$t#J-I8h?+q*E^mfKXLF{i*-=nj3CnHX@@ayyId7s_MbRmjlqTBj38~(;vC^g*O2q zvO)Cjogs&dzXH!^SM4Z(4*}yN!&gl*MsZq{nF{Pbc=_>T4*|dzKmXBdZn(KJb(Ti7 zMQv&Yk9_;)z+>emMeITl%Ja>~}&{DZhNz zCw&X|eD3yZUibr%;cO^GJXl}p&Mh#vlC&-2*4I{-cC`y@leEhi5tE5i=Sl$h$e+CR zmY;sBf(cO`apZiYqq(h8e@v{dbrSa{2&_%S@lhii{WRv#6vl6(Mw(sNMxC?l$!2HU zkaF@ZPVU*@%;z#|gs@8^7H?Mnr@A+t#cAitjI2r9x~z?;pDGy{2tee@VQL~a34%Lw zdZpd&KK|&jKm3FD0KiYa`gPr1`x&(8tr@0amUTMwh7A(D=5@cor7WL0_9y>m@K^eU zH@%}Mig*3${{{drdeQf4HhB2!UxBZGW$(Vd0Ki0fHYoD-J$nuxK78?dZ}pQO`-lhv zW0KPR+zgBNo|(w2ns5IAfh4;k%LESi0@KWL;wKi#5;dNBdisSa9eFz zSf8>KxN=Y$JvN?;RuBZW*|3)lRkhXb04gv80;qU`n*!ybKEE{+iwc5*3ZVf&FKr8g ziU0$XL8sOhpa5jomRCBRcHEu^AVLzgNQ5rTW`yWK5xCXu_IpC0nrFmJ#LhXaGI=}e zlmHRpqy>n8h5!Y`JHw(O6}8S1f)fXZdaJAR^YciCjd9L8f#I;%?RHfNkkhy|$a(;_ zbj(q#)*&*RNSsBng|%~wPW<9TvDOxc(u9I3+zvN#y!wQ7i1NZqjYn{iGU*gSe? z>uuVAJ?K-YPVM(KkBX4iLfX#XYKsL z;@-Xc27}&RpZf<91j0C>PNy}qqeI4>jl#ZDQ5v@_b=-hId;bSs{IS~iJopx=qH{p4 zM`3*NS4AoTt&BVBV81$w&J_r3Re90J7_hQ(41ip>0{|+{0RS)ssXL^64mwH=NTP@; zwjB0XukOs>U#tERg85_!*A*m99|X7Rj8+Dfo}UpPwUEH5s*fs);Icu#JvZk=ejuV& zEz}tv1QdbdB+XS3)M<%C7+j68GW0|B`TLOKv;|dgE~#~*h)%^1FcJ<2!#IwOiNFUm zC`&{v^Ndm^Bx52~&GW3)ikyfsF(D%&v6*}JZ7W~7Nu47S01A@r1cr|rF-*$d(+>nr zMm(=q^k+-XggbmL<-91Hvp#t0fSDA+g*bE7`dF5D*kY*bE^TW~aIQDt90{n+ngjq) z1O@<9G*Jwod0xbEoDZ`i&r}>Sr`su*wKeQo)Dt7xrk}C+Vk@Z>%G;-j~`P7WFmqji42po#W`K+*5!OT zl1_V)i}7Xu-qGj1dv?SUIA~K395|R4!)|9D8jEmG!9YXiCPZd75+MRp7uBn; zf#7?-?}v#wHt~cMSlbswd5(y299M?$;n#}&32|hc6OmvbQ-^)=4Tjl66;Tf!zT()C z2fy&yk3RRhmnc|4s)_Krac>CITtaxeDxxY02*4u`eD$&`pJhy>;>5|p!&e?V@+|-m zv54q%ypEh;Mf_^VXGa2n8hw$_C--9JdV#H~&%g2Jq9`Ine>wiVOp&urKnTrqU+~g< z@BD;s#92!KKC{xGzs|(1ZbC%uZb#N6jw0uTe8Ya~sop>YQDFH0$b0i}%d)FJ?6=n5 zXSl-~YU--4>Q+xuqj_j`YsLsfBqYYzpG|Ck7#tj8>^KtnFa!{B1dc5%uub?dwuAE} z*f=p@eUcEOCBVeQYDwKKi4tm%x?4S0)vNJMcR0h|Yvqr<&$;KlcVE@3s#mS{m!+rb zd(YixpM9pa*Z!@wehUhk0a)F2KEfNh901tDT=+mO={e>M}FQuQer;0Q~TK ze<~@blM82SQA5(pvjYbXcxC6EFGv6Um;XukNbmj8|9N!wOj#6v?XUl>ORE=$&KIjO z0rlM3bKRD=Wc_EJ^`p_$rj`vvr6{JsEwD{iR#tAg<(AW@Pai+JZ<$J}_~0+$%-Q($ zL;n+&7xBz<`_=sxIeyfgK7IPuTW@{v^N+;5ca@NDX^kZcK}OWxrjWY>z%aZwsv7Lh z(Aze>ZCJebNs`R$@6biG{goM1JLjCQBm^FYUji<}Y_vIWV00O8tf@+tl?8d0S7l*r z!p4#%c-0WpPH~OFY*b-w=A2^#Re0wCkdlacRR$Y|F~+&tdtvzC3R2O;B;|C{8yHpO z{hssAur)A##y+MBR8^Jq5{en71d@(9xPx4Ij^6Hmp05tBcKa5&9@Txr)%Nws)%q1f za`nyz&!_61W1sJz>fX`wR@Dsv@JRxxymLM^Ht+X}$*6Yd4VU`X`l>9}E;&&q$+L8! zzbK&Tbi(B7X<2~s!LZ*yL}co!SiN|mt|}s(lyz_EK)JEGzByvf2TO;R7KW~_&aa&J zQjffvA*a0iVnr@X4=57WRMrPv-u9)w0fJLcif;i3&zlwJ9DH z(i3)urMC}X`0Bl{>q@O9ja2ciVHq5>6pJr$Oa9U%fpTN9HX(sCtQQ&zEjedx63J+o zAWbf3(|=$jWy9h;HJrzD%n_oHimOd9QRs)sfZ)ADbjXsZ7x6$Mp*~2o^F4*R3NY44 z<%x(vY7C$f-@aI3gJxFF94w}bqRo-5s(4OJAfpgCKL~on5zl{$8UY{>1Q85`S2gy^QL#HN=r98%Yo{^D9kPN z6Gw8-o8I$<&we6~7EG+-MMOf3%*ls-|DHF#OSkf&5^b5T06g==Bk@xR^6Vf%XeQTI zs;UYwQ|pf-icypC5MlmgPLiaUXjN6YdS>z-%$A4&3Fdpe3x0NGJOa)0Wt??$wqMaS z-)~Ih3d6f*d44O;(H~kN@;P{JEd~iTD29pP6iKOh;p5 zjkQ)lS>F4?r+;hiU=|h@&R;rfZI)-fJRgk5qr_5K7W;Dzt|Wi-S^Uz!il6_|cj3F= z4RoAcH(FXM+%8fU40;X4N)h>PnIIkY+o-sB13TavfuPbb2Jm**k1 z87H3E)UM7|h^>gXHX$-`9TiF|5s8TRp6ZH;e9Xeyq8R6zYkPrU_TJzsrK9ow^ES`- z2%|R?N&xivP~BI!UpHQLx3&s)sBR$CQS$;NYl>-6mTs`H)E_R8=%gsTtH~y5mJ?LO zm$e&@M|qx*v6)SW!=Z}SbyZBJ<#cL{vBn6HrrGkr?BJoB470C`jn#|OvK$PCSy5^d4mTc1pY zYB3q#Vr-W8o(Ss&YDkDBV*LS;i4?xtz(y3SUlTY>a}i%x1rYK;C16P9bmDEA<$VxB zq7@pH2eZ5{cG_XC2h+#&kG{K~zy_bHheDbd(NiG0&sLn69*xus)yy63LovL={?zGzv z*Duez1-=*Q_~y~LqOPr{tJvxJxe%9`5*mAAyC&DSzxsCxBH~1a2*%oJF*U~a1_Q%f zl|?Zg0c6v(bqS5fBkx>d8K8cz$JPR<>bjmzBnBVAtJ=J0K}Uzn1Xc0V$*3r%>NH8& zi(B8kWKC+5#M-oW6_b`lRWUCN7jDqi*?%}j1i$rh{L241+w$Lj-~RO6cvEjV`N$J! zkPB^U7`5n3OG!I}A(*^KgxH(tyXc(so|y$2tke*{C@uCtBvCOV@~d|agc;_-0P;Nd z-d9zXBnfq*W7rt)>NbZ+#f2D|FMRfsuYdEm0Z@$2Tg=Zcg9_TM0SX#SO zCB__B9(q??TD`P$kjIW4`_h-bbl-jVef|Lp>_hzIc!Hn!U*hL}4?pu`u=@d{?qXhO5;IKJxA1m(8TC>@VhV~E02{-Gz4z^_r|P|v@wisi!NRhrC*p=SafV_8Fl@XyViqrKK+42S zLPR#pQk!J!>lYbdi`tb$Br4PCIPdqFY>3N^VT1(ly{fV?#N>suG!MWW6RT+l7E886 zA>Ox;dZ2)>%EGWAQdVWQ06FKawWH0AMP{4i&WSO$Kj@9elfVaQOp;^@Vq@T|7dS5uuGw}riQ9?k%zM1x@{mwrS_4T*dMCqNHi>-93-8#bL57F#@1i(=tXii)ihu zEYGdA#+XpUmza&UNt%eSRkSQif*Qjflw~zxzvby|2zi$P z03ZNKL_t)+c<)13B3>gI0^R$TZ-4lK-+A`QF9W#!&Q}oCf!78Avk^E#f+k=-piV?& ztu@BJ_6_g+;|D+0j67b+7SL%=w#A-KKJaC@*r?_AcJ-||!R zmhWtIjX2J>?|adQI}2}LZm-TUcG}T6jNY7QJYWYPrQ z7vt593oFhmfQ`|3b2Rz=-}%+h-SOkMEG;kO*>H0-)@odP$G~`!jK>?3={U{I9e3XH z;DcXy;;~aIa`fnOlGsa^R*Pazbj-11$4;F(b^Q48(<}Qk#s2UA7e4cF{QSZ9;~QSQ zFTL(6r&sv+@#CjXol3JjxB*3lBUwzCfrZ*i$wUZgKrzxpMYOGLG&5>jxV8y4}bv$PSbu)H%0xPp+XWM2ctg~~pjWx1^ z?qROX9=h=LG97=NWH$)ra=UcDs3tb8rz3zD7KTaIb6&>dO;?mmuxXEtt?Js<9-t&i zI7yb5mjD%4kBee7*|f%RlH~pV=47)hrcXTfm8vLglJxUzV{OfOZ`t&FHzkQ3PbSQ| zv@}%sm6daAtD}PlhDl=Ty51aZ?i}aYvuBST+h-Q`OP%VgON;x}>wIZ>12(HNz%d=% zBq9RAqZ##7v!DuLOc7&m%sFb3>zmyHLa1CiLtmPJbZW}xX@e&OH>&qOz~dp9B^*^- zZH^c)RaYeu*(AN&*vG)2cA*za_=VYpq#@Z2_(jZbA`qK2%j>H4zG@dBq56@cam~i@ z1wVnRSBlU%F;SYNUfO)BI8{ZoMIkE8%rTaQ0eJ7?`4a`s;9yY$>gw7gi9(4PDr~HX zf+Un0Op-Lvn*}GduYI6bR#k}iuBIeIdmGxz+~IwhIYL_7e7jt=;@wqOUmv#KQD0Z1 z#+xT>D{i=lk<9Tb%xkm#XuC`zyL7A_{k;2rR|VSKP}%j$H$$Ai{@P2&!AcV+*4lor zr-1ig?hM@|>tRie#ypYOdJobUa!x(Fms;^+2#Q*73u|wPD?ta}2|Wj$ z*xeEov@xbzG&&?kbz<7%N+S@yJp7qY-TRjJbY`RNs-cCP8k7X8(oIJSfXYmXFh|QC zq&kav2@R!rXI^p7H#z49iuUxoXVG5O_8>Rk_Odfi|Jlihe*e|?Zn@L3W_I)+u(hdk zA*~mo3M&BT97vf7fcG9`vpkC@i)~bngwB=*JKlkP?DdhFEzjDExi7IWyJ+95??t=M z(rz-Z=WB8yZ2x}QPFj{X%!ar3qwWgyJP*=A_c|N*FoiZXEYVreXzi;1?ni#Q-^ ztE+2}vYZy9ak;Q`Fw5-5#@cveb^P2Yu~{Y4!JxOcacO;RBQYu1yIPs3D!s}aMSb+> z(KBaOZoc{EGiUeVk$&t+{EvS>etzqH_^=v%IkloEPMkP>`pnXy+kz3SqUajs ztya`_;om6yhAnZ1gHT}Am6>@>%!Yx+0pHwG)vgJn8shz|Rn@w#+pHyH4M7m=Qimn6 z0uWcNuU*X2Y`A!c$aL5iX8}Ie7zc9Qc z`g74B<6&tbOpG+mMN4sFEQh(rImb+@YJ#hPLv<>6kt8*>t2fp!EiE5XjWl2cSZhl7 zqMYWvVYn(b$q=wwg|)b~c~G@W?Z-a2GD>G`b4i zJL7nbifYYfyuId~*w<5a z&kKRs89}qdv9VKilR94y7Z#H|bw#zhddc}Z&w7WB9+SE(i|J@|femL#nj~qyG$@L) z7?(sc9$hjv8RWgsJ^0xy%Z?m5bne{Qjg1ks%9FGxy-Bj=Lx;xW&FOgK&%W}f)+P(f zgXQI=q9~tx_O#`MA$92>w7R;XGAF|DMzFA7xH$W~e8b_Gz#DLU^D9q;Ezv-oDS(;G z%*b{QrY%-(Yom6vJ{#9*L-^Q%d%_RxuOT1>1_6{|!y(!w!X-Kb-~p)msx0cd>h%XN zG0CIS#UT~JBqK1hxDX}ZD4!6tqA+YZH&veO2@c2*n?uATaoTDfSPe)7V-s~w zMVUG1G~blWYkiYpY7><(g-s{pG|R0?+O-TDHo~>56i8ANX2v8*!?LvjgA{QNqHrt` z58^aUOA!@mvtimxj*jwabod@1gk7Z@>JVX%eOe9fZhl{(|M_a1t}r$2cuDti5_8(@ zu)wd>hjwR-tCp`PvfjR=TQ~022&XNY9Ds_-aB&FHvMj5*BBDIc4WX{<>3AffY?#5u zT4R&4D8zg3>$~uQKd%gZ}u(`1&QlB|-y5gHEXOuoD*03vMf~@DnxUb9QQ?T6n6}OcfK7jyL&$aid%1LmJgM{){tXs zZHOyjW~gUlLt+jLL6u>;u^zEyD4NAYq^+S7rxOXWB(v(L07S$&$6GR22?*hj3c&lC znT;{tyHEv*t*y&8XP9h~i8|Cirt>3u18zR?;xnfnfB1n<0J!%p-vN+{Flj@s0%mJW z!fcvpNgAFD-1pY+eCX4^4dAJ-efdRqz9LEamKVL`xn~|zktFH6ssengVT06l9dM=B zzxmy%2%+{dxSg#vq7^d}8>u3Q6Fs^B0NVunD4VjH8iQB8{#*X!^Z((@sV4wH6+#|9 zNpt6w$(qzU=b5Rli?W#Z27Ogdl5{%S><<=`rZARuC9=$`0trDF3guazap&$|(UjMw zmg`o$Y>VuDJ#eL#+f0N#?sysfcsbR1O`(`Ot!mz3#qMa+tW=w`kmeq|V0@;XtFbex zb`A_P69XtBC5X;r{REK!P_kiZsa(}cMzol&k2ahL_ZJrXgPWOYw0TLz1H81nY_rsr zV-}o0^=#?I82;SDpZT+sUkH6Z@#vQU{JFQk^WtNVh_6Uw-MKtly!E!1KKj*@)p)u% z9E_)%&P|_vZbDE3^|H)4H&|F&y|e)pz_Xd7sE-{xcJ|!aN<&*nEkJ|D#9_ole-Mc{VrC++aaBdkh6Ers zRta#y%Ni~+DbzbRbzZ=|UO&xxA|&b{5)`yyLu^RmIw3Fzi$sU9LYSyGSg5OVJoYw8 zMV$((sIrn;6{jR2Zig8vG1U|Rl$qHY6@@y-WQoWylL5$xSD>lS7Z4dIhFR)Lz2h`@ zB8K5XX+9`JprSgc3B&}(riL?PtO&$I#n*L7M7{n{m0eYlcrbI4jwct>oRKbo1jLBJ z@1fq^R=pj#Yc6l|P^wy%qsiEdQr;ity~9K_ovf<}K*QmJO%qp5U0JM-MzzR=ixlB(^OsaL zOH=QBZ!p~07zG{0^LP_iR#r~zHw$~W{@rhV9QXerzVrz0x&yCy1zz)VeD}9u(BH2^ zMc#m0ZoT!ZU;4AKr4!pi6e+7_F2>ex+TDnGXv_8&QybsnY@av_gvM>SI)Mn})weFU zKxeHY+IeOOswxnzt4b4sNwyuXp^#}G%ZT5%AuIte2{q{ghN3=_R0a?o(1x5iF7#De zCMRO1psyv)K2fuUP?|0Sar0S4#Jk#B8wL^CVVJ~=7oS9Gum;~D0&xI7L`1v~RmBMq z?~M)19%dvIlQ`@-w|&nVc*_@>|9Q`{bEnHh!0h9C^MxQYAJkTvcL81~s=o6? zUF+^MT@wGRfMN2^J6G4WOA>31wQ1_A3IIf`F~(X|QIWDJ>ber|i>k=89XSyd&V5Ur%ndc(nRX*wNCaPR?uOp8fTOsmReX(rx7Q5IG7$$>y~iUIDI+(00g?>pMW zhpZ(44?pnnd*AXNL5xxllY#dxq@;$*rT_!Y(N*t#%XS!&z0x8iC%x7WVQjg+mEpkkZ51HhFN^{IPdUMTuK z$aa*iHF&x{n9JH+cK>o?EJvv!iZx8zyzxS`LtzUfnkuMy-={8@v3zwc-SRAHV?`vQE z+`Ler0~k=g#1JegFVI@OQ5Zj#*nrmL+vv6A>}D9zr%uAQvp%)>Ee% z49+G@fkPZR8y0C0!{&i+V`L1Q7%~~U(%2OdZNUgs*%GjVg|Y%6=pIfNe#1lVX_{g&_HD4#1lAxH{xdzpkb&1 ze*r+DwyT1ey{`=ugF!QPGm3^eM5V4ulcb`o>aEFCRGGzljb%_tp~e`fiuW2|7sI~r zfU0;^fLT=;WQ;9~$#`S6zi42YI0G4Kg6P^aY%cGWQIyv6am~RmSF4A&trA~oLOYP+ zon=^>h2LyBxAo$^uvB*|VWkdqM!VP40NV0lXU}m3tOQng0vKwcb?pJ|4Hol$pMmjY zb2=IsWBP-|te1-lz+NDVG)pdCI6L0lJb!j&eQjL@H{W{8(!#=1&pu_@dJjQm4J{v7 z+}t>C6Up=Rreh1wJU#UVwDxR`0w2hX7 z0;(b*a}`9yWZAm94(U0;UCPX=Bq9x35)W5bMO{~S_J>abWVT?!&$Iy0Lsj&2QEOX17I z4}2mZzp4^;qS?d~rOjFb&`exc?ERoi=Vsy(KY?l<<4_YX;d#*VG^pMECaBHvakuZ53{$bAg!R2{I8QuF(UKy8GX}BgH?au(xpJ@?(nhMMPRVx3IXp zxU}qCHQ87jjW^iP^76qnNvmSIv3{wTgkm=|TwHd}PsZb?pZ;1n!e9RWA1b{(_4G4` z4j#GX_=zJ&4lWD_lW}$F;-$%GO)(iPC+VPn{`_jMmks-US65I8uMa7RK}?EW--SEw zyzBh=^Y8eU*FO2|jk+B-NS=5G@A#J2oj-s6w%hLl0F4zcyz>qAq|txa3ODvk6SU`@ z56`TM2EsQG#7nTHy?7Ok=(%VYyo-vHhz!H9_?Ype3MP{zX$&PJ5|A-$5)<@xV<~H> za9T_@*VZlqzR}e}(4e}54i7{C0GMa!Oc(>h42DZ=Y*QRiKq6sv0ky^iH)vZ~DF*nk z3A>B`~ySHA2(fG zv+BOw2(MnQPj7>i!(Y(bjEg~jp1*2@k{T#{m#YV&{Dd3>B8Alk0;sa*zNtn zk=z3d3;l!33*u{n5RrGzl@%FcOR~dE3Uch&u~W}Icl`MA(`Wa`AzI8S-?T*@{35>P zFW^gmx-Un=>9h9u@#D`u`|MKQLt|H?WynIit!r1$m}t>$(SR=jd1!m+@;|n`1dTLS zHwYocwZU{$)fj7xrLcYq<^o4!xU;*e3RI@!O;?vtX+kb^=8snebOsg&gSm|zQ6x#4 zWj$hUjQ?P{YtYqgtV%pzYLtKEe-CAo;!h${yE?E#HUUN){)sb!s;f(gi1(q$H?w6n zA!c-71By+0Ix`k7zAcfAX*fAw|s z-}R;jlhhbf*LAD(opXk_q@gxHMbO=QAEE1kqa`jI!Dp0YU*2~!yrRl zq((qw0+bVQ8YX_j+rG=W>IKV~ey`7X{UBQ5FJ%Qb6yRk~Qa5i62w(_2YP4nAqX|{*% zyQX&>uJ{QL*Qvv+DkI*z`G@>aKGw)ZVhrD;$l9>%I#@Dhdc2PikSD zswh>H$#i|aDyRMapuc!?*2|0WhLD?#HirGhB+bOv@P4#@;aC5~KMfuImGAqTi^~TN zTK>$ZKU__xx4-hWp4@-LnY;3M8Y})Hj#s$dq zhkaEH2HEPxi(MkBZQ{Iq{No>g{k`w_&5wQV)i1lwbAMjtH$O)A-uKSm{_Wo`YmfFF zXM&)ydX(|Kk1#-@@VG$)n<}z1#z(WlJj$}+#R)A$DarJnkTt0A+*s6pDdAt^EQ&Ck{ zO{e4KtfwGj3=`QT%lq&umXnwaMHKw1)9Ezt_n1tYBz0XmR|f`5gn7gR;?+AzY*D$y zxg-tmAa+%qO$h2$BpmIb@e56LUz6U(*08DTAApHV&He1NQQg;lp*pHNUjCWtzRsQz z!pq>T5fKCSs;X2MML8PPb(!bAd~i6;({egi^5e<4pAT%3ia1C$9ZfekH(qqdivcY2 z&4YzSW9Uy#{$X8~H{W%)kf((D!-M1U+1`+{Y*1J7_#@}o81_1zj1(rx2F^JU=e=Bk zUY>5QuSwu?+9CVS!rsgAv0uZF{R~E9{P^F&YhQuoC7fQtuYVZ7_8YTi@B3-|_P^eT ztfhuG;PflAn04M&ZabRKyvm(7Vk^u6w0Ws$6ty-^)~==9{i;w7S*J}9K{WY*uNixX zh)4snG|TsHKdJ)I?NyZ|U}GN-0fo(31X{_NR*O?mcyL3|3bA2htamc2dlb)&A_sgd z{l@^j_@>kn00f?RZCnF&Rc2W)AR)1{$Y4r=cgA}cg31XXVj?h`@TP}Y7=aLxs6Z41 zX2V3ra71~+K7ouZ=KI`wtLG_@U0(Y=nuu+y zeZ?(y9{Q?Y(yyB%^V($Rgm`tkU*>eLHP~YYTm@(oETDv~_fDLv>k4FSk|ar5l?9-_ zu9?ZES$NBfq9Ep_r6n)QWCnu;1)bm6P{5dk7}gpf_ga#X#Mm^oXIEAyld_lh#Ot&i z8=HuTh!PoqlGJ+d$cOy-*~)j{9@Tk zfpAi^8o_8kxYr;i7A8|R#AB2Xe?V=C3MEc(L%V2!cj zg^9gNl4gLY(tU6Hu8029$L{~||NXAN@ckf}ot8p7?{PDYc2?b2lD64pTF-9f4N>Sf zTEbx4^W*)p>AThv5eGNbm0F?;wR9R_YlFQF;A(C|sN{%iy?5J|VPQ=lsAW7Uh#=mO zw}i=PWSDxxg~7r>YwTpav9YnnO#Q)9Z?MdUrkkq-`4_+Pk3&~~^#}gu%|~D4yqtRO zYljaW81zp3-X}j2e){}FpLy+DUUdAHo4)qwxy^NNk&%?sX{BOK!o{=}p~Hs{+ayu( z7tfsySvz<-hu0{ga>l@#*|VdyvHi=*q6Yo_qwaeMkKK^1JcK zAMM(5@AA=4X8-;p-}{3<_=9-><3Jq0e`%YoObrSX&}4MpW}*(QXSZHb#KEbl-#H8T zp1tYP#DNFv(?tkaV@P;pJ%q&4NJJ({;On$<1we{W=1IeEom0`estBC*1Tdnq9Y;{K zZs8eCK%kN#u(4^LmUTrjrji2L0kctsVRj+_ya+RKQ_HDU`|Y(+m5?YAK`4@-z>_p_ zzE*;YCnga>NVOtLl9Y)>oq7=42#2XwRhi|fa!B?vAYx)>8}h|Ed}0JbNc)Yx;jaC) z?d95o2I#7k%jkjs{8jg5RwvgkJ5={x^fuWRl3`O!$K&xP6Xm^O)>~kvVzNE9nB6OJ^0+ym&PM8NJ*=*s8tPHuAPHoX=&M5t0L>G7rjUa3f>|| zj~-oF**6w;0L=K#cj9et0DuF_apNmrif{dMxcg4L|ATSMAATBt{wdL8001BWNkl0$ zA!~`5Ly+UsS$>!Jx+((%LTm_;&OD9^0JN@4=jvX62#z)9wuLMNa3m;pYR1%{?Ubas zsK86KURA96=7z~UUfTB5FK^P#l|8QL zXF7bB1}}J(zEh3wlQ(p0w=*}?oR(L+VQ;IatG)E|CXl_$wxflIFg%YT&W4Cc9mK1+ zvZ|OV>kSfsI*n@}cWL$%5NU=Y;zbUX^^DiaiH_l0|9p4_N@iSY8f zXK>6{AHUuXTW@OZBbX9YPrzatBUN;(PH$3Xq=icW1UMjw2@rLF(VM705eXc(#+Xn9 zy0MkFp)hSMr7~+szYjQ$HrY5q@7(*A_dNW-C!T)nPXOF@=PQ_v8n6{t0Z^|>q#^JG zfU8}IXK6tt0IH!|7?ad>9nMcAfF^w3TfbdZAAaBy-|*_U_IiC2s%2{|n;lek8{N}P zWX*{X#Najez4PQlpRz>9PrUf_smD(~`1`MT-8UJNgrhTamJiFKa8&`|3!nScYv1&4 z%jBHA`rdcuHUDs@_h#I2=Da!(Y0(qX>NhU(f39}7s_hjRo`p81_}^Z~w?o^?E&VE?d3y3qSXh+qyq;?3R8%eZ^}|r zZ2(a5-qq^87-BXe5z0rSx1lg>RRR#iDn6VT6Du^ey%~ z?(1Q@dK*gHL!bAcw=qw3Z~e6?u6zBmzp9&dD&j`Ewfwg3auuqZ$s0(ycFwu+p@Ho$ zA4-zM`+7Pa)m7oW%d*sa>1FxmXss@${a$X;UOzWko)@E0rMj_xp{`1TzwP!H_lLt% z&p!Rtul`w{CwIT>){XT`&pvs9WRRJnD91<=rPM=7WY`-F7Z(p4IHW3%KKj*z%ZKtj zzi@G7X?YH(*Rf;AR?hAZ3wu{uAf^>&{GA`f|N5&qcOh?S}R%TKpw`Z2*MM4qXUl+s3VV`fWH&%LE>ibV5NQ0L;b`341R-=;6r3i3nBC z`U>fQAlpmlYs27+Bg85ATM> zTnS~NE&ti==k8SnzHXZQg(x%AXK&l*ZQf6Cf3I?VSPbUuy(Kt+R2Y!DOvnRjlf)+0 z*rcv2UstZKiPOromZyRdpmv&>lQy$49tyQ=KvJ?izcG@n%E+S*#}$|S{+BZn_u z+90xnURsr75f5q#C@Y9K@8#Z0QA`0&EQ<-(B z{?pn!p(<}&$HBOwhM!kg4$ry;()Tp-BhCmVkPe1Xq3+Ei6VG_Vx}7fZ+&RaKEX8jhK)c4 z#B98G#0oWme>Y%E0#(r%49WoT%#)AYeBzEUj7PrsA7AsvZzGWSn9;htd|-WJ?e-VH z=D@)tbumo_1Me#$7?T=fL}W7BSXf$0i~%zlYYdM!Hx?ETR<-ohZfrfZ9X zSd5XNkP3iOSaY-$6uPtW4tB$4s%z*abm#hfZ;E2SAd(wZi+-Mjr08&!c0KOAApCf@ zce9A+X#d?>YCOdL8tdILH+O%xBCp%SA7(oOU;#kVUL0l>AyP7-`V1lPg~Zg47}P+- zN=h)W@b2JJzu#XPjn>4M>#G}+@u=VH<-`7PxL8k%$z-y!a=PD77nb@2{%61Vp`E95 z>#cX>d0Lj`GtWGAe&sm;w@EdcPMGY0rTXYCM+S>`mSa~>oT@){`jo0ab^7VG^$Q?6 zaA0wL?c#;=D@TtWIk$3VmkY+X-}&N?eB>kF{XO6F(fj|8_x;c=tzKaA(fje;-}C1` z@{y0c=(f9vN!3trSaO57Fni|}8aR8=2@nl##;~!~+mR|VIuuz%X0F%hhHX4et@o9f zV4T#0Yqn7nw6RE zoJ=>xSEFKFOecAkrMME$#`=5x#zMh zsj9lJs-=a6Ua$AWS5Hlfg2^rp-NB;=dV>?y)Vso~`t#?{Pp9K)IUbGHK(x3x7>(A~ z)-E1Ac;M2-3)|0gUs>3%D2oet`&;lEAB$g4pS|7=TiyUB%B)2Lr*{3I-5{6tSA_f3 z+<#SVTWrH$!oMNWzTL8oK_*x~#MA_WDTjHSVsJNsA18WAo{RToRY(NE$r#&sYPStf zMVj=eh=)Y_t>EWv{@($E002pn8e=sE+$d<~BnUH6pcW2sm*I(Rz$j46`d1=&SCs{_ zya!NY11p%5EM=y$m=Z_;!(7K&dm1uNy{dR`tVINQ2!QvFZ5qxOAY($^67{}jGQ*de%V{Rhnu9A>6ZWlamCoMSHL70nMA}@qYba#7&{m)R7J&# z>39vQYz!Hj_68s>$0JfHT^+DV=UkTe&aYlPed$7yq(=@PF3ZW2kDnJo!p508%X>gS zl${H)8-nsE;#LNrB;k1~fiDgDvme#)T;FzMs`+ge#?xXnd@8E;)#~bfK(hTz1 z)A)P;2_# zrB(M7GojGJH_S{rYurHIvknt$y?Db`L;?iUb{K|1L?K27z*CQ&y#4N1i&rK}lEga| z>H6P@nF7g+wRY~5)=qfcuV`k(FpUMhuj;?}+55xp_q_Q%XsCvF-)=U}3npWNqT>YBCvl@AEwG z4VHfK=RdG>0Jq)wQo~ekUaH*$omY5y`RKHG#uyfLy?iN67B|Y3)6YExrOMSr02?;u z$l=2mE?lhYX@Ahaw7Pou@Znw0G|7JBH-Gbe?|ttF-v8nE{m{mhFU<=;KKiM}fB2#A z|KJCI&Li>OQ?x!+B}T%C7g2>1z|RcRMuLIcFe3(>Ej$@Iae(6z>2tMW<%- z`dDKG%ETfPON}zIu!hGWW|FdD%Cmer9U~gmWQdePK`0LBC_*7^3okx|Np4YA6tHvU zIK{+TMcvqV5g*KYrci4GL{vMUu&P8(9T5%O&Je_qcx56OHqKX7RhlHVi2<2VyD=>J zvNWr!N>z+Ctw$joTUD9Z)fKZ1S1d`Bx~iC1Vn&I!*EZyKF&PQvV?~6!)6?brsBv!H zWum!yc|KM5d~o5)J?~5iG+on5nJ{=Zo-m*3N5DE({Nq|k77Jb&&ql|f0I$C5#SIJl4X6D&d~o)8UX8x1la@E&Rd?RiM5#xvtYBCMvple6wJ+D~ zRiFlv2!CzXJk4I0Xv{|pKE8b+3u(rWOH3@Gl8~wrSR|4a5D0K#ug8eh&`a`uSrnoY zNL>P5wuG8-(B|PZh7hcGL{-+L?-0-g^+>GE*F46d^fXw+dkrja0sN2tMDLxUWDB>9 z0u=2HP~Z^;5sNx;mH32B5+<$SCop79%4J!KhT^IwT=53nAtI{kB1ufV=Efw6@y=P3 zs*<%ym>7wyik4+L><>r-){n(ke!@NT1BgIOqw2TFPJBkUec$#@?^(56vkuz6;~aeG zdgqtfp>`5mX>^5NZb)-w%Q&|Nf^@!KxvQD>zFgZq42kwQyKDv9uhiw7-D!49v~5R? z|1Aa;G%;riWrc=y&GUWB%#C#J~F}0DSr(eB*cHr7y-??!)2&o_q!$y?;x~H{OG9e%p18 zvh}9kao0=JJekF|ls*(}?#3}D9Kr9P(5otzUT%A9fedNHxfwxB_%~efmiV??Fnb1k z#E5#h+S$ZVn?lvtyUeW0T~PnNx4j!e4?XaSryl*%Z7+E>NC=uFiE|Re+8dlcRMc*{ zibG+U2GmD5wU*+WLb|GRZ#|KLYk%kiC1wB zpq5J*aq4BXDrV;rT|42*?Zw|6vgwHIhJaAVJiP9OK^WIw)bW-BZF3)8W+%Pei8j8e z-NIOQ29Mk@x53Qzy4EW??_OL}Uu+QU`4}mzJ}j6O1g~IH{Q8If_GLQw{vY|r&prFx zLO)AVv#_|F_4-~h8Bfb{)mKwCu-5)>zw(Q1`**$TJDz#&xzS`)SJgM%{jw8v^~|$R z2|0y1zj6-15B}}{A+^T+;r)4*c;}{*>B_0qqsND%jnTowi%jP9sf((3(Ji;FoL_nJ z$*0-)g{8i=mf6Yf&&h#9H$C{^LvMfk+kbR&=&>g@UUKKPT&?F*{`67Q{>aero3v% zNCkrkt=>kM9hf2>(=j)*w8w19vJh236l$$CnmFg!Kxg`sMI?k|hPaZjJ#eds@Ez}c zD0>uLuNs{DL`2THG)X*QKpv{9o9k;!O9#><^FePni-O>SBn2A+8?Z5IMe6Bzefdxi zkN~4wlK_-t`2a-5i08Vh!a|3evP#~$>3EzbnL+`R_xr@`yZ|iXnF$~S|FB9~`(ZC< zR$>ORHc|0tY@JrZYG(F5thn|{gSRKuy+1(39u4WOU-q)om6imG%WLDUd*3*{jjrmx zzTLOVHFd@&=C4sq%j*>i(DwF&nJ3u%^npqQ4U zYSY&x8yI62mky4{(_%8I>&at}K3Y}Pq?iu#Z291kn~oe_IeS_t*iPn^uYLW&!-o=M zzWDG1X==s$vM4T|+cCwoESE?Swm8cSD;>hsg>e{eH^a;&TS;WCki4ifbt}~kwQ6Qmdvu=&GAZB9UB*VrC&lHWv}>U-wzh~8X`DO42xq}MXuyIU&ubG5(;fLdixXXk;hufa7n?e5UVNj0?C5%r5Dwp73Q)%V9ctw4C5CBQL6 z1o7U9Fu|)P){?PFl6mjFtE+NqtTDzWX-dSdtW>0|O7GqJ#zr}vrddBp?Aq%207r^) zp7$0Pmy#rzj79;FmD-hsGnVVhDTIlkk%BPK^YLU{Rh6-(sw?lkXyU!M=0=rPx^_6` zd)|#-|MxR?n6EsJugoKex$PGG%b%Z<&2&`~ys1C;bN?vG7u%2%AW(~MDd8MGP*dQ! zZA=jkpTQ+9W&t2clK+pqHxIKUIqC$>%-tj6oq1MfoqbkyS08G1x4K&=NDSz1(I7GK z0kgm^yIevm2GN?;4D4#OyTj_!@G&zmFlb=sljaXtMh7gn1Pl`B=tK0Oqt$11*OggW zdA)pB9PVcOheyPVmse#SlA2lj@~e6;UWA8-M})cg&&+;?l^T0n*U4C^s9kPBouArh z&CCp}$&>}2JzP@EJvrVl42b&fSHJb4&;7{@Pd^R-R~@|>fwWP~Ww1%1Z4s4H9`z`^ zzj-~W>Q$5%jzwrsSy&2bWDp*_=H|1{f9*?O_>KUR3VE5LBv*^ z6QxvUV?{v{$F*85v)pL3%IsFma|u9e?Oaw);eM(CC=Bll=dX@Hri#g4T@Mf-7xn?? zSgCBqzAr3W_4CLGC<%rN5UC6c-~1tW^o;$q=`7nGxc%&aTfX@Q_X7A_HjDxnI+g70 zCT{0<-2x}=p(l(E009Ys{7`FOFc>6MRwMuB2j2q#KlGzNy}G(4h+3OJ`NT)7EhPQb zgNNo3A&z4*y4T$p^t*~kN8#ku0hgp{9RJWi`JbM6;>#JwnrI>(-gD0@2l2q!^ec}) z(CZDH14Yrfvu6O{WiNjv{{82KQ>~Kr)MT1)t2t*P+v}g6o1Z#);&i986o!%3I?G}L zo}Zs>wd<>E%UNazNu2SHRLz9gXtjU!SAX^WANbXufBz5t(MJb+7@lvXyyyM(_kZBu ze&|CVYPP2Hpzr+ImQo>SF2fQkEnearS7RY0AV5N`b*Tdh3Chw)08j+C=d?087El(n z&VhKx&WTgX2n!2)(%O7|0e+#7=M#aTF`?3ihL|KnLJ(v`&_)9aAp!~udw;zmWvx|O zm5;L`a-KBHIYjV@tf;7@ASil@u9(ggk$@ABjm~Pb*&-c+uYOLXJfj()k0ff;Td~q< z+;_>q3AilPK@Bk<6UPifK^OumrP0|893!9#wQ~%>1O&j2tx{TqjSfY#QYw$I2Vh}N zh9;<+Ak5NOJRl{E2$@au8nwm!&9!&c^|$L=U)9^=?$#25NAPhu{@X}(Uy60RjfxvB zxkejGHM`S?P5ZzudVc)Fj%P17?8)<4?0k7JN-3ACy7%VN*sJPB^llj?C?dMZMhVC& zly;ce1W3}9v>FWh@vu)sDhQhGSx&PoP0lTx zJ#pe0%ZVns=Gq&K3F0K~tS&7rog55fcAzL^=6b!hymWSD`LuARC~dS_HsgA2T8DNx zT$-L~FP=Hq>#dm}ur~A6B&Me)>y2omyKb$E)6{N?{4L~ItNroc|NVb=*(~f{PM(4P z^t`BK+5j$aKVJ46J1c9GSlva{Sp3(~fh|W6lp_ilxQHYpDX+nfJ9)?j1 zU=*HETzYxqa$qYT`ipqkW$fEnK#1S6TcE+Vu*)8?n6W;NO;E*_y|%PPZEf!z-D0M0 zdfxY@pr!hF?7d5uB71LQ3#^8_{a6a;lVffV`2PezZXy67VU11^bOs&gSZk$C;MYVx z#<@+JSzMCVqQEkTVNDUSa5Cs;E+fKPt&wFJ01gNJG)+34mEK0*1VOFVXf~RyM&nFp zE$(cHFbD$D+}wditDU9E#`<~YEQ(B;Iz>hiIy(qM($pLbhlDaYHH(NF8y!K8Y5@`; zkcfm~NTk-*)-Q6X_bQhT#~eQjfAul=Hy?&y{&zd>^K(A|@A`4L?&?cE2|&f0`j5Z= z2X4OowVtM=qQ@Noi9pF3P{xk{fI_k|iq1sz_9cy!`#7jk>f+K_S{_)=F=Ywuat5-_ zDNQJtWtlN~-Ox>w6XZGp3tr)}WyK&gKADx_KOO^e&Ihp<>--7>4gfgkJX?Y9TQMxc z%o7juat+WA->0 z=5aa}5kZkl(quTOw<1JjC!QOL2o)#F}k}SvFp9t zI$>X!GeYI5CL{<#f($62fLj67433Nr$%9CXno zowcE5Q9;mZx0MOOaheV@o2;#^96EG$y-`o%Uc1>`U0puEa$XS(1_J;x+MGW9fN%GA^Z5yWx4yt3MCwywMG`ctP) z?=p6Chpu_=d*7R7*@r%O=(AsZ`rBV|!Qr_$dFd^?)m^$M`Rl)fl&^Zzo8J1Cx4iA{ zSG_UUiG)6Yg`IckfkJZCVqplLX$53t*(0K-@~wW&;TsqsIDSi>yveze$2=yF09c{6 znbleYdwaZW5Fp2H%Jl#thzUaHthF}hrzyR>xqY6O*7n7r$f)vRL!#&C;t0UmbkOg&ry>!dJcUC5QG|)KupmMh2FY-Mq(o3@1w|oMU;zSVr?d|~ z5@zQdhd~HAq>-z}EQxiq1xU;SM25jX>)p9w4W^Zem%KF^xupbO6j* zmROf|H#&3s4n(ymO$UUq(OF;Xti}Cq9LE5pl@24*A9S>`iUzfMJ&7fWL78xBa!M?K zvMdnyvUr#UL1bOlAM}$XZnc|4kfzCcr&F&r4j(?exVSx8%dwe#AN{YNx*{y>aRNX0 zi}1-mgHL}3{;ywxm){9x>5sqtBD|}@DSz}Dc=bJ(ej=#w20ZfEWB0!5JFAB1$dOjL z@1^&v`Y>#YG~X)K9ZKh%l+ZOmu8aYY&^hP1dxeE*1fu|W;|237)QC?5I&F@T%53I5 z5f~tl!h-E3fAJ~zgMt7Njli98{MT~^=O8+aW+flJ;<0dF$uEfqzIam+rRni~5fFkL zkq@J2I2eG>oF>A8y4WYu<{dyJqAblUTdgz@01B`m5fElJ)nS;&7#u<~ybf--5|Q(zH+5=yzqhK(YDa~}79x+!6PL@YiW)#mG3e0@R%ik>G9)0jrzTDDv zH{2nR!$yc$ChRZ>DgwkT%c|KuP|R3Z6t2cfO>WQC;&YvXK;Ql9w>|W^KRW&V*A5=K z?(CW80N~LFKYho`-z+&-gF_?$EZ4oKPd;<_>f_1;i0CRYL}{9d2q^@>#~%1|0Jz~L zud3B*&gH&?vl_G}R`b%m#ygy*Uv@kt-6!pe(j6f~2KV_`3vU zwv&-zM>{LUk-b=yy4q>a7q#rhvBEpq#G9*uLa}1J=rPzlbbHh8V|!h|xjK@|qUS74 zHxd#61SYWLY^xqN46iPqZ`B$no_;zAa=nKX&Cbkgt$j`+5rxL|;#e4f)rsd$Hkvvx zCaO1U^}12PV9*=%)(5?=QWylmZFkh_&?+|%oKS5}gJv$O4q#>Pfxz0(P5jaR?w zJDz>^+3rSs^;Oqyd%XqIE!_N)JKp!c_kHMBKJu=g{;mi9^u-$>bN>fw|M5S4^#1$r zzxmcXB`@UVJ%%H_?ZFps>6Qjz)gwhjxofo0+W-JXY)h^N#~rqLsU|EInO?~f0)qe; zV+!Wr+|i1;CGA@&=vP?)2tl>lQ`XvEcZ~&*z=`!1ZHcqz-6FBp5*5~Nsfv7dlAp`+ zg+y*}BLbq%vMh&nATNGov$)smH0lixuZsu}`cOXxK_F5THR{8jV%7$X2S56Sj!=50bRFHvuAbIwar-FrOIWi7CMq%X^X+)Lnl^w>m6e2m$A>RDnoZD6IU(I`x;wPUFRHo-+b&b6Z6bW8M zlOlt_>_gXaEc9bj|8iEv9Aom4IVIQE2(9#)T7~xzM-0U!#3SsiV@m}Eb)Iw&=m8b< z?qsdlvM*y@L~rEa6Bl`}n49{RX)F#%k#dsdP7BCWZZQvB%x!OWj+FK(1yyXR9PvFR z+>aem8Hb(ao0?nnjT77)+_UH5x+3S^+=DAUs%2|?xhmYtZaEHGE<8{)iXx0OIGZME ztfJ7dh>$U18HE5M1Y((eezdb0v(pN#vqV}c6@;NMSk96pMi3JOv-PGTH5?9xgKlro zPm-h-g;|ygdy|Z{rbeR?h8hX7%&~y8GCwzmWQ5&d&;_C4Fm5(mEIf?+#+WDyvn-3_ zI8C#9y`goGB#AM`7?Z@wC6Ds%qCfjZxJ+;AHAmo@Bk;rTxI#S|m#R1QAHDeptC>n7 zf_WT=DbsTR%CHy3A_By0NA6ScWrlLUYZ)Cgs$77h;1nogOxUqF21OnTs?IUqlgVrq zY7k_whyuXO&bwcW4A{K9UmjEm>@UJ+EdjuDPd#$Y(OZgUMF6YQ4-t_vHcNe&Iw2A% zK=P?Q{wQYFIynbjOIc1^AOk?QM5HkXiA02Nzvm5)KKQBAFMR#zO?NwC zPaX+i5ET(Hi=u!4UwZc&AA9I8`n`4FtX`k=@He3%69@nzX|1h@wU*hY*)R%QmMIA9 zgZ@UXR%a$bxa+lVd-yYd1VA8u{K*IPkI$kN^S!t(e=93HSf7=k%et6Z`h*fFt-49=+a&(1q8Mlrwy6a2NJ$DKK-hA&}t=1F;Q_bf7nc3cOINVt4!WKDw z_BkST`0&+n+_p*Wdfz_g;0)%RlzV z|MmOs-FEkHvHad2;0?!LbL7Z1zxCk{-*EHG5h`Z5*TYf}5R}IVh~&ZKB~U9OEDRMC zqu5zW*aZrnTHnY>X;W#_S56{Ait=rRr6B^oFx{vtxdBGPph$&bElCsbBnXvt2ypq2C$3LT1ppT3oK*^lw2#$CrNmi4P)HU97}dDMjd}^(y z>u`)D`PxW!t3VGsDzS^$VW*?Uw9QTk^@S{G%sG8_-r-`5U>sjhZt0l7-awY>K2qrB z9geH2?%deeLCy?fiWI)fPzdS1kx~sHpzP3EU?SxPETBay$G1=*^J8Kc$M0=vyXoyg!&$Dxfo3+N`x${XnOs%yUudJMRE@?$U zmZiOZXL4e)v$4L>*+`NE6a}bGoH!W|2U=-sGuT!TuMKM-|1baLU6;+m{+928-~9vl z`^WRIUwaC^_S81J{nF3F>tB1xC&|V027Ks)AG}(JBM2t>vUn@H8PPbF`*hmSr~cb&p2&cCmBi z63Xrut>y4&-pTTj_P^$f5f)Sgf<)wtm?p!42|{DS(JBQ5^Pq77fWU+qfG_!oh}Lnz ziJ9-Kl+Ob|PiRS0_gw9ylmUeVdsfqD}hgb)ToO&d?^YzRA8Q^crY-xy4CZm;oJd4h{Aw;pctXnN)Z(m zZBQvi&U$B3nq^TCI_IKVjYu)OERNGGMF4FKfL2Op&JKqCm8FGtt3BDC*2b)@oi{;{ zW~qQBrLLNu$igtqfI&xf3PMg(o2IEJ;O_VPC^o8To27%{FbZoypa%VZW^E8e#)KlY zw$>pct%#Xtre}KHZOr(~7k&Q+>i;0TsdwJ-9 zUjTUinXmd|opV5H(`2BK7(J;$zR19$dnLN$ob!cReRxhe2w9dJ1W3ee4;;E~;mmW7 zKJb^f-}44U5^*A;6jjIS=9j*jlcZ>Yin%k#r+l0z0H8=R9Mo!UL`6uXC@`UQ)>AZj zAPKNw%>**WD6NRl323bglre|H(3c#S%!d*A8&Y{NV$8dg>y)LbUQ`|UAWJ?80DLLTKRA(Ls8gUo7Ns%wfyEW-?TWXOmvKpXP)|^ zNh}5d5FA1#g5*oyup_pC;#Q;#3CA08IyBU}{`%{}Fv>C~A}cE^`}glJ`-x*B00h8@ zV6+Bsah588jm}z@rlfSE)izsd zQv|HbR1Q+0NDhKX5fH>8inK3-T_!6LflX5+LQ;q%;G9jm-Bc;9O_bBAPFD#|#2*e~9cm?xfdNT{S`E7EQB*f!gOozRD5_a&mC}A3l~OEXv(ycesMZ36 zFlrEaU`aViIe$?#f<X;{(5O2X zLcfc+Dla+VjmJ#=!YXf2wkpG2q>|k{_TS~p=7!3-ezeDE9@-TG+HTm!H+rPCpb-Gh zp(6iwizCT2LOoD*1IeJranc6i(uvpKJmKY!^Vzvuoj8{Cdu!Dw{|>jJykMqi$0duxcw6`hP7=$VfLiMH~aM< zzXQ9;9<<*cGg>$8v~9yV__o8yT$(DbhyrX|`Wi;G!Gl4o)k6TdI$F2?}{K}4ZbB%uNlr)L$Rkn8;Z#7 zcYkMym|2JDxdN1PPQ+0m)>?mFqjj35Sr&&;)6YlsdVM&I{UsY?($sngr{C|^o0EbP z)f)b8D5dh!s%2Sm^iFarBYsBrZv4U6qW3Rccx-!9a=Xx&OOx#s-DdvnJ)UWIu%?*Y z%g-+ckxg?(wUfC}+2`#$T^zqT7)N~Jf!urt5V8sY0DaL%ArK}=6-We7Gg+E+TTyWO z#EHqt>4}L6Ri6NW=TDxfM`mNA+n$;{a^#5TTFTq62r`JXN|6&{8!wzaH!;zQv&@9y zZ~xY>{)>P4q5hyB$Gu)>!x&>s(3+eQfOOaemi4uz`Pu!3RFV$9?X~y(?Pnf*%XhzI zlK9~VKCeyd`lH9%tvP4YhaURtK|i*ZXJ@8Poq8cjhaR(CSUk13u;jaR^rjn)30`sJ z=+xx=`SS}04jlOG-+gxX8^FR7GyDGj(Z^O-SO3K?{m$#&{`SB5L~r*)zRB{M`c`^ovz+2FZsn$1?P*R|G>50>;?0ssV_*@gj; z2n*1>sJ9LzVnK3f$+7jd?S#wvrwEA7Sp-m8u@lEa0NstX$>}*nDoHkw5M4g|7!wj{ z#Js{a0QdkOPX^DzzJ4|#Ip^Yd7}cA8J|j|E89ypoYxcRoEJ+&I8%+_eHJaYpAk2gc zPyvWz7Utn_&}>gs498p>Y<<%&!Cv3Co!z%ztZY}-dds=?))a1|_^Q9ci&Axu$u=F^ zYcZ^`rUVfH^YZRR_^P9#;CsGYLWC?3)_|e5@vzfw*3X?e(>QcEP^hBj((>~1U^xnO zzdvZSTl4$py&0C5R4ZO)5g`!q#C9O!lI8QO&1OBZRtG_?*{s)U!+4magJG|)wbt4+ zS}g&{k^!&``|-@=j3(k~8yJ|HHA&nfxS_NV_?+w!S<&JNw9^f4|dc8Kk4_$$xVtSlFj0 z;eYv`;YWV}KL0R$_6u<0Bs}pH)a!8D&F~$shVOYZOmAOq`{Km&2K?&}edyT46cq?d z{>)bb7&rMW0X8oSp_q34=aIovN$n>r;g3;kwh~_! zmdGfrShV*zDW$T^7G7PDzV z(^>hF$sQxXg8P=4OYYk$xLz#_y~&s>QJ%a`2Z66GO+><$)F>{dM1`QDkDOybQI$q8 z&lSQrPC}oMe+x zh=_dMCGlxlzSL3G&oC;Ju9Q;7Iaj`P!VXE59TxFJ3QFmEz2#q35qa#PPXoa1_q?8q z!X=)_=EO5!zUKN{d;M;`(e_WRQenLjFoUy+@0&4Xf}q=3uQ%I7q@tSdmUF)JFgWKZ zUx5gN18_LX9ouycKZe547JuxBh2MYOrUigq^xX(<+Y=bSRlZTx>0g{u1^%`IG?zBP zU=f`a4B6>;LnAyZ=Z3ho1r! zwx*`C;Sdp?eB#Sz&n(PLPfpE5Yb#4D=Q}swd~LIZ$8Tu=_)Tw|XMFCdrS3*{-O>5k z{fEE&_`^%*7s5u<)S@V=4YTzm?IBVaQI@45aNBJ+)oRh?^yL0wwzRbN%rjp zqUi2dzsWiF1(L7?=_sdA$w3gW5OP2vZ)D^tr2?9hg1gs4Eu1?os}=@3Mnq4$m>&ye z(kKXv5c^D}oPfYbG7zy7GFS$qiBuFp?zQrUuddaaNft9RB5gKqr0|gvS!9G08Xriz|S7S zOogYFNLicL-taxt#t>-{@#v=_Mama0bchOp0G)tO-XgEE;bucEeZ%-GE6B75xe_lLmf%2 z(eA9o-HqYIRHN2tnn*35Uj`y3sMVT`u`y_^UrR8cG#laJ1N(s#>A5s<%PY%+-g>9g zIlp|qoNKm~H(Y(q{a22K{lGlDW1|xjzF(;pA1RdM>M& zOZjzEQ;;umW$RCyP#&+;J^vUIfq)_Al5J10b$g&gwqFO^lSj59IlII-dL^evPB#CQvEh0)A@OTU& zkG27|z3#r#J`*#-$yxQWJJv{+&Kv~K$WjSc zDWMs^u>{dQ%dbagpaRlY!T7C@X)&FQ03C0gJLkBXk%W15)y)mkSZody6NU$dylYg7 zysGjQz`VLPi@@Ele(T+@ek($r-tRA@iX4@(on9XP{GW14}Q9=2wu5T0$|Ss?~nF0kk(~3N&JcOU<5?x zgY(&?St{a>0wVHMzMCv~L_|>j4}_|JGNPLS@Rl92c&xVaSIRDr86qL7ZT~!F$z}Zg zHz=d0YK!bX&KGQUTLH*}V#u3YzyypyAYve^tF*?wfV+0Mj9Gtrq78yG(=$l0cz)S3 zPE1VJYjtbwi4!NRwe5Br0BW^JsmjAs5kLTD5D-M8$!7Mqe&gSkd;ai$|IS)-VsdJ# z-JTSYrE?3-dhO7m{d05kUw`89#l=(Fq?5Ct0@qn5v~@$Ze$3b2aO-u)Zd_V8^X!vP z3^#hijsCHt*B#uye|f2^6d|z)he1Q@`s(UxYJ0ceaZ?nu0~0)d;>lq$5QaPNcty4Y z|G-wc=QZDP!;Lro%+J1Gf;a!>M=p!0{YuHN{f-V>_x{9B{o;)`9>4wW*ZGZ(9eX}r z7IsCgI-k*rBc%;6S{;{P^E>4=2973lB=oBz<-LH&NT9R=1g$kGDuQ7FiG0G7kLdLs zfJ*SAfAo9|qn~(+o)l_d0Lh<`v<{-M!A^=x^E|^97b}n=LX>`ggV_q$5?(L)dZ9eT z$3*%AiE8zRAQ2j+6apZ)csOu217EuXyjzuvUJ;?MVdqPJNWZ&bv&7e0^6MK?q;%j} z$N+>$S?8RSAglo@0Z8MR5CJ3zOb{4m@h_osY_p8~vIYSWNdcmGHI4;Eaz2Mv6tP#( zKEbN^005)SMd}s$6f{4Tm46j>urb+5Z(o%5-tJi1q=KsQ4-|{>_Q4+iFvm&&13~=0 zs((ASyVD<{5HKJ@9!rJbhnqpOYf?Hv-3jXGY$@G1m-W`jxq}Dx2gWQcFK3KehhY%0 zb;)qBvC&yxUILN*^K3&!d->G?f;bWcgeat1t>z=k;@_dp!tII0$Gmq>0tF_{ep~Z+^)ggI@1%{_@YC z`0C?q<(6BHUw7@1rE}|XJOs2lAU2W`;Q#<207*naRHGw>kxlIMj6Qm7E*+-J%jceb z=BsBGPW1=<Q{|B<2`7B%hF233P4*^LK1xUQ&7Xk(n(P#tZ z3|brayPZ`Oj)FjuwvIDvGi!Y+T(eP6l6YnLynh;v(Z%AlR024POG5xaMG!@y03e`J z%4S)brfHG_kPd<%jF>qd4mUb$8|!OH8gFz~mX{ZY@p=?VvlWW4QYMM52qLLwb0Ut1 zOXn8SBvaZ%wMZ#tolVmO3A85fI}1#hqyy$8j{BX?TAIY&UN=b+0Bkl}!m<-}z~zg6 z@q1Ih{kwjk3|)Z&DJWM^rM~v!T;}Ou%8JybDybszo92>oV;Ohj|Mj6a>>M+*SVZ&? z$(RQ7EwgB?QSvYoU!?^Ad@iWg+QTlM-KKIaOr%5{6(K5GYai)T<(&Zl1mzJQ0J!G* zmp=dOV*v2b=l`zIg+IIfo;Ua^fIi3S`DY)$>gY>|jAyD>N-+y6%#t`w;@L)%S+okG zsE$DF#Gw%4u-6U4Kx^}l-ueUe5wOL;f*K1d`|UBv!k8xjE{ctp>_6o#zHrP-KCYt( z$yy(H8=Z}2yLDjyfhaWR7thVj&7t7+$8PMbt|dvr%o`gUL6ATHr7|gA97JG1 z)Iqa1SXy3K|Gw}4k&pfUM_>0{Z*oqK2D;v8Ih!q*pqvm3A=5vpACvt!>rk!H4v zeApD{6)_6MBEpE2m$5(}O+s3eN79wb^Z5k?z*8rJhy`)|ZYLi0CZ=YTG9rMe06Zv_ z2RyR~p+fXn6#$^tVZG5F4hF!iHDxwML{f^yR{#X?NECVE8esMjKlx2hvlRNhwlZG3 zGYBcIRG^G;;DB%j4<8~$y-qhxGiK@a``Tzi zAR^~%ZoNR|F+wD*hTXOG<*wE`s@cWGMP@m2)iqJA!Oku(E_S=?&1NI2MH4j1Zg|}_ z*RQOctT)21eEI1ckKcwwX<`jV$Bx}50Bi>vomHcivx$n@&pdS!l)L`e{#LWKe17%x z^NW)+lUfrhyRg(bv$%fd%vtB)nyao~T3(oFPtDHmvo_v+lwP%O?gPL6>-YZyVPXI6 z4}bW*cYpgPPhrUvldtfr*3@`742-{MR!y$r29198nKH~#V%Cf3RBVaKkR0ZX6?M$w=}?o~d)p$LezR%=rkNmAMXfWHfb=saA5NQeSpZ6?Ad ztO1Z#CZkjY9g9*Vz&1-w5Ed?2ggmopJT4}WOC9xObjxszK5H}i%lJU=^h4$63+(d^ zt10{~kSk@1kJFP~Zc}^MEBAL{?hdma2UTblF=w#?0TdP+1}e~P08BG0z^Ihc#t14> zHnVXuXf|3iv$G=Lm(+;ha%8XsaQ(Z<0)omQWY$W**Z1V>h=8bS&8AWsK>FQo$7Vz{ zH@6P~*Vk9mEGBYOGf}VGGo}^s?|er zEP{lJ6lFF&GJl{y7!KAlYtzA?tF@Y$**`fswbALc+Y`elCPx0Fue8FTfg#^ zul&qUJ^Gs;`IDdiQTvTJ%|%J+O}+l;(N}!?y-J}lW07Z6;4FxUL@eUQ`B}7coG1C` zs@(Z16nR|5XENuJS&yi!P5o4Z#p^UO{QWZ!UR~$v*>+yZT!iAjj0t1>K-|)w?cFH^z{P<3b(&CK z3yc7P5KzcKrXZ^u2{re7U9{F_P$PwtQ%dP!GLV#lz+83JRRGfK^_ZCiG^(koDXsO| z+DaTJGc&VCkG23HO_MTYOax2(R2T%^`ts`H;^|xNd|ebYpFaJ_^vv`>eeVZuN zpIAI|iiZPKp$WpJ^JkuXa_RW-tBf(jVMknTYI-uNnW&f4y>`x ztt@YBY;4?p&zElAR-c23*wwox+J*q42%Hi zoK>Vrk+^~{%sIzg0wn@v=D+WQh;#99P^&j{{&GZ5^ujK$fWrl=vE;o6txXiwhc+Yh zgOFwxNk-sdYh zdUu&JKKqZI4$H2UzrT3a5<6=4ol%;LYJQtZCZ{D(zzVn?DdbG?;QaDJv)-7Tn9?Q? zz$CU#q}HtKP>TZ)?5wReqiCYt3XDE+>Qoqp;2a_l;Y52vkz#RW6kF*(BSkKiPH%l* zdqxD-*VbldrvnpRb=~!y^-j0fHCm@h(%o2JUS8^TLm@eI=#VyPoOBzFMi>Q+26VfF z<&`z9&FuVqsF^tx#*JQgdUi@_SX=8Ky87B6l!Hg=kALZ_8ym^=%#;Zji6^EfPoG|P zO#2TW84i<$#l=QFn4X>*47GXHOCGCjR~lvOa`!7rnJ$j zpsPnHOK1ZjN)a2kX(+wWW}6rka1`!ai5u zqcfh#CFgzAS{F3r!U7)RA<~Fko^caVu0ODJ%wkSkqqgs4=g`1612`;s?=c^~}H zDWw3AdBo1M!`$gipu9ssM2M7Q_LjZYI!!arkE2j!S*DEvAf=UvIA?WG0|1}7%AC(4 zW(V z=WDf^6hU(?Z`D(dz{gq;&(sto16Ocop1bZ1S2eq3yYHz zv&~xDWyv7vPEEJ_ok6GHnV&zTgWA;ezUkSSrIpiz?nbSKx7_sYK~#V4`L7?j`ufGQ z3qjo+zUr_E1p@9Zt1xI0tUmh4gHF<$Z+XerpL(|0)XzNq%)WioD4p5a$s`%ZF=Q#! z!p6RRv**s8@AW#J^<}n6bE19pB{M;7xZ7ZF(KeH_`ycqyBfszqzwn2D^x!*x`g`B` zzCZouM?U`K{Xy8e_hX;<_`Bcza}PiA)#k*!FTgAe0*=`^E2sm^gJKkTwOg!G2x(-5 zp~qYt0FYAbO7k~oM$f5xMFa&%flqe3`S5|85Zk_V5CT@^2-Ix-KgB}b;LTw9Li}Kjj^xr|FW8vQ0n@ZZc1-ZD8at)1RFP)4Xc*V@% zE2y`xj5oC+c`zXWK%TWBR1UOQ4GheImb!snucNGS)`8Yj)3ch?^2*Ze>?|Vc(7?L0 z)~0brL@aJ*de%BwTkmLN=4WS&33|Q0wJyuD_4T#snP~uUo~i>Fgq1Rm9dpv%SYKIL zpW1)T#>OBBLgye1qc|HF4Z~i#vb;Dmvv2<3VapbYyBkYSJ@KV5#OtoTQ;^RuFC9F5 z{F$e|o}|gKdED~{nJ6%o1CmiHB1vY zbz*5aum=ttvQETu6d9YQ%gg5uT+^JM+6@Z#O6kt|{hxg7@fSY}`{}QK{oVstd4C^b zHDZ6HdCKUO%DXaBY7Xb;`+9c!kWzW= z4`K8O66Dao2w+~-6ukQuWvdd+5s(6`02~3&Wp}sHR8=T_>#xN*x5#$eymv1L^koMl z{6gMPfDvL>0sF_#S8lp!)q7{Z|cvT zJhL>l@9Jt)q!gJ2>3ziea(ss&2S46~G>z#t&DRd1ppIzE}1{M7q2vspLvP!Awj<%mP5(`cKnT zDJ9~#TEY)eL=GIj9uO8zJ^S$I|MX?Ad^39##N<+Cm*J`2oxM(I`C`l$Jq1G4yX({8t|wSzbgn6=i24UvURXG*wQjd3 zj~qFolnR2tzggQ#zu&v+$o%T^^NmP9_uTU+vkQw^t3CUBANjul;BDXc1D$T~g;S5t z&ebxTG}^%+*8QRG4>KLm%ZvE5 zwQ2UkvuDY`+~lq8Iz9jF3+o#Lmucs4|NNo3xw#+&k-2A{d}?7~X?kDdOAmkHj=PU< z-`&y#8FT0W0FbHu`KSNt#5>;c@sEG96 z9hK;t@=F72tx^VyfcElj^+k_7Gp_$$*25<9qyuAmyU2cZJ`HNrjtCMdMb0`zWM6KY z6oB*OWdaUF70@c(R2=~Xu&uXHWv*zqs-Iv zMMOds)#}6HaR2;tzq=S}duI78!sPObZ8Rnuji}pO)mZQKhYRPPnw$=;%c7=^Q$0-7 zFtOUGiOE@;!M=md!`EEfkC)G{uKs`Ay?K;o$5khI?~Qotx8}Z8)}kt@v{=THC1fGt z1#FN-8yRbm?WWK4Ib&e3=>`Ty%uEl{4IF5&<$=@PXH0|X?lV1{2AYPp#|JP5+ki3h zZdrSkN>!>QEBE~JTi+HDcm9a?-uLBFr7T&p)e|~LmHG0$h#p5rdBSkqlEDj$E!XqUs~?=W21!Dc=F`UfnRZ4U>?7C{=!CQ zt3DPy^UUKn-hA{$2a=iJxp?H&A2;A%e$Nls6Vz@?C}}$Yh~)XcR+-8ekZiA*!2rwLZz$h% za)W_=){1myV3Ve?>xGsR1_;dHx?UMK)36ct9l>TT6}%vx*dc=p5u3^p=m zKHPTq9KuSwF_sb8y)W!CD)SF646h`NN@%+nOx|k^-LI9MIQ|t7puLU0oH%tk6#Iq~ z`c{{#@rZU#+K8>Bh=^DzRa8hNqs6`-011(AMP*y|hhZcaL^5P-x-kF%`0As7 ze*1U*00RS2;X?{GSvD7ClwXrqLj<}c;1p^33aU=|YjK>gQNaL#3GyR~Qp#~0`#Ncs zunCEP6-(D~ecx^;7NW9&j0GSH!R!FC$@W4081lfaBUcy;mgEixqMhK>)n_@sZ4W=? zr3%Xu^&9Eto{sJ9!b@!J+gbK#=lBxoqWcWX(8`jBSV!WI{>z{IssH^qJmPfFlL&$5 zc}`V2ve)Sc)w<^duInhJluEa@wtU~OH=C~ODy7!e)@rqy=Xpfrd7d$5b#--qer{}R zEC_<_?M@U$jq$NGP0R1-d%yo3OG_6KQ7P4Ij`#Zm?6y^!)+eS+21kz_aeVCt2GIb( z>%Q}~a_Q1|W5Si9*XcIu%~r=8S-dq%l6Gf%ePeBMsu{=e=Jw?yG&8p__PZY%y7&o+ zwMNqqt4X3JCYtM8n*zn97nV2HHv~?z~v7< z2EY6Jhd%h>|L3kZ+8;xR^fJRD5NWg4>wa%pDfnq>#JXfWO z4Msx<+5iJ*neu~>frXT8^yqRMx|rea6Mr717*NnoHXSZF~uDOgz>HQn}|C8v3 zS4wnqS$Aqm7}aBJi^hg*#5|^qeK{gR=_(tRA8mVx zqcpqHwlabntyS4=U_eAsCPjr2ODX`NKpUnV(Z>AB4*g~5G)+*|e^3Fh3%!Vt0qmV~`-M<5Ag zhsclvfN`7z0an7$b=@eAh$vG^2vMn2tS;T_^~T31eBYN+YNZ*t-|rJqqtURRVI0TR zYK4t4Y_cr1QhhLpq?7=ZrcoIBDvLeO?RK{-6&D~wWLHWOC>-)!KaQhJB>-AV>T4xP z^m<9Xt{6<3C;+b1+==N*r`vX%n(KI(iU)%p8!a4nbEB1I3Jhn;I39X#rK|fyxO8ci z4H<*gYC{`StA(B?d!0_V*FAcCzSZ7LW7TSPdmX*+*nRV*2u;EqG{!&kH-Gowga6&P z*_!&!cYep`KQfoE`2YYQ07*naRR3ce8^2kfeERXP0KgmH`rux4+@j0YhuA0uAaa`7 zPCr#+UVPv__nAL=@$S9lok$LhXvt+y-uTvsRKE`Z(skJSRgH2T3m{`>eP|=#XlmjIXFT@*0;hKgQ&~QN zz~-57bKdwt=!LI_97N)-nE0q42B*-l4)(5=;*M3Mw#Dzp96IuDnCD6B1YboA_x zP+ltb@sV9D&lb3=?BTiWN5mYdc;Bhtw_Fn`<|^etM4YR`+(k{V#DM_|^1_ZQ2P(XW z1-j=700J=pBY`nwbJpk#0RHu_{_Owp3%~66j!JcEOt0OZm>dtQ6-PjK&~s%aOOhZ6 zn$0E=4F&^yWSyOz9SjCpmT9fiRJpD@GczNESXo(VG#WxUV`F2|b&2S)#~%A1e)RqS z{&#=t+_~p(zx_65URhqgc=4hE#gKH!0XKFUQ|sm48#EdsK{hy^ZE5l49V=m z{8|*dvW7aDnVvC9XKLWM@fRQca;nskCtQ)k>jEY2UU)@nD8AMbZ!M7ntK(&pyo^Upo&`azs@K}G=Z;E(*kzuSM5 z*+v1kTIuLK*^90pj?F9};?qw*{d<4#m4EVq_dfEGM<4m;gExQI!KU$A%4hx#9{%Ov zh8yqw!$1E0<>h7H_g{Paccb)dcgo&bX=a#>)dtEzBWU1STMk|3r2+{^Ds+HsKLU=)7^H+gou%n}uLc~1YFcBLg1+}-gnqw1! z2#JEAGRQ+iB3dwsAx$HI1_HURr;^AXjtm<_BqT&(b6S!QgdYZyU=R-+5g@YTIJH`hhz3#Q8q;VrT*ryy*qU~-Ood@MF)<;8IDh`ap+gHq zvR58UUnEKK|6$RD*dTjoi+5@3F5v<~yD+?k%@` zhvK+DXwv{!*4MqjnL9Ln@%%-{6Ejn@VOVK44n_TBYqQnwwc73NOBY^nJTFNHAd(~- zNaq;3BCik7Uo~owYN=8yp7iR=QvaCK^iDd#7 zcy{g}ga&g6gG%1c&?>-eRF)`}1wmCvCl5kH#AOzw0wOoYSmecm|DGQtNs{j)paIyh z2DbjSL)^q>K|(+qBZiG-xN8JygVWp26A~jMVwxsW*hGOKq~i<9vaEbNyXOM4kiw3b zQJEbJD3pbrlQf*x;aO&gn;l#U+;RKMM?~4brUQT=|4pFkBj3P&FM6$TODTCFanh~q(}Qi-B2B6oXnwN~kL zBFB-A57j_Qk0rYOUa!|_6B{8YP6k0x)ylATf}mEbRtNo_l&DmHb92-6IhzS;wQAJU z&piF?cBT<%W_~dYf=;LFc{)z|Q9NK{)>byMObH>!$7cjlr_$kJcrc&uE%#N|1HM2*qTW@WiJbCiex5=7%;>3wV$FBe7jST=WDt~7|P)4-1 z{R99+frvyo>CP!qr3`I}MNVY^ICA_ZA^@{PvIBs1&mkIBn+Wnq<77eiGpC;b0O61n z?&z~nSWPV{Mk$pfi6dwfuL0QMJY`8P1(ZXUH<)D#z__k!X*Gp+6)|IRY_VCvoFvH* z&Fk;J@2ih~^5P56EFQT*DFuLFVE)i?0JwbV`L90uNdUOxyZ!->f=T3F zV6Cmqv59dYk3lk%>-r?5);6{=`M#H^R2hZjc&=-*%nnh`#Ievm$&$lTIw%!LzTM*N z|MqAqdv}tZ^98UUWV7q;{mNdgdKl5{o7-UyrX}OSvG$>cSHM+!k)x|wxAwlyo_i12 zXUJQJ;;0RK11B>Yw$XeM1+vzaj@#|_`1n|-*M9IHz2Wh%Tsr;S($v_*#PnEqyZ`ksK4}asEFPlmUcFwA zqV3B|EBD`eLXhjqvGtAB)90R?pE-8)*utY<{6ebCIAmyy*erAO`eB9jK2(BczM`mfiL?>5XSXUL@!*VU68(%ijedR_AG!OU0q`zu~ zg(F7U!B?y3W*h4Rkc}ZkLQXpyaesSqtitF-S>#HZ7;6YAmX=#e)s#|h5ClOe1Z}li z(s4Y`lT!M=FN9dSbg9{BRBJWYb+ar}N(}}BrHtd$j~~Czb-goZo_Ae0)#}LM#j&w5 zt+Hd+U8j}qcDGkoR;1%J8nx;e-0~fVo_l(2tF<-JY&OR0gKl){$>$B96$l8jTB#&S zcXFyyZTJEmN7h=~TNjp|pPHC&P6TJ3doI)LIPT_Je{E$misDMxRM}u+s`=cRC&$O? zfO>Ip^443AwY%Nwm^Zs{qtS5rQV&I{xu>;WUcRi9y8Vt@g%k!DC`nVja(UCCE5b3Q z-L9PIlhxW^pL^lwUrkZifA*(;I=guJhKX4KusT}KIuW9T5B4xtOcuv+JQ&hYa&wWD z%=Yx3hn__&R{RKC!v-Ie(vbz!jz##GvKX5~4y-_9DAHX6gW2U3p1b}K008GXk1RbT z_fZ01Fg6#pDd{!{1cZ4oN5otc7CMKvb7&`ydVW}yLR!$^e>yMPV3@HJeK7R%=_SOlvhUF`43acWflLrq40E;aA*oI$ z?socY&~t(=ydqSUAv?y>I%?ySj^}^7tf_Ch?;W03M4}&p=~$+G-X;3Eh}l^(L2^@P zfrbp};|3TEvvqsn`~Xu3I4JOWU>lVY7&WsQQB8)7m@>_F*%kmuDV5PS7gD)P?Rwvl zt#`N$=f3?~+ho{fhlz5?rhHsVp_CrFD+xkfNMzPKq=I1}v=&P&fDEmFMcOtwPd6GyojOaTE*P8r8Lx&GogOBSWqGUg!hsieHJ7 zxY=wZ89w#Y%pm0XEv5Ql}goh<*8>+&n`?( z&rN>e3#X6YeAxFwXkQ_6n5CZW%t^Fw8J{`y#IvW59y|7d_rL$Me{<^3{_GR~_-Fnn zSFS(seVqsHgA>PI${as;7C!z-`1q&lnV$N^U;bD3-S-0zKm71-|MqWJ>tkVc3@x>S zbBiOua5XTng{4cc2blrBGkqRApns^7P<}2QhJZuSXz0UG6W*z z+{xd*6*J=?>Q^gLpe5G`qyjZyHf+Q3=0RlaMr44EF@%Hy5Xi8O;=~VpAsjoX+89J2 z8>W#^khJ6)$`Ki2EJb5Jgz+HqD}r*eJph7InIN>zNRH##4Uxg*2|WOe^~5zhK$g)U zU%SNC?%*<4DLbXbs06+`4zjE45#2BCIB;!`A(m42AW!YK5{+s;BOTb)#J-~Yt$jc01-?)X!{NjAtO4TFA&yOmK)7RquP+tWdo_=-eAzES0*MVeAnC9 z+LTiE`u%FPIz2t@d0wyAvl2iE>3P2Ef-&a8g^Py|FOH9ohhad%u@uWRO$Sjdh#bcY z!qE5pIF3m0)@Hla8f1ymI`VxNKnGrsq)Dw-%@oF2-|@x#;-O2IE(s|o#!$-i$g$aI zz?)kuD6_>QQ%cE=^(`sf!-r2SFRx52&Q>a67%VSezDy`R52j{A(NB|vU5Ailr5YL& zpFe+bd!ru&K^*h>7cNXpHOD8LPdsr!DfS#c;VUZcqtjRZ{N~yDr@sE!|MKdH!v3>A z^E2%yo_XWc{4oFYNU|g-)U#1s$!aW!XpF|2_I{K3c3>$oJJm3|BNST&3Gspug7z-{ z;aPxCYmH1uXxKm@V~b>Vj5#ZY3(21gTq42RFf$1%$&#b-K1MSffnpm7#`ch`>vAsO znE|pS0T+ajoCB4>z+|)05rE0B*w;oxDP``yI!solwK`oXf$mZAv1VYlqe3iRsUT4X0EVt~PI^3?Q*t>Z4%=fDr zf4NHMiY;hgjrhu#eyN)5gjYr%x*9CLOHIClGJY_A(kQTgg$nITM_|MDOH)ZC30z0o zxD-Sp^nD^~ZErUk4JoB{>;T|?zhAG{>-8Gt+3r|t<+`r#`v7c=&N3~9a9kG&gCJml zt*tE~r8c@+t%hM}jK(w#f*^`=hC2z7B+;S883uUf$)(A$2}j6ikoI~}92v4X7yyki z#E692C_o{lXti3}n0jL}&0=HN^`z2Snoy=v*YyVdNC+{AdIELmR}5#hdKiYmR%@$L z^M#-+(~j%99(taP<7jnt%@}j!=pn;KNCBw&{UnYON4n&Q9f><%){?_9fBwh6Z-2P| zUGMe$@Vzwh}BY{!_Hr6eHNn&s_j z5JvDIW{r6?n*#c=m)Y3P+mO8@7JwX2FZUiI;W(sqmj4-qkZjl(l>w4rm_Ky<@}=hi zz<{$;@nlVun z5wKxHLNI7VFb0GGM@YwY5p^`^Rchl1sEr0f;c(U)crF2YBpk;L5d>?MrbY@;1c4gL zJsf5}21Eq16xJNY&F6i;$-5HsrL^82wCqVoJ?iwdOAo$kxn}U?3T4Nt+qr&5%N~_| zzp8frwqsQHIn5lje|x&ZysItV>8w2xM1Cr{pd zlk2+Ao;jUyvl2`^_T=BkN$;kUH};b#OSF!)O4ZWZ*}0jCg@xHKeeO~v@Q*FbKJ~=Y z)mkVVeD1k3000+;`A6@4+f6rJf8)(6Is3xd-nLr0ur@y1oSh$U&diYxRxd9<`SmB> z_Y?1z()9wPbUNro=gw{4@tt?Audi=xt^b=3e;fcF{@>m^=x-vk%laEnKY#ehk?F?5 z`4^VrzTSqYvwi9Dub)17@;YX`aB;2HsO&rPQLpFvo{&zFc#d`qdma>`@sIuAZ~u}1>N?Q_-yi+(JK)%1Xg01k*V}D4djbCF z|AmkLg|Bq@z&qddYmfZnd+)vXkw+f6|NeK}{F>K}Pt94^DU1Ii*u)PO<0!CZkT&X- zWoQGyju5#PiOE5bB5(_H!E4{UN=M|jGWiuOLd;$DD`}g zPy#U+HU_1%#$Q4pf;<+2)*ygTpd=gR7g<;fug=nLd$Tz{TbyZ$wLuWZXha#-8U?U! z2&Dl{NLm>rlq8X)kd(xcAB3#Ah?>kw#aS|_RO{HRsYWDI7isr8R`@ZEB6x{$j zkh(ph8!T0)*&5M2(+>jEQDOdFf3W>nXh6`bs ztGlD35k>`m{#)VAh)g?=vt1e-posF96LT4&R? z7O$3jOO+zRMv=8 zQE4_t93%rNfJ9D7fLyX6GY|>a_tP|G1{;X148&&Z13)5DS=Waz#R?Yl$lmaW&&{xyLaFQJU^ zyhbZJSgQvff!%lP-A78ybhMToU=Q0bi%o9-(y3AX!1G9uwJI57(lqsbzgDe6o*O{| z01;IxRUt&HwLLyQ#>NOKgpfi|zuz;4n~kRH2}aCR<{GEn=`@?oiOER@oo0Mv@}FHG z-w%4GrxgPjW3o!E8b|TiMCI8h&l^p?SM9X79M|_ee|)U660P{2uT-Y>V0wNm%hYzO zH9b3N%wTPEy%JQ@Os}_=9Y@R`ZaP%i-X3(j>Ez^evmvvrCnY6Gy1u%sVIV~%O|_66 z&vQX5txX!GX{@@PNNF`zuh(m}Znxjs+@6?fM*V1IWsS%&%&wzgXWZDAx8!il;_;g< zKK~2={Mn!Ue)+dM!|JhP$KL-6TT_4MqaVHD=GPs%?j~#D8O0-te|D@hE(%x(ZfBU= zlCfg%DKj65VjCa;UBqB7UEd4wmtWueZ5uNZirl8oE28!?7olpI1(D-8wq32Y>$+uE ziAWoRBd-83B>r%bq8o<(O>B*9Bgv%LzM#GB{Mo0DTz3nCMns({7*RBBg|=7w4h|N+ zNJJ#0V`C}VXXh4%AKX7~ z6T7>gDi>af4DMJDJ4EeH`{cKx9K4}jWA##vr(EbmSJ~cP{0i+nJ`C9k$OH(S20jJV zy8WY+QYn>XSrjFWTE(WX-rR0kpFZik6B83ebm785 zfdx0?I6i&)^lM)8np2$yJrLWE(I$H7Fxnuqc3i${+w2!PG4J^U{G~Hno4u*=qX4G>;E`X;CGA7+y}!|zKK0CbR)9#3 z<3$5yAah)K`nfe_lDYY2;P20P-)glSN7m~N={QnIJIXsJk1d#7PE4&i^<8iI{@?!S zzklSB58rv`o$r44L;vCzfAiwSiy!~kAN=Y^{_4}8`FfIM3v+UQ7UyTp{EPyC%d7J8 z3N5YhZ7q{fh78|9y|z6?D?UmE@I_RTQ8Qm&0Rr#w2*3iSFWfopWhsOqR9Z_R zNRU>=j$0h}c_g$sj7SC>N(L;SF^?0;Wz$8^SP%h|l#a7|)6m`oLvZn*k#^l@_ z+-;OAgrv;{3q+_5GXMeFNC;V)DwPrm6a;{#JVhf&#}QI6gVNfOg0(>@NaU7mW)MQy zvl9=&Uo?iZEUf|pfe?~e8*MmmFCRFI^x3T{4>&W@l@U|<)gIWn16)nU zm7@A8_v~o>e9yay!@7^+NA@6Kv&iNAxzY1$4)Bm5)Fen~ zV{FuRV}_`uJ#7F8E~KI$QD8Bc%f_AOb3!skLrHF77!3NZYh2H_p>6WOmu%meJl}^L z&k@Eb5@N`qL6TBtSspi?3wK>xiBhSM9wIu9Yk3eVON$7^`3MwalDk5UOyhxM))ntL zm<&H)WmoONK04^PTHL-o{Nojh2pd z9G97`X{QK4;WI;)r9w~`2CnPb!>>{b2#F{RLjX+EL~Gscc7njY%lpfe+^yF7#>SfK z2dsqrO4@|8_MjJ%6-Ac7KwR**9469YgWuc%}4}=6ibf>3g<3t(5MpIr} z9smF!07*naRCB-IClFyRP&$bt6`O(Y${>);iBc*}RC_yWx7*cPsFdzT+n(!5r|vj@ zuiI|`H9^Y0Ho{s}`o8WBC`q!7^`0d+Z>QZ(r|6uVFN$gjz@W)P&!WwW3I)aw$c43bm$US!OH_#mSrED`LJBZ>RrV;T zloAE8o0*ZwFksPK*|D{ny`FCsBfdxgKqQ24Mo2eU45=nj+#@JU4I*i+UB@ef;KWJd`@Si>o7tdn zJgqGc$ksy$KtjaPfLSBv?Pe-U3n z++4L-7Yg{= z13;hu+t1mXFE6c6P8=F*P6dIwcz(6t<<|BVAUK|!nw~LiH1{%{?AuV1L`edjP8Sh9 z&ui4{uIGE6H)7Yq(wJFJA|cK$9-W$BeE#Cnum0Mv|M-vp_-(h{_U?DT`$Hf8y~)W* z$8naHmM#|s0PcL#{QUg+9>E_{1mP_rCXi;~U>Na_l%r_xMe(1+u(q z#8R~8IX%;{|MTKDl9I?VM!tHIwU#z-;mwM&aySrXdj8WW+`I z5&%SzE4zh&E!!FfTr8mkMp5Lv1Es8lWM&eg@XOed+a3`M;tmKR08m;>X$3gt*bNbb z#g=VK3n#4BJf#NxE?P+>hL#pW5<+U7$KkcQxUGkffH2hxi!>Y-1|s1ol?i(k20+lA z?Tt#MCY^w!V>`mys#YL{lVzEOiIOZ4Qm|nXj$zHrVWrXQb)|HbHiW>yf`pV#nk0&q zU^WN@lyN4}HO5FOFn43hZP5%n#5fdZj2)l*zIe&iaNf~By%f>?5|#T`ZF!NmIf#%x zz&*Py&wEGNelv(@08Axxz$gGfBEu%Oan>6R*LB-~UDtI3-?v}{ z5pHa3&@=@>;CXJ6BnBXgBWAAG>I;V!T*uwo+HxeVtZy7Sa#%|D%U}LNnheq;=_jiv zZaCWSXJ<}5*QnJ1p+AUaAe{;?t*oEFxH&ala|s$_)k@U?s3JLO#0vX<#rMO>@$pzC z>Y1l6GB}lLGC9-qeC;@a6w)v|(VtsRzttCy_IZlW%a6i=Je(u>IW6C zQl0kQbbeMp_v|Id3A)`5p-xp2Cz^!sSIr)-ZC^Db0nuR>dam+%QL}Z!$=UJcl>(h1B+a_?h{usfn1?WmRpyOW_97Co$&)zQU4)2? zDWH%M7zzoI(KfO3fP+Km1Q?jJEOk9^1pi_fLN2Ha?k9sqf2>H%GkNC;m5|uz5xj}A zObO`%FcJZS(n^S&FvR)jbHNO<4p8NcTut1(xL`#b{{Pww=1XlyQ&-}|yc*T;YvJo0 ztgctULNNL>vLl5J%2{}9Bt+!)(rAnzRQ@-yxj)RECFtdrGC=3I~afJ}wZWjQO zBq0()O0IQBdb0EG~ZdNWhWxpQY5&1xkKSG()37Xm<7m3|oX27~SGZAn!jNt#3_IwGSVSq!oUxcM90y95I5HQm5PsuNz;Y)vA_MRKYr`||8PW=HznR7grEYZ8%6OE z(S~9vWj9!6HydCuI1=ltu<|i5v5iG&^?QRzWe|Z;`v4afS0MxeaGEz2LNLj5wuoPx;83s zzWXwF+FMx~)N2!fU>Jd+S{qB#lx=#E9C{_s^&%V~O1pC~7?mU#_*s^bKbWU&%T zSiitrt^mXgH;)5I;t{QV@6Bc}`(uv{=cTwE?UPh{xOo(q*YHgEGK*T?1IOTqd1k1T zTuC{9SvvG$nm-vbh{z;tS{BBi`04+(76hS`Q4~3jlVw>@4adgDgb?lawq3eHh?$ug zL|j^0I&$QQovccwBBi`|@nW@Fo1U7j_#OcMn}78o0C?aBAG-Cmw=6EsC23!C|Epj7 zQoolbQOA>J>Uj9Z*T3z;x%L0}k&oFfjgO1#Po6k&-k|oC=eNU21Bv121zkFH46ZfbBEil&42xW z{nl^&+uu3=!dYgXnVp@Vn_E~|SX^8LfJYyFbZKen^78WP$_gSLId+}W#;??Gzxz!L zB^@0`iRXEPmM&7ntTI}YARD{H1}Q8}?4=4UNaW%a^G}+}h^c6%pu-@8jeiIL z1`OtA8^Ti1mZIBsM-TvN#THUALswS|TL=Kq%4n_0#awQqbtM?x1$bCr354?WxZZY z(LKP$=qH48@h->TXhYlUGACa}euCA^gIip#nar}- zaP-WxPep?)OZv%x>y!R%H{JD(ubgeIck4lT^t$HOR(J8p;@sj`rqXAhTIy`}TtQ>a zuu}0mo$V~aUbNNQ?$69jHQ8--m)Dp3Sq5VhwUaj<>BW7O#Fa{2%8Ek)8;s-V=GUA= z;w&K{ltAe8){{tHURqmQkL$IuUO#f&ipor{9Y42r>BJ2;O5vV4^Ssji=6E$p+N?n{ zHD~wtGgb6<22M4Df_BV4{Dtd!p6^R3g_QP7n)3Wd?t90NKlGj>x8Cxti5u`wKk$L` zPdxF@?|zf#`a>10P=|=9IKuD7O6(0KRBiW!QNN!u$9kTeXq2l~d`Y9!yt4j6vEQMC zaX~^UbV7?*pg>V5x>z!}5QQ~n4q5O;3`y$)njbDWhZ(WNjCO!FHp`JDL0YLaOOXwb zv3V^pHvpgw{m#tR(lBZ~00u^;!gtuP0V1307XXk5jAG8BK|ctqSmaK!9#6$)Vr|lx zMH#d4{lKz$Y~WwV^%1EYLj*)XAw-g81?>d@Im;43p4M7QvfBYt;UAFC!xdM{uD=X- z!z(^<#R?86q^^G3w-1Hc{l@!XFE3~3UP@I5dWP-FwQ140JTe$I%9Q2YbpzjRG8>~6vtmpZk4zIfTIps@FsOKd;2L9;QPk=5 zJU?hQrWf8fV{?AF)6{@o8fbZyquAN|p9Joeb}>rc92?X`D( z_h|T7wzf^kS$(#kbTG>;ho#VGW<*iC;aI_EZRw*3JrwzR?1NHDr3@fie^lC?;l(02 zq_q~qbBhE3A?SviUw8WH$NuK8{^Wb#{$4ETBxPre(N>h_E=41#%}~b&_~Pe20RVU0 z^LEtI7**zeDtj@|J_k3ejI(Fj7vkw~nR^3fMUDqR?pdFL7^ zV3%E@?L|cNa7Q1N{EeZzrSn@R%~;^vEmPaw?()joShKE`@tjbI{tv(BEr0X}pS|(cBem+J zXm#KGw!2`h(`Z&4r@<<0ZLe)^wpT7~OieC?L9^DFICA93hkoUs*@k8h&CE_8t2gRr z&pifOX$?Z~R%=aby}G>G>2KWpx?}xb?cDRrf#VAyK=AtI?8-yUr9WfgnW#JMwiGf< zD>mAt1i>)m8^REO&8>{h@rlOR1OrdZAJJN+N!(4+$Dcj(m2W%=0Iuh`t~W7vc<$)+ zVo1KHlIMyJ}Q0fpp(@saD(#(>pRM+kcPih$frDOX#q2^E2eNJt@sfkM$nppx;P z$Mr36nfxY;&r+dL!)PBymK+^l;o&C^u6Y5_2SiR09BJ(3=gWHJaOUDsymW@fS;Oe9>_B|<1J3PDOK z!(|?moj^7gy!V}&{isB~O4%uOuP8i6e%vFv5%z858kv0ul9R8f=sw6_zLh7D-6Jw2 z+*v+z{w*5A+87(pD~(g7RKGuHjx}A+6C|=UOVc!pqA&=ir>Dv4Bn)YqBI4xaq!1!b z6C_B}43WYx^nG6l+}K!8(g+Z1wOS>FT4Qp4v6`v$@yAXjJu^2uIX+qOs?hDHVYPDc z+*%y#l}j5c&Bl+8`Jo#{$)KOMx7#RO={RG}27n2@hRXU{q362o_I8?OVNgvIouutF z+D>A{2J6kH=lZ_yC&^a3yVa=GpL*gOMmtk8iz_SV!Ek%KW3*~_+JeOT>PDqfRk~NH zdMZ`D&Ol1faYY*MZ_CL6Tf>&I5%c%Q2?!;Hl#SqTT-W9}Gl=lOp~GK4edhSFV?Xgq z#tr!Shadjv@BGeN=H}m0Z{QAKWhj3vEKY>FU}~4Ql`mCV_i|Xn3WFgU135I1g9{^C znyr0Ed>N_`n1c?xbyrI^!7|4j16VF0f>PS1>@dvM08vucZIgLxPy~8sK!I$a^eV!_ z`*JvC){KDy9a35wX6tFaBeozQB9`Xfyp4j~P|}5fp#XsF{s@R@Q-^4+jg{EI!_;(z zNG*oi7^6q=G6WQbQM2f^-Sh1+gaB~F3Wxa|6_^>?&HKtMjNO-T2&27dxvDljq6_bH zasSR7r0{;d!(IQrbX0xMc2KL7wTA3bq1BA$Eh zsRxaDaAgGmKKuF4f9&zcfAFLK?(Fl=F~jWa%-sC^!u-PG;voQd^wBRYU0zzge0gPM z6%nsHalHYoHz(e7-vj%vhEeWGscIo|8Dz_DT_Z#edn&*JXec$;T^mDQ6%mm@0M4D8 zcJCskpoj9|LeQ5fGYXbU9xb@Ik+fF!EF>IhqqP^IzjmMezw-G%zw_Sv_x2En(RTBl zhKK+RQJH`PiXfds5yK43`1EOmvKk18S}YHe8SK^*yE)qdk{ZfpSnV3Ru~ zYNarD$g(imkWVr^903s7J#}Qk@6=#2d<&rYZU$8T9`%y#ZvV{LGh>Z$rA%1&HlANwTkm<& ztSqnI^QN1fUhFs|1+yX~;RpmH1qX3v0&n{GvBg6Riz{oF$H&J@EaupW>s$@O5$Dc5 zgCK+?X5DIS0vgYk&56qFLTz)awYA=fqof*yp67M@k>~EecuXFtIw$LmNJv&HYqz!m z0FnG4@I0?tt4mkzz$OaXIRXRZ!P}$|A`FADI?~Agg-0_w5rQstX<^p{i9EC|8)GyB z7D?R9kVsR07l?=g0rCiifIvc6-ki0BV$oX~(ZvDsQ+aU-EWD9ZCP$NZ@Qwv+jAm=+ z$$bRa?k6@;G_z4Ejgu%%{Ys@Oqyq-+(k$6PfM~QX-w~J#%^tPZ`Nm;Q!7$X$ZLl%d z3#IEu{hrEFV6oxR(9m8o4mvWcvpZ-FAh- zP;`?)06=EVh(_2*Z-90&M1z6jIIbhD?KDXfX7B@_1UXVv!cZHtwY4=pJ#9bpFbIig zeSJOf0}|*+*KrgxZf$L)X*@RGY&NFG$D5Z|FEeLEa(X(vaQV`?Gb_^Qx4!kYt}mBc z+eUCd=|1=9<%OBqxEJ~4_Y5zsT`D=29A^rp2&ZRfHe2h}Y9mebQ%{{0LZ0a_0fZA%lPk+h07wLxilf*dF_NB| zlYqS$(P+2&D=XX0M$L7+K^*rwS7x>sS>7xJz`%yJ$@E5gHy{#G!~Yv8rQ^D{P0idk zJ@bXn{jsT?mDX26c*E5 z^)xV=C203I$!zn7no=Clh!qEm3WraOFmZBq9Y=Nn9=YxRqwdY4E;+9IuzPP+b@$u9 zZRY!C!!iH}k`M`!Ah>|EHcKWXN}?#s5^2d=q9rgQfXly4k{N z&+48E4t{-z6Um{~+`N@r5sG($jP&&&ug|zP7sV94{{)$z(bk&&E5OCNgQ7 zAK$oZo@G0`S5VL~6H1n+EOPzYWzukDV|hBE$s{wRod_bNQ!a|kRbPi48UPwNM(ulf z0tz8s@@kDDa?kw_)aU@6efp_ynNHygp9g>x;L_Q%f9sBWo__A)7ry*703=B#>GbZr z{}uN?_&ROk215zOs~g;W!zdt*+ZX`=7^TYka|3PE;)p#ag1#d0nJ9e5CGlxZx9g%+Z>)!&%pZ)m1KY#8kcijCl0YXuVl$8FFU_s2i5)W3M;Qqqf$ ztRDUIzj#m5>HJ@RumECy?ib%OTpQT!@rCEcmoIId`{HHz;>BZktogJv<(w{zH`(F& z=XQp}-pa~ak?#(A>!di=)s?H4zxd>{@Z?tk;KzUV(JJkCdIK$^VQ(c#l6U>_zx%@D zAM>sJjd#3rJe~|LUY^Y+^T|#Usg;$r?XBIsoP6_JUV7*0qt?pjAAjcY&pg*n`r^#W zC>f5{x3@N@ySuaT;h8mPzuXRU-mn+~fO9UJPqX=ScW2v=QhzXt;}{Wr#yF_$l_G+m z0Jw25X zY?khpxmLP2Tvke>YZUju9TP%_LedcS537h+*jnq85JAl*Qx7B|5i)jqgQ_gDY|d;E zKzZMHz@~d`lYkRp7NEeOL#V7P5ebQOWOSq_lU-s)@mo^FwgPa7s_oF@6B82|VPvrE zN}_G#m|$F~h;oIhfAoqzoCYl>w0Xd~)^bm1|qq zlY8#Idp1kA9M9)zo=zj9hQp=Fcv@EJLvOt6*ohVAH^rpZ@Rv{2%}NuRrwg z!{7fk^9KCdum0-a{DB{M>B{Oqdi1TXvQ=3iE}Uqw#mNG7P*0t=nIVY%pfE3BlsZC* zl!BTrw$9EY?V15RBBS=KHvvST+Q+fk(i$bUX~=^V0JWP*7}3Cf0tlJdm^1(YAOJ~3 zK~(H4yXsYEtkU{3cO)SpXW$A5`$#ZE*8TF10&ShSabwx*ZGnU;iWBdO$P4yF5D*OJ zP9MaCP{-}p8z|IHHz@3C*BUfYR1`UB1hbAuMEe&8TpQFA3}wO|qBw=fPjyrLJN*S&qcB&h72OYg}G@48%qov+>cbsKYM2wT6 zEz2b8T)OleB57ruv&?pujyqj_;?DK?yqHb1-QCn#+v{~=(@kfys;u&P0l|;$>rw(7 zBX#^_jcE7@!{$pwRLb}y(;|Ul#tEK#`l%kkeE=W-U|_X;>tFwy5|nsGL_rQZm#Zy= z3(M%9vJbUUMu81vC|JkZKn-E|i@EN$r%Gw{ADRzP;~MOpL=XtIfLlCX!~RIB2@xly z5xEI0f*KNPJWYtmId0w>W+ttgYXCqg&26S(f#WAmU%Ge(0K7lTYu@nf09pjSlH7y> zwK1vY(X6#TXA>^mTf|fRfZ#)qJPIJ6{^)y~=Gxns*7}nl{&)VThu`$p#>m3gPzw~RzeM^eA*{mYCG$K8>qc-Zo_ces__FaP=P{pvsd&;FZV_`Toyjqu{U?H%7VyBflR zzVTZgOy?zo`@-kXkxiDCY5n+mZ>hJs)c-&J*&l!Z1Fx9OHvjznpY#|1@Q?qPiMw5+ zF3vWyY_hSje(vnk&p!L?124ZH9{<>z-~7#4KFywZJj?Q`bjFy;B(*NPd^sBq`=?)e z?^nNa>2sfXw%1wd_lGBsof?m)X)&MW^Qy8+sX>2~egZ8~%2uhKY+7|^BQ0?D{B*gWZ9s^5bK>LWrdS#x4#qSGs55kz$hG`H1!p8Yd zyn-n;f&?hSz|IP%>9pS;C{obkto2opQh@?M!aFS?#dvK)-ZO#-0L-3Z7k#RNJfDkz zV~3=g;qn37WmSUOYcBEOQLu>Q6(%H!qNKE8!}9vSwPI923KWrb4ggq0Y3;Wa@TitT z0DrRb02Nk6E?!;E zc$0>1tw(`1Y4PWtr@D=D!+Y?i7qw3iH$=N`d{^u5{Rbqe&yCFwxFG)6o6;P;o+shO zQA#=M@;o1nmPbp=gqUTywKj@$5+{*~NTIdXR#lc|E6dAzsI}7RJk?rHrjwUnrfcT z6VttT?b^|`<=J$Xox6PHf{ByqWHL{4tyNK!&gIjIRJIz9dhB?6b8_yv>nls^RmFLh zM^QZ8O^f0xkQk#6I7#oFp!!W}pfW$UKH|nRIEYA=WnS-!lg_uDIQ3Ug-tonYmw)#k z{_4;C^iRL$)vx~k+hk$?>7V$C&p!V6L#OY#J4$};m9JJcAVNrpfeTCy_;)u40jMFH z7Fe^m0BXIOkidJ=_(;-)Pdd~x!8`x8Xn+G4-RSU(jSTm)LpBY0N$Ux9YmDAE5X6pS z#}yX^L~#e|=4Fw&DUi8{xBi8Mc!2_6SV-5tm(2#d*z6EdX>H1~5yjw-9RlKWUDvQr zJ>}9oW9wT)5D2M}IN)51B_b^V2WrU<9`2FggHwln)jbse3DyD#rUPKp* zYZHVy~gulF4NFLieKx0|q zg-?T6TUAxn>2$i?z6d)O>#X;DjH1YgCNaCREW6$AU@*{H=Xs7uWmPHFCBit4ZB@=@ zGh_5*HU)seaFC{$W@$RhrsLU>wPjLnGMUER1Q4oOb?wU5u-`X2-pQ^bB5I1GI7{=| z#Kyf|9|4I}zn8Gc*4CERW_fv}4IzoO5*Y(1ET~DP(@BxdjlxKy)hdePd_E_lvaF0T zEZpgI(%FpJ-EsG^(Q=O&E}Xx{j*N~J=`y#3oaZ?+2U6~@hyN-7G;mB=mhC)5!3*Ah zs-5nj7D3X4GFj{SWq|avUw*=0^REB4xO-!Y1h_gQdZ2nvQqpD=X`WG@0y1vEJR?28MpWGoPpZ{xHw&!>@bep(9^amFG5Y zP2WO9G)uA0*%3r&Rb<;m1^|GnKNu!)((Uy~1s%~>5u)E~WjEA)gT=7`Xwa)5*q{&| ze1S%RCL#o%exku^06c>Xh!dq0z+TB5R8X(=(SB2w2T*D)8G!(SyfL7*Ya+INGy)P7 zBA;-P4BKmBB0!3q74Qa0aKI!0Hc!V@VYG>ot|IMw<@`qDNz((C4E`|z0wJ2zxlRc{ zYAqRp#sh>ZNwm?CvkpnsDp5Ush}k@ieG$`7ZQXE3PTci#o3}PJr$0w zZUT3hBb91IYYfRHwTHKBXhb`O`^ zt)tQHm77b(uv^_ut$5(W*I2%OUhaptc1V!}f8M_6K3Gkg2%|YBBe#4Ypuy?9w5SCG z3$P|K#@Mo`sw$4-ZjuyLfr#lmb+#Jx`#wEQx6>)gqAW`qkaun$jYiIKHcO2*grt-* z#;`apxGH%t7+$}2pJ7-0dVRToi@1T4{A;eL&=%dg9`6xJr~nkr)G8o7X`gj-x!!I^AAg z!2=Jx;_#tw1L>{57hr{lJ`qHughv4&%SAE-guZ_NeS^_Umsh^$)Sb_4Z~wo)^E?0g zcYpVZGiO-j*v7{3W5W9v;LA}7H^1d)OhBQCHK0RJ*KX9@)Ip97zD zqx2pM#6a5^0D-9;8V^YiF$*)mL+6>4eeAf2qS(vh#sS3NwXajY^Ipv+MIcabShe~h z!E#|tgaFn$zjp*_4=5m>8mTA?qg9ikuOSbH7E+H$B9J6qTa{Ivk;BV&u89JW&^hP* zLroL`f~^D)nH`Z@sPRZh3X#e(kK(R}*OjNfjfhXL#R8{4ZXwcBWb#rpkjR=>ws z5ks#QpSYYZVG6h#F9QG~`ABJ$RqEX#(&q1M_M1Bl)R?_7z1-EMa>*nlf$C~Km4GD*v_%4W8lx$W6>ZGGj=yEd5FIycXX`CN56 z6nA0~SUa+0t0GICld7uR#>Oe700_0|A&Q8b&x=ksA>r}vc9zYDgJGVf)9EzJQl(Uu z^D>`jEW&PLqDWY*<)jlEL(|FpHs|Y> zN`PaEJVPMAQ!1sj)=;N>K6t!rzA?u5`LovEecuCK$~^nkCjsEy|Mvg%*L>Ia{}3~` zv6u!@JqQ-m>=FO~A}yllmi(=MZBti)!m`pZxHjfXBC3fP~qeICc8s`7;3UsgJ%3 z0ABmZcebIW_JFr{zJ{E*jgEoOaz`3K9)8nXopai`_SSWf!sas{f6r?ld6W^ExpDSE z1m~;>0|eIS=bnE2p|xY|b36gg(^(&B{54fv+CAy*?@^ z^MYAOqw=-rsIrwG(V{Gq#1QzfDFEziXY^-rgRM$M@cQ&tNc6N-Zrd&GY>HbIQ9DVkJL+{_675Xgb|_-@E<;031JY`fva816i@HRWh_@ z^XgR*K?|KIK6&CqT2v3b@^y+-nP*2=E3xiNUwrcJyY4EAi@W1(FJVlCCy$@(b$d@d z^{L^q$;+$j>&GUO@~dAtchB7q96x^ilOO*GL7dI2V<%5O_2thUI(lVMAb6?~R34Wh z72c*B%k75y$vHQh>`ny`q0{RpNz&`}wb6oDpW$1+Fg28RC`n#(jThP?-T}n(bMF3^1w%kSl@OhV@=|47klmUTA0ke2-7g9*zJ!=Ae4O{l=uMf@#009=CHd`cgqXCy1 zBbbQS8@%*w0z$D#4Fy0xR-Y}3D_vDqIS9ul0i~59Vb|2#7Tn&3?1Q10U2}TJV9_P; z@us9u7!;}q0Fl7Ew<=UhM}9dVfY!=uZivl! z$*c7X^0n~qEo+(kR_npl+ZIhhf&EWTbU%Lrz8505TdnUC-4a}Yzh0udo)v8WB@5iZ z?;0!w;7x`i0MO}n0l+fP^Nfgkovw#qomS)VxZCZp8&6MQcb zttoSI{kSpFUq5wM>3CA)lOi8K{mfUs@FV~Z!D1V{I2JcS%Y|dV$DEhO)P65&*7C*--1M`)zBOVYEJy+x;#dF} zn$8Hbs~$RE5tW}lm1v9v>(qODQJCH-$ zZgAlX#kK(8@V)2Y5VXu@VXac_SrrZkfItXDz|J`UA{7|}A_!6zxz?HpNhxCtA~@%K z9&3*qBuN4Q)9F+x1%d=%ltO?LTfe_UxVE+mpyD_JVV@XVDN>pk%=TthRpoqE0hH6p zq|@!hiAp-EDsy3(rUjwuc2reXBC@oya_RiGfLq^KK~Vj^60};ArherF1tT37`E+M% z+gi7>x@vTkc&oSe{gMxCJ47hR9y$jU;o~Ro282uJ zp9O$Vee~S`@bH_z!w;v=yy_9_+QWsKXZLlsoOA?07Qw6a*5#a|1H13ZQ}Z9*@_)Ty16*?!(ixf_X^3WUKN(9!Hz)VVsFe#{t`5YlmI?SxKPiBTn835=HM?|C) z&C_X;B+jwYF(SoL&sLzcs%$|zBA_Tqpek4ZNSw9B+;+MKF>t~M<1&&rzTL!gvi-2l zXTkl__2B&;i)m+WI;1Ljey#eJ1m{6{eBhfG?z;JWd&J?YT`~MpwEkSFiQD14_ET{hR;5U-?r% z^GlFs-K0Ajkuf?=(=<(2R#pHYNs^6?4I;XD@zTBb-YX)6XpH{!r$2q)OJ4%O?|=WF zSzCVklb>kXed~9BUpk-VmqGN7cR|@9bfggcLyq;yL8qW4Mrl^?HE#8Z2pPIKKb$o9z1#1@hne;dF$%s zuYUQdV;e{Ay6eQ|)}?elMMPyfm(HIB0Jv~D^yUKm)wg_$!okNr@DTv`j#s~VJV`|{ zQZ*VapFFt{Zy!E-ffc0AJuf0aLWER<>H7wIaUUQeXsvz3r3mL)#?C6z#u=rRF~&=( z#XA+`1Hlau836#LqN=juLp{BeXhIF^PH@xVI+94ZX5;dQx)6B;KG9IqXP=9a5NiiJ z=e?}~fKXwL%{02Z_}UubRtwdG4$1WZhHeTok^(~DMfjHg6-Ban>LQzT2UNenb+{9H zH=p)^d!wogWbG}p1fl1H0jN{*g>A)WdfL-H=WLPZS{qW4ESML(m!h8+KyOZ0(zt~Z zf~~3?Ac~@z<$=&!BtT4L0R29X;Mh6ViU3e4V@&LiDK$X@Mo~v<^<0?!Q3i>?aZPUH z&lb0@!PkLbtuecyfITGUaqsUpRD;7&OLFlBVhLW5)&DrAwE}vb?)< zdNdrBRpDR8>7=j@I-QQ#9Ff1_f%~34d$}9+Y*C(h<|3jR4%VVbU%GUq-|K7L{mNI* zyzJ#KosK73t8Tx`4uE4)Jtq!Dw9$(2>~rTfHtt+mTN4CkSLDTobI+AUetcuYRz+DB z!I=&zN#dfI@9u8JiCJA)HBlVtzVKD0WHem17Ob;Mf!10nTv=HkU zw9y&F1Dr;yr9y**+QZUkoc+KZ*p@TrsW zB4lZgRKY_&%VDAg>k$Ynxfs0iK^lJ_e=|E<7NWI*_M5lpWY~BJi9w8sByjBepLxMY z@9!lL22!MyX13zr%rF8ZAVf-Q?E*ohw|oPka^fTml_*7fBB^Q`oqbr$?Unu3(EYz3 zlt?cO>bMmVe#>act=xB$i*D};>S>e%+PUoc=QcX<{H--@NsXf)xK0)tya)&|11asz zEmdXNIV4Qt1PN_bF-w+ZQ4|@YyWOrA7iCpBYmG79L8hvl0F+hrp!~@!imIwKCaNk6 z06RN7tE;O5Vl8KRd3|eFkO=k8<`}UW4tpx1(Ws{tPA8mZX`~}&IeK*U;)Sb8oJ0|I zIip-PC&$lT2di&y2-b{_3gH(T z=!4R@$pFA(AO6$V|CR4{HC1GLuWEnei$`RddYXNubr~@WwK#YD*qprMJ|8Oe*hk*= z+DE=K7+!oPlzLK_g;|i0t@!+8epd4=HIY%uIA#VhAzPC-@Q^=!IcK#tSfggf#DGwh zrO^t(2m>iC;N3CAIc8Q1m=D2gCJk|f8) z90qPh93Qgz?b|QIIc_m@^&uGd-Hmlr7q(8a2L`{b0kS^|Bipjfzx^HmHLycOqqWwi zlSEo;1W+1uHnBobWl|KCM>D50W=7J#`&<8muj`#Z{ol4}SC$>+9>oK{uOj&*yU%R*GKn;Hzv^ zj-)r9Y-x=}#Tx0MhadU$V;^mg@cZBUADYiQJ6ly%My3;MGLZ%pdm}D)!N6}Tf+Eg2 zfr=>PDfHC$EkV&XFxG)S(gNHP2;v?*2fpFeH93JGTu?jEUl~&Y3IefKLZoG zIv@-Hkd)HEjwSdrxO`qj(UP|uvoI<0XY$A--iby;(sbJE^}Pj_P<1*3K`QdOR%CRH zK;3@dFE~THP0irn-$oa_U9{29uhcIbT{JbhAp?~8eZ55;J``D z3(s4qtsWKs$1UtFw>%)tBQ@W)#=kMW!(s;v?_OIcKcp?ch#A@K>}<|vGZ5B*OJ+3og_@R?`Mbi19Tmpt>#)6TikXgHfqpMLt8?8%9VBEl%kXDs%}+Q#xybmv_s z0OgGj-y3(jvn+e#8y~7l{@mxDT03&W@#@v9vy~%9lTF(_ zL~*onqI<`kr!QT)yffaiwn{o(lrm0|wIj=$n_Ik$N}>P&AOJ~3K~y)KXb^D@ya^72 z`iuy{V`k5*go~RH5KxhV8if#cNjs>!hF>ss^#07)62 zc>|Grx@GYCb^{oI?`$v%w!`P4R#!b1A}shaLh-64cxS#^lME}dM(Ghi$X^$DS}?%q zAi|7`tf16@J^;aOoF$}h@@+FSp$g6<I~7s0^}oM8+=z9Zy*S1?>O{-&l@J<+&rB|QKC(RNHr;tgb*$e&(}++L?Js{ z9{>P^=UEn+D2fyC?u#Hmo=Z4l)_#I2TWYPt_yQ_r*Z~qTJ4FfsmDa%IJI2hmVq<)? zEWyGt3v20cE5OC`=-!7`aRb@*e09A@vB?e@wd+ugn1>vfiwhAbFG zF=4d28mDO*C!O)`4v-*o9P3V}t1_snA~MnQOwJ1}0gfTk(CD2QCWRfaMMSh^MMQ$& zoidCu^suSGU|hl>Lim_sZL+rqHB@nkwrvn5|OH6Kt#1*L1yM-Cr)3!=tHI6 z{m>h~6Hx%zxdlnEbEQ&B1eI3xrmGmBD%0)j^CL&^pvXUks;UAJL8uO2swR_kFk04R ze709(6d^lT7MYm1kEo3{05BQvj0Sxs(OR<*MFu=7ztaI*<|Mmace!RE6?d<@vwzlrT z<@243=bv*nUs*oV>n>SquWw!-4M%t1ediay^wieY)o6Vr8()Yga1D#}LciSF6v9Z0Qo;^Ex^P9dUNs^C$ z>?2`hMVwt7El2<4AN_s*&9D7~U-{u5`H8ia<>k?EcXzATUH<*w`)&WzFZ{QE|Lk+m zfGyUKohS<~it@s_GvD^IlZQ_1%O808Q%^p1{o2*__4Rx2yF(kjd3`&Z<*$9{kwdR1 zR6YfC=obh8FatYAL}x7m03neg!WN|7FtD`L10e=-0Hn0iq@xG{opVK=d;S*_#Y%Y~ zrX9D?T7iHFf}}LXT8U$;wMHNYkL-t`^AZgaMOZ6EKC{vuxeWk7l~szgHiyVLjS9WGZ27TthL^~wjM8F7V`8oT&JmHw$5p#f|8;M0mKObD$+vM`yP6@Bphh{ zi{i2(&8s}`_6Np9fW|M{fOa8(FbH|RN)Pw=@FK^owXTt=1v`&_I~AdGj)}Z4Phb#m zBEZ(V-Rz4%3dpw=(0!V)_LclVgeBn!H){d@?hRbWKTEy+_rVl>&$~2vwJ^Sp@ zwY6@4Fz9v5q6EcjM~=Mor7yjF`C2+3U%hhe$m;4>pZ)^#auTggXD-dNkA3_zz0St& z&UEeQ>SRI}FQu<~)obG@dgAks&!=uUSQZd=qyE6ekxr+RG@X3;%jY)MHByMa3lapr)R6;(&Y=_%9XXFRVih)yRyPDi3j}y0TH7p1`w|eV*9;q?r#)tqP_1mhSiDyK2@mF&_ob{ z0FcNctBVMTc&KForY{z>^C3s**kNA_R`Km$O7ndSoU@vYPA;1e{R}{Hwb~JzJZaeZcMHk~dl^#JhF z<*k0dKb_8_XdrSmHeC^At$_IKm0+R>K&F%F?s&YqwpLadTkD*wDmxquN28IoRW;AO zJ1`4t^xz9Bt>eVliqmOcm3Fl3dsXH6T!0m66$Rr4Ga%|-cM0I)3ta*?D-9e&0Mv5I z@N$6#0(ZA_4p7)xM68NZDTRbu8?Ch$J$qdx}|lRh0+noO7g9krmUO@!I;(Ia?pS01>CN$+dKY?bbNh28QW_1+J{~*m!4S~tyx>V=e>XW$m_rHkvF{A%A7DRtNBMh@qt%8 z_?j%szWkLhoqg`e+wxy|x;?tk{v^WNFAOFOMiNHGd?3qnPbo`DH zyI~x!KlsXxq!XPxcdpFy$#^`QPM4NOeqc$N-~K26uo>s?|AD_nAXt=>@#KB)`IGh( z{N&I4{Pvlr{+~bmgMCwzbV79D>t6qcOBb&Y0ZSFfQ33=2&wS;JujoaC;n54{t`u3m zdwpj*9UnU7MC7rIIwAs_MJlx)3JEY|kxBX{-Nr<(9u|t2$dqN zvr5(G?XoC3J=aW)KeVV|n{^^mmZjD)A_y}m1tLWLlp;hZ9IQ3YT2jGu%mJ9I={cpI zD1`dIJ>^how_g(1JMjJ$(1`B6weE5JJ_PLW*X+HcH6!hM4(ZzsCH-C?(yw~i^XFmZ zfRf$XQx3U0SgBeUwBCaK&4d-QKweM~fl&aF1%N{WTc3i=p#TaoG;kmyFoNW>@p!xg zBC!TwDXUT{1c(8^&F2UZ#YPaE74M1Q*p@{V$A-(w+KK^-qRjGKDXo<9iS4ygX_{WW zbWx;SUS4us_Bz9&$j)Cp?@HSr^v2`uyY9Rvj`j9P zI}UF?A`+?^Re|;kzX)RS+cpBC(%SpeiGZ`VvW18!rIglC@A!MnIpGWc7W?pXM6lRG zTiVD%qmCi~676I2ZIlh?9Gy{zy7f1Ryho**J*fE=LjT1@tb8|ckvgc}bpj{)f>Dve zLj;F(hn^CJq4HMRI@KdIxXl}{Fo1jPc&vP4by0$hK@AcFU|a96OQ-CS#Zio z>$UcyNP&zJgCBxNQ~-e4@jRXM2BZ3F4geMgEGDoK3lfoa763iK>Ref5S(J4A5R0($ zVWfVyL=oYl$a;OB$qQLn5g~|(b5=+pVK^(5c^=1+fX|AB=&9(#vXF&kJPqIYHIqO1h zO7CdKh>#eq6vc6zrt>_X13;2=k;KANS1w;44Er7R4J#`NGtcK~94E_5qwTG&ESn!Y zelm$8Ywf4-zNllq=lFDYJVBIeSIa@aKbh{blRQJCBgfU%tJm^e@{E9$lW#XPZ|yJKe4#Ow)9AWf{;B(az3TtLXT#Q1RqHhwg|4-IP504`X2nkXXYoX=M=0$Y+8foMz58DQz#G2td;DEKUMZx4ZtX^bptM3pw&L6#DxlilASdp) z`{KE01(+G@WGH(gb=&=~DR|Lm#cKDh1&xtX+PQG{^91Z|)C_9>%o|M^_@qu^8Gw{> zm1TBb;jdp>YPSo3{_u>5govmB*?X*t2m*&aoC1OqR#c!rK$e;UX1{c+XLGSx+z3%w zltaLdRy6R9Z@;mA{2zNC*w^QqsPfQ;oWg0LMdQLjiD*X1kFOvyO0CL!#Yh0ek!Ar3 z*DC@1onQIkn|Jkl-|yv2|J-0h{NA z(I)A{wsJz~@d9?>oYUGnX1l>~IOxWo{p^{Ke(XahP8=)CT%dpQC%N>ubXAF(s8WyV9?vy8Bb@sySv+LZNJx@PN!PyZnra?rp6>m z#|Z1$e4gd!ceb{Nqwem`j(=f_(k`!U0Kk9w3xB7aOq<7i=R1GImG;`!c2(KUtY;1kPyi8U%lQuHyNEz4v1KmKRZeLF^1CyGfVe7Ww$5>q zB-YxpELD&s%CYlW13N?n&zIpn_~S3xf91v&9nLD=Cy7&p3f(FRT`z1MoZJ#Y&_n&dgW3&E8^Hp^IRFyxhjjQ$Y?^Pd+(p8>DIOD%@g$q) z7cX5LEw9eTvp6X~{n!(|Zf9j_>6tT67e&T^>ql0OpIjY{*5(gGG;m8%yzok%KN zT3(yY#(9xBS7}Wf8^@;8Nt)(o&phcxcXah|rU4IV_)&-2FkU0sjaf=WJSyM-kq9Xu z%jhwJ#(86LzbsG}rL~4&m#(TxMEsfDJ2|%PHDSfIzTLC57XB%F^yhst89chM&t($# zFZiGp*ZP~>;Ch6G{P#aJy=)}voBs?x{B0m0!s6-M14@E5VLKv`5~(-A&{m*k0YpT3 z_)-B-=qUco$u0r{!D8=ghR1J4ZlU%!Dy#nq5E`B(sI#sHY{fr?h^rx)bUKORB#IJl zA_!X>TvMka<)_~t%Brf+CL*QUcIt2r5=KOJ)>%i&h(~H_7ucdKdc7EHBa35)C=fj5 z(0M-mh1h_@?BLB3xzTrc*abHeh_~}~C^yx1UtoFh459~d_SP?p10(D~@4P&(Uy*l!d!2{0;jTkjY=#2jb#<@J0|33{#Cs9MmDy~vWv$bSB4d!btSUfamb|FE(x@GY z*aabUz5M(U&#@FmDFQX<8XS-(lgYKK7ZC8&sZ)8LCP{aD`tj|Z-BTy-y!YPId68ok zJ6D~*`sW)P$1Up3$+fSJSG8Vu=LFblt(CIrEO*ZR$)&z90QBG@BW^G=BB?Ds7$roj zuTkgL*ZTmHrfHgPC!O9rO_idZot-=Gy33f@=*T%P^K3F16JSvmk=9x(0qFIIKEk7{ z%I)h{``u1nWZRopnF&EgOC6)h#EKnexh>1mSyz=4ZxB>kW%JxIYoqgG9>?)yJS+2Z zVt30TCrum2j_&U4yhzJtPgw-uK#+`HUvFe+6CA{QRD34@!YDTIMFqxR+M{_B5UQ5b zO^x|6fJ8|rN;)E9%W6KKGqW)!jys4b$Vi|B3DG)_iU%OP-Bnqv9&WISHl)(@q)8#< z?^Vh;=lnVo20{%`00;orlxiV;5;He$K25a^5=5jL|4C*BLaF0^rE!z-fkFz=DF#Mm zG!go^TyCgsSQw~|dooHPDZhPcAAwbueb5Zl$Wa^pX>Xag0QRax=u;blrg@{zklCkf>anC*x_~-W_R(l8PMneBTHmvd@m0Nib z5eEn;@Z100kNzcesVNuFK6C1xSDb(52>`fu?aGN$r;{WZ3=<;CGpEUQj8>hF4-%Zs z(q3mIBBiYyTd@!+GQC8A6cK=90uZ!$stNwen;t>p#~=UPop-;)I=z0XfAQRNOH0cg z?A`g2er7M+cmKwRKJY=dHj4EBN8XzTTXr1hftgu#mbFRd)Etu@;*>}8L?`_Xp0cW^Y~(Lif* zVV=MA%fHfy$|AqT%!c8&|ItDO&HF$6{$?i(!;LR|;U#zEpZw#0bZjsmjy2rBiHO@@ zU67n}%}HgoO8pwSeSGI3f80=GIuH zUEsP0uDs=5Ju^BN41ow}my!(xfGmuHN-NJD36+uvVA=ZVai4~@q>}Fg#LRt2_i5hf z)A)09C3g}?x!WiHB;Fbs7- z0G15{1EZKS&oV%Y8cmJX=2@Oh$}C}#QU9;oj97xOTO=wryVPPp%MjS4xPEPnEQ9#Xf4S{3(B$%pq&y?}9*p;;Fmcp5=-&;VjI* z(g%ECk^3O`4)(%7?ltcBVNSU2#CDvk{!R7w|GnCN?-RVi6g_^C2t0lInK!;pu*PBP zs|5hq6^N{Xb08E?`GWo$sc>C4KZHOu0U)a`bSDT@LLVSE2iR#w*mFwb+X^msf9gRnG( zW!6Mt6l7^`O!-^aBH=O&!o0|dCyeP+$7V;+RC(WVCYlk1D#Q-} zL5G3XR?FMKL`Q@L13+Q zgqQR0d+gJ==D-xG*pcUwkGT43zOm<5shxRv@FxxqZfM}vq_)X1~M6q#e9(OQex zdMMoGK^W^W6#-`BMvn;CiU=vC5vkguG0-7;pTS&wo->my%pU=m`3dJndv>UrqSddJ zk00)B)mxtM(_i4`1oS)YS$NNfKRG<=$E~IgXxtydAqkJ;Dc;OrwTdPw= zmMMi%97a(OJl<@tOMWDbgGD=Mko;kDBt30aNO!@i^N603ZNKL_t*RSMLIFyWMKH8(EfETclai z2;;kV@18z=?$*uiGiOgBYGGbm+c-QLj3#5dU39wbEXxCxCxc0&5nZ_Oz}KGtx(W{8 z_1I%~@7(Ejy8!Tw7ryG==tEC^6qt)U+pBAH@Z1jiyxX}fI^XJc} zS^4vS<3G_wrgeUFlqN~}`DeZ`Ka5X)@PpII(PTVKCgs_)7jNIb{vFP!qCq61Zm;P_CdhDk35UVA-;<9tm=H762p> za1+=V!**7Y%HJ1}fEavCkXw%~?#42E>&RQtj*H2H5Fv$OT$<8aLkfwMwbl1hf!l@V z2UY|an5(EmMXKHInzBeH1NXLChb$Hmtg$Xv7XT1cyWLK+3<#MG0U!c{C>69?ZKVSw zawH^(L<+RVTFbYl3YK(RaBUXMnL~3Q{obitT?17**NN?(`SSy`e>)}r{hmso-dG_W z9a^?jdHv_y@QaslWx|0d4a31ve{fL7lQftnFfscSb8|gfDU*CM9Cuc_rYw{3I88IH z^vcHi;NTF%o<6mC*dG>U!KN&YZFiT?U0mvRqCf|JJqs%Z0z#;YqHM-7kwQXYAyiQi zlG4l;5ZQ8`r$L~#rgltvedY3N>B>s?Xs|y{hMg?xM0%VZbXGM&divCQGQq>cewI(; zNCR>d>nzPi(Tdii^=G#ZUTnFGuI{@zlrd+pk5o114=mfPFu(PVm*BsPkh zfOuwWD=$pDx7yR2jkp*djSj{|7)QCu0nlV=GMy4ZnvFm(OO06C+*(^%TR%KHh#S#T zuUX_K3>!!NK{6fP@52K)p^Xcwj7K>uvmR!GT|@*K0Bp6yhzOm2PA(w_7w40oK~?V< zgrS=!)>=o2rM33|)UgS}Tk56L=n%fl5!V&mo%Wr~rUK0H$8=6}{Iy z)xbhm_3f%SP7$fynSg+v6IaAR*oc6H6{Leca*)79^v^o3vMm8bIg&5SZV(oI5_4k; z;xec#t%0Car1wSiatbHcSKb&b5)F%~OaSd*1yIT{TWsZM)23W6+63|kg! zOEVe_h;*yf?sU7!bev9xz_zsZ%YX8th@f=vu^)dfj^i(G{8XUHT6P5OqzHsa5i=8p zZrYcnb@vYxfu_o6@++TBd1~tvfM`wIclLW~HEcE_%16V2P&114(rRdUw6fN|dHsek zD@E;2Td8J$Fl1{%q}6IBY04r*RF*jafG7~Xy4K6{43L$IdrRG-OadDyt(TV9TFv$( zNtTv-%vKQ$`iCN7Oxb8O5aeIn3`AgQWi<$u<#IAPdbWMKxMNh%&hqY0+i|bAwzhFv z5eW~OOUIz6qevv`E`>xgnU11H7(_~`*3nT$Dp*@x9rO<^o1(~xh(VYoNv3I%gi-Tt zO_}?*<4)Ikx~$6ncY!CWPM(*lDFCjrnY^eKF?A-t090%*70cADwnydB^eUJRRS-n3 z7?%@`s9M1<756(j(lEB4>3uYC&u9(edikboHkBp_{ph{&>KHfRwvL0 zuCi*0$Wga|bKBnY?)5h5{;+likvMe2;hXRO$WMyM3(r1t^U6yAaPgtX&R=@h&8x4z z@RiTK|06%?E)2uaK}b+pbam(xGb5?)(&}U~G^P-6jAAGvN-3JTZK=~Fc8B0y+`!#L2Pw$|Q! z^?LyDKi~M94CU>9`g_0e?c0BP(Aa(T-1-F(PN(BQ+b{@{>16x*s{**bx_Wf5&mxUb zKl-kBo3hNtgKUz9VXJSaY%P(NvShZcP8jGA0JAhNO9Mbl-6peG!^6QqDGGvs8PYU~ zn+;&u-#s`yxLcb1;NT!j=>s3TaN(h)Z@qYDGEH0S0?lQS zAMD(^edD#V$j_awwPepGzQhPg3P3R=WNiua?7ckgAB7Ik>!j z85Xw8sy1vY@$NW`olY!5s0ik+@@rx~J{$l%A*PrAItV~mDJ=86G$mpkaD)nw0um5w zOB4VGLSlL!(;QKKviV@g5d$}LG1x4q*w)Vzydwv!P9y@87u|gi)*67!CR;5(Nr0V8Z!yoF{prbJWI#tBWy2 z97bBJfEmg%GsXs5M^PXQ#zjQU#B>grOv-3Fo{h@~yU_RN`6+qbuoKtNLvZk^t= zoD(54o;!Pi#k}^tgZ1?drD&>GnD;p6ZAp`*hit=N?1;9z&RylKi}Yvc6oJ39h=>eQJ*|8O#%1VLbI5k-+< zFeU{Ar7_KutJg1|+B&zox|*hGrxS*8bn5hlZ-3*tlRxlGVple8b-)|Pvy*0EI#vSE zp{p+5gRsJ^EBRKf#F@6}uW2iPNGj)VmTookc5L!f$sD*mN@Ss$VzfNC*uX)dP5?KD9UAWCT*cPYBE2jF=U zMOa9Yi;EF)z4~q1;VnQI$4z5OC^DDXA`a7+*`pznQb8EHfnw(m7IeI97z6?7?mk!i;JQT3esy_20s}RF9DGzr?>E%M@g0kA_^sFsFpeT#7D4e<@u(h((%}XmH zjfl&#utip8NuZU>cnnCPQ`)RiN*QZSX?@rOU>wC|Sppyv3yZ7hQWj+xM?}OZ)5)OU zKeTL_rLecx;=U>sr|oldtG2C)DR2mL=DwbC>dft8izC|Jqza+*xF)=$doWoe5n4Wa-*thIZ4 zcM%9dg`pC#FW?XLR(nO6=UGvd_5=7@Ivr_6t#^kuuJNcrD+mVD!bGh&07IFok6nM8)isPax9FtW*FVGxEx` zb1)(ik+#+%`UnyKI7CHJSX(OPa&|mkQ-S*kM2_i}=4i<(;DcPIJ+mci=SfnmwOT35 zwl;MDz?KFPl~PjeI<6+sdq4CkrPSBI^843b|CT%RfroxrzydM?1zH0{#u&C`wWku` zjH5RQ0v9?2bxNv7zQ{3n&5W5v#vI?3kX!uB{Qi&po5M%o9usW z>nwfuKpR}`}(Nik`6<7smA&F5dZaN**c9-hipt%UEamXx#6!g@`B2pI9Flrzv1}nhsn-Gc-)GqK~Blh$hlQS6jGou3<*&uNf87=ph<^FS|i1RC7|S{R658L+g)mR zkXBcEFMa1_k)YjZf@P85^~=`=gMJw3)2A-&?A&QB#bs&ABIi=Z$taA}#;MiimF4wQ zE7vby8}t)o?sS&={iES%yt1-7on%U@jrFZgr>jVvJNJOF?CHe^L#Nh1{SMl)Xu_t zmv;4}6}&PJvd>*xffC1ks8W%DRpT*Fn8@=lt+ZA^ri7~GoCpdbIm#>+fVu`#<)@Rn z_=aKrAg zuNOo_rF2;ZBre3T)FCPYHG?Fx6#-I#8#kpj09b3ZirgJpn5s!tk5?rn?<>%d-bq>a zZ$G4dVz)m)7w-E^C*%IXp2^15n0wf?va+jH;L%GD{{>+H!lL=i53O&VZVK?Ip(HA9 zT%TfrfeKixu@+q}f+Daiz*_6Vl)^5B85E(g!|BkJ)|4)b8Q2;k2&2$FOIeg6q7+3@ zC?d>K6uI)$dmZ zt#(5z%@&jnM5NVhc9*($w(l5YEOWclbv$=Lpz}O$Hd>@0&$DEj$ckvK8*y9~8Hj{o zP?lv;ntU)&M9VA7svuj@ptYKf{^8Mdnh0`lIb?>(co=BiYDA{YM1XB^ILeD655geO zk(m}nUJ_B6=Rp{{zX4p02OJECdMR+4UfgW2wL9zO;8rqWf$`|%!WwVCc{t|AwU-}! zJ1tK!W zh)7+n)>}b7*Z;WOn1^QO2jl}E`^?wA^jQG7apjd`!;XkAJo^j)AOaCFShqL0cdt2d z;yA7cGtW~(48z#@64)`|hzIPgwZ`O1H~dptMueiwOY2}PERBhR5U>ta6<<2tVf8rw zTK9NqWTsgx9CyF?*Iq>VXI`T>me%f*&5cdHXD>d<{PVq2`^wvIwPZ(cHzJGt>fig7 zH{Zj--P>m_Jj`h71lC4G3YFGenljRwsRTr07?dD6>TmDuXBJ~b2g(t)Dnuk&>h*r< zKmC`b~G?|Wy!gRXJ zXV08PlC_Oxtr~Z>Z=X89dHwqBpZW9*?r=Bv(oUm89*>8?Px;lk{k1O`mxn zR=T~s^yG_Qe(l7e2*MaZ#8Kn=Kwyd9TnDvuIHqv0044Dz&ra1WL{~& zs%G=C=EB7R^o-42M3}1tWxuBCU@vs^y38*5ksaOm%pd9@4i;8GFekvB{^>%##s4WF zg2!rn5IS{4Rag?adP833BNF;@sv&r`y&@6L5v9yP%}n_ySkah!_D|?Y1#yIvEHE zJKzQ^0BEfXlY@xXnjml?MoJM|HpU3tLt_U7B2E!sgfc@)GXp^A^X}Z$a$WF z4BG7#hch7nvnfi`auym(UKDW{AtEVIqPyKC54qI&Vl%mT9NMmU2Pff z6T0!doSwgA-lOXeEI^7sKzql5m}Af98DoHpvTU@MU@n8BGG+k)w2O~IK|os;NWx{o zU<5d8n#VqNRwF4O1!kiY56||ls@su?i>$!Fk`Oo^3t<=7BFsvY6$StWHfRJZE9>n} z=nPS2KvW2-GzJ8VtN_3Cl(mqi1whGM3fMeXS(XZ0W6XGzi9nf6O*RF<2Oe5I><^!R z?pvoe&ShCX9*=I`*f#}~1@wBo(wMt@x2%XMpxfvq>S zJ34Hb(%#+O&9f;W7iBUW4p}&vrg@pKEUyruv4RS&UcH=W8Hnue?ka_kJpAbP-5mi2 zL&BJ)h1L;D!kF#s+0-n#zXZcjxWYA8CJw#N&%kj5?;{h5PijSKwps>0g-A=vR0Mdqd6-Rkt&@W=6!+IT4B#; z1#^BfteTs2wN_c12`-?;qkHec|#)NJiCfiSr(=& z-2Q-GZ>pdrzvaz}w|e`Ceb8eRH*3JHC^GH)^st2yRjf4*Lg1kpkN~TNxd_mtTkMU(#~5%)G(Np#;ln<9s_rKtSD4Vc6b3 zKjBwPLMrkc*>|c)v1PY@iqcj}9{>?5dH#XF-fDGPL?T!jm4S$mBB%Cf75efkigci? z;V^XgfB-0^$Z`$>NEn7unohUQEKid(YHyDRn2gFiHPq9|xHvqxO@v4iM-2gFF-hvq%e&1{^70L z0+&=#as9em8z=+p?AY_4L^P8$NnA5OaRY+>9f~f`!)bvdiV(>VL%Wh zRP~NENB%M!*dU5UBrh@)AVPL@%C#UAPtf2lcf2$6m)FAm$)`T;U>5**@~NM!zn=@7 z0e~03`V0WP_rp&+HZT_>Q`7o7QV)l`m?EE=EDVDnY$0l`h}jTP#VkzI>1b)GA%F-9 zfWt7d!T_w4vP=YkiU2rJ8UQ>y0nUZ29D`c!BUP*8_tZwc=k$AekdyWpxaXYtKkj$_ zJ%$IIV71=U^}V@Qa_=7X)|#{9Dvvax0MXz2yT8t21yR_0Ib59=$ED#cW&~hR0Qu-} zxBOSX*^IT75&-`4uYK(2Nl=Q!*#G?OKYZplK9RmYp%PmyBtmN{{#Tc%%~r$$XhN+B zl~P4fMqzV2PJZqee;I%r|Jd*Tv;PACe&OH$&p;6{E0Ag4-V37IvMw; zqmc+(5#*9kc6JW{;IqH=X8`bD{GG=|cyBi}#p*Yne|dSe(^-P7$O&6f*xcLQW5b9P zH#$i&TIrqcAEb{we6iQ-{Or&FmEZZTKL&uOf9hu+Bn4t${qA?eI27U4m9@3CwHIFa z`tow;p3+8)y{*fJm`_u%qMHP}**V zCgUXOXIWos>Mku!r%As*B*Gw7Dlq$p`v}yCqkxc&%|6)U8$<0E{g`#Mr`G1`)RG)qIaz(45?^_*H7fXr}5zEo=Qxh=jBtw}r_U z6m=7APHuw`5)uk72rf4RWzmATS8m^%gy_yCQo`)ep4t|5`HXCs014*hHhEPVYFe=x zy8%G76^4#A-XS6)s(J=j+6fWGva>gc$SEUD)r}g>vMlo~6$_qR4}^pqbtJfy0jGc0 z?@pwZ5`m)3$qhCU09d~RvIti=hNt*7)`Cb?u6ri21Q1bmx+{}pf}rLGN=%U_(@Ce( z4&!$HO~`St)}IeiDP@d@%+q9KinQBXM^sJ@5TdKbLx@?Pwp$iZD^%8TOsEh*Tx1o3 z5&%NdG^3~l0KAXfhWm?dKsZ5epLpWi72PMFjPun+tCQb=L$to`o~r=fgus7Ot)i-R zu-&7NKOygauU~Cd2${oVfW5^BfC2j+BwYwDY)Sm6V8JNQ*79om>hj zP1$H5fJ>LC+-3mAloTL<(nBBcOB9VgSw#egv&0BF(x7LlF)RE5={2n(>aCNGNd zU@#mWF_-Cd>Ht#|gCLCj)vpWzf4b9YZr?n*aIu$XCQTUxk>vW7tL>$BmS#&!y*w*kdF7RE zw^^2!h>ARAV-W=jSf>jTi7fc z<@rc!YPH*GnkC~p|5sZ803ZNKL_t&uBI=w-+y1bRfKeD~LbkS;Qi?-nd+E^!S9Pzs zKEY;TEhK#O;1e4se&iX(QKx7gGcO%#>`UI%;u@Uvnz^E?AjsK8AXt~Qo^wuBs_zMA zEF$`VNS+Cuc~_qWt=l&R&CGc*82Na;U~2=?h<&3{Kn_Ae9!+0l+c4OYJHJn^Krr!l{i zZGOXcZm_3Me_jNFFpQ$61cArYuv)qP>-l&!^sXrZHjV|!5_fuyz?CXTvCIJ~K?Ve| z0!k`LFi+3y3pR<15k?}VbQp?QHrCZgMIuv{A^@iH)m45nH>pI7!~ezcEiqduL7>R9 zGS8T85GWnctt)YFHH+dvps{~�H44*=m$!QIxs097b`s(?x`4D<;z8@u;)ZPLtv@ zU%f2WPA0jq{{5$#mYKO|Hk;O3A{-5e$#hDqlqAzM%bLyR*Z3h$tz`>hkuZuwYZw^W zS`k20L7=jX31KuG^_Ev#t!7>nh`P}LYj~6-E6Xcco(xAr02e{%zC;QFg`^cBpd;MS zSz45ZaWy&fEGf&BfRg;E(`j{ky4CKTOHS?FIxLDp=|3-Y&%-ev`S@p)Qh>tDU;e^p z0pQB(FU_BK@uA0D+)OPED`CBWeJsji7gfCwAX9f(2g}rLQFc4f))zX$Sy?4j=dCO} z3^Qt%qcr2Psi7GWaUctN$iqKy4bV6wqsEd;W89?l^Ky>YmV9As5dan;!k_r5|L6~X z?;p>@{4iIj2&+&=>q0^pf#8E5`zZnb+LwO+>gyf?d*I>sATXc>0P^9Yl^daIE^ILj z!>?CSHcx)!Q&=Hlo+L)3x)*A#UD^m%1*hr(fAXo%kYWI^h0#hmxXS%>_S{3aZ(Rm} zZ+!K0Pd@c&r~oqe*2WlD3P&jbU`1qX(LdbZJT=Rv6JHQ22*Z#Rv9R*w0u)72VM;_O zO`-ggGXNE3S$%Y@0ScVK3bS@!wI1N!M5KG?RXttjyS#sgC$_mQbfK3wa2?#Y-AC{L zL00?Bc`!TTm3KryA?^G}wO0v=0R{B``d|Mw0C?oRAJ4K(n86m4@km3FiN1T|1_1o) z|M*J)U#f5PhyTOZqET#xC+Q%dC{lqi7S<+7iUgKzR-{NmM945mGSuo%{^)m4eCFoz zg=sR_zImmg)4|~$X%)xKOAkCmMAt6gc>dWhop{yy#wGwG%HHn5|Ni%W8vxFnKPMug zYW0r>jV3Lxckk{T#Zlt}PyVR2<@TN12m8bKKmAF|d3U9yD0uy~>kfdJ^JXQ501wD z!@WbL^!AM%0Qm4no_L_UvAuo!>eUy2_&twYzk1{FZn?Zn=g*!iO6(6uVHjS#crKeJ zlSwii*mIi?grO=;y1o&8=p&C)u-flSl8)Ow7RdGvCojFQLrDGoqjY@YNPvz)L?o+` zEtO=@0DwWmVgZB=OT`Na^}0BwF?lq12A)IZCxm1292WZlsPgt}1=>fcpd1Gj>n))2 zsRAKdm<2G-Vdww=Y+V5(V75wWSTt3vvE%}?VYaOh5wmv%%^3{de!<#L=xc&_4TuzR zl^x`2DnZRa={JsQYXDHFF+gC>3s?6;pbG7fN@<45Z%l;XiP-&?FP53DA{4L)0xZm; zst9lqa74d~$g=Y+10jjEsK`6Xi2x;z8)9WXMv2*qa55Q3anqY%?pq=nkI4z)0?`<= zEsY4zc0;EjI`1^jh0QzHOAy9b1x8`@nXF~!WOnzu*S~sf!rb%2$%o(6wQr(TK{s!# ztG^lW<*i+Hud5mF|Ee>&J&$dIi-K@gn{vDSLWTp9BalI`({Wz}EsM#gceZb$6a_GZ z6gC=1>0~vI2nd-D`o-;+4wNMU$;&KM0SO48Fqfrc{A0^y0E$4NpegepY9T2`u$2an zh@uD?0i|RMrqC#C{WKEAUJ)Ta4OA!P?AvU?ykp_|Jqy!VZ_R38} zb!zMUG&umUOTE_Jozd#bW}d|lT)cGc>dn2qLATRbS_<3kX0zGKayuTHG@CXX?I_ga z$pD1oRxAwG%DHn}TI;2y&Ye5Ao2`~9jWGuO{8vE`=XpLD4I7Q1)ozRiBXknM=Hu~E z6w$S-*DUZ8?>jGSZrm9F7p-nxsmHlhMeOCJKY^y>#Qm?;b@l_?0Wnwzhfz>X?ffnV5OYp%ylN&Qye1$0yhf zuJL_TrhhFR7D1T`99it9LU8Ww2Wqwd7(O!pcb)!!OaViLI;0WnPG$~TPcGxBa2Mmm zk85`>LsIHedi9%okjll;JbyX>Q6JuuvMAV;;sQ~8C^k8>6{=YH`L&CPN@)Qw)}ZHD zc6f(iz0%!!^`SuEcxSw_J^!$RfE35=yvP>3cLD;OCX+ahRS<#Cd=(ca$rW)gpdU{M z_OLa1HVML5sj&JG>>(aRL@bItjPa+@F2y z%J*K<0Rga$O|+o^0l=1yut}giD$oLw3P~~h;*tVht+CcBrCpg{LNeBBrHv75OA&Ep z2b^{Rz~G|pd?_&yK;{wvnQfY;wk%Wg5{oJGqW17PuJ0>1GyrU_zJGabVoI7$>FBU5 z@}kiQqX>*O2%%Cqog~7506GZEvS`HJkN?4UTkWX3((NBkyWNN=`i1Z8IyRCL-m@Q-16dKV!=BD}VC)^XFZ^{4xMsdgzDQ^C#B4 zhYPVSuCs-I09~BN9P#Z;eXr%$JP=b!RdUL@Youm1fS7$n>KaWq){=EOx-)*ec}2g% zG@Ldmw&D?B_VfYsB*F8+nTWnvk&CaXPov5K;qLO>pZ%*3|JY9hi;GToA6qNU%=1NG ziLio0@yVy2e&N~Ax#QPf|K_EKpKyP>T7C17lON0q7_WPK;VYj9fG3~&bnQJj=4z-h zof?j**x!IqAwdajT}|)Vx0(GP5mj|_p$^!o(HTG>QVNtJbPQ^4vAVprAPD2AVc8Io z)B2sb*I@_%d6G68O|GD^*_^=&ruCmwOV6%gLB^8mT-LPo^;ilk>dXb zLHuemgLj8j?%c{G2SjoXRsaAP?A~CpC_o?qh${qq`k_mAE?=GRb@LOe%`1@>ZKN#o zl93G+Y=v1ID+eiM1=GSH;@z89?)P+m`|ti5i1e&P(?-94&}~H1@qslQN9yLy8>?%} z?|I*&fA##?|NEc)(-SUsOlPdOHaG6>?g7B|&0C**`p2)le(mg;3yr3>SYEhzzTIlA zEUkR)`De2{EsC<;+9+)vP-rc$ET8(|Q%^nr?6d#$H-7b_AO9=Hn9a@g9b?Di5r`Eo z$~;-=^%|R-qw#oSW8>iNwj)gdgzfDc06;1qj1GmY2Py9co1`87F48##j(*j44ZIW>c~-dl;RCnJcoA6KBlg z7<(W5f_7V%d+^f9*2cgb;4&xQg;9{J0z^*#27q}4L|0YbJWODHBnyf!hcN@t!3#iA z%G)gf?4oj97Oi{2s;ZHLRA}Zr@W^rc57W@Swi;O_1L8X(kR)Ci&w zMA9s?r2)1AOmjwy$8@X!c-k5OBt%g-IvOHCtKAC121{jMRWJ#hWZsY>A_d}7uRtL+ z;)XHS7()o?G%j$S6dv>s<3=M0V#3fvCoTe%tpQL(q>vQ2B2mo7m|O=f0H=K!r2+tK zHd|Sqp(4*YCIA49MiW5FJdc97-p^RXk#>@E6$`*j&#$M|$tw7~g?7?he4}6AQk%=n zxXj|Plg5@& zteIt)jk4k{6q7)O<4HfyvrebQ2CQV=PUE%jy>#l-84z4w-IylRIF7UF$SE)kV2mMc zx=T84G)BY8)~WS0NsY;xt;iZ^G?&j_Qb5J^tG7&vVvEA0{eHPjA)*q-Fbr&=0Vs~U z07k&Hnw>Dh)zxmJyEdMh(hQB>i@N3;&%Hi4m^R}$Pl|JA&z|^^gD^yN^nXq;yJ|-) z!oKFFPyZFDL6TW`;oMY#I(unen-Xuq&&ef`I#|Yu8mPdWS!XVIcGk-*e&aaFi%1o{ zJ{JoEa|%3EA|2~6km}dU^7M!5avybX?tlF|%;7%scbRE-3%O1{;nb}VsKF8eM0#!$ z0OAkcQ7q!hbfEVrSIe%_ksQt(P&!BEDW=>O%dTNOH^4lTP+arZb<<`zwG_a3n(Ir$RZk3TFb3=IIlkw5{Obt zA$gF?;Xq1h%N7A_l`rEaiDg@H;vC0f-VlE|*6x++)erOA+1rf!zJL3HAoaI(;T!Z= zwaRcq{`}6TpfciM?sozB)R{j7l&^pJqt~y#>dH9-+oJdefwfE&D9F{`&C&8kW24c~ z80_qhw=W;UT@irN<_Mrku?Sl!%MyLfFDgx;wMIZw7Dgn}%}+e{3?KojX0utP1Of=K z<==bq$DjIxU$@WShaU74PlRQnd))77Osjq%63WFq_qkw?DOk?iv6RMUsoC2Zi87{0@ErfOBPk`sGGgh~qpI{NXa ze?i20CK<6VWajGS@62C(@zUeWrp82IaqZQyE#f%~u)+&$eX>*`C-a~QRC=?p4>PHS zFMvn8nc1=Sx)y|Cg~U5vba7pmi%Pqg7eoYM5etMMQh6r* z?arQm`1Z}$0pNvapK)O<^=QunG48lA#>EF!9spn#U?3t8D|4P0C3yPmMIv?k<`tMl zHaUhM0-RN?Qd;YJR%PhBX1BvIy211*lodEMGpi31BfKtBARv%ORB+i^3uRv6gHJs4)PLz1{8m zJ=)*?Z+}w&5bc8N0r?;NSO1~=^Cy1p7cX9TY&uELo!?m7jM6j-RoAA$-}#mQ^5yTn zy1BV_||QW-tLYf&hrU# zwz9k>Alr9tw>q7bUhmqC>v!*L1HcD9`tC+q?Csqpj0gR3ueSmKpL+UJkDrZ2WxxJ^ zesTWYf9|h->dNKYgh7^OS(e|uI|a)KG)+dRbQHzk{^rX70G~fTXn*5xeX<#iilopA zRinJ`NB4NEMgpxvc6g{|_Hv84EX%TB7RMLP!fb`b%A6a}ZQ)Q0aECoWO;F|BCzad= zr%$5;^k$kX03f=^aU$PIr4d4f;CMnVL=Z$B1eMf90GGE<;J{y~>T^`hL*Yd8yj?Et z!|fUFMlR3PG3kh~WmGeD5UZF<0>Bww??KDjoB$vKM(_-^?lBm|)qqw2hzi>+Ei6Tr z7KOw2=X?osa@(OY2uOqkQkMB}m^I?I4kN82Q3O)4+f+qQ(MOk~h_GcMg+yrGHcF0g zpB!3Jxh_yCFvgbY)D*1_=^z&N0hLNA0bjWZ0FY1zk;(%?0!1ta0a1w1<6>dlAkrX| z=7}N-!U$25(xu4-BrozP3O(}10_43H-k9+ty%6`hsG~1@(<-|22hxe(g6Mv$?cbp2 zzE^J7q8izi&5^38C4vvj5fMNfjrs@scfqm(6e5ct)*yglv3Y@D;U)9@cdvqyfQ3q8 z$=Q;!0f^02jsglb0-%V6U}tr!EbL<8x;>d#hppXt>l_wwVUf<4Li;b^7x47dxw~k=6NLzPi>(re&Ix2)5s! zB4)ki*6M1n(`loE{^+g_f?j(|4BWnTV|lr=y!@`xWOs9EbY{IWip`9T3UU(QdD|-0iFi$lk$T+-xp&I@>!tZVy~r?-*0|`-ceOWR$c! zU66Knso7nLfQmuiE-jsV^pOkGqz^bDj&9%DMbvqg<^svi2lpFEu(^LyqnD0vM39sf;kLJW)I`?T?xPdBC!~% z#HYKdSDKa59QZ09;xQ-ZDgyvpmVrx|sm7)j;Iq*>HqiHmkjzH){te&6Ie)?1{OYSR zxjYQwpfv}k%KqL?HW>=An}Fo&hKPt@D#ebueQl&pfz6ZGp1)O&A%Kv@sd0wUTW}Rf zNCIF5#8?M632CLHrR6n11*ocmziu-@5ot8qK^V3gYBC-P8>MJC9CkX*W-|b$AdHq* zddW0tw4&}xBTI9wLt_d61i?HtBb*WiQKVaq=4dqTE%kIj0(Pml6b3;fZftMgGR9cT zVc5286e_XUh&za5k+R71EYF#_)oLN2wG1F4)>>}FaU6!$*mnE>W$sObZON`Ov9;FT zIi2aAJKs0ed-bYRDpjd8fD-)uo=`0Mo1tD4W+5(;i>A4cOK51)81?O$KIJI&wZ~3i4t~3MZI(L2#{okmgMZfL8WthTzSfSVG@_`EBp3Sbn)I%TNB*e*l21&plobbot)bGFvg$R!P*% z)>UQBm!sDywXL>58^nD~Ei5 z!*_^82pk0if%^splnUPR_U~jd4}biRA9(#YCM$qUP_U-R+wDa|aoKkhnjsi`HYR^HClmc))Sph)BvB{>!mT}Z|xDAE}R3hxFje)!uRS$v=RBAd33_jDMsWa}-`{TAVeuYND*ASK8?2@}0`As2K-5s{z!$3M{g$)En-JPYQZ{Imal@77?YZ=ZesN~hBr z4h~6AYAog*-|^bsB#h(u@kc-5_H1r!?CtLZz}~_B>RPufxfS;x`P}2e-08Gl|N7St zM@MCuD?qUF+Sfez-KhTW|Lb=@^U06j|C$G%dh+qSET^+HNs__wghT}i1-iGo+P`uA z`Rmtq+U?fza^Kh@>cqP{`|gbC)GV*904I}CrU)#^fBs+naCz|2l;VtsV{8XNrWiVX;$PGjK1fd``hi-`uf`P@@kr=Pd)RfP`RkE;U`)=ct4DqZ{k80_E9a<@r^?T9B&N zy~>mXLaWFZ8~}J4UGdedb;PfdCUp!{plKMZ0J*}FYUWIoMq9uN=&$0%K1%60k%K4^ zKrn?=X+5wID0ViNOLTC}H~>(xJk{2;+C(Y>aDYrDsIg8pfqJOQArnDCe@hS$EsGUK zLWRWcJ`h@Km|0K=oKj~(<%}325CbaEr~`3*2+1Wop#YN7Yz+wMAOb>Qo99^&M2;;~ zAz45Xi^>Z?PZtGMuIOCSoMM-6_(gY++vIv+IYv2r0B+9eWF* zRRk!=$}cw6>h#MpH`XGB_dWDA{gn+Q?a;{}2r8NlsbDQZLJ$BZBAHBv8dR^lEGAvs zSn2g!WuBWt+folEqph_wXExV&54SH|xCnxWyN3#Cd370ZEDU*Jfl0uY1&@ZaG@AjL zPN$>7px<47_L*nOvRq$ZJ2>24T3!i*WNY)RDT-&FeL4&SB83D9Xe^@=QyMNIX+>Ev z0|}!z>~`9RhlfFoK>$G*=`bRqRx2tBGd!MVMFFCsAOMlcc-rnHQ5?2f(ZS)wSao!~ zm!%V9%U&lLjZX433zRO)0z?9>SJwK*m}xp&TiFoA(P%gt4gt{=g}OciCGCFP>nHiN zG&4Lp8n113TsNB+TOKZfL4cHar=NXl3|rq=!`Yk;M+bnqC7fGR^`vg{qE~P*pxItYw0fKU`g5NJd#0;Cj+Ey^N_<3^7YM|0^HPeWQYpZ-h2 zF8FdJ?N_!na(TYY-`!#RYEAOgOIYt kI4Lbs}fgl#z)4S|KwaR@lY3c!NKAhIrH z{P5^e9E(_Fg~FCgv`V33G46$~7*0`8C9Tf#>Y6L3Q%d(&R^QbBu+Wk((yri8Ck)u~ zcRun_v$|2HBTZ47X8-BcPm7r8b16w=N&~1yndvR{_YSYcosMSpo=-jf=il<`A~!|B zAUvDqfMvTKbvms$j*+A&QxQp`ZV&{=$4Bi}vbMH0nNCVuj7Q_LER!TbXGSn(S=MSr zhRZP0MP3rhbTW2JTEr|Z^|Cy-){5{_zn^7UmKT741S_jc$44V!L;zt}T3RL|rC@!l zdvI`UEp(IhGh549F$k2hMz(Jqn$jA>rYr;)SP)CV86Yh!Ek|*u+wED)vr!SZjS+Kn zFbzVrvfc|+UgV{)#lQ+!!!Lla|Bbh*SZOXLr6IxRLJ$!VmFp8qMBn(1?-G%ZedG`8 zfu6haaQjr+001BWNklWD3ic1(kA5X{hGVtpr{T$B0*-)%KZ>{n6Ka z!@HYjsc%bD=gq;ahJr+-*T3amU;Ol+6Osxv8e88esVbGwe{iaSg@i~20cst%(egYE zT?#JvwkD`hn29J$)0##Hk)k*Tk9v7FwNne`)Q8)*JA8!}U6N;WomI{I5D0;NtH4u| zn()Pi^j8YL{QrHc>jz6?s<#TMDqXHR(70EWzzTrZ6(Ejtz>3Jq*4@Xu&jY{@{lvfN zv^x|;2ufTrD*DN~#s z?PpekD^H$K1Fx)K(ocTkv+w?{Z()l!t{;{~VXa+XTmAg!Kc6JY$zYTu@&5jPmZck; zTkiONzYhTY{>t)l|K`o>XV0D+4hNlHkVMOAHceVlIx~4*_Lh2slS8U#O5gsDuhG+V zskbg>+-dW4d|cSsXmS*^{FMIAd){`icMvC?;lX5id0j-uQ728)3l}byY&7BF{;tw0 z2m=s(_UyScXU<2Fo=(S;X}Y_&og_h+M6H(6q$lHOd6;!soZ|W=_GVoHW zX=*x;l4_a5)(DGb28%9`Yds2NagTs4Y-wT79T-RhkLtb6|f02pHw zh->f#4XG$BF3iYm0i>>qs&i8Ol~&TyD;Ix?c`hf25UDt6#gG(bS(c?DLPSyyzoy1B zB7cD_z!nKjX-9)HZnvW_4x-qyAcCqKsS1AqByyb-2z}MRNKHZsibx!lol*pWkwRFs zR)7c$s8m%Tpk?lrTI)yESKOHzXbrXA}E9imMZTMRqen6G6PTmsPF%pZ;m@X1(GB!3Sty$ z2KMKZ00j5eGYH$!=wLP(r|D$5t=SZj3dr`NxF^Krwe;e6xl z#V4P*y0y8|UD7w69~GHVfj+ZxerIO~0LJ49lIlap4vQTq(fcUXcjGnldnqhvPDH6#Ho zCvgSM>fk>;IVYce@e3ewc5 z!JQKuMXLTh6-w+P;)sCS9RQ+zb_}z1R#$0D@JWyERkZ@HhheR;xq>w7T$sjVTmWU} z%c@!!;<#eH#porsKm641St?K7Ee;QpiU5d!tG9ASBQ*Srh6&wB9a+eZscK2ltBj_- zS{+=U4G?io(pKBoX}jJpz%kH1$tvOdheymYKhG-jFHF z%$S0dj^hML*H(_lE9W=8n!F!#;k_at7BSWkAt_~rLD&VP!RNJ9kw`=$?YwlcKuSd_ z$}{n|k-!>OO1oR(xZAW200hLAg$-lR_)36;MBYaB9vFE;aDJr=qGnO|zQ|U4C|F@& zw;uqFJ0J^xEgsa|140CeLO;5afAjErdb1(qA161}q%6TGp6QYiljDSS#r?n~u}rV9;u{k|epg zy>CnjXjeDeh*ah!A%1P}ykX6j?cV|%LrS@xqay6$YS4Hs6`=LP6No~WHS?}-|6ZpU zthFEei$4H>tIt1q>GA^?FF$zgxyNgxwn1DnFY*MZHxQ}9-9_s1Q9$$!Gl+|^3PkleUjO`!(%isL@pZfkE{pk;a)PUM6)EeVXTXW^#@!MDWd~;La z)Hm}z)rGf{rO9kSNbF@j5Nfy9P#A!@?tX&6zQcxZ*i%Dkzxp#T(M$VBf95xU5di+p zPkq4cdG8PXh*+yc#z)T!7b`0(U%GN#DNUdIWUmvhE-#%u-}`6(^mp9Bcip%4kdjuk zG9KS(ZS>y$O<(u1zx)&c>>nI#ZmjR^9{|A4t)mMU?kcij93^F0F7KUgzx9YhPMf zSwhAjgfD*KF_7?RZ}g_Oyb&^U7$5U4y8BppVHAnzPLpXZaj zoUCldt=9UpPv07zn3=5zsEWY02IZUZ z&0HLzo4>EUM?#Q_`qAa=2v}xC#JuM#$sL!SO=-rZS`lJ5;ZsMvG(AqU=4lsm(9v=0V?%LWs(`iiy z!(kAFfDA&2oELeN2b0lE>$ogfYkl_Y*)lHl$0xf% z08Dag=jMg;8z)CMm8Nt$Q>4lw=ylgkSq@GPjWHYRYk5%sVYkyA4v(4b^6JKDIPP|P zaTJkeNz3ist5Gc7UeaG#CbY9Ovn3hJEB$_6PG8`;zeF3FMsADu$%%c_Vr!YL1ra6` z7ITM88My6*o6G0QSFYc6oacZbqGwcOhbzy=tfZkIM|>mC8sw{!H2mSrs1*BB(8d(2 zVSEZeV`o$9!foQW89r=&fK$giaZ$AyJ*5oi%F$i2z$Z6d?uil+6h=Y<@?vNKiorV7 z0lYk7YfM=d5fLCkmAv9FL;xywb~mG1$TcDr-u8Ag@tt0|NuLh{Sm~=u33}X)bP!r& zoD*+tsg!b&5_h+&Y$i0NaXlQI22_n&6))u%?@^`f;Dxq3WjHoFNnqn9K_$Hb>#I2R z^Ov-IzgiH=|Mwdrg0RbGb?-!dcbe~-dr%;0!1J` zU$xm19vbN}08$jWDYH0?({zlHvPG^*<#`4WLMTxb4+euyyPM@h6>?UNvn<-)K3ra2 zCZx$YD~eKS{k}){e*3`<5U`fhG>wzc*=EDxj4iWpODDTKyE@QWmIr~JPA85!S>nT5BqbyeJK`2?C|Gc2zA!Q5s{**eXQ=((f<9-dANk%o|;kA_^1(C~;%}IA^XE zU}wKJNJ&HlQ7NUA0;Tw!-}XKL{_vmt`ydK^?_0p87(FFb0ek>eL|u?t*jOtDf0zXQNq@C&8_M>o5pMA^=3>FqDejO-OspqG5L-Tklm6!MO|f5YUYq&jJ85 zyZXRW_rIP7Rw+64&8aX`)mvT}jj${V?U@_}0F+W$I*Vd$nF%onLSU@j8zOQ^wHhf+ zN5&NW)pJUbCr(C6S}kizM9lL%j$;7?Aq!yhJV`=pt=1v972`DooWfraPnS+KqotKL z4jAW<$~(X71N9|~$VWf)JEul)sLjv)=SsK>+nvof>YCY8OJoP;>%Mk zuLwrt-rvPtew_=!fBVxP{MSGEfh&*w)mJ?J)~5Q8-}}CPucMW+LVzeJ|NF1}((On7 z+)w<#sXf2u*Rj%Cgo_n*J^c^dzYVl@`+#k#Sa6(`McMXHhs-Q zufF;G@#9~(@~(G&E2$uilmGhlU;n@U&p!_U47|3sad^1@`OiHHpL_IO-}(-P$=24^ z_RU)lf9`W4a`~S7Uj3^3iRc%9=@;OMN8b1TA9NGA|NaNoHn;fbIEq^9>#GQ2ZGP?A zjqzw&+VSvc9L8~fWpgw*0>Ir{JNG?s-_nwO{E3fk-x!OqG3HM`^w-TR>MeCnj%IAa zo&8%nk|4z8{_4rm;mUIVXn2C8M}wn&r(;a{wcq^UjhowPdh}br`3LT|m+rfm=STNm zzOT%Kbe4litJ5;ZW+xWS3*zxgDO7~ci4t!YEe5w;UmgJ<=jDNO-J z%Z$vR$SFBtaFkaLIWopTO-t$6b=-szkyOLd~;ikO+dhVBS1s=00)7{-`2=1!q z%a8>H)#mz^XD22VMhW{2Jhwi%;RgIox7%KVuf}$I^p|nE#d|2>+S=yH{;rt~6ey?i~f}l;PuU)&cv9WUY?3t@qpZ&&fef1=reCE@SEH8EY7rU)E zHU;nP?`&>toxgC-6qKgZ@pzi$vpna+gV9nStTAB{T)z9&gX3eZ^`(nH-B)~#E&R#sOTQ0p+CO=sg-E9qXmt3!msxixh0!sRb~@zWcdXZLsZ45a;}J3O8u z>hT~A?nz9M1KYvTVGxAJ2Lq+uO4ozkt4TZRcKRnrGZc%E&L%S;eB&FwKFuaKu0Au# zW=KkdZN;GuXgE3EI(P15cyeRsnhtD#rMGdeJ2*MX((=hiuG_Livcf0`*RO5I@eA@k zdNbGK$hWPB$~8j-*Nq+&DAC|MJg|6Rh9R3-UU1(klh!YrrYY+UECdfF&utjQ$_$@> zYP_xDB`UcfXpQW8LUaJAc+=~ZTBl*ubMiHGPGvAal{t=8R8<-cK)GtTvG5M~L>O>d z0R*fth$vD(^|c6MB}F{8fOX!=+{njjkyjXufC!7lIX9Wx2UUuQLr*}YuGlT|)Rd(T zf*^=sj(1l6k04jo_bdzos1O(gggnyX*cBj*q9V@$Q2|%it{S$x03fOA3Izc$2m-AF zKmcK8n`hIw)t=`7`J^Ea_*B6;2&2dvOFr)59!kZ-PFUka3rq3zj?)HZ^8f^6dE*@JU_ zDZ3|)M3e+X5CRgrA~-ZvliK-$Y)+;$MV8G1h1YL9+3PMJ9qekdTI(>3u3g=U<7hga zT)KEsso=upGggX&y~&j?T?K(|CpM)miXu*8r4(TpM!LuiBIJ2ttg#lBdOd4$tu$LVc2fBdH`_q=1mqm92_q7dxwXkDS-$G)5-C~nt~|kb(g!HX#3W7r_%xC zJj<}8APB-ZCWS;~jR2Ak0udh1POK>m7pv=S06ab%?{B99Acm55^eJ;Wwn0&pC;`C! zE52HwksU(<1gMA*TnjpJR0QO$L18bF@bsE)Zv|{U8P_jqVZcUzzImQ}qs+(UtvJF+kvgCVF0G7( zT^lB2jAiSZE4lM>)!SPt4jMm0MQklqWw+8mi|QXTGm%2CNZsAjt`9s^MFRqr&qiph zrACEqeQ8Z-tcI4n>FWg+#&KJrF7p)8Hvt5IJf8uEK@fp|{sd5$G>fC}MN(L6cmG7t zvK4_KibSw1^CXV6BQg-M&hMzfH6)iXAI87Vn+%Ve zx#3lvfaD+ki~r;2|HsL=sPI}$mTi^QDqr>Af=g$Aq zFaIy@+t8}X7kG2t^WJYT*N=qF+4E<+y>6@BQlw|u5XrP! z%Ozk@mi?_@Ble{M<%bbD>}-1e=#rKR3%IxWl67|UW#PKx@lhaZ0U zZEt&9-NRmxNNGTqE+8OSmEDRDs8up*(Plychfpg8%yE=v${1gu1^^)9B71e_cCFP3 z(ZBWpi=?eoH@2&H3Bzq|uYnW^`=Zq9SkEiXt`D6E0(oqrq6fE9wVCrpK<+@PTPYFw zkge~mfj&Xc*CMg^);dCaVFm%Kkc&Kz!q~8NtuzG0G4wgu3%n!kXdSGBrCe$c zA~-glc4sL|r`D7%ec#>IbT(qi&ZZ`Mw=02&=d z$n|YJXu@ch@-g3v+-mgqLCz#wX0Wm_pg?DzIEpOB%2vyI<59}JY-WM@?>&6nN8PLH?-E1$#{47 zpw(JBd-2ln>Re>$|3RcU2&68F(9-z-PK=eep z;M@dT76OP`2LxIw`WUQ8?%lwM4bJ=ds2=E2N+Xpb;`-=8<%3Jb*W*0;t1;l!jB!(!F{BT4`fhgf)s1Ga8OsaS&=zircN0F&03r ztgNKjY-y=C9*?s;>#d&2%i`eRcynV-2NddHa59aeu-EIgT5W4EiellSG&u`O$tJL) z(b!ntSX;N&l%*+68DYG$vmNLF0D4PHQ5>~YP#EJXRjjdq)M~X`tu_K0W1~<{?%nP-7Bn*&^0T0T75x7Lv2RyzqX8jU6j15-lPJ5;9ASrF(9Or903 zM8j8StH*V(H3B%MZ-@ONRRWQO>Uz;|qch(Y^C@N*=nOkhjO@aQOTH z7tUjpMvPR1Pr)wC^{luta^wH(R2qtaF&3-hQU|rzy2h0VtCSXLY|zNCXrdSZ;3AFg z>~DL=d(oO&Em>m$F$h8wa2YOP7~*0XR6TRC3<5~=j1@O?7l^2Mup!TLr4*_<8AmIH z)>^TAO4BG(zAtJ6e1S$!D7VL9Jpd%a6%zuAkk)Y&#<|wecxG(M;b5eLXt}>BA~ji~ zx0?xBI0&P%3M2C-t!8pf|uNG(`=`& zO8`*^f&NGT>NgD=L=6Ij$l?O6_J8`RAN+}b{!3EMij!LjPZY9ofjQ>AaV8jm*asDW z7&bN+0|-E9n1EfkV5^iC0VH6X{bwI||IW_NpMB&n0pR`bdoMFT^YoRaUR$2My1To( zvc5hZ9+x)#_HX}>9)08~!Q!cBKCemrm;d0s8b@Ye)p3%n zZTi^b{{HU9=IZ|55di$kLD=s0k|c_+ zU%i#*Ga)&@b?;w&_)`FI?)*6sdEM)`l2&wl@TItu-gn=p)fvUar>BZoo7XOPoeD4=*jg5K})5&cS@J;R(gbxCW z!x)&EXkpxjW#$Tn96oY-nK~~;tTW>Yk$ftzOWLf98Ea^fyv^^LWFwK=<5Nd!TfCCo z75I$c02uZTgPWMrip8tiWy!cQ=o`VxaJGyXpdq^QL zFpF?ywF`(i`f)&H7NV*{s*~Oo{Nx@aAqmd8JaMjaF^XcVR8=$};#`HYq3%ek001BW zNkltuf4#K?tH_x*qX;-bb{Lk33&!)e_@_M<_ZtfF` z_)rj3SfAWs99OND&1TIzfb&(lIE6d;J})sJd1>_jCDqg4WNXGDPMxk+c1}t!Ew8`o z{?L}Mvh12r3+bR0x5kr^SOX}5Ez02za2bbcn&rYWm`+`@q(G~7D-m(sZv_f~ec=^uj1!-&h|EPx7(^w3hkit(|tO6DP4TCI|u$ zAf(cm{e!(Mn{97zi%6Eu!YFRHId^FU1w4vy}+ zc*z=Pj1Vv!9gX8C&hjkHr$w3TP`Bc+x7;~6IO>)w>ucwZc#oyb^6_*w3W8*CJPfo7 zqC^>vVx6a%2w8*U>1;a5!yrPy@n}384x)q&r&q2#ZEUKPX11iXQWz*zWO@A@o1)ue zF+_6|QR);#zxWqR7Zx@rdzC^W)Jj{2q|ZSWFOh0YvjGD59FWCT=3bSCP*_Ajny2D6*l2_8n~hfY&s%);f&~#42BsRt zW`QbEr3sWk<*L+RcWsd>rJRCt=msHH(FjEJ>6ua!^Z+1O5H?0>9av$iDu(?7tV5{P z5K`5j3O6Is7{x7STNZhxr`+5)OH&Cs;3z7dpX59K(O8Ei11`GCL|D1 zU`T8j21QXA7D6=a!~=IaNxang)3;>gY!Mtoot0ZHc&H?RqkQ`2zbJ|#4+7n52fKTN zY%+{gc(8i}h}~{?0Qo=$zdRWj!^{0OrJ^XLD^J}_^Q_Zpf$(fx98M=7-0k+VtWY}o zi+4PgCIlz8V*N@wk&PC)qnqEVOOu-$HjaqL=)Mq!X=sj(#xWcfrXNRqZvD$CO0 za2$q7e{F3x+lj+gp65siM#_>+X#sFH%f3oW#=H8~mLUZ761HGLr~>bu=oAN__p_B zQ4q}W6siaj1VL$~NFkyF9UQz;mgQX2fKM#&xJPRjkm(*I3#Z;&nqD$%*@x1-YcP(-J0wRK8+;(0^#bHch%F>iW(f!p8KLK)0 z$1Pz1NIGd-Yl@;ku<0}fkvM4wN;4bFfB;GbA}B11M3B%^(1|hCRb#C(YcYnmfe5~O z0>BGhj|PGOkWkH>M_3VaIzJ5%Txly(9J1Byt znt7q^MYO?7{Pr}3&22=McO3Yo{fy=@zSvN}0I`KYaYSGR3IT=bot>R)*RG*0Ha6Gx_YMKT6h)|mtuyEP{gvI_?T23X&~P{u zkvPp?wY)l=%uY^*X{!u%JDnC`5Mlu1<3ZeN$C3Ka8U0 z)?_*W<_nk3^t#=Hy+d~uZ~c}B`Z1)_a(V5->t22FvBw@cI=P;7&#!cr5B4WX+w`~!`V(LG4d3+G_3NPqM1JenebWa&_-_H=fd^kDg9)N!QydSn2OoOq z)$06Uc=+J!?>#))OS=5U&p%@u25}u+1pp9seHySTP4`AtMgHv!HRUZw>nvap2VOey zQdy|zr>*N@{Ew zSx^APighmzkrEMSB0C6p?#MXRquj)*n$Y?`sGBbNmGAb5h*$>pgy`aNTSNqwVp5Jn6vos>}3zBF-)CtYII9J~xFnYsL z0Vwe8r(}*p`P8ZENu$HEva4Tu{L+1IAS4nyub4Wuy&O#Z%Rff$tO9Nq!7nAZvBC=% zhPh4MxPFL$^JFvx0#1@vk|fr@@C<-14K2S-OyD;}IocXzjE)02yrdr54kQ`y@c_WP@07^gFS{E4U5*Vl(9$DyV`Ys+?d zd1Y^ZPeh75UFx-vMJsKsNs?Bp)xCE8=43J)j0Qvms4n08Dp%{be{icbxkAFmgZB!TrftaKl zpBI6w9Gt(rsY9J*Dvo;F*KhQCQ7ewGJo}})@4Y9C!rfVVba;X&XU|=Tq96!qd;8XS zoC(`bKhP1Ztu6!hdcDr^@jzpzzq~OT%pQH@(fT!67zpc&OD?nF3BTYa@piwzqo2F2`1$SK4mBn&8yQg|<+^BQx zsm5ZOhz!6y4hogkRAKZk5IYyRbJ;_vkc7oU;Vx5v#Tk}PYs^m};7gpUAY65GfQTG~ zWR3ML$=yLj=u#~kfd~QTfQaKy0IuVT{znMtij{<`&P^WA7l&K9qlhq$l}l}_Z<#fv zwFSmVDs&Z9r0V1~k2NW!S*g0ShXd1Dm;eJ$IIM<+u=?jt54Ukd zbMs>gGXmm6e~fTjOPAUVaL*AifArnyY~1Q}ajF{X;{~@b3rxAQiT#pB@+-K##JSuB z%bz^^ZUAV#nd2%a5v!Ud5NLr#v0_V`jRGmKvX4Y$nj5$1nIK6bVQa)`QV<3UL{-`s z`m#6?uxXkpO&|V71rUnBcszRhwON?7^CHy*N~_s)ys@#;YAx;WAC8WX%d+VA+ZWDn z6-6JVwnkFSou#~!$aQrORv-~q{(Nm7 z)ug#~qDno2S9uj=>yC7lNA7@n8Wnzl%u<%6(?+fiR^JAc)Y<~7(kC}&{Vi5;PItPZ zD1soMicVN6MN%syf4%OuD-yd`kh;T*tTwfzr*H|_7w%#WZ z5ENiRm{;o7r>;O2c6Z5vHA)c@imo8sSgCex@)O0gYuL>b;(7gaDWIIq+t@l z&;FzD`>~(-U15Pb+)|%$!K0`LnjiLMZ}pGnme+jOo%GJ_hn@cZg@k|O0%Y-Ki+~_1 zmq-N2B0v=W?2mn4eZ)Wg@gLV*UrX)y?*`H z+Un}^%F6lk=eM@Dq9{VdC!TmB%d)!J#F;Z2J3ITN)W+84Bab}7QiyP#L6WpDoIiiz zu8Z5d`$?SimsXNi`zTGB?aAP{zp@?%f!N})M;@_UwpNnuTf4`{#|Y}a`|iK`{4<0| zS{>}~Psh`A=B;W?t;4-(krl&(XIED@C*$-@uX#hK+nx^7PzBenU+Z*|*({rkPd@YM z&jP@wKK_^Y-FJVWIWJ0w#Q?x?I68B7bv&Lu{lxQ*S8VfqJeiEqtR5fkAMRf%%ThJo z(PqYbGo4TtrRLl}uHX`^00l3_9kw9?!mf#@mw`@LRaiOB3;q|^RRf#$+4j|6mMsD@ zvvMtX8jH5Z%Dw2TOO2{14pm)ye50pIZbNN2qUSHDdcF$P>FX?{$RRBbYp6npptbg8 zu@zg`+@Yxn5o*2T02M$Y(pn3%HEfx+)})9VT1>=Mde7y6*9LXNI}`wP5InOb6$Ap- zl!z8VKog0uSh0kT9j0a3(}tc&;L2y~PLf`nQT9-kbxTkRn79YYXVNOTY)g0Ll04h~}gwk%-L z=UTg9UE^^#T)67_Q-z5&$UX!8`! zI1nSirC7^Cq)G|%k~I;4GN#OPYn4PHu?g~w1#Cir02ie(OiC#oQ8t-og~?`%$r?#m9fV;NhQZ^HJzkVWkryI>L;_M2sfbx!T^o%jS$?#CxHp?+ zT7_}k+S=II+&Xh`bR6iwl;*DU_Z=VX9v>f+#jKq~rSNPrIyoNPyms}j3m4Ngy}tiU zUYKuu`@2TNK{_jm(3nyyJsVBe*H;m7GA@do%VLBQu%$Ge-T&Zyd71^(4iRr%z0Q#4 zg&hn|Ha54OfByPxmd2XeZB>*eN!q1Jx36!{Cgat${%n>FPqJ3KH3{<7&G2M!NV0U} z=FYY2*VAe7LZVxQJ+3YF0|H&pdLvasK+29Io4wuu98{Mtf)h)0`iO8(o{ zrmK&H3VcEThDfbOsK~xHTY~5!8NRB>LtFsf@uE5Vu?If{2uY}c&I5Q* z+LJd43)i%3b88hVHynTv4I5~lb-D8eXW$|59Pi2(3Gu5%xRl+vXyq!MOd z1V9y>1|sA;_W+;>!<>;#pk}2+TzJy;$A-{rh$dP1rW%375$MzjnhTb#zXu+Md+i@h zpLuW6Y7^)RS%MeY7EOt-X!~mU(Y1=2Z+Gx?y)BOON+wBcbj^Fx+ zpHYgYS@zz~9sJHio8llL=EH-1Kt@6&TI%&@v)R$n;VhjYLYi|JMUJvM&1a=42~g{x zG?q}T&6uMogxPSCwBj&`0Hr7jW)T!;YPOPCYdxLKI^8Hvg1jh#Py^H2@|Mf-%8D7N z5D<-lDDITyNw=4jMad;}x*ZWao6JmE#&O(gwS;YwgjqIqbwR_yRB1{Q)sMPL(aQP~ zA;hh?G{*7ewpz((IJ)iWz5-hX$3UI@OaOd)-b%Ha5P$`JezIo@a`8Grw?nA_F^9R$ z?SEYP`KN&%W?m#9sFoz4*2)@e7O9>>KpaXUrzU&jt8!S$z|mT0uq?g z)F2U7tx{c|Gk-;%-w@vX*6$FJ&wcWbuRi+-09=06>j43T!!WL%CSW6{Ln-y}CqCpp zzxl1-E{IBL0%Txm6b;qLOMP!0`cqFe&=Io%kTBFmX+@la_6iIERyi(g8)XSa5f6;R~or*6fg9ZQ^ zt!F?4g+WL&{mUQ!p8Cjt{1ZQ}fy=^3kz0hq5*xkT4f3fe3e)R^AeN9@0sij4`;C{l zz!%tvBIY8B^;tGlC;j9y^Fw%r-v3M!|7!G{Ht#~H?$>`c5u(#uN9FSJI}x7frl92BOm#H zSV{!LtjZL|#q8R(>j3ZrfBysPGkfmrJ^Q=Y(`<|g@BXg0XNAnB=E}2Ir_<@(moBqe z`p}1dzrO1KB^&nXcPrd>;5nLKs^;&ppKvJG~+}ryv!|-wNYxD29`%UB; z{`hK_>Ubx`rA{=j^2`CCrnKY*^clQK?BsJ*r#Z*X7aUYTBDQtkC1-0g2r^gxi4V^$ z;`Hpr7=VB`p#7~BuiYFxg3OkA!Dd7vsB1!*K`A11ENizv3qlHlFwjAoO|8poK_Nn5 zRmC{{J#hoNhET?ojgYy&Beg9z7ij1JGOzEHA`uj3LZyg|K?Y08PjcZoI(Gpn3L`)z zBGwdHj$ssggiZtjgCGDzYi&T}Xdn>*2%Eh4-lDG`T=fYS?nZU*D`dtWAk{^HQwQF) zglY*iX6zU|5!jv_?zTIfZqy>bxa*ZuLqg4KeOaQrIZmw#PwiP8?6lood899P%*&b8 z{NdI^%!l>&S^)wHuqYNOMs~VKV6*_2wghWf=>U;bQF38zpa2nwP%8?^F_^MeXaP~9 zHNq^VwIbSD1d&c>X=P>Q^>28{SPaAH+VfX;cDI>XDP0uVcrsd9SxK{^+gZ-?pvY6D zTFWaN>uamCY-c!3r&DgV`j0>MbQC2DgFG#7jc%^4tq%vcNRegE(oAcu$QPtDTckkH zl%~w{jMSC(ZQ#q$4h_wLcU9Y=j&Rdx4%e9!Z~4_#ed>+LtP z!9c7GnAjM_5Wv_;37mUN~2I`^LU_uh~0u9`o3@BQs_?vX4Uhc%PdTDs@^zP)?z-QByo>Q`02 z5)f}oo3U8WWt4PwZtmM6&kMJ)erE4rXEYkGZ)}n_lgUIx0E9gRB02Vu#3`aq;-tH^ zw!MATT6^KHJ6L#aeQiE3#^cd^wkY!a&Wq=6+_Y?(WSeXBE!AfUG`|1iW7vTP2eK=T2({yil+xi6(5=9~^iaOp?UgSkNcT$vv z71l(&xwW#fImj}*SWNFYe_=M8@9*yp2EAUtuSjXFl~Olu-0m4Q=)b+Da#OjfxuQ}^8s{(~h=dx?QrDtxI%#Rfl~|Wn7*6vg z0Mzv@s+!YM=hq&4oZ5>EfDp*_j^j{odFvye_=67tz~yKE@Kq1I5rn|Eo!HnQbIc;48lqCjEJzY^#6&_0ffDp#=l}wuS?d9a zfy~L;5KbS;yK=2{*A=l(;w>*HhFhybDsk7GwG_F{el5$#tP~w2k+*;IpZlE;{?bqU z(0hL5AOCWL{k2+cz`Wv@%&X;^~Z<)xu>tCX}nluB6#J>74O~N-fo&Cv+1Zm7_iA6c-@`D&EokN7Nx~= z7dA^C=eeC_N8{{9w=|w02DCAwb~PU4~LZfOot!v^Q9X6Jop8hK0~W8)lIj zxDoaN)ol(4cOp^|!5~#ocjX#Jz$y`@GJQmZRI6@?(!im5BO@Rxf`$qaE7*uRWJ%Wc zK;;0hhEXX^NJg8y$eef179s-3N-w9c+JNdJu*`lko!X-iWo%L0}yGfs;dYKfHsL27I6y6l^L@q)b$1gX}1p|-Z^2HcGBi< zop+7F&{$K;MX?mY%|9(ozfOgy4_#Jfsh_Mu;+D1?V92KeP>8I=-gxoZyE}t4?S)&t zO?3a!Rrup(!|C6Au^wL0VRetMsK4+B1)E9$1cfntwlh1qsif56n87iW9@2!^QI=sx zi&3N%1F=@X&KqJ%6)*!k=Sl%q2n_1XxwEB(*SzkH*?dd@H*Rj<*xs4W<{$dEA9miy zNt7m$w_cOc%8&w+IES;s%}ck~I&+X`Zge#2b-RP%;OdJn zj>iQejYcB?Op>%Lb7mf{t}pVrumBK)W3XvoUVCxVc{dyT{hjGx*w@;K$n(!XH(M;W zw{M(1b2gjjQLK}Jy8E@U()r;G>?~Q0v?4h;oPo|wr%aOQGoO7_5yX)$3U(G2oNsIm zqS&yPUVnuhBysorxqgx)Sy5)01EA?_F>)y6dj1FTOY(&4_4y^UNDwf1gt7+LfoB zD;ebMx%Dr6;j(xE;N6`O0H$e_XEs}ujG~P?9B+H?oO4D2x4_TiqPuOgHZuIw#nA)~ zw6w^|>J23!RU@yUivL^oP-CMnb%|qN*IHi-F>fiijlzia%O7t~S^xkb07*naRCXe^ z1={+Uh@6I`+^%CoOLVt;tMJE0y*m!*G~-xFHmL8m8Qe-A6hLUo7zIkjrMiy5%-AsE zRx&1t^s3X^f(9amM8QL8Z7IwlOi(EuN>A4kuYL+b1hlpcdjYg6z&5*TwH;R@)|#_$ z&j2EzNC}WIBY{#>RnckzRSaQBLsGI32zyr+S(5ac0o7WEi)7iN*XveE$`wm&HJaaa z^Rq1q(9;&kN!9%1Cv1IJZTD?-u?5^?03U#rxV_yQXD+;o0CA22$1l;k${#_fzVh}; z_KPoi+0#bsv{nsAl{Z)MF^3pc1Ykmb)0;ma<($wHiwLl12JnKym`2K3_MSub0)j-E zYTv48RgusOil8V(0?;3>4tkw9?P{e*<0I$X;b?qtc*x9~8*3uD_r56eyi`dNV@Xk* zL{Wczebss&N9lNU7#X~|eIx>9>34Sbj4_JTbUH1Hq9}?mBb%F>M@L6-99M;31Q-~Q z8OlXo=EWQUgfWiOUawb{r7i91%JA^$XwY9l;Ido@lto!~1{+Zt&Bhr^-s|)+KQ-ijsqaZLR6-`Sm1?7YnOZa^w1SQu^%H znbGKIvBvzr6j2*ncf4n!e} zWNGHKA`wM|MUj>|?dW!qEe#V`Eub4LrhUIOm8c zP5Xv)mdzPMiW(`B$@nNuQiVnsPzZ!s`4Fdw$|w_S9f5deM~W0`LPMwkg%F%Cv7)bp zkl#y0RdqhBx3u5_kXG#f@eRJ3;_zkVaX5+GpI8IUM-&K*n7&n@@qhRm@BQ09`GFHU z{eS8je1B|hS;mqr2>*8n+p#;Pm*KXc_?;CF2yg52LIDh8s z)oa(rqv@L-`bw>nqMY|S!)w>BJ@L7xAAb1Z!~MhQV(gtWCMwDWfLyzN{gS~d*a>KF zcOQ25-}9B{tt&qH@ymu*HrFp*zw!LlD>vHrcDJ4nS39qI?RwICtx|aF=FxamaB26Z zi%WNJZJdqz>u0oa2m4pNpNUh>dcx$|^(*0Y=Ze+!byN}=&@m2I*ID4_fA*g>{r{Ek z`)~fYpZ@9QWnvtQC<`(&(N5(3aa!k+3Y~Hd31*xXx1s0RaX= zP)qD1ytB1yKbY7{xeZX$zMPQlCjh1sl05L#06>U{k!9~E<#t1=RmIL!m#E0Lgc-Gx z8ixV|sA68ig+KxmOa)~kA&MeItl)USP-(j{VAwO(2}GbMaEd{-d4&;IN!kVB(#A!R zduKsd5Jh}FaSDKg+*U|so)!5*XY)8t(@s}H*m;^17^4J7e#UVEc0P&Gvr>w(yznAXY%bn)m$UA|9e0k$6J~$& z*6xc}Zj_~c>WL?ucaB|Y9kWwNgKigmo|q^xS|zdfHX#PI0QT@;IvPzb-g)2A;lZre z*<4#^p~+zgY{2Vb~+Ydp#|^_?xeFNgj0D2^wSsdHJUo9yhr@Zf7NC0!M#cQ58eY0KHv zLg`1N?A#rzcir93i$rTb8r}4MAx?Sc5o6NO>!-ujp7(Yz93qKHKtZr{ARvw!oR2k%>58IGo-!^w3JP)eK^_VD?qpCP4mq><8oZ|$(x2esy-P9?}yRE+)z~iL$)vCp@>>p~Ge?q|v7Yc`-D0o_z+=dEFp-NR2 zmX;jC%IdBB>Oepqd{u_2>ODv*T<%}hMZ?WCiA2(Ls5Od+b2d1b;RH!f0H^ET5TPtG zt&NVNFg(pTwZ5MY#M9V3Pfq)Z-@^rtol#AERWhZ0^m3vbca8{xcvsr8h@!YPez#xc|HJK- zzR63dDm;9x7y%)GFWF{LPBnO8aE#TA0f7*tsokNC(qE}u2+Y2M$B(OJC-RT5j$Uah7FF>k^=sdd z%P=zrqShAUcTF54QVXm$B12R~!9d-EQVLqTh19_>;g+G~v*nW56&btBC z^{dZ*@((@)0B`=WUJW+$Kl$S938UtQ~c=E)cC zzVtv@%I4agMpM6+os<`Lj>&p8C9h_50s{pF#u!fB@caEq>;I zSw8#g9{P$)7cYMBrz>dYd%o{GJx)6deK0EHSh@q%oksm(e>&k#H|q6zi$#8Tbj$g; zHyF;QQxPlTvn=ZmItp|rU7gNm%%_*VKN@|e(mZi~-b^)rxQxKKX!VE0lc~Yu^D(Z1;4M*T60B8WFpi%=V zZ4yN1w5{|50I2l)*7;$p^xnD5&y_Y&l++%~WmPGJrC%|86$;xSk}?#lu=(MQV~4#F`%g08YxSlgLQxQ=N7S%^Cm* zu}UrTG0bu06@dD3b&_R;lmQ}uE6XB}JJBCu*?$?@?K1iHtG^OG{S~NK!HtSQB7j07 z$VEBbQ*KTmW$7U3r$7v3t!Iy*h!mrd+)gKx-JPA`V9@Dw=d*bn$4X-F_DZ4wY2MUlv^G3eOnDBj)O8BO-joH?_*v$MOiyRy2P z_TyZp9ttG!Y>P5S026CwqclWOR20sO9ZzSyewW41=hNA2&MbpLe>hm#-#Z+SXSRGv z(cOB@v9(lM685FnPxa0KAy#QPrv(pG-HO0cA;kLoHaK2yAtDSF)%Wqs9S6$W01C8# z5_n}>Poq~ui%Pcc@YsV(>(WhZd;69GR$kj6AW-}68sBa0b3h2(IMT5BvIs(Lba1o7 z)UJZiDyI7SKM3AUF;T3w_RP*%78kaMP#LZsWeK5?1n8`Fwj^5^ZA=`4P&3J4cMVy+ z0KmY@tnKq0+geW54#M@Hr$g${S~D0TLjd3nAHgRcIk&@{ ztgWnStr2iAT*(PX+Gr)G7l^W=Z|)<^#Rv$I*A z=Qf1T7^7F$I&r5*gp0)}&$8eA>ifi&hy*}s8g+XqDoBz<>nObcCQ?AkJLnIF&e_Am zgEMEhqDa5^!sR4Q)_QA68c%1_S(dSNgyNaY#bU9Thir5eMM<2RNH4M(l5{&ABpi>& z&U;O!C>;Ps+9<8)Bxw0%YfCEM-}}g~g}*=YfqxnPc;wyRbKF?0NqJkzN>atUsWuW{ zyC!chgamB^Ib;kYHoQ+5%Kd;a00Rm`6~>3Pv(kI1EBpn`vZ_=a@M%O0;U@vL@!lhb z0uwbU3^O3tK)HlM(G?^Fps2M8Ap>{-P$5{|1rh`#Q~`lOL_`Wmv{HhIEDk_Pi-RUS zU8T(vQpnj6z`A5<)dZk+8U&0+Yh6Le*whr~it>rHuoGaZMXHDh0}_4JTmN)fmd?3E z>f)n}LPB+^YzR~e;P1S6@3pJX0l?#re(0+n{?ma@L@DE~BT&{`q%h7Es6?biJPRV3 zq|-wHln}YY?CoMc?hXRuy#RAIpO}?y$Q=+C9VH^pIhQ7ptAkUx zGVhe4iX8wkkjqi1*+u}NHU|leXd-ucM4#zy_d zZ+ze%|BrwFrH-N6<*hY==+fFajx{-#%Z;nMufFdMNz^Y)xv{n(!e(_1iDuKI&pz?l z)z#tA(d69OVUqT`{eGIJdwY8u>t{q@ZEfR|pZerukA5s%;yeHHJJ&vWeQ$3!&@63k zZ0zmtAKaR2N%Eq&^Zu<)C&{zfd*1WDG)-5HW|ii4x;aQY-RQ|Do)4W22L0xqZ(QBU z3L7WMH^2LBAN;`Y-u_T&Z&isYiky8mp6u=H-uz2{`Mdv*fBtjd{4L)$nNBYa`yc%E zN|yfD-~U4(JBn!UXyKe9wdk)W$s_{hozHi7$A^c9-87aGr{#QA5s4h^9^Uid`SYEP zz1@*31rg5Qv2ipWHCJy(ynAM0p->P95I`Y#IvEdhn%u6|VIU=`{F#D)9Gs2EmTPc7 zR?b2Q6yO!sTpdzn^M#=CdPfe>dJS$=k|an81Ybv{1U)cB$q^C@bC4|vfF$BDps&;r z#RTtQsFWmFVJMYRA?yRqejDNkz=paQs*RvhS(k%^sHh=3L{i8g!pp!sgi2+{`jNzO z2sa6z*t6EUmOJ%kC?be}wP(^f4$;J+7%8JxkycR>cZ#B5S<<>l_2z}7yz}2SX5csI5vn%Arb`+UI{cfb*KwhBE239s?3w6 z+=fQ3g(H!H0ZGEDyp2Yn9u@(pm@gU^vDs zZmxK`o%uz%y4sI;+Jn^HN(ejh42VKn&=UmRL+T?3B%P@VZ8I=rA4-I9j)~Z!Sn5P;dTnt2j1u7_SwqC} zXmn%yhBmabb0dnn#wb#_v9UHBuB;5#o`3%G#fuj|^Vv@q+2Z~OHy!YBedUFxc4pI= zAc24{om;repWn+S4hYU(+?-FcUZ;ECeGepYthHuUly0%U(jOmA_xHxxNTo5|asJ}r z(dc4#b3B?H?oQ@emZs62mr@UI^Xw{H1>z^8MQJTibkBVcDbZzFG8ePip-4HOABjX) zE^p80i{W6nef>INbjKa{te@E`&u%srlU7LxyFiaoxbe-#5;1r2X?|HUqU$nSZ%9AxYX%h#>ddqnrQdj7`ow^T7{{D z5?O5th~&jrqedvq!XmiL%&p?}j^hvk?5@GBdYq7m&=_zc%)XKM4Ls4hF#%!mzGNY# zl#Z7DHjV`ZXyv3~i$R~1LPB!3=~0-Svym~?q=vhd%5O)cwW=}>n7t<5Xs`mJh`eW| zs79Aw(q{<}a6V~&ZXT)iXM6gvjV#t*oHCEWT^cqBdi_V>bB|0XqrvL>OWnzT9<9Mg zD;8CDKA(QoTYiJUImcDr5+ERX=b0IdA_S^Tt&ot&A{Zs@r<3k4rh!%CUU_ zH%2?>vn-!ZCTW^RQB)K~nx;e)$FWlC#`Xb%IOmKpNMRpSBHlS0#oZ!vh#Ek==k<-P z(b3pB4*=r>-vMnK7CX)1+((~o{q=txi=W-h^%BpB;XvE;spVsNV5l0 zq0El3_$(`uBxd2F%=5e;qBKd;v{ROcBI3N$kxG*2N{fiKmWTuxftK7iL@10%?D_nKS8ZQ^0RY&82oj0& zx%Dnq5h4;QstlNLlLB@8Y8)j2>e337Qr`Kz$hyGnBzTC8Ql$?y{UnOwu;b==8SpP= z212cj^BmHP2z7{sB1WV9Kl-6%WuK<~=s)@8fAE9v{X0MTfxsbAyO&QkY*dp9Qd$1g zj5ajRnd5p-@YghR6n5y)B^{69ynTZ?=G>|qeQ6--@-9wkE#-qn>guinf-C?cMgWAk z1SSCx3bxrl{DE&j(a(?m(D!@qi>&OKSQBQmqCY?)ij+1Q{{D~u*oosGe)w%!mI?SM z(jR~H(eUL*KJ@GDW4`CRzFTQhz$GKQ;$Qv3FEw`!0G_e5k|w<@%R8Oaaop+mio#-~ z*%qYLe3nHf-r3o|zJ24t2k-B8R@T;sMQ)W+uYUD|#zdd~^yBl{Vry&tXX-GV|LO<6 z)kNm8|<;M1QJ}N%{ zxo5Nz_Uge`zwYVJKk=)-^gC~P>%INe!T{qS#o>?{AoLw8^OLPVWzx34s_FtWaOb?4!S|BH1Mrzr<4=FfcF_sr&#?v?Aq zA^)qNJvLAP@HJomY8~6x-g_a6)RRv=TQ~q9Qu&!P{gvT`(z~nA?~e}_y?#2IFSMC< zdvSAaJL0`u%w3U1S*o;(qQn?2s8EI4H#Nv2m9MW!3B|gsJ1o6<5W-R_l@ynu7Inl2 z5~>go+b+5k)}qv~Jb={fV1j_`!z&qNmmp$@l;#>PQCihTNkBgYLpG2!l|-m2^XKbV zn2^0dsKtXiU@Rd>hZI4OTA{3IRh`-^2|Eq~w3DQ2In6$lKjcPk*J)hPk`Y0dhu|y- z`eW^p_toWUSPPm$t3>F1pgk552qj28a|JK~2#XJ4N<;xb0v15d zvW$V0PAk%&+uBWaDG3^52Zs@iU;hE0P9ARojsR-B)3TC0lPh1suM50&eF*IxD53#`Nh~lj z0915*!X5-HqDEKlzo`A3*q7ch=#GwD!M5<7E&`Ay&Gb-I>*cMz*=+KA zfABHyyfG@z76_1by4si|imp8WEGQxccU`>0dr*p;wWzds3s6<54bYkwOgjTYaMqDB zPNLXo#}17WSCTT>qA+oMcsSbK+k5DthYk-%gJG}8%RDb$^{Pu(u3Vjtujd>2+S>55 zpZny>AlbVAe$_4acP2MpJWA63)>g8+x65q3qtU1s40Ny874b*=BN042JUVy&+}ip| zn)G+~_KK-};kg?|lXEDgVWqaO?d!0G z0NqoyDM0NW!#cpFPSFWwLgl$^I1^7sCN+3E5?4=MQPqT_h;*E25pm9mv^CBED~Fhx z;92$voG+%@#M(q!$JL%$^9=(?aG@Qa*Kq$7C7pm4aflgWzgSGQHc{LK1;Bu)L_|;s z$wY}~4+896>1~|!niXP_M1-C5aYWp>i9=}%s7h;u2dJ~5>U{=l6#TRW3Q*_g)?~&n zCk_KU{>DR#qtVgV|6X3?h1OB1tK08&(@v+8cIUHsk|tNL zUA4A6d#=wQX}7btJ@K9cunqveJE`HaFLmQiz;q<*&c_qI2@D$DZvE`qsDe^Z)=L07*naRBXJ7^n0J!MgiwtnRyi@ zpZ<=oAM}ULIS}^FmPN*FfgO8)<;Jyszh`vk>eZ`h(!KMpdq{&|;h2#UTg*BGrIp4b z7C~FGbDju|#xgGeSSwsCazt3&=sWM(L!K{I*ZKgE7rBU(?K<>d)~4GZ9)I+sCw_kD zYrjD$^~sO@cKG;_5By&z4tVFgzZU=?#23KH6(87M+s7}}{VF!0IzIR<8%h14U;PCD zcuHpWPeG*`UgQrY;;W&&+a`=BK&#URMi+UZykfT zU9SBU^(#|tWXncE2ujd1qOd0PfA9N`p)h~(ue@JzsZqMAGAd#Pi^-ys#6l$OvfLV@ z($omM_y4uO_UM23+-P=$%uhf4BmjKuW50Xi&foXm_oQjZI~&E(B4?usL=+MQMpRk~ zmN4o{NdihCBuPvJaTF_3m}mqJU~?2lc|L#Dy$^1lJI`#dUAZ+L%@AQY9Dd>x|6y}; zb8T(y(yK1cX0spq;lH$XM+cNu&)+OFb8u^V?}Nj7cyxHboCBj-Yt!$q>&a|$b8}~B z|LACZqBgee+kn{_tpe)duE7sQs=kHj%c4ePK2qK$iJlhfP{Xx$;XI<$WmU(Wp0j(nw=_n#ZAPrE}!E17Q zn`x<+lQf3w66~v(Ny79|ooQ5Q*R|4nVvW|n1_Y<>hefFQrpB+KmW|A!RDIprKUu5A zbR0ygl~W9woDia`&;toRJP9?k5sc9lv{C7af=#+hl?u9KvRtQB)YQdJ^E zr9xws8BzIYnHUIAoMZ2x;+xu)h4li{r_BZ**AX8C&OU$>N#)#@cZ6j{pLMy8) z`}=$2@oev4=j_&*ZnswyrL#6k)2*{x*RNk!B!iWtH^jAbo8Z%4!lTh>G9H6?sCKlF zw=bl1r`um$SsxvZZrr$8xEG!#a!#Dw*ptCaCo0kPdCRSvU zI3bdim0?j%v?gZXAM`Xy92p`+p~Uo@-Ji~;=kK_&JXaR%N~I$r(%K+lV2Z8RY$Klmpp`-*?X1xNfY+IuQp@dQ4xJz| zLa5kMbB203*P)ByEvRTq0Gf!}RxBG<_(%|m4FXc%%!w!%lmO#bXDn5(im^)sfk1o{ zL63+H%i+>S2;!i|n;M@b)H{f% z)&Wmo&DhYR2mpf8It0Pgp1fNB4{&_F1t5sERse~jT1th0&=Bldp<`jst+4elH`Mq? zg+k#`@y^=_swGwdTO35Gs4CPFopUkNMHDMsN$Q6t5g;UFRK&l1{&h99S0iaPTquIy zbn9~!SU3M!9kWC+P*zJJVN45Y6fS| zVC-j;>}Y=;MaiJQI-O1!911KJE=@=)r4-Jm3+raRPH$yprPu2ilQ`!W2l?L45s?TJ zI7LLG!>NFK_a9zm#*o%hrm1*{Ivu5qMsMwriF9P*()r2cfKarGltS;U0A!0Yo9}w& zGh1hGY+v`@pV_(~0@KNqh`SvVn}&Q2#YU$H8=!7%N0 zyPkP}XHJMwZ1TkdP@+hiKL#q_cYViqBH{;cD_i^N8lZXTtH0iu=o26NtrG_{nN8pL z9p7_`hSF+?4GfRa!W~3J#8ia|jTuSci$O(z)qtF=%&k-i z(rMVsn)_*_^RoC6b9-cnNRbIxRW(qkP%#NOk?pI`0>GQT<{bnq!b)lO;5}%)Oq;4Y zLLh>6a@CSPQfu)N$~zEIX>%2s5J{wn*n31Ggd|DXF@Tgsp|vJbh@eP$FIC;}(5)*E zcemg7y?@==DyEkKymv)eIx)ZftN-H1-v1r{?N3&$F1KYjhbLTa7Q%Jx7D{_$T07-2 z8I3g$0sshjs#yBNhWVvXH=V-wa@#jj7sF~R`d=#lqzGCe7C-|0dw+e2#k~Iq{+7*W zzFtxJRBYEFuGo^j|#jk2@4QSq**K=rfGcP{MpBT?e|~iVo@9`Z3I9-0Wu+3 zSEA7@9)Q>{t>~wp_!Iy*=RG4REJ~ZG$O$4)k=P7mA|oTepgAeumDz_~PZ=y#w#u&d#mzWHgygm6F55 zL#6n}_Q9eMneBJG>7{$lY;LYS|J?P@e)>g4acL*FcH%Ti;<&SaI3n~BnZa;lu(IZg z!kDNmONHd@ay;7+?}L@Kpg{r)Gly~yMVT#T6Rv!ZXrkCeCV-@*6<|O@vG%i7h0kj( zybb_t9G=J7nHo)tMJl3`V~v5`bT(q=0aTLqG-yVuL`uCXq;|2o7S3D$RADF#!pud! zpvHi$R77Y}r2?U$cY1jQVy$XI22&?02dKJu!~N)+KKjxwENn(+`efzCbwT{JK?y+kS$9d zl!ySaVy(eT? z^&6R;A|{XhyQexyVxr{2T`RNc!EA^2`^WVeb_Ux3{m(pL?1}imW6uqe%`bzO{ENP2#on?&|8` z`nBC>K7U0~1juLaT3z2<0i~aQ=4vO6T;V$1&Ed+xTRR$!g~gaCHcKSEExMB=VfNlT z_UNo7LQ-03O-Q6v&COKHu`h~d)-R4o6P40hsf`n-eMb0a3EKutBV4WG2?&5i6(-YQ z88wO%q<@1OVSV`uIH@4qQH2Spf9d+b{4uI{-}R$H4>7`0Z8)v=ef z<c&&Ey+sa%!(iJuS7_B`io)Rukg#PDF%AQ5A?+Z9-D{ zlY@*CM2$+f@Bj2xKU}qBmi5P%DR0#hYC&4fv>sm`%b!kbxBv9=+V;zIbwVpREvo0( z60bCY6RWBsf)NtrFoGCTjFCdr5c>iVQ5^UZykijo%`BiANR&bfbf|cF_3G8UEK6J1 zq6A^*oB#vJ>dLU+>%=DV)#7BT<7WY?rKC_H0ur?&98L^AtM zr_L_qAU2JnXfPNovbim@v}58FyDNQUlW18i7Sz5 zbfeo_%;rZ&BWqo7?v0K{o*fw@;sL~#<;vEI($MWC&ap6#k7kic6d9w9Qkr7ry;6#p zIZfj7vD!giAuCX_6(mDhLwq-}N;=T96z}{=6+Z4qW5F=305U>a^A#sg)17Zk2p*E&o zJskjmQYt{*0hf^~u#?-w#^G||o5sSSs;M`9%{P7O;~yr{%$^ZUi^JTrMNmXK%Vy3N zB6+8`N~Ev~N5X3FtaqK(-busNwX)2o)2Rdl*cRjYsMi~+xDO~wqi10vK-KFG0f5D4 zi)ptzKvdd9R6RZbdH^6L1m0-HtYzt}0V1#J@GwF~rC3zU>}n#CD(^xyG0T;Lt;GPa z+#v|7qUtAwHK7vZP-rl0?agq(OSDt4$lDE%+j0I=VtnfTptY&CyQ&o?2$8XkgUh1@ zL;&;m|LV7%=y5fMu_uf6XflnpOOwvV=2@0}Hb0t(Q$U?WnJ7X9F-7dW^Y-AN3RC*q z-~WBeU;zKM)-3Xm{-=Ke04(4ISOUWkA)zr^fQU39{ru1UA^^PlbzcoNm5(vn2xu(| z$Pi@t6isBbnobVqSuvY0EKDuW)iocPj)@$q8IT!Ic8sAUr8{~XFI;{0&I^~El^3oY zt!)f1KY#1ZZ+OGu(cZZWy}YQ?s?paoMJ(d15UKUett@l9dwX}>c}LnGZk@fT2%dTB z2^N>RY*C2P1^}*H9zVXjv${HX;Qj|X-Tv0@(b)^=0KD~anhw`i!SlJT{_erf>t6r5EYC`t-I2ueZ13jvThBc^+uzHb zg$oy6<-FG#UiiXxq+KIuUC|6Sx#1NUgLHRR}K&WBmiOuWF8-=DlbnRp6SbU`<2@K|&H0CLL>6ZFm!%EvzllB&k9% z8z7yi%G+v*9t33~ES+AKhXu^@g*KX$2(u!pbaJ97PC|Eik)@rkR9RV60b(eQJ)#(+ zG@-LKIS~sJkP;)pNVD-#f3Omq&ds7~)?4*KY7)p0xnKDnv9_=pB&%MLathRffj;w? z)$^r6+h45RW-Xk$GrWX6nVAkNv(M@e9UE@u!`{IqOt1Igw+IdVn zUB_cv&Pt_?QCcP5IU)g42x>N)<;DEc#q$vgMT$tFLO@hnLlu#sqX-c> ziZvocu?9p$jTE9s!~Q}wnhM@C0!=65mB9)DX8ByHNE=<+%ws;!4zFClwRL7-{Up!b z-IpG?{KDnwY@DR=wHsHu-JY{P9h~W{Z0y{aoZY%pD`ygIBJ>W}0e~Zl5Xm|lnV1FR zDBjrEGRBm4Apo7;U~PRWSxHh+<09s3@XdcUby@lrl!g zsTr=VKJ(N~kcgdg1x)kV;o*TYI?rVfX5NbcWO=q&EY?;x);3ngTzh&b<@vyR#OD%wFSgM>HjZn zZyIY^lAMP{L}s4lZf}3}YOm_<>7JgRoioIc)CdwGdKMBi;Snf{rYr(7DA}@U6Z~OA zf(gSg1Q_u4$2KfMwgJ+k#ac*83t@o?FV3}HUes#5?S2)msLDYnnkwe`( zA$0LS0Z*4UmZ!rmy4cSy;3atD*mEbkm;SsK$63k0icb#ciBbv#y!Y&Vd?6wN5{YG2 z!@!6{#~X8?RtT0wY(q3dR(%!iQ;-lzk__aboP|GBxfy$f0YnHhCvcEwb=$1(1|`myle#M2 z`@w(itTTy8lC);Fu0{=7X(1)Rh)rXi)+#YUr9oy_R|`V!=Q_(WVaa=WVhnJI9hP}n z6Giq?7C<29Js=W+^K7(s&K70aE#K(5C-h#F3T|5^%+@wq5dzK@^TZe-zI5eERhCJr zk5BGztgknX1%RWYgSxJFFYGRg`PSBGu(s9s3emjv`s2hHrS-;kFG;DcVm%F$=r9kB zO4ddji$!ti@)hsF7;2iPC<>(!SqXck3`0eV4xWxTx7J7fH6+L0uMLJ}K>}134M2lf zJ7=8(Qu^fh@O%E*Z~p#|{h5>EggqltQ5GPa_xdL%M`c;1NkWJZ9^4TS5bvE3DP}6F z1tBI0_WN0{mp^`VEW(H?$#gzQ2E!g8?LRq5jq;9@beN?E1Qtb!fQm>fjez3+bd-t? zj-j*mq=*Qi2z>G{{sbb%r5#HuEQ4q|EN1n1?}vT>J2H6|RL@FMSw%D?Mi-wIJu4^2 z77|HY&_P5bfPyVR(5c{nidOEd)Cxcd975^O)!D;n3?PeiCAXLIynQGUg$h_5)Y2AI zQe6vy&?p_|eXN>9L_}Zu!mk3rhkxLQBR4Lz48+TJwj7TB%r_jo5X^z17!?s=a6GOw ze#ycUdwt0aPcaJ}@q-`v_!df0%o^MHZh#O%eGp;k<*8GysEWoWz^d0DwO|2)5VH#j zP}0`zMpPh}nBHgHq5=|K0!UKmOFu|Bt_nfUD6l*vfBNO}J>YPXPiAWi%v~bMNh` z45R}k0|&-;vHG5KpYI~3Chk1a((wnCK$a6YZb_>KAtC@W2#F6E6e6IXJ-GXg|MkE7 zJKbqN`!j!iel+=epZM?3=10R81SWlq5zGl2%43(X6!+=e2^?oQoaYZDLL1 z1<5lswF9zblCrUn_wUqoQB}=kF}wca-i@nQzw)JTzvJa=WnC>6aPQ51W}Zym$a37= z8Y+eN?%m7M{mFjI(6IXj^v25}C%j7o7AkrAH{03d;@ms&8iyO0Gy1z_4^B&NZb-4>!) z2tfoCl7JWQo2HCwVYvpn1_Yl}yK$Vcz7YVFGK1l|Ni;yLMICXSpi(i!qSyrB*^3XW zDO93}D==u?ZC+BRf=e4fBmhBvc6|~t3q|4rD<2VK5aWRyA<)gNj296@sAJ0BhmN9< zy+GQzs+aYxs~cMrfYO=)fzWxUmG(eJV=W954ejs8De!i~&+C4jBY42mtkZ z1Ls``AS49ms>MwDgEi8r023OIju@2E>;qQD!HXawngS!RLImestJsTY$KFTZvS;?J z6tQ=U=}A-UW`ltTwOS@G&M0Ak0HZTfG*MRid372>hvs4HgI|t1LJQ1wljs zt64F#RrBcK!)wN%)EC8hhsrc zNpto3#V>vNi&w8+5nO03$Hzy#Y*3bqmtTHyIzMTw-Pzej(7*NTuWR~tl4h^H=f&P2 zW2t8o#a@9BB55+c-q2`b=RiO5V>OKYB8opK7BH zk7hdG+P!e`>tFdQz?9|Sz3=^Sl9|(!>DT_?>(06LwcV4Gv4}o6I3a|9cW6o({Cqxl z)*@h%W_y<}O~;e*cyc;9vNgQ()mIj?)5&ad<a72W$E`?YgZ2?6##_pt~@vk1q^o33f< zR$U|&+=5yuy_BgzJLgcT<_ySk*7LZ;(_1mv$+>oxGka%k)0hMj72W%kE9KGRJu!48 zDu%JqvVsmoaC`-YS-wW+5o_^uk!~mGAgA*UUtTW|Mk<8Tv-n6PA2vD)fEtDbB@jR) z=d86AprmP!P(>sfqKJ!-`cjmkQd%2bRb?A=55m5-Rn{AY1`%T5odbn#C&xyg2<-=M7LC*g!aTP6J0+Gc70*FEY4c67A zw>9}n31=F9|93x8H+|{SN4}&@s%O*k(uE6% zUMJw3x3zc=Azvg(GVh%TG6N#zy}q-&D2m}|Xws~Qngxyz4@B6pwH}aYv^G#Wd+XL= zo~PC}&T+pt%=^85zelL5+7V?%VW+3fXFu|85l9ZkEDXXXN!U99n9U|3sw>NLW%TC8 zX45pat+P=d5vsDde7Qeg%%`XGx+;o=TVLPw-Z4v2&Ff>UD9N&PYpdT>bLC}pi>z%PH{SHlTk z{QPG=^k;qq&ZZXu01CD4zQCvjuoAr)--TPu1rY@lQWqMtQe}_;{3_1Xy?aD$l*#jv zQf1BX!b|UY>(qXhr2r*>TIp>@c z(yL>lP=sl9m_!6Hl+9`pMnY0C|BF=EX3lph0zkAY&WyOy3J3xj7Xm*+`SQn2Cwk_f z=qXulTDW@m>1;&H5o;TL_y4!yEBOlnkbL#`Iy!*fWPk-*`|Lgzu zfB2vO{!jhepBnCL9v&a)aZ(n=;Km35(?k=Yv%V-NgJIv0n$4zKrFG-dMBlk{cYQE2 zS;QX_^R#7BHDPo*v}A6tO9axyf;7 zYh&H!2airppN|Q-NIk|H2%7yLCx>#Jhxd%{=Pp0Lf z%TKi3FuvpESHJQHUj~55c(zy+U;Wxwv@xSme=(c0^{%NjWtaB$vR+!(fJ$C^24?D2uib!lHlFP5}+@iOvT1lS8HfU_tCB1OW1SWa7@%iKgj zKyIVZ5itZ{5n`L>gVM=uZX=(UViLL_I9Pq6HW1L1WpodM#3-D=suLC;Dk2C)$dJAF z%;G%*D4^_P--5WFEvpj-ry1OTM(H#aw` z#lm|A1P`*avvvE;+poUzPDRRE?;7WvOS4pmDqNtAB8`9w6{68fp(Ke?$Vs9#dZYxA z5t#%ON}6hIj6wvK%2o|m*&rE@r<3VeXE@r{T4$$6QcWSlVS>rzw3yGF_j32%T?9Bd zY)G5YaOdgM!`2JlBZ5F( zEWZBWuF|^S&o?)BgneC26)BzM0Lk{wUY2J^M@MO*Ce!ib#}D51+RI=6+Si=5ci;Nf zXfzy;$0(^udoIL{2(y=b(66dG5Zw?D|99vt-g!|Ak0lb!nyCTpWnU+L51BNRdc@4kcRK7TOC{>MKD z5vITxJtDIE*?%L1MSJJG_dZljCWS_eES&+i z<41rtq6DI|DtOBzLZThYgHfqR1dvbszJ)(7m<|BH`Dc6K_A6N}u{~|WqWe`mg8%~) zP&82^i&lKhxo(MYQk&Yj{9)xu%b&vb#1drk`52s)mUl3H2L%zKF^Tuic?O9r`kl!y z2uPrS>e}Z03_9;hH*GpOgOQ>WF*-|(F|A(~MZ|kA>;YBW`?~jt20}YH0N6$12kbfI zxlk-W8s0%z!tSj|$%h|{(*EAAQYz%Jo(;DQdPg@imhl+Nsk3r)WA~h?iV)~*S`cK} zlimH^<~TDw;LPxRSFtoLXt?aQ_RI4=TZ}DfzYkV~E33N9`$H5Y5Z}yvv0!$r1O!ph zhd%PzrfKH$IlvAO6!UpvRMpfb1t2skAtGikB7{f?Nn!+qS+owd5r~BW(L2|XU0_g# zqT)o}dn95Av|k{rMGQlft`}0k%qWOJRaKGFN?}=5(^=u9VT2y1i$$R{BGNB^pmKJx zxv^c&7i$~CvRY_OS}W(|pS)HOvDW6N?z$v1ERMY*QZY?f1QF9Tan2!g@h=|)53}{#HO6Z+H^n{*;W1uyFyGnLv*ZuO*vW!z`sdN3=`cUyuN{Qz* zO#?f_jhEj?f^WU~ufOzLzYve zhJ%q1;yYGikx1)=(lqVY_2gae|Hy^4d@HWOf$3W@#GdPORO&a4i!42gU)S z$Onn4^Gk#~E2W%s07{z_k+i0=D7^QB;gB$4L1qU^P^m;I0G!QcNvf4nMkOF*TCXN} zSz&sMP8eneWL~lCLOkE<7K;poBnrjF(^l)hJUgHgy&_Q|I5&c=G6aMo2CFU$ES5uD#9!=;E9k1gQ2zdt+#GpzjDW2L}g-;2bmWUA*+*!Ts_0l$iy% zm!?;*Ts=NGA|)a|?`3seA*!wI?YgcPi=wFKPKw6T?4+1XCTX4x2cwOR&8^+^@x!Nw zhhr3#@@6`1k-ZI7MN!v2p+2TUFD9q!2(F^;@puvk~v@ z{EeDl{9-wCr2Dt~Bbt{8h^R>SOkg?5n!0h`yWo`o&;p34wQftmM4widbSd5N2az4q zbdZQbp*H|n4eALW5mX1+#A$S{wXNHe2%>Xd1Ob?(hdfzOrOEkuKD^*R8E zG>A(C|4g?9=OKbP5NT}ftjRJ$f|WSW_L6AiK}+-io&S~yx&lceOVg)qlLV$=L{zcz zT{OYkHS??|&?LE{gb1q|K#T~WR*U(3G)P5wHY-qop=q4eI!kpHI;HD_;KuOmyTs=Z zP8ia-NGtGy!P~$dh@wHz)~CzTEOfMWP8$Ux1O!MJ`E$rB3JZt?9uOdJnJCsmQ47G;F-aI@9H58 z%NZWg7!U^2{RjXXqwRWj>|ml()Y)QZxQ-yRa)O+dW#gT#rEZ*f&tiCQ?}FAUNfKrT z4@EH_3} zUVh~(U;YXa3HX~Y+`N0|zO{{Wj-3SR45dw7;bb;9q>L9vbD+1w&wB2j#XG)O@Smv>&Y*gerIZapGF zXtw;iNG8!nQs)}>&N~m_09cXoz5yfzg9J&E74rgsj7gFt2T-l#V}MxfSVAs#XdNJt zPK*wb{X`V@O^mHj;pqY(z=%rgMA##uwY5?iMABwK5bp!eB0>ntYF!*G99+ks2!+R| zN81;#0l+!Whr}IF0FV#}gL9~3Z$GaGOUu*TcHh|u8W5s@_fQ;^Kbko24t&mE&z^J^ z6M8P111m^STZb~vaEewNTiYn4#pwf$aD4M0RQ2o!uMf92HUVU@C>2s=8!xN~=hI15 zSGyN>l~TjLL50j*EXsbrhk$ie1)XX%99Zj!RLhRU-m})El_CP`QH4rKVP7WzWUVQz zYmG!0?CY+*(iZ7OB(kolo6;nvs;k*}VvNa$L^v!Kg)O0<4>eM;XcCjzdVYL#1OPbo zANy^U=fkp`UD&-uh|ZP0eh#@S%EmTskZ%fm0T%)a(lp)J+Gwz0I%g|F(n$uOhQl?1!ST_NZETjNRKmE?lG);%YfoF!vRO!qlnfKs* z15uGf@0o~*&^a3**5R;+SU0uvzG^t}EwU-IRe?&e=ND+}z#SW%kqQ zEJ?GfY>XZrpA@}3PZ1Z3MVKPYA);LAE|=v``e;K5FnTXnP50G!b)t~G?BDL(HPTm_qWw6I%Nn^t-SdPDj_1Q zlxoWl#chT;R)g;LfVSoFvbN>n%G|&6%`defGXU_tAN?eBMYRza0?fzVSah%pw!uGe7G-E_V@veAwt!Tq zQxN)4sZed6kvy=<^S+hlbn;|l?ZR~ImG+aFd{;COluvP>RpQDZAnfu6d zL7C^SqjM*C=xV;a{b^^n6A@uV0j;=JzWLAo=3flo{|EocUp;yFz+Hj7w){h=M8EuY=q8JW`ufP7Sjg3u} zBmqoW8xD(Nk>rUGSGMT)Q_n<%%Eh+S&SlD2&&m)74jEDskSo;zVashSNiwb6!OnI!==+$+BxNufO??g;DBof2wqPd^E9+P~e3duRcB4fAQuE_wV1m`SMG5Zr#!* zpNvl@ljHZj@7*ul?3tAB-J1fKjm^Q6r+3?)iEY!VnM@{!hewDR0Q}|LRu(;L7F8 z!6GV(=SRFl#BZ1C(dw+D7%Y8Ov503y1Ujg7hElE5NLdR3@$f8CH%DNQjcP^o}aM5Mff9wMV*H<`KRT#pk507GeuE~96u(4Pk`I~6JX^XwXo zG$frAl{WK~xoy&lwT#h&9DRLSp+lZePjODDFfn+8O>J#seT12mLZu|~ zEJ*NeM*n0B#)JkbA`VKH2;!16664Mh%4f7@10p~LN@u2j;qnEbdNOW|-ExJKNdO>5ENt5 zh?Fr~Tbm?7Kthd*2tXkSM{Z7txC+Oxrr;6)Aw)$0XT_7gtX#=Cr^Qe0J+1w zo(F1+L|V#j%Ebu}5uc1vs?UQ_68`MUB>4E5fv{=O%%d-nlm(PbQP{n{Rw$Z*OOPt(WS&tgNE>>B&Uv ztXx!8Q4pvkF&8dwTFcW(xxO*9O|!l>NYc^u>!v?abudA*yeLXzv?8^+xpnJ}Hvn0Hh57dF+w8fjns>bPl6Cg}!v|a2JumL$ z^k92yXEfSk-cFMAiGGwMjzo=57ggmD94J4Y93sMW(rj<h zgY1!@tgbAN7UQ6{7)9G6=}JaK;k-i2`W>2!?a`eNE7C2#?DFaIta$HmbU35yK2y!3 z1!$qoA;K7K2O`#c24PeRK}Gnvy&|M~K)Xu}RK3y*}1SOBn1lO!5fyp#+I)$E-(3FTH4_xrs-M8d+t;Jsv73IN5T7*EERE?;h{s-O3K;!!EbULgX3)*1lW z3y3%o$E=8$#SnUCrO0_7s5qGgNXbeFMOa5HUIA8B;k-wMlj-U9_KtOxbq)m=iy4SQ z#N(5rB+*KnYT*P(DM7?uFGsZfUf-zX;OSFD-rVZfwXbT+K2a(MfKan32oqxxqxE3e zn@z`)$w^%`q;;C6qtSpF^DH|(Z4j~F>o3Y8%d+XT5P-U_%A&~gyef+I^>sk3>qhI+ zITuuzEKLExJIm}xgSDoyRaMn>Eh31D*^`2%@s0IFganB(?16>n#ll|-aa}!%6h%y!-L>+LktOElq89@7XEaOCCTDho%PHn z@$8~fpfDjbYn2EfDy_psk|c?Ej!7sY!KBw(D`mP6kB|S@U;4FQ`bWVU zfAu{d{MOgL+?Be7c0G3~Kh(m0@XVHmZC$Oe-~8Ucip(;I$PB?F-tB@!6u63`HoWv1 zu7Xp6&qakTIb4N^ZOPQgnLPB+WcG3{5#-Wa&VBWi5KEBoL$# ziipyR0IY4aMu?SbLwyzuRjyb1o3gA&%7n6gC}5jLdhyLeG##Nv!oa&6DfE$S(*S@{ zm}ZHuy;8w5fFhzvvDT=Qju4cH5CuW7OYvRecW1QgRov>?X&mQ98(O)lUc~)4?pUjV zw(YfY=04Bgb)MN!`0QD&U*Hejc$R=nOKzkQ?BD(yKiZw~b3gqzGqAoA26g+<>o2^r zrzPLo-D1_8JQ-83uZ_{EF2=LV7cahb=T4UQhW*j@?zUsUSS&U-H}X8++1XY~8Dp5e z0B3pL*e2^6Cd))k(`lfVGA zPL0uPr^hG#k-7fTo(DO6I(zvY@4R{A#lc{R2zh_FD5g&A)x8()+`04GYwt>utg7{+ z{lnk*|GxeM-~R(|zH#s1=}CA*Cm-gM>DQhDa0pHH2036WANO^x$BnVf1JXWe{04|GM$((4VX#sR?Q z=JwOaPcLlm6-6N;Mh|*D6z0Y3$XgGI9eB9ivZVBmab`-nHP)V;NWmD z$de@B-r0NfX#eQwXfl~>Zf&&vM*!IG4eGijdpaBOPPjTZ&dcrg9OC8Qf$*B6$`ire zSfK$rrduS93ILKeH!bAoO2DPO4?+itv{DqA%cJ7%g_R;j)LGO)QefnqmR6+>(z7jn z9i=xwbb5r@B>@bTl`yN$fEE#grB!@JZikm$(ukdfumwmVlI9lc>GlHv@GC+Efk47L zL1kxEIY%VYCP`AQwJ`}IAu2!&5IS}h5Q9+gZE{oSi?f<6A_kTd6=D$BGm9cZA`tXm z5CkZWFCyHyv3-0rt_nInJnr?C0#o~kJ*^5GU} zLjdeHHH21N#}P#U00qE^z=5m*J%_?B;ruZ8OFJs)>m8Whbtc3xdcpWVptC-g*agpl zU!M6a=f8Rm)EE8p%U_eJH`BuLXVgk@D#?VQz`lu~JyF~gNBR|LGU2twnUte+q? zfuX{CAkiYwc;~}{7gm6cW38}pP9;fW8#KD9UAHBMaHXoA6XByrPY+LNHlOwf*{koq zhKYXg=Cqhkt9tR$yRN?e^#{(&jq5KeZ7{@SX~23unN=r8@MQn!#hceNmu=;}-}$X? zo{o$6z4v`}U6hOY`r5AeP>e&YwbSY3w}1E7Z(M)JHTA;7hj;Jazhj$vXM3|M=HAsO zr&9m~VQ)P+e)*M`kB?7mRXgViAx+Hs+S+V3TNH)K65li;;@KY@JoOxC9U#wpf%pAA z?|=W@TW{^`?j}iU^mcg`EF8brq}BO5+MO| zAb{3NhavXfBeEt9(P@qZLV+B#15-jCEem4QGXwwvv)g%22_V1_#Y2eG$pqv%lllDk zhKbyLZgB~!xTXLAAOJ~3K~$L#BZe5W&HiYp%$X*A7e_2gwX|fPZS+}Ip{}tZ{y>P? zR;P7cnD6`Lc{#1Cx|%m@$rhpgy{5{TirMT3*Eg-L$Py`?CF!8wcg~%hp6u=JaR_E~ zOhl)rN6y*HmoA--$HU>!BX|__PHPkBq?~nHYa$^9(0D^g6hJpIiU7fA6~bYd2vJt; z<-q4ipslU9ch(sFf>BmnWB}vlD6Ri?k`Jj|0CTVJqO@pWu(b{_7c`1t~OLOmh zo@eVD7XYd>Cub!|vg6|!3x4{Qg+JMf7#omMlx2hMtz>dKE{dr!>E4BlPY<3R9vxPK!`>y*-3YePhY^Z6p^;lsfIMCQ{eAQM4RE&_;e zj2Vqar>A37((7mQ`8-W}NutthJxLO0UER#I#(CK|*J!1^Z-AgEW(ZW4smm1 zd2YRDhNn-SDy2h>8W33OkqlL7JEP!F{5XH#nCcSNV2tvJ@qvg;6oJ^V@(H8O9D|Kv z$rZ3lE-Nc+DTs)qK>_JyCK9s)LGOKCHbIRG@$g^#?caFywf6`4h^RW92F`*J9dGWc z2nZS*Gk3;xpyi5eEh{$(0onmx0O%HG#|RV4B>noo{3k#3$-j)Gf|l7~AFFu8If%r? zQh?BHTL{473B@@dgJnqHzxyo!_~Pe36R!Q>M?NN^0t9o`%%D~^M`%Zk}aXWtVR#M5eQuxrxr5< zi+I0UpCv32S?O?$q+0Ty|NEZ=fFJs?pCoV38);{8lQ64SMQ!)1BIVIhYoMO<1Bt*N zukifyc8Kq0*9bO=w5AFC?VtWc_uIes(?5i#HM%+#B2-hTJH-}7kyF(Tf+^H$N6%)Gw2_R1?Sd+S*w6sSc4=Y3T* z-~84$dj0gBue>~&%+^NKaMSjcB2ro>Kt!Yv(C7pJv^JgJ8c}sln5OYXHQU-<1A@2i zEYSBdL%;u zhyVD~AO7(7-MDcR06z4g4=B)!MMC^E+lJu0qlao`Wv8<{r%MK0>wzqaa|F8aE0JwVXs<4p4 zot+)`hiN5oxeHO}E^D=j?$VHg7d6EoNhp>i53aVLq_3`sPN*tU07^(mi}oxc);spj zITl-!qF}2p4gVE%Gl;0L_^{0zXBKD`{T16_`9vZWkYrpzYQp&)Yy+Jl9K|@S00Tk% zzOrQnt58BI>wt2!;Af}KlTzqhr}iy<4AMy#40xfU%fp3Ek@+m{XwAD3lyqp3>5SF5>Pv-M7@AvAa&`O&Gt7@8N$)o)TTbsKZn;QoQPc}B! zvn*FiJv}(^&Lv4|n-WAqw#dfDx_=vslFq0i=XKgvHKkPrMkEql19rMVTv2yFzB&!@ z3|F+s^7Iyo2MxeD94SpmIx7ae~`^)4w!{KGj|OT z5fC3aB|CVRuzS^T5UDiHTa;MDbJNsmrlp-}5!6P|+F*;W2!Qi0I9>t7x87U;fVSK> zL}(maJpK9X=u5$l?d*&b1kcT!?tFfhek=U9>U4hI^S-Ov8qa+5+>2t))_2$xR(BDM z^!O|q(W5{)J4mEf@B3wRs+SDh+?hnr%F|Il|G~kA&ZwjXX`7~sE91S?RkK(u%Bs}b zgidN2SC++SG$Nv%ogD_)+}sr55ZoXrsD-&vN`n&t@lFhC0q_8bXstJzocCHQ=e!CV zK^r);vfqMp&a+2^`w#YYqO9{q;ib!4Wd-G;sq1okcMXa5ADxUwYa`M`YCfNih9gh_ zwk|9COYaBgX1hCEKmLs&U~>D7$3@Xxy?WKT`ZFJ{dTJ!xRk`M}tZv`_*4Ea}*4FmP z=@E#XO;3k|zHKV@ZaO;=k%$+tT-e+5&d+BvtxZ`jv{s|hXf~TU=X(7fAcXwG>2$&p zExmvrIM4n5Kx;jjOw%;0YSGji^tAKVI#(>FAVdoCEHkR#?-?KgVduy(89{by1O6%DMU0z>ofs~LMYr{DJAWy4lrNf z@jD01Q+qh?+xrNzh!jrd=E}7f0Zata_b7m%5RpLU ziy0s{O*I&8*Vg8FPDIj9h9G~D6f$`7CQVcJS|5q1XpJBmKJz z{?=dn1Uz&6oxlIt*zBcU5Uvt=&K^OXI?8_vF&0 zox`Kz+Qo~2`|o)9hROTfl!;Pb`PaAJ`SMG%a#o&5p7a+@WnD8b769hL?jCzbN|e%C zK`$S$gkUG{nSt>Bqes0o-`rgP;QK%5+1tjKWi_47^0XfskQgEa1xUa^Xb_w@jmFuA zlGb?BstX9%-+y3Tqx8CGKN_st%2{!*zIa6$T~&Pev`{=ad~$m6^7RJ~zmeoN8@LaD z^nJ&N^`i%~r~6O9@4x$fFK2x{TvuQF%C`a3_Jz&q=^RNtdVK5n_c~QLcoiD!r`t2JxuI%pa06eX8+=s{#l$b zu{tMD=Cj?Mi_gxq<@^wlHqx475i&)Bls_+jh!i455?)0J818^XkM3E=i!{wpnS-ZIRn3~( zG*;3a^K{@Xdn%o`$XwTT-V*>p5caMt7F9)AmS??zcQ#aT2tkG|mprrqAmoL$F$jP} z)nYCngTZaQ^X=dsS27skwN0x8GZP{P-y_NLrp8a~wR7 zsx0o`yRS2N_~;8+lDHZYog``U+Phzt??t)DvUD~*GD&KT_f9G|x07Nr!Qrs~!p%#L=S5ZY z`h(GCdXaWckLGn%)s4@4sn%efO;h#s;BjKo-3vRD$#^=OX`QUCt!-{>E*A6g_yh!i zL=nyA^EB&y=c)EAc=y~dMLH=IC)x75v);JXOTyB){|N}HeoG9(S3k?b?3_o8sw|zc zIy-BaI`w0<8B1XvTXMd^?JaQ$rk-6LE4X(M4l7v7^2AVqfdO!(V8yZ-?QRtX_^Ki$ zU5G_@YYFn4nLQza$cHT{ZGN{$2-NNZQ4mS1g95fM7;h>Rb0VdC5Uv6S()J6s;}sqb zz-$M@{K@{92(mm~%zTy`K+oO~KvB*S2^31qbZZ4BinCTJMTC(-{!AwUNZjLzkQoBu zYl{knAR1a#Keg5(+|HubQbXZYg3_*z6*D6csumP^Td5bg9=mPydAY-@!+mD3&YS>% zh}=dRJr~mZLm_oo8KCoxTsfYP!*maP7B>_D0YxO}oh|C3L2l&xK5J(#)yaG^_n^kJ z!ymb{muf>qD4g5*}*VRQ&UuRv8cDUMs)>;2PeR= zw${@Is=D6T92u>qlX5g%Z|dg6o^D^*FbR#;hQ+KQB5ln7`R*wI?{7KwYI~<@YD!d^ z93%?KU~F6Q%IKP62~U5ELP2!f4uV7&{s zAS9*H+ESA_9WMs`Av2d{*&pazwG();+2tlA2jKdU<#KA&}fe0&7jFb>XR^%9B$;L4lDJUH~ z#wG@b!5F%EO+Q1s-|Ol(znbo?y5l#0XWGNcAN!p1eYdKfz`{N%-FxeN=iBF;efC+y zZ>{xP#6b{xVNn)^Wk^~*t~z!)Wam2a~k2 z=25g*IZd=?0j)Ly_cwmv69Di({oKF&@gMr+`bQ0D@>4(e&jk`O8YBP~z!rpKgCLP? zlSlU7)nEVVfA}kmk{JXVyE3qFJ|NT@=Y zm)XW3aitAIVQq1CK3*=0t?jG#Zojs*wH>vR{iiN%UXEY*@Kfgx%0V*BdnMVZ+wEq{ z64)9o+pUOX*d0Xeo?47^$Gk|F#+XKE1VQw%ul?%N@$ucGH=cdpjk|B(1Ay6d{OM1B z8UT!O%&^R}emlOradmWlhUf(1)6c&5&fRykDUzhUvvWC$qBPA;PsWTu>;y?`U7qKR zP-rBH%vL+A!f1PEcyc_6WV~FI-ELdE(l{QSnJ@_7xOp2e+urT_3k#JJGP2gSqSo2z zNQx+mk|1pFUw=A^g7fq9;c)1WymIv#fJGu}`0V)f*jEMZR{M5y3e?AhN~$3om|VI2hbLc&pu}C!f6X&YQmI#QM$O;5PL5`7JC>fChRS`cClaPR*d+jK>G%R%? zmF#u8PP^eoi@}agr|tHpVRvwRyEOXhwI`0x-yUwaHiiMI%h{ZBGeZZ1jb4`JVT5tm zIXypKWEm^h9*VOEi|KsC4ohA5PG{|QXJ=>k(%#ms!?*Hs-tTQZxOK{m&x?Bpca6;vSdfUqc(GV8 z0+AqHDuqETr4msTk4JL=p|xwZ;@NUBPnU5N2P&MLm6P-N#;}uw;c4lNcBwIi&f_>n z;7+?21W~u!mnsQEIh)M}8@Yd3x2ZBu$LGd!A*DhR^O@CU zW{j|wr9woOB5_zc=a_w2ila&ua*=0<5Cq}JID9c$dk}SFzFJKBqACDH62faXQx-}E z1c)TOmXks_pY92W%n0z@d;i}kjCOWS)%UR0!sIJw{ggFSI(XrZ>qlNM*6ORx{5^7H z<1PX4g|)P%`m5}pYM{r`d;KxC#~k&?+qJsZwIjH~u8YI-M@9 zF*c5)tNWW-wq!)1Fbt)&B3-0KRsf(N5&;x>A*GnjCSe$>KxS#0<+&gkCrPW-E{a^2 z+B<+!iM%MJ3W6X~D*j_Fz<>X31;^Al^o7m2D#Gv4^V+a}c*P=BSY@?5WaZXS zI<8Evm3Uq41W_L^5H85#W`u`E^X)tuK@1hR&W%_Q5?s|4E+8U=s(C4qs3|!r)>~_> zK;_Tm*fi3>8VdyeV4_u1s?}W8P*Zbx9$~cO{vasELLMW|42e8aiB?B48 zVcd?wkO)rBPFqQfZApO&l*qjPbWR8&lFm6K9|{HlV&IA#s3uM)BBjFVbY`8-$`$#= zAHA^yLg&-8)&MF0ArZM+XcZO{rSF(gRRUdUG`* zxjen~mw)6Z09e$%;?MlA|Fi$-Cx7VM;NNHau^;@@PyhVCKvt8&u8aJ63xcT zCvNO(qsZ~4-Ax7^gn~*4gE-6PLXbAqR7^$-5+Yq@ySqb1A}MoiBN60f8Ag?~5~!Mq zHqIg;0Vl2G?(LH(Dn9h=4GI#x#c@knn?3j3b7{8x%x8XQ?^<;0o$;4mIe5?0Uo{=w zFU|bMGo8iMb~;-@r0*Y|UcS0F9!(~v)83#RMs(%s6Ja19Ja{lV8~by;^UmwbY-F8I zmqomj>~8Np|Gawj|ND)PecjiDVHg~p0Kop$C#8rxo%VD(D~kN`mFu}F+U@rF`Psq2 zy}iA?DB5}FowxHWCGh?{z53d#e*FFYYk97dR?<#-het>4IPCS>XQyLCCK5OHpE*B2 zK0iO@Ha_*_^J%)6&&B|7eXuqKtklDCZZSK^Xzwj!`J=q@4j*#4X-vPAOIjcX6w;KsDRxyqtYM$?nVh+bfDM1 z{;uEfBBvs;^irrYo$C>tgC^Qpp%uUk>@2UB?gJyC=j?VC0A!tXQsF68Wfm|35}|WG z5KgPura!-{bKTZ%0TG$lH)40S;;S8iDiwqT`F4TT)c{~4BUVN*S8XDg1ricE&%=(Z zzB=rC6?q$dt(U`EDboslxUivz!0OC<1QaMy0D_RxSe8n%V|G?a$qw7?4zsh?`idhW z|BtL;1mEe}Av?hc8I#8UC2%!d`jc3d4dL;A>P{6WT#UpE0z)1Q8LCR1j6F zXjS00a$VL!HH>T}@OX3rY$5+t?B zNoXKUTA>9X00Ie?5L8(%NC@x68s}@{oOKWo8Ap<&u_Xc73im_=0zrsutTx6@=8K)J zu8IpOg*Fj`X?I$25=BvTc>mzawcd?qx6>uwd2@Po@A`ZZ938!Uc7C+Axm^^x*B@LS zG9-5Z03ZNKL_t)&^2B&?tjkPLppiZ)yA)6?U#v$I~WYm5cUz>I>N11Uwf)9&<#k6HAqrAsR=tZL7?SXf)(H74+g z^u-2|dDpXm$0i>Kwbw%v(c!nUEWLHA0Xz$lgNqL9Lx#7z2(queXcZDIM8LHUz~&`e zfiD*>iGe*SfvZ#Ws}KSsgIhmQJx?pT-Daks@*uE+YF8x0)w#J&+4mGF&S(p)bs5Di z26E1NA+y325OLKR3Oyu`xW=oCRYN7<`T(pT>FU;f?3o=nKta|rvsGcl4v8%QlzEOM zf-ugrR0xSk&Ke(#sBVQ_S*8YwS^4s#8ij#MeDR8#S;;^MX|xWd6u^ueg@GVnmk3J9 zI1UAo5W-rsSsDg5S_>(KR7F`jSJyIoRJ}4C$axKdj}zlqwZDe?5%IeMGOIPP`cJjy z8A+-ju1fUk*Wgk32az2TFd(}M`d%9ttLU(&RjEoL2-rEO8#XoZS3il2An>b?fRR79 zyQ2B5))IryCSqn=-hKPcc9M*r`vvufpV;0WoE}e!Oz2z`MroREZw>vFv&A@$fKi~Z z+B)ZoLX*HC46L(=I2iPGnU`f51d$XJ2xXC(sK|3d(zcK?n9k-q+gkwEIX1?1yDdS& zF-jt>jqu%+1PXK@k${zGYP$geNf1`#ZH@?#IF3{pwevEI!q8d>6)`wQUd*#7Y&$!f zE~m!XLhDvrw!2}c-Cxd&GH2~FWJp@E)>M;k126v=+Oou#P?RFwhNeo zr-|Z~h4y$bW$i0I5rYBjx_DicyaQaUV)dfZtz~>vn=dt5jeHTf-CVC&$3PCJO4jpZWkF5B2h7O(-`bG&IKbo(2NKwTjj{Jg}NEA*8pf z+1e%tXZ7=96(!bz3m+nAz!VS7kU$3a(r14CBOm=FH=HyGqOK!D1h*0?E4vmEowJws zwkG4W)I|_R);Na-K@gF3&R81=5<(ek$LHr)FJC@7JrR<$#_8x>NlBzUEf^yS$tTAT zf*@#jx=O`sS{9(nGeSm9LdZ}RmOu6l-&qs|GPOD#AtNb?1Ut^X*euH&(Ej=_e;NRs zwZsI3);b?<6=H>zAhJM!M({MN1VOBKDdKfVZnZV5ZcWNlb>!-+EQIhjfsYe3-}Tjb zKmL8+^wU543qST(|I5Gi<3Ie@{@RaNU7zVsja!7791?%Qt;`kf+Q42QkV z{!l7+;Yc|LpwPXRd`wG+iuEg*U(S^7GFR?nyhC z&lf1{J9plG;@S-Y3IqtWf-G_cy%FL|Fa0(EeEYY3%SIjo4L7-2LW{XTr zX45cez47{+omOxE>h%wQ*;y^wzPdTGQ!7>+;^cyJ@;ivuW)u5+Qu*Kl}Cv_fP)drQf@I_YMHS zt?KMo_pipW>2!KiGg~ZYH*dZoNC=_w%t)c~(naA003e2zvE6C`p>wc%Y3tQjU)S17 zDUXlur)e4ml1S}e+pqEj90&T=VSLvR>zXaX>w6tAIIf8R1guM&DyGME&$tWD zZS$h|U(Qv$zm2?Y?9hkoq$V-2W<&JgaV1ArSIaDf;3lZLCSp<4X?=vwxyBIk32Lj? zeGN@*Vx$0o6?rNXAv(eA>hQ7WT>@Gg#W%n6sXj#H8uYq$Q>r`{LC$)-xiaT30098t zxvpv)2RykP`BPZOjGk1bqV;t($yLSUQwN8!F(bL|DdlH|U408^nO&BZt)yceuw?+S z);P;1&*OIc>~!4e#7apEoG#{390j2y03`%C;n+FgFpQX4>jDv^kR&A5i8?j0F%u9Y zF0(lcD0SKC_63UkJnMA&i=~-PiU$wQt@AFlFJWe9Eg^N=U99*8P&jl{p=?zyea%Vn z@B&64cFcs}vrPf13i~!|rqS|VZm&IpWbd~|aBg)e-5IOw+Hw$U~nyJw$$A`~D&hG8%skJ{}v5Z*nwfB(V#PN!uZzwzc9 z&ph)~uiud>Fr{YZ!-JzZY#rV|RDzi4!O7_do`2S&IXJri|Qtu(3ud(B*P6JAdlw=hHMT%bbuH-Ra3OBJ_H_(df(*86c8RH9a{U7o`&< z1Eq>0%kw!38OW+e2a#u!nUXiK-Jn7?!F+LOJ0e>$5imsy^dQmB5fo8@^JMPW3Q zQf+Lu&PJ!ZyF1I}64~89I55U|1i9UAO{PD#3km!q#u(B`T z5_78QkNvqIyOaNjkV7CiLtISzkM=#EoUFIG1R$Nw3>u-{=Lw#&urvAB;{A&xPM+NeTCBmxH4U@+)WEwH{| zI!~ujD?tQjos`n9)`tgkcsZX15_`S&$WDVnKhbF2tiH=0MvF> zoLH2Fv$3^?*_CDKoU`b(*5lDg8zV?Cz{bXqk>V(^#xb~*Q>mo2##(EPNs<_mv@UJc zJ)kly0~Kfk##&=cQ7{n*DUGp2!WiqbUHiQaK$wn42$&@8`Fut~Sj*aIA%xGe>~y+? z*4nr@5=QGNjM|-WKASD(izJS1RXu}<;24r5M#Ly-Imcn39$jz$LAHmfd=Whod_e?1 z?DwuECV2RKwTE!s(S0|{rFAgk(F*{8CS9enS{qZW@uh3~4A+D%*RLxgGFzf5N24B_ z5U7#Mh{)stWmJ;t#?nmyvnqUD$6kpDNYo`lo}}QyO;jZ9HH@+%)&USoppnKo!ho$q zbj|HF6ThCFgsU6jhN{NzX_{pFKR*1`pFk9Z$cj=#$yhIWG$0GW>*xM6jF7g zGS{t^bZZ7gH5t z;u0kyWKloOhqXfWbSwkArT}gI03`%htTYbS25;6I04!%!E{5@e7eNoLPp8dfGIq|5 z@7?>fufZ*2^XONkwEb>qX0EnCHbc|0C%Y;26j<8HU@KmGo{ z_}|{J#o^tzCX>-{FjQeno7o~??q1$0bs@uGckj}CzKG&DM99+R=J4|9{JfQPl?WuM zpZmXm;afiOaR4{m?969bY0NNg_qv_IV8d{E{pr1^t8A%JI6&?VhDp*YnMc#JI1E6z z@njNghNdo7IygAozjjTRy4`M*2n|zdwI|h(HQiE^SCO=0txF*!AWHzJ-E>ieQFL&4 zXFQolQ5l8FV9*c4@bLbFL3^{??H-*S-hTV;2R`&flC-AN!>jvOXVW{M|J=WW$8B*O zTkB?7g<16bgVU2!W9{Wjm(NGj$>fbzx8pyGqR1zNI%~tA{iQFx+KM~F;ieS9+2r`- z{$Ut~B^UrWIX!BYO}pLJrZ_x2V36PNpML9a{Mx@*Kl{DA_xAU%<#~zVh^XK1q|1C` zV^avh;D*D&d_D&NcIYe=Wf=sLfV3{H(<+b~g8=}|R~zqxC!u%ae@(3ttveL&p?TL>wemJ{H+9l^?huSkB;6SRBW$hR)4I{JAu-QT8V zV|2;PG6+PauxkIuXFJx<2mu`%c2yk>A_8!K&_6jj*F|2ckl8t_!!VLSGE^m6X5QY} zB!E26h~diK?tC`Ce|XS}6CxB!p|b$w)wOdbUCv2Rr!%kyF|1NS5fK<1GYJHOFph#S zat=s9Sr*PYBx1nA8blO;Kmw7CD*%|0Nr=kja)3k)&;!hX4!!;Rs7-)af$LneP4MGb zw(3&iHSn;`fIRaa2VU0!_5!f*TIP07_#>8y)B9{^8N3oxL(!svsnZ(wHy&+uz;V*}wMGdsG+{Wf=rje}Znevsf;o zK-_uj4JCw5m(M@_{OJ4y35J{7&N>o2=nuNR&fB-%S*FX~%X?q`@~g($xYc^<$*U@e zZhq-iqm9)7COEiv*ls7iejCUIfixxW?rtyAjD=ff^TDN!lv7=3sgwx9)3ej7QIHvJ zt?4E$c5ad8&6ChYNLUO5dhk%0Fau5V0(K(W$ zWy*4Av)zu{**rfwJ7c8TJneP*X_^WOmwDFfcRO((cOxm~D=&Zkn?Cswso>@-cbC~r zmnM>lR6L*a)xB#%*x7t!na?LjLJA_X+7Z##_EwU_wtT(eZdZ0!9Rp#O>0Q*10eYO=(BxXSL{NL=h*6F*J^60e zQ@uh+RUv1y|01Td`Y%>FdkqG_yh1dbb5%wRU%+|R-)vvP$qg|{eRS0oZ6%NENWhxV zhNkONMbZwgF0;YL@QWog1Na&-}vbB-OSS=Q|a^Z8N;jH1vnJF5{Fv}SUKmbX`?8*yIHBv3g2!> z8XE?_srjt8&-syh)-zW;*M}OM@U%IpvoSzF2Qp)Lc8buKxo{uNLHJL!9DB8*yty{!lLPmDG~is5jWrWrF^wow>ZTcr7- z-{08YxwKf!<2cr3>72WB=l0gt_GB`t3K#($J8%HjYRd>hN;29oI4BGf1xgYTTjQKF z+ITlS&kN@HaJVg`m`=wNsAJn`g>qrgOz-{AuukjW_1q?r=06b11 zrK}Nb7DAB%U?*H<#9QZ_190Gw z*KE)xzTuIGdQJrMD&>Cf+H;3@UITzXc=1=8i~Lhx`^hHV8(^i;{Wwy}`MelU=0On0 zN!uD$D!g_3R;S%lq0AO@YJrO4K#9@$X&9(H&&yJGd%exgZO>iltj-Hvy#Xe%k4_z_=(10Ie~slqj42F@l88q9-OM zPszCsx})#H4d9j!_nwez&d0?7uCl4K(g*Jw9HCC zCZ~OOUO;3I!=bcngIHeL9Zn{b*>XIPt?A+vB=*{(H;hYDC>01R!8F*JNf%2Jv|Q%f z+grxk!A2LX0f4{qSAQ(9?sUG4RP^NaCzX=(>A4WD-y8Vqh@IV?&wcLqi=r3|dT}cb zRT#V0e9d3#=1$MJv@qp-I(y@d zH{vLK@AK~yQp6bT?9{xo^Deg;cxC7MtFL|Oe0-)v_=lgr`-PW|Kk}zuxOMyO4}bV0@XDJ2@K^r&_vCqYbU1tO z3tyRK>4T#?JL9?52Z#%Qx-8YtJ^$?8gS$r$j#{l&Lh9w0zxdRR8*jby&hNeW;zvIG zVPIY^my^+G|MFAT^4Zb345-s>g?pFo-Z>ZyI?LtKEH!{{maK-u;r)|?IFWI*k!R-F z7e4egAN{Dc{PX|tXZ;y{zRcDAD}fMSzWM66eaE-7T7y>7l}Mw}8G`=6S9~NfW-*&B zmuZ#)5zglecEHY@ot*4n+wZhnhj$N(s^h!p_Xb5#F6a5x{i|=ieX~E@gvV{`cF&_? z_QKMA7c0DuWL}I!0X$lu2LKFANbfcj03aY!)v4N(t~l$gHBIt!Beb2pFh~W9RHQ2C zv*4Sv`t)pvt3n|F2Etk;x!MTlI;e*1={=bmIJ-Gjr5~JwrYNRycTWSqp5fH2`e1W`-imTJ69X&A`su(fK(ExiK6{DcQMnG54(;{O|$*!P(MUYY`Oy z5Rs|-qykq>m;ew-umi_{0#LHiS_&|>R7yIJvWd388Ives;dMw;Kei(6q7Jg~Fx`#xezVb9)d3!O7{_(b4_gt)0Pk zUr0JSKDu`0N|tANp0&HJC{_pe4tl-5F=ZG80DuArg$h+^ED<=zBm@Z(Qh;SoCheR> z5Grh6x^(&Y^n@9#(+oVGOiPnTNp$t{^>=Q+4d}X^=&d)7guo>3_Ij|nHN1WMFwbm% zBTibPEZxDh4Jgh{##j z>-7%q&Ii5iv-44r=Rp{D+wD^o#8E5b%xB>Go{~}2x_gm(tqw)C})I6sQrrR6rUAclNOj+~>eXR?Vnz+?sW2~`$*vZL+9fLE| z*<^2TPv*iD+H+tbB9YKq3$4OHot_<|d^~I3`eJ@q^ge`othut@sAIkm8CrwLR}jiW z=X%7-u1xxeE@pMsDrsnCK{bDHje69s^%@F*tL&I&oZ3Hr`24j==TU5EJZ)d~Qe`W0 zeR;Jj;gR}v7o(Y=>XI((Xl|&gTB;>;{c-D5T8YlS}N3BFE+uUOcb-F#Q zRW4ne{`xK%SSrEb*ch#~r_LcH5W<1;Ky#zoZcSr;iaq z|Le}=sejCDhtscdL;&1swYApPnSQ^YXSon!xm*e%e{DP|iUI&Wb$O>K%3rzv01>se zX&Ds_5t9E2(?@_v7#dgF+I$XO-^ z=WG~;h!DlmWHM1IB0_5%IJWG_Cl^B{E`ZrO%PgdnLMUeFc0wVdTDQOLk;KC`OeO6Q7p?c?e=681=C43nM?qv)s6tsIc&vkB3G7~kU^R)oU_1; zD17KeN{J|(wdpbiH@Akn-QH|^PDJT4^XX<%Dgeh|by@1NjG}g@+hgAn7Z?B*i-j*! z@(vmxM^W^_&%8g&a%LAtv2!L()3PjI|K@kf!bDNX)&aw0GOpOkk%AxufZ1%Wf*>fP zqAUTBh@vP&#H1CSot|6ANSJ0zt+lKIa%+26l`rvw@>BH&*0Z>ZS?GD(tIljn!2(|TH%V@?% zl+<>AbGaY;PrmDSe(TeJvWWs_)<(0jLLeeqt5+V24+Z$!yqHzAMguGWOm)#-7862k z_4*Fj>q4%9QG^i2n3a-SQ90^VgcAeoj&b9%u0A zsdX#>@;oIGODT*o<#OpF8wP4LIwwM@g2>n?G_7t20a!^SDFm@|AbjYfg1U*QEb|}; z(2G=8sp@Km01!z@#f-pcOhMT8xUFM0S|@R$i|X(^&#|s7GsYTYNsyGy!}U?o3oEDA zR`qPNKYydbR|faGiopT6mwJreQzyCY`*o?=mBx$u;opz4_ zq{Kp}KkPA;mZfy@Nr)avRD;*VaOP-!hgqFkMkRW7+AQUL5)9t?a;_s2L1R@Ng zYx~!CclZ07uGIUZ(fE76@6QV^_zQs7$;_|rZ6%=61^ zYBW6i-17$q_g{YbCIIvYgZIAoy+xjPoCAQ#Xw>UPSuqh92O$#Kciwv2TC=;eyScgb z>X*L^Re&FMcXp9bDIo-n#-qKn#_l6w+Gj*m(nJHlG>oEWlfDy-o;P z|Iu9TjWhY^C##GC_7?N1`DGQztKzh4*0_&wuI1}BK#T_t2#GHgr8aMeh{7ZYB6i>$ zR+T7^i%BxGH3pd1vv}Axck0EXh+Az!f;s|ODatBehox{tR3}}q^M)iaAyu^lLX^5> zjh@-ZIbLt9Y^|-Py~?1eZp3+IOh6=jdq^NbHO9@JLzpc9Icu>>1tD&POkKWI&%d8u z!R#E{Je_6f3;~4<;v^PAN)>V4XVwd|ngEAurURj5!i>P|EL(QEG|R=vII}t2%JWPG zL1_wC7Fz2(PlZ%TOA=rZM(mtaQYo1&3t%gi(1mkW10o4jGGKPb7~!29Uv7iIo>kX( zEkq21Hn1>88>^L4#00=ana6P?Nm%C)8W`Po$8ck}^s*H#PymIA@(fZ6Ybb z*+rJdP7zWPwgJpCorCMgK{OeUUwQ4zyyueXv` znr4&9_w6ir-QoQ==&2GP&<>?}yli;15?L5!NlSxtNOFNg^aXXA76^7c39UmhKW{^S& zA%RKqV$?*k$nf~kT)TF?({X3V z%h@Emwts_!5aGNXZ5P6-oC?tj^UYSo{3w5R8nAgwwRC3PN$PmUKCoF zWv;Ca!cYOAB-QBzX_~fM?fG;eNKB{G8jGoZ=6Rl_OGIdQdXHO&7cAa~vcVpUq&GXg zFlqKz@5{q@%R_d{)i2$6q#99Pt$>tBHyg{j}YCTYa~ZuEsWuYCJ8Mi5O# zM5PO=v=OcWjz;#vMe*S8w#FH}&E`da<&c2aY8P%0u}-o<5(2=Ne6HwYpvpgjdM15s zkpGw)P3onYR}Bc>R5MzaLI^1pkpKoHA3Rv+`K=I~S{Qot3iF~s5K<{b;b{lHrepwq zF@!KsTI(>9ibPqK?A&ZN4WsCzB?{T{WEt#i6OJGRV3%i0B++X3s{Hq6R=Eb?kO3(O zVg~RG=}2r$;fq$J6#fVx^2s<}<6Bq9oBcE+SHVwQpV4yjS(;d90a;2Zm0Zjg zt#+#@03Jc%z6(HXb=ulm>ue~6(^d)j?N_cY<_ivjcH9C4Wz3Z;m(S17qbOP~(?F{G zyW3xZz+7H^Vw;dNPc$Li=Jux7`?v4j?shsz6o$$d3=tA34DH#MxYiBI` zmIcI2!t>BG5P}0DjG{mV!Z9KXaF&4yl(Qm9#NB)Mt>rijq&(6l<@jMK}ZZ9^*4&uSd>1n&)jl))UNFIq3LOScDB5iV| zq!74R%!@J?Ae<|MAV37;Toi@bGPBkx83CgZ6bO+ni#Se*C{5FJxv1Yq+!$`o7t=!L z0MPCAjWNEDXt%dPB(}eJ`LiGVY?c?mjL2aWXsx$*E(sa1bwMDbcrckv7=%)xwXW19 z5lkl|ZM1V15D=-~?`f@_af`*mFDF6L7~?t1j*pLknAsWgAGxzqu&8s?X>Fy7!iO_V1S5FmO@HT+S2rOVy+Eq<`PjU zC4^wl-*mzKwp!~y^NrsnRb4|-rI}QC2l{rP#;71zZ{Fm!jt}oSXO%WesTD9^=_F4x zX05eFQ9zxgxjv=-q;J0Vhc}*nKlnB@40U`%5TTS(f|;iCM8!`(@l30`6;|2thyczR zBnI|;!)toW`SuumW&i1#H5m`?z5xK%8N$`s8$^s5ot1<(EoV|Bf~?M#!>wHbQYpMY zpS0R>uRCCE(n2G$3Q#F%B|Ubyoaagfh}3GwMP52*k)5PaD9IoR00{DYo-T?oNTPNh zi5M8jmy@DL?`5D+NXJYhkiar95_pCMz~;#kk#F>Zhz^*Y<_7KuAOThUVhw!pLGC8u z9|*}^SZr&pQJ`AMUS(H4JOPlX1FLmcl-l5^ruV{|lP(q>Z3qLErAv@X2obl{GEIxz zUf$aVt0V|*`S|#_m9(d$Nvk8bHuvY#)Mn%yFu7$`F6O7d@$0_^0R4^a0P*1Pu+>fw z4FT%1_=z9p8^iu|aej6> z9gU{%eg3(#+1OSue^#1X^Km?I$_1k?VR9O~Ru3kMGo%iGZw4DC! zpZWU$@R$F>_uYN%&c^022*S^O?)R?jU%ql}H!r3;+Z&|zzw5g{5wzm)&f#cc;|PB3 zSN>TwBVYK!`uzMC-}~qAc2(~qP*|}4=;!_!JhDA`<3_7Beb0NYL{WTtR=oB4TZaet z0pMd_|FO|@d_Ft7`gG^`bawMgx1N0Fxp{uv>#Nx$K+6Bg|5;TG{pP>=?GJqL1EbNT zkss&N*<^e&9?h8T%~x*vo&CY);o(8Q-*--1XEq1D!PaKC-_<$JX0vy0-E{1tSQcgW z)|;;_7IOebA|dGP{DD#u0ohQm-BwZLtV1P&fV3{cF!=L7@E4^B{*Qm~cL893|N7m# zw}0su|LJ#s?+;}8g28k;+vnqXAVEpq-t9g(ScC|HBq5{_Dv)wAAB#Xa?X1ZKiZDzJ zV`-*9C@|XC-Ws1BPtQ*uox1f6AF@Z+Ol_!xkN!Yd?;p2LM&RRp^^tWWwkl<#NpGos zR@V4qtfneIn}v|1O9lW@cd3K5^zs_HW^AZdDoeex#~BC!99yNrx_%aF(Oci3v(7o8 zWR+OKToa%GA|^!6S#2y4AqhnGW#LtoNyMsZV^$Ch{7-wb&8E9?MY;y@)iMnIr~K;9V;M> z39xAzP_KkK)>=1PsR(^*56-W&YKFNERC_bT!)1^5#A9^U=(0eRf*=Y5W;RAE6*5?6 zw$_DVAcZW8JP@+bSrkZiMkxqGDWp(Rq*)e(2{J^n%5x!QFdS|nf+S>zK)zX-8IMQP zqoY_d0rYx3WQ)!?$Ap+9$=TUx(Cr)_9c^uGb=$o(U0%AhdwP1(YPFWjg*Ks3Dv6WL ztsTddv^wYG5g?akaeREdv$>n6g#)QnTx9zG>CvSRTm^)Fe|T_mU!u9PbNzEK{r=_4 zyBoc3o-T``)$Oz|?_PTI?Kd63bUq(!YzrAENv(Ekcds|-^#O^LL?Xs15&77-PmE$H z9mGXpgIHLrgII)-Y{k)NG+!(;DNV1}Jw2Zo>jcWp;Wh&@+u^W3+)NCdjmKj~$jaHy z_D-3*v*mI&Uv_%5Os9L7uPl&FwA!6`JYGnN%f$>4ka&A%3xQ_ysek*45C~3BPqub8lO#DjydS8p+lE4yQbq_+ zl%)!Y88!wRNB18XV+e#bjsdbPyL0=key6vw(Ju=fMnRGUOIj8MhqV|Cf>3MY%M+9g zntE_&*>MRD9Xe0Ax|q!$6_O8a>-O-wZM9Ll5?L#+n5#UHhmL>jS(>5X;#d6NuaCcl zt^1~zevKVhEl=Hr?4IU7u8uyg53+tJI{={H`u}Nr(^y%u)p%za?M6Hco9kfzlgx_Rc zHA$KNm8-jMS8MIKLTg3Fd@hwzRsi4wD5Jj~ISe_G;2f(`F=M#k8d~kkdJ$Jzan76i za6&+6g#!=~fipn_K&&XzFbsieMvqd;^BiduHZ8H5HK*o+!n)|ZS)0$`WgBl%gNwt{ zSj%jgtO^P8$B8h2@K;x2!Y6aKR7x*@;pyzJ)g}k?qBr%fOF>gSe9kJELMznqhK{# zX@$M88&^wim0hIK74GitdBQn7J_>@Nl9f{O@bF0(b&@1z47=Sv07)eek5;=odyJtU zM2s_!am&%9pn|~Jt-IoAZdk*%MP3_?pmcj=6Cn7|~IcGJIo`{GuhOD7E+p<;0009}}DC+Sf zB7#r-tsi>r}#!Mp; z1OTn{StESLHcXWjC&mWAvBzwvv~2{j-WLJDbr~Uk;eYtT;tZgu+r@Z*2?-^1g({c-rtyKmjRdGp5go36w1IKO=L0(W^Sm%sB{|LP}x>hoXu z;@9Bgwi`E|1!MfEX&}ySO3WuzVJ)`-GBf0zWL49kzigQsT3bRJnQu~N z?52$dKvQF&wY7)F5hEar)e|seiZNuIHS`!{TmS$yxh%%G?S_twpE+|w2(^Yc0<%>p zEj?%bNE&9e2CNm_ks&|J?qN&_P+W)_4iYw@!WicONQRIp0>B2H(OMZYWNNHmX~h@^ zLxupsP*a|7*BN67rJkQ2F~R_#O5=nKa?$CI>hS}#A_%p!+1`qVkAY}Flh!INi!6)7 zP8VEmZ-GUyYIYJ4k-bXoxq(&%12a86mRbqUmCAeF5fJWQ+>hghRMHVFjaM0@TRZ2H zWeR}AnGr@42>@A2BtYi49IHxl;SuVph>a{e-98hJBITekWCy%H8}0}o;#?S`5xE7+ z2(XgUbvS3dz6%EGmCx92>b92!I*x0bsJ1<-+xU#vWEQB!8*Gxr64PtLOSV#hHLAx5 zZPFYYTg?z`FV`BDfd>A8_2>g2mU+UAWfrh|KfcRlEv1u9TG` zl@`hmoaJIwmC_f+2r>qWqVRklh=rZ7+wXJ6SMv$u-0?!k#nm!nEZ^H6Cr6KMrLCi> z%5xiU%$JMfqXXY}i@oi^s7C-wDgg8Po8P=}{=6n56=X%Klw=J0{XU_Z%uj~H!M%I; z=CkbjwObGF-+$)z?aAb%s!aBLcodlM($&iye-FTTKKEUZ0h5(Hot#Kn0a97z#%RU_7y=-Nb7Wm9wKBOW)#>Ee z^#dW?Bq@zn*RJe#`_cXT548l24uDolo;!a*D$QIaLUr=M+`M_KC@U{yPN)y=E}wno zsxHb$4?Zjl{r2>|sw_#9ZOVIebbK^9-P<1LX+kt+Zgug>-uCu>p5|JqZ@&6<-*br! zN1DzTd%HW6)5R)V4F=J0J4ll0Y?3Oa0jv<414O-^KRrEhT=&M+TSAC9Sq{3LGRqCJ zVHlZ8bLJ~qJpaOXJ$!V3F%7Db)#NCA|+>&<;R-tf6camq_=QzYt`1jwOB#x zrDH?uXow6?Gi%_Z2YTvdur#h77AqaawA9{h+!o5|FkfV9-bq*fP?_d#Cy*8DrK7gBp>rU@amr0%P?Qn`7HC zVL;${j#kQ+2%QCR>_YbRpfxYpOE9FVC<`GpXIwaLv)frbz41B`m;qz75!@-N(s5h_ zzuRF5ppEi*IGxRX*X7JLoN28YGVU;As9p@3SV<{KL=2g(X{`hRS}PzU9G9B)adR>N z*>R)hqAcdpDEb4~enXsdA;d&xqC`&+cU2$}D+>83Ml!Sb^Gb*xV5idDL=5 z#u!Mc$tbO4H|n^q>$~8NEqw_rL4Z1`WuTpJDK1U`$Y+G@wGA};z zeE&^uA0y=p^;57>iPQwNZ4A8enHs0Bu@bCRwd`%Nlz0mYoLvCc5i%m$@x^*;Gq)Ci z*A@bAGzD6R*ap&Qj4@hU=)qpVQ`fSI-N1(0?o;n>UX!iz6`9uZ&r`WM@8vCz!*+n@OG{Wt6oIfNr*pLPBBIL|?m!(GRzvEz@F7Ta&O zFimYLTTmOoQYdYOn^lcjX8{nkGROoXL!|L&%k_Pus4U7nTWCYZRP*_ibLI(GD~*Uo zSMh2Vb$9I*Ef$N>Xw12gT6?aG03I@_ly!;8w(Ve~3aM1(xgLU*ct9W|Q_E8d;V=dS z8k;CZYt8ujPLTmCrpt&4Apn@YoL~OUKi&k+Htzv!MwvusG>o7jjy7S?=8dO~wV=Ia z)W&>I`z`H$rYx&0OS;{zA9|cI-*=NZW{f+IqmB$AU|@*GqpkUT;ks^` zF5)QYBKM=_r^2NKGW$q$0sWU7!G%ulh;DLnZ@>BG{-q25^)LO>|NhIr{NMby|3!Ydx^N*Yt&&wzX8{t!sl>|bi zRn!f8!%>o?!xXC%<5ym5#Y??U`P9@*3%Q!HLaomz%I<|1(A$FWFizm#*i^a zS$?cG+I|y)DosgR?`!tiAn^Up?=4SC_V}%GeRN@D2eW6ZV{h z5Ox5SQqA>(Ax%K28G>sJN9F`UH}JazV8|RizAKfaBFT!}XzjTUqSzkoEtZq{{PEWI z73;@qrHecd{6Gkob8?I@#-L!DBtvA#l&TPjGfcCL`vKOs3;~c#tM zXGH_Yz~%w!Ad!q>9MU|k%7Rez20bgJoF=X(2b&gStakj`^NWt-@m(Brqk)1ac6gT2ayD?=e8j#ih@jqoX;lH zZnqb8{7%>zjfPoP`koth#rX?6N+AIpJ~@z5Zf%VRgQ4rX@4x^4u+!h#*;yuw@t7YR z9Ti%g&gWs+aU7oKi7Nyk<4inw^yD)yJ$rgOjXHhD6L}_|JUm8RY;O;fBF%~{2;AxM z5;V+swu;jvT_M9T2$8WX`}+W36dBC`xK$oVlFakC5=C<-RSbs!xgYHE8@vXytj9)-`$fqedQb9%<|L= zeWrECcNk(^Rd&L7zH{m7<-2$8+`M%w2%~P#Vaz=_(Cxjb001BWNkl2*IzYSCrQQxtfot3?uGLgl`7LL6^viMb@Bao9@<_a28_|D4Rw1F8TRDKksmk! z{K4I{+l_*-^Z3b(|Qs&D(G7{f(VG2 zTEGzz5O|{mQ%6Av^h00!lZ{pz9|IB@ty!HzT@Q;8f@=FhoKu@dtCPmIB_EKknR=GG zZJB)=u>b)P6=`C~FhGxrQmO)7#}7E$?3}U*B-K~A0qYPLR8^^ns;Y2ZUkKJfL5QvD zu#M=D0E`f>(Gt-l@lqS}iGpce0l?cKjz(jKP)%aanI@ekaTs=h9Ib7?HX}7hM(8kD0M^TjLIp@sv93^FvXCWFPM3xquIkKdxtjLg*k|8lBT+c&fXd5gLXsv`` zc~&5+&;VnE49O5jRF$%~Kh3k%a^W~)(C>zwfB=j(0OsMN`@`YT0BHkNUK*1jLJ)+6 zrYMTA6P}))E|>A{&fat~Ik&fWGl>~c6mvp7TSQ8Rj=ERlSR}Gh$sv_ zgQWqzOcQC;{{Ft}gs+mj$Du!P!GKmOO%i1^ks;ERtjHKd>roIx&bY6&S;h0P6QpS} z9QMmxX;Oyt_Ez5yyy;|SGyoYuW{hT>b)qf`!(AOuX?J&5N+mp|RFSOm^LyJys_FDZ zN%Ju2DkbY0Z3Ly&!O=m#7XcaqgF^lM@wA^ifAHKDqxJm5koqi9BEBn;8$g(v_yu;NE_w3A!8tf*cuPxGzNmQ$^no8b9_-& zg&#PwGD0|=(AQe0N!G}r{#)4^DPPXu3~vRH)@4Lby|w-fwt#YD(6Mc6z>OgTb&~Tb z9LMfu>CkJa+d6f%EkA>6SPsiajkSef+In5iIWlHnY>(VB^Eb&gn_o?~5z$#3r|sj@ zys|D|Z0)p>?s)j3*E^P3 zuzen!&>#aeKy}N;X3Xs^6AbF^fa@`BPs1*^XaGP67m>)Q$>iAgLoQelNB~zU%8L{@ z0g1icbNB8hVEES7`F=lMt>P#Mk0+0%ET4V$g}jtR27w#Wd*}ADG>hXZjJin{S5>*U zw|8=KvRKSL*X3N;ECCsn#w+SXj&Q*kGQ=I1aoc^CGsaz)0~%u#B6A%FNVhY=7-Qi` zYRITAS!08(;g& z-}uen0f3+UsUPVLy5%GnJk(V_91iER<#4nmDU(Wm`HL@;0m8}^(bXH*Zrr@y@9sRg z^Ztu3T_ouYyO)3aU;NhQQ+aZ5EL`uI+t+9B9}(%cA9)B6lZ=E|le)7}LJ?CBgd;P>BrejA9=)H!&v8V72mrN_g7GxTw5raX-#a*bLPXY53C<9qDl23h(Bx(1xvmhlf(aNGj2UDM85Vh7 zr?aWa>o)(O4R5TQk9DfR)G}R$GuG&YMh)o54^oUw)zv?g0w zf4xaox3;~>RWt!#eZ=~F0Sq=LZW&tufMASKgkW?nHfglZ^2`{zd*{R9aLkyvaQ?jG zdH}STO-_zavouGJLO5BTcfyVkJWJE@Xrzov;!<=KfJu|Z&h`MnL|w1fzi5B}IAG0S zRhsgwuyCHKs=d8EsbnYgd)=B2T{nto182L+oL;o z?)akPaK=!VRYjzvEP#8jeB)cfVR5{YrL(uUEjR>0SQM*Hk9>E_Wg`NLm#f+7LKa3V zIU0}hWWF=pF^ei*t&@KU%#dMRIF9T3BOnmmH->C00LO7OGFeq5p-_boEKjm-FD!~8 zilVB@w6PjQ#()MUwsywjtx=Zbckevu^+qR?)6$r#DseWKMuL&r7*#P1l0YLcL&QNW z7mH39OsB^hWDxRB6vRoqyFI>l_bAItEu~ZifyaQ#LTXK%a{}-?-q!B;_~;Y}2ZPaU zwm?MJ?F5W@GRBy;%!kM*W4NInz-OZF8)@>ndGXbr3VXw*l^-^SrvAT4`>hR>mBEEZXq<8D zjjk{jzsW^}iUEeZ<7V}d?_)Jn(veHVUBLG<^>}GkA7b}QHoG}72+DKU; zBIklJLf6$w8i2gWeBZZYj6ldhDQS%6T;TeKAvEGWp6A=dbQ7}KeEB-MSu4u7{~!WD z)af+i|1_j-%{TzoB{zyA!9USsFWn5kg+sLeLwI$$927^)2S*c9O3$GFzgwF1dz_>TI(o^!muNR z_@kpk&iH6B&dY4jA1szjX>^=ruImX$$f^`|*)gBa=EG6fW5~H9W!fL~WTlO^eJ#B# z&&w)z1Y0d*-`CSZ|ITWmjrM(?G2ZD!zUOKUL`*3Sz>Fb=R2Eg}J4zZMgzI{7oCJY4 zoh*$ZtqA}oley;wfcX3ix3VlLigLLqhNE63v%nuOX9b|DWFE&wA9tAWE4cFEJyXh| z<8G5No+A*kP`RyuBck2C?bG9v(RdgJksolu#VVft)VCd@b&^#7{NgA{R%KbjDiIDt z6j9UzR8neH>7CtCmX>8z02n|r2Fg-$!G#dB>Eh*=zWK}-Z_28u3K52#l`ND|2p}t| zl%CHg@GJm;F(hS`=jraw-eNhIQaP?$mRS@;QdMLOXToUh3fFZw83;Uov0Pe5Y&hyk zRRMZo=&fW@RfXg7swiDwbc84?z4|vOLH+-+HE;~IKR0l0B4gT^bgfgk`E)eVX>ANQ z!516BGR8j+@+TtF+H8K^=GK0Ttqg4H1KS6B{TXUDt!*DT(dyLL?13>Kqr20#j&1-H zLmQ_@L;%{dA{*6}+Fh^>p#Y#Bn%31OYFU&GB2G}RM)kPaWzPU1;pe{Z#{fVn_3F!i z3;;l^;_9(hPYU*~OcN45aAS0BUd-5>w-#oav5KD_tX3;oq9 znVe3ePWSY5(h0kjGDPObf8sypO07h@yV2wN)yR>^3}im3j=Wbh4HnEH1EIyn}0HD&UNc5|(z5Qji*r~uP-ni$q*Z#p*>1Nr+-SeYYp6O1bP5X2-l#8XApH` zKrr6+^Ey5{?ncpMz8DUBM@NUUR9CKC&+=qzYgFk<%F1=%_68YLU8*i;P@XXd@ZNy}g}-liA69 z<~dAorz(n3uU}?azZ+#)QC6iUdhqBGXFTfqHX(8{Ik@}nlfig=bh?#Dtk`(26^5DU}^A~mpTYe|%y!H0m`xmY)=S2{NyN z$!vn06X3ZE`;HhK92|N>Xzo zOlL^6LHlW#<3wb`6noRDNo*6X^<3~Nn_FWsn=_F%XV=EZumN_~%r0s^zsBh{=RUUT z0%vA9fw6^bzVGKnqP3P<5y0g1)DJ?2EC>SM_oY;h!?PqQ^33%-DPlS$t zMV&0m4FUHJqAAOaF+ip~-vM+15P;QE%}7!y1Z_h?qjkUE*IK!*6Zk%3tSHOK@!B%TCx~`MT3AfswXt z0*Ev(qNuZ4#J(4nr3`#8Nn;{oNRgp?_a1dR-eR#-l5>Hs<2a5dW$p#!h%U!SF5UK!m|yl%}MOj(k6ki%Ke^jUx~oK?F)_GPRbd7C=_WRG}>^+ZRJjLr42#@2qrTRC@U4mv2DXf-oIF1ZK@@ zu^GbFKe4VOK(uwy_`ARTTR-y)zfcra5Cq4E$MfaM3oqVAW`6x2|2hC9@v^FVM0&Yg zXwzW;vQlZ1rD;}{6%cb>rmDJUcGTO>vLx_E0Q%tZ!^@YhHQ#Lzv6AI@w0pFe42Q#h zuU8h?csvFp??1SI@zNe+=y{>l1`m8UFVaq@+wDdzbxT!>v@wci$=vrvniXl8@18%` z8w|1!zMaHL6h-6FXgu1wckk|l2iT2;_#~GAVVQ%OqR)fxBA9Wy!QA#yA*13p^Th<2 z8VQkS6?X`7<(K~OybK~X>L(uQ{<3%R3Vm6!gx;@_sW|TGXF95*y z&er{VM;(9n@q;O2%5@#B%zV1i2A8Yl{?&b>^B{67N!?yYo80bo|K9!fyPiBba2z*Y z7K?cngzoiQmyObcL9GRI} zY0|FH^dxFLY@&vkL(n#&UeofCH4W)oT@~wmH{Rri-kGTtY77}>V}ELBb+#O`U8Gc9 z==zafYCuF_G+5(;h=61o>JAf{Ig%BrhP$PSoje2b5R|E`LARU^GzRNtCG`~v!5hTB zCiVjXuy%=TW%b(}xM2XKR3WPi=Wo8hdZ;T2!U=s>2r-{a;Q)Y{&E{2+8>3y<+dFqP z%Q9^g7*tYAS$UqDq^aY&Ky0yGg<+tz&XTl07;^4`Q@W{e5pF#x4X#JXB-9j9T zX2uWPFmMl#jy=E29d9z3_o8l=XJp9rI*#y%{oc{(?7g?X^};7#GK__)T+Ekf=8P~& z7FrubQcBI|^PSy2RTO!iD5b7my_&=;JE0E_9uKxcAso+(dcCOI>2N^Ckulub+LDzP z!i`sDo@7Nl5!=~0?>g-9 z<3|@RdYvdbILutvPqKuVjye$`T)HwoJ~<`|A&|(y;qG{}U6$pQ%hy-&Vl*DaaXgtW zj6NlUr$>|Pj_Bvrk*ZFCR4x-FV#JVH8c|*>T;E&Hve#aH1(72o&K<#hN7NY;*KzFn z>ji=fmc_Z_vcaHNRjSBjkxKx{z$I>^Dt2~$XK#NxUfw-AI*L~*FgSejL>tV@ z^vdlkMweXDmN$x`0731Z8=oAXRJp38)&{avrNyZb3s3Yuyz|)eor{;oMnlxwp3Rrp zBFoZ(kXfs7{=)gY_ultB$M?c4S@rt<&dy~iOXfHZ`wrbpKjyEeUEz=V{jE>i_<>J( zDeS3T&i>g(-)At)r%r^7t*)cmfn-=C5$glk-x1noaM(VgYkG>YYQXL5^#LqwVM*%- z89OU6NwopkaLhj%iCBHj=1tqKZH??;-3O#S00)4kCpEm%6&4&vgwG|VEOWyk)-oqD z+5iaO?=(vwH9%D}Xg11hg$rqIr>xXX7hQ>dyeDUWHA55)Ul+sZY zEmuhp1X-4`4hkX4vhaLYaDgZVXJwH-xOZpw+>SBq_~hZBzgy&GlE&xHUq(Pfni+6} zn9t{6v=Cfto#%NF_{Q+rY}W7h4VgU8Tql^#mQtELD@!f_NeD)ykYT^yolNJeEEOC* z&r?!%{6JM@==)^MU!*w!%@@Z+;QLM(2Cjz$@+&Jk!K7!(9(6iUS}Amh3h)Q zQ9sKH*Eg=m%WT0=q-hp)J3+Uj>zXP;1bensnfbo&IC?nf#_`f|d`ECU@Tb!$=ge_~ z{ve#q=6PBcMIktM91(RoRavc;tFkP+M$Be=T)0|IWm$5@gD_O8TFmF1^EjCmMO7ni zj0HhBpD%nrf2`@?O8!>voTir&U?{Uf?+Vxi8%`M2uq;bzgqzRRGXhS5=v% zd^GC0o+!%13mnG6G$~!z<$?Va_a z5fOmfu56?UYJKCnR}fK4fH%!a5i(JW9h6GTQU)#M?0bE>Vttu-cVKb|qx zR!dnDyKObi7!$&!b*+=KaI)Y+f=AdB001BWNkl*-~#}-6b(C_(ayOm0GctgN|JaLpFe*-S;boGEXzFK z_5Hzx^OuPTOk5R}ZIbE*9i@!J*?hi0&fLIv10Mt!sTqM_P{|63R%y}=d@fu-%*z5v zhoKJusw%?JH&og)Ze>|*mt5FD&=^Bx91X%+IKH_~0JHARBnTvfwo(ZIp6V5Em!%Do zEpCh%X~q}=vqfr}*_hHKt5u$-gFznvI=#M9np6bK~bd);1^72R%>B(d*%+gqbFPRiyiIPxg$+`j$7%U}ER z&wTDPv(=M&5*dHA&Baksa|MN#HJU#4~#IR z5ire@>({P*c=s*>|-&tq_?|=Bth4YtBPEJmzCpVtm za$L4trrl^T+TQt8CsJAV%2!|BHTu6AZ+~Tf|8IZoWu~u{?V5B`(OAKi^bfybs04WbODqxN@?vloC{`3^YGqbzduwwcN{EB1}FgF zKlz#e2urwm`h^atI*55MvCmx<`wm5YDyCtq3o8vL7VPZMDP5Lr`;w05N}%3+$+ zCAAW(ZH}>}Dxb;UZlIw6b=L7CQABH|)-*u?M6gK8X7bbiWZ2fY0z=kx;V?v?v|${; zpx|5^A|hJ=1!x_5`#Hm#YC@`2#sCq4aUuY%8RMKW(~$9~?&F38(4<3}OC_}Dsj05O zY4|z_Xb`~|g^eXahMbrLFn|XnPm)TCz-P8dr`9h3M1z2ukkx`aO(nh^lV(wZx?`M8 zk=L+3Sb+m=7hBt3qs-*V@u~0k0f3k`Mt8z)QOHi{3@*DhG$~v!3c^U~lA{oU zm!(4V!Z4JjVw`)PTgfU6f-Fs2U?fRX*YRA3GvoxyvihyOSBrVsu~15~roOikDI)|d zt4gc7NvhJimA?r>x4z5m#A%0oJxd!d%y-VuG^yt^$(Z%5vws>w&dzWh(GXCP=XqWX z2Lm8*UC)~OZq%z}>A9XZdKE9nTf_Ne;fJ2!Tx+>p&U!t+lBMJNy>4`RGVvTQ2tuV4 z0{Fgf3~|m~FFlM4P zD&itIJ~|kW&P5U1-rgo{2*`CiM9TJ&6v81gc~&syY;BDJfH7FDk|aqUKYIA$r#`cH z{@mjyPkO!HV!jv*hF7j$s!Hv8&SWxCN*_L%Fb>85V~8A-G~9BB!T4U-i$+HAG)p}{ zV92wy^gL7=3AoKJx~}7Up3*d%FHTQSvP@>F>Zx+tyLLz z_;56wOeb+X_q<^5-1+fnY>b+n%w3~ya<>Cul=DazgoMmY zL8lwd7e}jURhBEyaV+<6%toVa1Y;Y}6A>VdN8?A2p7eXe zvQVSZ_JarC-rv7+dUB$r$t%6LySKBu#n2o)ehfel9^4xahprQLqM#~bBqXC2%URSD z*REfA_uadW6J+`P+aJWcyXQJVc10SF@Zo-;$#!8<}D?arMH4wwcp2ky94gj=b0vi}T zHMEvyi9oPziKu?B*%_K_IW!9jHc1mhmJ3L&*Ii#=<3dxD58HI+&t7%2HCcttOI{-b zSeH3clL4?rNLE6g011sGC=I4y6fk29an{ymesr|#$<#_}1TDD$NI|#0sHXokX#+S5 zULgP(U1_;o6hedyg(ixkj@G6q6C#aBX_j)vY>{uT*I&gcK^>21LuFBb&0;c9Rh11l zwAPN}IKm+ymprh!ipE<;M6DEZ#+a}*p&R$OX1Um&HTF!6At_bcEYA=%YR&DXw3MgD zPgrAdaOO7rYd30dll`wb9s=M;dbUH0a2c}vN`_ok%5^=?xZ~uUbJz0_5RnPN2#5*h zFwPK_RIcmTuDh)1tfjRE2Ru-}ob@P0+m@hczf$zuhGW0z}&{|cM zj-p7GB||97ve)YYkd(6DivY-R?CQv>s@fWlv@)LWWNGSo9wGz4JXb_0E2)vl0B0N+ z6OLFe7JcmHdEV{y#^dpPzR2^U^a94+*=#Y*lu|0{hFe=>qp2!Yl4fNomDb3r8uosj{$cr*#%go~Ke*90ifdi;Qzo zRe9idi#$h!JkQtJI7ZqSV=BhP)_9bpiP4m2lKwy1-ZWUYEGrLNYY%72lk?3xzWLSA zRdiJ~JP>gZIZvKE(;k+8?2~!(zN$h*2=BP@-o1J9%zLlB_P4(EElbR~aMl9Y z)oLk(-)J;F>77kSTyQB_USy0x5c&YtkcnF{W87M$brnTHSr%4#R#(=VFpR@60MvrvY_?Fn`1HB+itvs;t>*m zyaAF3K)ZDUt8;6SArNqIdl}fW(Ts7su6b177l5&3wE^Tn%&PJWfAlW_;OoBWd+Jec z&!u@k@QvU3+SrLU-;jC{HK04oleW5>~=e&@yYEs^Xu35t3tnd>-fs0Yt1&jb?;WI-CQJ# zyj&rJcC(u%X}jGv%6LMSLj3dJ`E3CB$N$$S5FuTrX_CD6+4onfA{MN`2Eeeaow_ zyoTWQcLsTp2*G_X{KA*MxVOKj$);I88jcK^%U7;WCd*0{0;E#dYzCXMSv$Qxa%{Kz zqtW=ur>?g;&B=HgH=6TVaAH1AwIh0h_JJl8GDb_rCYN?f$`ZG<*7) zYaZty#1}vJN>%2b=RN=23ukA;;qX!1>VE96eaEN%)hF)Uz6$`?Z(P26=K%ox%isIV zH+}5Gx9>c9`q?Mo^DhFxbI(1;vcjTqSPTH9tF$PxEK6@Z`4obj&y(k0c=|Vf?f2pJ zJMb5_y0%5VgeQ7DUx{r2C^d|JaYVQQ0*JsFIyUcPXK+XYUEB#bmY^O^PjNx1WKv`s-=K)v%i^w@+;N;i| z89H~$sq~-=6tgXvu8Xh>5)iU=DJlR)+w9Q|^K1QW+&0&B7XT#2U>%~_Ixrwv8wNob z1nz5jSukQ{QCeifGiZ*=p?Lj>E|X|~!?p6E-L4jNH& zm8P5_=hz5>lha{I;_JTQBidAgi70FhN8>o|1!2Q#2!hxeCZ&uUSd>W+gsLiz4i7Cc zDZRbj!R^~`GR=4UmyaJEhko2@wURVR^URmp3uH3NcLxK|G#pKR={H-g*=#~Y-A?C& z?|c6Eo33jiX|(BNLN`iZs{^_gzZI=j2A__6BvkHSz_)zeQrIi1Z{WmT5-Fg!gy1=K)>qx6EH-``WJEXw@p zC!f+<87hJ>Iz1T!@!h>WOEek{SJ?`gDN5@FQL;$ez4B|He_v4)UtWH`Q^EVAs3e^t z%2lDrFr!rIMjmqR2^lg7yrz7r{{%7f%=`9ky*y5md8P8%G&LpJ8qXs@-RgM4>pprg z)|Hx0Mu8u3&aDMx7SINMc;o7m8kY0&iz(%XSqmJ4vYE1YA1RQT!0WT zn@{fFyCQ4J5^PHhGf2izg(jW#PhntJ7{C;^Gz~iy$cX*6@gxV_%?`q zGgP*Y{SNG#bz+OFJz85}x4?%r)>7vqFsO^4x)Kbu8HZHAB**C>hkYpHYrr1Y zcfIlIHw1Hcsha{Z+a)*cBE{QZZYl2FbX&nE?l&qr-!{cOOU@GA0U> z1A^dEDTTDv#TRf05R3lLYUmDXA^CWK_1YgL6|;24Wh)R;`Be!!*lt<}CK zRb{F&tAM0zR;u)T$rx8kJ5YuTA*ENTiVN;}@`;;Ic|n|J%e}!B&e`eNqjtN`xv)lS zr8oj2hGE127{e^jeBZCiGK!+2C>UpHHjf*fFz_#3IwETuQGg_(s3`<9h6Lw8WVA-W zC~7EGNza?l7Yy-J$>Q5Mj~elKJTX=?##-&p>ruE&SIZLGoz{3bOBbb4u*xzw207;r z-80rQ&f0O$8osI)02Kf%(|oyHHsiLn8!-^7++2?&&E*{k+BFsXaIz@ zw%6^HWf4X3Vpehw#;M{H8FkIa4YhM{)3ut#J@7k+AzlP0Tj4|9g)VT$BK=}Gz*7nF<3nMZP_%ucV z5oe4L?3z2{uE9+|kKL>bR&U1_9JX$WJWuMX+GuCi=iQR)MMMPlfp7dyhVaEdJ{MR8 zfV;O}y7AQewx1s&10*13Eg`1(8MP`hAds9f1dp?Rx2=qw6k|XXVML}P zs3l&IK{{VHTk&=>ky2`tJ8%xZxC}tDo61>h9g4SCzXMoH51c=`tvJ%=nQZ<0u0Z~I zNQwv%R;!igd1<KAlaM>FVr>>sJIv zqpdbttCGB6JepXtLdg3M9ta^?tyT~OQ6nnL%8;3jC+;9|qcNRM8c`&La1ddZWux)L z0C=7Zd@t~Q&Tw~kAcT1FRnm45oEr%OF4id9h-MOA`PlZt%lLmjDM3Q5uhK+W?ciR9?=Wq?X4x^(3V zL-p_f^3m~eS(g2s-v0iLWN|JQKtxYGar4%#+W^pL zc>TS>ul)RP)|;&5e8U8RfA@#KBevF>3J|oZdfoPFmHo!A{m#2}(F@(R=33Of8UZ(I zd;qXvC~jvkIp=X3Mt1|nS_6;S?Yg8f5!7{*&WSTyR{-mytsxF)lZl8J=Z>#p-yyEM z8E5ClaP2zV8dZ54qH3%G0?s*+sTT}ez$;=6^jflPJ4qFYuR%e!De*(~DeP9{u=Yn0 z88S*-f09j;`A(O(x5R9>wtX9ex zO+;kPh1sAE?lK@?OtjlPT`Wj@jBzHVH6TPFgfv6~c@##|@v*Ubxg0KuYo$BwUZ>Mx zjHUU^mx2hwAP_P?bh2Pe_l8Vzn9!c9(gM01yNc!2)+n z3}jRm1s8(VC8@y}TUC`1+&vn`Hw;81AY)m*^4i=IZX3MKYuScbVDlc{Ax64+G26S; z>oat(wT89O$w|WL>FHoF&`JfqpXY@XJTEc^HVneiWU|VOxY?Y|=3)s^6f0F;x!#_P zWR_O@2R+Y6YcUQxw_d-~YQ~-jELkFAz{;YOQX+%U4}wM`SuO{IK~c;Z6GHOQa3nm@ zX?HvAZkmj((Zlhi6~}QLS*;y$D$BA)P~zsj;Q%b$7n+4*9w zjhRknQcA7$wQE-v^To}ZH;2RF&dv@2wOj4kd|{0dQc58Q{hrdQH#iuM$Fs?TOGzb< zn(_Vn_xJX9vn=nnTFGLbruj~PPg`4-<>f1vk|aGjdq@DSZW9H*aqD&A$+*=m%YrdW zmieK#ySsbq^*cq8H5yT`*IlLw0gT3HyMz9GoR7|uIF5Z;w&M0;F+&UKLa&w?kv_V7 z_0rK*W#%uw_~PEdzVN-YERL1VtbU_PD+G-U5X5>N$QVTpZ#GMaudYA2uN8jrbGM&) z^0`JMDAfGu%Fc43AKp7vrSWB?%G_$`_WME9o{ndu(`jaM&N-m9WCds1C@Dmli^GE( zJKdtl^D9^0QxwJR+h09-lnzH{lWD>j1%cOWHaSNrMZbS3U1m`fOs20_Wd>Gdt4vjF zbUG0N`@4Ii(P;m$KOHW0r99yovX<11C$4b8h-`l+OjlX69bCG!KOWDQ$xKxhf=JVM z(T>^f^0fK&aU6Wx7H^RB3sB}c((ZaaZ65{C_kL`@4P--GFc3a7_yhsGdiHTdB*M+N zXp4;OeEfB)s9VV3`b+lWz50;If9!>or$hxDHwOxv<@%Z&1->k zO9w<2$T~co2pE6?4Mg|vJz`8)vVk8EfHj(PtF=j&b1w)P zCs6+_Ru=iHDog3fFGO5x9Yhhhn6tGG0O#D7(lg39mzX01AYGQkxsa08m4hv3+!9$; z1%Yp>IsusRGR&4srPXS&h=Rac>j`f*n=xe47eVMvXS2WywDMF1Oo&dWp_JM`>;Uj8*PaXj zFi92+oz62Z7Rm2^P{|>kR3{)$rfOEr3_fK)@bWgq!{B;_z2Pqc%u~=QioSs zf4i{1u+!2;tyU!|OLgU1VvL0mXChiHi=wE~H1)gy8KPm9EHW@;2mSp@<%0t+FPEP1 z_73)D^Em=_`w@XD@}w-vG)b)?DFQ@)xhRC>PyNBQ7eD%j)<9sY5{P7@DLm;Bm1Lpa z>=k*&FeuC1mBa=h#(^S!sk>}5E;t9yYrJ@~4#j6oa3O{CM&mO8`0zJ>_jb4doQZdDjTnIV&`18d`+5J@ zfBXaA@Ld4V?(|;x;K!c-;I|uNj4?!JJ(&TJzI0{xYd?JXg%4fv8_W*_-}e^FF_GEW zTn6AtW-C>$Qlx5?&B)|wKJ4tUgTs*Qsw@*#m1R+!ot>r2Y++ zz&LQm7>dmgXObb~4Eg4Hx)%q?F8(0a5)I6CO@i|`yVW;1<46G3aE1sJMKR~Rx6^-k z{HW1vu3wq@yZ`Oa0YI8A<5nYT1YBS%?zZFBy|>P)68_+y|K`)N%w zFo+QG_~i6Af9JP<{}2Cw7)mLlxW;#)MpTyh-tNwqzwr6RYykkfgFUxtzL>o6=4+i! z`-S&?&3Jq^U(B*BJAQcY&Yj!V>b?DgfAy(PfAatR3}dV;%U-XCjLqkZd;> zUA?mZ{MS6yZMAeoaoBqH$!Fhl<7tnD*DhTLV99bEg^jbbiLvI|)yvk-osM`^ko?1mry#-~Q3$!tFg$2WI(fzT3ol?E^X#^s}Z*LQvI&TgRe z>ej9Mle6^FQSZ*(SHlL)C(Ge+@@*gg@ZbDTe;fc_dgaBJUU~Vgd!tG-Aw3J03C1{t zjgSBy+fbi$y? zdI$Jl|93y@ZuYIa4~>Ew*RKJIewmf5|4 za@PJ4)+B7)?D!WXhr^cJ#Tn;}ZS)1#*ek5#cFv1F*L>NY2wVvsL}aW6ahR+6gXoUT zI5Q5yuw>TS>fi*tj5V%?wzV$3+|pXB9mrT?Eg5T#F^tt!HSJoe@Z721RD)U*LEX(G zBIB$kcdU0{i~%w(Bmfga1VP|l$kr1kcZCktLB@m>QhL50gh3++BkB1}i1XM6trG-D z0GTJAyt2FBWWq8*1jISh#*#&b3>hOJ#u;N!6nRw^047PMM(e7|v`xA_kt8EkRdFLW zTKS$R%R(!qwJD2=bI}Mw&V^Mv41zLGfpjt-aiO)Y1PU(*5D5tw=Ky5Mt_ic}K@k9l zyIEt5UN@uNOV}*5kRijZAjf%Q>!<^;y3+x^lj%Nh7l6d`j)&`a1RME?Uaz}(BT=Jq zHXM4MSCu6oaKWb2aaoqu7y=j$M^&ZDQctJjAe32FO(v@(sQ|FsX*F9dFYuJAn$0E= zISuSEjJn<4;lZJcX9T`vh_Ao?=HA|3zuyOd@p$~&YcHLgp6u-G6RNUUEf$Ni%&k_4 z@aC;s^VxziJUlu|lEo^^8c{SD4DQ^$ljp^)Tepod4)6t{)oNw54t!s0edqS=*=#B} z3j#lGM6Fg+N)8BFR?KE|Ks-F$-`(po#QpsPUxZgLUpLxvlu;NZ%cLlB&c&nS6Cp&i z8GBM{Wt1{fdT|_;Wo0e62$Ustc6#h`87ie0NfJd3ZL;0nPNk~lBJc0)l$G-R$oE3u zYarv7E?w&PcET_?IX*SkAkxn6AdcfzkrkF6YBREsbB=_}0yDIZb79^y1{gVl2Ir2I&jFa$w#Zdg zXdr1c1MrJH&+}DTu*D(=@VP)&RDLu*8I8wTQ8XGc6B@Z{wF52@nY6}Ml{!71>>msc z4|jSyz40hnrDbi$5TxfzDHyjzkfvq3*)6La(43wgOCACRd7;Yk-Pqz#cl7h03*PVA zZqO#A2u^x-{o(e{roC-MY_M$mw!Jpjuzk`E38J?AYbHy5Fhq2iXMKXYln$P|v~Cf< z&KTVo?eh~j#|+s9h=+6k_Iy!LyU^>;FRU`wyPy-;0t6zgWk=Q|M+Dg9Kdz^;?Ne+X zzqO8MU;&Vpz#g;F4A*Wo!1;52o2@_hDz>}` zT=!Mj>{63;-E@x#099E9evs$6HP&b|oy{2Mp6?SuQI?+PF~+Pmd0uwfO)2?gGDn0~ zD-setUoMk;I++`5iAV@0g#-eZ>V=4c3qYt;RaI4*&W+JomX$@ZNapUM7~@J+1XjBk zs_R;ah}dW}gb;3-TdArj%Sx%`B5{|*)?J6l0zw#tZYkPqHaX|*Rx64coCzXV{ZJUA zE!nu)v_zit$N=Zkk~P+Np5&axaYG31qBuqyZFINWL1blBxEXhmBw3y*U2-mK?*@(D(gF$cPIckk??Uwt`8mDr1bb#t%iO8zWe2EJqGNfHsQ!F!DT~ z#VtRKc+?0QaU3^WLO9YJm1R{{%Ge8L_OGyQ*fDnPf7h0A8$GFuUT(1pfdJUs=q>By z5khbrXWGI?5y_<~y<>Zaxdg#g$F#P#&UQqr zUz}bn7X5x7fjC2C!dQ$1YsMi5`-{Kzsn34$x2t6MpZu-AnWx!J5xn}!OM82Rot=I% zON=dzW(QZV0>J+dR< zzvr3fKKI98A;7CgM^~@yJbZXBO>uXxGa5ZOIJ!I?%?}QamdlyZ)iO`H6i?iI?pJ^1 zpZ&;>J~x|BC*#SnwmuVvStL!`C=Q}_9V`IcxpOD(J`wtTu>QR}kM<7^FCX5R&C;En zR_OJ1x|bh3I{oRN{To5pf92Kt`t11j8^=;Y}Y`uHQVod;8cO_8Y(PgIO~7eEy*ie(;N5`qH<5{9|mEw7c!Y!y7NZ{QBvm#UK98 zr`$K6fBtJ$S$_M?*Wq27EARa_vdV?_7$?Emjq{A8wJ~`&ki`UsEi%^X z^frFKI|y!(C5as9z`@pGK*o>*c%El%&EmAyi3}S8<6g^`zVs?Uxqq-Hgg+e47;mH$ET*cib+R?7_ z<{WwkNNY3=YaaW0spHl({SWMipf_UnEaH`Sjhp zZwVpdMnfqjgt&9}-tNwz)9DBXmS{8_Lal9Qz0fOl9>)HS8`p-T(P%jAKl#-0@yY() zei(#gDG*WsYxj3fho^qvBZ@#al0|a!#`Uw4$-@Va$k6rc*Gg3uRf-4%XbEmUc`3`5 z$>QFntNVGDB2%kuQB>8PyN?=;rWZuXJgc;-s_ORb+k5-_oCyN$`+~^t@3hZOA0bnc zM~mf*bFQWSWU&No3}bbjEpoLH7yv3oZ@u*>itX_AoMY42L>xARsFZ>@@&eyCI(Y7D zKe&3TP$j;0>uy=5%QTyg#{dElqcC8cm6c{pFvKiXj98kh!LF78BuT0jtX2yltGvj) zfCYZzV7Gt&(cK$2u7q)eu*mKG=RSB?=4w2}UD;nQl2xj}(lW{a>`Sk-JFPfwS_MGB zxD`?g>FpmJ&KJXOKaL`iCgp0S17BpTOmLRvX;qb3R=y2kxzOr`$N8VN34O zZ*JR*TUfh@e~JA7&UIBUoTpx%JDqI1w*Cf*ED@_qU9U$kU|o0=04!NX%&q5Xo$XT_ zb66`Wq!Q}c0LT$7i03$*KE`-yx zC&oEZRg@(I4wy4!S_e#EQI!rBn#wV$!cR5<4Tzz2(;BoRa#Y&b89qX zTyUtW(htK*nQu-!@C;Cmm;h3qWlR=2>?7=&aRhs;YFNIDnw7;nHc-K@bFGQLa|2cDGf`a;kNNtg$*- zCe~UaFvbWe0Bxrm3eJ*bRTfpd)Aqe6Tjf&tRxv~x4EE;pMHGfvUhM7d5#&m%Fp9Dw z9~;7oSrjR^pq;zo+$@FwQ4}@fru4liCP16z$zaga3ae^49<8{L{oU?=yqN#*y|&;S zfDMPU!S0T-HfRKpm8vpQBA`%4bH=R&272fxo zx`2DH-v<^XF@O0XU!<|7_+0t5-E{d`=&K)H}&Sk3|0~%wn zDk+S@N)@ekJQ|LpATCO6w5ciu2>sp8d^UUg82Gnu>q6J-F$C{~jBMHkw|*^%Snu)< zL$n4%+}Ly3{qJ@i=YH_x#hWf5tlN1&05vvG1X>$oETUzcAzonOIP<~SrcgJdwTLgk zx=3ohJ^@(cP#aFlhE}tIW;U=0=X`@T0RThf(lbtYcb(>C>sqH5w907B$9Zfe0|3UD zv$ID4@O9tv-3-w&C2=cN-qlB~jb|--zX6_@1H85Z2n>;N?q%hYF$|(6W3kpsnZggD zEK4Dq^XYV*N8+k}geRv9DWgW*N|uFI)@UUp_q?F0QX()$zx>rds&AW-wMs}VDnn!| zt)nQ?+WI1h+ktH~$3+n|J%c5p2UJHG0I|_%Fvid+4Im03fHYgD5-6o=j*_kA)3w%8 zuIuSsY(M#ZAA5&SEpf*Fa)L|m&?kiu-Cnm+)p$6J<5+rL5O~w+q%3ozlxqkh!{mf69jgJqVi(t>j#1a`Zn>TNSktlVxcd)-)q_f4i z-HyW`G^YC1U-=yX`1}_?uM1L20Ww9}xu%E+w9yPA0C@fNmp^)Guz%F8N^1?P%JS&w z=yaIIaih^_-Fxf)>1e^^LipuMm6buti7ZJhJx_oI2NSr~ZZ~HQw2?&k}!=+veo*1nFC2+~Ogu2Rm4JiSDqwUu``gKAp(&o`{1cN{bE>cIv z2#$=%RHkUP4jDqaR2EdL-Crbg34Af1aV~_EEa1jy#`tWU1Ys06n~O!J74!#th+G?b z>&`=9hBK~J1!#l7zkKQFwbx$~LIzROW4-}mLTH21Zw#7UqsrH{@}y+81Z@BqBPKi_ z0Ho&wSt%tExxI)i=Pse10RUgi)q@7hSRIbR3sIT+myPn*256~^xwuk=Z|`sH9hOLI zpTv-{Mj^WD))WN(Xf)c{*C3OYdT?;axxZR2kn#C^ z8i$^?YCd1>?hT5f==S0wQ;WqSUCa*-cC%I4txY$pbm<4)DlNhw>~uPvcE=Fhe)G*2 z-upsPW{pPh@=O0(EAyVGo*s=xp(m!Z$<^yu<1o;b(W6Bm;`q^Vkt^V0 zI$iV!oxCh(^TpZegb1W3uU-tD!j z(qFC0Ac|nQ9PIUjD1d@Nk^`1N1eTM9Zo3JLTMKbJ-rql5CV5ry)p9|G1wKobbH>=U zYnP5sAFRsJ?%wX5J8yBu;y9|bVoVJBm;d#je_83mXwrrNk%b-ru*w*>j0beFz${B< zGt|1(AM~c<#2T?&WKv2)tljQ6!tQjGe(B3EF(J6@Bso-t$g}k5;A*-|t(h|>l&Sy? z0B|9t#~1(>_H_K#wQHBgqrB0K%Bl*2uqbBDZo5C|oIaR>@$cU|j@shsuenlY`1wD6 zvk?VFQAxp`d*2hUzH~cDa%-t9)Oa{w&Qc)+L*J8LRY9RuUQGMF4rfu^?7jBNL$XU> zh*q%F>Ii7o`Zpy%QMAl{EJ7A^8YwFyjx;ENo9BF-PuW!<+EoK&OPfBLlO9%CHrkm{7F3xT2)pgxYHn?PRE|LvQj3D z86j~-3%x$Qmd!kjV-U~Ef;&G`{R6H z2hXifw}#XaH}kE-+Q1J&$I3Lu_eUl%`1(gw19%&$6fy24SEpEhUbI^ImsX zYXboDSqeadogJmJX0v&AHtKbIf{P#uJ%FD7+x-3i2^QbDvXTwI+Xhe}RnlYxT zGHwJ*$#-`404qXbD2=vKde$2E(`>bRJ3CcXCP{Mn^5sX59_9W~uGQrBCjG|_e%%sOX5lp8uAtVrWJ6)wU)dL@;uoi$UL-IV)@T0|IhG;nR@_dD?J<`=!8L-wOt4BJx z&W*;RQvdX*Rg{${yu~W@WMFj0 zh0t2NQYrwvDvdD&ylk~2Z4{B0tyTc7qBNc_ic&?s*Y9>MRzcX*R-wo}&+qTGh9@)O z!3X~Ixpbbs{+)NLs?rOyT&CS#j|i**vYIhK&fATS7x-DeY{b4Vcv+~jG*YtVV&Q6^ z6-Dm)xDY%Hn(+Tm+puF?_C`Gj5Rve4g3NX~vUA(EnJv}?6I_q=+Vfxg=?>R`bw!+W z5dI?iv%x+9z*?h>wVJfnb+MbRn#bFF8Lf%P7_q@waBabzd30Y;oFn2|MCN=Buxqv5 zdKYWgg(JY|dM@0|5cT5#B0ARtCL(LKHMl`=>{>qU)#jY%!WjF|N4}dOO#bNi z0bqCc;Oy+t{^h4nAG{6()@bL!Z_k(rYv$k@ibv!w$^@`c$|P5R%35PBaV|nH0s!y} zDMM+?h=#0`fZ0a(VE5S}p=*}C4daB|;> zz#YSgGsawA-7o#tC#Pp8U;ON62`ss3g6N<9%0Jrf(?9g1KZ9hfWsKJE3c$(GxFW4v z{T8=-3uEkie(0z6_IJHce&QeeFaJFN{Jnqj8*wv|elQ!4UwP@p{oTIU+y9^b*ZW>i4_JBFXcdF;QuZq8N$Aa4CJ?2Pi-KE#LC#&wS>W ze(9Hf?1z8U3JUV+K1rNs``w zbiz0bgYegX3l;0(|2C0f4W4;RUZOd!6?F&OVncUv*Hb;dqp*3Z>0; zo+oB+cjwx*%azIFR-+gfoLIlRH$0n!zW>^*uN_`GBx@J5Ni%8=`a9ASXTwpEXUG_k zWE`$tyK(aH%&v)Xy7V61J01^*M0`bMs~5Doaewcc$3h|acs2_C=r|cRnt`IS({1h@ zwtoDle&nD2!mr+W^WN@Y2gvur01&ETWrzSM@O>$HS(cl*zuP^^Gh3Er+#DEo2`An`F0d-?@I}%C%>&E*8_BUS~d?-FagnxjZ;%KmYudvSi=C zbNJSSH^1_^SMT4wfBnX_tJkjHd+Xk_U-JyN+9)EX_I7p_)4WoG%lyszFMr{aU)^-$ zC!cu2r7{7)w|?xSzXkt>wvG9|V|y&mh%shd31^@h+TA*i1DH3wm3KTHY#Cv!GmO^W zyd_%?ek+jGG|5eRzXL>^l)dvOaZQnMmr4Ktj=(}hgqCsc%&fcSb4R`QDS{%rNYqBuIKLTcfZ2JI2x#csR;s+rSHns%|gVR_AF^mc?MOr?l~;2Z&)9 zDQ%JAbh@-;<3@wXFpkWHV}V%AOROa1Hh(} zVHh_p5;+loTECOKyo&nq3gJq|0ugdoC%ld$6A`aVP^~9B&ZeVLk-f9BsRORERl4qu zTlDzHdNpkx<$2HKh@3I7h8P2Y)6-MVxhrta8C#}vRpmt?_jU)b5ASd;I5HseeQz6KW z@x`wm9qxbTv!A+j<;t~dSC)%pG&HbFYv$LeSqx8y57;T-nDBt-nx4SId`Q6T#|*>#27|lsI}J0q^rV{K@ddC zWQAO~Y;yoWhDnmyNCKMO{Xv%Ho@gHI?~aGdsL>1qudJ4iy&r^rr`K$?+7It9eJ=no zRaL~TjxyT!y|~pFo+i2?B9M|RW2`mI0)f+JU~Uw0A>Q-!Gkd$2TD@>SUCw8VU>v=`i({|b?T^QcC=N@d^A!MDvQ{b0 zm~nSEkN^N607*naR6vfE(#ANu1(Wg2_snoIx_o8FXj;w7s#1AgSObjlAP{+$zhj5r zY8&_PU9I=KZn_Ax;N$f%&JEpP`mk$5Sg*%vTi~x2VWBlu#D&)wbAr9Fb*kF8TC?M+ zw)O-Ysa@Kls9e-rM8r)w4kEhXLZ4qYUHtR>4?L%8tTBbH$Ggr6b2h}S_i7a!Tr=$I zQV~=q@NRC+Ww*nI<#CRg;r7(vPz!6&h2<=f6cK^VGR+tni-IE&aK@aHV6CYOkS^2R z-CmX#zV8=B5k)P@10cSbEwxr$Z~}7W>YA;1GM*p+cy&P9_kC+E6N00s87Ebt=P|O( za*M#6K0NYu1~4bAGiRw@?bR30`MG?IHI{Q1z+iP8qgLLet=_enxHpf$y;zIeDNgHc zTPP!}YdygxTx6|we5>_4s&mjRF~(5q3c&)vbT(D0^8KJF%P5LQqoI_-0@p63Z3My)m?OINv&(IP3-UWf9EF=&KMBFOXHafFF1V}c>% z#Y$Dy3!=$%s+HQ?J>bIQ+~#@NYWIX>o+sv$StD)_&!+8e7(|>bpN_M1nKR(+Ze&ym zXxAMK=hK8S@H|Nbj59<*WXm!Wi~;c|>YhBBGp6@;`vp}}@I2400Yr@BFl>bQc&&`T zvR1<}hWLc-+ixN3%p3Gd-b|~zjN!jp?jcdGo6&gad$x$T6G(00A3osviqTy)P-&Vu9(@34CrO}oZ{NCUgMygz zJY#Jb#AukWZEj1cfGvVRkZv}wvrdS^4RslCb%2EsAYhCn@kK(Y( z#M#_f`_dmji$ZK~@4n;D{rRg`pPx)7Nh1P)fBVzF@Pj|}LtlRGTBFspR+BaoFpfh+ zktE^4K~j5cti83jHVu0C?ae>9>8& z*OaAR>f7(`>>VB)%x4)2S!P+%Y-*$b#`pitwQlPl|JaZH*gyHF0PvT-#KJ{rG%7_dJys#l`LI@p#(nb!XFAtJQM7{h$Bp|8gImdFB~wOuN$}GVM<5bU6It zv(LZ&O^?Q{W}X?&waLuI%e%wb>6c&l;?DN=T5lsL{5vNHWuX^~{K+SuTI9L!CwZBJ z5@8(XrkpHhxA$*HjSjGMG_23R@WSUm^E($WT&OOF^zP1Hx7V32X8q%XZoB*1#~%6h zkN(=F3$N+-N0ve7ccKQjTN{nUAB>Ox9r9L<~ z@B@!ZA`7=~-vofKd-vB|+}lA4a+7`Wb2m5F_U<0sdBdB&{`$=uWbE$F#f^;%liBgs zjzC4%U!3;$XQOepcX7MhiEm!J^QO06l7bFzP0F0V;hW$3>%a8-H?H3VfQuKec!ddk zc=p-nzxi9=y}8x><1bx}TC%sE{Kh}~4LAM^7cU6(Zq``LyWjuTbToqpw-p$@Qi(o$ zFYZ6I5|RL}Rf+_Pnl|O^Fs@SaDi3w(D&3cQb00$uG1b^R0|E#HQB|%p6L1wh#5xpK z2~(3JUL|p_>xKwaM>MS^6iB962HtAnB(&rb#epmdDR?Q@UBfhn!CFhqmEm{MQ>gX^ z4rI61>awilvEgj7Ktv%VQKj^ZbwQIOrFK4R7&iAVG!E}vv({|yUSuI%{zx4e6o}+f zcUA~%0U7QkQUk8hN)*6kfq}_7=U;$ifgo&}P5nR^qdf>Ql8q?o4^M>f{lF(62J`|C z7=j=|K+p4iPbg2O0A4|%z6*^4nNYA`&hsn-hA<3q7?n^}WX5Wx0%l+-0Rfo7vXX)DG0#(n#L^Usz=4p6Ir zolQAc98;%9p*+iDuO~TFq!4bC=$5&vGzk#}%4{+FEyXT}(ffqgX)KjOYqvMm4I1VpeypS}T&p!K{ zQi@Rki|Kf_yR!|p~C2E zH(q-DsfVK=j+<&c?Ps|ejmC&-XJ_Z|u&+F?nFK)~oz8(5sNrY~OaRJF(!t5RZ>-hu z<>#LF{l;)G>~+`U7;fJln55C_g-^ZVnf?8~F?Kr6#=}%%5Jmy9+1cKRT0!6k`};RL z-LNd$!;>Mik1Fuk+Oo8QB!KV7QevLx04St4nWVG%_0!LtAV^>;%4|HI0HBca;9w$9 z8Y8sjX)y;TiKGOa4#u5MONyWemMY9ulQcg$H)6o!E5E&92$Nt7<=j7z%m8KZZqL_68!dFDn zmoLf^+^l1mmD|1S5E1L6{&Zcg45r>mSH>Jx(jJ}pCm^gz-z%ubWsEE#oaHc=*)jmY zj$I3ok)R^=t9YVnCw3KW!IeO%c!k4XySU4E00JKE{0F`XJw(s zqhYhzA|jx?m!IAuBa8&)b}VjSQ5+#6x*BIhPbo_lfDiyhrDx~nP@P^;y9W$R zv{=k_?Y_RUz4i1HKlj$+9%Sx;jcau4-sV_`-GdzthXBy&bc!;Mqp&D4TNWk4$?-|j zXvk7I`m;FkyPe)5TUb-*vIGdCFpyFNK{TJuh-?^!R_k`sGRCa+*0L2a=rT`cOVU}l}l9S0K%L>fOFbu7s zQX4<;tudue^CIuAb;>gLy~y{2>3m^~1wd`6-EM2E7mFeYLap;Sj>90H%~C1-Bxw?Z zE)An}euqos&9hPn0cf{&w&t^Wr@d8{lx0>5oJ@wEuPhl$Ww+B+0fa#`9#N5())q=p z(u@u1IO^V>MAONH^xRQGm1LQya#EO}LN-ZC(MW>zwY{j}Swo}YWIR5VO2l!)m?8?3 zJS%3iEYrqt&cFo9XpNw~STT@NimWSIC#fo`!7x%@M9o$VjHms>cBec1o<-wdgkda+ z;kTan^ur&yl9xxFwT7mJ6urZPp-}GfZIKs26t+9bWRfx=6KgU8ff=Omhzwb6NjF=u zHWo8FN{@PL4YE8Qj;$r5b*YVz><21oCgbs#n}2G<`XAZOl$GwYdatzQl>xf})#(P}RT5+z+w1alt7$S0eYf?74eM&A`<4MWV8`i2WLM9%Ocb(} zd@B+Ih7~CHVSuRMl z#CMkWWI6Kt*11l*iNa`8SZj#&B866~W9rR-Qeu&%jm8>4DZOGeI&HT*h=NGQaWtFu zl_&CI_Q+#zy!yiDnL(oGc|n@aljfQOr!9dc)>@OHAcznc86;Nhol5y>UIc!Kh-GQe z(r^CC&%NuLKEMod94?1i6h(bGsEr{@0!0n?u@KS{!2_W8duPsaxxVlFd+y$uD1a2Q zQV_Am=<2AW!^3lXd(S@mg`=aBuYLR5pLp$)x2|8G&*%T^KmS+%h*foa#0lTfA3%Db-Pi`vh?(u-|*MI{af7d zUi0XqTrG+<#j@}Os@~cf3Q>d}6KkzS910=-o4@}<|J{%LC;cbSvo&HJ}%4r@y8#zv)^}o zSIk5el2~0!s}p*j98I*6LEwkO)5&wsy?E);g}b*0x@0eq>s#&AE5k6_zjNF03Wqt# zFo+hjLMW=G>%mcNRDduu0KDh@-|$*CSvtM;^7F)boU|IvcC+h`$Md!IPPQmU;}a|c z6*PzhfYVa2x-3xoPVe5G?a9}^fr#$j-rqgHH=pRya2AEp3(vmFR+ZrHfze;3&-+?UFyN9~kgTJh6wBAJ-b9@BMr2oQ)cq)rS)m)N;SvYA zGjkPIWL_fmOBns^M~Ie4O6d~n(J|9fRW~Jskm4+|YpktmqZqU<-AyoHgj3USu8kB9 zoI)Xio$Kx@ys%2HSq4k7`f%?$cxHoYqJgvcIGkDam7p|3S(Ls9p(mt(lj8$R6h{rR zw$+MJaNv846on048s+)veAY|CgMq9Nt-Q+z*EYTAaq&g zSxRIZQhF$tS+dMvEQJD@5K)q~LP}z=*3{;i5z$(MN&tW>VyYjUsl(;~Y{Zg+w2I2C zJY!rIF95QOg;uE9*|*CXumWr?MOBT_M1}A92%w~#O~#8w+HNP$ed$Zam`j(gG?HYI z&S$gPLzk~);~|p{g9bAcMZQQ=GNuuQo>KGqJo5db$eF0u?agMXMA>S0W;0~AaU4&l z(;x`aEZyj>Nr@zdHTLS&t1rF$;uEiXy%6XJN-EiGwOtA26OTVpd%)&K)9yD3ljOVbp9U*4R$3cXV`Yv>pzJ z=g*%%?oW*+0GQ2Z-L*~>$ILLFXNW>cFOEVF6c|7j>+2hXem@K&V$>xuKxs@6s5og1 zPDfGHD9WNVItT(G<;~kSioyh8;@m=k!VnV^GHz{do(@NW*O91%@Px!XPkWd=|D_iv zlj-jEB`JNSP$C#@8gWw_>)E257pH^a_V#8NWLQ=QaJn4_v09zyiS75!qzMdqp^n~SdYo|S*=P$l+U6-1z5U2KZ4xSmAGq~Yi174rfb^Z!(AL~RK_lml-#5#ZFtPz;y zC#M>{jCfY>YNcN4Od~mP2d%}Lo|S736!B=2B*G1sHPOz5Dh@5RhwnG+-dG z%fDg`p1V8aKw+*$nh~+esdiR+X?ZJ2Tlh=_Ht0Sxnw5EmLVP;%q?E~WO(Jx?JPX`V8p@;m?*(qptP&LpJ_lnMgh zXbVEP^+bSRC`+CDHX57`v@U`1jmAeQKI4HG_(mIFN^mUrfDRTCRXP$mnmLEFFV~_a zT7mTVQsAmD#GGCo&U`1KVNZ8-a9d>U^@b5T;HuT3trtKtbbOmjQ7vyJj?cX z|92^b^8BqgZx_GwPNjrYah|3}M@LB`YBpQlUhlMjr!31x6jR_?V~o`WJ^K_0!t-HfsIB|mU+9=l~V1Uzd%G$6qUtS z3Hgym91DR&M(Yw0NgK}(Jmm?22o#4=6oqjV2q7eKv(=o8rvM@dyl&7%frHbb6e0*! zo)?Sxyw~eRQ8XCz`-4-@^F$?A!by^}T1{PO6tqawqSR3whH(HS*4KK<^Q6GC&}o_? zFcFZoQeb~PZnm1nXemGn41-WfAwuuycmP7U<+t7Lc%Hm_=QfiV42GWaZ{55hg(~tw z2(*+dKVIMLm=cLV3Yq6+vytRQp66O9v9{4mvn($cN;RaA1X`d(r`n4^%!n+dl0q0` z91v+q9-s6X*cyX~O8HVMCF8)4QK)9C)ofvZIQhx*TL^-RObN8cDY_JZKupYlAf%99 z;FX0%0qeW1>39yLgg`GOrsDK_(;Ji9#+KbytN-1HQ8UiOLMe4KJ(!L2*Z=lwqE?8A zx#xMl{%2|T2wkt5-UniveD9ICf@mxugXIBB3w@ua(%C6$xWw`+51?f~%of234+*?i zP3bJjMTq6LjBCbUcZ>_0ODSoE0tQ!dOk5A5>Y<`eSmG&5aV2+TtpFw5QiT<}6$>Gh z^h%@M=haGAhKj02O1a9v%XIpKI6D}jR5#dYN=oZWU_<{!NR3v)uz zN=cBaELnKcQWz#-ud^crGV;^w7y8F9-MxMT0CrW_Y__(y&fmFnXFN)~-3>$9^)GMAOB2dfpD}e$T&o+1uXzm?D0E9YW9++9UbQzaW07A2I z^$4=2-q5A?eP0R6v$^}#aL}L6X5+!}xBkWN0-?V1yHhQY`@Wa2 z-@oW4* z&KF}{nzTrT@E&>1Zqf`s{?X5q2|VAkmTuiV-rGGF1mWvm_eKEz;On0F=l{n~1Hh+0 z^=Sau*|}hJf%R)M91S-&HeAmq{XPI>^XbvyezVnVwvyR=Uf8VJ3J6tq&2KiFi@7f( zkX3-9Few1MeD#kmU3!SDEHflBO!oZwOLy+v{LH7nAfy+1@}-wQr93*nw>_JlF6QBI zyx(i}cK3Dx!XOG>_|o+(%O8JYhm0snRnmkk3zRpm4vKPd?%YnR)l6EA{>k)R-}p5j z`{hpofVI{N0RY!tzVY(Qkn3`LZ|&rye|mEIn#UgYj4(F8b@L_weB-yj0}H#kx%QQ~ z+$+!T%-Y=dcLXF@VNqRq7_Y`Pvjh<;kL+F)_yOPC|7XYK$U=&xw$A-na{b+XdyFbg zX6d#|$B&K-EKuB+#skYx>N5Gfc7ooeT_8i_(;5-5ap zi-KcoBqA`zFoP5XD1;y(m9dsVNFgiRl;U!E{ySmHEKQruzOoXeU1;kb> zVPhD|EX@eW^MW{Owt8ztsmapT*4Av6<%LcfO;4%OXn1^lvc9&7(v!lJMFt{A#bC$+ z42S*gt=%YYWZ9y~(@v*X>XfXp#s~lbyjVgFClwJn{IW&p-FPr=;?NFfb+Oo>XBJPe#K_mo7c~+?QIdW|3#Dq$QQScJ1X> zyVdA)@**hrGZ_x*H{u|$I$NpJVU-uZ_v3B)I#eCqnm z8vrn$&4{6yBmi!w>M0qF$Fo+uW6Od-G@ESz02E1*G~&kE+S+V7J3cvXw>tAQ?Y2Af zbde;@*=(lEvfm#>QTW0OFD$aG*=lw=o#T@et&O!d48wEhw!<(4gm$~T-t8jW*IapQ zKFhAX{6Z9MmL_k+O%v)?(v)7fe{c{*jb>sdlgV^Cn@%R_BE9_3L;bRJW&lYbFpJ}(yGb)#-$<;sRG{aDMV=W$+dErI`L}Kk;y7X?RQ9pQo;*4l z42PpetJ_;^NqqGBwcFO9??>4}d%^;cK*55nHAH8AS`hk0xlkU*v448f7t(C+wUgE+ zF&PbBNO@-WZygu8O_~vUS^`WK1zBAd+GEdglOrhL(3Jkc-Fcw!bUf^J)=v&kqR{`u z$A7EQ_M44JVsLP9Xu*!gQ{QU@p1N{*BQ3I|t@dx8<_q0FSj369ccF9AA0F(VUV1os zSCrN^}J_*+UETa+2Laloql3OT|&q_Ee2nHR$srz0C$)L#= zo+rZ4n;!OwIq(Cm%eaxaoB~VQ_d_C3$}fsMjN-xI1OUP)alR~B%LG9fNh#0oUAVJ< zdoiCgTek4l6v!F?^w~p3v5Z}U;40$@ts!tq7RZJOMU_d40z9G0(m0pOk@Z6Tu+dp` z002T@YqVPtm>+Z_&XDtEpyzB-tssZ)ze`x%%_Tx1gurw$_mnJWGv%qRI6BzB>-m0? zG%sGdG&~*TMecjv`ZrzuAW5URA60S@#eV!BI0wqNpLQ98D+2 z+OjmVkWti-($|_npz@URRGMd#$(V=*hVBLr1_L6S7bP%-fp3kCqbQ0JmCfd}S*zLh z1C?iK7&eS4(o_Q%M&#Dw`uespWtOMRFgQI;+Lx@Mi5VzyLiu&Q51B$ z&EfE*)oSnG-uHd4EK4Del2&W6Sdf8VeC$H7-C|==fTyG>GqQFzn>CVTF<+&(U?Knj zAOJ~3K~y-nUP|;skC-+#dYW?3=lXL)Xf z#I^PIi|@Jdx=%h5gji8Rz*>^RGKg-sRg{I+Rs|x8eXkH# zU$|wBg-UdX{Qx&MdwE_IS!uaUq6Y^@|LpDl6oUu(%qxGbU+((XD+@!77dSs`nVj;c zUk|==TlT-yrFN|@GphmVx-A8XU5E zIwK-$D%jf?hqIv8hRA6LvXtm~GRqcHVi2kz2&9s)K$2Y^RzO~<3r|V6X;{YO|M-hvymIBr6OTWB za&l~Sm7?i;N=osA|KJ}sTgllCClEqd%ZPY%bW{|2`4E*-aU8c=Ezb*tP>8~*>-j;T z^HMOs^PTUh28kdA?(FQuaU2AGoe~6EYXB5Ny1drqjUpmuwAM1i5C6R%bYK3|zx~<6 z!^5)FgTcTUBLq$+6W{maI0Aql{Ll~ddfngr?cds5-%v`qSG6e0Y_V`VSP@7sP$z>! zqqV2h{+<1!yGM(KM(G!Zl15Vs5r>UtvpJp4lcePbk=ABDn?-SS?%YMskIo(}xRe|Q zfLph30>F2E_qXXn&8C$I-{w}=^VIRtDF8^tp2yZ&fss(rasOCK6-AAkHx9o4`~T*L zKJ@opr-z5P$?CGmj!%yIgFXP9^!pBoacw%Co}8QvPRFOGi_M*l%MYDbp4ixIW^*{$ zpE5Kro`3Ah<;Ppi?#|Y>`$-UbLLjqsc?weT>z{tTu{jFUY(_!g8$-j(`E6dT!s6une=QzJBclq`i1?cRX4w=IOV5;5`5! zr7)HOK%y_eJGXlt*`J)IWu}1%0dC&7?FQCpGze^?gg)S@L*ah@Y6Gb{L=@tI-&4VtaL{ZTd0sx{!luL-G27ARSBD3m_yLu=gq(C91 z3VdJrQYwK6e&~T^}3sua5|e98e1+m)-SZ0yHYh8 zNeE;awG=W6qdd=*64sI*cnmxlkG0WxIv7^aPOU8v7?^}Yf|Vr|7=X*N09TY) zjUJf6rE}LS5`h2)UTRmp+O(-|dF{5l*(nhf3IWwLMF5E)lv8S|W=NhceBYBo4x?%cW4@An^m z_~DI>^+w!SEan^Qy@xJcc=VAgk3IGXGfSxuu^A^yNV4X_#oaKG8cJ>TWO91>(q*RN z(+i*Xr&Z`B{o7p zr`rzW0Fa1Or?XvT^7M387N*r~oIk&_wcR?r+dsTJ1kk0<(nX#v#OZK4U(ByO^hp0` z@xrsWBnPi~{#YbPezSb zwUf;E_=*oc=Dtj_S6buy`@E+;=%lZDMy}xnccN8^>gCd~{JadO-ZL22s&p9?%a?ZP zIpgXpzOpw5z&aEP^-@%gwlXW#V&HH9JS&x|iA*Yls~&=^a?GWWPT#`?BwS$9T5FB9 z)({aR;F-{e8-9J|)$OS2u2$AWH#Dkl%@X3NFUpnq;MwJ16opFq%vhEs11qUM-wL1K z>ivEwnK_Cgr95pc5r<)HtesA$&7>7KlF$!@P+Dt{1jx$s7mHcD-SMPvtg+U}I;d$( z>0tifX_vp1q@V6tV6KVmc{%86c_cz1%CacSa=H2-K+Vhr^}|JHh=EbmLGC|!Pls?e z4bC=(_syb}3E(zI4xnTLCM9uubK~xv{hghybUu+%2o!4@8$#gh$&V=MTSIwXeEjR$ z0)g22zVG{fnl8v%M083?jvyk-G6AA2&1^om#u#J5Fbt#6u^&Z#=nL6d>-wR;w|5Q! zTCFAkltoz-If4)RvrqgMb<+ItW5yt=+ z1W}&n#+cb`R+gnTrqrdBQYkf^PTe$AN|j~NX}18NEX$qkEy=QVB^xAW&kM>@8*MDv$#?<)QYdZo{@s18i;a!7jrDFNMvg#a>*Y)pDgC(bTaGr`@`X2G#W6MX*wN`$NP5=jt&PW z$K%N;+uU5=+~{bF?~fsYysLO1!o8uB%`F|D)B)O1$)g!SMre%?rEgvc&cA%!vGUK)XmpqPGEjTK z?wh(4=#1b7DqCFh!U)0l=Gv_8|5xCE>W9k&`-;SBm9Bib*{QG8<<7WqRwX27S}p(p zN(MqmmmlQ$5?CyO9ybPuTvRv+06JzFl)${?OTO=sE&pFCV3NSRzP8Iuz!qITxhV?6G);v- zU!fmVa^~-S?|b7o{=?6G25#JW=eynw0RQz5|D$(Yz9Izg-*_qVn*eb2>P<&Cy|uHQ z6lEhxy1g|3)_L)s_q;F93qiEMzyI)+3r_D9YM-f*L@!^vVY7MLR{-$8{L7!)b_oGe z);f`Ao6@tXSlux&M(0Jr))Zx#Wto!lzxe*YUY2DL1UvHV`ac4|ul(Ate(Se<^Dq8~Ujl$1{(FB{o2<-d01yYggQLUAWSkp; zqx}5k*Mz<_ASVT;1~)9?!L<-}u-^-~SiBwb0px&5Kzn@+EG-9s&c9 zS*bVq`JeqT0KE3eC-PjkJ56LfI2u|?FI~BK_vSDNBBS#lh&DHOl~Px)zL=(|(b-A= z?gO$F8?GyzvbeFJAoczyC1688rOGFFf~EZ+la3t<{V>5`$(C zV#AO904b0Ba5lkk&6l2NwxXgezV$o5_ZNTur(S&F#mkp3TdRRVAckSIySq0WO?3%( zkB*7hgFt5xwi`kUB?A;%`N9vqO;ute003F*WTzeYj({~K@JgHj5D|nxa-4HetrqUgm5*&n zNQb1?K!dZ}we>)#@;q=AsR!w9q6-HAqCn+9UL_^4aJ)9IIaYP97A9Ng`ye8MV5ED& znq{Dym+K1?q1LR834@ryA_#DD*$i5nEHAvE*=hF>S<6BQR9>Ksi5fv(&H$AkMhtzU zH6jcKCxtGIvFFd7n=cmDvN6{811|_&VWX#{KrBn`Rw!*sq0pDkF{q~j5lRWb#MPFD zn6Rn~s3O&-ESYQ^Hw2JissR*aSjp950Z0hIEb6HF>Ytr{AQBT+^$sqQ&SXglVXS55 z*>svT;$}0+(#2vif6sfraXgvazJ04KOC=-$ET&T?<0|8Xz&LKijf4nHY1+MZp^e+1 ziAw(+u_pN(k4NoJbLkscOG>HfcwA)p>s#GZYZRkICCDsoyUU6pCMK(d6Ps`)d$w|B zn6qqXUD+LrWW zHYv-jGXmItZnpq z?Vam4UTifIRFbGzU*8=JMnwuy+h;~8aXg;;o>IzluWD7h3M`e_-QC{5dq89cr$b|` zL{VgUdvkp>9%pGDsO0dl4^nix&H1gfT_*@`8id-nw%` zmqwSS*=)Ak?UQuqHjKbRNlC^Gha<}_jtW9Z!9q$1BX2ZJrBWucffs)TI|*mV^H=bK zd3o5P4aUXsfe1yI$pw;2DHbxo69`;|jd8 z%$=i3h{%BjXMS*{84Yy;Tn*^J*>bj|A**a}b(ZBlsp=$`C#`j05uCY_HOr(FLP!^| zAVCrYFwknwX0-=7Qzg0o-qqQp^|jXse&u;qBnfDV0f88lA1L7o=`pZU9&4Lrc^oH5 zoaebEKaLWuwJS(mq|+eqg@~;+LXZ@~8skRed!Dt{7~}cMU5>R@5|SmOOHe{ecrKwRG9`q>#{ zgb<#P#8j4r7euAje&8J*929vT20kF>MIjJRj!&{AmP)ZTK@bE1NhR_uC(8in2SFG_ zmdtW?5?LwbVv)9zmQ+e9bhAo%N^4W<(hIyG2*$(l-rjkOR2D@eNf5=7Az^vZQ50KK zN+AdxovWKg6=oPk5i_`g){Tvg>o;!Xd9HQ2ySrNy#e6=`^IR#_X}7i3X_|7m3_p9m z=Sd~k*Ve2lXY(lvB@kOl(*?(X*i#;Y4E=~X%V)Wlgw3P{z}A=~X+%*to6gCS5Ew;q zS(HLL0RaStAPkHy-6c3jsVMRyC-=S>Qzp$|Jf4yTW@||Ri=wbXsEy6dFbqbc6J%jD zt@XMmCnwfe2CU_S>s&I20Mt9+Jk5O1GuAYkNt%_j`N9vRArNSTFc8A{K~t&{5G|E~ z?{OuODG)s%4b@H=ttBA8p5*cO|LOBs@A*5q?wsh9{ z@+Y|Dod*zzpZ@Lt003`!$2U} zrKh4K@q}V&Y*7F)b4f;=YV8=TS98mRg4x>f$+5{(QhrtQ3`|7x`JC#VK~b{F zvZ7dQZElX!)OC1zeEjlgboug?fA|A`3;wr%0sw#XncqLSc~dI9bn!xI2>?2s_OJZX zhu!ht_rbqWSG|GPXmGj+!|IQ=j_WXFdf0Z+^?06pNRyRyxqgu(`2z(mw@&t*s3da(D0I z-Ti|_It)U6?YZOK^N(s{i0Q_S=i)eSx7$clPgS@Z5egxJ5P)8I{zZ8H#W%n8?b_r5 zsoU+w&6X6tl%XzD0hYylG@bOka$~dEZUhm&JQ;iF!JncD#O3S2yfjYkaUfO%kjtb6a;1Dr^H@7b_xx~~1#@QPYZq!6 z!My+T3XIOo2yzMcy6g$(He<~NgJ)iQ6`FG#!?0Ww&Sa`x5@KzHQ38M^b|FyanlZR` z`T-m+z+?%90Ae8}k!2zPu>?e17#9(jELu#o3GQV1}{NSEV-h|HDU6u4$xsT30%wzvwN@%=Ela7Gxs}9=bWx=9m%jYm zwdbD)TX;cKt)jFtg`iSf!Q~=Xhn$Vp8|!NfK*0T@J_}(w!9|@s$c6XRvhNF#> zc>m7rbGzqGPWrohd$JR%CiFo>Rd@x>Q*cX!h~1B9Z;H`dph ztyWPQA{ve+olfWC#fyLVhhJ!SdP0fuXuQ7OCEa`J>h06PQEzR1JTDrZ?OdDjblhmI zg^dlQ!dP#DhM^QnL}6T(I?We@ejgAYf9$baH*b}t8IDi1Hi-PDH@@xK z%QudW_M6QnS$pN-%P4V?r^Z;fYAeqh3q@7}$&wzip< zmRMV3f)JFF>+5STj!zL36EXp?1z@sbKFgJiv%F+Bp65&HH5;wGD0cVGE#}kH!SMX0 z^&kvJ<56$3;RSLsPD^7BkM_d|+s)Q^k{3nl2ddd>ji&=*ilQ(K!trp5AcSzs8Uk7b zPUmIlN6es$f{=_QiO}t|8V#=##N%l;9+vs5C@bApr0L%E2OM|*&c8AWs{uk-8iGGb zT<=fW5OFn`csbe!_0LW;$-y5hr9gF0fDTYTBj{RUE_Ljz4i3OF9djk`rV6z(b4ANl zXQNceExUb$)6FGlq5;WWP}nPDBlklkf6xRT!}Dl z^a|ZCjh0f(=Hub$l$oVaLFgAn>5O5eV+c+>1c~VPdYI*lKfg$ zrpVy?AtJ7=^&BX+oCjePog5uUVX!T|&mR6txBKp9qXl4_t)?f{*=$9(YP(nx+T}EL zJ1imu5JDJZ5y1ETX0wTii^T$f=kuAv3yY#il4LrauJw9h;Q79aqVUG8+foX$6!?Ks z9$5msw3);HI+)}AlP8b4?(vW$s^^klVbXG>%)OV76iMUi{H*Jvate3U{e z0hqgILe@5$&2*76a~LJ#Q5N`No-c$FVGuNua6DcR+aUIfOcNOZ8HG(|JUt!wzTZrm zgZ{YFSwp^-gcHQw$#{+cagqRoF?xMttt`sZ;gAd=qA}L<{K4sI(rknfAc{__lb2-_ zD&*#Dwm=MmAn0~fUKGTH$lrPW=);emGr9mYwJEUc>zlL1!V*{u)(`?rCsP0jBHw73 zj&ml^oR>zYX=XLAZ6v3IA)<;Jjp<~egm0{sp7`Boz65LoArRzzk_rLq>pdcxj^{)q zP@wRlPLdBy1}l(|D*&;!f&kCJ_zI1}`&8VP5Y=Zs`Tx9f{7=8-o!|lpD41L% zkP(~)kf<^*S8o&5aAQsI#$09cGc&NbZ!NFG3y2_>DTRoLNJ>cncJ~8OxDqaRmz+6# z5aLhE-Aowzd7g)1?BH}FSQbf%`jg{-(s}87aj(1Xd7josNs?qmo~1l_eT?Jg_7f~}Yh8@C<-J3(|XQ8wt8Wm)?5E`bCxn>K7XX0B z0ug|HA&a7N;J)KM?*M>*{6l~Hum7zdsA|?2TpYEuCJe$L@P!Z-NGb`85)l#Yicb&( zf!2CsW24{i13;cXm=Yhs`qFnCI+M{f2%^boJQ=5tJ^ugF_U1viWmkRJT5IopraOQ0 z_rCXfZcs-98bLAwnI^RcZW0Wz1PYg`!fyJt+ZXEx|mVKfVXYcjsl! zk&0OJ$>OrM<<`a)U^*I3UcGs{y-!6c#q1D)g^?5@{+sW6Z{OFmt7Tp0&MKpN(~F0< z=Lmv|!F%PlC1+P{v~DF@())b?%^HlZVAW0{xXjJF2efsY$qN5pAMwk)vk z3&Mng$m>HjCVs88N5d|J#{31wVwkSBD5hnx3yV1K5J}pUq5J>_Eng&>-cJG4m$m0}R@9SA6;nca9a zTITu2M#?M*$~zzhAdXbh>m`pq{<@p59wjD@HI`+eQnj(U8<|J|mdm_191%*HFRQvl zAjg))XIbW*4;chwGDJ|Mk~Cc`79x#SP%rD%>=DUYx4F5^-q%&>$y9XWu1JYER!L>k zEY&({!Tk|NPcRo_^|yn=id+RP=|>e{o}D=sib~84UZw@lb1nsIDCx1pEj9NU2z7 zuBtCDr_5}$3I3sV&U+t4(e~DkCLI}due9%a@@b<&?20#EdFkzMeGA(%^okZhW%SX# zyNZ-^7El5|%Q@H2vW@X|00tBjN2)E3AgxKMNff{CYoB@U3!jhU_?c&(dG^_7pZS`v z^^9dzot~YZUtGQ6^{-DN6~`$6iLla%vs#4nqI~3$$4*a<7W1>GUzhdz*~TO}Jf0Rs zO;YV1>}}NBufBR~G#<`p1&W`ZpE=?FaHFd77hih$;QC`(k`Re=f&g)3%EAHwf^3X? zN-JTvTr34)K6hoEKl11k$WqmLKkGa1D`&N#{-~e!(mRLu#v5C^dwaKDd&yhxS#I5W zbvm17Sr0*mqrsP6d`W3a5~D~lGXQ&EZ*T2XRk^=^;4!~cwpKp#6N<+D)6OOFG`@>^QaDO|bj)u9`tOuH185o0zvN+Rlrju2snmG!&T`MH1fe1+5t9D(rQ&&Wg`%ggoLG0 zB@D9{mYA^qGK&aFLlfwhwy+L`H%b#p5<1z2s72aI4)jrGMpQ~E0Oy<|MQO4r;s8Lv zBZ4ssDY~3aNl_AITILK37Ny5y_*?e!%S>!=U z*0Y?Ro=-N$Q54VS^WDAOP{k=CQ54OuW}%Yk>S~r{6KLFh0D$>o;l1D5*`8irp7Js; z=<(O>IS}Wpt!qWfizIOZ7#25=Kt!s&!-K1W%zSZi5l2xJ$Lzh*+UStT7h{Y*xN&rJ zI37>xx&{PmZBj9BQS2 zd0EsZ9uUIW$svf!mkS2Tvi^L&R7%&@3h;0=Vgc^~(G*1$TD*iyFrP0$K#|cpjbk&L zPKzQ3)UFm%$~sF5G%*nx6CwE8R`dBhj+6bp-Se|^=XjaVyk`J;?6Id_d*xT1vuTnt z^LTg6bWqhb`$jBDDP2`n9LHr*#ioAr`je!*DW|oymzU@L{=hn^sw$3H8>q@^vaxZL zFG4iztw)3q0H2>R0Nt#57an7cxfdm1ORAj9c;jOK) zcRX9#?#l=*SMkEmyQHU&pRaF@siGUZ!z(Lz9%VMonY9eQ$ zES;@urIfY#Lv7{1_}0KNzw%4}_>XJE_x{`eUibRp7QVBX{~v&Sr2z)H{|J~ns=;v>I+n@Bl8R0E&|K^MHlUHxP@aa$fv-N%6@r~~d!s>0F zxbfuIA*2?rULi{1Or-&G5Zg+w@PI0<0UAX{5pmuU>Q!I`fJB~|*_$|KW*}tm!VgNz zW(=8F0Pvm(h>=(bNlmX70PEEf*_LfUqqoOE^O=PTRX+jbB?GOC|0Q`mT z`GK?3Bh@PPTwF{yH#etOQ}CRmv2Zon-N-K%zVhH`vU$yr5ddKcUAnt~FWe4f<@E`mP0KD^^?{5BvRNIn>E-x++aXz0b zrLunSGoSrE0Qk9|{n?Gpt*hCUtLxb4&wS4Z5s^iH_Gf+)08Y=2m-*u8_@0o`AZ1lB z%f(r>y}fm?zl%W5+1lD(nmKEYF#zyi{^$S2fAin|jZc00({Fm?o9^DdJD<-1;KzUB zM;>|~3Yxrv*k}Ow#P59cFZ}!8y}dm=JUn3n=efSB0R1C3whiH{ue@}*tU;;cqtn=^ zq9_62i607?;>rB+~I2amLX28o0u)6h42O4*5FtsD zmv6pOmQ|F*&iT!)$$1M*Jn`hyr)Sf5yyG44+~@XocZ1Is{sTqTwelipRbAI#`qIs3;-1!OV{76q zn~0Qx{e#f}LqWX0LoZx6p({E{>xn*q#WcHhXLtY301m#o32We$`~3d!96iLBM+5;v z@+iU#$Xz}y%y3(Byf)WsaxFn$14y%YX?iCkBB2T+tl%M~6flASkwQWQ1;9)Vmfdo& zft$r5{4517Jp14U5{h{5Y+VV6CIu91iFAdhiU<|8t~p}UUxNUA6J#{W>T9hzTDLvf_??e^tUnmAVC`z}d|4FJ>1Dsyzq*ayS$vuuExVmghd-#RVZCU>qA2X{9iV;_-MKMJCS|_jzTl z3vqQd*BYI7A%a5E0~lFynAT0 zNz-(1XXozW-8ePuB~7zy*Y@U%IY6-I1faZ^vb3X7dVF%~IV92|YoR~LtaC|{9^O4n z(qy?PvN&0~x~g27W@S;V!@_YC1#{xKzJ2HR#>VD+G27nW3z%mhC|5=0oI5+a==I~x z8>85y$M@zYqDO9QzxL|+?6THcd(ZQE?p$4$rP4H=UTka)ds!BlsB*rs4I-ovdBFOMRwXj z*9Kg1Q<`r*fUd9Bl;C4F;dJv09YzyIlm;blXvp^s1dVo5^BN%d3CxU5#~-3*vEZ&~ zwd3Z5gG0h*wQ37e03?*l!3x!C*cUD1Cge4{wF5g}xpA1oXX{H~Gb8KAFMt9_AkFXy zq5QVN*0I$lVBw~dG@!JN;?_#RkkkQC&YKvooalEi|nlmal+6bpyNH#C+KXKNOTkWjRF#pO{B_Je(0D{z>?}MFor7c!NSa~4;;#|F$Sq22sP2{plrZ4~mjWqENQ9#&v zPSUil>wYhL^|iC{c#MDIV;3M*QPh*^$w{9G#-kCC0`&cUPZ*TeQ51)g(hvZ87Href zgF!zqbA*|c^31ihS(+-P0I))ZsKVmotV_)2jeeI#B!Zx3L0aX@s@Tj za5z$gh`?EEaPj>h=0pS675cN;~feVVM_koM^2Da9Py7e#S^nARg1o<%s#(z^CZnjxy?eD2sQP+CJ- zdia;KH4*irPrtr-!0wkydF6%A{r?^Dj}h4cfcN~l?*yUF;;$nP006K;B9J=b`ASc> zO*V3yjl_l;*ZTD9TEE>;L`uYmG9?Hdteftq(qbGCoY?UEcV-0uu0Q%UxDJuvYW-_d z1PWSN-#)uVUV!&P3ca<}LwK#9`uMN>^G)45-u+%_54f2uk&rhQ2^U%c1dv{+c?|%d zlnJPo)<#4~g>|P5A-bklZO@c2tJI*zI2w)Wy4G3~Di6+j24ohnjX8`3TwJR-+HbdRo0o)kbJ8wmm`zz4fsQ(KbCzA4%ufL^bs zwH87N4dPZ#gs}I(5EL2|k{3Y$rOfHciFNk$^whF_>)YOX`?ZG4@LhlLd#)t|>wKCf zom5zW@WNJBWtL^kTvTQF#I`7&b&j+;J3I62r_*U1#~WLlMcp)VUe2zN{bI3j&h>h| zUY0rU%d-5oZ+~CyT;J72xlF4h$p#=CM^R<%XtcSzyIYi19LJ|;7rVQ=m34%;To!R0 zcb-QSMYnF<`s}mMK5%>dgJwTstRT zm?s-W2x zuzS#)MTNb{l+S$a8x*B!yfqk_=b!sRRaMunUl-4Zx9UB4AN~*s zAu4I%MrLOA0)8}{Y;JEA)$J&X_V=#|*puT|_V)H?m-C~$CzHweSAOX?-}}BlRmYKu zqN~~T^z>qHckm~^@oR6rcAHe++em>zs2B4(>Gi(w`PX_`TG#HWr@kgjBWkNG9ed|} z=%Cc^kNdrTRo7`etg2G5sAlCurV-%m-A)uL| zZ*ZGGYP|2(bU`Q1v+nq}{_%r{B?5q+y@WQ$_Xh>o+G*}jB1O7 z!g&QkhVS@~h(wx&MR+B|i-6da8g+vNZxEXaBVmsS&eeNWD=tL2DcETR9)m%ei5o1i6WKqQ4SpfhcQYcP=;9xlP-g(C! z$$8c~a$fSQ#cj(WI5lyeIoO7pV zCuthL^2*K0X!wOMJiocIp;eq_an{SSEb-1)Rhj4I*7g<>8DpxtD$BC2Yb5Lq2ENe) zf~u+sfQU{{PSPyvS}xYs0>Gf(`-9IuYmAvrr)MX}*REab_p;ODWA@%NJC=UG$0CkB ziWsfRvQmUE-+bkX#~&RI1^`f&RTM=;R9hPv6I6t>)>+n{&*v|^@Pbmxi>hpO>&07> z&F$fM;utlcR&aH3wza)A9*+81!p@zZT^$` zV0c_@Rbs?50J_>$RYiztmYkhmEEktI9@`e-_u<;>Pl7v4!Z8g7n; zy=<b#3n*+QrN%WumC3NI71^J1+u|rTxKpM5wp7dv)pN zizyg;b#?I&!@aV74cLHw>hb=3CMdA-OfH z&4ILCOz-!@Fz{Z&Q!COurwv2{ZK&R;$T#+tLa}G-TsP;|rB~b2#)fOi-2uSYFRk}Z zL{ozc5rWiAaCg8!KA*^US!Fdye<#O5Y55uIOh(feg9Y=jcB>+|J(lnH*5&&k| zARNXwUNVvq=SZX0y)rK(2BowJ#A#X<6)6QFxdNcIV)jj7MW~Es2Srh)X=>||loF7^ zwK$IS&ELO65+%cwK(~uycV)U%?&@_I-#MQqDG`y<9sokX)!uf^4b~Pe*{Yb&=UK0h zhi&BIE(R+xaWWHG3xW0FFb>uvh^ISyI zxNmLky*DNj5d=CrJyS$lYiH%(_`k5&F!xTZEp3L{I4YeNLdgXL>S(}Kg^@y&i2Nxa;GZv1cLLDkw!la|7?1D6|Mcho^tXR!*CR@?WBK1Z^? z58l5)vheH? z6o~cS@9y7-(|-5BBht+;J@?Nyb)Wj!SHp4M_O5Sb7Nu6ru~t$(p*QJjHk$AN5s?)8 zCcy5hmY99eZS>#*Bu@qfc`dOa0GRc9-g_r5ju}xEMXAk$O$R8bxUc=XA{CKYVyt2# z=oPcq2rBLxWUg-wJl{}T5xV~9fsO|7^MCKhztV)f|2zM(ZUR_v?8lSMqN?8T#;@Dk zJNVwe_#FW7zW0CE#2C_A0V<`UC<y^?ZA`bo7us&q>i}G&(*$ zR!TYN7K=sFYjpnh_V(uUc@jkxNKxj8NB815X686e22mXDU_vy;cYn_ZeZ68CRL%)06E`K1yVv%0 z6rs|~ysX(5^W|hbVw5=22$sDEl>LJn9pYn*V$W$Dmt`KOUA_%OBuoDYA;YS&qtQ^I zI=pi?eBzu>l4P-1#Bmx$+FE~b@aXmHH-7xb{??n`^k!)*MxK1)X(YLO_b#;IYIi?W zRdsrrJD*Q4mp86IQq{}MZw9~r;^M+P7f8I$)sH>?IB7i^O;&?+`A0+(>8-8pG#fAS zWytC%iVXF7>E_YhQ>7H5`shbK5%yG%2on5G$uj}tv#6x*9y51qZ~)y2wg2NQ>Zb-nT% zzk=Ov1Y0`0-JNxt#cL)ckl=`@DX7JUd=l8u&}1_kAUt@yNJ^15QLjzPtt|99HjN1E zrD=cB)N(dfToDCuHCSC-(;Wn8`XvW;M)0nJ*GQ-Un=)GfXw!pDGo|qBEuh~Lb|Cy* z$l7}6EVNGa!|zuFK+Lip2rTnOC}nb0i6BL>2pR|ugLb=}X#(W-hD2cyAR^0Ng^6QN2qGL-acFRy5Z57q5W#Fd zOVZ@v;QI5=f8pt``I^U`cq)!!_HH~HP9~cGB-4(G&E7PSS<1)&-%TpuKL5l(b2K9RuRswroVsQd%iz%RlT#Sh#05Fl>9&f}+KQGJqGI!4H?i}d7N2gauWw99ahKpG~ozAzn zCrT5$gmKOuj*bp*+}JuhIXgbN+TDJ9es!o2ov`=dy!5h>F)ClqiNG_X7b0K}p?{h& z5da}*5m+uu6iJe7nO|;g?LO3yco%qr*h=6&@HjNjH>`Q9!DO_55a|BaS=A0<_;Pe+ z&0@4>4DTbzw1ce(DJuxNeGko(-QX(NeX&DPRluy_B?G&Vvk^7ED^7$p&kIt{N&lS=e+7T)WcJVk4xIH1*y$Aj290LPUh5lwu#` zS{r(lwKk4pL>0~`WQ(IHcHR>ztyQ-KV;iU-Vw$FTzGyKlDa$g;GDL9BX%r${PRp6M zN*QD#?m7>y*fDE2Ft#2=b1qGoi}a8xrWRHg3^1Dy;#paiO|Pb3dhx~4$(u*x2@&>s zy`m_KqR=`brQ$g0^)mLJh^nd_42DIK6Dbhz?6ua;T1J3SzQsHojVLrc0m$S9J|Yab(J(bk4<*Vb6BGik}F4bF#)ngupC~KZ2;WR!YZ_ zzBn(Ovr5IxTvgTVYQ9`9gWKes%kv_j&su96d!t4G03ZNKL_t&}0Ffj~hNE#&+)a{f zndj0rM{v$fr?ai?Ep2Ex92_4{)1)__&u7&lwbmFD5|GSnv}TsNvP$d0Xt?%x0zgAC z77?v#VUAm8o17q4p1+5n={I-1X|t^9a0nAMBO zL?W2P*?hKCq{BnJ5-@4)nj+1DM(Ze!#7hv61@wfvC@T1uvo&x`9LFFMG;Eqq%ppU< zE6p%zO=oM9Ruo2R%i{&r6R&%Hc->5H3yHU1T@e}(8rEZjK6DIB1OXD1TQ5Ej0PG!+ zlKUgB^(}N=5EyRVM0J+E z-G>ku10S1Ku}~PW{ar?3K@{&G!*SmF4NX_(H@@+W z@PGYd05C?ERo)wBhN5mh19wJ%(G#OoRh9O7kv6GGLT6W{h`!7`iwF{;BIg{TLIN*f zy(fjNEqMXbhDB-UDuKiIpj{GtSl65n6ZXDjZmnP{a ze*4$pw}0)IfBmCj2SOYUheg>4d|0=VTkf{kZr^$IvB#wqSBCbc0)RM)E&G$Rvn0#r z^EnYMm&>xM-um`;e)iM9W1^U4UVA5iqruR6A4jqCe0en+4GEdkBw^1N7Z<%aQd$*N zQ4|F;tI_!A-pS7P*5REylkLsAu08X7x#()1iRhVUUjN*4pI<-DewrMgoON%1_=o@d z@BZ!&P^sIDlm}QeJCJ=9Z#eO(xFalTCs8p{v&~div zGS+$n0PxH+Z~WpHR|h~uU2#g<%VzWW?$)3z^MB|4@Bf8=@=s>7+41pVo);qc^wUpY zUY^HsZ)6^G^Mbt$~$)s-|&Wm`J$X`Y$|O?MF`3{ zSJL(6@d2zvVqEO(NXyP43=aU99y@E7drKUBKUQguADs zbDG;4nP7LJgD3DlGbml#OGFW9B+}dB{mzJCD|i($kE>%s08~kmZEhqD*Sf`)rFAf1oQOHKR4S3^gf4Z0U`W*3xoIg2x>CST~To_do>V0T_?~LP9dY@66tV(Jdq- zAqOHXjg)vegV0+L*Un;nTg4ti6dIoiun6(W@nmN4!P19m3H<`Bbqy`D{SyEx1pq2b z)1oK^pn=5^okc~6s34GlLMB&h4$}3A(!kKjjR=oNU_@DK2(mIt0saZ=L`VY=5D*%p ziHHHgTWE@*n&pNa1AwRiKZ3P20wB?1u^4Y`gzJtH64}h`szu#P8yL4y{AntA1x19E z7gpi~O%Ut~Bdmu^)cOjU^F7aBu+$Nsjn9KQW23-X_g|< zbbhrlo_O}Qwow$-RSf_q$H&GP=Ugw#0HDl^D2c6gRc)1)NW?dMOf1U^M0&k`S(d{= z|LpW^XL}ogk|=T3GJw`jYgJa2A|fOaj^lWHduKMg%9o3?iR|y~ zEfxz80$kVDw?P^pVqH}LKuU!)*q}eKwhnZH(P%)Cjw1u;Yg?Y2o+40@=eDkjBF{Fq z=8M^4xh#uvJQ`n3FHMr5kOPjQq}S`8U!HDmY|XD`ojq~RjVBXDG@Z_3ljZs1=B=CK z@hFZ4Ns?Z_@yK(}eO?(#qNuhuRHhK=+UBtG90>veme_m9i()w3S>{!mq#>6L09xs) z^l_p_qse$9o?YdmQGYR;UcbI|a(d(}PA^JkJsRu)V3uV?z5w9SXmWCPUY4bGfIx8) zd*?*JI}z|AtcW;NSE164rE-X*NS~ctJ=Ao6{KdCJi&J15v#&k3jmhZX-R9A2p6TXA zTl%(QnExY&QY`3Uk|+Xr-yPQe#1B;010__0?z%Jk-z~x`4lV zRNEa|H@K0WYo6nX+qx`^4@HfHc6%yo35n*X8wBUQHrLwJ z);7q!uy+m+gD(+I=suXN8!Fsnq`HgKn4>Uh0RbWEEU>K2T{sW{K*7~?g|lhaQ$p-0 z<^Ze4uOQ$7u!CttL@BM5HpWQPnyR^yTI&!qBccFun~3%-Cei`MO42kG>Jm0;%9HUV z&lj-z?G7Od#kBCPw-f*|rhp!&^6UGn%Hp+KXKj*JHyfBJVi9N*cYwP+u`B5nXw_uu z+9pYyFPD)qv)PO^-0rku=R_^P(!3 zY1(s+JO`2~frtPnapr6-!iqF0wOq`@Dk)*fh9IB zu)Te8adB~e=Bz(D{4E4zl&W@j?%W*=1}J}M^nUlODN=;Qj0llZZhLD7QEQ#WF`b^A zI_Cz%ArZ}Ivp5PYej$ZbRS^x_C!S&Dd4dQ7(r`Gwnq47M6h%=y7OCg6SrW&~WnL6@ znnufI-tP^n${9l^Czrh}+uxf+k(pjCjERko=F<{@>e?4&4Okds05J%q2DTa^vIq+! zl2S^UNGru2w2F(uim-Rid*-jup6FkEYhs%qKovlhwgVgkBB&NkZx;k;JoWo{4QoI{ zM<@A;M=W2t8(;VN`aVS1wSH`Vs8b^g76$-Clv1I?MW{1aA2UEFUH>9!4H&Me`Gym3 zy#JQG*L__?7}_qCYhAQO{QB_#03w5MOL62TyjVGqD|o93B^XJFv1!gtA}9h1+rg?8P~2OVzZ4r3Q#Y!3NM2tqf^GMIfz) zDBUL_@Mr$)`>}RfN7J+O`NhS-wF4kRmN-s|sv^*!LR1u!Hl$UTu~0-^ULmM60dsKa z33O3Sf8po;r>}H3cH95{kN$r5`hEZIU((62y@8rLVU{mRM_PMkF(xKlt-IZ}y}e_t zH%1Kxjo8P=c2hcTo!mRVHyRI@%fi;K-|yc&I!uzZ&5N*QR@&4ypU!4l=^`(Cz4Rj= z{-*%&o^Stiy}#raA&;IOBb+14CtM|!Kf6Kr2t#5zJ z*FE=z&pVB_A0vn@7o(koeKW%U@r(a!c=3Vn`zygPeA73-N4y87fA)X>A_V=>we8hc zZ+5T$w}1F|0pJ54_$z?EmuvvQXFl}__|zvJdW}B*@sGXh-QO5qYh%4{nQ<5dz#6{N z_Euo+!aw?7nrr&oANlatfBoA|kMF+yt#AE<-~WuTh$s)Xtjot9zo7`=HvzySfp8~K zO@L%He)0Lwuu#_Pk9xYQFMs-{|Hm&su)DXXh$@QGi?ce36_F_IC!6ujm*=tZMA6>< z=AGA0o_+S&@BO~-U`F`d=Kw&waPWHsnAx+VR?j$&VgV#@MX@|TIa@F5Ti=kVldTH2 z#dkpYs$R0qVoA$(Yu^R83jzEZ8)QA#*TC=qfVhI@S4q6Cbierog1^L=z|8G5Z=2s%lAEhhldIFr=W#P9q|a;s)9g zCk}uCgh8CGs}Oe(g)%iH6~HVIk@hYE5gCt02*{q1fKYV{Xq+U_!h3`?pUtwY7nw*Y z1tQMZky1iR35gOEt+j3pUVGbi34I12=4KKIop+8IL$=*%c5OPFmz8yOnWb@F6=!GC>kZFO&UBJFW(Vw;wTWi)IcPQ77~gvB_SVjB zzO<)qrX%CLcdjPH(RkxxdS;!qBA|1Mw5AB!)K2j3ggI#EA%gSX*7aaGw9b0x(tf|l z?Km0NH7BtKhF;o_;^^@3?%Db2XgIlZ=kCG5eqI!to14d{cbENfyoL%c`ujLL^-jbsWd+tKo2bc`?HvKT9OiltMBHq81Tj zw1|)*5mcIxbX_kVYD)0;Aplz)Y|*qDYue7V=BBl^U)?Z$1!L8@np-V#+hZYflX07Pj@PROsR?rm4wh}g^ zWgmU)@zH3^EtfS-Q|CcZgIk3p|9CthMSw^ubSDI*v{FiZ(@DVEI!UvtE&%}u#W(B~ z?;9maW|=P*!t9(QL>68ymnMp|*0r@!Q~2M&z0N!De5fr|iZ0GC2ZO<2FtAk>{2nq2 z5Ip-fAu3y2+ur-4$OYu^?qQl{n;RR}b5T`UlFVl_MDX5bX_}-73ma|v!=ZO}G#Zyh zoiB4{+1eggwn(E0nUyw9d(|IBkvY6~x8Lgnq9QP94@oJ5%;YPw(x$$==Qeeg#EDj_ zuIj~d5#}fBWo22L$fQ|T6!~;|rO1?Jxm?b(UZzMbmy04Vl`?z#`{!q8im0yZZ~M)y zkG{|D?QJfX^H$`JT5%80!pwYjHbca^wjy4{8?&Xg+1T8?bLS2sBuN}9ddK5QXgZc= zS&`>0T`JsW0)SDR34NN38I=Umcs0u-QL=~yqq$75|p-Lu00osqoh?n@rc08-k~w3ey9S&AIJ7b zH_-la=;WbbN{7g_A;4E`xp%+u0(jVBv;Gs-)=|{dC^dwX&K?NRTFVSXB=ntj%=)lv zAV?<%zxwVPymB96(j8k<@WP#TOs7td-uwF}B)~ThIq?qM?smtZH|)C|9zJ0Y{q(DR zr(IC)JNNdOWo@6;Q9-+!F?(hg2=*cjNn0jRySw>{Chw7H`hn_ zOCS6pApmBjm=Tl!Feudj!S{UsKlquS_-fO5|JLjElx|U&Swl?N*xVLGM$gDju(rO_ z8R<5qO_C+WG8f-S#>5E$zz06~!L3L!_lyCf)V({G`&*kQ)iQ%d-M{MUcu`=S{C`VajS03f+Q zz5@YUyDT%aivomtee>vzgR|4=_RjE^|IZHtz@txWBH8w!*n1m_X#hZJ(h8n==1pJ! z&UcQ0y!Q&_>gvh^?`-cqbT-slWqUJ7^JdM=uKu%1$-xS0K>$(rRmk6e6*}`nE3?)9 zp4_)nFskh!%&d%A3HL$cn*jh&QWL+m7t8p+I-<}CuDf2oM~*a5^{x>r`|+4kt$U`D9>(G_?e9BK&cn6+8# z(xA{x(pnM`8t=J%*G*{{KAgN4iy?8100JICxd2(z0N|{xi$wsc1lSS*DeqeiV?+QJ z=6pE~kQ!+n=Pd)XvqV~eL45EqxoQ1JA`qE~MQU4VF_+Uz zwpJmKA`w zT^s>uNxDXx>rXsA9Bm-_)1zA-`)K*DKlLrZ>iFcMHynD$pa29b4~S%~wZIO50Rhl^ zscRdji8vRkP@S*0x3{Mki#UT#>c_?nN4>*(c7Ac%-x{CJPkJf?Iy_LtJ&4*cwJ z9*>3^tu3djH(4xZMjMS(mD8-3CQ)Pzus8x94TlO45X#aDbITm75l|}{Z)9oejgi4% zdt)<+V*^N8+6Q4k#q5!2Z*S+-+pmeha1@U>Vina|SI%9Ql^0&HCnBtEy|tTNyJ6~D zvSd^i71I3f-9{gT6foznfBjRSEDBt^wpmrvM+bf8^u-qz7Z;a%uYauHfBbWQ@I}Jp zk;f*l-n{qb$Da_X0niwBuDPjd=c8DAas7cgI(ji*a++oNNcFOK_xjfM&Owpayo7YOOSBZ$%TwFh{@}BB z#Cyk0)=fkZnG|>@lZ^=gvS&g$K0aD37TbFdFIFO?rh=#QoT*cLSZy5`-n_ftHoyv% zX!pkMYuFa`NMnAwp+uxH=UqRel{s3|*IP49t6z|nJq*!O2UUb4;x(*9nqC*eZ3pD` zPxt$uL_{Fi^7~eY+PLW0zHbj^9oBh>bFt?CcA3cgCg?tX-uk-Ms4jGtez)np2iSII zZX$C;6wrv5&bG^8Gxgz|-%wKnH8#u;>M*7TSwccWVedm1zo2IeP22Dw8!rt~ao+NN{Cu1 zQpD`*&}XNv7xQ_fby=1FFL7@kbz4%@iAF@`9?$rVcdRO^>Q+&JfXF0*f(jx?+lb?{ znUrTM$^si7?Xnd`91umG`oz`k_`unAYQ#r7p~xTwGOS`KYQ9xWp!d%k@#b7$t+J2LVY5x+?D91x7LQ4|UID2fnK>qzUUC<;Wh&aSVm zAz`9pXRR^DdK=8sMOBt%vA))K-i=42B#pdh<9w^r)=E#OGsi5R(?}zsF&0Ucl@$?V zO{60WL;&m^BRJ<#(R@>tddEc(vDN{IXJ5P12~?#;Bq7Buta6D2h0WcK5ah2m8*u$z-CGsviab zLbBG0kahOOcU+i^hJSv`bv*~5#tG+<$N4aBgJeTV^bVfFx6a?wCDEX_D&$@WWBC+ayewfQ0h zOayDD_p5f2#vr+9ez=eMZq#%L65=zD!^p1wIqm?Uh>lS{^{?8e&Qqogd~aD zz3yZ(DT|qo)6rm%MNzQas6YdWNSbt{fsd}_q@hcOn_hh70jT0J!l~U01`#fxtkxeVv2(6D45AX@jHL^p7ZA)j6eH%#3<72y_pufTUW01 zy6x|K{dZr!aPgXJuKCc1|7mmc#F=&uH9?@`mg+tFoul{x3fJO z3@0EFk^=OdPWFet`!~xoo$_A0ZKT4GfA zt4Rq$)A6Cutsi^y_lU64td$ZGrS)V~5K)q*)>o+-1yh+4{Ad=IyZf8UksU~o#(Qbb3|NOpSfO-AvetG%sE9)#^?!5b- z=U3kH_E%|@F$;<#9f`;rUiXgqw?Fgt?_1>xu}(OLs6X`yX_N?d;Ft9wZ}jH`cL0>ca~QG1_0tHEwB)9H=euxp1bd}){;U~cvE_7 zW}^dh@15?#dHLmE_2)1%J}Kf06V?z-#F-u9_` z2-RrVuZNCit}4!R0t&#W!)R!Dp2klPL@P zTA#0>9`7C0hCu+4dC*$OI{+*QBu!)!5&GcfQyU+VeegXzq@h2;{2$R+J=dX^e~~Y+ z?NS4zhqP({001A^xTVH|<~L-N+J|%w9f^o|FW{YX;ysFp6r>c_Hqt;tOoUiWhwMx_ zn*gfBr>HalC{j@p2mOnb>h=56$xtg*&sh;5C{lxiVYkx>Pz%hDb_j?8n_;X+PBl9y z=s-e-AP7Q)R%-8~>1-ND$_MtZ;Mf#oOieagKVaQnKh{Z_#NL%p{NgXU_12F*weo=8 ziI1WbzyXVAHyTfzw*>5+GgV2OsSgPs7wz9k|hsCT!1WiDSvmBJ-Bx@1M*=yD( z)4jB<97ZxVgi@7L@2V`-?EJ>5Y<)d8&h*#2``ZH+pC*nyF^f`mG~7*+#JjTHZV^Po z(ZzN*IIBvIChgg5VyzvGMj`08a?{mb_xkJ48dr#yRtv%^_E)m? zjjX?_t*PReAJaWaN-L$TP0Gp;wUweIj@CC$dFB<-MC#(js^32mCE8iHy4LNl#92!# zL}3Mhg8_)x5UbtmcgDjhAou&}$&)QW29Yz^LIfv_N`#d#c}GBo)Rb_lmE7{!lYnmX z#0mkPJadW#&T@jFhNGQySdmNs03ZNKL_t(5mj~CJy*`P3E00C2Gq#n-A)r-jy}rIG zU@0nqJt{(hsH54lh+5z5OeUjQG0a3|qQ?*gEjxhiX4D^7FB%Ch=BEZ}d(5%)1{uZeb zhg#p3I-{G^*l?Jy%-44b@|xrQJg)$AhaCVBhlsaDjkhDzX9`k;uyFhY08Nn>|JcGa zvo#getP4KeO)1ql88vKU0?b^QLX&3ayq$%$2|M5s-CmlgE=rP=;kh#QCWtcq0TSs{rz|Gt5?_?)N$;Ha8-z zdmaswj@jqD<06oCP7{ zY~E_IfVVD=BV!F%iQ?E8bLzy&Vls+jt${4SbTUN(5ztCcXS2WuFT!!00Ptu$K@jIS zPH2C3x7X_s1wso|RE9+W<=|l0c=RM9lIO{2G!l{1r%rBfZ!saqdODqWXYy8_#M!|f zcyH4rMTLYI>ljctrrC_4c0eOz%0M2clti%-Q72EGo=(SFkuaoj6ppa02~ZSiW(Jhu zXwYhPLmsHgSpg`Eu~N#52m*WmjsJ8aOwSqrdrzA*3QmAlp_Rv^V?|2DG5fW(RU&oy z(#6?yeEQU>qL?1+4+M}woOicA=P5x4*xuQ~@hEsiNR1{UDYUk9b}E7jAdRUkM+n?) z$8nk=VY?kAN%r6aS6GlpmtM5SEK}q0ERMARBC=AVNQsEGrq$MKtD7Ql>Eb>jf)}P5 z!VC`~Dvbh~lpqi(1TM>}C<-EMw_DwA>%s#U;s1kD!!dV$?h!I5-Tc@mJYt=H+w$ng zJmIFtJpQiRKmCyp{N?js^ipP4N(G2_Sv=0eg#w-z@W?r&iimZZIc95Z6vv1P#4k&( zAV-sSOt%Mc+Mj{e|x{|*4Y?LU0A^YX`k@c#MjzV&6#>UADB9c!w#U{rxX-cqMe=f<=y zUOEsDT-qDXJ!(2FF5JI&_L>vU7x#VsqA`pdebsZHYAX8R2W|y`$!wp9ps4azZjDRQ zBuSO2?9R@<)})kv(;Mp`oqzt=CwI5Um6;lAqd2*AdFykZK?H2IQxHzG1OQM{5YOUY z{LL@=^Z)*y&wRQT9dGzg?||byxx_Z8`0zx&63^lkw7nVV9P=(9-h?~u#hz(k4GynjC&8&;c=ZW02Mj1?6~+Cl!wKR(6qR!OKif^00V*% zSQ4aJ9uLU1Efa&Q5Q;FW$Xg4*&Km%w3?OL%u}Ev z^JFs7F&Q^Ybs8+a02qiD5HL=38dJL+v6Q5ASvcncC{Pozk0(4HO1X>&p2nSMI;%mPe0<`zKCx2m6peiuQW_lWlGa(4w!7G0$&x5%q3NX35tpT%mE)Uly0$83)_NVQX)#4e z_I7qx)=6nom7^$eI*zYg-X#Jr?7$Xm(WsI=1t84wzmgC8RPKv53 zTkYI9&{`pB=Vd&e6h#%qI*Ju@+Uaz~8D?R|Q>WJ2Jp#0z&BcrN=bck9BSg}Q0JL*1 zWZ?ynJdc$kMCF+Q9J5Dc24cqo2rR*qiai0NbrWU-?3|s7c*NMT*IEbMh<&xv>t4Au zdf>hb>zg+Sd!_VbI@;da72)90cd$Qbw>O0y28S%AkTHZQoH@PH?`NO-#C?x{!c9q> zDW#&=KlX7q0$Kt_MF2!9s_YU@r2;Xu0y-#}5xg-N3B@%lld7h7L$O#od z1WppV{>D>x-f?+nXQ!2Qgxqv8sZ6=La$+=mD9`qXMAEOm_=P~~4}-aU!FxdsHW*`Q zzs^a_$hh#W0R(DJ&|&(*h(wD7(oHuFM8kr_b9b1qW(`;)0bc-uuO0q%efL9NGoi=Y zX=rYz3^$>gIfoD7P=|-{Fy*kmef2T`Ue(FM=_l0q0&w+X?a+tsvn=fE(|g^b@hk;E z5M&Np33%tccOt$lix41G(qv)1ZH%}o)-J@9k+AlP6e$%DJyj?O?u`tnDNWPHEfT7# z5(u%kG%Kb_)CIucN)_Bw00B|gVEX)kP&)@9u$-yEEdT&3co|3lM#JH3I=<(gd*|nb z+978Vs|o2zA{ZmZj4Zw36vKmN~8;b#i~%Rn^0g7e(z_K`G_0};nEolOuxz+3Og znm}Y07+0N_B#PKo1V|AnA{|SfkVp(Hic;%b>D;)O>I!-42A^yWxQKyq@ zt*k>*Fc~>gn4}JW1!Gx9MZE~)1Z1x8;rIXos6zG8w z!83z%?M}M7*0Q!*-)yHzf(VE#;<~+<+3P5E*7W*1iX&k$#wJOeW-UaBVsq+rPe8O* zNt%pDPASe>BIwpP`bna*mPQbeklULEckhRDEh6-K?SuU>0Bme@S64L>3M<038siM% zzk*v=Jfh?+2&&Kx=hj6Sp@)Egi3o~x0La?Oa8#VVW~J2uMM?lo0h^oc@o*$4h|uoj zq@~*@5rYVMj(|Em*?_&>?E}))iBtK(V4Ea9acbrFuRC$`MvTZT9HqTGZXedc~S_3?(NZ;Gn-i!lP3c=iZToa3@81!Z-8tuofwqbX?qtx65Y zoV)pPci;KhhpKe$=EvRrzmCP+aPBbxaPQr>|I0>p$L+UWf74^;e=hlhH28P;r{VF1 zIk>REFT$e#A0O2t>70OlWvWx4%mIAG^&T9nGO>E>}IeB`rsX8Z(c%m}BJB9HZt8 zG78ay&|xbs11KaQBJ%K+U-Oc`|LZ@626D2_LbKJgcxz2CWrQTuz{1SG{%daqfLFif z|G08tPoZe#+U>L`XK5U_+Nst6;8|J0N`QX*H{S^WfAv>?dCj%gD5bI_cFt8*bu>$M zm>;52vfArBcvt#xh!Vwc{f#SI zm!z0ZPi%BEt!C3HC>#t&8|&*>f-UX)|Mp{{;WvHTS4T=`NghJ;0N|&7?mHEWu)OVO z{>OZTfBXmU3!h&2b7`-sCOCO=?aI!Dz42HnL|`4KX__!wBvC};(SfNP5)Q}1 zRxA0N|M}6YhyC+EQ_t&1f8yl;VvV!5%Cc6w-A2Tp{PA~%Z@=r+FFe)GPn=v6kqZy( z7SqBSh~q4dw0NgAT4MkJQAjBfKb_8wU8Qe-*>j^Po=#?2o>WztT)4Eh-uK=-=c~T- zAKv#70NA>65JeP6YH+}x{p@{;=-FSnkOn{WhIjnLPk-l9O5;Ox+LMXttaR1#Pun2G^B0w9ytkvN;j382Jj zHY;Wi-g8kvtU$ZnDy!0t25F3WD^}FfF?d&L9j$M42?0Q+ld*T$?X-4xA8fbVTUWMQ zd1{SgmZGS7ZIvVmNKutmYt&I%78Z$E3?VQ(r4kWPN}avt)NnZ1**-wjru4H}6=|I$ zF#z;edTF9eRi$a{JtuLrnXZpU6A{U>q^e9=mD9;&TFltf!C)38-a4l+noNrQ-C+_Z zqyRvigWcUJf@ZM-vbVo4EW$7z&qkvuAnS-k#2Sa7SR_uA_l})vcal1!1DzrY`N)y9 zbub!^`u&W>^?GfskOeep5f=9BnY{;O5Cl{JVk$QsmuV}6sCZvLmMkJ^nlQ_B;>6?1 zMmvsibEE5cDx$o25qB6P4i5)2c&bSyTpUMn1WBUPydxFd^q3P9@3;0DiIvtU7{!{M z+TPwjeYPJ(L=+?1PPaQ64f1v(g4UKuAVSXB`LVfn4`Gk!2?POrfj!5bX5-M zW6Qr3Nq@Lb{>4R_iW%nQO1}pdROBKBlJWBTn)78glhBbfg(Vz(^L={#Vxg>VrVDB^`y6 zj@>aD>;?e>TiSfo^ZypVLI{lwXIT(n?=f5_1VD`%3E6uN8sSm|4ntxcr6UpX z?84TG2-HwCA_YykHVQ;hox#w#AfGub5sN4l-0FdujcJ%!myZzvYpUTkCPL>-RThy} z!RLjU0l_<02f?9$c<(D`XK51ah!omZp6`(>%1O7=HqL~Uk4ifbEDEQ{I}tlD%-rjB zB#=uG#1VB`y@4Cn=pcFlAr(atB7rx~Iu?!&x*pk z*jn4^L|XgO8m+k~in6qxJrYi)<5@9g24Qv%X2nQp1jfoZ0C3(3$gCK(+bt0r#R2y9 zq)BP*oyqf<#ew)Ni^9X9qqr!FZYPTp$kJ#s8TVHcLH}}pB4hCtuqDTot6cLDo@bQq+x3LTb@xn?Gf!^C4hM*G>0HK|&gOjJ$I^DLN zLRC6z!8qq^?e#1oVe_38LjZ58%33p>RB4icK$^xZUW5=-oJLU;v8(By2#^uAB9*Aw z)K90=IL-jQcTNDJD7IEW=%EfZ|N2tHF-1|FK70K`9@J;E(`T=rE7(i&XaU||jRKId z0Jz*OE>Wy6y^ylp4>Upw5wToOo6_JQM`X5#MuQJZZ0-La;FYGs8mtL_HnFjFpCW?D zN-0@_RF0q_((E%5m>|P$!HaGmZr6QS5FK%8?9Gt_;OKfDp3Bn7V&MdX^WK(uaF!?j zus}>`#m!c52tYxs&88wUw_8uA)8<20{@=1|&g537PT`$HS3# zEWphCmCt`kr`H8>%I?odEP?k39v|G7SnnC;zymrA9 z^YZU}g(>L|e($#)eBi-w<%UPyfJ%p76oD>WynngdXKbvFhj-od=_ZRQ}VCdx4ul)v1d}Ed(LPU&{c4onGNkl*Krr(+0 zE=|+#{+<^r4ZC~8l&zw8ZS%Ux`2N{!>*9qSr6qW$w~)3j-*3udb#(>BZEUPeCgtAl zo>po)9bdhYFaD-y|M?%kKYV`k8{aj*{)$&USFC^6yZ*lZ^E+Qy42s#b$XiJq=O<6~ z*4O)=_}KkO*0~A^}h!Qd)&C54`+w%}aX;@!dVfI-bO(#X3x2vj(l1fT) zjheB&y|=R3c0QSvj=AT(d*H&Q<*v53cNa>SC;ju{BZ zy${-|VunXuf9kWJejv%@#V>x=&%X4_MC1owzaW`DQmV3Q3~0xdCEqzX7U7*^5{It> zA}n*UA3;ZIJbKQfeCRH<(n=x2&OG%zK!}`yI%)<1iNfK#&W|0)e2EkyHcWWJOY}^^ zbjr1)0!6CM7PRDU#Il%EU{Md|CxtfEHO^b-OfeJZ91$8*_4*_YyK`C26rn%|KqHWVC=dWf?}=b<`wFhL0}b`o z*3QaGKS|Wudb^nmGE}-k04d9IZKWOJi@Tj(SrnzI8jS%FR5N!~mIVqZ^FHhCR zX1=o0olLgQoNgQAz4b)O*ou_0#>8oBR#xmmP^D=C0)xRmu#Z-HRWXU;=$X&C`TX6( z?JKj5_1<_m@s?vsc6YbEvuDnpm`uvS!KB}9vn0K4ON0r8I`E4mC1M%#Vzk#Co!itS0A`=_k)A2Ucaj}AYfHOmJ$FD4|b>1U67QK zcXtmuy*N(#gM-Q0n@*MGY&e{4?Ocimahm39t6d_n&RA!xsj@T=l%G{)%F ztW|74q7aReB=VWhoF5HKB6ab?fzpWR0dRC+uUsjvzj1|SIvzP4M@8Xwwnl(XD?J%I zW9r!LG}Wii_LaiPq-4M}O#)mQ7^bZ?1kp`5pZ)A-&NKV9^^S9_$aq%X2{XDHZAU~x z5FOINQ}Ki+J?2xNxLv7eeZ6zTO($1Z+X(Co3OLLKCqb7BMp$>_xz#B0cig^ZDm-~= zWo@JVzQ4Xbfb~%f-dh3FDaw0bsC`F63P8o)JDF0BFt2`*73l80-TUc)Bzl1q@@!L1h_{!R3DzlV1MzSdF?F z>!A_M_4DKGtji+(n9Y1)fM`k}on6TOLla!$rVNp)4IvHyhwYaT2{451D^l~Etq9m^ zwML^MGb?~Nj*DV;*ERWcTBcd{#NCG82oTXLjY*6|0^l&XP)S(#um_<4Rh7DCRD9yn zB|<2Q0vhkAWjtnnniP;E(ax8qf~w-896#wvk3RVDeM-gqyXQy4VH~ZI5@V`Xo^{(w zq-tg9$N&Ahuz0@Sd9M^DNk?e~;+^eHCdC*3$tA5o$B}nJh|KIfr%5syjYVWSHAoO? zWt~OBJWJcHnAw`jYDGHHye&fQ+$q z>M>#OnIiJuDBYr5qBvzh>;2%a2_YgW5J{4_s>-w1t{GFdTCKb8xU7_FcQZhL>eL#7 zV)1~$o*VjMhI#f-;9kF76hmh5-dPt?uXF&=djSDD#*qJSQ<`+V?4WTKS;khdG0H8y z@JlkODNB@uO~WR`g^0|9N*j+9ys8H|a^IjAE+hRC5T9*nyhl6sBoh|!CgNV&GtieD!Ur}X(ZrLkr~W+RKqJ_ z_riMqLHG#;ImuXyr+R9Nfamd6fBZ^4>m2ndtQxVL)aK$5s5&c z!}^DQm_y2K0Av!reEAXp+;H<_C5YF+)*j9+)U;|CTSlW%Ggq!%Mu}>}SVZ2kAPNu) zBh)DoL4ighBmoV?SvStJmFai{1Y4IcuCK4Mw$Mc z>a=jHD9vPMM}y+m{@Z`Qx^fcrUjO~ye{4UOFH9Nr{TD6^s-69jajKk^X|7J3*|_J9 z`yTbE)8F+yFIrjYwDNq#Q~-=DKlM|;|L}A9zklOs4)T}2@@p+td7{?W)4_0NjGax( z>8ui;04Ndh!gt+yzo`Tz`TgH{@4Vsb-|(%*mU)&GMX@?@FZg%QFqTc_ZDpfKf8hNe z2Y`3}#@{aA>z%*(|9t&7d|9jA)mrat?|K(qxinPhPi(A;I6;mn4#c7%fLKH>Ja}cf zhqbk?G4?lq?cEPQO#t}acmCZQ-}G_-AF1rF+jpa+I=Ojnxk9(w3Q`LIfP^pxfJjlA zP}0hPgj5KR^QqQ}D8p35#=XJgy-sgb2xj)NssWAAjop`wnI^{`f~f3;;Ur z&1L}JU%9;1>$bE?rnCJ}Q-Gz33HM$A;C+Alsi%$g)1P@xDRt{dKKA-IeAA{D_F$yC z|Ng;qpZnY^TUS857Xc7dK}(}6m&Tv}{QV+u>xVxBAO6fEu2P7gY@`l0a%owsgeIOt z7K-OGq>8XyLNT#pZ-$tPW-#UgdMf`Xc-QJO7A z>I||q*H^vC5F#lhBJ<=O%%Z4131DMt!$42~NCXX%zwn|8G3d>9gG3O>JCBryb~8s@ zs=rXR>t=v7KfyFM#O5eKO_=1ePTrs|OL3mE_-Z~*Xl?|DAbG(5Joc` z4?&QSJPL>>z*;E_IluuBiCF@#aag?&_ZN679hE=aQ zBpDPl*I#L;c{QBemu66zbbl~G;MIP=m`DJa>tDQdh;4s#y(&X6! zxJTb|qp$}cQ&p46K&eE;dJzN|91Ox^6i52T8?G;sOA%I~C z=sr^6h|z8#F|LMLmJp32e=hn7w$Z=;=t~-zHgB;wGh;)Z-RSL&T&YtqVeRdKO&ZYp zds^5H7M?SWHQ}nw1)Dwrf`>cJom0XVSNBk3D-XA$Jyf~+3<5{@PFTLUEO?Ktc4+)H z0=~G3$XqkOs`A5jHvh5a%O3dD;LuZXXcGuKuhiFL0uAwhOkI$L@G(GiNURtgc~L<0yR1Aw3nKc6wC+iA~=DGH`>?3{Dn9|577 zBa$bQEKMG~@BkuNS5{AaZxqEzh3!_t-V!Q8oXp0pRtq7J@-mT%B1p5?SxW>pSOrrGRaL1J=}39+NP%-UOZ z8XGu2%fjsK4YgKr5|u@%wE`e(E3GxN*P4GdQf z>s$y{aL(5zGFf=?Mp5*VyB;*)jq!1s5H4PUaAFmZEK8I0wANW3&8Eg#PLnuF zB4JiU0vxh73-|>VBLcv!Ru;!IW-(^QY}Qs+g3cNI!T_$uj{j}SLu6K}ceSf79uXW@ z%h1|z8dS#snTJ@Fhjh)Dx4P=eQA;2+AVPp$nq4Qr3N@Ei<3WlIZ??zaco`67Qc9_i zA9or3@jkem$Q+ajz130=fQZ;PLhi8F3>@#t0>PoLk(fb_A6_No8omZuexQMCZgvPV z9TzD9k1WW;TX5?+HvTgJwWU-oa^o)bdFX7Q5Pgl7V`EZo%+&KS6h$#_5#|k{6-YzW zjtIUca$CfUg>M{62PFYuAVC7-tg%*WYIj#aETVQ!%EDUfUh%(wI}azn{mwspn8_X~ zFMs(fjCH688PP|;+EnhdpZjcgrS~o0_Od_vgWq1R{MzsTK}3w>IM$Ts`RLvY*5JnK z>Dg>D*tec-Sx#b|{>T6LieLTJcOJRX&d%U9uX)`s|MD-+ue|a*zG*xvdi~86cnnd~gh4vosqH20Cf=`@LB)%UgM;760s89sz#|<(psnf}P9Tg!H~9vT0tJNm0DB zwb$#cR@E>~@?N(!91fkeT4S6bGmB^d5wyz<-~Mxd2ms&v+7}OpqbzHisx(FrBWAGH zf9W%ykmu?9{^n>{)4TtyPC@;BuY0kxQWkdSN>vtyv_(b6S6bEYj@C*9=YdzD?CuP{ zAn$De0QiYFy$b+d|Aud`%o_o*Ly2!8m@_UZ&>$nof z342jGn&;t0YzX`T03gfbyseF?pL0S_$P_`AWmV~%f>D#KswfI-0$wJQIB_VL?8@|D2@3A4-U+SKKPda@PsEn_FG^2!aw|-8hU%t zzkiB~&(@^7`}V&yU7~PA9F(Srlti znf?9AP3LYhX0|un@*V;8&hA0Gl@Era)s41O=!Y)L)XCmvl0oznb(%YPNSUEUnQHF*`&`lf-*pRF)`G3gU=n z#nc+>S%Gs~7k9fWy0_9L#4L$`Bu(OBH3oLpl~p0$dS_f&c_e7JQvlK0Ypsdu+_cl_ zG;hVLD=U-9#2WMtBTeju#Q|cPCY^RVoi2b(YZ(Daly!bE9HeQSXPL2nHY=wy(u%Z- zv|<4Ef~6G!)Um2c6DNuQTX|en#NKGlgp%h;mPG&Ecx-JIFifh=PAGt~x|&wy*jjPykq`(;0Wcb4;z%jN zs;o-q*t4*Rw-`vn*(p-}et&1X*xQ>hdje^=KcZQua#yD$_re6%jIeVOCb4iZE;@jg6|4Wi|u2tdOOXUce%aXu9iY6SY z5MK5rt7jv&7PaxJ>T~TJYm8v2%OGe0pg|9yL7o92NT@^d|5#u`Y9Y74VFD`wz?`J^ zm?q19_s5h*uGPGua%80z9nBYd*>wdQP~-4IKx0Ndtf(LHh+Mij-zASZ1TB`i21CLz zK?I9g={(mPLqMyRexT-d;mP2+_?G6!FjduLA`vLSv!9P#nj?5e5gU(Z zQKYJJFOD@S?VW37nTV%UCrP)}>Y363ppGc`>XRbx*jh&l6)I4irzs)|@YmnER}}2m zdi(q1C`#glto6n^U)eNC*fXQ3h$1ELe~u8PX%Z=|G<#vMh@ABRLZrNB>zs2S0?u)_ z+abhOOJ=iDK;k4*gr*u;i)B?3!E`!Fk~oU7m`$|Cm6g7=MJrFIVwv|F=MvB>c02L=9;AYb>Dws}70iULch;@!c z(#fR1(EVTj_7GbS5qT1d*s1q~=Wd#vH;v`AZwB?CN$8p?lCqTX^T@oI51QaC>nwOo3 zI8Nl`>DBZ1UKx*v*WY+5j&(6}!_oML8%_vYBmyB3o=hrhn?w+`h(Q2~S_TwC_AXh~Q%6!%LKd_G_a zPBROimnBdsB*6nj6t0806g3+t5Z0-q=h404&-&z1uK*%yqCh=fKa2bOySF^1$Uf z)5*@2$z*(R;$-{Fp7}Me?wlAOOql@@nLVN)Qpk+xy&$rH5NbqRU0wD2`?oy$ru*)@ z&p1vrWl5|tyS#HnW%^M!-u%Nq{x)jT0Ti=IjEVq6*m@p~rVm_tpfs~KWFqw6{_C$l z{Db5@?u(wJqsUmZxw%q){z6&WbLV=KFoF5pTZvmOJnKJfOSwy8Om-{lM32{l(w^-M<2W*Zsgt z1PDml?N(?Q_y|LZqUeWyacBv;poQ?0@H z^4EXsQ&)Of6zkKd%EBC5v+>(*Qc4{W(eedL?Kt#_TKopT@ zH^-xb)*Mnhu`F;aMOs8W2WN(0R$*wI0hbqM9&ki~Bpw5KBohS3LI^1#g_)EF6agVb zL6#u04?ELi^E)-GClct#0T3WKCLm&nV-B5%Y!pC%L=A!!ve;r+hcHh&gO8Q&dJKNh^E9)C4&s>XIi5IOkfUKW5O++lB5ES8HFy7wXu@>8TYdTib zvGWWFk%-)N=SAxc2rG@AJ;?OJgF9dM!fOu>#uqPM9E^s9eCEta=iKhj;ENvrC8P0l zuy0UW;w9EmSvcpS@sKseRY^&_s&zJ*jJ=p3PGgb?{3ZZ7`fHTZN;O(0bx{@)vPdW%sEOf zUEb45JGMb|i%1fs4~!2SSEo*`cDso+RF;Lcwk#{>^mtsd(0F8$6okP$a$ZD`P@*V` z(=NCrBv)a5{nOZs?DO z)7>4OO(yFbS-TYh3q=Z%tTRcLjz+WTq$nyts1RU0)=4U{)@QEi6Vh#;xa7T~NILDj zs;p-ttk?>G)~M=N2LJ?EcrYj@vn>E=cTywflb^gJO=3hy63X-Av!VuBRLjpGeioXPS6eVeY6IdN8>stUOeDY)^@JCrMXHtXTECtH{R?>F z2;?!(LRZh4g7LG#GQ!t$umBg5yC$&`1+~+REd4&q?v3+2s!$WAE&(^qZx?|3FzWy{ zEq*Bk094Y%c{STO7R8jkYrwVI%O#u)kVt%pPQ`f|^C0Y-1gr!oQKBN98dCwnbTZEK zOxU+NX)DLA%jTYIFwa#nQ>0XkCQUHUlHdZ*A_Sg23xFvdvjBqg-jqUG2ZU$tx>Qxd zfbD+!*&qG7PP_9Bro4FRlC?%_9rp3v-Q8ZV7fv9AxVgEJ=lL()@Xic#g&-2o3IhOD z>6FsNbT3Y|_l`=8;|M`#QGYxeKm9!qWOsJW@TAg>sb*w=LykT=d8gpd|Yn7{Pm#aOsUD#B2Q8pG9wvjLx5Hn~%fIw*0o5wqzVGo%Z(LZwU zea?M@tg>)Zn(hw}XGQ|5L&j%rRFQuzRR9J{uR7FLJ^s>wLo<6<) z?9*qGl!@6gl(^?DFAQB5abwN6+WDJXFhhRO=GF#J#x9<9B-(C8 zQFM6LLJNQZ2~o@uGmn1fYu*2De$8!>p@0ZkZqqbjsH@8~vrL+0sfcrRdFsq+nwnc* z`^ue52NR1gf910$PoAzT@4aKgifCm-f&*2=pn4*(1Tn^>X?nvAH$3{?Zxew{I+;xJ zUM}KS*H3%#cmL`Chl{j-@jv}46Fu|H6PNDW&Ft^H?=LUbvunTp>%TMn{`X$;l9$Fe zG|QrYp1hY!F5MTRkSUARVyuz}^#n3(B?N#}`2+9!2~~C88EZ9G^F_nI<0@wpe%CwR z8(hVlTGM9`;8cQhRgzg>dr9nMTm$NAQfQVfg%Es@9`{z3mp=8Wd1}&+yylh=)L84i zGn}jFjW^xwL-p;4zZEOSO4-q0njENWZSb*7G+(F4<*6~hhlmQjR$KQGEc zRf=Mqrr9fB^$KPTN)eU1a_j3;=KgHjM8r&|WfM*hsH!!MDEozf{?5s`u!;G|hwnS* zW_|Fd?{F^AT1BKs4xh|($};Zt(-;nlR#WVN&JY4YH`dl}_@QgR`{?&S_R&wpZom2K zcgJ7;`(J){H+c8*D7eib!o%Nu5Wp*6`NOxakDZ_OdZ}cls%M|S{|gs4m)mpiTq|_h*o!)DFEUhn{Z=gowKP0k zt%#|IaLV%>bE?YQoScdn-4aFeoJd$32#n_6jbK!xu~0H}-5V+kU)Q4PfAiYs2UwYB9%LI@$$ z0Kfd@FWTH3CpPU5SB9fq#zZ|;FFmmH*=J8=S-yAg6~#jxylU(rmp;W z(-l*aU_@EeF!8hy03=G<1V0nVhf+h*%XVaGURTcAK~*_0#HZz~8jXg**K4jQ3N2<; znl9IMtrGhE;nMEBEX&QJ^kJGMDUbkO0uxdu_D)r;tNoLYA7w*^O`a2LMhLT6Wo=5t zb>+RUjpeQJ#B$=wKLpLYe0_&Fse7%zKS5B>~3R#O6K(Yt4bn zcAPxE$;2YEHLiRpv&^Q61y^OYY7)LuNl6L27{$Oe&QRcu=1k@Xwn+Pp}*5KVS#xM#; zktiQIMmsLbSZxxT(F*+L0%dqL9k@Bs-^c~GM&2MW+$e5FWD6>66b@pTokijZ{*xe#3eR0hJzx{Gu0|d$rv(* zop*7SF-nD$tE!GiZDc{tvR){ws;na5P9T7{wkE2+*XseMpZ9}`t6Y+#Ayh=B-|LrE z1;mh5FeTcA1&7*cxe<)v;c$>;h6uF_Rax024Z(+?fKf#df#}xOcrfgjMOBnlzt<-+ zhB?df5PV(BV9*N^yrbzPc(2mbkPFrz%X>tQxq|`$B2|%~(^-+FsfdWEh|{36Y3aRB zl2|F2Y+}o@u-49Il|p*GG)+wi!3ReK(a1Oi0+fD9+Z@<1mW?qg;K(Z)4AHE8a3jU#(z-^Q_!*eNhR7t|d*>aqfg*S> zBtTG=x~@U6#;)ub9X@o{m_()O^>YcTkPuYiCB!gkMVn?BTUms<-ckiIPMq$i=i&&lGui$TVmd!A9uQv^TLUTT4XDtbqZgNJ7-!nnkyEx98_< zHlWN+iLwsX>COgMml8snrotdr@9V7B1L^m_d(k3XNj|&krMsEwsqb&CovuigDIMhb z@xw>Nhw<7vGhcnhHKRfP+_TSp_mL-8R!*-hEoXM*idiupAGq|=6DLkAEiI|a=H}LA zmtA(`$dTc2XstDdd;RRl;iLNxTvpe!{rg{X_;7zbnZD+AH~-~5e{txUr?0x|svB;& z-tf5rDU0o?r=A)PhhP87m*bzm_N)Kf%U}KqYpu1UL?@1)K6>KRq34dOLL^*y<(15Q z=DDYP!vWS;i|Ne!Fe&WHjujEP=i`5T&fx#;FW)t~q<8q)v&O85C)VVn|K*~w6<K^6iTx)EUa)p=R zLufJMh)`<`^av6tCJKoHA%3+Z7;Y$9G!~c87*?_^$~0Om+e-4CYwUD#y9KW=uwzOv z)`Vad&L%xaRL=XypIrzGlM))jh4~IgT!n*nZUdqVg_O=Ub=4qUFll#s#UHIAzVLAi zIL5kT3h`tbs67T$t12L|HVw!D3^qwB63CGK;p<-t=z|YDaKnqQnU$q6_M4A95+TUC zM1S|rvMhR8UKZi6?wJ9n(A;5dw~(QcfcaA35SlF$;1sY7^zQxS>}_`f=mS$=>z=!p zfg#|5vRy%BD{~+Ie*nmP-Y-lze*D-a`*)u@e)RFjAG_=A@3b~Kb9QYy8G~syo%KgU z378eL9fKWF6L{>g$Fn?1Z0fv7kWp{Q#z+Xnl;(DIbTOIlS~Lr_S}kFh56>Y0pTbqLJHO8^^qm0$pCh#ADNL7h#Kx)La^zy7+XpLwQs zwGT0VLM&6c zSQV_TPC&4UtrM3d*>n=3Wd)_Wc8xkDW@BS!ZCcf};gILqv><>Wl2}U&ljgw-l#S)e zmDVOo8U#>JB(tKH;C-k>l-Wp7V=R%*W*b#q$7fhPwl<2q*9Y0Ea#dZXNlL_*UV62N z96ffVsw-9FDi5#^VSROG3>$+y55>eoZNsAn05HZ(CR0*%wF4;|6w@NL18dTrrt*R!GP%)F4jAvPvY;BgrrLXJVdj?r%dxH!RGGa^$h^s9j z2_jw`09QE|)fHcK$~_LfTY!X zL1;<7o7l!SwP?N&ifU#X57=d6MUP82a)acwFokLtlc-I;()KA8(KYBA#0O{;Ao zp@rq2bAIUpveJCghO|VjdS02aJ%7+Hvjs-FNSStvTHpr2!U4K?Pg^`@0gWN*i02!4 zym2AKaPRI*i{ntVMA}eFBAU)7K|1;sim`_=qOv>97V^eg9H{NiMq`zvswjuUp#(TD zBH_s4V?<%J+&fg)btTiuWH?NB@4d8`6|+gfWam0SclV=EClJxjoqML!sfd(iv3vLK zwbgZ~H%zI`zVf=yiugA@^rOo=cDALONP(3dI}t%UAc$^ljsN`hpY>ZVg$1atppt?V zLiu1&mNK0LRoU9wAOe*ByW@6aWBpX&>N+4hRo%gbHXI57#ilQt+faT0pJgI%< zP)#Rn%y?6+u~}y7y3)oPQYBG|US}naj|Y2SM=yMq_CpBX2i1@y*>vKj(`hg7*RD(w z>uT}Ad#_1ClgZ3jE9!xi$QZ-cn%Q&)uyYzzwf1E>RwY%xYuBzog+jA6pFVk=D(?_HLq{Xrh2sW#}mvWaRBi4#%87%pq)KK?W{qv2p{ za~gt(Pz=wBsh(aS-V>;*91+z%XfTuU#3rWKOM*ubOeTe4D$5FLROs}nRbwelt+g4O zCh9_g81d|C7Za-isa?%vRK$zKM@FOsk#o__6w~cc*Hu}S3IGCFiV%{9l^r<&y*{5f zzEzg8|I(Etv5n5iFqVVIWL&h;Ca5Z#NC$>AqcpM8aiyv&J4W8CLaa$ZHnC8RH8-Oy zQZ{6*A*M7>B?Kj{L&3y(KN%){m8J&Vc_9ctux1zE{PPU*dApFg{zBWL{eQv6=l(~* zBy;_8&gmP2Q`#AkYQyak171`$gb+KlYWg;_B!r+!#!wpzsU1QRFW2TSnR(^x7SsqL zx{wFdm8Vr*M4r+7MbZDKL|y5JZF@*WQ7a`PGN$=7#O)#?CDYc522oU&n?r_MVxO2S z9c!uTd4o6SC87HwEpAk^E_9s1i)VS0^hE8n<6^sCy4$KMfDntqdC?#Pw)(2qUiXSy zF56g}jmL$AS`=)#Dy!gWHa+>o6YF*D@^tCS%dg+FYwyiB{gd^L&Bqmyfr?! z??5?TtEXmVdHAurFF>8!wV(OPpLJC&!RJ}}+rRT$=Xdy7;Gcf*LsAzvy!fS`efGZ1 z(?_qo^6Is%;zPgiKRoly6VAJGGEUR9s;bfQG63gAPn}v>S?NajKmOJK`8*T&zy9@a z)Xq(()3d84o@el`ef*w3|2zA<{f>85RkdgD^6|6Jku!s3V{CA4^PTU1olU9N4~b0;vB|Ku z?l(6IS5xlmRKjquqnK7O;j$}s<3W7=>tE`|eATON0l;iUC04)zvoVPTh0Q|A8vvZh&OJ-J_blPl=Ptqa;Hd`iz}Fir?50=0p`Tko zmX}x3UcauYs!+i+`X~ULJu~sXO;A#1=2yJ@Re0>FfB7%}cM*E%p$BKP2^;MC&;RAk zZ+gr4?oa&g@BRDYOAlRr)%BYj#hyL;>U!ovRn^Y037(45g*MzBB&vGTO+T`{;gm{h zVv+&C1z%U;)TuMCdHpR!_{#lX1AsufP|lzZsJHy?-MxSQOF#Cz|Ni3-Km5?kU-^n- zM^{HnX2(i@$Buz_1+>tBjI0lS{q)*!IAWM1r_M|!?lbpoLo@g68T5O-swyvX^S7zp z7g7peaJyLdMFo8>NC1GEMA5FNqNVo@Aw>H;N*jqat0KdmszQLsAQ7{J8!64ynz!00 zD7_eJ4`?I%KvZ4BD1P@6cHZE|}%zR`ds@rSA^ zu>_IUQ`|s76it}O(-n~!-Zm5&G|S({yV)Er#JXS;#6>NfR&#|Lt+w767!9khGTUy| z^ZkK3?}%*(&YDQeuCA(0l332Yl!Ryb?G8c;Kqv{_RTy^o_4SoMbs5j8GIsuh(k?aT*1O&vSDum$U zF@#PUmsZH6RW&XP2`*tvLf$JfI|@!yn|trt7pF;-V8aR{qR_0al-Z`Ky1EJ~tm$M6 zX_85rmXo@6le%&Q4(b3iofSa|py{j*qQGRym!VViM0?X zUehF3(IBKq*H#08RqL2jIGMS`SqW0t66+2z8KPu1Q-J#Y!6o~47v*$)eeK|Z{kOdO z^~RV}r;jot&qt?Doj!H?%tH@-!+Qz>I5~Uv%w$q1g;pI3fYo3pTh2RYjIq|J`m&_j zZ8$H(-g4y~C{$Hh7b>BFcZ0$t`Q}E+M$;tmA?#RLI(4!X_0w6XY7g~G%Xzkx_WM3b zD1;&eCC|Q6W0R^3>ub{xge`1h`@=l%8Ox?W$QE&;?Ts$-`}4K)g!;C3{O>W~1xIe- zkk-@&BtFqmBr1qmR9XaO8|?}$T)p*)YKy;geOgPN(dO7RpSL(p$KlnW6)MUmLP9ZN zs*8VQW?DosF0{0kMWLBnccjsxZan|zBAnBW+|F>(&Co#1t(L7#?iFpj&K&2OtJnaD z<~u?QKH!Dhan4ldZr$KRcRB%xdRLn!OfAbi1Kr7n`8a^JY>XkO1aAxzsWrxFklb zI!SXPGv3(r-m^)YFnv(0ZbQW223afZ=hxR)N5lS4KC$cUnYApN#_Fp?)awOfj3@)- z{f;<^{?5T{HruspSBw!gk#zthqNCAJ)ki=2c&k=z<4z+(90(xqwTU~{hL@(MAdtt0Arxc@qOzadsTs| zF(yfpx~fIR7*3L8GM%clvbUzRQesVmQhjA3h2sHy50jRH0lg0ith{F?h8-nDCF3?+#%#{B8k2WcK# z-Mj`-?GXu8RU!stNtjG3Rbeto5-Wuz3k+J#yQZpIOTdDn9UZiBkddxwa>5TOa$CxAc=YO}DP4M{L9IADoLAl$0s3&0GubD*YH zHRjSM%GUPq>n_1W^3?Y)9OUwn>u$JY|D~r+92eB03U*5?9LRVlNfunFykcYP?CR!* zt2E)%-2=b14VD)+b0 z-v6!-$ap#)PgV8giBs==*9ZRmo^y*~f8aeoL1p=+FMd&+Ti!VuF82&86ZM9J+Esbp zgLevKSz63y#+Y7z;C-m7`saS(7uV06Q4Jrz=VQ+^hyVFknu1F2c=wO1%ArHgIOngs zZfKIM+3--$W|Nz5d1F~_*n}Q_;G3^~?JYQTYO?v6N4|Yw-jI9l{aF#S5B}Vp|L-5plbarV@M|~U{3FH~15VS#xf-A}&75=AnxvO2;7U^k*n~us z$V4Bk_kozz`%X#gTJ6f?Cl1%Tbp8_V|MZvd__5c#>&M@4&qwc%pFHsO`)_^yZE2cp zZEenq3IMASRSEva8(;bG!w;EMk{;ds+Lxa=dWHj3aou&-|Ltc!_m;eu=e<|{@DEka zQDTG0Xt3m*tEx~I{^ZHimtB6@G^-oy(d=eU5V74x;en`ZZhAIqKq~g; zn_eRt1{G7o?>1*kR0v?Y_=U-q4?(QqB((r;yzype6?{D$?#_B??P^FwQH_F~S8Eao z&t@|bUBqI3_Lpu;S+dl6FO%uT;Fup=J0BBYyn%Y5p49eh<#tSogov?*pdulPuZVy| zb)@}jluN>F+C&?O287lJ*(&#q4$=zZF7B|6eQ6N!_|N!jynWpq35X0e)UW}}OPj_U z+3M5Wo+s_vK-gAEq=V6;Zp=clq)wbr1ahKMehyXP0;1Cjb80XY0_I!@%^9a+$Y|pu zX>z@^O_=J80}+{zfM}aUUvU$%5lta&upm`PP;V#%&o;56ok>v?N@CKgtgGR&?%dlS z43pKf~ZGap;a_p0TeJ>Gx>yaeQ9ssh& zzybkZY9Ex&PKc($e+CHnSi8N^v-c4Ix8Fve`E1;yj{pQn%zM55nlF9tsoMYtB;#W1 z)?4!jA7CF&0-9y1^UqjotIFkB4b(tP?RliV?o+?`iwrP+@gPtG78n8qI3NHSPyyx1 zvqyIC-fJ-j;(_w?>eG979oU+jFqV=eV;HDfyR$5g=e-+&<+i77S85hYjK@D?A@sZ{Pmmav3Y<44fv6#Jbq$cQDxnmXy$5%xQj&0LQxQ8Em#)^btgW@ZULvC7&058ZkYO@5 z>Q}~a5*6_fYD1Zbdhu)&1R*fnUAy+&dh4w(d)X`cgCR4YK6b=OuVtd0}yh+sfLaOR#gOg^7tkhHAsAI^E@w$&>QB~U}HQ1 z69mB=+G0)V^h$<53PJ| z^woJ>OvfOiXp>AE7TyK$W$r;dCoqxP-mPZZI08E&-&SU7n-|rtpdG1&Mdq0Gd}p|o zz0Hb!;XER0JFP*JOU$B6b;&d&FIeq^<3d&l>jh6?g%23@Y>lk%p4>%a10uVBPs(J z)<6H;<*Tcw%>lD#&#ry@_FEejG#ZbmTa(G=##TJ^S5{VtXnkWXNfQ+0oD)$Z&U?A4 zf^=hZD`x(R)Vuffd?=at%qh>DM<^^B`Pv!3@i%IoC~XmnG)X1u55&eMA;#Q#&ummg zf{KtekuHIOkmWW6PewQisU@57bSsDg6bPzn0RwHyf|r;Jq;>%W?^FX0yCJ5s1X%HR#hSR5Pa}XK;9Tb#MW?<7&b)sM}}jbr|EVg-o-WtdoL84(fa-9 zxn~~x2hLJ7kaBl9Rnj1;3U0!*MI^#B1~Epfk!UUWFo#`K12K2mMscd~&qWU4E)1jt zZd^?4YeQ=YQOS*T>(tGSn~)T3EAz#ZgVDfD9fr-(m>})Wv!IPgh~CnMo+gIJbpBHf zi-31iH8#3bl{EMeBRPo$#HvB5nUkuB1PBp9MGYGw4H9DMxYim00Alw%hxp|$*4cP; z{UryD7B-UrtdHxxmya~?v1iu@gTZX#9{lRj!5~)+dCJy6gZ9#$9=dbKXl-?)XYvQW z{Lqi>`Gj-6s;XYEcje`mBc@@A0_42_`tEnUC+>fcmK?OrC?=WH;6>s4WAA)#OPA@4EAy)>>7Kl~C^aL=!3VrLTN-b#?W9!290+-V1L2*S`Ao2OfCf^y$-+ z$>iVt#=pHlhc7*R@mu$N?bg@c`uf+sA%x()F!NWx{v`mak|arzq?5@MKvmU%l*QCq zyJN?W;b8RDuQkCeZ+`O~JBIxmL5rgX6Ue18o~;%RI;1 z-+k*K+u6&P{^XB8^2INF7Qh{M+_kweURhc3-jmN04hntwD_@?=v^TO}{LCW&_V3$k zZThRf_G{f}ui8HNFaPqdTzkWf%gZZlxOVjqy<+qqeq&xG{rCUiKmOKl{@do=R8|ev z+TI|oBm}R{2O<$TV)nHKV0mPW4b-?j6^2?yLjaH=sXKF~CaGWlhBrKX|NQ`d>Yv_~ zq;OST&Z^YHGL0wWqN<2FB{QDZV9I;RfAf>KfOKWYl0tIB%(f~+=_+G?K&AEOTKD#k zwadh5OiGUGk+SmkpqmB!cmDaD^e~DtW7tH1JPIQdb37w@($F4@v_asFE6@Nv?E)8U3}^%h znzW)hZmk^ghelK1u1qg(kw{qF#)aF#fCd(p2%|`h7VT&zn}Jm+GRSB=c0^U#G*4Yu zKM$(W(Fj&HB*B3K5rc%8^8tlW=2;?Yy-u^iaC!G=W4)Sgm6U|>L}q2RYxlDAU{W6{ zPY40QQE-Z2mWHFcuCIIXwHq62$BrF)?6L2UMuP_)NPq+|?Nb#kiY|~|+BG!r|Lt$W zXFk_Gg?jsK)Oj*)e-pRQP_r!Wr3U}fFAlG`@Q2D;lKip$GNmoAAH` zN@VgqCC~@DVt=8%L_~a^2J-fI1`@zVfTnU2Yt3Y9b7koYpax370dCmusm_M|W#<0E z64vwHe&B(2Ioy7JEntC17uLH6=m7#O0|s~ra8*0E?*kq<1)Kr=C;oCmL@g(dA@U-e zCTn03am?gHfO;bG!5EHA2cdb8$q-k0ayd`~I{^R{;Jh!{Fw>}Z>uE9q6xailfCnxE zHi3=FlxrO06+Jk{skVAz^0fhpF&PoN;M0V|yyg)R)N(FCKsp`=X82lE z92;5Qv7F^rM5fcy7)`BZ(0DrWPWpL&GAX_IEK3ziY;2M-bDAcJB?5|~z8E612s&S^ z!#~7HsyhF9;qkY3?>>sUbXQa~{)j0y)IrnD;7z_thqHIt_}gkEsWwGbVh401Q0Lf; zl3Y~g-)g{pZAt)bOJZs-Lm+D2YIGp_b<$dU&Y;>Z9yx zK@1h3>Em2xDSmNNKaHD2@z9~ebyY77NB+w{JO=X2 z^zz>F((=~kcxh>=s_MkrG)u?h@o2PESG6@9e3;Fqd9UZ{S|o_qqA1cdjWi-VckCMU zhR;6t%&32G@6KJ%KJ%o78k5w{uWxLmX;N1eRE#k}B~4NVf)7NrYj;*v)pakuZuRWh z_4SRV(aNb)CnA@Pi0;_6>x#=SCxR%Z(`g7&*KSr6vG53yq**ri+HjZ^g)wQ8nDzB7 zkzlPI4pt5>y&oi3Jr;WXfiaOLnPNQ?DAqRCi=t@2w|MLli|Xp?Dl@49%p$_7!_g=* zs#InDH*fv=pqI13c(!4UWeaAls!5ury*~8@S&ZWl)uNP*^;w#xaXtj&T>$CQO23+w z-fLCB#F#O(X5F0EkC==~WSmpBMnZ7G5fLd9nfQ{aQgA}tRI)J)5QR3VHt(mS<({!* z3|t+Y3sqSG6as=*p^)ZGh9M+@Rgf49XrAZBCBF8e&_>cyT}$LJaxRqsfU_*WWbY*p zU3f@t@(Z$NZG zu?m+}ZJ5i#fo#0AbK+bmXvWMUB7r1?7A=MZ2@3BtXJX5lHA#}yb=cUP=D9TnOUt=6 zEWyPW%@S8-B~qtpO5m;Ow5}ASy+M*DIRGNbvlO5ZysDaitUA|o?idD|C~IzlspQ$G zzxR)I*$cHFdBfYALs-#NXARdOfN!MmJ#yIC9^D$GKj1*nA zG5lQ>&=7o61!IBHrpZ47d|TCmT8O2EZ;n%TQdfXKdNes(e|dteU2nM+vwlW_)?fzz|QHeU6%;-o=@DPWJaUmH^2GN;pd)wo=5TR zcf11)w?zw_159+q<(C~hdeoQ2@@VwtH@#IO#gF*I&mI|$hL3*hVSMWXXvo_xJ>Yz8 zC>DGnBC^){s0$JRz3a|*sR%RUyN@%Qcf9@Gts$o|^X~38PUn`_y!w{snfLbg2fz0R zh{df0YisNO%m4a6K2PVpdoKC&zt|QH^o?(PZwFA8wJNDPr}Eaf z+~r*LxzB$Zz@ev)?%#EAv@`_HE!PczLw~yNtBD`m4MXGG-f+7hFw^+V*~Hk*^^IPy z2hlvu^Sr;ZV`Vbk_{=B%7Qn%S2U&uMTy^Euy?&n}gRBUc4_XB`q7V`m%epg+jzdrxwdUrJr~rz z=Fdd{WqViC0ty<7$i}n4ux%Z4G5wN>6m9x@1hzam@B@*Ftj!6Vzfju1r zkp^BCmC)42Ybtg&H5yf0K2F40i747qL{W4LLhCAwo*BEHIl4(!YUF5BAOz~Atv(l( zeAP(s&eWDPjcptIaBCWAV?r#*WL02WXr#2=5P|W=Un@Fiprja9-HZ$XF?>J+5lnj= zP~+W|#(99I0#ft`i;5)!RuU))G>A_6ql^%4_~94l{gC&JNorCmE9abdE*w94X7zM6 zn?NwuU``(!mu|Lm=g?K&JI(UcSAOGc!AzDdk-6;3tG$ z`;YGcG9Upm0Jq=9D&0o6-h^(k+8H{41`xgR^-aI#xr_IoDd-|%#Q?n5qNooYKKj%% zhi#hezx2TAQ>TZ+;lYCkMdfEd6s~^J^!B%$P4nKqeM5lOS62}qybe-p4r$%kJiEEE z(eL+@G_|&Qs;#vrPp*ze!!*qX{gbL7*0r^@vM82Dqm|_z5fM0OAjI&lXx;}l{Q3K_ zfI5Ar1))siYrzD#ss(EZI0_K33Oow{h-J%`0O|MM3NUbG+mitY90NSq18n(o00ELE zya4xDfPu(sJ_B|F9`Jwx_5sf^r9jTaRk_K`s$&r$CS%To5L7T242W(79<8hIipcN$ z-x>rq$&?vXd&Niob8Ns2tmi09XUV+NmW5dxT)@~*5O@0zs0hWNnwO>o^K_HT6 zJq;*O0s*M*d`EHWuh7iOHSx%Bvym!%G)0()V z6eJKhF;+e0N$;wcy(k1XnVjt<%YXze%c>~KFe_#PB{s9N6p^4Ip;R<5AU*_juC6r1 zH`u@|$dQHicS0@y5G)4mQ}RN_Xl;K2l$oTdWj zYfMzwtu;_qzz{pDbPi*tK(KxAlNB zbL2}}SzZRgd%wB4DWb!{AkDIzbBvvCfXiQAdW@C&5VP-ZAK#1xZEo4ZlqQsF+StX{c z5(p|mf>%`#X0s`5o%a&MLZCFW(Xt{>AR(eO1qi`ut8^$6RaNO+U^3crz{M?QLnZ;U zDhUBelJ4HK=d#N#w>Gghx%85~J_Ir>s#%f+2|h>+7#xk3X0zFFI3Q26vTQ3FwbHnS zF%{~(hX|2+k2GNbAt0h>q8dco>hEz%45)}i7B&%0Y|u1y&b6dXnx+|IvFcbqi=b#I z^PuFMQ$>;*P^{Ofh+H9{$ZySt>|*8VA82dfn8VLK{*QD405{!on=zJbQ;;Y=V{Ir3 z#TX|dWQ`s~j?o0sMvtB1H#@aeLIA})I*CZ2Xj4%J)gYSLk*$dA0 z?AdBOo=RPWs_&`*5X4AKAgS0_Ap{{881{;TS7tUzxcB8Rd@V_BRji$Z#oTr0J5#nH z1j06&=k6D6d3+XD)J(p^YZeKW(Pm3FaH&WK)&SZc^q+kCX&)qnV5}wJ@++@7{M=I) zxh<^%A+60oL`CDq%&9|9Ya zAPRl=JKn?0A%uJW>f;Mbly`Jt7iKl<<= zz3_GY)^GfWUa$8H|LjBEC-?o$Cjq?ajc;>RPy&Gm!?diz)mLA2?MrUx=lN(fl#6Ic zU-`eRho5=2-%mHzmB>c?6d))gNLe@) z-L<@9Woh)%m%QW~4}9ar*IX?j?Ay0bf+R_L{P>Ya9(iOMWkP2q7Ze$Od%yhoLAARsthNQXE#o>mD>vzx(G;o zAR<cJkWUxpq7ad<%UQ8g3@CgCT1mbQ05H*E<7A%A2 z<)a1f?!0xPRX~KMS~E4)iHby)5X^BKY610&-N8n=Q8e%nx9$P%1b!1)-JmlB0wO1I z&@Rt9fJ2aaW3>j+=Rfmc+C#5z_wQd>8?U8lQdN$?>e6z?L0oXAAr%RBx`j}aDus#% z{S_blRhM7+?9+!TSAO?9PkJ8){XwtaKXPb4khGyC0^p5rh&rPJA!^L?CF$bo(CiU6 zjLfPUq7g*|jXCOI;ZE4LV*~(8OUvJUB)5}vLa+~X?PMsJH zM=PUItklrfn^Ix|VKSZ=qJFPe*A+9DWm#8M%vp|A7^aiy=Eg=msu=*McDLtpGhBZ`qVx8!6V*xd04M0}1dFz_n|+1lSyo zR)7g81;pBAzysd{gt1%|XH}vP7pm%AWlYWnb?tq1GRsQfR8g(>vK&|kt^u|dvfcpb zJs&?&yQ(TF)F!A0D6y89v&@^+t7tzP0VCk@vixqI9{>c{6)Qgir>4`#i_*tu5X8H8 zaN)`<>2aeK*TB(stJhjRE<%tw&;u;64)lNlumO0W0u(T}zb$%dg2Ltb-$Qr5sLt35 z9NiAKEE@1#hsI7@_*OT_{DA0UO1ciwu#7Nu8z#`q2@5Z_ETGa+{4dPDg-$w1w&fdE z=}2LsRO@mru`Qs68sMgr2^_-&nh=%FQ$}b%Sqw~}g_U8xP1@oo&FtbPsLC8lj-MbR zCeb+QR@@>Z-B|OBw`h@QG%C6q&;rlWrNBTzO$4Kwt{gGqX%gRh=?_vOWg}^3ckJkk zLKWljWHw4Z3q!y}?CtO7n(-UZtXGKw3w!R8a zeE;zv5`3_UU3v1Ym>V*rjoYBv_U=%h|Lnwb+o83AI?>&BReFZLqLAR1@Yc>?1Yv7yN<`5liBBI9Wm(qm^^3A7%kt9wmkx#l08HHL z}zH^^(}AU1eGqjQBc;s2kxHx0Jzs?G$zwe~*e-utF}nfX$w z)Px2GVPRys#OY zR&Ow1Mrg(A*A5&w*fi~=X+|q2iT$>nOXQuZHskTqu08#JpNJIr_6=9f^k>1^GhB>R zzy7EuiaG!#M^%;XJ*GH30ve^ZJYOajsACaG(lP`Q9JE%Ewvo1pqv2%GpCLxS?|miA z)J$4H9HSMDQQHt4Gl3dJ5P8pbg;iA})m-po+z5<$!CQJ7|ATHntXS!%-t~T(Zd@Sb zf5F2|35i%KG*z-al7WIc&)IZKk&* zt(2 zhi3F45?tpRBzcgQ{zWRx0SmLUbqS(?ntZV>fJB^@tQa*$qyHy(0t9G~M8U8NCRZ^F z5!JpnQ|LXE7=ZVfNCdF9Hr##Q5~0*;VKC3W;(E~6BVjT@zh;$oI2^~|S=G5}W-!-I zqVxQ^i!OTMg%^X${+ABC`0}Y>$89&?R)*Ar0eE(*%97tdOEgQ7{yDWoPF1J9QBq8l z1G3ITG(-kaVr3|WkqfBX{%4jla4=RQwF_v}qfjk`W`SDrCk)$YRAT(tMT`$c4ae!lV*^0fEfudS`^ z-Md#+iQFZZTr?OA*48$@@Y&C*>eIjRn?L!JZ{D+K&r7cy{FRS<2tY)mAPB>cw(n`j zdiS3JLKmFZj4(&g5%MG^!AjZWPpC2O*95_HkBAEBpIp>}I(u>cpt!=2N z3JLJWH@@-t=br~qRaMgNRZ#_Vm7jR(pt)_^wmp0HkmB~+?|9-nPrmTN^RW$|{rr7r zd|n^_v;U|2&)2>FVu7oGglBvBalA0G|J zKl9%AfmkInh#aDd#4s~E!-z4ob?w>fpPcC~ystsz@?=O7uvBt=_75f^SELFO10}&J zNS-l~BLJ~UYP)do&ih_%9Wjd2%v%f4kf4b434kInGnj#d-IUCyBwQqC3yD%;V5$j~ zjB5ZUfJy{|9+DYo%URMTF+r_#gS>Mgzj0*;3mL4RVd>L1^(yl|F-pfWqvM%(mZU&a^~>IanZW?S?Ch+Fj3*N&>eqEb zK9~oyGmd!bS1uS!fWAVTTEhwUcz z0sC-*nG0NDYMsCwa0g&=w$A|#K)^9z4wwc04mbgv$g}S( z;3D8TU;{V@*aLhAD7+idM6nT|B^J>DTn4-XTnq^Cbbf&(SE!jvj(zhzQ~Uuuume~E zp2$~g=DLeAPCt9^W0cBQOm%;z*EXZ^WHkm2al()`u6cK&-`kz>EF%!Llko=7N{l&x zOpmnRpY^UEqzUaPgtpgv7J%rBP-Q-7gBil8ZChr?Od$kc^?;p3Lk4B;Qk6^IY>+kI zuZ_H;OFN3#;Tznw^;st+3;|@?ubwcHxxtsW_HhlU|}B`;fiX#4kH#{W4aXiR>Le zzI^cDAz#&#$z)~aWL@``mX@r03IWHC9qsk|J9q93q1m;xv~lnag{w<>MJ4Fswnx|2 z)+B^}ukQEzYM!9V>dCdbSCe9MW8EMRg^q{Ax~{!*{pQN(BU=~tvcMzVLRMnaQ5cPe zV}s20?>|uJUnSdRbN;N|XU)ycEpA)fzPKGgzu&K_3cz4yAR^1l%fIx*?Vb5%&H+KO zy1HiPKI^Qr{_qW-SYO}BuS0j9=U=3kP3LFl>^R=};+ojV*n3x1)%?P|h_p>;#*L^p zZ3_h{D)vQQ zBtfio~g^9{@$uHkJA*uBt@j7;IB3#z08sL6Ve`0ixVA z6V+H(eaCG6qehH|t#j-hi#q43-t26QA)>8oQjIFHZ5w;LtIDa$aI^6#Yn~Pt=ZRFC zaJo?JKg^ckn73VVO;y)*RhwZpR?1c)!61 zRuThDv76JOkP=%WTe$?SGno)rjx;D08zHr(vKW3Ee&m>e$lS-mJ|O2xT*1Ylai_R{6&tnL;(B1DZbn-S`) zsdgMuRZdJGa^5-P{3mglWKg(bMTD}52vjoiM+B9iq7Z7vO7KbofS5tlPLx0aZ8KJl zuD7^z&)MfUJKJ8b_njxcCn0XM>y@7kBd_t=S4Kes7-1XZVyom z(o#6*C?O6pO_bcVD&H%K1xQMz@$Fsn*LE{P{)4l?cRTaD1yGXeGrrU#AesKvSA1g&A7*PhO@XN_y;u%ZO+Q1&U%Ow!W*X0fZZ`yTvg_5$9cu@xJ@-2Jq*9 z{t0HPs-B44ded#pj+twKDW&B(>dP-Y_sz%V-|)sux9?oM;)-ce)T56)GQVx%s`p-f z+wHe@M=41eXZ_#nZg}rwzwyBkL+{14@kD^oHu(4dXCB@Mr_($z zJZ{J1xa+JPcYfgZUaz+~+`R9e`#<`pe|-8w>281ar+@J$AN>>iED``X=Lh{km1Fx}IuRpjD!S#B z)kB-(;~`2bLv5B$u4e19p)0%H73I?%roCwdz2DuAHC{8uwTTkXI@4*g2_Rc4o2cSyDiMOjr@dI+r z_B6X&D9~gjncd9@g^?q`RaJG+rF<2j7^Ah@b1oHwicBk2VX$8Z+?Xd?ys4+(uuC6^w$fPO+iNX%V4p0dV zlvU9-#88PXsgtPeWVqH0X6oTu8$xvC9H1?eszyIIGdnleUp}!i8Orm|zf44qNrHg+ z@yDyG_O-A3{XRL9S@aJAQc5HR|SW84AVPWUW+2@@-JJVm>cJj?XcHOW2@&vdi zqakku-Uh4ypU!7_KX5KE20m_34sZ;318_EQ1OU(iJ>Ux9`@kVU+ct<8vA>$1pYQjV z3gl7MzJf!Kjf~Sv;zUgjg^g_#=I7o%9Dmh$4q<9|9K$;Y%y^yyZ~E%3K)>IA26z+b zNg&wBct5+icn)wba5nG?unfGp?^p8<2El|3!T3B!3K#@HnX7zB46NI;2qCm#gP@kc zJ6-h3w$B~C0mvvsCufIZWAj($=5_a&QWQJ;sH$^OnE_%ZX2(`mPvw}|cx^>~r+#L7 z2UsCdOyRP_B?ORBkVG^AR5Z7OC`e5wGS7iJkXX6}NP;G~nNkr>N1-w;4xND3@`>rU z)9;DYENNo2BuoU!D?bI0>1_GnTlPs%$(Bcv_d0FstgAUf&I?3$3818bkxrEi9=dlo z{SYOzt;AMh45MK)X_~>HBCl4--ZVj@m%uRwsAWw6g+#L9648Ed(C_yhv!iO?$IfMU zegydHZ_Iq-YG$_FzH^Qpi->Y!U7mh-uhz=91Vmj6+`Wra2HBo|zu!N4^hk`7si|n1 z@xg-!0D`Lb&N-e;#s?1U9}F(uJlyw=GQBb9PKYGRcszFOLJTp+jg3uJ2_X_8#soo* z$7B0}b37~Wbqy!Sqk9YKpVXal1wl*!T9J=nhDyv6C1}{c|A4LCw&%_rJLcwQHKnfE z9DqU=$`Bk8;lc}FQ~a4pE4&5ZgoMJnW#+z`soS#jWWr$q zaR7Af&uOMGz1vI>%Qi6!8-*`{;yD<%{W&G8uuXU3=Kug807*naRK@(+4n#1dgK}S? za$@gUvyC*?h{-q^wj(0RZW5R&##H%&yeOGf1DURm7~0XjkuKWOwOl2mc-p9y!3I)l z1I71C$Ap$vE{Vq9p&F^GbB@`w0Z-mjD&BG3VUAHKXYj~whE!ru6+&y`4MaF{_^|E2 z`|Kq|FQ7Bj=#)zB7jhRM5DlyU)tDEPUQWS;d*omM*>?}87 zjZtp6_C|u0k6N`cS<>EdLSt-76od_S<%pt509B&>7Jw$6i{(Yk&{*`Kh5@lAjV{(S znUz57h&g8)GT^32)n_)HQ;8ELc9e*kfEhFkj@kj)AYuh{GMO;(jo01G#sfKQNHtvD}L|a{=47$?cc-1lERW#=}wt7~iC5j%I*uCr!lXZP>l|I|}Y&(6*qKfe6OAN|80 zaw6M)@t6MT|Ms>k09^j&pP=PqhDI3;GRF9W?|*-JEv61IxJRWl;T%aQ1fAU?IA?o(+OQD66imb7SfXJ&*&|uZ?gwCN zp09k{OjL!Pi{Z?0jA1dAuPl$llqO=fSDgKZDU1%?QdwzRF%kt}V8c4PnXwMcfvxC_ zc5{sR*lJS1`QU1_80xGMIgN<~kyz1aa+C{OPHob$=_N}N2A|M z_B_oWqnzr6mV2LyyH9V?%+Xet+-%NtWGLeb9p9Qd1FD%RO+adui7hM}b_`H5IqBRf zU2N-e8DzD&ZU7f;shTE%CL=CHj=-waOo9ZU9rKD&K=d7`aJq7`gWrQjH6=^1?@gvKr#iAQCF?7v|=uNWut-iezR`_8CZ$jn$&>M!EW!tvtY{t9gy(f6Qgl6LXFw zDH}))F(&K`=ACPzV-eX&^GrxfR+^f~1urUOyQ>z73ZL`3;URAL0PBf9d+CW}ie zh`#*bBbioQ5SA)O5G87=fJI09OMuz;WP_PBD=&sxASxW#Y^j zm^BGIXpAx1BJRECgtYn$9(@fM2T{*w<)0HU%!tf57aZ-I>CeyfN5_t@h0=r*aWr1_ z)n*h4(#-Z&DV_9bU=9a12c{UinyLS-Q;Mjl9jPG=a? ziOi*J8i^U8Ey%!WAcJ;pS-N8~y`mHm0IKC_n=A~njY?)*wN$){SR=1w^wL6*7KrKf zCZCfONOEk<#lcrVtQB$FM4)(^JRZi-s;iio2_mA7L=_fx5K&dv%2f=qFt^P)fAZwY zWZX34hKNK~W^P=CYVT|BuD^2w4W>`p29O3D7#=q>S% zDa-@&vvbVD&CN|px#zS1+HXTERpn#b647Kd3QapVH|Lx~3GWG_!j5O+)gY*eo?E!o zqt3P1a+G2}^3!RQ(k*ISo9r~49%L0SKi^c>2}u-wNm3a0?eg;S@#W=W_RGt=w6rwb z9FE81*S_{*bLJ=G;p*Dj3(voh;Z^R=6Cz^Ai`y12x#VJ1t$VfOGy(?3O(v6PpL_23 zv7^MiYuB!wJ9kVb&C4&n^!@LDf9KAfOFMR6eDOuEym9TBXPyaSD$Z6zs$4a7p9TTm z_s+lI?Cm?}P8>g}YH_Cade!XgtVCH~U$=R%xVY#Xube!wvbtt&opWy2u3gS=S}t5f z-hclBfX`mPMj(inB6va6>-Xm8<^f!K>7_@G96fpRgo*&%@AaB?)J(=Nudn;6%8M~W z#d|+9a730IH<-Lo8}*@ zS}DOX-6@#x5Ww(*{BlaBSf^KRi-K0(v;zzaR7k)5=obOJ_u4y+DozUIRvmfI!Ze&> zDh>`%AF8MVA&HSKyooV2iU$M`y+If8}_$NSP49*G2 zsSr~Sd8tSO=ByHlN;DL(|XHS3`&U0d?t5VLH zDiQn2i~u`NiMHWX!L9`G`EIj)dFqL&X6j{cejAZf$Wu>z^Y1x178bToCKCXIdUowZ zbL7DD&wT#{fcNcx<%j?9<{NIM7@-~LqJA7pj)PZ`Qv+1h(3(W6F|q(m zAu#KkWpbbfESoYyRaKNVYZ5T0(~>mGO&JBr-?v74(&^-tBSb-N;{`xOj3a;|JwqyD z?8^*Psj5mh!|a_C>!yW3MCPEGTFrPoE=MDx7~@^{+)G5>`)h$aZ~LG&8fI~+Py1_UEQSDv&rq{AVRr3>%Jp2YC>cpV%A8Zb`(NT(0i_bV`z1}A(K{A#W~{CCyTh^{vgg( z8aC@@%$|Ivc7xg3^Wq$67i}XZY9|v0RdvnYiOBu;Cw-Z=ZHb6PNy)QsVu-Iok0fSd zN2#f;*=>UI)NKYRX$oeiGR@>1_CnDqA)x8kIbD)|xE09j{2wvpP5^c~&)#JeXbYiI zZApNdEQqFtcy?sR6bX=YJ^>tvinJ8~Q;WiMwIY}4&;Wr1{_xv z5~bJcfr#J}AgjtmA|RLQM^qF>)Hk<+*#jaWhS0{5Ewk{>Wph;47E+$;ZNKE=ODbPI z`Q&#)2+zN;Peq8GN_5^y#LQsu_~V|zRaI5J8NdO2Uy9ykcpz(aXJ4WIb& zJYOSledd)I_R#<*00xc$4+1ZbBcOAvb%c=Ww;!XOOS29%!BJox@IQ6slVL*Ne9VPr zC5ra@gUNX0{D$|>0^b{tPxkv~i;kJ95GLNg@Q$~?kghppT$&)CaL%_)qtMmW*tU)U zCqdZ0fD13&bK!-T%+1aoIeNHlpV@!-xk(cxsseTWvah*6=li`n$k;JeuHM|7JoJ?Y zkQ&VB1C8%PTVi4aQfSjm)V01s4?-9L5r`Yj(GXj9uCAHE0b|7);Xn@#a1jxhbErFT zl~Hm$Fv)&$3H@ANsEa*RAV!Hz(-OgZZyq6e7n^D2dv`PTO78fUJmQW8PDSv=*5uPn z_v~z);P^D=LU}g}NI^9HvTWV3IwfVZdtB0!$)x4|i*+vs`IKueXEDh1lo23ON`(MP zRVx3etVUKnMF5=3Zht4KNg(gDI%KjZ)P-_TjLg=nnhs03U`m1gG=xcTfKHK`?y#PQ z_gIl*nIqjmo4NCJ^QuselxGWXsNnVXox0MARrN2T$sr9dUcF3gl27Ry*waM zFvC=?n7t&C14VaM5N$<_3>KQ2@q9^HZ>5twu+tQwd(Emqc7xg8+TZd|m$`BNnVa3*Gu zomRU;V@D`1J5n~+qOTaj;lqcGv;6F{&sofW$tABne(X5siq_;>0O%C+uCA;+`|Pv3 zcb~Pu3tacp(m@nes=B`Hvdip6+t}RryKny;tgwK2b!CN^7LG4$Zmuou+6I=Nmv%4A%=D?6y!Q2%J$CYBXd)Esc-PXd3op88b7S+{kN+JLiOPBBox6R< z_O@vsee~-RBQdvayJydyZQD+)uCAHWcHu=A)phmA{0~-FR??7~8%f3Abfm-gA2|-@5IS9RoS*}?$F_*n;RP{K_Sjnna64_1Y1i=GSEEFfnvj~53=Ql zLWs>I04gz>X^~tt`H!(>I7YQtdYfSRRTU)9lrVk2vO&zIxEzkzmzU919$D#wEAJ{_ zT$8Oooa(T2(SB7Wb|ua%Z;U0VBoVEo_$Mhqg=vkGa}_fyK|^buu%kpmQ4lCX!jzE_ zur*L3Pvqc2NkFC-Tr7PXK$dv}xe1h@4uEr8Ugk{97S+VwoHBdJKo%PURuu+C5Rr<( z6vS$?mWY!BPax;39zhBE)RW)(|L~-r`p%hAn4539mB@L|b8`#FmzSS??zyF%JB}PV z(lirnj%_{OSRbp#nc4Zes+N|P-hb((BGPlcUR^Vj^{XPHpeZ7tTpCtzmQ#S|@&wc4 zW>VD<+w5&S16Gn^WsC;d=$2;WxmJkCM4Bm|$QD1VFd!oDe40T-%;fSkH*FFH26fLC zt2P88a+L+lsg(fof}yG+!D0{*VMlgrhJYxE%RmCe$T`MT9#v!%Y*C96O?$-*rsmRL0KHz%Zc{{VyzXXh z8r!X^s@re5Q*s;lGYSbGKYsk}?|4TOCNCX)VjR{6gTcu$NC~1U>ReS--t_aML-aU% zX;1m>r#}6+KXTr_`=_s-ot;(H5JFW|b8~a+>ucljLj^F=Z|J~c)_Kq@(-tv~q zFT3oruYdjP>^GxGIY-1D^S6AGteB1D36dbd20Ffwx z90;xw?=`e&TX8ka(hxgG6qO_jf!MhiBM<^P3XWor*_)z-F}>@$Zrip@V@e7w@ZL*^ zQAmUcpa^0Ms@1MoQkw=7 zmof6adAH@wipjY&5X3=Q3NL^NYECTy3Jvzg6O&6yHWpI}C~iSmGC`uy@6yOj7i=4N zE5gmZ9EKxG%U{=*b-ljt6?>%4R3=IItT3PMEy8_v|@@2!h67N~QDj^CGgj zxw&m&+jue_kH;}aB@nsTHciva&(EDaaY9v3EU%tC@ix zDUvyg*i^GV?FoHS5W!x5a%2h`Hc(NNEe5J8RVC&Sf-N8xOIYEw_4s0PsXIpg6LG%U z|M!s@H6@X|cP9Cl+--Vdg(33{q2A=%#gUBQrbGN=_j1P?yaxViH0>^z;@__+S{!%mWL+Nni%J0C;J0<9OApV+^Y+upCNN9jL40Rpk?x%}d)R zsSsw6__I9g0C7l6o3Y&oST^}&ts6hp)DzUl!1*?fSmkg#z9I{KgB_e zd4|rt@UU)jhiK_@&DSDQwX~yk|<;krN?b;ZwGp{|iV^|I5cI@1_f8P-VdFiE>nl_9^ zBZ)%ZoqzrXE32#f_U&6t@BQ&T zt0Bhs?VTUTp*?b6`MRnB3Ng+M`om^rJQcZMV~!kS6z_dR`@+8Oudb}A zU}kwH1`ya(W~?wGTO>=%IGg-2ibaHut+13c3~%3iviM6R7jL4lK8AsQtr)`VNLHoG15r^p0+ym z&PhyVnz@BjGWJGf0F|T}h=`qIsu^U6d5n>qV{(=*c>2jRv;_Y9Zx8H!KvYbK`=*<3 zu`lnw>oWvun`Sf`MU{Jg=|cd1>7RY*(4j-b+)O6>_U*H$!)#2s#16DuSXo&y#`Uh9 zXZ8EN5QUj?63nWVsclC zuCA>9>;Lh8U@)`(xBuP0`jK<^p|5`VlyBa9^)>Sg^N&6D7=XvV`Hc(CKi|GT|Ge}5 z)qnplfB4a^xa!Rk6+(68L84Ki?5I|04SRj&d#~DW>!+@MV+cXjUW$}9a?BD%BS#?! zJLE=2K$diYJrTpg46}X1K7-5^R6 zs^gnvHoU#$<_d9wgp#q!b~}@SbH?nHx*GuqY|^zk&d8cB(~!PUQd9)VWg-*Y^~}WV zH3Xy_h5fpN!-9|sOr_%$8n8hG&E2x6c}-#{BH&b^F|fL1%t5M|Hmu;}8K(C+tuAS? z(=CBP9ym*9YSv>k-_?3iF;VUrE5^d4Y2Fzk!o+s14Dyw)>U#Imu9>+RX7=o(2941$ z1uMfD^k-i8x=W58K6?Db@dF1AT9EVl*S+rG!9&NFmwi>OY;3flU0y!UWRNdI1;jHm zGyQ&lFc>`cm|eNC00KboyV}K+f6=bdmc;4Jx19ZX%3iE5W_;S$EKRB+Rc`+4)Jg+l z{SApMe^O>-a+VVx3if6hj-%1?6h#DpkolEKPc%l&SEVAFag8$HO8Unx)zoAR{3a%~ z&Y<~%MO93U#I$}g5R+el9LjWhkT4OPvx?_*iOfXQt18M(zQjB^W=~|lOreNfNqK#? zO5It}d&p{HX4uQBT6sUsPl!a3D}NeH#LgS`|D`XJm7bC70b}50U>!IP><3!F0ha+o zU@*V{fU0Q(62OkVcW$B$#F(viqL+XPumE_V4_rDJG{6|x@YN2Wz3ny$A?(|?52}wp z-UA}^M2yk-A@B+?nw{GYT#RaUomcFp78e)${d0gzfNue^x-nu)4zh6tz+@n|6DSje z;oum|@Cpcovy!#~#N-^YgGP#N;L6zon%qHEz<3Bw4cCEJFqAqdHf5wzI`T2LGIOp} zius!ekd<1C$W+z^BpGGH88<@5YIdUADL*64CC!2StFHsuK|rPoBp!#-+8akm-nuK*Bcf zk>`h~7}KHiO!MgF$D|@w{ys{f3hz5>+h{y`!$vD2wXb3f-VZE)tg4QBn;WCejq&pG z3P3OgI`5qG)^5TW;%0kw+aiEeKUJntnLl|ll^zzC7EYSBb3a3BD}E6-g_y#%A9=d zT*K6vQ89|AZ1IK4et9jo)h$egs zo=G8M>5!uuMI7@*7hk-%ZQHJ;T>xHw`DGBPL~?0aKYH}2iYQ5S0i)$8B-T$GP*RDZ zoyc%wY@JCrH^!dg>dJZuTzT&G`}_946541>_V-r5M?}3|kC|WD_sT2#Ua6{TVSZsW z8ntbE=+I#cI*6!gnyc=a@!sz~clY7L2W+iv+pxaAG4f*o8yjm>1q;_yH3r?>Xhx&s zs#5p8s6aWkQIvc|YimRA9RZVx2$Y=JFtcgNgoY5R%6kV1ytxrnlsFCk1kI2da$5JD z3YsQ(>Xk=oizb};1w4KFsWT=d24)AS^;wQlLkuDk(*kX)5t69lsi^Ni{c)lb=?fW>@^W-w(O}Cvnzs z8-MOgx-V5V_{_es-KKsUQQNk|;n2pjZQDm5`x=0M`8)sO zoO90Z^?JMa?5Qh;>g_lEJpSM>PnoOVeewrqn8Ba<(kK7wuPaBNyZ?bQlS6DRA~qC5 zL?)y0`uh4W{L(L;^6M{sdCMDDjLfNP>Y27j9{kRa+~?J{uYdVf1%0o4_dA$koF;>0W94r+W99C-9PT$hx&Xs)` z_{gzv*Ed4(NJzI@X>1)jX3|t_MZ}Z?@{T7~@`(9>-Al5|V30C-r_Oa<|I#YN382VsW7@D<;r4b)$2(Q%$T3T6ppW92d3T z>cvB2;xs;~P*kSAn|BTlU>8MLggA*vi3qH3qvX<4^FCv=UQ`Jc%_0+1zEZC3?IgVt z+io}-wM`?cKXJLq`txJo1R%gD(>=}t7JxaR4_pph47?0%^!*X222s)0v7d~>%R z94r~T3wW(nv|0F>TMpT%1Yq=;&$Pe@xC98m8gLjibe@6TzyJ_n9;g9bSXfwIUd{ql zEzkmQ24=R+Z2$*=joeTA#K!Q5gy_+qG#jc^*EJalPOTH2a~=o;M~c+yL7D(|P{-;R zP7ssPQYH3G4x--GB7)$+HNk@lCSv5}kjIL1>7tmLQidd=eO73Q!75Das;-<95hFz= zkmJ?1Y2aqT{PYhNV3waw$tGuB2-53e+!l)?k)mZL>Nr^4cv^Esl>OVHWKF@LQdeM+ zaw&X%CDf)<`o42fl$Al!%$F$?YikPU;{XW)WdKa}&Zg-!z21Z>rO2FMpd7462mm7C zG?W=N$p1v=zELs`R16(bsY?cIGY2Fw@Nne+!Up>5lyCBgpr-X#+vAV%@NiZQlr05BSjGoD7is_MG#KXMf% z(lh{Krr5E!<>nKRVNWX~={6h|Arvc3R&A7X5G8F8axSPW4W0Q)hCQJBr>TuhbInd| zi$Z=nQzLH@q0U-v6gNIi*Djn!W!goCpnRo5n)gScFTG}P58=GqiOqxmE8#wlDQ$`WS^k;HWMS|3`z4Onz&|#n& z>$*O6>^Oi!hYz()Ypzz)G(?mY33YvALt?aa&gSN3uh*NKn_FLBUteEW)q@8QjE0-g z!F1LEB7xXv*-V?fCJzo`^NBcyph6&F_9E5_1!e7}guA5>4}d6QkPKI8dUunZOeN_t zD8n&aHmZ!|pCHfBRNAh}BEsyfCdI5=nPVvriVVx9q>?66_$orz|M6Q#JBEpjvd@lE z0V6sx=JukRBa)&@-NK6hp$s0~ssou%`l>%vCRKtM7V}4c_(!|X-sRX4A;w4wbEv#? zsr$1?v3v2Du5Q-EjQjKA_&pegnRa$x&!4r-d*>8+P=Bt);sUM z>u>M8?E?lbm?FukhrQu;Rb}S8?>)6BhRIn$(>)KI`omjpxZU2jdrv#&EjQhvs`uRY z=~KS{+fRS;j@v&V5vuZ;dp-@|Z$I-loiVXab+Aa-qUgP!y%&J>nO0SH(_6UZ#@h;( zVc*>Uz`X!&xc+8jB9E%>z5kx+RrwU>2n4`A_kG6xbp5qA8|xdueGlAIF6pN0Zb^jv zG`vuaAy}mz6Tv%Iy3QNeZ*=V#W79NNoz&~~>phM>=%Sj?M5!lh79vJzc z*H4V@fBkQM*FJpifxQs25aGUi?<0aEpFB;{sDXeGT4rb7GcyxtA;~!<1HvwML(9nx zCYqa@nVXw=VDH{kEtQ4FCv77lx89cerkA#8XPv$K|M-JHU}ivOdV|4W5H)UYZUShU zSXXtB*zfn|=jR>sXf$q{SoH*v0E{NX6DQUtZ95uGVhH_yf7h<1m6g@eXxKFIz`^}> zU2R)jn4OucyxXy3@!WIIud3R@^C0q?PyF@4g9k;#Iaa6uBGG#vRYD9_$ZezAG))R$ zRhZd(zxVzGH#be=EAPE$&?8@c@bb&wYW*x>EmzL8k)?!E{fo<~$ke7wJ2n;xH!&yR zREyjFxA~T*S!+z)to-53XIq$spF+?Vc(n293?AUv6^dMqr zj8PPz$z(E_OopT3WYT~@>?F2PwcqPG_D$O|kw_F3f_h(vn3!LOj~zRB=m2PAX140h zfLOR{fCjAK6di%V&WqA$t^%}7_H^YvbaZ5y1?G=bIIOo0hqtS?ndUfAd zeqnz8;)^cq4+bXtK}77_cr^OX6Hi=t(Zx%8g*hMj# zo)i*G@=`^={M8BwxeZX!DRLz`$dxsAa_;DxP>zI=qhkJp%MFa6DF3 zI`6#x>t45KexB;O8VvkQ{~Yi+!_8p`fgLk@1_y~Evam2$RaL(~h%tsZX(sJtJP||{ zX6Hn7d3ias?ZU#`-26=22Jh<-CZaMLkN>Yfm_ubU)eX=BO*UY!!8YHGku1(X7$7AO_dq*lUs+Cu#7fR&Jp0RHEI3?pH8(scW5K`(I^DSFS^C$^{ z6T)bK-8AgW$13}mW0fd9wY^NpzGsWfqBnF6Hvrh-M|SnTGu64jrX{ z*jx^X1hQz96P%w$rX+YN#n7e6#(Djo|Oci%dS-$e=%UIZ~UaW=`P0r5D=$r%4>-7iy{RzvBD)QFGA&(~|M@2E2 zOk#}A`{CwrWp(A7hmR7``o_k1Jh4d6oR%^PM5L}O?>&Je#<%oP}WpjO4SIUH{ zs?I)pcN^N7nE^3{5Qm$a#9URCiX1w0I7(zn9V0$owFe z);ksA%3D=1tXfWmEc2J&KSb*-N8~`TW-Gm?46>-*Xl@BOK(u7AgSuKUJU9zaP)o_;`d z`7!AmlP@UqwW^#qnN^LBp)s+H+P1L*B*(6W^$R}-;BP_S%F_b?{KbFx#6SIo{{)3Xa++U5ikogwku&N_qbPo#zJ2P`pS<O`@YY7@Q!~HqY%-| z%*=;>`6K`Sqkjaz@RwU|zTJLu;|;gmxA$%U1~%P#^PM0tT$e$1|7Y(3aLWz16XVvK zZZBZgy$_^z(Kp|4s~Mhq_MY0G`_5bLFt$$RD+NV~pFZvGZoc7GV;K|(#?}jz`l;j_ zX%WF8&cJ_~YIy%O*X`WCQ;#?I4 zA?Vub#>U#_V9?*OWBX_{8jr{Qe&0FY#`gH~iSeYVtBO<{b8Hg?6JuyfX01r`>l8oly|dfr;VFtuL=bmlX3uj&O!!0?jm|*;&;dmuz({O`|L=-fJi+}`7CX`Gc>Ay(ET5HOqxy)rX#kZ6@q0F3Ekj>z%jCr+MRSvk4-t#5t1X#=wp)%n>O z=iSWA;G5qxT*KwqlCOQAgVrGgHC3-1AEw?z>?CGzmf12K06!%&{9uToDGL-@+WcCI9vbM;juF*4DEU#mKoD(|^cEr0Xy zSIc`K0Kex-0Q8lIyPgjNc=wg6z{3w~4s%jmbk)0|st-O?VxJ1otKMxO9v*xM`N{#{ znyZyTUwo*rP7;igDvy}!x&|O3HXCh1koTr+XJHHhMhdy~FLOuCwuX?Y(DCxm8`dl91>K z1Q-yi6ai{9p@P710Ldkv{W*3Lm)QQLIXEPNd~R{cm&7)ffY=lXWRQd;1W2GtvB4Bm z)sckCt*6YH*?X;@Yo_OcLey26G);_?hS`<($(>6G&?T!0_0b zN79LioKux*9LKg+<1kOgC{5ZqnN5^| zRmS~_T_1Cj5lcXIVGVCS9Q#w5JDsjFM(aW$U;J1@E|>RHuGeGo(NKSk*4nFGd#Ax? zl{&|jY8A|m;XO3AEFxqGSps!E37v>Us5dWM`ErxK-T^BmM1ZN~Lq9lEW6n8t791-P z4WV&jY+jru)=Kr}n~9Gk^~u+w?4O60QX7LgRb+BbnYxGyb5>GO68I-9;$26-3`;&2I>((|U0q$BOFPcJVE-FJXz_SQ zA4tx_+Dd7G)>@lqCi~ivk^>Q?Q$glaz{3q0PLc9fGV8Z4N`-ogD5YM4_fXRtNq406 z<|GCAd>WgQY=qVO*ni-Rjglf>-m%SUTp;r+>toIX4V>Pif=^9yzV{#`bFN9WNbmVG*ae_IP>#25d%u_lETtDT$?hk^bb28kWON&Ucl8co0i07_Xd?Sjan55! zlqO8Umvd2CLwjxobIKZ{dgps0i~w~MrY|+7exK}I;(>m^r!R%MT-(qg4UG+6PEn0` zfxu^tKFKFd+g*iPE%rf$#3n&tMC8!HL)xf*{rhR9!yuQ$ws2}qDQAolsD5bh*CJA^ zU*0I&%FNx}J+-*zoNH)kh~qelYT77gousM9YUk#JJQYO%qBx23`Fu-D^N=A!m^q4~ zATU7~8e^=r?6_PlTboYTAW{m7{L96pbQIO%S}Y=^Qb`+?&xg5O$c)6s+9*Xzn4`%0 zk&#%-?Bx`E9Y!Ig2wqq-9q(BQKUL38N*x<`4h;Jn0g;DjeAN_XyfU2E-RD$ykWwAG z|3@u#26{93Q?b1IE0_L3@VT{g6sD4`mrML0>IL~E_ILA@@fP5hE(QX>qG*;#SU8Dki@ zcJ}qh-|snRo#Vg$`m%@mZvW%Y{qf|fnbMdVkHrt+@ap4&Fz4=2?71SF5Gcx1(jm4gQl20$9)FS>a4 z^>Zz(pm+Ly?)m2dA)<@NUA%JDudbeT-PN$b1z`Ne;{j+=bFQ1aJcEs%f9?eU z7mptYV8!E)&Y!bj+46?~{PgaB-?nut?*0h?kB`j0cFxc5xjX&2ZO@ONaPiVd($2j3 z#+(1+7x(nt^;m|9{Mny=rEk*RqbqtWwIAL3rOX6>|@Gl0~0002QgS8&eFnLDR`@e4os z$q%`;<;#|vQ1{*Pmw)+vn~z- z?ISOq0I9NaGtA6vJvHY1^T%166pKY;OfJm%pRkU#F-j>L#~%cxq~u$UdTd~8#hCk&7RIMb-@)i20gP41%&Y|<@RybGCn3W?-Qn9m2=_;;5;tc>ynn-cay z={g94Kr3O-(GX{CNaWRby!qlJVX*>Osl`z_iYr}}gQe(5;$oY`&@}>yW9OXKp$dc) zYZEwvbxsmE2^iwYin9=7C@6PTL{w5kT!wWhHW*{@>W(8r+fN@o{ET5kN0CRt>vAD! z3@jDHsSk2*a(W+}l`cgQ5tNsqVaY1$z&e4oN)fZu8NCbQ*k#K8hM?hCX{}N<8L$&E zN?Wlc(%ISGak#x)t{iS}-??*FM|+2eFsQMip>1eeE(|w3OF$kt1ITAj_5iToKaREQ zP6k?mbMC&|ed<#J>;$@iSF<58>nA^HBGRAvi~_a;zXOf{Ie>sGmn5K)8N`25MjX+D_ot84NTP81l?Uk1_26wjr%5ZGa1( zNdcD#cr`0pWPs7nZXBEeDDA*oNI4XfH$3aT*53j?*T4d_;aQda9c0&|0Qcm2%C4dB z>!~+x(izmn+3|gxYGCSRA_A=xY0bg}c$u9oo6}^XOC~$!x_z$!^lNSrh!-q(oYJDa zQ$jFMk~v6B&KFx(>{w|)Sj49iDDT>^a~7$uQs?FQ>42q9)KB$&ylEGjzyo&unwvE# zMMfY42MicGWJqgktEU>pacqof(5n9cEyC8?Qn`m6TWb#;JVc6&G1fX}S1cAwrE(m{ zl}e>ticA;;L9k=z?pm$Z&`=biBS(&uOC=K+QYK$$$mMfM;&$xV5k*lhmm4;$tz0SX zJ8%F#_UD|@h8PeyYl)B~HP$)^^42+s#Bm(vas-ef77)m>#Bq`&HVnc-E}t$^qMalu z2*QjHLei-hBRB?Rkz<%7{!{{Z==wivy^x{c1T+1I;qqxs)qFlTa`^C*N1v206g)mG z?280DX7&@jueZP%nSxnBWRs*^tw3O{^^^l2aS4LJYid%;M_>ZHP`w`=T|M2Mot;EB z%xPnYG%IaE0&+q%Veu?TA!w~hODv*Q2&drk;>a)s#iBsiiPi*=C#4!~5}Poy(MAM8 z5DXa5zqz@|-%*D5Qw^{2#ezsw-OR3!`QcxYXFlz(4<`R1Oj_K|p{aDijL@K)eWppLsmDi9B`1pPo4_3)R}v-={+R z3^c6+rL4z5A?d3vB1-A3+>MYTO}e$U1t~8nWpDO$cb6-bO1Wa43yi7NYJws_iAx;2 zfQ&F}t->HwS_Oe|junwGj0zlaQ)7$KDqqM4K}ev))@)*(W5-qmUTD@@*VWnC)ZCEI z=d5#H%+NZY{_l$UMh_UpwK&a10$AMk?K^}sNHBeb#Hkvc2QKRhD!vwTI>c0#v+Z9o zubT)K*PDPs$T)vm^&L+ClP!f~*waV;r&VhDOkRB&r3s>xf;-BW69(y&#|tgWFFsN~ zkAGVn%hlIh17OvP74>!L>T6GcI{^6loijl~V(at-9fw>JbKZp7Bm~!SxMHmUU`Yff z1(qZg;j7EJGFuUH&Os~@IVZqTUF4i2U)DK$QH@bh^=!v_hlEN&(wfQ+MAuw#r673Yt>3-&#%q0defK-xJ8$f{(`HWl@xT5U|N7%&zPNVv6MtGPTz2Ut0R9no z07qeQPpn)CAb<4KPG9c#T zH~(R!Qnt>n%wV9c+n!_Q36s(T=FPpyDeDod!Gi~Tp%br@Tvw$Hf*|WX?%SV4L{QgX zJLj>L%RS6lC!;*_*u!&Y&!2PsyycHQ4B+DNaYJ*?;!<$~sZt)xk7 z&DJur0(q*7C=#W;8w+v}(MXf{nb|X7f*=qPo6>rTj8ZlgA=bXIm?tHt0+uY9TBc=p zOfOkZYDukJu6*>qnlpdShwNSV#1kGtpE2|5V|LyCtvf#Ci!*0lt(9hWWP>c4h`#w^ z0ElSK+BMnV$mjF9T+SG?e*HQC=bn2Zr4dN(6T&&R`Gp?ZQ36S!=xktc~)+Us$YIkK<@V%4j0*t2iMjhVsg#%w1hw&bfUD4(#8z z??^}c-aYU6EL}k5a$&y#{hOPcpLz;_0Zsvi0HXi{Fz^u3kGZ+}1X^ysk>QnCk zzss)w65v$t)&J2SbpdY!eqB(&XyA&)i)GOwvv5%Ylz=*L9DL*J7v6c-IsS`FmSEw+ zC4N*~ekmJcHf*>W7z*IN`ydXtE_?#$0^GDKg9|S@@7v!V3&=h92$8$>)-Hf1Pn0Yc zVgM{z;%TE0tD;>o&|aU z0ww@wW#H6K;0W*va0W047?Y8J-UT{<*MS@`1{eYK0}Svk@E))SI0@(vv;sqb4xj}5 z7AOOQ);}{8Xa$A=`vIOi_r;F(c10S9Jvm4z9fW~b9PmOsum0}!F=w3F+!B^5r9z<~ zN|Dl}l%H8$Yz1tL(OPLu&JnX`BPd0ROlq`wQ-pkcSSg(rnCm0qoW2MCv1JmNzV4f2 z08w1?jC1mmx8kg`@4dHg@7}#5M-FdmYpd1bj*gC6tyZa2M5I_Owlp=LeDcXgYbX-u z%awB`oude>m9E7#VX0IqN^20TwY6FjMNy?(4Z~1i<2cUe!=|PNV}jRSdv*8j-T5F8 zCa)Z4*_t3QO0ifGgt1CiF z-#oUP^58Q6y0-`Gp64;9z%e+BkO#c`?oXlhW37l@$nSVuCqvZ5D5Xe<#ApBlvEIYc z1oD;O1%O}Z2_Pu)p?{-vF5iS~9qF@tq<*NAL|`4eD5^S+;-p%Q%FGr)+%iZ~C=WoI z5hIE9&o|4}BZxRQ^6Ve2Z?dDJPZ)h1jV3<~ccc?S;%6DOgM0hTFhfuw1;4Ntt zmr8oj-wzowDAgn8^wA*8-$~0nftVQ?&f@#39uZMl{oeY6AcBu8d$LfqT8(S9_Vy!P zUEN(>-H*o;wHj_TwhX>rDHR00#niK#@TrjyL6{5GoOB>fTUoAEBc({6@d60NLLuYe zqgJcgH!t!+E$WQtPdVijPpl(?bNu@2sra2zYUGIFEiEk&5MkQ?-u~^Y&h`e_A1!;J zkk9Mjv<$B&pyPWpCIL{2#*Q6}3{@ebmtTI_|L$iWUfS5$K>D=oaWin}JJT)`;Iqpf zY-}10G-v2`xmw-vZ*vy-r*PJoG2SJPJUty!6PCd?aN0>nz6+h z$wk#u!bQZ_QPO^63Pd_*dx=4HTu*u-BI;u{D5P(cWK0!!l9%TQb2b=(e319(Pd=Z= zux$eJRb+hjtF-kv;9Ar@iBN|9EY zlp4@~K>z;z{XKQRft|YD-_7Vz{RRzc2?FD>SK&ly6$FT5>yuRCBqos{2-rDDT&-9U zGR9v$lyc5VVjHY=)>>mswOT9nR4bMAQEIKURw7akqGB=M+|t_E*hmBu7(l)M{`*Pd zlqc$F#VqW^--4%YnjlEm3-X$_B(*lMRfdZ-`T{*z;*&c70Xlz$h5KoF%pG{uy;UjBDo#u?E;Ua3I9vu4inTT1ak zXA=P5`?s%r>9gMf@Xhbdu{L7F){8$I5S5sPlk_Ct`No$2@4Hi3xK^p%^G~mQ@~_V} zK_Dy)8^sB;EWY!#SxvIV5RMswGMi+t{SToOYI@C~-E0cQZ~D zl(*?q(PAMYDCHbG=Lq6izQ?#)<#JC`V`Dl|kWdD{f>W7D%Cx=#5|*p4I{_MX!TA?d zDiyzQD6N0@#_Pu%@Ux%Z-PqXpm78z+AfNxqbx+N_>dK>@V0Prg%N`jzbZCKj@|1~w z%iJ60Kk}<({_ltGe{jTz;gcp$@*fv1{8Xu@XZgduWSlLVxAtAAtJNxzTDdBfO4+t` z+cC-3p6KUkCf@rJsrPVNtE5lLj~_hgN2OF<>c~%^%)E8ma}y_w2jJKd(cIZ{A9?f< zWDx1rty?EfoCx5NN0(i9_3V1m(8Ng->R^p;bFQDW{ITT#CQKZ^b<375n>SCIJQ=_P zOCP|3KX~w=RM&ROl*yYmZ<;cB%85JrgInD~`@Px;u^0e<`PYBx|M-(2Xm4*HIdWuE zW8;MJ6SUTqN~No->)m(XUAuP8Z~x|RjWOq+d*1B1v;FbYrcGP9a+U94X1;p*wU0ls z62KR~{3QTC`IjFzx3-WE7kGYzr`oY3?6Rj5fP~o!#4&qC9?x$V@v&5|!3NGG)sRAI zc zfdQ;p^Y~HcxpF2Eg<%kcK~$}pAb?0M_F;UC8#gf^3d1l60>2`jfBrbO7TIh5AyU4+ z$+2}j|GTX|=N~=u)6sr_A}_d3BraRmeDqwCbvA_|`sAJnR7&;b*hwN{6IXGFT^yC8 zjwG%{Ni}vAQ7o_|4w_jkNHmcH;>dZZI+rtwh%J-#WKO5FvMii9n^dDDDVJ)FsaD}? zIfh8S7zP1prNnZ=HmXXsOWu)pPWe6aSmD1&MDY3TwNaukA`%9&sox65*c6TeKiBu2- zCJ0+vT8!2kp4C7AoCI6|kqQ#5dqD5Y6ki?22Yx7@ zEx;b&bYLWKHZU4^B}2G218)Ks03(4m;9B4fpc8lj*bNK^h5#o6BY~m7PT<$T+rU{s zqi68|X9BMRM}Rkh7GMl87#I#*0K5+D1bToL;A21@m<~8#Cr|?R051XK0D9z+X+Qjd zt5zdmH}ED_Q#28!}Y3$WnW?DN~NroZf$Kf#u%mB+Sc(->i800| zHEXS7X=@u67_)QdF6TsP<*ZeTl!hWL0_U7_y&!j?Q0R-KGdu4P8f}zTY3iR>oy5 zfmjhZq_R#V!cK{>r7X7yHik=}lnQgG)Y_w{r?Jr7*wA8BCJ~T9OTH^SyC>^*mF*M= zID==rgQhw;l8L0ESbpZo`rmhJrYqrrG4{@$53N_Lm2yuxj^mzE>A}P2l*>gQ zSIy;e`Fze8qv&mcoHX(z6BwUJ)z#JB-ri26lqL}#J$iJ%{*C!uP5^f9*ZmLe-TR)1 zXgzfB;6bOJcB)q=an6lc{$%CM7d@shWXO<|NUq3QyM6l(WG3$L;ccTvjZ$gOB7k;VvTa3;`_4VwzP_WFqJ*RS>BzxMQY1tc#`8&)?_NgJTG&zS7~+#^f>@7(#q z0(5`>jypWzCW>lb`_`YQ1C$WQ$>1S_d@9i3!Gm6V?e*0?K@un4X8+nWU1d~TUAs*1 z7ARWWN^zIs?$+WIcX!vIZwtlUy-16@Lm>dNL4fOXiqfJxHOq>(;<-QV zc~~v%FfGdboL_4AAu+k`Z5TsQ;79fI5DY$is&9$C#l&Ip$t0MvzX}mwr&W3D@AReG zEU@p%9J6$AIO)y|O>;C9GpJbbBjFBTd3KmV4>WWt_Yu^jyKYAYjU=4z#RnZ@Tj_-i z>X8?r{$%ukz{B{qr>3;DwzgJ+*^p7&pQvJCGJay`9l1cZ7mxUh|8bcbb4C@$SyCJUF2ivZ^-2d);IzA`SOZYIQz(bJGt5slkkrX6I5C`Je zbN|iuI`18~$iFo=_47?RzI)h_>?Et3 zR^@+!UX8ZjvH?^p_*={yDAIc%0$+zlRhlheSXGgci#l*;!`|u^XypP^)uYbxC*Kcatr88&*Qf>3poAHmrv~K4DmWnpHFO$ zo1D&iV1)xhfx|kHpBspbl z*LpC;s^9z}3p`*fJWgqXM^9b;RqU1;H!Puoe>`dabxpq5TV%vdi$ed+ zJU`yf>*WQE3rPLI1U3bLmE{}F2zW}U|7E_O*I{+*LkQ}?ARLAbE86z2M}$n}bq=<)PRYObvVUCP>^T*Frus@W1$ShOzvc(}jW z*jAAy*#J^+M7!yDgfHLB?=iHVNj?3j#On#+H|qsabog(PDf|2mN*h7r0(<5!Cg+;E z1B#{AdACqQ;9*L`T9nzbvo%}g5;lhGNNm!?7L-7tP=m@& z;9gSQaZv`E;{vHGF7WU*<45(uzE3z^!G?*&gVsHQ3E00z5qN^D5h0+w&lbVu!5?0x zK!z~3byg}cC>jX`!J5^mf`Ij6x>Y|U#|Zu&#IXgZMa(%XkbxfvfrOKC6rHl?xdL_p ze|gg%taQqk8gl^K-mV3qf%2_C_bhpG2ZMuK_b5ONDT;ZoPwL{ojNVa`aMZj`7uSPV zyx9ess2gmipc?GfUgPK})j?K7F4qCK#WQ`5&73Z4mTA36@4s8EYM7ruZ#Vru?ak?z z!=BTOyNhNYFp-GXe?d+$BmS~B-`VlETYp~0FgX?!>zFX8+uj5usmWmEuV32B><#s@ zV@_JOrV~EOu^6Ni%-lcZb-4oBPnag)%h~E&K41!t-T&ts#v&h(Pd6os0jL2)Z+Y4+ zvCeTONw6kJ&X0b!`X2lkyca?=h)9SiRo_teOgxMS5?D9OM9spw}!$LNoV5zzX1tY1pT==ccI$$@U5>bAtC)Q@+o zL9fp{Zn}&-0S{L*%0iVo4nP~5ii!%5pPijCvLmcdUx<%>z*KFkL7mv!_>r94H9L8P z7U#Puhs!!_cQ=&-;~NJ}0!@S=6Vs?Ha|muo&E+Qa|HW zKI|vs(|&K*OsvL9AZRgdB12zZ_-d|g*`%f!=@^5Cu=hn&?ww>rBmAe<*$%ufP6Vso zhWss!D^SE`y}^Q>#A_QH_cao~0*`d$R~bz$Ev>a!0CakZivKYhorE;Ao9cVoRzY+p zb)rCucuq>5KtF{Cdy1kE>YDHUPMY-=@0OzK>X$G=K8b_0Ux@85=*giVnIgSPE_Z9~ z`MPoUksU<{q@5b;uoRZgLAZ7!^<-&k-0y~QHF}ca#s*#UHF!+d4EGwlizEOuF?H5 z^Xlp(dBIYC$s3~clV<_w-3gXfA#~^Qrvt$5*3LTQM^v4?LIFz zIk4cUK8!bLq!UZOLhkGOe|=r=z^FjQzV&c^zV$_aneV}3EXaFVH?o)_$NBZ8{7J(k zVeIee#P8_ykEt2-`{{6Ji44ElPY4N%{ z+W<;K#MiS)g}fZ>mC!-z!veSaaum#Iejqy{PTWE{gy3nDKb--yIYJ`OWu|`_w!4EU z#KsHbQQwg*Kq20&v0+%0xg$G2FafaLGx`IIk}X9Ma&tod$wpN}Lu0wdG_V!8WSg`a zz?+@(=KL0FOo7wL88BEWk_-FP6c!djp#iX9FeWBuUznM@dsMiGhsO~dN?$b#j7aF| z>!XKCDk(8@dwY5wuQb-{Rf?}O3t&%e^K5MplTmwmK(0#E?j@BO?HueRmw7J~&KAX+ z=gN|ea{nA3t(U9X?(n1x(q9x!UodGoe@?1Yrwoz}8F#-E7gweMxqsRqjqNw9dia*)W}2??tGwQT zl{AZ{I5)lGoqI?a?oZbl6}J?A)v%m}LBD^U1dCLJHsnl}4OXC{6kf1=@ho2hwHlRd zrcOHDy}+Tg08Yr)0UDxu^F9Bctfzw1)>n;`px*3&UENgV_FH*9ivQk*`U9Q3Vb?12 zarb+tuO^fE;GpLSG2z|z0Kx~ytY(2dHmJqLo7)-L#WyqpZrZrbV6^IC1>BYXcf(dfMg2utJ%_9TFQ zfRXtIkKSpqqfz-gm?LQ1f3MeC_)GRDQ{YWyv*1O)f26UsoNtXjo%LWLr1P6T0iX_N z>iaq2)~!R=Z^s)*Lmul3ad6k&gK>p!{jOMGMnORqpW{@~&B^NW;^O`O>$PpyRJ9gG zC05VM74vVrsU`aP2Pk)StKapo*6;{2_JT&6IO8?~{~nn>HjXW}FAt^#i?`L>^(0F+ zEI|_6j@q=AH}<*HfJmL7tlS$tm}Bzin}hSu_U4tzUzdciZOP&))rXgd%PI6X7Jc*% ziR)u=+eCjE3SLjs&x`Q5Oit$JPA~D;Ta9M>K5@=i8wIREZ!yXEgJG@W)kdwuaXosK zC?+Q{rQvsYhtr*H2a&`{^oAt#5h`vsp6XzLNWz&dfiD|rG#R-+-|bEMk zunkS#lXsZ0;NdKao;K~o0kq~sJuIA1Cg%*QA_iwep4e7RSA|NYU^7l<@`Aw>#rN-% z8)R$at7Yc6(D6zQYO%e@N_%+}&9qNSBMJ>{5T;{wb!H2YB;S^OZ8TEMS4T+LMn^V} zezWuZ?NL8dUoMtEMP8~U_ib8Olr)V(c_L!Q_r&Hw^7=+oB9M`LI$o3H*`QKM%FPLZ zP|a0xd-?1^!p#j7a!VoLwhaw5i%%F!_EH-lg>#~UJW3FI^dpm<wG)#sZbYi5=IeBRiZ;_kGXT#1-{H1k+SL3nC$lqDqaqHcdg#37i2;%HUEP4=E zhI3vhH7!CG|9XtRGr8A<$jA8I0uJphl_(!A8#NlF48~XwHiW&+N8#XjM})+J@p@1s@^I zA#mo0T!zd5#212Kum}u27=-w>x)Wrh*U@qer+s+7#qz(l&w;s5I9X72TDURU&`8ee z9Y=T`Mq&27+3N4($(q>9(%0{y!p7cD?%Y{a%1mZ3GsWd^Li&Ja>6K%dmFV?{>fh(F zr26?E64(kUe}XyC8k7$a<^s&jlc$hU^~gx^bV!p1{2B^A2TS;8C;3-$g1PbkQ*Fj1 zl~gTCLDeTlP$e5U?RpI)oA>im1WbP<{4T2Q?&ihn=UT_#bKE)flD_KwFf6WOC?hTe z8h>S@iQcJ!M7>^GkNB0%KtJ9!>u3G%KwN4RiZ!>dq&8Hti)b8grNVd`#+6BE{93n7 zM^vm(-zXa-Ux%ABxVDcN`?^;-;i~(OpgZ6=qtNR&ryJ#>vOsX6%-@jYQ@O}wPDNB{ zSr~SW4o*{cg|Btl4o$6=7tcV1RJQ{%Tgri|yeH{GRHWqnXY~O*6jp05Isp72{h@uQ z%u+vxLLE^r9UN6*Zhh|1H%m>=qKC8pX&KKA4~PGplKPZ#T&VG4f)NayY5TmhUr zd~g>#Ue)uXJQ(32VM$K9)xR^I8E_0S7BrKRMAGMR&82xa%n2R>DNa*?MbNM1p{7K; z-IwEHU9F`;!BhIzrq?O@rt-}AhE85Y-E8BEK_>Yw+ z1k7k^SV@%$7T#qiYGLjR!Jp1%6iX*WFXHpIA%2QqzQin^&6)Q{`#v|$^A%9yNNf+V zAHQsd7K+?uj_h=PdifjV>)ZULq7iU=8rwM8QV89UReDNEZ6zzw4Y*zmk5mK3b8YSU zr7lNe_nSpWJ|~Qxno36<{pGWOQ>gdZ`k#5@S8^%|qG)1wub=U+i|>cX&i~&FuyP1W zW=?5d3w#`p$qFywx8djp(Z?_~V1}yOI1h~HC}cahHmMF?AI=BqEY|?u5!=FcK_MAn zxRX6iv6u=i49l5R(BogpR3UhOpYa$Dg#gl;LSi%#XTi@}*OeAm32Ytfkz(NAyNx2=DyW(9g{JM)mJxA9(68ASV;pG+`l#5gcZBXw-^{Mdju7zCJe2S3g8^MPSKYAD(&s5LjQ`L^q@M3eB8{aww8V@FfDcg$Py{2p>%C>9mR zRQT!ph7u1Wwgh8keg{XmdDEPwJC5ZLYFTU*&%ZvfwBu(I$vU9B(NFO zC6qw0#)dnk3(lz$60O2A4yM^imDpj;WAvaP1rnR<>gLT}nN30Pv-8^LYXhgpC7-gd()^0lz|yDCz1i}9stPq06{Gw< zR+T^;(YW@we0|M*D&o>h>$cjhq0ORjo~E=HgWdoBQste8Xyj(>4F%3Scr`En9|L=_ zmBPzH2`MfkOlw0N!=`(h*^n$j@SHv8qZ{wAT4cORmk5o zj5jpBAC(n1x$M0ctc8Rv|?JGR^zAlGU@aFL=OL7qjWso3>$Ffu^d zWi^J!ZLR!TFZP`DkZS&PUzybuF}Tf$7xIQ)*kojvmE{6e!_PDmnGgOnIc;R)GV;rj z+R2KN%o>h)*~lArwbAFW*pZS0y-G~><_>}*SZ8D$_GL9WEuwr;Nc?-AXH) z56S={SkVw(v%_MY?G~Mt_r7HstA6L`S{)jNugBsxV-m<=wZn2G)$wQrShr#gM}Z(d z*1PX8)_{K@fuUFY;Sl-W4YjH2KbYuaeWjxGP zd7dK4UuEed;ywZ5g@Gu=)8K#%(# zJ=E(qBc$V6)sd5>!z#qd#l@)^!|}aKs)wDRr|wpo$bzczDnwMQYmc;%onc_eCG12< zhXFsb&y2Oq)5{a^QtIJr*{iW(1U>aorZA`6+{6lV(kkRNxVaU$l0p$&wmInGJLwZT8ZoI&RuU z%)E{8Z0yye7vvZn=Sv zgn6`gRk)sIMC}q-uabzs!ouC5vXw(38H@I_#ITOLV{VC^}i#_qDD&F zGNmvb%PryAV^NB(tghAv48&IDI(5|v##3`C@-#PuwPsJ*ZP7V%Vxf*BX9jPIDBU%M z`X5%Ff=>}16L!Tgk;V~G;Pw11jtTlLgJ6J63brFCAVV_fv{1l-0Yamiy;zN9e}m6z z5{Zj=7hpuH1LkR#349Tkz(T=kb<{Irb=^!7gO<=B{=C9^=A8A-NMr`T$2h4)wy!Ddw> z2X-S96~<~bU1Rf;@^ULzZ_Rb*?}f%8F+T#C?;|+{r&;f2UrZDM*ha6_ZSD&?ujrks zQ2xtqmVU@)*V9N!-m5=i@Uk-{X2Z)qq1W?eoYBZO)hvjP@g*KRZO0R>zE!hxpY?7xWz8zh52XquZn6b zRFj9P2qiN$4>CxIYx%~K35^|E4A{Iqy$4)7yiXygW>nS*n5N@<7p81~hkcmF0R4}Y zH0h_*4DgVH0&DfH&XOXZ!qUXJT7F=kARo_%%IGrThZI3Pb)Ad4%;knq?oO#Upw z|E^G)dvd}D_c331c@8YXB>8mKFr$3PeDrwIeoCjX86j}*AE>j;!G5suty>LWW=iOK zBVlAm!gGgEjF)=cMWnby)#l$9Z7?GFtfGoY-K=$faU!i~ss$^={1FJK1hAdw9<;U8 z7ND!#_>mn&l1o!=zta+i{m%9ujwKfoep;GYt%uy6OclyO>KV}fs|R2pz(GQVp8H9= zqTs86ySmnQe^!BdU;rtl8NWDY|K;DDH-Rt z16HjGACVq`z6X>MB{9z-XqG>Q|@K+nfT|H1~tSQX67G* zhm!f{nZN9;u@2)`%zTglsSzOwwu2~5%f9g^79)NrOv-?LLjD5c;p5W>2(sZFw^oDL zBpQtWIMVDLfZ>PB$YieGSlwFwyI(nj-2cjJSq|U%zWNh&!OhK0c~wRl^Y&$*nMw3q zh&(jeZ}_-*^o&R2Ns4v?;Ua*#Jndyb?!I=p(<=mqtcNW7qZP!crEZ_M@Rb zkbq=dJzBOza9Z~$jlmqR_2ytEd`z5Vb*0W{v*(6-G2e$mv7pDhy!MM0Y&M?v&|0hhCX9=5sCdR zzMulVn1iBp>)cfx`quDpv7-asdEe0mqRYF3_skUf0xoA%dt?cJ*_Y?zt>`7v>&$tb z7t45x5ncc+M+a`X$t0zk)O$3O)o*e-cg|G*75K#+QgUH!R29FOkz zkFh*%W5#RMU*GC2FTYyly5Ya`G*1NP>JFd*K@^pqIeedj#u0)k11)r)(*fW&Yu8ws zMp+*IByk)ja2eS6w9%;_>)XjU)>T?tx_{Cq_83n8RNY9r2WQZQR}3Ty2?@z;Z>#mB zJ#D51#2K{vrJ(sYl2B9c>$i4jm!;}hGUjtrS>yD~gAJM|(Yr=bf- z9NB)jeUs{FbJHi%FGcGW;gxZ#tm%+Sxkg}1r)$_`rryoK;nq&TkFz%v* zHu*d6v7C_3F7sFyYk@JL)%J)IO{V(~w-S!s-x<~L9d)`+?hKQDjsI`?_!}`6d$?$V zU9bqQWbdZy0zB>2r9nGUbS@%7A&z7zl`+IT=AV_6%-Q4wu`O}AcpOa-rZbT%KJ||L zwY9;MG|?{jvrBsEjn-vS2LaTM@>s!1j4&E_?47*wT;Hl+&& zl{#JGv0|o76dOBp?nqQVE8D&&T8(!mhV-`*8h;W{()f>0REBC(wb}$jF?1psmsXF_ zO2Oe`F3Wk=ZmM-JI&?k9d(HQ;^7xcekVwXrHG+mmP8dBbJp2!Eu-m@8+CpYPLRAL_ zSNis+W!zT+zfnD#t&}d1C~Al?D8Lh`tojrdhzc-*cVK#71)n$AZb`yaANW3O(;>-A zA}Clq(qVJ(=346W_BRQ0kZdtFSt!*N%}u)Jm6qKY9X>B;$vG-)@4z3`yV@Q#=SxlJ z;r0QC`fKwxe;*D&6w71|xsSok;3)8;%Io*TYE%w%VXPwtpI-o@d1Fffw^( zM(b1P6TsBOMW3xvi)jy9{^2}xzBqcz;eVIsun-)Ni!jUq=CeQ7WDS8qkA)LYJA{E4 zNLq#>ufo|uFTQzCP#hRi=4cGx1LgA>z46m@lmy+)QN6qlrLRQ*TCY=EM8=R1)akhk z!BHIktc*w%S9c?29WlaX=I2olCV=~2(q69mRzYu4 z>L&t6g`A@~d$B|fz*U|5bePWn8t1ttkvo0i0>1xUP4*yNt$NI8Ngv6~8xyh#>j%6v zgWNWGcdiz1SAEPCcvgrJxYi+idClH4-!zGAyG(n;@(?z!4|`U5^PYO$gKqZ3j!U=w z{{i(2zH`KsPbQ)pfhX=;`ppi{KdPPBy~2SfD2GUlO))^QE@RSkccrt=pKov%#9Z@! z0pT+kM->H*L8e8<3id)&K^!yLM(Q9g0fjX3A|IjLfVRYmemWz@vP`zQnmlCM8|7wZ zU%`WJHvqpJ>c1!VR@JPqk|Kq~K4gB-p2d#kn9ac4q zz0BiPb8}_?nkqgA`S(aTrknJ6{zsFgkDGC?&_*?vfP)nDckp)~dUx^D{F!%e{7=4~ z8l)DhVn+J$M!NG?=zJ>0mKcn)`aW2zW=&a!waYz_t!yOKp{@A;SP$@Y7->)NQgDd&Ek z)oV&!ETh)mp^3jU@YPJt?+q*D7xbEu!7yq)8k|b#Yt$2y_CrP;CarM6eic*cisW)D zpY`iJFZJ#`G~D5zM%1Na{L6JKtI2_to0D}3S5a0zS!%RT>cm5>GoqGkRcGug&PTJY z|4yXmpYQ*)Pg^S0 zZ9(+oq!~-c!o)}MZyH`i_{f4*T)#Qi#c)m-mPaiN^??cVJh@@1*0?#ao? z!NI}x$zaYfamuIL%Jj@9v;HXDZoT^x z$MQo@{B2I4QP9~pN_gN62uE4aw(sA+l1A6|+1!jAQetwh%M=laxkv6&tm3-aZVdS) zJuhu|i8o+kKxTZ9i6Tr>ju@~@i?`{WUJ_DmJR$T#;ly$~S1em}n zG?kh2-Cg14zc);u9n#%35fIRuIUi;2Y+Pmj8 zOaT9d@pWumVUbDO@bhcG!h5i=dW%6?9f5hyH(ucdi9ik=rw>#XBe?yv1!7b3O2x5x z!J~cs7TXl!e~AZ&n19BK()FH&{G|x~0M;4#DPDFk!T*c_N~>zkWoQj@G>QC}|X4onDMVwjITz0gr_8Q?nY?hfRkS!C;XK09k0`o;`~ z{EE|1fee_(IT5&is#f_Pp6xC|F}81=eX~%QMY;Bbq&d!i_!-m;4;(2btTwEFsB7ng zFA6Du6cUBc?~*nG10RLf+RTpInAwcyHAV%V8#Mk`EH{wnBW&N&@;!=e&EYcC)&5rz^Vj|$-UAw`Mhgor(rYSS zpt@RS4#y035_3W|lt8b& z4BPZ{efn=J2sfcSQZZF=`ioWuCWE^wrv;iS)({ok7pEqDfr#q>aX_$_p%=L{i)sTp zyu%&&0LEdKtTf8-nJr5(D$1f`8v~ILk(6C&1zlWm8`b$@g?4CLv86G`$oA;zM=GvC z{^DzL=RgFm zF_mh0y6FERmlt%>#hvw^nwcbY=yso9sQp+Yd=!o3PN* zDzYdFE+-m4kYg?#Xe1?xJq*oUcMg|nl?&$d%BsDJ2U&cK_tTcXdQ1JrkMo1Tr(g5O zxoH-CN}|3R6mK;|1xPV(Btojsqir}2m?wlMTYN~)CvY(zl)1B4)b75E4Y__}Z zSEiI{$-3t~hbuqHhmNGYA5-|{6n^Vy;A%V<_PH+w9eQB1cx?21u(c_o{T~e8T-}I( zpUA%?aMjkG~TXS&VqX`iW)EnyuBnXf^dYr^afA+Uh>DZmkX}yu9>95e~RA3b%Yx7`TZ(hBpf3M;EKxnz*WW@=gAO2*K7-=zXShvwi_W2$8+g zj%6rHD!c65-<6}l60SXVAN(9N&9_u2phOGx5HsF!7HNGyhwJtkQY9Bhz^W1XmQ`&L;*1KYo7Glt+mc)Xj3MNpn3Ti z2uSwz^YgQ_i$s$n_tY$$x;vO+4oUe98nbfuf4#%R!wd97$Pf7wGV%Lji004vfE;xK z8XZ0F5t-6UKvX12PagkuvL95G|I=NpcL!pA#{T}|;v(<`c=TDRS;!3e`9C$dY;=E2 zW%q`A3+7~G>}wnO(kdkC8CR+^#<3Z+_?+XKJEs0R_WGZmE97+~p9mNrZ*Fhr53fJQ z33Ek$Jhk-l@&fvOlalZ%zmk@*cZ#q>^E%JT!7wT-9u|1{CVYm{g$;U^qW20DH?K3T ztek!5-c*#a{u0umddhxpfJ=e8J7w%vgDa8G_ZtVvfGeNu5;g{~kCSl|{nBb=7B5@s z29;m==cxy2n|H^wGJp5_reRLHr=zG%tjI>ZA(M%Dkxk!dTUBnJY2-Eg#WIpTQpe(% zap=*mklCbvtXNDUlko1{-$NccJ8waFyYlbDzVhe+*P>t_u}Kv*eC;yCu-4g=Pg#{# zNiv_l;92+CU-ySI~-1NYpu2`D4Aqjk7-`H$`c-T zeq9v$8Jj_sNu&I};ON_(@aI;|<|fVRd0f6NnxW};$=P^m32*zF5R$1XO8*Y?sM*qv zu|MC&yq@!Qo{yn(?F#PIYpb$C?O)nGarm*?tX3gqq*>l1arOIIn`XJ-j^8a1{ zA>(D&^yQajN-?+DvMm+<6CnLr;9uc4s`U2L4v2|~s^)IJRaM)ComT7hO}4e`9=Uf+ zY^>z0ulKGls-O*9cz&&cWIiZOo zPCK!)7kheodIg5-*zl9~R|=4d=yh^LXMCZvK>Y+Dz76_&HXujy02&& zDlC++;+=?bf4WOUk5f6jUSV0q`XD@Df*hK4xs9h1n&m&2VO`OFAflU^VNxV}H8x-W z-j84&RMoP5!5=F^bH#AoG{7hJPL=AdVc>p>=veqz&ZUl|itr0k`s^e3Tg{#6sQEC8 z9U&lU9Ok4VERml}cCnLIdAWJg_6T$373<81P|5r8%dl;i%l!DbnUWvv9Wm&K(s zkTc{e;hR?8p0oYeYK6q28Cxt&Ot|mF>ZMrQ-nbAZ4i59))W;p4XdF){fB8Vv{-1N4y(%T-z`IieUY)sWb<=dtQ6J%6l664PFU4g-YaTg3l9+hL(IYJB^>Z z(*iFGyTI${uUpk(4? z#a_catdZpTn3Ql{9JwGL^TD3BNgCy|t!e`<4*MH575TMzQ!66o=rbGnUP;wh`xHAV z83hbxV)MbJQBUi=Uu0ZTD<{7+@ao~dKINgz2AQp&TvweoX`?nvs=qR7Q;X*$hIbr z7hr_M`iYmYI|I24Okkc!2z^N&%P>de_GlR&4Y}nD7D~m>w+4C!%6Ce)1?bM_@&P<;H&C?S{)!D6Bn1ed=Du_-S(#*x3C>ST*``083b4fCN$3 zHL2KYo#o-`EiV|6gX3*BMl`-qi`Z-ZzKZ|FZ8*_a~^`UfPRGZAG!r5|63vy67ly``EQP1XMxtLRc#{{ zr^4JIC-^pc{^|+;Y2je!2Bx!4gG~Y_5g8dv8nbkfpvp?^*|Ye&*z(&4v zZbJ6ax(VUSnf8-TIq27ivaT!iE`BaSyDx0*3nyN;$IFBrGCxpI%4R#&1qLuHr#kyv9mZHx)W;tvj~_`x zf%5Xq%CF7K3NtK`1z*c^ik+;ynr2RP?Cq`}{{6El)hxTwDr8Vjv~Y6rGV@3H-rBkg zxaD7-AGL}N*x2Kyc*}s3Y`RcJy(tgc(>SgF^rbH$oGt=o#QmhS zO91P=xx5xBGjChKypH`(w}ZjT4^e8Ngn0s5><*tTKEC&8-^Wu9PtMq62vg4##PQ7F zM(M|8^lmRu<)w-@eJd!eOGjmCMM`YLa9wVP-SDP@LGUId>Zivx&OmfDi^Jasp0xVW z0o#1R&0qo6_dQ8Hg1DOBjmht4w&KJ(4VW62j{&Fa*ck5sJv~Ktd(On$KSpHfk6IB7 zv1X()J1q_s9}xcSsFPLeHP!{W1ZVWFTm_J68~;i;ze-C!+j@E3 zG|n5@H|kOUZ2Y0@GZS&`C*pjjntgc`J2W&zF64#p98XbecK;u84*&xxM#OXdE*Re< z@6oBM;ddP;HbADjdcQx zf1A~$*zLY&fVE=I?gO_r&fXKB*XZ$TvvvqJ9$>m%UoejwJ1%)o9q4AZxs%omO6FdP z7=OAO@31xeP-dGb{Q87$n;6EE6CNw}(&AT0VZ=n8nUeu|xhH%ZO*D75#sdWWZ-_`n z?Z5+aw2j}?W7e~>>fPOQt3++eqbp4YKyHzF)+P^JdvWBVqhrJ5whVYhM4;x6u};nQ z6~q)2C#R>B6clfye|nYAI`9q*&}WWWQAJefHFCvnsfK)=4S2k<96w&D{dn4^ffV4x z$|46z*=2F34g}ydVdoN{@>lEC&($@C{=g4!oe%GArQ>U`&d0~^{Ljeo9IaSf{cS@S zK2t%TXv5_rH?ZvLA?##~Y30D~l@8F}(Kx4lQ85m%6PW~0?h>@MINPq|HtO#DJmB^HQ94;H zBfp85_v1gxJh|>vw4ymQeTFysga};r*uq^pQ(t<0hqC#v%i!t)v1V!?YU~t3_XO*e z>#ARd;sVc`W36`wWnZ7}^PW0Rp=V`*(WFpqt>b$$lBJj16-be z+#Ij&Wuw~S%k-z`w?Zbp#CKXmtAJ>)m9u;4w(e4*=6+3QP#CKT4{{Oo0!*sa$-xZ?$+t(C#yd5 zKL_qF)}D^*#U2-L9GAi2g8{dc{^pSR3wz4@M&KHC1!{rc0PxTE6e9hbC(U5#l6>Gp zb|%)-v}Zkcee;^H?qvY(}zLqOA;CCN(nm;%IdYF1SlUHe+Z5>!)!W zGMo_2bP&DhSly`9dz51SDk3(0Jb}F6?90*;Wt9mZEHfrK%k$Kseg|R}BSGDfsFD_C zz9DtKc@NRh@bNJ(Nj#ltPp00_t{JF5?EAZQf~lz+mXAjT(tNKeO!EBlaJd~EDtEA@ zKYXQjgCj>`eXIK$Rig+}lBDMVZ-4uayn_%8kC;H1;QWCcZd$>^OCw@x%6AyUmCR4U0Z_bpuT8;oOOhkeF#(XuFFbc2 zQ*bse1{^|wL1&uWdkh5wodJj;iy?K!z*lx12bvBF`QR-9Mhc4vzd-}=mOr@iz13ZT zBnw!=x(s)E>kU){?w4cR&pCwISP9THWH*=gDck5V4DRf<~rsU=i8$&|CJ-^hde;nZLgk$Wy zzsSzVq0kdeMiiGCWsv+o0Et0%zS{t`zxd*dcieHicq|whzI4r+g`*2?!F%l?DO6Yv zC7pJ&*{t;SRVr0xf=Fnw>^U~6=EB3_@A-Fg-bJgb`}a@G%+A&N%8M5-wl?>fZ?)R9 zbFJOG_xANw2L~F%3kEDlp&tjzX_^{qRFNc|EOm2pbGvr!u2if2jfROV!7%gm?97fG zJ3`Ra*Vk7nm4=6htJUi8@NlhGkD^GtpKCUMBJ5eQ9z_Cio&$QT%#84F@%BDJT~QHim%U!-7C|_ToW^B75`$7Zd2{Bi}eW zJld%B=S>)eK4W3M-Mfu}oe@qWj9XDf`Q5iA-6V6_%=FB+r%#@oob*Ma+xvGmY^|-9 zt2VOMSRw+wRIk^UEL{?wJ~OL`%iPrT)N9*!gn}Xw)f%;hqYDRy1`Tt_xm0v)&)BQ4 zzN&?{6fqt5#^dV!b;Cw9Co7%v+>RGse6iJR0#G21?9!!6mn~mb%z;FNPN)0hAO1K@ zi>eAje}DfG%a;!f4)i8BRh^oede`;$GqdDajMnN$07n2+v{i;BV@GRl%okGJhD~36 zIk2*T)B_u?JvaA5DE?vHHDQ$AaQm%&eW6(?ps@h}>U26!iwFeQt@|)Bopkb>>h-#a zFP2E%^759wd-wII6U@v^zjFNIdZXUssuS~#FHh{-w+{u`Jc^>XopOq`IguHvUUYnX z|CX1xhWDMBhlhtpM@Luw()R)K-Wg-W%g&v2w16vtq@H zI4&(%Fcc<$smV!I-MMpTFz}*+KOPW_aQWW5EKP@phpT;k^?Lo>mn+7YD6-)Qy^3aD z<_wnFg%PTXzD~0Dz-$y6`H8u3%TNNa^ZT6(>qa>zBB$;2c2kiobF;HeYi+3%m&>Ihs31{owOSJs zQ^xSn&|tM(CStGNJJ;@XJMDIoBwnOkDjQ>KwVJgyys(+e+U-ua+ewntxhzf7$;rti zNtwyms8lLN)<#j}gVw2twRUD^cKh~;|H5Xa!)~AW>?Hy4hQfFds9LHRYa#=OwrU!n zLRE!hpXD@=h{=*zBVbaYa$HK%c9wZ3$zS}pN9P~^U;p|r=F?%j;EFehN3+#T_BO?< zWz)Z)u0+l0E=WP%Mr^I^6=1T&i|+>P%2I^LM2378J9DwWE7eQY?}OZo_nrXD=F&Bn2LgpLM!i>}ed#{U-2^lQ2k%+;zVKZ=@9HbpuA{<< zskf2hz3+KnkS*+abzgDWRmd_C2~9I$xxMD<_jvDnS};%%-urX(>L8lTd@Kfscxhd7@x?PUvsVx$Nzyw4 zfcaR=zy0esFPNKs_SxrOef3rEwPZ`Bp-SeGbKiaTL*ILN{?X=J8a;5&y}9m}1Q${d zAZYmAckkWv5t)F+09dqS@zz&g2|uSUD{}>bHlK6O3#}!_gZFPz#rYTIpiDqvHr;ps zU3cDj>1CH4bW6`U{{Y==(*q9#f@0ug0suHyjVyi-tejhJxwR^qIVYl}l4a&3OWW;s z6h-AquEqN=H{G11owCTng$t8zCL*1r8(LU*?b_8+HOBnOpZuwc%+55Ew3B7&-~Qd- z;^%CJ6`C@!v9?@NYnkJ2xdamlvygGjV5MLa!B8fnBxFnhqlY4gGE0)Fc!3Z@l!W03 ziSupm8DRBME9rW1X_^r+D`k}U%o(r)vyyY3Ei*`vueqe~E)((9zLMcml4ME8hv>~1 zlXSZR7nLmKH4hQdEOFs^GmI$_2!_F-NtQ^QcLY%lBD&uDkRuSA;M*!rM1#dCau{93 zd#G3ODqe#KqAI*9L-Sz<6&3GwZgx&pm<^!TSm(vLBu%ra$*Ckwn$6C(9oy&Tnkq6r zK2AhVeEwo0_>|;DzsN?lTCGy9M5QP)F^C@994wG(z#DhswQJY&&;D%VJ^GDrGQfbl@``kPJm-#y zYIvs}xc`14+`rLKQCseII^z=)l1qAMU`8~X&3o^?_uh@fl=lUQ_h!)EFUc`%dWf;z_oxc0fL#Lm9 zy5_cG#(TeH@sefB_P*<^F_1D7b22#iaJ^nX>Esin@F^c19W9s3XPx=Ika~f-3rD}# z=x>~G(g~q&LIlSgbL=NSx#W?DzsI37S{(7_Wy`j|?X7R=>+5SY8aHhi6zN}o{V?!T zpaYBnj{)?7_b)%{=%YtRM>lM!5G}jzy2Zdzz!>l}@Bq*NM)&W3a~#Jv-83N5=yZa;tZP8`Q^WDSB(pJO&eY%PZrJ>vY0R`D`#-3+a8 zM3i%#f<-8CWFu>BwNj0uh}dM#r7i`?TAR6yjR9b-EtN~PM&IDjP_sGbT-xb&M3AOQ zr_&wiZ^Wf?sT4<10={5r-)jzSbKWynf;gbWps zknuJaA{YZ>lqrby2$S!X4Mc)1H-~99iY&8&l!9`02w!2CBFk}rHp24Ze9%r8Fj*6~ zyGfS0)cNpggh%1MM=MoPQD3f<#FKXdK$J?QvUgs*%jawo2zkv-bA#!Gg2ageL<%M- ziKzHI7!UND@Z3d6L1coCrl?AmhV(CI(-uYifVjaH6?F~9F(_0cK+L)FXnt$8pcpAa z(%5ddRkXQ(VtRUdYI>^E>F#%nwJ^6LK%qojDwTqDaj?i`;*pWzzIrw?JQ85w5Qt7s zO>N)4!(~pq3)tk+Wy=;VUKGlr;icHWe|&uZ{>iCHEl6awT5Z|VWdnl)fuIT^6^!i} zd-25=Tdh`jo0$3JH@~@5Dgiyw8+6*8=bnFFbB3A(r0JMrj;dDsioyVhXkubw>y|C= z^x{Rl7gZr4T61FpC1UX&OvV~ubRJVOY~8#ES`XyO0Osuwjuz!QfCaO( z)9%*mjY1SzL9~4N@+3*8r>Ci4Z2`P>>(-Osd@=`3WdOj6l`Glsp0Pb)N)eG4o_~Jj z%9XWxJx~{nq0!NWt!8U%Y)`;(CMG7Qr>7eelZ{5hTBE9Lc-gY0Q5@~vyEll8?A-C% z`2O*c(UIlLmO??G(UIZ4YIS^k{IwmgDbQ}UpMCaO?AnVXmZQG`RSXTGzrQp%RC;Y^ z(rl(_7hAUcv}9Htxr&+V^?Dq~gM))7o>(2*y=Q8Ay3^^r^wLY^N@a9pq|vDN4-C}n z^?JQNI5;>qHkM`StFLae*2HmX<;oRN6jiI$QfbM;g^Q-9rrPb+o;`cFZQDk~V`H^t z%a$?o;NT#Ddc8g~J2N{w*J?JKttJZERKUlXqsZEc$;pYyseyrknVAKpQYnt3IF5s| zc%b>_$^ktrq^IXFuc@?{htPXK2U<;`feIIT|HEx(4!)|0=b83_FG5s8h8l(p^;*@3YKBQ4~eC6vu3GtB%N8Yi%4w zfw&ix{$^)q(=<)fG>&5%MU6&dU|_%)V~lmqEm_iOHk(A~bd!nk@lL1HZnvw|YPH%| zE|;0f+GzXsiNnt7|A$-7j`{O1uM;7tRVDH8&Z~&EHj1NQNFGNKKujX)tQ8Y68`Ey3 zX_9%#z{&>9YS2tsT7y0Hs|;;$OPLeZ;c_)Gmq~%?j6HSL~K=| zK>`UxU=4x;(4>{QR2imJF@TD9X(B4bFamMT5gD?~M7y{CFW>#6k34G2D_a39TeiH{ z*{fk`LNV}w-8*+3_TN`uw1$XCG%m#ouraFIQyU4}6>F~oV2GHE_s)4AB(lBA9d~|b z{+^ewxm*=-94kNs?W9wdF;Gm<_W!pCeqk zoIXMqdQd##f=w6Dkj%TBSqER#w8*ka)2!GBy{fM-{54e7aPU0KWdcJTEVT9!hgF$^ zEj&cn<|t2WZ8&*jZ05X(SJlFvISvbzdKDEmCfJW31Yv~jnk%m%X73#U4LL~&FPv9E z)mv-HvKJwj*9M8m7kd05uw*EaB_J-9iMiYD0&qS6@ELLvW{CfpnZ1|$?#s{Qq6^j# zK?}R#AgvxycFU&M(c`@9B}?-$tZ=10deMa!tS%PNyh<6K(Wb)X=dEvkn_)vtm2$-x zqfqhky~iHz-H;2;z0f%ySOY;6%~~U>3f*}B!PKPQcG>E+fs|N~R$Q13)1>>v51#sY z{}r}-?z+p1q)D=WeBblWJ>P6Lqd5BefB0JXbj>9fKlj{o+qUlj@Qttk>)^m(h`qFs zJS*Dc!C(beuUP}&^Pl@4AOGFo0dUvtcmCv=Xa4XHfB!!|hp>I>|M|>k{^(Qx`ai$E zU}&g!lP_3(fLwFyw{NS}Dq&I$1wjQtKm-xr?RG-Ux%SGued#a%;`4D_0&%z7&73oA zR5f$1+wDfy_Vx8y!`^!lH#9iB?wWOnp3<*>>>_JzP8?+rlwiH{L1x8RHf+n~IEt)7 z)OCe2V_4+?xo&Dr&;P88~)x!gpq z022aGQDtSzrd%#9U$%UBc(`Pv%sV39KQXy~|9FfT4 zTCKlcs|D%V%};VsbzBM@4OBk+*?iIy5vcy?hd*w&TK8?rf<^Rs?-pXR##Cxm6*0zo zaUxKK&$1**sL<4;AgeEG!h0v;MM8sBsHvjJNdn8)8dJ>blur?WmjlFLhj)OG2Kz{aYojUw@0!a1vg z*l?bX5|Lr!oHv#;=R)5J6|^0XJdI{!OeiEk^9xj{cmxh_5wV69HjG|l3{<>$6=62v zeJR?lVVFVG-{`m2I_Fe1j^iZF=4R&*QeI|NjpDekuWAjmVHG&fCo zq^bxGl4+JK92prI85tcNu2!o7IWpFYYDmsCH)vxJRJ7Tg>2|wmnh{Z>QIDe7Irs9G zt(!M*o|>8(7#LW)c5OhffCIfaVFhCXF%ww;US$9N{oecG;RUf}FFLko&-nO+wNbfT z@?Na9Bf}&0M$NFL0+z{~OVjj~SGFl=aA06`c!9AtaC+L^cB|bTAD1hH_ql2yrjv;DTFX?BtLKNFi2^7IV>^s?W)iQe zDh}d{ZY@$GGS(20K#sZZVkSOn)zL$PL;bY|h&b;NW#|Fapxy1NYMNwob92G+JWbQP zPui-;XDvDK{Q$@s8^uv6Dh0!uu+CO1JC9hgywTrpjR`>`2;=+5r>CdK_m6AArZL8@ zI%?I>;9%&y2+{S##6)v$ZpV%tP*Ny^7A{&?Z`2nqTGUes71inK>E*XSBwj?6nH4%T zG_-ipq6Ndls-c?+A~HKW_w2LJdMAPE6{72tPCjXHa6k)Rn-E05{TJ?=o7>OC;=BN= zGBCIjSWzV6J=CK!JNx}07a}66V8i|WfsQ8yWEglQKbf7K4s{G-`s%v(+;ID?_4=EE z#ylb<0XjSLNWin!ultAseSLkWy#17UiGLt2(IbyM0vzZ@C&ER2>B?2B`f7cE7E>kK zt=1QR_$mN06l$x(!^6iMdu-mr2oTV2cgDuX{(JckfAi>7p&1Rpkw+f6WN9vD9KwKZ zx4UQ0o>yPpmeWF*jy~$hfx*FYxs*erAm{z=-D9t8-P&uPF_yp9KZMW`AI6mzy!29Q zVq7FhW5F^W6R-~ zuiW^Xour#|T4|QC+EP^JsHChe?GThnEkQ`w5D|nj5oc`_1PFfbH}9K&#E<^bF{<>} zpE``z?0bJ>h0CZloqDI_W0HUGdjO{t}AQxV6aWOPSmBJbjaqiL*j&;|@ zJJ(*4OV5aisxRg*5|M7^0;5D#@45F*0P8NlT2;MwCRY*WOgs^V)d+>k9SQa^2N1+eb& ztAtpKEx$}rWdbBgl3dWFrzS{-h%zZ`dJ63vW=j+qR zsWH|$uSF+tFSQFlgc2i)L-**2R8SeiEef+yk|aGGr|^&_5Iz3*Bl8F32`8LfE|=pt zrk*rf3{|$g|{oB99ahZsWF-*B#MNt3kJ?@JxUi0NI{%xz(JYvPN zYNgz4b${@~AAjKse*s|Q-5UWY;o?gUuRHV2um4*B(L=E%+>LY2KM%m)f8`%Oa>Ix3 zxa~XTa!Da!EcC3AiHL$XpE5I_d%^jKJ^s(zKKfg~<-Pv#AAjc1k3RPMm#LC>DqdaU znAuvcRLerDL1jaQ!GI?wuU>MsR3=ttIO!-dB6xUaCa{Q639c(X%@XHbDlXhSpLuxp zDI1hjG;=<6-aARU+MLajRFWi9)lysrsYpgFeYLVN9LIs`2^F#?2B_QZ2t0FGF9`q{ z1r#1xX1sV4Nzg&m%)1b*=fNe!!@JznB~P{m-WUFlUWqvvBCyFTquwjLGMjp>v0%Y) z9F;@gqA_M_YHD_Nc4A^8O#8u#YyKVX5d({vCusNsK($(}R;u-SgP93<{7KAtE^$agyA}^vMfg|8u#(}U+K}iQHVvO;DFI^nR z7!yu|^Ep#MWSFhBUc`GZE(mz%Q-X?sG<;*YeIbVeC`{BY%>s)X1+E0|1H=!*2*NQ$ zYz#BK=Y8+3l*>C`d+ovdA0T35jTZ$F|Y9>~+eUYWiik|5mSeA+KOJ25X>$lDeI zHz%kOF^B9?i`m;b*XeYe_rak#z&at@?5(ina@iLfGne8xE|nr{tJNyz1>)8i5Vk_uJ-xWGLl!(0eR;$%%w?H&JJh)=TDrR0Vv;f8GvuM$xxKs*N2O@%MmbvkX z{nJyE?PDix)JAL{ z+X2z2D2PB6g^C8KVz8BN8KgkQD)_3t`Fr1c?>T#|)qkwD_q|_LfznTN^(o%(eeXT@ zoIR|))^GjRZ!wwUUahwe0ls&b0aDe`7oGu7KmEDovD5;>^H$BCFm}}lQ_LUuHj6B_ znL&%fh&egtOGx8-QnOM-L`qQtJIbksX)Mdb(bZLR=XqzNOaM%)kD<=8go&dXP7`Z+ zArjYpi4e^}79~bvhLH-q2NSArKD?w%tB99)(csCz@;ERVY7n_>2l2S4-y54d(` zzB85yz&MumdUbGcFs?^YdB@-RbnvA@xD-H5^gAYC?i}V}HtT0ya|NQCdw|VC;1{2Jfv)eHyjvmTp-cgj8{FE`*zHIG&O~EXsG^=4i;$$%A4H>{- zKn)0d7WQ4=`n}t}H-*zqRG$&BobzwI?ZW{7!1p}oi(m8*iE3q&`D@Z}6%pDOKlJ@g1cPS-WuSR!;brMyq*OMu^OI=F&$cOF?a6I5q$GRT< zkTYi)T^+`_52F@9iF#;FUZZ5izVNB9jsB5jxq0)UXHQW+Ap)&oXFU%czi zdtKqCXFZo0DRn6&Hmu9k_t`a0)vWPE+$8mV@3Jrcnx>JNx~_AdtQ6hG7nr#P<6YN@ z$a1-MkJ)o&xH4{UetE+w!ey-bSlIGWYA_x<)3N!64glDaatOf1-_Tl~<=nT}zLF-? z;}Z{28t%~L-Z!MTOmZxRy|YPugbK<~Lw~xiDPV-iSng}fOK6~N^vBs zH9`XLq8Gk20v?CM0cI3ax3i8$`3-pNL_{5@5>8b+Ts_{2=S?X&lu#dGgTh#JeT%#_ z5t!g*Q`=9veI&QXY;cVKsr|5hx{HW=>J4}E^`NRB{n-C=-$j1ib&qq=xb}=xgFvc> zir4b&A34%>U1Dx{pWj1D>5u>955MwOy77i*jpKCb@RIkXc7Q48{E1I|{40O(t-tf8 z^?Ld8zyHd&{O)fxxdAD$>>Z9FB2$3u`7e0k|Mnk#>g?IG-|!9p#eC>5UO0U3`)>QG zpZ*U3ZhqU%ULHj$0|=}W^z7$77r@)!`uir+Fw6}UDwU*WcGGj7_m(%m`OKL!%>13- z^<4mNdB@v|nAMivb=R0@2$*u)bYB%NbHCa#|MJIQwVuXtwVX;}q(09mcSewDMewN8 zD7j1wl!~h4lv6fNq@wHTP-(3wrIhGfBrL*Rmx*D(!SZqu5wSAn<)ul)NIP<{MDDb%fS#u7~|G!yW?^TjNyTzSxRYVXVLew#bVy&8Gzevr>!|5Am4O@!_dtK zuTX>~azT#3M?lP`ig1EjD`k`-T9XGBGwwvrFxr0D5mDxjAUy4-cR^4xD9 ze9!x+mLVvBr#(f92*jp3PU~^KUagju$b<&;Kj7MH7mI}fIp^cYkDoYkV(4f4NA{Uf zO8LyEKD}D6U?^H1{g_AZ?(TM7&zy*eDI#HRT|5v?j=yl{7njS!Yp%U|n9UBC>yLc& zV-J7WLyjETA7*n$Y}+0zWfYN%7cZSVb8a@wPM$omx4XxQonYmcoyxRat(1qJrCR3mx$hJJ>-BmV1~a>K>5_=O z?sfN5ZTfvb^K-tU2tK+*=F~ZuffF%#sS$(BbTTNjF()-s(QzsSq|_0C6PdT5W<;ru zYiW_qAMh44lcLk4s!%aiuYZJ@0S$P%y|F7Y z^JCxj!oKgXx#n6IFHnQ3e(CgScO>rR|Ik*^91MT@{6o);&t{$jPrv(pzm}qnml^O6 z{?qfWz4qE1V!g4#OzqR3{`6|Oa+kGb!kDR_&B6j$&CH9GskC#1D5TArZ>ARMXES5) zZ-4LY4jh})A>G0^qJi@=Lyg`7;+JBPKxHB%mrvU4239xqP&M=7)~f&En3{z)GQnZL zhE0Hp!L>j(0(20mioz<|7C>^vpiy%P@a4QQCKd1S8U+enSY@W~_`9!8DgEX<-U}Q7 z^xK~QI2eBQvA>|M5W%cw06DzduFuSI#KtYF<7xr+RqOZPKJsA>bP}^!90z`q{>)!} z)&jyL1Bj_rFF4Ahrc9(T9}Cw6P!$kCYx^!g)?jdrTjuY1#6tthXhKC%O-3#9YHJeC z0=rNA)l%ln+;v^obz1d|nDfEG9}y{=^-hc+)rSEf$Nv^S2+q zx4-YYioUJ(QyZsoxmuk& zcj3tX{%q)n*$^8?b&~1Ah0A7`&xf6z0nQXB^Q_f+wN9LdVNi21V1Te*ty}>urF^(N zoTe$IoKo_d>*imGDAds%A3|EM$9MnnyT68T%uoE{E2W4Ttyg2_j+A=phS>}(MdWaO zATj~+zy6!|-1idS_T3MkbTpeN(eM6Zz#=dEt_O{yn3ZB6o0)N$Fs)b2anii&ckf-K z^OR>lR40<6P>ixpiTha=sAw6>x=Vw{>f<<-;&mqsv2het`|QWhKkyMpL`>9;ml@E{ zIQI!+hnFT(PC4a{h#+LdmJ*ZU(;vC#s~WFUC$BOyFFm$sVzTji{p2RvAol>@efr+C zo##FG`2d{Cp=!(^qa2-FzzL*rStT-4QI#^eljp&$N5y^L=bT$;O%xP92T}6nTh=WNvfv{Kt)W{IFJ;;a_&Tm8LI#9CS%iQy5YMmTvsgsa?Xvu;cx5v z-v8B70oylEL7!pr6f4M@v{-egU_^|@sUdLg0=}^dXDCEfWoq;v=ETwbH~i)lg-$+I z%qgW=pMU4gzXRaifAq&U-1rOtFMiR>R8>S0C}*cW*(h<+`|w6PMovz`?>IRXsL^B$ z++_yHv1+$c{;;((w?|={hl+C|{J;v()VpoHqW!fQ8Nk^_K5=b4eHO6E^KXcV{!6#} z?W_Ork8Zu+E%2l#J=K?xH(=g=J?&{X5YgpJmweK@uJa@Ceee5|`@7QL^!1p>KBgUP z?!bQJV;}o+Z~o2Sc;h&Zmo6TxR;wTQ!T)aiPrvcTH+=gmUimNo#cK`@4j%Un*A2t$ z(xrn}fA2r`Pwfl~5Ef{e?Nz$&6I= z^1bByD1>MC7s+LjD9cDw(P?dD$;6m40Hui& zrOd`Ql~GL-^&UuiU1rWFPn^8w>T71*EaiOnmrkF%aQ^JsbJG-Uq0B-~lAIRn9vi9uk2TGKI#1P- z(e7fgw|^w(+;y{*(tm!BMH(!GTGEX-BvSL>-_<}or{f@nYP2?R_DafW*7t{pORCJ2 zX&OBcb&xYCOt4bK*;d?adyU&0)FP^=iY-3R^#HN>plXY7{J|X8psmk(maTqHEvj8y z+s~|aq0YH)3z#A?9@vU!gS}Hs+)3r^xF;GxF5o#&Vm9aDw9p^OIU69(T=kW~94vrp zuRJW-ph9ju37mL;Z~tX4d+Ei?mp}BO4}SJDpPQ!0f>x>;0OM()T5IlmtdZbr-tSO+fI25LOqN9pIU{??8?-Le^Vqj zu0%}y4NNrEto3rWa)s&nV!>P0YW~pS9&DY+YUUt#-vw*cpU@}KALoM~@X;|MHqeuv z7__XMvxjx#G^&V*QzkpA#j{qS|6w+qJaJ-wfA5-Wt~q*Szwi6~BS(h$z==(5J&t9X zfHdoSxHnbfJwT^v`m0ZUX1P3k_`@GMpAYMGx#Nz%df3Asa`edlV%Twy(934ymVEpo zc|#G7FxMG_N3iG5pC8BZ$liX=i5Q?1=!oM49&9=4)e^lfrwb5gcd?3$B05dea(O7C ztJSjW`jptr?z!jekN^0O-`8}1|LcFjL2Xl$qGs0R)XzF=QDtqML=@th8jHa=k?3g9 zfGo%e$qY<+nhGVF#`WHV-(G?c0y9_vjI5B8k4g~*O0jXJrRaJss+u@+N@k)~a>qHl z{HK|@|3!(D3w0~hty2VC>|LoL!fJ(?a!zKhrXzoeBcqji&Wj4i)*NHVNe`i^QNEkyYBmbvDoQz zM32l=6;Oz|?JR0O06-LKsp^at$Jygk#A@pJNURpr{a)>%M%zDg`lA+cq?|zDXm;+W zAal@Fe1X-AA*vh=AZRdc>WxxG6}+Oe!Q?>gHmyW#rc4P$p?ghG)z*$0HNoj%1c2IR z9*J2*5i!e#h2y9YGuOt+L_ujHW}Y5%uMse3E;87*>U}sQVRcb zcI7D__IOxRKPE*bb8>4%bqJzN5iteC#1zcalyif?qDvRd+_NCA_wEptql(~E6~SZp zeFm&Prr%Da_%}FL90zD~>VylJft=3MfJ^hh|2rP~b)x$EkKHkq2?lo|a?0!VIv_0& zF*)y5iuj%Oec$E$>PJ7KF=Tz=y0_mv{C4 zoHD1%*;k#)bZ~HJK;LzX`8?8bptftm@i1xe`|@yk?%X*em|9dJm12ftM~}GnFf&hO z>bstp#`T!HJfF`^Z5+p2-}TO~AsqA9c2?Sc-Sqb!z)V)qXEG9EbhDJWPpSLOpNmxX z6Q6lPh13dV@3%*P@_Y9thWP98&$!Ch3?o4(){rF%w9`N+W>6vG`C`^}GbwWUa9Jjm zNlF1JO=EOB+LB~7uQb;pstHD%@suNS*++w6W>rg{}?pMGc7o0D9)` z`+<0Fde*Z6^eHO^G=Lh7cTA`;9*D$>nKf~5tCc=&J2k;}4;6gV6NNwLR0XY4rWCZ7 z1VFWTf)|yeVdmoePB{rz+<)(+4-e!0ZQcsnzry2uzn|6+iYkGk;X$bEiIz0$`>d*^ zNJ>#x2or7wB8kE*B2a%N+yI2RLn<3@F0#fR6Y$y-8JM>?Q1|2nsr zb*!YqSnMT58m^Bp001BWNkl+Rac5^|n9aJ{kf`2F;CC%k)b6eAj(7dR1{HeDqaVx6 zlZj6$BPu?;XWmCX{$(*5fBpNP{E2`1gFpO=Z~wNG($k;*l*MB4g)iLs&;G^#2;fb> z^~RpFfjv9#$0YzW;*^|#7BAZjTB~g#qGvqw#=rT1yzACmp?1@ApYyJF-i(TWIpo;J z0f1T|A{d+5)3#dFx7R=WpI*6It)-yraw1a`C^Peg3-=T)%k_nnc$oF7HcDBoR#JqF zpe$Md7YtD;g=jVma~RH_KUlA(lquy*lvIg5;g&qK!88dNW>y4H20+GEplUjanC7kv zuNzuan3Hcr5D^$)6`R&mnG_&3D$}HDE{$9l1M-k%EK<}YGW?v(b%t|F?v%+S9rd$e zxcaJV_xJXW>>Zt^@!;U_6L);_^5x3_m#F>mh-4EFZ(dg8J(z=kTpNvsCmJdwi8&H{RzVGC z$kziaR!$BD!bD04sTKqjm zNU2MW-2=cQ6DJ}S?;q?XOVm)3kmYg@x?&&Omf0#k;#cz$BtI1V_;Z-XD(3~&!ke|E zbg*os6gQzhR7K8@?lJSlJR^twu<#Q&0hBhw z;;5QY+i{6gvLaMa;U?C>S6{F1?DM^+36Ne z6NU_CI!%*^z53O!zOU*2{$KdTsf?wJiF21`=D{)%$fC`X85kg#i6bw$>!@O9yAOJs z=u~9stQqIM<EC6+dZi7{{tnL$l^v zFb526vm=0lYP_~k7~N9B_RF=u2hgLY?T95X=k^s2A1KV>Bp`$~{9;~(c6a~w2VVPfGke?*{wp=Zk01ue;EzVG zKVJnaJt={3{27Dry=+(_?Dy5`acBHCW^%G)i zF*C@UWIIF>4@umfLRF_}e9^^!U}mD?Yn3CAjF@pgU%YDdiJ|X@`Mk?%zF2f!mvfdf z-SREF)dldRi#e`DRf#5GMAhlf9(Vfm-B;gqXP47@HGS^$pJ(O=J^1VT+{eRH@W2|x z7^s(NVkSy~ur!{W+2zXzYR1gNtgrFQ2A@K>RTg*HPa29%*VA8c^(4ZFCexaLVUA(Z=bTk&J`DbN-}IuZ zL_`lzM9lQ)-u#c>c0a9xo_OPf4%Y_&k*HZP8?AU`2vRX46Lr2^Q6<71e|Gv_7kTh? zCsY+B(tA*2kc$ndiIzzJoc+>Qhr*mXc~zhZst}Eduj(Gv++%a})-#DHow@toH~H+F zo(CXTyf6w-$fIBL4#$1!yb8&f?j_xFFFhA*fEXutkcg!e92QS-x$9p65uT=dUt#9>0st>X;YzE{IjJa2#YA;OcxiN=1{Q2Z-Srel z8^R5yV1YlF6h$OnHi3vL$_8h#quyML(;Bda8n&gBJfG%&5>bb2G;+VxfSC5M6}{ddBRUl#qMUqn zHo}g7kw588&w4I^cm2UF0B(53vl`gv<`#gO{n7n#YIb*aoUr53U^Uk2Id$Di(zYpX zi(&iq@xKhf<&lqiG}km*DW&UXW_I0UAN$cOSu_9kwLf<3*#1BIC*S{;-~KICyJmU# z6aV(L{a<{fsH&0~wKCXooH$3i#yAmCgn}UFR{B{+%mx9d4Xn!ws@fmidaDn@vu^t9 z`7$>>yEb@w&hy@N%R2$7k<=9hXo))W;~9Lv*I6#tT^<-HQ&~>y)9)ADdt#uZ?T zMW+TW<#4%Pk7G0&63aaeKtGzle1$@*CW1V&nDD(xR9v0Pg+F7`yet)q9E98=rdRaaeo)iqu20XjT5{Mg4ne(vnK)q1T??SL3Tp&XE=V_ntR@~<*; zty!12a@U!Na_$z3oufyNq?DYrc-#BA9_xXMJoS2Xu|dLn5;cLMmYPLNI>AiFwkH<_!%dQGm#A0BGel8$w52y#|7}PxlL|T9g73 zqK&H&K*_ZR#fe+tgb~4yzeJ{BV&bGyC`J04s=#Oa(pK4`YJdLcfBu~3Jr}TtKJ=k? zec>)M^GVQ<{_(@p&)=57RRg?|)?ty>E}4wA6la9Sx~aR*R5`I@xBeSP&8l?`D~D>< zQc5k>a!c-+bbpV(K~#NkGP6_kNyM(Sitb_(5vN33=uGUNND)V_qVKxC>#(!qkbK&z z?RA*m<6B30h^Wh1N|{QTrfI!icU?Ek=Zj&W>?NG0W>0>i6FhO-`%@c|+ioWyKjr!a zKqZ>I%!XmPT$WPGG%=^562W^NpSw?=xp?vNte;(T?X@RQ9Uq3_*wN#Q`C`6U?CtMN z>v6qapF49FWU8`U9VX^!8qKm4Sq0VuqM%0vW!cd}-PHCra*NM6B9d}R(A@Pj-KT+`viu@ha_&4xaA8Cy)=zy!&+0=pdyYCwId2obu}XTA~wuCGZ} zAj^FMP;?>(F{nnaRErFO$0LevS$zs z+T1I$WCBymIRgZB97xTSnK-d%F>|;hJVu8eDuFkCp_`!6{b6Tb8SXZFGzi!wFtsB--Kjk4bnYo}&#o;Tvc0*D!W+sq&OF4(a8~g#s%q&rAk&BO2 zaKJ3;mAIW}Qy63O zcGN0&DRg9Ncw%+wRB(#GAnyi-W(R6ZGL1zV-~j>5Ddmj1b++AHb1IXCb7g9)ajmKe z$w7aEIXkCFA&>^t7Ex*`rA)ZMI@Si(-Z@HNpZoHAhS;|2`sN5--8F@7z zG4nJ{p8jBpE;f@CcLd$REoD=Jv;}IAs^!dP&;a9&nWw2RQz_!4a6kbnDvM#hTCL2i>#{2&_WdkkX+_s}sv7;Ctj{pp`Nb>if#&t2E4npc2d&rL43aA3@Ou8iWVJ5DWicq6A^;hwTrCzR$xj?Cmb*!wx{4QdNYZ2E@2(MoQtv5dlH+KvDIZ zhbOZEbrEGk{Ok;NX0LW}9t@`h)S?)`H-6V;Q3Y6w0F*MT77$e2N@TAXb)(@c5eO|3 zS2y?O(*Q(uJ{vf3nI<#1f)6n}gOVvZzl;+4ezsbzBf>|>cp*GF1Dxris>Yl`s-`K_ zXz+m4pdu9vQ@aIzV2$6Kp9z&5U= zqQfve?deZ@?T2^uZ@ zB8}?>2v&7=$?L-;m_gVgQNxiJ$E<xR%9>$29*x;b^2td!#FITnHuuHU2p zOq4u6Z0I>fD%ACH{2n5g8$$S2$*mM^wkx>SEWE?bZpiw+M;ja>DaA|DOvMbG!tcNB zwzg&B9C_;XAs*rhn}gMAb$D2O9lARO4yooEGn(1n{{HUn?!zAX;N!=R<(%ikd_JG$ zzMIA}ma<;2O3|}t&z-*e?k7F*8+UehvZuWPMT^3TD7sl!P=P2hvF{gD_|8X#tDXn} zo04r+EmJvj_RNI~-m_ykdGgd^vDn!eJk{i^Od?+tR3Bm+q#!1K#Vh|l?(_Pmzx0M_ zDyk0J8VDwy2$}k8e`lJO%+z%mpr(8Y1C-6%Qxj0dq?vL`c^b=VHHFj4$)oh-&LM@O zichqfc~uR(dO)Gxa5|VGW@ZBMk6T3#{ryrz)l>|`9<;RVq`xg?A|@>wBF=7Mokv2O z3#up?^|Rro{iDM$EQUpqGOoujoj$!y>WxS z<#|hxWuq{H%HXM;pgCX$K$VGoa+n-IsM$>l?H6eUGPE6&`e4LL+{7I@h!A ze1W2mVH?}6%hp;auII5Ge1c!?3rz z+xPu!HX~FV%^XFnXif!*RFw!-2anJmFWv^{3ROlk|N3wI`q!{n>4tB4)b9SQpA{lY z=*9z^CM}Z^=SdYLoLODM!;lie@WFTAn+EdbUjOAcUG0!f;sh|~R8*%TEiI#3%-}Ez zffzYy61DYennrIP)$xOTfyFYgmAF)dPsIE*@ z+_e56ROunA#S5%dHF1WTz=$?n_ckV7=cQG!TH>T;0gEW5L@E0TzA0;}acY!tZRvbR z*^8%JslHLF)`F3@ z{6JN`F)~v%?YhRbaR#P)?VBc3s%l2g5@H6kOL%CzvJZ=2)(eYDnXK}Y{T`$VSGR2K zm8gveKOtts(c!2$25ny2B>Lp~S8P*qEQEwMKxAFO@$)V3eEa=vZd~{Ee=Ficjd9Z| z7yZ#MFFNxpzx0bTj+ZW7ET%cPa(=Pj|C66`{e7?bq#GWxyEhCAX12_o zj#frmjpI}V0B0runfjTpqLCAuSu$b4r*mIQc}S*l>*B- zbIwI3z@}16O%*C|Weyl6Vp1x_M6^tj2wfBy3y|Kz89=!h%9D$>SV4p#l&cIc9m&&f;M+7dD%p3VAW zM~-?ILl3Av@Igpl`)QgC-m#iEr7}sBP#_8}ys6NZ9%m4q zi-<>Q-lVBn^|mjXq77H`(s2@*$kizTfLiGmGpmZK4D@TuwGW*1ar7S(aR_F5hU<-v^=`9ZTD*NIa< z%tS(Yn2Ac6a_(BSk>9sBJQA5|JuZoOA69Rx1R!`)-j0N-m+#M2icFJ}SS@9Sr*Z3v zldC2|m`Wm3A!g^RZyRT>5II%dA4D!VT!?m*H!wY?O;H##TQmlaB)>=Lj1Pc z!NKKAmoJu5c81yB?%wY1u47@<{v%NcCjkm(1eRb#oHJ8OM77?KD0Dfl2uiiC7B)jl zd78>+KKq$zl4Hk?9X)c)>BgwA0fo$jwF`jsRj>Mv`OwQ_P-E}7amO%B1ks{nnfOCMyM$?-{2QjO~%7?DdI%VV1$`NHXw3QUZcu@FhtFx-x6nrnmQS?R^<@8G*J*t z8fFyW3%0PO?SB~n96xc#eHZrM_UQ>S1lbma%32W z#bUl#?D$Shi3qe@E?4UjWcKxcy87UC=g*&i@C)wgy6)n|OXtp=KXPRMs;f@LwhAY$ zO+d^Y*ZocvV5?)ml@CRzMY2I-G0R=Izqi+Seb;v>45)38Bm*|$R)HfrB(pu_jsf{w zi0BP({I#zs9P`Lw&fQFzSVq=$5&$On))0|tD()y6S#o&XW#J53OjXaF{_0pm$B&#7wHiyCAhO_ekE| z_}Ht=?Pi)3ZW{_mrpP?W>8hoPh^o46!$&rami$iM{*EYFy6t_pU;mUR19;I3U+nYi z6<)3?0>GS#Vg^Emgko6ypW`^@99?zBarDRO`;4vLRjbvQ66YN7R<7mi4FN&$Zrqt- z58Jrba?fUclNwN!YUMY+g2wLtrGZ;^GiEe#+Ox#ys&D6CmZMFL*`pZvz;(k8@;0?d> zORLrD!i5U}=JVmmk^Ny<5RutN8qGZJ^bRbwROBTuzn?7Vylx%K8-p75k6-uG%xzVYGn-M;Gz5g55FtrRWAh*MDosgth# z1ou)8O4Ma?l~(6jxL}TvyD6la%%G#1XYL~nlQ^YfT12BGDNI%B>E$P3PDD~Lt%C;R zN4!=Bxrw0rr$4oNN4_jMRob&VS8&~+ z*c!}K&3?RsRtYnk4YN{;ii%3kIVV@dR3eDN)CG4oBCl%J<&3&X>VBzGFNpwjT{n$m z6N25oNmB*5>9bg^Ls1j1+L<}$h8Kj(?q;M+UDt_9;@nhJT=IN-n29{6h!)1XzDX(K z)!8A8iV6f&`=BPK#)&;~%#% zfAsEe2j+mj^d)aOf95=3rIfa0JeSBRm8rDDqKJ5%S6xlE9!DlhIVa|6n%uo+3Tr%$ z>j2R>6HsJ=!)BbE2-7N(;!C|@lTl@j5H)2YR8WsTkI?z^uP!1 zA3ZkfXTvZo77NcwFApx4Qp9YS53_!@Sa?HgHdES0(u1lT%O0DWG$c;hdp*R$YgqyJ zrobVxUNyP?VAauje{2=7By#}rmuX}t8ky!cl@8vbOv~+m#A6M6dhDL zgO204TCLo88ZcM zq0?KDoxq=*pzlK(0h?_YCB6WhDdY4MZ?zNm-RiZ-kArNgzLF8NnnGxZI(z!msV}sF zz|f4jNBdTT;XZc?bI{-UAi>Qsf@{8zF*BSjPgP7rBzK*fHo;)jYle!Dqc|MGKbd!Zw3IINX-az?D+pjIOf8+M>=kx8!k^!PMDyoUDp#Z-?{z+uYG~4e!~y_ zYf&MP{PzMN5vjNCbG@6&fepPFt1_C*ZjiC@6QabaD&{op6?eM4=%?NfU9s*E+igqk z2Y`njZWZqJ^2e*SV2-AhQd-e#n3c-e2;KTrWt%HLxD#1AOZ0IS$w~9F<+N_9~k(wc~h>Gdq;VK46Nkob0 z`2LaH5nzXh2g|jpk|~I+>$#t$L}XHmKowG0ika%TQW?$6f^?h6oLvDredmS0`LkVh z>M8@N7B8Um?c%%lUigbu#=dC_B7HyN;`w{?Zl3nEZ^|h(6^vF};ZC!M`kTQGUnhin znHivInm95-ugKFRAeIV@_N1Qy594{4Lk}* z(EMSOnXOhUPATU+juT-63ixg0oLyuGK-cx_^~klkgEJPL+~NNOXdK6`>xtk@qI!}= zbw^@xe|2D`4q70clz3=1i141>t zk*%D$D;c+COcZL(+s}ot&ehIybvo+>&Aqy?#R2HF#bA+ftx&whJi5ZMiYK{(#RH(h ze*xmurM|UQ&5<~Na~-!0>>wHdB7+)%)k-~H-ER*g&YUdtBh!mt{&E0sf6H4U*kpUoH@_Ib z&%f^HUj2RF+rH@Lcf8%l_BqdeUi;-w|Hq$s)vNxi``*>lpYyP8mKhMWvII1ncMbxT zQUryFhM{-8o192Rj9{9;WNJkP72}?y5J9HsN!?M(InNh^YMG|8T$NHtMTw>FQ%aN) zOrge89LlB>6%iS$bZ7LdMN$waBbb=OG$|T%(qg{2=Blgq_V%v2>KYHc zoxgmzEb0=!M2S?)6Hp>$D@5F05@AC^GQa{{AP|AgH0L~<4f}h0^ZA^KbIwG#?fn39 z<-!<%r#;15S^5Q-Zxmygcs=h)(UO}Q7kvVw{9RN2)R0(cw zQ5z{{yJNJO0mg|FC%}q`JI5)fX_}bW6Ab>FaXtD_v`y4Zx1$3AO4f4OX_`_~fJ(_* z0y#q62vz{;2@=e%04b4scK80DO$Zc-mN0!*DyuYK2Z;!*_Ou{bJRvPFrL z60vh2wKlp|0|CrjN^#M_lmfeVAPJ5;M|Ho?PN=e_TDEiI_|Z52-pc@f{p;3m{Pi~m zSQgqAnDuN3ys9SVR=jn#No>f69e?0^@42XxmGc zn9Q6VQ(bQd3`8jr*S;jqRQD>ywgqDVE9h^H0b0=_hkkCmz3tphsBrz0H^Nax(%-57Z&qH zKkN7R_EO3QtGqOzDx2yS#P61iJxGqS2=+=ks+BGPM2i8- zJwU4v_o;f-t6q6u)BSBfef=1ulXx)PVUyZ|z@eU*9%lZu7>Gfhw3<1 z{lO+k1cyR6C10qqiyd#N-w3jtb1CYHel>M&q`xhyhpIXcMO02jCeIHve1w@BG~n-X zpwrPAzot?!ESTB0dN%nf>0wqWf>!b2LY!tG^Q|CK!g(eVZ&XeoVuxeS-t!2jYE-;Z zO>6mB)y-8ECQ`!Dqn`k9@%&>p6c0iX>ATJiIM?hQ6EpK{e*Fi3?72^P&2Nd^u{t=! z|4`-beZhptO_Wu()w8)_W;2x{qF!dfv{g73hlgn?C3ihDR6KeD+-|2TGt{z2>`O>$ zRiuk2vI9M>_>3zU=g3X{ESp-Xu^880Nd8?^F~s;Tz5?Bj1zA^=-^mrTSwE-^HBm)` za8+*1R|VY4u@{imT}O^TIdL^eQW4N$WBV-bWpihyFS_{MBBewlr;YpMAxRL4%u`L6 z55rZ@x^rhfABLgJIdy&4ckY&4ym-OPn6R_6lXFga)9eLKZEhBT13>XJ$j=F%ta`$= z)2*Fvuo^hj)NEQFE-ziaETYGcpNQ450du0AKwDP6BiycPRv4-QjS1CgZ6x%1%D zw2-K%FwDbvh)~n%tXx!3m)plMobF&p5U^|`C%u1O=N+xCwp96q*6Kr5d>u1!i;1VkB zmKwfbl?TxnE;(nH`>mlh4a1We88lSYyxk{m^)l@N8+F1JK+II+ z3i)0DBAUA7^^ioV6q(HiGpmrtW(=jad`2Jz!W``nh&C{j-?n#sS}b;|#+&m;VuvEa zcn7?U$e6kBXX7{$#fGdXi6aYKN6&$Y)L;}2eIEd5SPZHXicf@XQI=GdQcOqhto{mK ztk-MDUuLtJBT8N^HBD3PT@~bcAC~&<;t-X`X>fc!$|WOMYtt03xL=_?Nx~B~UUR@>jc!9&ErLdVM(XN(*N+aUr zEQly4@80KE<3FsO;<=(BHnp8xF+{$RtJ`PfH4>OVZ@v5yHC z3Pem14kbQ+;rwGB`6wbfdGh3ce&2iVwei32AOAN1{?i+OT|`XT5dC7Q?j|qG@R-Po zq|Dohl9|5ww|)}s99*=g+T49rwYS*=!+Xek6W zV#{4lnG=zTh(uuNy-QuYu`x;#vB5*+L?9?c1cuCcJ|9k;IJsEtTyyo+eeR|*-gW0) z7cO1=;+IZOQ*r8yy4o#~iMfv_wf#YR{I(?OdZ;iuwZda!(9YhG{r$a^a^H11B{SUq z0o1e4oa1u+leHzlBMyhbOr(gDy%iNi_Tx!KO=|QDSdrrOFBDoK>=|Y6qlD_4rktdR zXTzkmLjs7RGEr-o#Z_B3Orna1IzdQ;nHpsZv!{weUY}wPYO;IJwG5m2{)t~{%ca8lnG|uFk98>QJXU~Op}?_Z7VJW?y`Z#B85|*bDE~fV7~Oj>#udl z&gH2tW9TYc^$WwPcUlNV2}Uih_n?`;;(Cm&VaKIQ2f#hRiU0chy4!Al*rz`ENmbJ* zi-U+Tu>l$x6jRZZ5;%kv9BKCA3a^lYDsT1RL-=myn22}p4jw@=WG^<_F0N2!Mx5PmHd8NF0oMYz2Dv3bt3a|Z2Y^5+am~A@L@mD=h8n64U`4jp z7i}}sG2hwQ z*;_A{Qz_@pUD(-Kq?Ed@a%>6WS!HwRuQ@k0=j65VB1|mgg}3ZYkC-3-DOXa(H-nc(}Y@(@o@z6#*FwOfgOBnk=>I52jQm*L#X30R}Tf;I2h0 z7lRoAs%%DPFbO1>h={36Nh5J0Rx5RyvhP+hnIsHQWOuZ9ZzQy%*8AA_*HxSAtAJ9@ zM|O9Q9y!`~eeUvly}o$q^7-@UrIgir9eM3)bGI_+o7YyHz4>KrIo-fGN}P6fcK=`A z-Zk2`tSS%vdLLuXwf5SN^Qcn~jE{>@1&T2$AXO+2Nkma0fT%HPMiac`$Nh2D#79%~ zDr!P&Cbs12^?DUwK?RjUa#2KWiXx9H3XLy7K~Wx-6jgQJ=j^rS9KHAZqxU}6I_H#W z4O_UY!Kt(N*?X-y#~hE|zy5t+-&-!dbyi*hb9$F5%&{kQ*v|nJQ?&3HLQ_jVh3_pU z$+t9ze`1X}uCF2;>9D>|lS{HCERZLlxrBUM4Ezb28kzVOnX8t7?c$6iHxL{YE}HvY zDK)tg0HJd9tM+``5uqjm}m#L;m%@XGV?xtLlbFjR+Ua2$mqpGvPg^8o6QG5_`$`v z*gsgEK6$E+)FCQ&+|MHQ~ybSe@oSm zgGvrXdj-#{p%mmStu?#uX|n*`%5_VoLx=vQrrUI;r5ML?7arP~bv>r@6|Ftr3I4UJ zQ&C!LyA88S&CE<8P1I1RR0aj1T?u3cQ4=eSM%Cr#5-o?7%vhSub2BkjX3t`>Fdokd zeB$76|KQ-(n{T`2<}(1DJAdwh2OcC;%qZTAgb{TtuYP&x6hcaz;k} zJTdcnz4kX5`d-0oDw_4W;($wb8;wAU*@ZcSBeMx9I=Ro6oTiU2U@&bhIx!dKC>W>~ zX3dLn`i2W(c88s_RlF01h-es!gY|0t5N9Xgq?3-pBAzZ>0W^_XoDyQD<`%sEK==0# zKIe&_^B-P*JHS8kBge1$`JZpC5y;s_qT=ZV5oT!)ZI@b1;XApRIcZ4!NJ@5$Ux~EF z9hWgHZk0nsMDrAmJnA0LX_QMnR18TKqD@JrY#xhi9+wu$jz3mYl~QVNZQge(qNtz; zmY3bH`$0od?#|6E|Bg&7ODPGY1gk5O3X4v~lm#Ja&DkHCB+YGo%c8}Vz3;LJ@o zoj7r_6!zr#%9Y~>AAE40r&{a5!NE6v<2T@j*H{1OQ%enclum$=f2M&{M4?0&h8j6} z3IKXaqFWRNp0Jsj2^`lON-dR3;dyS&adR=in8Af=h|QtmA|o<2k@)qTP5_K8!~g)) zBH50uqm(;qJ#l!nTrQ7}P5_vjJpAy(7cN{7b?_YL-uOj3bv-DI3e zn+7vZtSyPKz!AeviV5u}da2zw55!KsV2=JTy~DJBCsjx}0=e4+3nt8B0)GmI4tHEF z*N~bUpu5wDgDexkw`921Omb_BjNzw3D5eLu-%6Z_JYe_znLbHwv(0y1^$M+ z4A;~%XU>e{xWB&|Kj+=G)^QxYK(*ei+uT}fdwYAOl*MA*g~zM+9$ynb|g#GKEnPQ5`Qe?38=1eJ2BO@xt|Tq^CXo>9tg^&35mV3@yOH z{m4+jKU|GVmm8s1ZeS)^hMi0W6NmSfh zq*HaWrV(+o23w~jRx*o7txnYmpn;j^X?BC|EvPBM=_t+VBDe&29D?W_QUMhJ_!`&Pkr<8PP4vbEo7w zr9T{iHqEY7_tc1pqo^(>+G?!?lv22Knn@+1Hj5*>76(dXU#=eNhT$D&$qtvUuycfn z0mOjU+996A&cfl+q6Ftu+iW66akiL+cEf+(!&`1tB(y}5Md3K4zdzx|fofBnT*|2%n>bDJ@>uld>+1NhGG_>S-W{_h9ylRx&O ztAo`)`{!Z(_|otA&L;Zumw*3H{lrhb;Dyh>@e}WS#_hyf2PzB$Ni!I=Nt%F|9Vz2# zA&*j?MMbSOaYC`1bNMl;Vg?j0M9M_SS>chj!GS{etpE(>B1@N|d!@aZ89`{M!)mqq zgh%~@+itmSxmc>Tvk#xWbm{U3KK$YJv=I^aeezy55l+Q};~oI?+GfNnX5Bm`6Zmb^ zz|6JQqobq6VsE)vxRGV4H8VX!^j_i5zmoxz{tjXK8}7E=!beoR+fin!gQHivV_0s` z0*WI&f@dnV5aIZE?O#!z;>09PIPG#d!N;EJQ*tJKT3E(JzP(S=l+#$vpk}2*T|3!z zq2j=h${3758pl|)=cfalJZ})(~H=n}XL}Gdofv5vUp0LnPMp>szt9d}d#TW>wHS{>YU>eR^-C&tCNx3^p_m+o%$@WT&zEPi-+xVN_&#xYrPFoX9?jQuBw z4Cb`f^XD&YHZy>mZ#sQ=v`@kJlnWOwKm70oHQQV5ojQ5qo4)B0;Fy>E+%u&?=AvqC zRx?v^eE|Tlo6+Ppr6M4L5kiMYY7hsD&2v9EcW4-fQk<5kW+qAj>aj6Vsp;nB{7EM~ znMpHkPAl{F^BlshU~I*mKkMM|^y$;f<#M^VoTt|2`6D0s$i+*Sh*(X}{rVRJd~LRN zJ@~Twq`XKSz)x@m`ak2lUiXvZSoc>4!#Maqln!wC*S(0XA;wG}kZmj9FhRAQ`ILrP zs-gPq*tB!yGMt8r67P^P&1$JzLWdbs>EfDem>_|5qBCFof=ewfdUYUJL$%5sB5+7r zRig`EEv71>9WDvn$0QF;3K%7uKy@s}FDckVgeD50mI|}EC5ZrW5~vv$*KlcvP!Upa zbmCqlr||xsdn$Tx_-+8_&)&XGg^7qz(z{C2_{p7znEB+X_X0R~_OWIt(UFb%5K$WR zBH-d61HS7&eviSJ`N`k;LszdnWZ!1er1YVKaZm12YUq-&gq%VO%1QHaKOF`&6(7|A zPTX7Fk!VNjRAH#4Sf5pKbY|*r9o$2RZPV=qZWs@Pca$g0b91RzEwxE=TYUo@obva} zigHZeobCvG(a&bsHEuPw#UA|q6Ue8O$0p{_-4REb*tL#kR(coh$n6qS%Ti7MvZEb_ zT(o(SX^P{`z~b94yz;-QiHL4C8>jyS=(DB0QX+C57#MxV9|5@Sw%ZO450;DNuo#(W zxm>#H*-}eE-qGAQ#5`R5-YEbVPh%o0N5W!xnXyXEaJ*hm(|mlqu0uU>bYi);^aD#p zMRl{;tk=gbnRhR(H@x9jKaOIh#W1Ke)!FO%5D=AGfdV39CMu>XzLhOVG5`P|07*na zRC~^CZcS9tnysff~8DEOsw&*}u%!rjon$;{K#T9Zob!XMwWoL}Rac`Ym=WL)dGOT_4GUI5cH zB{w0|cmADW7?PtASPT)3i?QeSae3^~E~%Oilv@Ls0;Poi8==>xoEYmEO{VljvFtr+ zCjcg)-t=qplg}Bk@I#cmAg2h=1T)_hT+<03)#md`#D-xAv|^eaZx(6pUm405gQRYK(M(U&e= z0w5w|sph7Sg@{O`Efz}xPn$JmQ3X3y8o){^O+-}r+W0=FF-PkhgyOVi>D6ypvf)UY z+WH1r)S8-_5;&Zs`l%C%oF7*NYYm#N(q8-R7V*3#@APHjGqyj?9eZrsy|su_<1YF; zu)|@``htH9;J4rOTe~~JU%W5e>2AN{_Gz9?;AY9C4#YamtrWg;_4x6Rdz{SeeeeIv z-QWF+e-<7AuluD}Pttz;|M|bqoxPx{-}W8f4q%$ata$;cbBp}vYpLJ$9WQ;^_kZ7J zp2w!I`ngwr^}qNUL~LUK+C1TrUai?;QB9?pLtx|{jCC9$xiV1n{xI{px0)HmplYJN z`iRIY;ncKI=zR*oZDmy9J(VLr@&BoTvr1>P5@_H$4vRBqZn^E&+xAxn!!TU9aOuI1 zK6w8Fe|!Gi1vglU*f+u>vLr#ES9i91CUU9vjcps*Ck#Q%v|KKSVLUoIT<+~rkR9mW z`|8fm(_MF3sM#DEbPS(hYD`RpX$w$VvM`_uZv))1n0_g#6E|}%w;70K79)cBT1H$9 zlP22k@_eGStyL||+vcx%ldh5Rn{RIR6e0=$D9oi4&+2y@<%l#8nVRe1n0b!%LWGh; z6|emkFMFyQA!yMS)-BxgjV40O#Zy6`FpJqR3{AxIKM%ZIb^!nsy^V;-1ToO;%xzMU z?s&yS;x|li=6NmFqjM?08kZBF%^TFF^q;fn(0u7X6ni~ z0;%HbzV4kr{nO6`==R6m@kf91$Ma^h*@O%7tRmTdh|I>tqNV3cDUL@4LB>bFg&?$s z$jsoj!Cr-CE<}#9DL}(mnTpTwHqWNYwUp>8Wg%s1VoIuwhrtm?P?YSLs4&mcNHB{S z852|Bq&`j3#Immt1%OPSQA=>|_dwMGoN_wmy|FU(b?%`077D+_ZxOiLm%mnVb6DoG^edxCZ*gf|~1b^q}GJyTn z{$jZh(arjJnkGlnJZ9i@N^&Hfx%wIV@WT&ZzI<6#_x2XI-g3){6DM!I<>rIKgIeoy zxp(T+DFSUa>#J9en99> zOpa?jRP!%^6~Gg@xEce1m)`vf0L-*lEcW(}YOR$A&j>pgVEg83`7WMc_!bemzwA9^ zW|@5@(BPkEuE#9JGdGWU`^B4eQIabbsdDjD)OHsIMJN-eBZ1Uh80cIK&WW7?3H-sS z@9?RkvG9(G%mO*lL{&sQ7V*}(*6rwmAQH}$VWWjZE>nI{+ zVi<2GQ7bt{EtfAHk8hB@{IG|v?>6LGcVc+R8ATm=< zX;s{a8Zk$IqC`muq)Ds^dY6&;AalS!IqdPInPH$j(FuTOCPYldT^@`n2#E;0!R@p{ zVj`;Hm`%h67$t5OOquPoc3BoBnnMJK;~g-eEm)G7GFY9y6vzm6^&?x*hr$X6y1l+w z>+wd4)UD4_MCNF^LQE{8 zB6587*rgSV#bT(#xES&Ac@YtvJ$v?b7Tf)q>%Jro zp$uu--(m|Q-bjSG^C@?g?5Vj}EF7y=v&w}+t5SOgh(y%#`9(t2olU$&R3F)r&7S*R zT#M0=BOTdCg3N55C%|;p*?VxLPjGi&RaMu>6oj*YqY`Geo+oU*Dx&XFPgWgSaGgtc z8`1Q*Nx&lZQr_|IjX#Mr*j!6rg_ON8*XyaPrR;i>*KXbFd`E67J+TMSM4+(|v~0QB zA9ughK6?I%;>_ACV5WylbnFIT(FH7?Y*&rtP?vs>mXso*Ao~!Nv3S2K@s=b7#n?(I zul?n_{qeo+?QeVPT~7t@oG<<|Mt(v)^>g19!;TJpvFv~> z)W@w~QpYlG+z>>>d2?pwSI%7`wDl*Z>n17yGx?q0eG_hYed=Q#>+5csCLlV?B70p? z_+Oeq-uoBtzwy@ryyh2QeevSO?L_oF-~0Ul zUi<2wYpty}n}7M@mwe+ld}A&32maF!062f{5jM}KJmWD$;>bW@Z~w>u8##*P8)2I_ zvzoPL(oDtX*%=rhD)8paVbVxM&h}*^1G>n*p9 z!$J+4&Gf+!eCUCXK5%?|+|_vo&gYbQfIq3-$43T`B4X;O&s_WJ7T4Z<#-UrFrd}BF>6@C`U#_yr*L(mPAAzn)?rMTGiH4nuw`#Ai3)9Dyo{L zQ&a&Baa|d)& zh-xV%NE3jlnpr8%*k{*axs{_xbN^$`4tl%sKy0VXrp?7al~c89X@eprCc`lN)|;LU z+y>|m{J?|vzWv^hJn-NS0=>g<+$a&VyYKfBLCakMr`p0&p#s(bsJ9C8W2(1({L&1En_lY-KngarBEU@6xJV{2U6R$ zzhgj#%v!rRfYZ(To_E;Jy50g%pZg?rIhCrpz1?QBQIj|~ZQBqqKgE!nb`akx9~>M! z>Xus%4-ZeDI(=~90L^l_w*;Vy^?H5j%4Ihd+CNw=79$apiI~mveDUI?^=4y&)2EIO z4h{;lf!6Ew`3sjWT)HHp`>WNNn@<0`Z~5jMx9+d};m;?sQUas(B9}O&iHe`L#Ocj% zzFJkBMw&MKxhTZ6V>Z5hl7k(o0}XWBu}-g0#+Vp6Dy@Pi2Q!9`j*d>AJhd1X<2X#4 zX|vg!J$L@<@$uZ|vu}8|r(O=MCrzX8UKUd{tI!?Yu>RCLGD86H(z}1m59qx;w~!d3 zF%r8{az_Ia=tp*{2BJ3*B71~qt*Xg32@XpaS*Tf9WAp}QSttiki9rw*X$tl}i)>@bEIM71Tg9d%!_}e-&J-hZs!{&4cryRUUFD=_V z1FWWAIJ6|Qu#+N*jp6qq>L+rXt=ii)m`2i??ywGVIc$n#;vnkNYSFp~ZsmLa+#Noi zz86t{`V`7EVp27zaVgG@IeYdo*nT>}O?=D^w$u`TQ&;nt)mrxtPXV8P-}gP|$uE85 zX8n$7o&ealXs3UA5VL(K8D8`r-a%Xf(D~i5FNGm+KvW=8<+Q&AkvruFU6%rXY0~`h zb-sxQ?X;ti>Gia35L1h{98tA|QF3hiqTuvX^GEE36H5VUz&$DY3)Xx;gUmWzN5kjI z_hQPK1C`x&RbmKmr)BLe(XQSaDKHSV=U)6e z?<8Yce(T$ad7T4ZQdPjDDRZf{>>uo(I6ARdEcREc#bPXlhhZ$A`Nv?Mrj2(>Vdh~N z7K>%i-2D}U*%4U~!9;bvKAz{+n!s>)u)o|}_z+D~o2U8mm1ANmrS7lxhH)6j;Z?7C z)yI(?)68sANCBplKW|ZtH~-pSKH@Jw=F`upstM+~F-X-r+k4Dd@BhHZ2EG6|bJNZ6 z?8pa9q^C`4Ep#E7K>xh8__scqA|qz$%e2jD~U*^9z<@p9z{a-4xqiNUrN!rZD#2p zsRl36w>b2k)4db65-Q*f9ZtvJ#W+e+BFfg_R7wXWrJn03f__7mG5_%?#r> zwuXej&_|onMa6?-A2bmw%q3?z5vjJsgQDpYGmBRsRgB5ZzWjwRy8E@S0r1qjp8EE; z-E-Gd@BFnl{>rnz@Hwf3!Y~XS1M+w47wqrpbLP~kQ*D~BUb!-p5LKt}In}&y87fcn z_Qs*M7{=BDfts3vP>1RYrs;THDl-)`b52bu#Tk1Z__|=B)?u0_kJ*`dIgCWqMAcA= z6)ueg2)hbr@n}ka0rVCy=r~$yw1boS4D@|)o@Zuvy_tRTIH%pWKR+`d!4{J?QwOTR z$U=R`P5hN;8fWI1=Y3Mx`cloGw_LeqD$1&n_4S@*#j~Ew$Rcm~f~P$zzl1UU&hP#< zfcO99^$i_wzvB*{wEn}T6fT9Re#R4?;AMHgocH|spZnjgbCUt^s#pHZg$oz|)64(E z{rBH5=guwmTo8*%nyCEC7rz9+a#6=&fxr7Tj8%=*nQh|HYh&hdxdidlCRI^r6M;dM zL4_*@D+DpcJe!JS=*R@9QWG;YDjryviV-uUmRiSQaof$e-g5KJd&|}S{_6P3`r@Ta zANcDJ{Mmc{y0zJDwL1ws9t06XqlD#y@(4&v{EHh_nx+5x&a2jXba1#>F87wJZlwDA ze?XveEd&!p823Z*;0zHe`z9vNCsYx5Q8^Qb%zVPpHoi{vNt zV9q6}BE+tPlPJ#js-VN%W-0$sh-&(N1s2}~OeHz~?*Gz1jzbg>*|rak0flQRRYk>Q z2F&CAlDKS92p}(`0Bx8zbt)r@@6TFpD(JLBeT#Bfg3MBRaFUMpSl9`f zIwm3k_K}mM+&@S?TOmlex-zWAn<$qQ-+|!yb4>8o0yfyGS^-I&k7=@vl93s^iMmm` zUu9u3v(Nslct*ZJ{`(&W@$DV&B%pfg`;;dQFzm1Pi9kRzmDa9Yy*h0sG4Tdu2DBC& zSU)ILaryGq_g(rcz?#>7KqpV0JUl#j)T3@Yebeb$>rjW)(ZN`UQh1s+>-GB5r7OMm zPz&1tRWTJFs){gsF;Euc2#P+WH@;L*he#u1?I@fe!yF=U;*LONb-{qB)dSnH49bbP z(`1j4DF_rmq*kG{$?it%Ui)G&S`OpkxHxg*SF=8Hu%*RNkm-T^at^f2mAA+mZmW-vfob0D(= zQvQggH4l0G+noM@ZdMI5VqzsFhg5PU6A+#2;0UlcEhkTREo2~pM>!@7cB|PfI&Lsi zHir+~_?+X4iQK@IxEHb$x67vw!ZqQU#d*WYZgzk|p|w^rQxWHh_Jf}TR&eOwwugrW zpj}EOCKvC6Sb-~7&h77exW$X*C#$@_iTa6_9l({mNf@lw+Pqsxw{Ib^!Nt4*%)wlp z5YPj$nX*E|i-(vUm*Ie_&3f^`+des{$zY^T)=W#`Y}pR=L1rRmYYIct1_~+~a-PBw z506#cY~Eoz$^#WdCFXc?*&L!(kd6mAbp6_T z$||Y%_8(}i&8-c!cD_&4P)#MtDLWVGFnU-O^yHaS=jDJ1CE>+CirBnXGB>KP-~IxrWf10-bDIwPiJtDr5w;iy*gz5`u(8=$~6O^aF_bQ_in0P}j2 zVbb;x>TmTMzxiul{6$~dzuCvIN4-9t{Zk~9t5V7&%^mym+Q`h*G;6dhA_`-t0F>e_ zrF;P}xrQHYmN1w$7Y)Tx*O~({wKZ+6aS7i$5t(fAO=>$_yU#(XD zPs}{co0tFlm)&~vnHS&@Uh8QC1(X3ux^t@9eC61K2O}t%TQC+bO$-VV>r{CrcIkL` zQ}M8dh`oqfs19Yk>C8=^@Tl9C%f0>8VUu=z_4q>{{F{${^noi^u1qb=!ptm^YUf8& zOiJAWRx&WZ=3MOar+?``3ZN8TEEdBs9v&X-uMVO_M@+yyTP{psF?Ze>2S>1tQFIQ*lC&1{g*t#QxE4YQt1YEuzhrPK8rG!>z_Qbm{P$yU9@Wi=|vh?FjfE_@LY0%?0qOx08 z>t!570PNQtZG5gF(cnp+qlFm2z4sZ^MR9cReNlD&+$VF zkQ0D&Z~Wpw5NP|DC{dDrR~C6=hZ_R0*?D;q82PprGQaN)udG~3t;DC;Ybvq3dLA1| z8%ItEqJAaGjKLOXF$B9-b0HIjVnjs)n9M23DL=`a6CkqaR)JVmJGa86s43EqwsN%) z*Mo_JC=}R}3v!K#z}a-kaSFs)lj|HR-Xsgc(CAd)6(-8Z#@favgkR!kFErW;^;BFgYK^N5RLj~aMTEI+N^R2C^ zI)>ryEg>l)SoXP!-AdK?gnU4SV|^xpeVz za-7nHB2gJ`#C)vZf${wjhOzDMFZLG8 z!^6YXYE}NxpNzv$OC1*@Kq`9W>eVJCd@C)zlg3RGC?&9IrQ<&1`1I#>`~aW>Ybl&D3|CNRU4Ap^t$G zbL%a)m?r3A)Xd6uX#?=s%Xe_<9FyHE#`ffvg!f`AIe+eYb37%|u?< z%nHboRqF-^xx|1SXrSkZZq+f*b8C}dY!WWS%$wzzMNUlH*dmjSog7k;oB~haiHMx$ zfGCD`c!k*$TASzT#KGZWvABGEb-iAjq1L!NNqu_{HENCOXonKIWuuF0da{w+4eC4^ zGaH71D7tA7v&-eDX<9Cqs%^8GRn?U#oZW~eB=iwUduU4(ghL|Ix$&@7V3p|Z%p&4; zT*EN%P`$NNPsIl=QI9G-&+{99{Z}7xYJJ(4KG%Vd)#@OcfS5U7qZ`cxKSFexCNAVP zeIlBswf|TEM~2njp0kz?4-aRRtdW*d%4>i5mjJx&?e{!28?=1smprc%VH{lZ5g3NS zt%XHqhZ+68hG8f~(`F_j?@Q)GAtKW>dE>VP`v5~73NugBR5-gPky+9``~g`vV^(D@ zy%IQ%qnU}cNc=4D5mOm!H6~R|(;7gnLx+p6%aa40G3vORMBiU@?-)zwl>gn0d5Eaf z8T$eZh^jU5XpS(H>M48&P5NW){k(WbeCNqwu8!C?`Zasn=sSC&1hl(#0O6EO*#yeW zKnyj#$S(n+#O9qx0HZdd|V8;nYQSA^~dk}(?^`c0Dj?TU%8p5 zkAC#wzxmty*H@4CR^#Juzx^x!`Pba|lb`*xPp(`n+!9z-%!-KbLU8^u7mvtIXCHrq zGIsD1n1PG;@iev7YPDD_Za#Bne|2!?%q`0CeE6E}>}>uY z4RyO0BAnQPE#MNN1a>nn&n1XT+5mYpyj&~~5BC@2VzpYi1+1CfdmrzBF9z_PPucFw zW-4mw$IIKOI&)C~zIE$PXLt8)>4~E56!Ulg!oj6vHFJGa|J?jIkCGga&KeqJ2u0*Q zm6ppTmvCRQjP=R6fnKyvM22^O-5gzs$b$+Ixx(4;0yhHZ!fl?3IZXk{i#)q6pGu)N zOP4qy@u@IzOfblY*nw{kLn|@YKwGBG1^|q>u%+p@n$;Z)dY)%4g$?9Jk^~U7*1Djn zpE9*pE@j%R0eIMIX|PrD3O%LwYJm8&gIRPlmAvEDmTj|l_iX?iU3s?KX&?EX%xiM5d=*5QXKs#$gnChtyaUfmcg+am zsqSj-h^S|Slr?HmZGMcV?jtf%IB_!(K*_s^$k)1(E>dy2{&oob&fkw@b9aY)@{?j= z`zjZatH)PO^?0)$h9Q#fT>BpEg;b3o{ zODv6fo~~ZKI!)8%D_5t@Gz`Px;r^);N8j*ozZEyUzWPU>W)?L8${TSXt5T|HGfTdf zTG}L%dX-O+@Ma`F6!mI0Gq~F$xpE|Er*{p*VzD@Rcr-2+d&@m0Zmpd?d-man&#J?P zpmV?eMP}KkI3BUf7?Tsa#7}kuHY`HceW(1`6gtN$j-Oj$hy%>Pa@TwhRI@d6S@U@ME$N1SKpLfgf#i z;IwUW;K{|FJ%HOCA0Ks9RWIoz)Z*_+U7ykikN`lX)lyaU^qKbqc=(}Dwfs2$S%0!l z&~UCzcDlmJ&^O%;zB8t!9j;h4ub|PjUH;3z7J)N7ZA=zh!Y`~QIJ1;!?ZF+T0+%s@=7&8j5Lpm^y1%OBHc+;;1&KoG+L5LGcVcTw`l zzyqwlVP;)N-Dxl)-Q1(hrzydVm@eFazW{jJ)1F>SskIg=WhkE3cKt#|EGVTWiy^<| zvWSdMN-4Dtu0UC@kGnR(Up?U7<|FAq;EBIk2>&_|t~-{Z{T+N3W)Xl&DJE?eZ@L^x zpP>w@T5By#>N-(^ij`W4XxdC>M%-a0@5;wb98e4jgGfN~;#rxwsY={F5vj^*wc6^E z)LXT&YTzagTLLI$htF9`7;^@u3uONqC#?WhII6fqEe30u$@d`|hH)s>%wGH7Uh^@{ zuKyoiU-hD|67#g2ozM1~yMMv|DH=im0RHKhy`Y6PFN2_Ad}wCok>A{encYszhjHKv z7&C9$EFl{;spW?a}1LIy913?S7E>UNtil zk*?}mA8&G7h`LShm!wfaDjET)@3-vkEw)37RJT^I!PoH-7&!Klgu8RgWy|FmBcx5t}x%`UzFZ5BxTpDQWn{csdUPGb&(Q z%5AsYdgjc{2djg_{i9NNGff}-@Q2TxJ9qZ%Szq!L8gdw@mqDl>)p3*lA2!pj*MhUD zx3}x@P4~l(?+m4mi^a)PC-;`iT5Cb&TDb6A-dX@>`>TJ>ou6x7(#U#mX0T>v#tawR zyA4P!#fgnR4>W)`AtEML+lB~H05L1XL~ORjT>6`5D(H9VJ!rBbZDwX;EfQMMXm{<7 z$V5~K9mk*AOk4{y!1FW_r)yr43z$ePI%G%YEE;Z}#3F&DIFjZ12vzfz+fgXx>MEyU z9EWk-tkxlh%l6 zxm>DQ+f1c6jWG^%^3X{~{Hy;;{` z08G>EvNchYKVZmrQa z$wW9r1j}CmSQg$(DFjHHxmI|0i8zI_&SN{YFR%UXbd>9`p-*YfDp7jSkeRs?X(?}zTI4n+_IC1*)=~E|8ojQH8G7rO8hPqrXjmu`exp?vHrHdE;%Mbl9Zg{=uhwp+V zF*|}@Lj<;P+#@I#MojJyY$oQ|dZ>pqs7io?+`;uA;E4bkl`@ROaCCIy=F5-jtZR0f1TvM%G~6d=zhI!}kkI&ghX?u6*Zvq2)nO=H_V$+J zxQO&JCIXNiy#4`d*VNz%sh9wP$wQs=hzY$(Peiw$x}%B(utj0=sB%yRW_}ij84rwr zVHmv!f_FIf_x4O4JMjs+TdHd)xJck7VO!fX)i@*ah-7BZg8W8k`(K2=2}SN8{e6hd z$!g{yHwQ!}YCGNWpq;;w)Y5aV&~^j6_K9O^bpm65GNSnt^ex zD&mcU{t%p1;H2sl&HP9SU5$ZX4JM!#&K2ODSB& z#izdGW&eT*B680?_smm!$>V;*^M053b&vwS9p#<~H-Gio7_m$60$|d{rNG>-3ldNW z3{dg?vv==?A={4zfT%Gy03^vPLIrpKQDqQw>0lxOwG=Z?YQ0(*CPZnWNQls=CyR+| zbXaBQHn(Az+Ri`uEOP2uU>$18*MiouE;_cJ$c*jYNerPAWwKYX-S`XJH%w$Q)@Tlg zIXACEOO$IW=jk@3ikryw{M?KGs`sctXk~VAOyp^q2i(qE=yGqleBz&-IB{aNT9r~3 z|3mzbqq3rMPAM79a64^~EUN@gPLwO9_HD_uUZmF3ukwUKj<(*E| zv{RZUBGlyl+yBeX_xE)1oDU1Uz7Zvbh`^*WE(evI_$eXS$1EbkfAW^>%pIKLSG znOz)b$4n#qVth}msh4qc769IV+6foPhE07Mc{1PycK?~N)c&5n^%`+&&4of)+wZQl zS<=6c^k(WRG!$0Z~UY}ZI_(z}hnSZ}G{QJG$^rqi^=Chsw zY!R6kJnu!(8@mL*N=;jvIem*udVKmY?$yzE`DU&eB_dL7F8++{2oMXcleFe;N%o5PmTEy6rp~hInrg36GZUo$Ye!_v zjMOaME2+kUQtf?G3K8kNXRZA(QP_mgM6F2IZm#@L0)_4EeBj7TRXyyC3&-lbrOR4OzotK7)2vnlD0BcR8 z0R{w0;DH%x9ghxAoVoedgMs$0)R^g9 z)Pi;cXuwD4C6443+EJ7u5Y==kARlJoj&EsfQPV- zDhAOegMh@|ChMyn zfwvakAuuY4OR1$y)8ychL()Frg^QR`DnrcaIM7-L$6qYn4f0DhGcLSbF4yZd5ld^O zRtAX|pqS@r3Up?u0J15jU%6|Wf_e}S7sS>5h9j*uX_PB2SC-=nG!6rUh}jWSuQl&2 zmyQcF!WUUhZ@uMKZ(4~U-BY-R2hgKPvJnxbuZv}u4L@dx^ zFcpKD=yI`8D1)1uJAg8G;)8?z*Sz*l;0UO%_;G#xe|!DKiSP*D`e+9Dt{TsgV#;yB>KXhlw#uF3@SwAkbORNuApfG99yr*Z<;iLARxtD@|o28JS9WH zd-19t`W8uSTtr@whJ7jJNVzC!>%gj}NFh&Dm^>0Df;wLx{`U?-CE3I%Jx$EzDjHKi z+@yE(<9;L2i>E7wQcvQ<`6j}}E|aQ@sKe&V`Z0L1YrqUen> zvdPiW$v+2h`Qqc_@FK?@dZFD55>z?5ZKR2;5^>2d-|@ZQw%l8Ia`d*hy$zt3-2Us< z^)Vfh*@1+lH6LLgnX!&UXd>QOOyI#bH)+UbC89|50u2dhl*BkM!zkB=WJ{s6~3}U7yG7^xe9fJ@$8?EOFzYw5+{poU+SlU#_XwXhg; zRd6Ce=>0l+%bTH&YT{FNcSt?QDB1GOqeK4-a}=q_(Z}4}OJ%oHL1wmITZr|SsjrXi zul&m0AJfd)ef`NF|A~8m>5d6Y-sAPq-rxI`7rcFfW|nYOSO@`RCZ&`oeEJh^e1|vu z+8adVQIC3*&xAXl62=u@{`{|yrahetfRC)T7Pj;G2mq+6>yqYq-c~AXYq--%Nz6gx zpXZrCrPR4a18?uOq-N42dE-<{f$C!{Y$hU?CLy!OJ~GJeNFC|3z%j3B z&&(+uDnzDYT~M~OUfcuNpoI%_@jW4*qjIHMiklyCEfjoU^S8B-<_4F?)ZAOT$6$-a z!f&TP&3>s4X!_Xqwdudb$@+13yM8Z}MPuwhGky2ieTRPUeP;G?qre#gWO>V5fA_|j z^Z3U-4uEI`{gjpGF5ELSQ)Bj1n2G35-}CNAgkx@h{3lsfuZbO}Fu=skVnRO%Qkddk zb$I&p>BED=GiS~m92@|+eEI5M|J7e#x^(62xrZ&|Prn|q?O?)pX-juHijF6CtwTVc zLH-|q8UT>4@D5Ni^K!X&cz8Gr<6<0pYa|febFYW%KBNtxr##umgqTbA&>+tu0GMri zZ<*^HDYSczp-8tn$|vQL6YRhW7 zvayT9=rOixW!-#A@R77Hna!ZPpW3yKUyekAC!{4-XD~R-8V4>QSHY2|nvq zd#hX#*G!I1cXi_$KVq(}v~K~vYi8AT`~6np0RUg|RabTcSOCC-z(=?57$u+kfy)2^ z&jSX4f8_tV`ntP+d1^BetEh-X;aY9iKGjl&>G*}`E#o+@rw!c1!JsC(qZel4X3{zQ zAyBd~?^Kbo4yvlrk(YY-=$+b{ilZL8P24)?#n)e{gX1RA$|?&#u@7gNlsaa|#nKhk zkv=a|3Jl&-U4%fT76S^Xseou0hIyV%wvlzI#gh{a4m?E%+-p=t@x8uJ5=FYir3A$$ zBS1BCH!(nyF9Mh4#unt*Lkpii&1c^Wt&!E6*_O^}rPh)fG^9@a-ur;v`K79=Pkd51 z->XHB>1p0!*NEj8e;Txh$oA$|rr|sZ*!_^AG)>H%wBSZ^ZI!G;KL6cA0I#X zEC0lajlQ?{5O!ykZ2upLA~GA?T}e9`)ivF4ftTL>V*m>C-fC5A9mlb91;B-CsRp>O zQKC5V5?b$LY+Sa&V5V4mHyuGx`Ji)DYaIZZRXiv4CYc`ZUqqeXD6P3y{Wk03nCkLK!^~3?Ftk% zmmqO1ND1L?C*yG(Vc2Ze2{LSTg4j+Mn0ZIDeqTrxEyxW)ENnjfk{BfEr(TIQREj35 z+Ju;fVGMX80)uG87Jw1c-s(>QT)y~eKF*FM8Bj}g8x+3`H`wwBcCq|p0PCy&P?`|) z+$KLU)zq@5o3`f61$70PuS&DR#RsHv`Gc2#I}sUh_MwO0|Ni%HHj}|#^4MQ@s(y#m zy)g)^Z%r=vBmlfSe^kQG#!u>0#P~O&v$UgoYJTrwXC5V-h~i+DgJ9@{#6aB{iA)Dp z;v^;&CPL>i^@)us5M#8R{4QTB%)Ixc_wMiS@9*vJ@9%l8G>juNgZS#z zE3M7z^>Ha>Z*TP*zxkUV$IePat*Uze2Ort8_wRb0IdhBsf8@Puux(d$9{7zh=URK8 z*L_G=Jc2M!fqC1OKoa0Mu^|R*0};Y;SEVXR*;KXTUtQIy{ODBD>8ef~r>oOH(=lh4TW5&_jr`B!!owJZ(?z!XQ1+`323K&UJ@EQ=04{NS8F@7le~ zxD<;XI($6?HapsE)#t)1RpnwQaSmxGm@^&6frYHZNA~viraUA&F|#mOqZTRKwg*Ej zHdEgA&Gx7dM#3$FrMfuPH|Xur_Ni!zYLt_Bhb=U5Ypwj=QY#!%RHOj@!4F;;h55oC ze6iEX`VUBKYq|RaKtaJwOjzF16VKv`-}PM{-H}=jMxt|Vm*4Z3zv7huK7ZeRa(oOT zg6ABA3-9~FefNFdU-8OUzW4pV#`nDSCvSm!9V*?sFo%nKDM-1rDgu zI50c|GlTigxH9+6c1n;=rfI^|hG8^`Iv}Mm7-e_rNRJoc@~Wz^8n2n91Z3U{NF7GA zc6fNi%PmFB*nvbkNR+oLZph*GNJIt=E+{KzGX#y~0E?GJrAT5l4r^vo$fsn6Q&cH% zLp+FI6gWlIQj5E1BXC&rHc^RSj+ZpFnW9lWk1m;1N{K{Vy4PG6j4S%cJ+ZKUlI30M z!a%z4(D}|Ty~KCE{&hdn@r6%*>JxnD{n>7b$Mc^5{8EZUpOhfzHEYdW)mt+aed&w8 z|BfrpV^x?1tG!X&R7G`gh2YfgnVsF;r(g5*tFJn@UabK+|Hy?$9(m-GpSo+a*}6MR zC%9W@F&7_Ts9Cx)SNLYvKmLsAqKc`N-b3PowiN2lvQ>2ZEFscLcV=tnpUgYWTmhvjJrm_ z$xz?iH7mjxNshzN*^4cs5fPyQXElu^u~9@si%2FIN}Z;uq?!HHox`G{z<~<%c(&vZ zbR2KaUk%s;uFZD>7&_>NAj;1Xam<`Fp>cao9)Bh4ec5>g*jtQ&uO9%<%NI`!pp*OY z4}U=&Z~g3NKli79{3ooM%`FI_+?1PAcgD@c(ag1|dCR!2h-h}yLMerfy+84(_S&1g z4g&z@FMCNEodmApWms?`|oelWz=r~z_e+q>JSq!v*Otx+*1MCJi!qWNp3%YqIG}0Gmhh_ z)2GK_9LB+#Z8y{ThaY(KvB!>%4p}g=9Nq$pi9m&k;y9$g?7mn=(nWmvW|@}~e;UV; zVwvMODiuEHY8D}dgP&v1X$HeGLkWE!iLaQKi)g8Z1(l7n@ff5Z1DLTGM92}mlHh=G zXN$Jh!9AEim8a>VC;_2RC_Qcx9bLu^ZE9Jl5=e)cLD0E5-s5faK$HTcGzSXv5+3iA z#a-qKt))(_DXTAe8;B1~Z7vj&toP#3OA-+B#xD41N_thShy*(VrAjae0gY*gt%@oN zf)CO-?cyuVZSUYr?iz9I9h~bAWMTiY*ac3!j@8apfFE5tKh(kDMb%N50#i{PM`Q$) zi(0D!q6kqPf8vQJc6ayO?d(-&pO5E%`Tj3czP`1It&Chkp8**%(Ay`^eObtd5gj6FpZ*cbI(o}%%Ad!Y{F^Mh0IZt#D zLh#H5&}@7d-dX}OBE?{8@Qj^%B~eNgyE{Z&rO^83;?qwm(dD7ns5)HS-1#gmM> zzBs)?;x_RMMVKQocPa_T8eu3OaaDv&2?-)rUr)8M77T&-SzyHu1PCMuax|hrUfvT( zDV2r)s;wCXQPQ(R4$?g2FKMwkH3{Lgwt4i?M<0E3wOSqQ?~mhnu)ja9R<*LJ=(xMH zbL!y0Luu=Kas(XnXMc1O^7szNxvQ^<%Sb|C(MqPcX8|A*yy&0mAjq67?a0eA2ODLX zMSw@opB&YX{pgSKZkk!4_Gd1dL}X$&7g0c3>*Nt3j?hxMgW+z;RzbQ@qv)iVC0O9e zrs;6N3BV!;AQ=#nAJq6Ol_LQ1Sx9e*59S=Audn0^bt1!(!O^0~C6LBw+m^W1a!CD$ z6SzaC8ukn9@0S313I#`08LCNs7SbEgh`5If*qVvzumAe7vZF74>5G)b%?V(AILi^9 zxPkr9MYp5NVVA!m5YxZ?#0eMB%yJh204-`$yZj@|Q*nZQ;l4k3`744-^XtEH+bwT@ zXPc%(Bm+%bUQ}QK-ueu5n5wQ;<90i>*33f_TKJ_#1ceVPpO|WEQ>Ryi#%(G=v}uY! z+5y2dO=Yavt7srp>{&cmbeN_l(cg+#&z6pHmIuet<3kZCrAFIYnJN6mOWO{g+l-UAOJ~3K~(1XEkrH3aJa77RlPqWo>o;w zVcW@?)gh8FlCVpMYso2N`f;<_w7E5mYVs7iee1-QaU5G~({_R`=asAKU;p7B;hRs$ z0Dt`t|Byet;Ds+BW?zRYBCXkGbHrlKsth~3yH{UzZf}48sq?8Kh&+;7NqI0b{TtpUJeU`1NxDi z3#I7p?*764sc{_Et6jc9i+uX-UM@5{*f-rsw^FH)h5Q?_WJZY+P2KwT5oMM9>+Efy zXH($GO<3Aebb8nEO^WfYo13**beSv5*m({}@{3ediWC=TaJ*WrkiDF^8Clv=32qCW zbid=y4k-BI-+t-cg{|q)7C5;Nmbw_r|LMX}mh?UQE4nx>78M*Ne|{$LY~Wb{fOE&6 z&T^c~<5=0(;%B++_3yQ!tl77| z^(~LaxNPbiry`f6)=EYz5X5!l|J+FWL|L7x%+Maa>ES(uv)E0 z_tm(XrfIv~9Bnt-?bJ7>v_p<0P4_4(T3%e~aFfa0r%4iP;ZqK=kq}h~6a2cJ^-zaX zr%xU1AJkfFsfR~LM~6obJ^1bIv^_k$B%+Vp{-#;+ErNavK*gQ>hNQG+JaL6W>Wb9PN}6)I!p<#Um;7oIr_!Gt>5bK+|L ze)7e-nhirC&cpB`TBP48P}7pEE5V2JqS~m5<1qN#sZxoG8(7z>kg|xc~n9uX)QPA%fN&`}@!VW$PPWAIh!s#FaWYfya|!hKDTu?9dUQJ?8z;u5u7P0( z$$q3ypg5FrB;N^g0qW!n0}km z)~J*?bI9mUghcteF@JbOmbR2S~Ipk%Z(^7_^u2<`WgM+=jy;|#fz5b4q{J;DV z5jlVU{F$?7zr&l(ojVuXwTP-t+r&7iTja+Q$UNp~YM~3$gRAZs0gMceK?$XlZ$I?y z{wZ={qy#d;${qw0Y^H3)_ljn%ThxhUlQ!@5FXI@RFFn7(@pnw5d+q&GEgLy^l8EP# z@Pscep)-mjo{ZDNTWjK4O3ea4XHKk?!kE0TUR#u4@K>@TYn|Eesq@%RGgs^|S&5bSqpjNH5 z0vdIKE=8phHR$z^S?v1pPki)>bLqMly|}yhMf5ZGeERbDyy^#D0{EFTXZQ9F&YipF z^y$;9VYS_EAAb1Z#~**5#f*+>H1s;RIWHB$?G@Wk3lS3v05^qgK_ zKS&2OEnXSNVHn1PgM+=Dol+{)1?uLXzFUB@IJW?}`6k{s!mp)!XTBIx$)JWdamXFq?^Op4RdWo^Ph{8UDtPC}6b=Y~`k^ zf9+Y%JagvEt6uergM)(;j|RZ4x5n@9xq{5s6%6m=k3arB^;e$a=(|kZZ8K}lzVVH3 zKKHrLS=`=}$KvY30lxUy2q9<=UgprsYh5R#LW!XgbZtbVn5-{I1V% zg4s>4p*a+gN+S>zei7W6Q{k7odo6>oKQ}$1=29d_=)5j>XN`tago6&%FoXhS2}e%o zz^HoaA6u%E@?Q#eB$x#U+B6Y!QIV342k&ghr&@wpV7#3c+dZUhHGl1{9mhZw9ww0a zJi<5-sLiBQNt&~}f9CGMe3wN^H(Vbh0^p9#cC+1V%$Qr9%v@vOU{6dDf#VBTYNGd+ ze{tgy0YTy!ysR6*ov74O5B3jEpE^AbV;$-=was>W{^9cvKYad?+y55BFUDpBC>C7l zjuH`tiQuhc8&8R?$A98eeA_>L-@5^+b=ckARh3$bijwMg49Mx9T|oKq$Kafx<0CBD z;9HbQ5>J8NBti5cMO*6#3>Q_#l7(#ZF!*`^H5Phm3h`wH5HjwCX7_Am`zjdwt4fj? z$S(lQx<org5X3u!WGxqlPiSWAl*|TSJ&TuLQ=ovfd@#!%K?7$EF z<9{nTIza>xHae!D4`SZdQM606AnFj)tFJ{^zv)m33JicSI#F)p zeLbp*n{V4hPosk}QJCXRg>*bl*X5lMAY`ywvl%{-kkQ3*WhEX>_lr|SX7v^T1Y`P8 zm2EdQo_H38P!p#wn?U#-8PKJO4^fgpiy)|_YF5C_=%>$G!ZH1OVG{C_$OiE}za?RC z%e$3wFd-^}&2En5x<=db5xz?;rQ&JqLF^}%G_pKy5zs1HU0(cPNhhbQ) zR{Q(=JNB>t_h0<|zhJKa<&S##OV?a;4O|*kzD0?NH40oi9Frtw?rdNg8}(d?7q^Q* zZm$@N-AR}?mRR^wO|- zZ3H`>DLBc3a{!_`6cv!^n!tIRN>v9N7`9T>-FmNFIzl~k1ei2-5gCTjjLS6wazMwC zEw`r(F~TF)Qi1|j)ZqgLcW-SPhJoUaQ){KFo7WmSjXG4D=(nMk0+m6ATI>5ic-wNe z{O<35^l49jI-j_fnst57_zpaGYV?C0P7mNx;o|BLtM4DX+sjRhTFEfH>g z@ejVlE$5{#dkHI;e)=6hV=bWfqwSHqlq&E7@n($}Ie9Kb8@U;fNJ(dlD!Hn~g8Pl3 z)M=VLm4nP}vNjBZ6e%K=(6S1E!=oeiW+Cq8j>#r-Yt3pMiVB=@FLOEWfRqp3MiYAIdagW4&Op^juC&}*mOk~@(y zf-;={I&HQfZ&O4eZJOY0^6CKC#34NK+!rl+iUl;Td6ZJR3ztjGvdIxtwbn8W)!l7w zY#ciiSxy}f0zBOyp}x{InLAlITI-;InQusOOdqe~3qSn&zmYqExqENY^wqD-HBB#g z{tK_TUS9OV7Y}2->Z)_KRC9U!@yEaZ(4SnmaN&Um9*Fpdw-usA**pY*hEb2q^Kv~< z(W8SenD@vTi%D-fmtF=%B=YR-?eFjHkHbjpjK1bwpY{X@xMb{gHy5DOeBp==L|j?! z)-jhroTrHz?F7!b-^a7gM`jtSd6wVKj{71u1D&l>7!r32KtBQk3KP!hcSKC9S_A?Y zxJwbhK6!^EywbW`yg+A=zhZ$ywY(Jq`0HOQJ)59ffS!istyKbz4n+9N+R%_Ak&xX1 z1$0?zXtJ@k&U{I?7#mvTG5Y?Bz;-xQt`78GKcdt0RF2iC@819pH+#TC( zM~MEyG(3CsE$Svph>mMPAdrKkX)On}Il0D-U9yQ^_+X4AAiIy!3BI5r4|VFY02MXxaN(3#iS zp5+Fhpp2_=7{-HBr}p>uYptwcef;r@-+t));nC4IZu{Y6LcAcX3U6Svx(hnL$G#iR zPY*LZ>K^7LgnS}tB;#)a`6uuDWdUlftJOHvaa=tu`=|6%re`I~2r7tUC*r6cXwkvq zrjm?KnksLYj(rLlzj+wHu2K;%stB?t(fon}ad8nPN-G&= zaA*E^@A&b&g&0RUefo4M`n=~q55UfPhe8A=+~96KWscYQT=S=7C7hTl^G7r0^Ehe+fU{R!#gQQA>@be6eAO$y@|CYW_~3)Z@he|{OXv)W zyz7Ml%|NKd6g|0}bqNfY;vEi!TI~2r9xF6Q0*4o%fv=hS@g%kSb;zaD8wERYnZIr>`TVxAOIBj zX4h0g-hsFh_uR`R?sC3io>)#5ngIIy9{Pd(U+EK-MU>6jTOa%TGodvJ5cwssRnfhj zT2qnDW^;6Obm7rQuY2ZSe$syz$1ynO>CbpNGYJyo3bv=aL)>g3$d#^hH2aLj(*K%s z%=014>a2zvqvM|#KWw*KL_?G0 z*(2Z^Q4GT%Lah*#QW1O&arZV&;@Dd2_kq{PJJTj#?&xe^%CQY~Wcb8J01l{1Yc`as zTANL!lxdm>C;j>d-}hfOb>9E}-+1A5&&Si_aR6DW=0LA@S?;avlRcujZ&T#TXLYyW^*HeyfxGxiHlIZVPu?Dw@qhnHBEbo4I@QUeOR=aOTX} z{`T2t$(I86@x=}Xl@R500QZ0C%isT!7X$b|-}`?6c>7P?GH6kiqoboz2YTdf+pHxx z=#JFun#=?=kL#RuycO6<6U3!FIbH$Eqb* zjz}6sBh`MgI#hLOQ}gIr>}4pd_TPrSIt$w)-kySMBPyEqS{&Xs+p47(`>3jz0?;DU zv^BF*R5WVh2wA!*TZ^=*vEY9@P2d6~t`8FzcW>K?X2F}0^f-H>8I4$$BjrN}QVZtj zXzT97FmkbPw~^i?KhDhAA&YGe`ts*#T6B~zd^2xIS`13aDajPgCW}@b+U1HRHaWQa z55NAeQ|{`HJ3rCq(|`WMui;9%UaR%qw;y`wD_{Ql?Kx(P$_4@SbGqqM?!9^oKYpa2t+dd6aQz=9CifG}PXm%dCX%K8MmI@T&CCE+-R5^F-OKD38Tj?)NuJqt)A7U0qc0FH5idgAC>Mz(d-7B zEt9v?mc5_7*64#~4)LK@cau^e;@M4%Ue3;HEhI*C2(;Na9x|DAVE)AYzA zk9_2Je)q9QFSuiisQNTBjlRy+Z1Us@HrwPtJo)NeHPrh|7r@NjYcS7yup#EnqHhr) zMQ>&W>W-tMLn<232_~9jX6{?jlC9D>g91r^%?$$JGxwA`?_yj!-1M3za8ZS$HTJs| z1%?0B+|>MVv!Pz5N7_ufKk%bwJXEn%UH*X=>Y}qXoKp z?6|p%fbZ_?tyb&(gM(qHJF8vxC4B6$$N%Jy|Lo}K=%L?w1Ftl|j;y&8z@1zY%ZZG% z-p9T!pCe88{MJ}Mb1Vn||HEy+T#BleaU6Gd&Z#OLj}U@Q5G6jsl(?Z|F@e*V=ZZzX zi2hhr1XbsOxD&zb`m(uzGAF;hz&ZY!lW;&36-p}nN0&Mh%%CbkQ85TSs(Jw^G_Qrx zV%}$QHcsmH!W`Z#gj_NZ5*5mMq`U=s6W^sl3pxZTv}Oy= zMZh2T=}O0|{_)$c`1*HyWL!RvEFr=+wMQ;oxcaKAlA(5m0W1T97k~eYU;N@1nfs#` zF8uKy|H*|5kD9f2f9*}~{&O$*Z2(1!c_d}s+_Qu(f_S<;0tNHdXj20$`7SvGkM?H$ zp{puFFGk!wo}&>5kw#~@Xc6tGgt4uMvM5o_jcBEcPLaur+YsEAbZj80{oI#-3htU& z(zR3}Y@37@h*l8UJmpl}HSR+QXn+8BP<~(*V$2?G$70?hg_!cY#5JIKl6RP^2sT_7 z9&&-sa(fIkTm|v)=ZZhx83C)4=qqtZ0%U76Dy(zokXgMLEp(cz&PWiQEyhB;jRopJ z@p}8!{}EZvW@c}@__N&KgIuY?`rm14A|Ob)3?KfhAAwn1ef2f&?ni8+tF0L_n3OC5 zP=$&_$!Q{QIPOf%9kUh-C(k28Rd*>`YOVYG`=?KzUJc_ojvxE@@0}Rd-+JSlJrXIL zHx(Hd_*@U-{l$*d5TD@)NH1?T87o1zc64;a{cIdZhCp50rEg>LEw;o088VH01EUUA zRzs`1PtzmW|_?N%<#y7rke}CU!JOdg0AvsF9(-KzT zpXLDAm#_F`Cf?mIT{`5?t@$)<+7pLbq@!<%70#2*-Nj)GVVWx(mka6<2Tmm;kfm(y z@M)Tg)?Uf{^S|&e0AKpzmt}E9{VF_NkrP+Z+sApcuYBn%?*8JJz8C=MML+eHx78BW zbG44^u}sr6XmP=%!^1weOJSJN2pLcp#>`5oQ+B@&Az1fXimI+uSr|1(`vmM=Y8fne zHO_^?hI>o`sbjKc2`mw&bg{@V)#~Q%TUP~SYppc{M2E_#YrEZ+C?RBa)ZL7TBo<|~ zT)!gH`*{&#ib5pVFbuh-3c=HoUE7Ja78En1IMFZ+s@QIun{BP7Dk~JnjAn;Uma|T^ zx;LImRadKZpqazKDc0K79h*(4>B@Q|FdUBy*TYnO4b` z_TBQ(3Z)RZa8E?Y056U!nUhc6aYx+VW?B^D;_7D2V~~kLb5HG0Hc}1JpS0L9B>_KX zzMC64(sW5ytDRvO_V*8V*SmzPG9Q9F?poq60a(2Lb;0sOkYQ7w#Y0*sW+$77W+=`M z5$+A5=CElBQ6$x6eVH%vkVK!-K+s>|My^ipwlX}R(r&fZrfD+vmw}X`EJG2-!vW~j zHIDz28XA+Zzzh^ zg!TTdxuBFH5VK~KkkgPkxZ#IP1uA;iJ)65e!)tFhzglWhcNEpB7ha(lAdtrKBlg%x z_W<6Q@)y2aMIohGi$)cKl4^HccQ#GS9EE0+G8Qonm0gpph?)i7;ejJZdQ39?N^9$L zMk*Zb(C`)^omg|Kn-iXeg~FYf_mx1pvxv6>0sVyRF-QPWf;xxjrPS4Gy@nl~6u8Ni0QHlvc-U~8yKR0i zf=^k(E8UOpUnGI6wKi?1#~yp^^y$;bAe*Nem@`_`vuDrj?Cd;p;lkIx`n73l;;yB{ zjiI=2QBzoJAlRYEX9RGo6*AMcgTh2T=Ke^kLB$7%qab&fFe~#k%(m-A1=6O5p71ay zV=XW!cY~FbK?1d7iV&OgzIc=LO=rfKHVpLOkt3~>Bu^p)zP?kK z`Bysvj_DOQT?9cwaWJs9z|Rm53f%_9y$Tj&Y?%vdz}-_-cX#*BoH;X&tKIcZDdlnq z<}GjjDNWgwCXMu#909GLbZ1!LBE=U> z6CM&q1>s1~EXOMVF(N{%@zR&Q?Pj=9#{-I|%y+VyLvX`(qE$CV(6d7@fadTmxk2Q95lA|Tm7ih$jD z85JvPsZxNdzS(dCL-Qu)QA875u+|!Dqgpedl~T0SqoX4Uo8a1m29fo8-#$u3kf2HW|nO03ZNKL_t((0p80rnW}0DA#D!99ko^}7!$LY<2qHI zXPTx|9+7D>L@|+1)5P+b;}h~&yr-(Q3;?>C^6{4NN(v6Gb8Bt2S`jKD;N>22Hiw5B zo}X5WL*=({`(VVsAk+{Qn87I|>fK*inm&Ij2g{WJqDV>3MKCe~oB$x4qGa0!DFd;= z&8LkH#Fu@Kq?ajDN-4X$yZih5W36=o?z|Dee&3(}64ymZF>9 zQ{POg!vUvVYH0L?+BA6zdl8H2&<5>GZ&NKPOx-bv;)i&GrAC0rFbrqToEgV)7>hur?Y0cn%x!AyrM;b+yN$!J*>2!IjN_9}Jn8V=yO$m_#ad;`^InR0SbD#TMBU9}%cqO-OdVO&d-uK>399{^BF<$|KFuv0=HdhvG8(3_ZQXe1X^gZ0Pc zQC=6JQQGpbX@pVCY#axNOcN<+5z+gs?2sC?yc5T_@_tx?+F{RW1Voxm?vQ3QrXiw? zZu-On@%Qz5J^8F2=-@dv*3(Ba`Bt5*!TaQlxZQrH7SViB3+vc+2HBsRwaW&!3H20ele^B(_; z5B`t8{wu3-J&eOp2T=&lgeY%HNHlXnnQ19(>&8bFwgn(yV@cE29ye$0kf0W|ELi9= z6TZBzo_j}LJ;PcvL-ruIW^h%OwJO1ytj9m*4tfHeV5v1tP@<(dkxZ0LW!U!@k%o8g zuxi$bWaJEou<#$LF~ZxRlpjnTW?p?!fzqodY<+)f zpZlc`p7?P8S59aJ90y(&XUd;)4m(qKZf@S1tyb#?9(XYM=}+MW&1add=6Yx6ukGwS z^O?^yv#|G5|34#v6Bh6{ig4B{e6K3&fb2tZOZO_MiQ5m!-(XRSo_ z0#t!O+$k6w8@mJM#{MkRG=;RAMS6z7hl!~MPeve~BoYUN!bZemLR*7PqeMl_$aV=N z0-^ctV%Tmc9FKjbXkOVxoM@<{#7Ik-d5**~L?}a}(I70ps5OYpqS}^~N=*2v7Dzy& zyo^LF4ertLBcLwzEMNp;O|_I#g0bBf!OFf#VPWeT{6M00yoyk==ops5D__l{`_;E`~2BW=@T(C zw-Twp*hvEqbdxT9>XDR;lMM+9O<>|d>limjJM62XYz2`Y-_ED=vRm_F9;@#f#Y8|fS11PCI9+g|C@jGkN!IVzw_abs>tr{u8Z~1 zR5E|tF;#a@E!UG@-JRok*ctjF-LgKmU>Z;E?wieKyWPI=$A7e+?Mq+0pZUrDK>%#0 z*MIHzhyEvyN8o(3yTJ9OFMn|i=}JrcZ9nmLEoHMg;udeo-3>poHFqysiWZ1(HXDej zmT2QTs{uT3x&_jm$=<4l-n%QBs-$O)W~YIkc4RW&@9MO$`wi&bLIt zOoESQji)Q6u+W`}H&&!PJ$mPWDf9;>8zRYH`arXj2(f;i{uh;>X zNGUJW(EG{zBY58jt{|rReb0Grk5b~vC5+CQZstG~KYGVs7IjE-rwTa!?EQ}ICt#xmApW)~+*K1J)td>I0KbKzAX2Z!NhG+>~a%!qdtxzq6)w0e=Nrge>I1cV;ZEDR*(Y?KW zO_FVtRssPT;|ezDmRkhCd*73Es>mf@!N2z`_6G34gMa?mqZfB}*LyoVaMx0XkwW$S zYTDvsSc*6-A-tubKKUj22F{S>uY4s#Y4Iexwbq_^;)#nFFTU`)7mVZBL%sMGfq6^l zO#s|-OPuVs_X@EO?e&J~vR%CR)M1(?v!+@; za}NW80?19TnfLN(n%pq8))j4w7Ad8$uBvxlC)lR~pLb79A*N;~vobhhahSDiS_H7C zZz29c>x7Un5KUSAzSkd{2Wd2N7cOD5`)<|u_aHQco#!`l@Kb0yNGfZ@?ULlv5x5a# z*PfvN;wN^wXD~xaa=J$5<4T|6;C~yjH7h!#}sQkiV70DNML0K(Fnq- zXtRcV-P~+y5E04dSqtOeFTzvjV*XRaV1Oh&0Ro^Bwq!ikRbevFrM!!$AO|Bl?eQ^% z4^$Xv(ZNzxf?v&Ar$w_MC|18pR)x$YIPQdy5X4bcMzA1z$N`Dx%hLgAdzFEAR8Q-% z2Hvv{YusTb@FAl5zW?^`UU%IKOD!js1~41A%kYzc-ey#gLX>~C=-jU_Y-akO|2}w-Zaqt`09Ufk~bm{O}&w5tI|1+)= zX0xBTLqErc7H2p2OP4O)_qqEn9bR(xcU|`(8YNb{u!xN3ZPu29Edqgz?%OYHgJVWsW2i9# z>3Auht24hvpA(tUr#cDi@#alC@{82rQDIq7XdU^n4Lrrql3t7~=tCAJ#r=qqBCh?$ zBB>cGN!A-RK#(qaSJIIX0#}K!E&-O~^Ui}<6PWaT+XWJ`XlXIB0@2b8C$RkXC!?C_ z*;oC__d?1y;F#}w?sJx}dhe9sG_t;A&BSVv$ZlZ~XVAY1rb=3DR`R=Q zfiHsaWi-xzTWiy1D=KvudIq~USm_Z(4-WfD`0cu=jNmIhMc?=J9&@_8ds8i4Y+|m% zg0yK$!h-jaXjVvZB)$B>BM_ZiFC864qufx>o*EledG=0s6M@xQNq8n0)UW91=tx!f z_xDRF<2a&=1o2vOUp_H&I1BpyclXU^bD4KF2c_LeOsSId13&mGzVe&D`JtWFdc9t2 zi6DG2Gv~DGavt_O9GK$bSQZrdGLRPZ2>_r?Ay;(i(xpq6F1h>L{`OCP_MXpj&i9a} z31CK6v@@mN&gsSnuP(hEP=oX4~!7niVZ| z7^W7H2`ML(OSGh4_KE6-W)qv>4MPQVYmLjHXmLktjdw{^-JI#uTC0dG+CsH)9Nm4p zZR1cO=mkeU&8!y7fRp}e*cFSL!%Hx;scmB#H`kKu7k#UyEz-a;tXn4_2-|bO76F3; zz&MUGK&GMO+JmJ;F6c|o017aVSr(1hWKp%We7ysy?hf}NYSK|2Jvur9(7Qy@ws2GA zsTe5w;!xH1|N0eJf!99!IhVcGsLVpKT7(>V?@k3A+gpLfq@|@QrHT9kd z=`Zm+j-0rXy8CuBF?wibJawtnVPL*gz@SfDw;gB;>P;KRRcn)osFnn*t!p}H^rZB@ zckoJo_Ggz!lm6I*GEKPmrcUu%v?T^{)SA6 zpLhz+2|C`*Yw%_rB;}q}x^`o7 z;zd%wQ41w7QB zow?t0ukl1Mp&L#?Gi6$#V7`Ze+7Xtr{42CO5wU;NJRei)Y> zzwp}siHX+bfIUOE{Amt8`IajHFN;53esH$`liS{{T58pCT-RF0Ita14B;RWmrsa+E zEXFz3(r76dfsC&JKr?*pcBPA#X8ROKRx4=M@9^IHEV`Nfxl`vNyTeQ*Bjy)H8YziEMNPO{fPO$vMQ)4kW+HB81eE!tIekpq4&0p#5FQl8!V}X5~hH%VZ z?l?}zjmhusk)tgDPW|Q!4-bznUAlDbwbwGFK5-5~_hpWM{c;lt+y>_M&_fU1fB%=K zZ6x;I^}-JU4v|_b$>U7>9pm*N{y%V*;A8u)+3}&uy5Y5C3Ko*^pGtkV_(y5UV?Y#h~*&1ZlnY<$VVa`Ez#9HjCo6+ zHY`Ixwb=O_@nwxIC>Z+@TVc@JUHCk4?dnvL^ zyaQ0xX=)`kO(Tq41YMrcjEHPD8#2jNRiw}}j<5%%+165YqbI97#=$~^u?~demIGMc zpB`7|ZHcf-muv|4$+ocx<=EV%r`$8zYO2vLhtYzFSThxAt+iD4ox?VO8n0KV(vjc<6907Xj~m?vkRGy9CzNOiUjBJ=^o z7=&t&ww=sct;Jo;ecPt)?|Rx$5v^KzSx6`_&h6Vs)VsK~Qn?lYNZV{VuWGF=^$r>6 zsa7+aQgubBMIr);ub#GzLh#}4Cp;lpz>fti&+I10fIxhd0Bh|{+<1QGE=r}|0b8eK zl08maYvmq9Kgq&tpOHJ>AAy!S<1h4DXh!&A0U6(fcna+dp;Aqzee86E)rM$3)pcsj z?1R7g{>vZzwcq#bW4~ubOo!2D+CchJb3~l;lRxkpch`Fd2m7_wVYMoy)KWO$yFM)$ zidWzium)c8OTW0=*G?CV-rL(9h5=ZvR-|lhd>bdenE_sF&5b&96d`jHp%E_uE?SOl z<#RrkA|>o*+sxsm)>72W7bY6nHY>_$B(OH&XEPrhC;tckAie~UU;Wkj{w{?%&4~Nd zewleQ#ip(V8AXe|m~on>)KVdKBdRh@ZJw6Ko^Fx>utet+1)@iovt8v-19BRMftODh zYnrxzl%hL3yMd-H-RIb~FZ0FS`K;gZ4gmh%_c|*9S;V?9T+t4qpCC2M9p?9c`D^29 zy|cUCU9TfDk%gFp^d_2V370~rIXO-s>HL%=sMjYspU-0J30!Qm*&H4ow$=_053jxU z+M=^o4@WYJaXai@DRYIC!Vda}2dab&}}Rn%HbQJp6x(Ril|(vy2s^ zI&NxPpK%tbCg74G9l{)i^>%BP4}57HWPzk}rVYcOno1oqzb82<@dxRw{~jv4-}M=! z`LYuklo^*Hq(Y4>xA;{w)a66~oi-aJ`pJh};#s8rf!ll;?$=-MqWU`@`OwMv1pNF> z|9o-1xe6FXGXm$Dl8j_HW0zrO{^Q59Y0>9zZB5 zQ&aO9GLya|X3UTzM{?*?m8@+#%)i8YQlOI3v9Y67wx4Qf8?)t_XZ#;A6%ys|$i+bq|1EIjW7UYf$ zQP4RfoIDhm5TOt43UNVCN+X}^YPIS^1)_E%10)ymS~V-X-QBm-L~^^Tj^o%hQ0YdK zYrWlWRJD}g%WO8A&c`8!Vp(?+VPqgCBBe}|Z8jUCCw0LyOva5yiYNzJq)LIorHC}4 zqq!Q_?rz>hgisgxFLakF^fT-?#)Aap zXea!bV~(_*$YS=$#1|Mucb(~pDS^xMDTuE1@Awb@;Xgi2tD1PrmV)W1IpCNTRbwnN zXG;X^VHJU(wWp8HQoI-Ex1L zwi^*y)q%6{@bED4O4SrL<|=4yyWP$$+xns_r3}MhW-JVHKPDE_IR#uk-FMHoY*$1& zYE8>#)TW8&3!M(Pu|FA>LEse*>lNUwV_*r9X8{gl0FGy7 z?qJ@<5u2v;%TEZeZ_?i9FCS327bQaXAj^o5+NoMwYdyVBSf5(dA|ly*9l+oJ`wloT z0rgjZmD8ZnY?QJf2sjcP4?ssmmC-b(5dKFK(P=s=(WAYo7IQC2cL2RAf{AK8pnAg(Pny=#4TLJic z-V<%Nhe0aM}Y{uhwllkxf%XAYvkH9?9U7oz84(s-+H;G!&53Fpfk!mDsLo@0PxW~|5IhFG+S zu4eI(5p-%tDih!|82|x&d)_qBEz@oF2v@D1IWnCW%M~pDt|$cO+(K zRm(6|&Fw7gg$LLtv76Af2&zI+3bFu^@{1YUk^QL9(rip4GF+gXoO^4-&{YCpX2LX( z%PzlzNMZ9((O#JwFa&8?{3|=Qb1|o7;D1FRS^{O^`zesSh-2c- zh%*!|NeQ7H%364#PM<5(Jjlg7gGI)uzf~+o5|;#@tWkCQJ0qKa#Y05o{Q2`Fz0<=vkvCg}&~ovKCjgv1bJfny&Nz-| zPMuz_*Q$EwU3Z)~?@zqtt+m$mdi|_xuf6_;>#x50ENL2&3LTyjvpsO?EQaOU>qfjg z<#gYPdMJd|H{EeRv2KZ*u&!rkXD5t!hV324VFcB?z@V2LXU)QEUw88zpSlw%(%H*@ zmXsL|qpOW_sQkCHTDlkURB*}n`ndCsyKa8%P0LsA`}`OBRh)24FZWabvPYKB_g{}q zE%6yH>3`z$_`w@~5Wt6T|HwEDMXMZdbd89q%5uyzkK_2r{qij$NfS9AyuUt=2R2RH z&1SQ|zrVZQ;WP^r7SP&R&BwSlC+=a-@Vh&r(aiEA{guD?SZ?$EdYAph0Fc(9sxN=p zOTWw0@_6GL-jvmdE$L~YNpX01C?dnKigG6@B52k+@4&Mbk75@6(nO>(r6a7|k2XnM z6#YIE*YGU;1Hi_6L8Y+?z{fxF(eE($zwskKw%HtY&}4S^7q|}q619e5Xj78}^Bw3E zvwnwVQIP1~di5UvHDz99mykzJNdCZ5}-u`#m7i!Fd6I+!lA+ zY_=jyjF+qlh`BROQ)|IADW%j}80RBBG!bD#L{$Qv0o-J^Q~P5Qk-zu%=ph^6?|wIN zBBS_GDFmr{@me=H@vuaAX{J&IPGjX+z91q*VKmw#H-H`eq|;=GlEg{0xLd8may}C< zHEWMP`q;t20moA-jZ#(BTB)~<5*woCWRNTUd*x%n4LOFq&yG8%h4%|gPnW?)bJ6m^ zgAbVd!OniEp-kD=AVg9~Z;=p-t6RjGkYzpH3A-wZYI~|yXYG=(s>>YP&E{ycId|@A z0i?t|&N(e2*#v31F!KDj-pZNZ5t;vT|LepWPqyH(Z+!CNll=A1|NOxR9{6)nwbm|N zxbW4lewFvFh&B&X&qBPp4o-xSM=6EBg*ntY89ZTOwD1f38dL% zX7}DJ!%(3W82%v<;)p3!&PDO3T$su@$K=GiN%tu?~-%MbP^E+SgWM}O~kE}t7ef73sE>Uk4(^gVvq#>^1y;s)#JYhC!*J!x#dFrf0=Ki$akrnlTXreYlEF;7lA-11OG{m0H$1 zo&yVZkgrTZRZ^b{Hth^SIXueHnN0m-mGZ%`5C1_Uzrkd96WgNSFU{Xq?u6WGAus)W(A?zhABfTV?}LbZ`+q< z)G>1tqLF4vm5aoR4Pd$~pJ=9%YtHmqo#m`aHklC@&tkn8}L8fT@ zNyQf1`);}Ui+}m$*>oC0ka69J2sCg2>)^^%tG{r-bS;Lc%n-6fZ295#fP7kll=_X0 zjme~;;v1bqAu0H)i70!%j9!uJIh?u|@P&vnN>#%#uNRsrjiu}nu>KQJaxfEtZme8s zUbB4cS3hoBcxt;4LQ*72F^23-hRMWP70jo@y3W*V(@G6tDG;YEy&5MijwHp6#cJ-y z#pJ$h2IbuQ^)KIa<9na}&bME)=6BqFcje;i=c_3D0eQDfVq+SUmaM>)2TB27@;Ht- zr0wvn?~}19rIZ$nxyaB7c^0K?J`Cn)d1i58E2CBbDa{UripvE_Dm*IW(py4h?em6VfTfJKm;bhWxy4G@CR2;r&A)z_=si^ zoedJ=g3d6H%;vHj4QDYm+5?DS-c+uHadlu@?(O@|(39zOnvoix?YSmm_)7`%u^S68 zXZ)Dfe1j@5@R*DuPygvZMd3X7!#`9T3sb4<>p90gr6dFv?d`ZerQT2*D5><>{(vg% zr|6l{O8P>tKM{9bOXNOWhAwfY12k>F>pCLLX0y%BJv%$+nZv$)`>b6#&I^@h^J-|z ztC!E_%+~90Ox;%)!!ebYuYKg@a(U|1sjbb;5TasrbFXbf^P}#J@Hc=x%p9zCiYEaO1D`%W^4L&M@dotzCBk>v9MlGeZ`KNCcN&ENj zAF+>ROoj;6x>zsc-q@|Y=N%QPlUH(7dk`V@SS*HTo;ZPX+h`grTR_jh{IV%F1b1o~ zyd87Ei#aEH_OxVRVqvr&e6nH)fM%%Oqj-!39fU$7Ef9lFv)2rlrDNPl9}V)RV({Rzz!_CZe2yiOA3#%`CZ;Q)LZer1Z3{o59bqNCrmch~bO}4bmdxrj!E$ z1zEQk)AoB~)f!n=>fokZ0N8X0u|e)%Dbs&0wwCLq8~s_L+FdR&_9;L-_!uc*oRsd;O67 zu28=MmWhm{avECkm-)Gi4e=cRzbD_Xt7uvy7iV_ANu|~Kghx8LgkW6E)kIv zCr(*xMKOUWhv$^6ULw-At*>_?sG8P@%7dxMgo4tRp-d?eitel5c;tbD7hfVGeeaZe zrg|=yb0Siu?Q>^Kg>Sv(HW3MdjKEtgyu}5~AY@ck`eXxY&op^e5L?Y?SK*i}fNuzq zh{wmFgJ;cH(`C(^*#%{;-2h9rY$AecpF6>=%G|wHv0dR9liQr%A>3b}Yn3*4WtVn|hTnrre@Bh1ZTy)Wa5CYr>n~H8^9vS64rkY6kygBb^xyJ_h zsVqj*gTp|?qXj}Q+PUN?dde!Gy1R#_B+KQ}ERI4DVD&8fi-^&>53{}R`{l9~5py31 z%w~W7C;w^Lbmd?C53oab5lNzb-=8>fyzhH9MLd`uV3s`_gqCvFM#G6tpFX{Fey8g@ z0-1bBDNUQHHOmslx9yUcC5bJ8ot>SwZ8-#ZCSAJjy6cGf^2;y3^s>uhjQjTO*>z!B zU;f<4%dW-Xm@j;x$c=kw0?0d^uju;!Va10o;hdT{rc8pSgU8z;>4R;Xu{O3(0vs6*;%P{me7pf98ANQ)ifBKx2%lmz4U{^)W^PL}W5) zIPhY=gkjChMxG>DQZ+FGuy}16vV`j6PjHM8#D@=QVcxY1%E+i@A27Fpi!tve>)$^A zH+|QEXf~V8rc)73saKUfd-iT^Z2{D$o{5axJCwX6stUyHmI4RX)gwa`7H66{P;zWn z<%ei+3^ELto$qqwHBs&dNh$d*K=kMl9`<5YgBT7SrjW576htOpVlB^v#JLy7V8{Ir z-nTyPzjxbzi82o{7?voBTE@k`{N_DGpb)}rHZvfGIRvv}sIs9zpM2>{1lro#yyVhL z4jw$XwYB9hgG0T8dSGU5UX2(pI4v-fi*+R;rA(t$w)A8h1HMWvP0z{G)GI${MJ?Apgj*xMHyy(Qj=d<5jA;bvL zk8N@XC<;siQfP2i4h1NszE3H}n8S+($v{j}ow&ppGlUwEQ!I%{j7^AviSUE#p}S9p zGL&V=b}5zPfaaNZS=K!e#s$G{(ojx_0Og5&o)1P|QI~-XKIj*#h!c<6x8?B@( zFD+ts^{z_3=S^Hhw*Ks`fq8Rlv!0@)$Vt{~m~y?mHXO5C*{!#ScBz>J?&Lyr{FPU% z)4u=A_eI1`R#HmLK_uC%mW>sLsMRawe>16JdZ7;Zg@iTN7f? zyoXt{BqiUxsw`|kCh4gj{`=EkCLD9+l~?YHzZ|~hun{GM&=8djLHyOP{q-k5@o5oh znsD&o!O#8c&;7z{_D0J;`iK80rDQsTsxB4_J2maPj!IHPRaK3V%Sk>_$+e+yuUGn` zKmNaVeZ@cj{eS-Kv(Kv9PDD-9m=#wb6`P!0*O>!(*L6%m)cwi;v6qGrG-nGp=9gl& z!3{79p-CzI#TQ>Y|Mz#Ee%e0NIwdog)JucnUcn!0MR!lRJT5dK_|*~C1pp2!&R(Ud z?8cNsKg>HOLj%4`8630nK*8<-*!BLp^3A%2eW9{)<@hcJaz+3kll5yct%vuLtlUmS zukP@os)PW~etn?`^Ve1X`p;Tx9G6x5tys&qG5 znFMmy%<%R5zg9owBOm@%GlYmd>>WVY^~qIaqReYcIdRgYX*>^f=j^%P_=Xcsz5nhH z*om$+A*J-tH|_^;(SeIR7noUWV{bSB+vm2|d*<+MxBD2$piCE-qd-EGDXReXbWuhB z$R(RSlySFE%*ZmI%fxWcd7@fNFK1$2c_Ycn0hp{q&Z*M&EU#k2;gA2~->f(AiYu-t zW9=9v(R4D~vuBURiW*&2mfQ5$QOa~MrQH1A{x_Fja@l1u2D0Rz`FuoG0b@6pZ1@ne z9-bL9YXN|^?Uu`>c$}u?^FoYqGHFthl+t9;DG}N4jwpgpzGQY!eX&_^2w*Rx3`(8 zYZCzvJv_;sK=*tE96Y?gZF@7%ipd(7C(}lfESC#QM`8-0q-5McA|CImPOB8lGzfuX zoWR0(vK2?bq1z6LNC&CdeB zA60}YRgQszj@aL7-Z2KZY0+kE;^Yb3r<6nGcddCXod~ZcwZ=^tUsKlR+O?vpfh{#j zaVQw9$|A;zFVv}Ag>Kon)Ip}DMXz7c2QIKHt+WWQ)eq(E7T2~|%)74p;Sc}j`RAX1 z{%>E9l$Oh-QTv#K7!hV08_Q)^9Fby-1y#xHylm5c*>zHJ=ZWgKzU34`hYtZjAyl?s z*-{Qg1|TUX?oe3DzZZ|a(D!ZC9Lk2e=9HIdHrw34fB(j8Q&KM~ff*Sz50*+JtNQGT z!?eT=8L-kcjoSt}*ELxd66lcL#~VJW3=1HqK-o=Iphu4wzswLyaocU~*rje) z0RS=4_pi@jAjpzPdblfR_byU+7Hwn4Ncl_!89XZEZoQOJ0--OM7I6V$&)8T2-E50%qO2kfn)qm(u_*fn?n7T z)rm9)_^2Rv<0JWubozod73iu5Z`C{xi=t7;YwKne+^1?}zRWb#pG#t|mx3;>8V-3pVea3hwYSqLN3>A=jFq3j_$m}r@+w3@694_px(qPL}*mWJi zv)N2Un4GO$319d(|HrPi`q)Q5mg6bh4lKDa&7a6@tFG%paMpKb?z@z;LL#NE*pL8> za$+)>s34_2iRWSY(pUcKHM{70-~Ddw{SjmAy1@q$**43+6F^X|1X^9P_W!DIOi7;g znspl&&Pa;*6t@k)_ru+|V+_Ep&oRh1#X-wK5#7UCVr?70dYxYLn(_)$8H2#^YGfi( zs;)6MJdL~bk9)^x&d#t>G|LX8pTj|B+yvj_cKZnh6?*qgZy;)^l-m#A{pgX0Ugd%h ze&C~o5F-UUYtY7c_ajeC*>Nd*zi^4CC0h@1g?-4j6EG^5n^`>m+Fm(H3cp z@oV>f`NJQ&r;v+h7|2lR(bO%j?0Hod2kBsKFM`OHs%^1=Csk2ZbN_N^Ci~c@oN_A? z|JfJ+biFwS#}s+8v9U2}nyt;Priqr+nK=+!SUVnhi~;*kfB@|KkN(5AUwPG4RySiz z?7QCfZ%NX&%QI)s5-6oaOik0MYS(t=4U-RE+?MY9{?w^cUEeJiO8|z&00<#+4CZFS z9E>w1B~g({GkN9sD;9&G8KrI87DUllA>4!4Wm<@w`c%AmV~kp+I+1zY5OD3aZ@K=4 z>u0lB3_(Qai}~Y6AAjM6AAu+(dH4~^F0p&CL+P;lqcCaQWqLs^!(nn2sY^%)%H&_pFuI z79Et8q(LjH_5xL1gJY;5DYk#@3dgW#*fBTe0gfr+=Rz<#){ykq0YJQV82~172RDyo zz-mXALpIbN@8e6x(OaXs!~JFCjmqs>gI{m*g}Y*P=<}5$&Yk&u`N}J=eDAy8`R;d~ z+1}n}^MNb0Yw8E~cCK5ckshoR1&kjZ@Vqd#E}nRtID{Aii0`^1^nLGn`cMWtF@+GD z0@k!$r_dK(cs^zN_Ka7oBIz+sF24BS=EkO7BS}0nvH4UK%GDvKi6QAJWujRk3LNXB zp<)%g+;$}0RvZ_2rQk|=T(sPusey6i$WQ}a%Wo|ymB0hdkgMTYYQ$v3U%Btg>oei^ zZu>9RCdXhfe(P6>m?zCN#xR{uLx@G=H5Zsdr$R)riI-e_$-aI2F1qNVU;o*?$aW|h zNF<`}pHCwhqB+CM&=0QJ6rL1yeulC@%to>UdntLc3yh$db;a?NjAW7XUr5*Y_C5>A z6z5?X7-3Yk4%h@>fn|N)CrM0X*_SlG-B2*frj%_ls=8b(=8Hu(@-=Yq*=iW2!W^2) z)KchAkKU=G&iI~Br($RfrQpC8^~ag)pP0M0O(|{C^SS2qrpw+$MEm#e-@9)whp;i5 zIXp?bk%0c9keB+AHnwGmtG`hGDA1hk3tAim@|8qw+aAB?JIq`HPBBPG)3@su(C}cC z=h5)X3Lb-D!&nn;29pI-e4IX3oWvx zI(N|lnkm_cT*B|{?5OHuvG~bPe%kl_%P+qy;*QvshU|CV_E)NEpqHp};K-p*A}N_( zU$de907qIKmJPU6A@xFnKV(11y3=Z z&Ze^o47ITwN2182w^jo#l1DY$P#|(YNBh!IBtwYCl1g(bD|3lqqhK>-ySmZ6Byw+* z8$BjZhlJK;QxUD$Vc?f#@|j^EsqQ6!LBBu6FEO(cfcL%kmPs=q;t)c^VKW-Xih$kV z37#l)$b}JOeBp%`KK1cWX(4N^?8l*w}uQBg_6 z+=PZe5Va(rW(qY-0EDEF+d=e;Ij!JlKJgh5S$19180DL6Y;0_8ZJjxDcClE-H~|Ps zF+^4T@t=R8bj3sWKXms8ooe^fzxElU*p#H&_c6v8SXG#*ob5AnpHk|3k$y6nST-4| zs4;Tp_9!CK>!gVaydK!)$!|Z&*)gwlBN1Ut8e%W1_4~0(XLHJ2%rE4xQL!h|5S>f; zAjnbtvP_K~ibi!?$8$70VfvOiLd4l}W|YkyMUa;{Lv{+Gb#v;^wV3umL8(X}S1L0W zo#WOI2R!R`!h3Ih-vu7|_oAHJIbHwx_P4)_h^N!3h0&#y`aS*D)`U6Crc(gh+vm=l zJ@cKXUz_da$3HnXolcvkx$f=nXxmm*Uwq+5<=2NFd9Zvwd*cojY^+ZILg@NL-T@V5>?ccW_zsi&R(F_=^c%qbyB>U)VC!6ZrS$>!6uf8V}ChYlUQ_~OaLgD;+X^2u*~>)Tz| zS-}61qW~$R#Q0kusNP4sp*b%X-qIrA(0KfHH ze&-*39+iG({|-~4T5(ho!lcnQM1$jD19y}q{JWuWS!Y=r*abf`Oo9CpS4;PtERRsQe{BCwppbf3=Rx&d{pW4@ZGO! zmHoxUhKQ*`L{6PLStGpg5%RH~Oq!eD_rCYO_vRBPPpZhD{K=naB85s)qTcpzW|ou| zDk?geOqxj(gSpVfu3MTByScgPiFF};-@o_fvmvA>zdcc;2OjLYzJ1SoT4p0VNXzBo zz<~qAN{kqrl+w<8+4ucyW5&$6vK3AK;AseeX48<8o;h=NI-6S7uqI64co30lQVASl z;N^0ms-_nht4-H+Z7<9edBQPBpPHtbOs9R{6Vyl{i73P%RhW{)7`gitzz`x-3>>F) zx$Urxy#@}CJk|j6=p${Jm4^=#m;#duL{rMf5?R`cl;i@UyG$qoIYmOAM6qdR8%+#x zI++$n82iZtX--e8lgT7D@!D&zJ#f(hgD1@0!<>*s#Mix#;~JgQO5Zgz>YAPImE!kZP!83b=`b1@B5wr4=FNZjfP&f{7@X2KuMB{o65#|JQMczf-voitzfObQ-Su z001BWNkli!)I*5MXi>9)Vyh}4!y{${1wxsm>v@@}`awFzL)o;{aba!KF!Cr_RF z;d9R|7K^UylDKwcYmmr;nBr^}MR(>4@dRd>ch*o05wq<$1XY3LOt^}a1R@rc>O3hT z$Y?vklXP2TknR4yajHTg@cJ8)({-)!f~l%VYPzw;-9 zkSTAIB072UHB^%u>*=QnM?rKK4GmZ)TF4$ zP0B;+jVgrj<*$8dy{doq$A59nHCGKZ!_X`ZQ|Z;xfv-pTTPyr}A5yt;jDU#>$8q_$ ztH%cb;Km!Sf8#a$dtL6h(`Q}1QtDwU&_h{4sK#;KTwfhuWsny8p#&F z8=Yivd8<3e;Fv3}yoy6$<`^5xK*&}dxgbhSq+O%P#(2G$`!GYyG})9xm=ov6A`n+i0SI9ul`^D;D279 zHn$zVg9A6QArOZUi75sZIeJuJ`Ih|{Ujf{4TVAk^K9Q<>1ye}^K{+>yYOPi>F)4CF zYnN%g5z{%0o`DQ_IFpE_Jwjy58!F_fml1v1&;XsP6OkG{ZJ+wC?{l3b#ISeI-tF!4 zUEeW9fS9>yqHUnl*=%!Tlq6Gd_sm9jCbCK1j7*rw1RyIWe!f07hq1a$xY{qO(4-2h#E_0<+#zq0ZD zTyh)m^B%lDs_zklRbj$&>#K&k^JO(0Q;KFPO&gd3eX1(6JD$`TeAP5gQR_JYii4Pp ziK};Mp6Nmtup{iC{(>g$ZV$Gdwtl#uz=aV5h?Dzr(e_PO8T%yxpZ%-?`uWdeu~=|L zn6)l)U$uU&S3dRBlXiRGOMWStkS$Er%t4EURLyQU0H7*QJn>BcTU%RQ*M<;JojTRF z=8vY92n_CU2MIt?*QnhAjU{QU9brzX?M=H}++Y{L>H z%@>PPr%uHX_Uzd!k{*3DojrT5>)N~SnuHMAcG-1K@mtcs8?gWZ+uPfH-(}5PiXw+W zR}9nXY-@9in9Xg){%8I%=Athu#2f>Qc>J|l$Jvq4PS1lv3B0+v5kg!n7tGYeSPQp7 z8!f)lLrn@EVY$^&FfV48Y?73SK=jC?>LZdjqr-=lIjT_sX7?ZS*;duR{>m5EXNGyl zWLSYY@N6=jOeW>VH{JSWlOY)`%(gD!!7G0AO>cVB=GNwPI@Rn#FRG;Oo!WPO+qRYf zQB^|-Ol(|NfFBYU24w*A#eBI~+E!&#weNe-D5#AyRi9-q>-w(iy1>EGxRkqWM2vs5 zIE?~E=q{2e)j5Rh9{~f5?6ONQxn%F&z5n*kW6VsT<#PGmzkcV*lPBRmk|tA$LqHCp z;+*hERf*l3l1-z?F;5Qv(cq#|azYi~M!T3f6uZU(idE9)*4AV)dDqp_G)>bqn_HVy z;M+0AV7qvM8pm?r0%GuWumt$cV{Cem^A{4H{y!OLdrGy9JBISHf6=K1TIKSP3+nm9 zRxWoM>3SHZsKY#w%v18lkwojZq`MYoXB0v^*3$^4~8Ez_m+4-Q{4noXp%xS0dh9(xD zK(G_67^0{^w3o_*RRIVGLoj`E8~gi-6US{kDc266d3h>^5cllavaJN!nUMo$nwp_! zToWNOZyHfssvda2&gnY!$f_V(F}FTPj_ z=gx1(7zN54Q%Ya_@?Vy_zVXn*W-^uRNWb=p&x8=P>+H~eI-OF^%+hsT->1IoDKl

vxMogGRc+h$gLi%8{%_n1;FBNwwcq%S-+1d=-}0t6Uw#caYR8d?h}APg z#mM$yd}O*>UXQMC!|_H_Apidbz)kOdkA2{rUZ*mlS3W2aEDUYsf_fYas!}eSr+E$M z>6%Wr7(#(mLI^3DN+k8YoP*aKO(PWgMrK~jm&~M+YSY3rG*p3pL`p$iELM4ennx?t+*4stoo8LTA z-em+jcis5`5eb26#u-($$U!ScFO}Mki9?908bU)v3vRovs|91jfkK>wxLC9)C9(jS z5LoF)Kl;(GGjso*ePl2?(PPGRU=2e6=#JY>uS$M^Ub1(KCZv?0sv#PMjXORNv`bwP z-DSh;(Hj}6QT>|&M-<2oY>8B)Z!O4~?8s5FlGFFSy0Mm1 zgrJfDESJj=!sgcId}qE~EGLs`;FynwK}7Go{vB6ddF7km{AN?L&z{>p{_^pMAAWc- zpC=LN_0dO@)e)e(?m&!9lFst-643X(Y4L$Mi6;lK$w`?Ef{0WkGDBG;Q(zJi(Pfui z@{V`BN$Wj6~Hg#2&FtkD#c^H3>$>Ha!DDCvoFij2DJTE<8kuq zN3AG_T4Rn$8eU<`*t{XSu04PLd@aq^tNxl=@KaAcb$(22Hy96VLZB+c2}IX*Pe1*% zr9wCMqM|ks4We6}Nt9}l_#3|g0KfHH{NDHWM3_!zF~;-fcVVg;tRvM5&@0~zz*c$w zgB+vFTHAl*gd63I-5bcPAs|Ud z2!R3-oBIk8J179>r&R%QBbEssq@;l-6_RcNk65+~;{hciJAQLP>_7|wtX*fxwqZ!R z2$ z@(ayQ5v4#e#Mx{kgmA@eUp287I3I1&u&csVh_t!6xp&{*^E>Bv7V{8-u{|4ukJYK| z+Vk7zZ8Cdr+fq;zL=fJd}vYxMNiHo(GzP2M@mW+G|0S@NZ4u@uibbe(3w(|NiOI$3Y~SuiEM$ z`6!n|5JQmwbMrJC)ix=p_7w!3bv0wvASg83fg&<#8Y0Z(`Cbz_6qRnc{`!>qOD?@= zI-Q2HfmUl)ZA$0t*II~9s@41&xWH?bA!G0u-nkG8Q(ctN=mA_A%VIZ+ix?-Z{;F{W zZ&5AO)*y-MHTlX{tJdyU)`*jD^g~OBDwv;zr6Mj>89(T?@E|kP6+Z`2z)DrEKEChe zpH^Nrsu=t@Q*%W`#1KYeY9`Hr>4E(h?U$5Zc;Q7XzbGn<=qZo@D9EGvq<7mKws#Q` zXOr39#yN?kn;v~iNG#MVVh9MF+BU1-&ITM(B=a1}7&cThjyIaxnsp@mGo`+5+tf>p zacj?(q!a=-lZjvLdBoB8{bI4`Q_swkNi&;mn5>x3=Y8M%C>#7yxhkt|3ueVoNv%{u zMXj+pq^Jx-o(7sdqXZh5BRCcBsbOR~5*%gXZ%RRR$})u7k0krw|dHJbCgr zfBm;?oeCkw$V`3T6?3t4ciXmbn)<=otWlU^XNgE*&oxjjoEZM?fZ5*opMg9J)bWplS$Jwj~#Kd z>MLLR+OK}%qboh~=}-Q;YcxRI-sp?nn`zl_weDuQ~yZ7E*Ty_3lm4Ekl|2;$K zc6N5`)b7lgGw08rUt~w<$z)>iL>c{*l6fK7T1BOETdJwzJpmZbT2NsZ5ru=ziaHww z@?GnCuP@mZg?@~%a8`$is!t_nZFR9Bk~Yb?EQk8WTrpkwxBf7wKKc7BvZ=moWuH;s zt6ybb;cRc%bASvQ*A*ym%(zyA^PunVrfg|;Vx+NvP9iG#)Z0ycB`vL?-I||+z^w^9 z2ztU|zN0y`XWfiZ)%ngGz*X104IVDZ6oV<;3ZE(lCo2H9?2-&<;1GyJjHJav3xzHJ zI=NqN$#!Z@Q>ci3@4HU|xb5(r%>2ls58ZwD2MK7J=tMA8oTgW(sDg0rL(5Vt&Uz~V zBAXwgOq!Xf^nFTwZ^8cw`saW7C+mZH(Y{Yu&HV8k@4UkSmk@$vY6(?^IeHY20E`AM zFuQNMs&OJx@xZD=1r3W~CJ>Y9z6A?*LyAELVZbH=*_NgXAlQx|V$3q9PoG}4OB1kN zpNNoBzqz^5G_mjd*=%Z#P9a1S6ni%JnLE zddYU&2OezUnd1r2JMVzkr%xcSp_IA-n%$Q&4GNIIfe}&nJwTJm0q)rRiu4QH24G!Jxy+Uxw2k*QZ#AGHE}T^sCQmFWGu)ajvO)UQlQp9Syd%c z)vjF>Cun4=pcei_VQXtoFwlg8`H6%Wn1UKKAXaZBM`6GeT+g%GIm=5@>nW6`NFG|( z?>T!ebB3phoDRGYos>Zj9LPOVGIv!7reRvdY!S{x6bMB8;3MXf)gyIAqjKmFDDYRl zR^`*p<$wIoK54{Z$j&=<)~IR#kfR{*U9;@_t`DnQ(!Ryi%8B=Fy6Fd8W~BaLQ@hB1jQE*e4LqQvzd9{n3`mPW~%tmy=aFRr{jmV>{PWKPm`2arW$)K1mE=&z?Q`z1sEt|3sG< z9k_W=wrwlo=}ni*cGz~ZV((#;gnx4U*_6!ta`48e3p2+!nM@|;d(r$O=W$6pGSuMb`)4v~1k!Pxt{i)^F0iZ}{&YT(P=rr0JL`0+q2Bl3z4CWZCajWNwBc;Fk za=oip^yxwP8-n9DS}DVyRi6*eVsJGm6??zP<c^&*nJ~=zdA^~+i8Fg zjS!$E^O1d@L7ZCGmn_THUs8_QONh8%SLm77+Y2LKD-34}31|_xk|d(YZ~DhaS2gzz09@k*;f1H3Z5*Om6wt@En7QsPPoMECkDJm<;q%YEvsB z%#oXDtCTNnl@?Xw_S*w7QtB-mpj0%U&Z?U^_K}y5W_!%pXH`Ws#FD;50i^6d)%U%H zIE4_Cs8%9{n1gwbi!dW4A>y35mQ=+8_(j!Nt^!kxaj{&q?NU_DGD=A|H)odaYBFh5 z(f28YaQ^&xBAQO8#0_KKytc;LYVkkQ24 zaXUO*+6c=y)OcdC3{5Yv6`Mp9m^O{77Ng6Qflq$wlLs$8xPSk?WxG(-Y+AV9MMUP+ z_2iS^1}Mf*!tcAT&lx&wSM{MWhE7zbwNVQlKYskV=YBY!FZ#ZpOq$Csd(&(-J9+ZN z!GjmuJhXH2lq?d#k4*aBlfeTdl2Ymyi-m}W5JKS1&8@EMUV7;z1p@QM7a#n>7Zjk+ z{&rv@qbp*z6od}JY;A4%K~|r-uI;+UR2LIhUDq23l~QWkPDBccei3ORJu(xs%WWOo z|G>I4yjI+cW7xL3X{^JSsfa-)P=Q+VZZ$l1d=r;_uy#VFtdib*GmaiL`Q}xs1m^I# zoE>vq<294u0%aEkw?@Is=VCC`b;$Pm8r0>6>p;*(-W!?DpxWsyZ%&1zYlWl_Fp!Rc zutSI7etFQNM`4H+pydD{cf-gjruxQ0LRf`_lv$J7skc!U1ckDa*O}SWVMf?_~g6x*`51Z2skPYgQfDheElj-DbH@6A_3_Ip0J8aEK=M z%C3r>+bcU>jT>8lOVi;zqJvbyOw;LfHk-ZYx@P}HZ)M8bCX|@9NRnN~?TwdGtwIL6 zo1Qkpso}Z;9Io{*2R*f1_G)DnL#cGKY|d7pN$xz5|8mt0Nbh-iu~?28wEm{y|GV~? z9y@kyxg0&D#wm8`k1WIMUydDn$@~<8d#P7v9tDoEmJN$&1rDKfEHTk^Isx4dr`<<4Tl2)3OgwdN*L6?jw9x+iL$?9wPoCV>ZeK4q-0&VZv`HIo z3Q2?=af?Xm)AiTCTU9-5A~umcX2c3Jrb)ike{ZS07QiU08sz$4R!T%rdA<}FXyh-mR#ue1`g{AZt|0o^8iTpM za-d^ae`f6_MlL7S@_H0uT0YceP^4-gX1rU!rZzyCUC8RPYgagKr8)GniuWmSOw}`m z!!(eKH{N*jcfRv20QWy| z??*oTtE#$OE=9^+#Tu;EMQ(oaK=gjhkX9a9F5+d^Cf{;PUwr9_Qlx0CTh{p&s80l2 z_`^Vp)Y&V_fEvb|BkA1Suv21?2V_YS!x~h?f-ho>%jKezKExQBpzg#Zl0PQcCBx&%Wg?*PPuxd*A){n(O5ce(=NP zvhDkR|Gs_AWOCnqTL2r!>Zd*>FTeb=>2!AD_}R&1Vobp>{X^746}+O-cAbjE829hr zzjxn0W=<+G#3ZTfy6v;)rn4CnedViP1rV5bc6R2AoiZr<_wSp{HbP*cNYxOFrtR(R zW!q}bJ>-T?UicyKbUJmILbdPvzO(2ID$@J>&ivHrv*vyD(vN?NvZ4V%-Apw_C)+Is z)tFVO6(Cq>0#x-c|LXXBK}7V-Gqxf}%c{@`7-y%df@D6Q15nMO$3B^~#Ndb|&0L8l z^Gb&Aa&1-l;Y(mujK9w9xJcuC9=H3i1N5ew=;%>A{4gIn zG2Y^gLIK9Z;+`w`|I> zITgz8@?Jm{hYs0W=*SU0dQ<@%I%Jy&1D0@l@E03z6J&9Zecv$$Qiu{H*zBdifNA2U z-v{DEAd5ByU>HnrY9WGklOgGS2ZD&lWO9Y1_a@b|kM?9T384|uzV8$W3=3ki$tnrO zfr#LVIifKW1r7wuh9Xc344{)vMen#hKyAO^$Bynk@RT!*SU=jFtkoyVCZ$ivy#Lxg zW!ES=$qM%Yu$CmDAP!~Uw}meX(?!{yq698{BFIRPh=dr7KC`G^M3f|TeP`o)Twa-N zY&1>Nw#&_p4FJooWzWvTML#6a)mLA2;NZcH%?$%e+Qss@XMb?|^l2ipr~sRg(W&tP zqP{a%JAtb-HsK5Krr9515HiIj)@GDhvLS@GzvCST4_vghXU``6$d-uhan7g$r{KAe z4*AB)tBbN>xsAV}oRP|r6JKsC7nIH!Kgyrgb=`>*Cyaa9f5^IZ-Ak2@SAFm!0zJF& z>@&|iQ=4+@Zax?Ad?{x?dHSt(=I;1Z!BO1rrIOVqN%~zhWWR|BH6K`ot_(HoJg@GM zSIlOw;dDT~&Q^=h3OBE;50O*3V{I3xpD{cc**XINk2cLcU#`qa%1lh;EOs77&BHj> zT~K+oU^p;C83IRJvTk4P)Fyl+C!q(RAWt4&7``imB@f4FlQrKAS6@5}gbg7GWEmMn z&8waT!sgDH)1~=}TGJvMmW*SN11lbN1RiOJ&U2^5&s znS8ky5$AfyLY_D_!Ojj15Es!Hf-26OJ~P|g*t+b}UosrS%sFwA6h^qxL8^T(kzkZy z+(hHxOqrw>Zc!_%w&JcdU;Fykc75f0-+QQ7U(C#HyK=!h-+7~Hmds3T|L%9c4<-Ld z@}t_otfDFP#Qgl<{_qX8`7PI6>oyw&KD$jI3Q*N|zVmvFwL>ET5h?1XaNpa#?v~p3 zr7cA>>+L)_fe4h^1ospbRU&k%M6_7Unb{)3O1Jw50;_q(x{EbsLQs2t>705?20)6W zBWMg6SScUs?@>V;v{9Ts=I~{ znu|3Kt4XXzFiL*D8xj{#AO=q88VlRC4^5BsePF~`L7oh66tIbvor{QEO;z^uy{byS zE10$}E~}Y?by~@2uBw`Zh_c&O&SOHpQ{`tWfW7RwmOX!&jtG29gf*EhigP?VVVW0~0}c@V2pO#Y$c3rQ(gZ zlPAh_jD6RGXwTlgCr_SCeG-vA_51eiBWM%jEbcjX?krMDNr<`cyVy)lpF2xH-zR3M zb9)jIYm%hNk3ivc$X(Y?CKHQTl$=$HGfrp8HHi3|-#QsWoHSD+;=oA-qK`b>1Lr_= z@)U^Z(5KFLy;PJC|roP|-8g|4pS zDu_;>J_nr3){`l*#e%i|H7m>9GhCplYD&_!eW`=pYXIV|&Th66YQIQSg2l6G7QCYp zHVVms(XPbXu6yX#G6`1e3=dN)Hl9e8*tl#Tr4FSoRjr0^ioRRf6c@5mhIL*2Id0GD z4J27wS1O}=pN|zs_v#z^mdL>lyM8w>6;)L+ADM4_1BVU`gH>tqwALq@h8SKRiSBHUi6kErHy0?!N944o*{&&jPh}@^uAqWS@Ru8J zs(R=!LG|cSGEfGPn{Fz0yV1uEv}@|nIZ5hNEp@R46Dbr41gVZXKuT4But!=2076bt zYSpFeXy!p_6o|=HFr@@LWFmzG(IlypMOd~(n9XJ}1VEQ<2hpa9R-Z)4cxM6hDFNuU z3v3F2I;x_+_yt12j%hvQ^N!o`#a)s&xRd~(CSwUTXj}JElH@@{_4Fw-gmOHo4hC7R z#MUqkGc&PeBPr{ha}JH-h6spF+zdvzlbWVUDKTr; zCn9QM3@jl0_IKWN?OWg4G?A_Z2z{S^{L`NvKYsk|nX{@&%t=H=sNyGvA9^Qm?O;S_ zwJH3Ingz5x%yWwI&AGiGuxV){u3M9es6ur=q%7my1Q)c75O5!Av<= zssLCir>)7)EnK*$2)=9BbjtD|&p#c+nC7WdO>f(YQ0`h2-x+IIErhb1-4~=l8;+XU z5R7j(Suvnaxei#lvTQ#9bcmFwwi{ZzZuqurk?W0F*|v6X*NQ+LKceiemA1V0KpoI? zs_HX*wtr7vqN7Hk7+vL&<#pvQl5e)ysi)zw`4#0&DYZt?MMRbg(oMt6TehN8*3Z!jL@3>e z%2+b$V#+{IT>&l7X?|4Q1NG6wp!2G7&QwxspY`p!ThRN;pS3={GLAWtWkef96$DUK zvb@ndL_{=+s^ol^Zq1MMhN>+q70}|InrpHS$J9+zrDDL>U#_^i)V)-SK`mL69)xV& zSj~dGbajbb*tI_SCt2%ZMm5`4dcK}HnsJQ_n=!l401pcN>pSP6?8+pX@<11h!fhL* zl=(r*7L_;55r#!MD8ssaw7v>EW!4P5&MUZ^szUYL*)y+I@%cHNeXVQ$pD6FV{@u*{ zz3+Vc>-XOW;KLuf$NNMz^@)g5@HUbd6E0G6DOyBsi4!Kz4225-Xh3$Yx5LadEF9lZ zRlz_A9{ie5LtRj5`P)uk0RZN#RPt^tmkVO<`@ZY@Gw05k&0z7U=NAhCcIJz|?+i4- z5R~d+Tp?P`EWweola2T&&*wWt)V6($-1oKxjPT#S?@I_w2n0YyyS8<;GvLUPtWv1l z^1h;-1cx37s@k@#9dX;{ZM+Pkz8_V`P}xgAt8fNgqgLaLg? zcO{IGWfKA3BHQu?N)g*+2a#BNh)8uHpTDmZ|J`<+l|M86O?f8gm+m6g{H{uCtpwfh z?0T;RGJcuWLUq-))N`x}tX1;pQ9X313|x))m)q8#8NW5m#v%tWx&*M z?g1i@K#-WQGoMctQt=wN_x5#p8!7@9eZU1CrcX+y><sfU3fAH-~=9Bp|-~XPa>+bsQ z<)6JGDa|%EVvN)2)VLsh1BzB3eV(>yh)rwQn=w&8tswR)kqx`;%*kJY7@z9P(4#Rglf6a+m!pRa)zE z<;wHxYu15AtvEPPK|I4AIToiyH9&9CYLpbb_Ge|}+lmm@s6%eR?8E#LZ()f_)T^W4Tds?-iG#`d=D@Cgsnh38GxZ_Z5w~-s9Ky%0d`67#npB^Dk1*tK5*f4g?G} zEDu?!ZKn7^IkqjYa>;BwG=r_fIY2?`M*D9ZY}%|e(C0was5J*DZ#op0Tzc8@S6;?1 zy4-%}2kOypnr4{E=7JZ3suX!bM0@t^5wTdLR7`7IUjX%ee`?RE`Fwu;4e$HjcfSeX zzOR4v?z=z4%q-e)NYJ)zU5X|_0+9u{Knt%*2u5cPprD6!@6|;G328K4**rfL0B5%& zRi~rRn6;*4FuJLjlvD_mG>K?8?h)ol4Ocs046GP_@qc@+`a>mf%&S!0}%QW zEaRuPYVM|zq$}gEimq$B&MkaHDkhVunX+ZOvG$pwkdOd8{y2!JYw6G-09vAviIAiN zeA9L*tpLH(ZLCc*uc39R+TpyGE3@k7>s?7TW%GW#z1K1UYm#K;r}8duS*Zz;IiC%; zoA$BdMNuinD~(!dT^8N`nkSA@+v(xMy9gXA4p|xMQB|`1XU^rY0;7*^FE6TpU2X5! z{iNP#>=vXl?V@igC2j}DiaPJ_DG^UKmZV9R3Wen4FK+UnxE$Sxgx}9 zij434CMggA5D)oWDKD3*YXC(vX*6qAlgT8;*tV@CcgeA{x|9+DlV&oRPMR1?AElHC zgpiX%tG`af!$^zNl_ca-BigIw0^{aXH69I`#mVZnj$8#BD6)&S2#$gdXvSjPBNBN~ zt@Dhao$TDW@A??y#>Q+jv*)(%qOOa@5}>nZ&#K4R`e|!c0u4BpuIsUR8G%9wOw{#V z6Qgl-ne#spvGM4uDv(kVefod9Ntr{A&}9+T8;9UrW;U+}F>}f=<)` z^wJs5r{OrcKG1anR0p(F;hq*Y(G-KfThV(f(XlFU#)4%e2Wpjum21Up-TfTCa7MDL ze8_ef#JC;TM9PXhEK4#!(7w~#@B>sU6eeeNm`$oe<7h`6&C2p3U6=4HHL{jn_^0yO zJ!p25ytNKrelKlA(JFPI8!r7Y017p-P_^Ae_bQN-#m%cVVAmGeSiM?@crtj^ni*}k zCsh?JEiDhJ>gHWgE+1_XRQ>^mlLxE8@De35Aj$Oz9lf1QiCXIt+SP{?Y=rK}I4&}! z@5*VSp~EEN+`Ote>8HmY`KVD2nRYZho7)AIP?aoRX}F!WiIJF9kwi#x>Q6uio_Xu( zLW^95E89^qDb#&+vfH8WkZjJXzf?FT#-{5!qhB$orPsk;Wex!K+OJR;hzJN@y?019 z^qzOWH>H$B047zB&(9YZ{nDOOL~6}f;#)o=Bg?S+irXP)Q8l>RU}dzaL>P%kN^0JQ zP%?k2BE0O3rM$P8VWozH=7(TdT@6C5IIz?$UC|m>el7JxMob1>P=Sg*b7cdl1a}1} zR4}Pz;G({(9yO|Z&%PgNyF91q@h}S#|+yo>gSX% zSCn1DeEWmP&357+9Ol?`&VlL-o)femS8+n^G9!wGpk z7Gnc!)bK%fP%-&R%qLE~@`g_(kwd^R%~iyPxM|!rsRiliC5HVAh{=u|$%ioyhr-Fs1Y#MlFmTbOBp~Yhers#C zy}f;YXKvg3e7PtCQ2=OF4I!8d2F4B@Wj30!ZgW>uGccq{l$j)H0S$8t%sUJy&M&H} zI-k#d^IHw^?I?VjTW`5 z`k7cwD;m7AU9PId)rWG8zcu62k~OXM!>9VFvVM4dg;YYUUe5k=)h$PlqU`~o>*{04 z(JPtB@`u5-NWlI2tQ#x&4;?MwvDU7tD~-|032QgiwLY1sMK@51?(*=uC&-Q9A&gNK z3aMSs6|j*jx0vJQ6!{aGj0?B zq?FOr@mp5E8S0zrN9T>(P4fbS4wqMp#J%V+hP(D)N(+UDG0SJcJ~XK_xJ|C+k;X^}Nl$ zC!)e2tE#n&moF?ZG7p0>>1M^KwAasRTwo~~)q<}VNb;wql#=~nXEMy(wddz^I(0hh z(V~(AuZCWNXLp5CQpNwx-kSwknq22$-^u)MRrNOAgYLmX>^leu0tQ_(7!dS;6oMdS zG8hcWdaxaiFyG8zgu)LDTbt!DCEIjZVOviQhvg@mqAb}GB}-gDL!>BRfSIl)K$DCB zXmG>K00T@<_n^0`y7$jKemHqfp3MAjbo)dsIZ>A{0@KJiihDy5QhTq8#7gw2|nKnUXhLYa#54wV*U z6L8`h3(R3oA_A+vFm-s4Nhq!Q%~k~>myJ$b@*aYK88AmM+ghZ$`<6XoZN+=FD8?-R zuXI8GH<~wA%t=jC+8H6K7oLY!Qw`RXiSJMHI~m0V!>iOg+|67OtUYgeaCy|J)X^40 z67@uAH6f<8P7Oik+A@w8ZfRR(N6>R@2in)MUTW_)K|kN+qDRVAvl&^l9Tg_Mj3i&V z?TDcm+d{$*!|-6B?qTVu;C)4cyif@!Ss~;VmJ?LvA_wzaGL?{=9Mto`x*I^6W~&jj zxg8-ng^GG76*F*FnMD@6L^7Zd)YyheZLWR$s$V13wNp~fDFs!BgaUCH&3aBiI^Jvo z(KN+L@U~oyh)uLuNek!9%#0Zsxgdq0t7CH$;hKy1h&V+s|5xvN8~)&{_zsl9<)@Tm zoWy`cuM`aFe^Ud*dc9_|Q79VI98`<)=+O5s5AL? z+P4mj3xX4kV_x9Z3@olS?tVqPK(g;rYW%Zw;h>bSio2s!P**`J*r`$CX~Wuy6J1{+YQA^#vhlPVqqsu7@WS&Wi2k)GU-`;!zvsOl_`kpMI{==1>WLry(LZPJ;@UIOB(aJjMP(owp@Nwu&(3PK^7-I=i6PGO9Ab!?q&YaYPogB4XJu(tBQpsb zC-Khj-o2f3N}20!QiSHwmpz1PDk11A%Z+Yk z`ieB7DR}KELsA8!UcZl-MJui@k+2&jkxi!@@QR`I%11sk7+mxSW+K7OZ3MT;k93vA z5oT1Qw~JREHTcTvFtbJ(SkSMwXknyB&19+GX8CvP=p-?&w-0H%Fb05NH?%a?v8s!j zl;z?OxZmnzokBN{U%0OQmY`U*#qLT6HU*$Q@iQu<#}hBE8_nxP{94pqTxmg9r$tN>&*@22^s$z-MuiQi^mLM!e6%$++U=0ss$JCBh z&MAbLY8-bT85dc%Xo>uhh=^jG9(dpZ!tJ|v?}(B*GZ!0~i2~>1NI^uPTs)Fw$qH*( zPf*TriZZDhjJ7YmmpZd5MAS?pklzN%en8xd7)pi9+(8WN?CjpXdq+Zn7*W@FBH0oo zr8yhC%F1f`0%mRym#H8!m^r0cex0U>898&xGofUhSglr@d5$3@=92lvMz1KTMDHq* z2OAu#i;K*us6_(QK`bX#xO=bCpo*KK!g8LcIyarD1QZhsCa3$eYGrt->M)&3M42~t z*zCoi44tZAm|X>i#4tq-#;n-2v36i&FYXHJuwy`A&IFCa?X)>Oq>yIUjX_oH=1dcW z1!Q8}SADrV;^UM1!-#H@jUx;@tX}?gpP^EPf3fM;y;Ti8v_{jl6Ab|eua>*-uU$)w z5r_7wj-U>&V(y@6dPI_*B19q1i@8PbhU2M@p-k$2@icIXcS34I^lJ zE4+jwSmgeeT_RsB5jBx$;fpekCEO7Mgv=#(3Q3f1%{nc}RnuGNT&7MyhQtoi^98|# zArL^wV9K1=>x|WE3R4In+lplIvn^KwAq2``BGozvl0oZP4JtYn9Ftk?WWFOs6J2jM zF-9uUhXH`5m>{=yOtI+4{*PZMNuWRV$sgL=+l#C4{`Y-QW}8yVglUEbThYL@8X*j3 zshWdMx#8yYOJ-)`P?RnSEP6F!XwViT{AM*5Vhn`~EvApfBF5=d{fjEJR|_Cd6rtR? zi5wvWLRDLIr>M#eTu!Ie1R_vfiwR(!vtF7N`dx(qgN5o^m1)ac+>{pIQphc71ROL< z3oUENqQ_AUk(;C*qabV$bJk3;Cel=?FDkQJCZ2QgaB0rCfZCx+|6HbaKlone%LH)n zJbI6^TEbPBA=*u{BhbU1B&vpG2ysaHO6p15MPr%Q}QGq6qId zK|~e+XbL6SGZ7=uv|6nwzU7_o4ix|Jt6%;n|KuOa%ir^{kB1Ou&M}6R=Hugaxj+cT zXOrx@jABZ8y*}O&I}Mqk`CCgSolGUw2s5Xg2oxd_OLVX#ivQic-D}sb?d_eub^De= zOt3{`a%K1!#DTzBxu+VX-|!Dz1yrK;S9pTl{_aAR=qu@r7siKGjPsTjMDY8<+kQ4 zTGNSS)wQt>V=LQ2F6~PZIh+ot$N6=`Fe}pq$#Lt>1yR|7IRFroM$;IDpouVAOhE+d z-M|(HT%4B)_{c~2-~dGQ)KiVmmss%{Ovvf_-7FMtIwyC}zBudBwmzZuC+ngzrYhl9 zr>xScG1?XIq-53}=Ms&Pt3xiE^xW;Wx)q!Rh;s9r(o6)->E_KF0G&E@`u*R%6Jj8u zg9Cj2iPEV=|84QN?|^lj!gW|oeI?dJ-pYdDNjz0yR&OTiadw{O0gb`w*|Vn^`1b8v zlsKn!e0==iYaTp2Jlfmc36VJG z?>ZRbChRn&oWQ9F=XRBubC^PAKDD>^)p#TG?Qo$U3Na;->v7SDGjmXr8x(|5@U^{w z!Wpvrxj^;7=L;W4M5xhLC}jrooQ`GT;-pSSIg5+U$EV)|Fe~L0RHHkm?qRacE2`rR zKPr`fD+HajT@^CHCAe&3Z(=7vS`vmQ=VpD%PEujjj@5YbpzVN4JWYL9aTuGSjr`9J zz6I-TG(HSA<3V;mRkXoEH>xyf(5NS~<=Az~`}hjL8ac+(2v+oOUG(!D5I)yl87)N6 zzTW-hOM~uo0A)VbtZsZ=!P*Bq9fG{r@M|MRQDH)q2)$U*Qo>=Z%@cN5w}S(#8o6ty zVjvrg_1IM=O`@~}Jr-E#?)Fpw<11YE81x#+22mPdqqzVa_3D7b%zx|M?|AJ$->t_` z#YST!f=W^bMq85AYNBFYkx0xERgDh#l_G5fZ6l5F8)FPXLWcKwRHWJUdj0Rc>B~9i z4r6dxupedgDyN7A2q|A*2u&j{bl%xSZcQ3ilDK_2UB0riGT_0A@X#F%Xj;7?x|S+V;sz#g8&7_h z5rsw|Z*=AgNfImK#Ix~xf*tGzo>_zAso+fPCDO1i;x_|<(Q3y^K4S?#&>Z3y1f{XwJ>8c-x=0I5AY9xMPj zn;A%nQp8MR+0C5S>$L^so~E7d0J^Dc6$5ShsOa0DTnkjO(1;D2h?vv!&wulTUb^y@ zH@`iEkU2m7wLf^`^PdCo(T{#C=a6#_foK9VXKZr9oHwhuqXWp=-SUh!n@ub!sdGjS zRHCNIIEDH^!niO}POH`KG)-}$&3c~a+YmfYh-GirIo3KF#Lqv~hHOaXzx zgnaoj5s5Q!F+fYnC`AAgIY7g@fi;++37JXsu|Q%9VlCox|*6 z8>@(73WF^70UpWN$EtQe2}$&uN(5Tgy?gmGB(bfKSO5SZ07*naRC$o22(lL{&CQuZ z=n>u6tB=vXZA?}NJ+uuSWn=l74T+JCTyl;M`udU^ECY3mQm&fx?5r<}C}3}Hp+W`f zO4iM+@A&vQXs9g##nHii@L3JU-C>t*` z0s=E{Hp%D9^Cg6sQ;MPH?#v|$rp%ydC%aI3MMtcn!?zyXW1;E~U#}^UEpvD6w;+X9om0BIig>|yU z+e|zs2Z$gVKyT zSOswJW=Q%wvpWn0=xx?>!Qr-=fP1Np`PZ?iY-?xjm~1>YvyhwZZJJq`eBc6bw3$*i*jU&XrK=}aG~ts{)q=Ul)I~RcG3QV?GFZY z?7*$>x(&qaYq3saVg98#+vp4~X$!>LPoG$66+D&OxSt*laex{<&Y5&ma82hf_+-S$)Ys zq+xj4LktDFS$U{XS5!RS*4^rpn&@j%i9U!OyCM%{{lxuMnD1-X?h*C#p-Y#nJt!ws z=!1&ECo^ks`-s{pjMYkI7xPt$#w;YW@$vN?CjlEI!0e(CRRAigVD6TnAGU7r!rR%z zS?y*CV6%|&+9ltsB0Qx`RR(WfaovwGEUOknpVxQUqzm(fUe-r0vam)kfhs@4;?07I zal-m`i>QdB&c0`A+qKK7@Ly)9*S+F7Z?;B z`N}p_W}c>HbCqr7YtQ__o8R=75W-vD`nIqA(H{bM^2yIX_R)`r5L24v!aq(EQAXy? zW+M@T?VN3k9W%v90R({t!(ubJ*v|~&oR5x=kB*OXdePMAm}jMyVmBs>xu`7jOiAPT zQ&zI5(FOmg#~g9yG%gJqH9ASaUvnEaZurW9j-Ro=4-vGjVwIB(LlSv4dRw!S5$Gi>XP+qsmBB3k5|md> zt`0F5+p~)Q>>leye7DhCX{D0o~l)SvNyZiLsZOJW)Kqz(?Y7H?Q zUNa)ASRQinsqSsJu+?TnQJ)-nX1s98PB8_I)no{Y9HD1}y!Pe>M)t(9gmtBA8#*aA zM-q**r58hup^3_@ijP(NW}iOX_O&qPhFG}XdN}=$i^750xM_&wCGX}T=-C~TGC1kT zOk*rksHs4F`_3%LwbGRq1r&Ti?OCkjs-KNoDWz~cSOEkZj^UH+zPJ9eSgq5W_!*7- zTBYnwn=~|Dca+k!zVZ6N*v`IAZFWhRYk;pC6=(vf5tWMyH$68$`zq>ke>vpALM8oC z--svaP{OTStC=LX|3a6Nyrb&U%JrH}Heyjo+H>D`6heH%ubrxLsdZZK*jgIxKzo+02{G8lar{c)gAx?(Xd#9~}h>Vu25Y zqKlEMyY8HcK$1aI2p~~1#3^Dqc)%+yO=cx7A$0(-H-`c6{`Y+_gL&S_RfEvQ;)+t5 z@a=e#5L6J7N-UFl&Yqt2J0>5nP;DV<#Xs6lEp4Tg6#E$wb&XzXcHaj4tSu9=#isYJ9c#G^;b z4WqrF!YH$IEPLH81<`tR=&yk6$ZkuD>2E%TVzu&(3;^OSiKX74Dv9-8qI}nMR9y3IetQgpju-A^4^U0h$OFRlu znWv^-Gv^6VlisGm;bir{_q>=1MfSwyld5sGnP)D6SgW=9SjKIkS-FcMsWC?)qN0G7 zxhFHMKnrszA;6Mf`tr!-$KaB$$%&3JZZ?}MSHJM|GhdTxZ+g=knfdF_e*Ftieomfz z&ts1hQBEmPWa3!D4&;>V;&d7PYk(C_nN9XfIfME1>C=0Ad*68OxjT37WOb~|c5do= zwHI!B>dm22A2KJ^(}fI(!ApZA)2yt1v$$n7Jtek=v-q>OIzO3;~(scN^q%AAfnU1l6BSEH;+@u@7adsE?qys*36kio-etF@@Z^1e7zTN+k?~ z1Qc&?!|DnFuS8ZYf%DjP8k`PEc6gihVvULuwC)db)vPZ$LFIl@#~DJk2D9PGW_b8v z930@Or?$rQy?>QD90lxn`gTV8)lXhFApi}op__>ok-vPm6IoAdRcJ1DGc=*N0(KbO zF&7RG)(=ujIc3fih!_Ow$AgXQmKiKoAqR zTyg`+c@Kf|7HKx+Bt4t26@_5r4<%v(m^p1y<{Uzt;`HL{>H78SL`OU;u$5nP5mY=j zDRLuf{*=NT2)J!E#ZE+#HAG7#YWiFmQd@ckN@{Ks!N|FCFA22;<>+Gh1sb`d!X6S- z!wYoDd#jYL@B{m%N_uj(V?aLGY6WkD?ig8pT3HoM&URsG#4zPh8AljqHC zvwv5AbAe{ahEa!yR)M@wdKhleM4`$C1Px_p{oWVB;Y^}dLyIHs{bIXG%4oEm&g9`! zKk$Q}{*_;r&!VPz!yDeX*=*Rw@i9V8x~2v$KNI1OwlRV>x?0zyzCp0`_60hrp%q6B zL=ACIFp-nM%Pf}CNp`#4GO2|SQrg70M?}oYA1~GNHJQ;+a%~9D9n3dGpMxb*qe8M45a`g*V^|6nBukiP))oQh~`sAPafy1N25aMS)`!Ak( z_E`WRyz#r<1mNq>KJ&yEejUK$|Hk(-vzaC4tZ4Q`p^m}KWYC*aN;yAp?p%oR_kREP zQ%cmP_TbE890rLTvHuD+Jhti`k13*X(>og zr^a$mEZQQ0@^1x^`w?EXxFrY)044F2Te}y6Qi+9o@xHRpRPJbg<2P{ma%C&W33j{G z+V@a$v~s)UT|4Lo@3)$CB65?J-B`!Kh3TP=uFF9B&U%Dj82l=^s1Q~6vmS82otT-B zawhRo@oiqdjDv&n`QRz;)LYef=zVTYhInVRFndbu7>i~!~O0GKA*2U`}=6+D*L{%K`B&MvGW5PS)wUYK=5*wk@P0 zaRFFiZb)BgI)W~ijjWzUb`w-+d&!skF=+*h>0zjh?Y}lUf&QrDW8YG#-Adc`NtT&v z8*Y6~POk8;6L;OVg_j;uR{;xncL0pM$;>PXcvSVFa=ULu4VB7L5+wGSHo7pBdd&OL z_C`RS^BgO06&%=JCZejx;e|R|TCl_G_<^EOIcZ4##4B(NFI$Is>(HBR;<qJDJ;}+pyoa(Md`rH=cVJFM;=}?zXRT zM}mU8^_)wr9oD3tHq^0ui%VU{>3;3ujc3oFe-NlA z41Os+Y?lDk6M+)}TPWOstjF1v=UzT><6%orHdGs1s6(n_W1!zx-T7selbBP^9KZfdH!ERQ&23v_MPt%T$r+_`B3~&f&bGv0`zI5sJ0Ipqo&RY1wlb;2!zyH|L z`WQgigb-rR{Lzno{7E&6dG_ni0C>}z-u&z{PXjnUJ{I+jY2T)}%AAQ1x1{G_Ag3&J z@o2pU^Lo9$bN9}RFWxA&sYK9_^g?7ph@=SsJYc1ZJ9qB3&Exdx({Y+&jO7gFobm?1 z*|X<%c6I>F^UTbf&F1j%E`Xc2Ztw1%QYnd1>}U{zB<9N@MCLTlSrkvJofUzKFh(?Q zHXr`*Mgn2VI%cTj2}{~qsBv%VFkkkmtSu0!#`7RD<%<(giQt8?ddzcHsc0GU%OxJiU^5$wb}_mOcYC<{r%#`e{dxqTrC?< z^fKbTl~N|3-KIR3gW#Y+i^?p9XwnJHJo6l4xOwX)Zr>uJvuDrl?e1MTe_n9!-NQps z8cowQttN?gaQ58!7{cw_w{PFRv)LSPHuH@eMspNhjS- zogX&H{+V-zVOCwY0IGSMt z)I(l*nS!HC1GK=}Rc(K5RYL2G5E^JueZQa~n5k@w6v=97FWV5(BK-TUh>CvMK(%e* zI#Qz#8-37r8LQwT>vkLxmTAO7wU<~t+O`wG4Zu&>tj#!Upa#?sdv$C+Zn-`2Ut7gW zH%ia6vwz-b#F}GbOq2dBAtrJT;iL(T_cx9=Ya#}8vX!T9Bl2ut;hmkGpn(f0lyj(L zI;>VZ!r#sF90H{@GXTvaIVV0oKH6FBav(|ILLfk_+L?fya)^PI3t=#YKqp+5yy8Mc zbp87E3lBbMkKXg{_ZoCYp$kBWB~}X|7Pl8x!b2q?(LB!*yIz=ePehI3^AeH2|0j)q z8;FXRyJKpNwCjtyx`5at*@8*6d7e#}5vhaKmB8K7h&x}JolD5R#UDk zxwpq*r#AA>Lo17V!}1ET(nYUMI-yjIr%R^NOUX~coqD2OKENS1ubCROEq%Y^92Y7n zd#AtUu@>LQsi3TGN{(RNb3q5Ute}nt%v`L(Q9W6tS&1&?(*|v$RIHvOw{PFL94}mW6cqPdjd~DjSp8WDif!(N;sJA4qf4kw`J3;Si!Qvw~;j-RsvEB3NC1}~M@C9FC|Ka@@SCWr|LNF10XLt3F{_+1dHu%Z!{{adir<8%)w{Ok!S|-#3qy5UD z%CwX#6m{h&@p_j1?7FZ1Ldk6cXt>7(b3#`Lz`+4h2}Z&M5NJbGhr6g!H%Z9u=>)m0K0wB35r&IH8F8PmZdo-(?hvFpGdB^+l0N zL?KLZnuJrM0Tc|x5GVvwBR;ZU0!iAy{A4@qO+-XNLnYY6Z45HvEV`$X16nphpi{eh ztKFSbd#6GySwaYe7|TU)@d99g*PG)zckbM|eH);iot+2IUx;xEF@_SE3n*sq2t=Rx z)n6H*_dov4e~X!`^hGqMB*`fD_V&ISujiaCSatDXQ8SJO)}p7GBtyzWgTk`4Ko@V=xE(JuA9~jf7o;i zeq>I?I=J&Jo;-B5Va3k@p3s*J8!;@^a z>u#Y=XH;rj{AB_#tyWW9?e1yDRVTX`-zb{8t&-t+GF8Yc)qg5I%R=|GaOXJ!`HDPg!f zq0uW!#8$s>_b8ku73TsT+2!%@CwB|o5}4Yl%4{4$Kry@qP*}yBUQ!#l3&DZ2Nu+6;RHD6HxNu37ZhL!sMD*;le+0nmVgPiy7yt)fJb2_I zAC-(!Ay5bqrS=#T)W$$Whet<;M|T`Zn|q0R(gQe4KAoUmn!$WBWEV?1m}!cF&1Cm^ zpjqx1>Dr74{3;MA=h;Gl8Lsoxff-k>a7v;^=SLrbGV3Bca7szc`K6I*(u8GH`||m@ zJ+ozlT-?KzqTL5qS$C#U2d_{lGE&bdl%cvc%G_)}lUns?7(Xa~hSVOzkZk(J9E@wk zP3hJul@{v&x>H^^c5!*zZi?;8f{NU`e7Fwoqp_hlAWI8A4ct971rGiObChVWt>8vL zqDGCrSW4s|hN2OlfPK}N&0PHYoZb^h!l=lp5tG@9d zRq8*CXGEVZ2G%`;;MF95qgN?V< zjscCBN6ezj>wOGOldjn_3Nk6Ye&(a2qq~QP>3rVZ-HmY)Rz4)m%ztF^ zzp8<7?qDoTybxE{W*ua$#b2D>r)ad|4ORu2%RZyF;7Y zI33kKT-Xu=tdRpUTw1UP7kc4_-ymbBB^veqPQT;NmM!_V`rWA97HEsdDY_O;GJW}_ zv+BYUi+IxOPTOlO-b;w+)F{$<<%?}|nKRoIPIN_QL`e z@0pF^y_V2#IW?W5PrEBojz;^A;t?X;_(3KD(MgO7s9$K;u0XYcYtKc|HZ4qnJrTX| zDJCKcGa*e=I&=0+4DrEVLI@$oz^Vk8rl`YMF>{=zG^e|F?@|bv^MC*4H%`;^lOOoT z-p*cKPq~|v7>Wc?V9pW{eCvE)aVhGUcfR9YS@KnTXl&sI8daETjj2=wuPpSvJuS6lA9n+dL{0sW;vL;`F1ni_SIO8^?L26&s%gW0{|O{ zjo|f-ELKywXs`$vP|*EsoRUzfu^m{%zAtANb^&5=zuY~x|n zUmXA`rMq{%XHAEWHeItFHX|ajwQ2k9Do6mAstd8n>KH_&L1Ns_K(N4js++id`!9A8viHP z>A*q`TgzIIygAIgySu|h<7v^=?-3Y9h50g;MN}`HG%vRQW_6qqC<$=&@H+mw{eG_^ zK6H&X${LUy;bt1ceP6Ejz0d~V$BpQqMqfk@BQgX4blFR+XanhfKw_G7jW^J~(`nL6 zPc-m>C--C|-4O3b_A`JhPtm~v_V=Cn>M(oaN@XmnbaQ@fWG604k51d~_g>9b7gL|S zG)=nK43@g(>I=krGh%7ZpocL8gevxw-bIs6RJ5xiFFpKWFyrb~CL)RTd-<}ub?A%I z<~(n@Cjf~iy%+S0WR@w2CY`{LJmCo;05@O!HW3kMXLpB6yjnogqZZ+sh=O3(y}exu z;pXjI7cXAooEd?^fdU1DK!E~p(WIwY29OxI@ept3d2@GNfn8J(?jK+^P1DZG^N;e+ z?(Xh1#hm$t7hX^$izr`|k<$NI{m_-dR;{`qw1+oe7RE_|*^2<`D5`4<;25ZAmLU}6 zuF)R@IkJSItj9`@Nb2`@zzUn&FUsYk6A@n1Dm=@cKb#mkCV zd*kY6XIRQLF4e~v*>RJq8@1`EG7@aQ ztI!D=)=@Xo1?r|qq?c~G??q0xe_(7;LT?9;)^c=`1Z%9Q+snZEDe4%x6CMREBhuWcOA>RhGO!aUYJ#JqqiLFi^_O<^*4ne? zvS#x(Hc<|tiUkYdjD6STZ>qBhA*jSf%r!Y8DiSmnWN>41K%i=*+VJ`*ZLH-gJ#Jqr z4b`@w*%@Tr6VEMaREXvkjCSDnIQ_0QA1vU0jBD<*jL@LQ@n;LT^qHseTPwlz$ArdR zh=5oRj|6F|D6*05%V&G>z5wS(2p&?O@piNP?Rr2*Hfv=juq4xesd>pm(Qds64gqGt`-`j1T9_ydaN~mWj0Bk?N>of z^4WZIME%i?3J54tL|`Q1V0UUVLUHvcqELJ=8IW{Tk{WJiB+1uu=Je^9HZYkSc<{mn z`7BL6f9=|n2cQ4gqaP=t)y~8j%)Hrb785xExPAM!DVvsLum(P=f>}T^YEDw@UjR-L z^UDcoE!MIhVU%2tVZ$!!5`a0G_d(7@M^Nbkit&qHo(O!%pAklyzj*iyr%^G*Ro3Kud1_GFQJ+IgEhS{tf3VuI2I+RIKF_S3( z$OE2Hy)%jZsc60JT|EorU|%^CePp~YJ0{90XqdI-%KuoDcdmR`b7{a{?<)n%*SW_?>!cuPZ&@)EgU0bSL_D+7<= zS$$z7h46Z_xqJ665x)A>uj)ZC+#w46g$BFkw?42TpCH5xuXaZQ+f9?a1y=vC`+Q>8 zT{w3D=9gruTsH=@pe%zG&2{;y-Ly6SosJ-w)^Xfrl^olXnxVpPXo6rHE@A{(@^}_w zmQCKwX}l?HR3r`3+@NMg#A7IG@enJg-eqPQWozhk34%FR~*24NQ5>5?C+D0nyfEmy(Vc=J9#yuFx}+IN!Lc;?ylv2X=h)?GfRDAPLobV#cKu& zr(+<60E#V%W(#6geXC$dIdR*LjE^U1Kba;y=Y07xpy80NT`y zr@u4^ldYzr%IrQAlq~=E_p@b=%@!>p*LDinKiK*`R}0Xg6&to6O(zP1QE$f0d1=9m zimmeEh-wkWV|RClhz<{rT2i|x2W|Zc3!oS(;6C&VJbYv*?lSl+%oiv>E{vkrR=F=U zR%{%TxPPgmF%1FrmA5(3&@f8JK}ixLRk|5hJ~pxi5>4UZ!+n(D=-=yw`)PcUzUdT} zC2slC?>CQA6bAw*E=$y+GS?wluSv$23Ac$86XL>ZjSnPZQZDm-g4}(jLUStBX zxKht^n&-QBH+#E#H6tg3i8#b8K>>1+zjk(3J3FhC(q^+}j+rwFLr=uu7$Spn&cui@ zECmsH6^bRg=I(Qr^1C{6SL0eW@b@E=?0dZ%2FNA_WH z0RHo$W?^xf_9VubQkteo_*9=}V!1GbkkZU%C*b-G&LwACQ5Qls)ubP)KM~w!6SHC- zDBj(#jzK~K3~P!&IVH|b^pM3uYA4d=G9x!TVeyT3x98%~V@o5|V$HIA0jczB5NIZHZkN6A=Y3x=~m| zQ5+oL>Tj5Xn93JS68G24V_X*jK&qa7OFRTa(V^%j8jUvV=EinS`ZP^&zImS54fLxj zUxt)xwd89(xSTeB}y@6B7|# zzRVRHyYb|l;u zEje26nqOqDi(IBCS*b}s+3~A-NCEZ0-s8n3u#bZuY7F2Sh{6)?^ZMK-$M^|dl|iO7 z-?=kWHBDM*{T{7sYkW{l+#lVc#v!XUU)u6U{i*HX9!q!N{um%jnwP z)1|1?w+~(pe8q8g?yFM_BJP%r>0fL{DhiQ8YTL?+hql3?V>!%A6!oz52nq@rFt6gcHTgv+LWE`h(#a={PDehou-d^157hOdb8%d|DO2p6N@X$90dW1s zjSJ_`8^ZCa^(+{+$!SD2f|V+jD8>~UXxIF1J3Bja^O* zO@zoC5`ZpP03iyrsT^@&5JRVL4da(jHBW9-=_QiB^WM+f!!e@-I+@| zx8?B}w?-6aqWah9^s(bm#$vT(-dUGn@=k<3t!MCWMvaLiAeJ#lCpgS&N*cu zPymHU85>32(EA2}B?k9uwWCBT6NQxc_~?lC_Q)WhVG75h)+i%?Tjy#EVtN)g3orc0 zigVYRUj-)!b!vKcZC2%r$~B{AsDB`T*r~26EQdG?UY#@qk?}&9IY9KHowh&@Kb)i> zu02`@zE69xAHrfG`_t6D4@b_{eW{ijBOC;JW&WydSwJI}Zn8+MCk^|=U+Yg}^i}_@ zYJwJZVcfs4P)@Al+8=Xko>aQoDPzCfnI-3@y6c*sOB-%0-sdvDY__BK<|Uk*IfTg9 zkWprJ$7|7}(FFvF;-#z})E3)LPKSkDDQ zwaU(85XG`oUT`gMTJOXfro_9n6h@Eaej_t8!EXCCE978Rv|6oX*qhCUI_m({P51#5 zQJ|7nS}L|GLV+8NkSuUhZp`Fc%NXTB0w|+ED5{O3F=4|pbw~{66v70j${`KeY7WLp z9o9O*-X03*R3B{0g*q3{aI48TIS7<$DWw?20-^#zYAB@yc0~kOv`#6F zoTVNOq7WqXx&XwW9b_GAXe|aP77E6!a#HlveLU&R99L7$mWzg%X`XWk&3O-D0-(vN zYm9AL6n#q_^XRF4=@Z>N5Z~7}-4fe}Mkrl)csKcRyC>J7?>#C6fX*vf}4Z((}|*?Q#SPv;m9A^=yfVt-%P zpd$ZXlb$s+HK|T&+hG?)fY}sxkwF}j$VAYrWK|2Z1^8RLgL1$WC{pa%kKskHi1DH5 z{9FC)2sc18UfJ4I&pDFwcd zmPl@sliRn}OQ#818oHCCbYS+AZ_s*a3RTU+@|m^3sm+md`&U~o-^RX93Y^h1gDlnK$#es!N}h!eN0iukj4~XCLp6p?rVOlmHSs(+R%8>Kj~D96#z3I z9UYnD7MBCc%=Z%~3D%nb+{T?qSWsI=qD)8eMi=y zj*L5BR+;iV&vJq0CDl$lFiO0}?XlXPw7Lwd)*e_QF5cR;@wUEKWQ0oWDHG&6qaZRH zfZ1_))^k*dY+KDmp`rsq&bedj#|EFjc5STiuU9E9MPc&MUW6N-=lQ38>ZkCNKLH@k z$->~<3ab5!gk?#?iR(9ph2xDelDgqoWqG}eeicH<%$8oo*2uCK!=0TePRGZ`E)_8W z$eARYb#5t=~FTX$tbit*5l)u9#Ny)Plmst%p)M%IPgJ9q4-%_q zYrQhEUQk@nDF_^BD=`9UvLUV0G~SHcBW=4yfZW;yXs)ZKHG5gxed-DT1d99nkhJE4 zphP$?I%0;nNdiVw1XX&kv@lH*bGG10b>iF9=%IM|6(=#ryt20xvl-j^7W3HL3W02P zUL#bsWi?JVez@19OBYQRMK>-2IOjC-^aJHBGOa+#pzZ3|RRKbvM;^h|s|4UTir134 zcyo+0BeGN3=_%m0+^Al601Vn)qe&;HOlM{z6S~R^z%)Lsu9e@m4zCw;PIBbIws-g4E{v8X5PXQSHP zi}u{q8A`v3ORz-m9@t@!8?}O^n}@+C2oU6g(`aUEG*VF(iElskeAH?sseUM>+3TH& z!fG|iSK(3&*kl_}dPI=SN;(IHm^@|5oRy|^dIKna%Ya6Rap47XPV+qf%-i4mm;Uf+ zD$0F`{Q*2l-2 z5GEp`Q0y0E>l0B4VpsKB+4a*LHlq#tGJ zT2E!gl#+!x2!SLD1G6|LMAlGt-hW#+0mT@M*U33E%j%m_sfd3?2rMQ@QGT6E5-+3u zRJmsnJZff{5~@1raU`OYHpbb=(VbcrrLr!}Kvk&-Clq6JPFsDjv{9JZ#$oGo&o!2F zqO@BkB4g=XX6#*bmSpYMZeBdpDKMc{HRC^b-WJzhcwwB&pS<#!Pk%-}*m5-R=fddO zS{uatsc}2Of}0Q#@ti0G3sC^z@$Y|JDufup!6X(Udit5KNo!C1=?}>VpEXH2S39t* z-K2JQ-Cw~5YWS$|VWJRY%yZJ3NlcS+&Ojgv zIfF>z%Mdd^c;PiSKKrYWJ^H;l=hbSpyR);nE@s3iYIHhDjc#agRHK{p+^Esl>$O*- zi=3wCY@wJg#>`>JISlJq%JY6A6;wJT_qA)M*WKJ7W%Q!Hz23b$J_%H^+d9!}fswgq zr~Pw9)slgQK%$Wm23K@3fhcP_WKz>Y8+@QJO+mL1LI|5pOQ;N-3 z4#)uEyxFYLB0wEFFRIZ~niY`}%uKidYa8+OAnL2?*|gsKcR=P~N-V%HwiTFVk39PO&f(l9goZ0q`> zjIG`#8e7yd=z>l|2t*;J{O|tT|4!B@*LB4azVxLp{q}GFb_f-_S|cHZcfRvok3as2 z-}$9KzmpN6BRGXI?w91BDV7)wvvFQsp^2j5&as^OaBpTs?<>)l&b>lJDd_b1I zD1<3()}|~F0%)3aj~1A**{q3ZcW1}gB;INr17&q8!&4ZYI$HMlaGQR_K|)+ji{(@< zM$C0Osyox(2EMxaZR>zvesO2c8&wcsN$T%8lJAHh^v9;$2Y6pCZ_`1E!IE^L?WMD} zFE83yOtX!mn&sxFo`5Xn@zI|a1L%;+0lImZ0~JxFvLh$z4kg$&8q*JHiijBO^D>S8 zVg(P#?JG&t0Cx|hgJPWmkMndVy~tBGhC%BA6+?jH(#TtO#dsJS{>lhx{YylHB}fC1 z3P?8nuUCc1ETnSl1WFyj@l(?e>?Th0ob)+aQ|$)e9ykkpBiS}y@&_ztc2pL`i0{bA ziBOr9odyx+d6q_@A=E>L^8By#3@(;d9n;yJxr1n2gdPBsewEZ^_FskB6oU(Wojo13 zW<>?jy_?&haip=l3eRD1R9#FZ`G6dka)^rao0}66p~_%DMIinmkYk(-1uT+O$)7S! z(|WxI5Q6AEs;DEMg+21wqXr(!(27hh_?n&_;nu)JDr|F3CL*TnvmzIMv^hwP`N<-e z*;PQx-;hRd=pK5W(qLkZ`zKrF99Kk4@zu7l5vBLM-DmqxfZ53Xl%M-weoi*i0}q@N zA5bHAP=BB9l|q_wD{)Jh`7NE#N)6@yYgc1{?q4 z8T#Dj{hP~b^r9S9H9CtN3S?zKoElwZ**r}XQJCk=W;2T_S@haebTL988#TJfKLB!W zbDdN%+EZx)5mOW7g{V=ZGqags7)(Uk(fZcfGP73>b|9xzy*PCPcWU%z>GZtRE=S~#_E^d7hkpy@4yNQJS;X*-Ox!JyTT|!h z=81kI(b>9tis@nNC+m-M+i#B|Tt~uF_R5Y9EJXC!V@yN`2l&n3#Qr`Wc;FnC5)Us9 zK#u$eKlrEK^{#iFP?^voG$JB;``h29a1$MCGe_azn&#@6st_wH-f|ACp;#0SL{wnO zqIs6LLU``E=YHpRe#gb$EdZ1k&YwH~-gm$I1Mh$TlTUs@T$tGv2lEIla68>NjjJ?O z+QSbAqHy&p06I7zX8OqGOkr}yUt$tfj;^$)G7=ZgmTay}L@|V%ECR8pY)q3bc&UC~ zua952e(iyC7c%E*npUgbaS`FuQ`8VDKn*=E*aoe>2905()7r?l7)b`EFi{IQ#Y>*` zUL4g}d`Q=l-o%xT&|6Iyt{4P(Kjh)b{f+2;N;PlX@;jmAX(4S@#hQj{aGgRw_ioYb zbZ8@ON8>bnE^T4YbaqZNLH+nf8JudMoh`E^BBEd+-hxEtBKEpMB8g`Q*+PLDo=UnI zkeSl2+8h$kKQ$R}<*%|hl7I$!b1OH-IcE#gNX}hFvfBa>EeVv6yRLb) zl6d>fToVV#Z!SMe#el6Mu$G*2*Ne2^d2x0ZnA;bE^#8?t!0~(n^QKL}lsF4bi9!c} zg*w)^s-Jw_+|_Czo)BWwF85-zR0YPMnDVHyQ_p?#o7*S*C#U?~|M~A}ETm#|z4#Y{ zJmXnUUrmbDw6i9~u1x)l+)|99!Bn%6!@Gxu7Q6BIw`{cCkW67b1g`D{v$2eFj`m_I z4-ioViFJ(B`Jo^FA*uiMZ#>&I_{+cW%S0pw|8cYV%%?x|$xnUq`i&a^F23e9hlhs- zD+k_Y!&`~m;(svg9agf0bDk4$SKJT0+lW8JZPH3W$0JB z*yiD-=uRk3rW)D0(^k}F@;`al1DuN^F>9bA6F#ey#me_;%U%G}#nG{$uyhqy82i;( z1!}zNLZoCC`}-Kva5-05U2VWwfHs<@(YC_(;>Sz`-R!LlQvpB zH5Nd{B%9-n8FT6AUTPuFSrd^P1}lG3hFaDpkm!qL%cgl2*(L-E6yETL?}{-{2p@U) z;n%(Hp;LROkB*PyX8!Si|HuE%|MYjJX_74=$?^;`%*ohB!_0LdT7{s0$ef7sM?Ml_ zoKi|pJ(Ug)CO_oU5Hw_nj26<(Bq z?rxxon}%v=X+zcUBIF+~zW$QRw&1v38Ie-^bNhi7Ua?*j6lMI~B~Zmx8oRBWO_YNQ zx$D*HfkFtRq9Dg05y86w*`^RTYLSoyg(^{IX5aTxVTO-3=#YaQbK!8ZNu;VfZX|UY zps7fht*Qs0;r2$9wiyywD18|~C4Ba-QW^LOwmLrJ@p{I%>4-55zbC{_N6-w?;X+y2 zus|NQvj65V{KC3;s^`ba%rW}w>h3K=hJH$ABgxpr#7XV@s3pxdi=u;m>s#OU`q#a# z%%>gy6Hk0D#!30%3O(7|4?Xm{_rCYN&ph+=@BZ%Zf;lCV-#wXz24Bk_{(f=YlfnQ9 zQ=vK?vYs*R_F*8AJ=^a0+=@``=7Xe6$k{CK(B4SP&Hza3yu6{$L zds#i$!8wN*EzYZ$oUrB-p%OcdJriGU0BoVCz$k>t;+05fOp%jYts9BFVN9wIPN8Ld z(h=i^5AbX0H^LJBTC_lk)`F3C5%v`6k6q_)Jog;_KTv+|XaBwk#l$trMpkA>N}xcd z_|rtlp7pmw=qV^W{bSCVN)V|Uwor@7b+#)sKJ?8ON5RjFbN;hE;U(hWOT<6g)Df zUGYMr{asYV2%RXW$Ake2=uk3&`^1}_sS6b_=Gv(nYE}+D*mz7GBcN`;6~fQ|??3-z zfBwh*@jv`Wa0jzMY;(-af;V)7IVRbSTnKdR#RBFOs2S0KxKAY+Alp3 zT{wUK#czN6vrqim$3OOo6IZ-UYvDHrfXvA=)|oRQ3p7$r;KVGXN->Ql~vI{z{8=KtrCk*=iE<2BMkTTPlbNasT`~JPX zU7%!!)(k;p!nu35s$<^rmbXxoxxDGZR6K-Y%PB0!RE(bL0*NNgU|Zi(*^j~N^}6FH znlahSL_hOiheRKgxjF?{0j$1h&I^zL`RE5=FeF+(IU0)>>*1Lw|7 zA?A<;W6QQ*9F>zy8b)i>q`Q}L=FGq&kA%$m>eUn|931eYj}mLVTrXWPb1}*5$sciI zM3@mYDs>|RS4%WGrF{F&?Q>_(#Ta>8YR?hq{gW!^vr5iIxc3;K{HY>P&WTN8sp82! z2f&>HNUQge8X{Nm5UJBNbFJjb+796*YGIZoSYOJW2XCodwyVjaJN^A3S z<0!kL9Z!9E;dCpMj8zyRTq|?AtK+YI`ro95YOa2RJea|IyL+#D-Rp)I3jy zUy*CAs+rU?VwLOU2G$U|mviF+;T;rNunw z5W*&Ju-SlUn&PK_@s~dJXMYI5&0DtsoIP`f)g+CG#0IBeEmavy_Bf(ooGxHUoU}fp z#YStG}IEGqE(}p z&9l+Ig7mJ-BsM^D;F4bFvZ>KSAaN#R=7R&o7$l0@<;yt)@x)BFC1MPAAsj-~uLZE; ztwRPNrK2HCDtJQ;18W>{gQ*!eLD`)F8ykaVrB|c-Q{W3%-Oz&e#Q*Atq!%pmQ#CWu zb*G^|PB20wq7b5HAnXhz7vBg(bmd9`-D=fzB$zJ7)!DOW-M}pIjTs5E{1ifX&wJkU zj(5Cco*Urn1p#2&jEI@u_O`c;P-SzxtQ! z^KGTd5`wYG5O`Cg*iM^Am?F+@=acAOtHjl+(N()-F6#C~KV+28It=xBC4`F0Z45fDkZ;7%yJD_|t#mZ+!VHU;f#j{n_K=V>#LuS&x}a z@n_fr#o^0lx}Zrn_~*=`U#(JZE$D%P%9CfRG=pK0Hw6iIP}KF_!p}gPD@~vvJ;Gs zQ}v#yauBs4$LqgxE~;46Xm-pi$DL>cmmv1?Rg|!R=|mO^QMF8IWp$4vOMpaoRaUXP zt1mmbZXPb-0^qjC(0y&8rwNtS^cslehD_9#AVl>P>!j+s%TG2W+iO~ZT{WvoO4BP2 zQ9NK>H{$VP;dZtsA~3HC=<1PciQU8Q_0c-JVF2`FjZpqazx0F4y1PZKj0)%PdG~ux zM#W<}efsokU;B{wI2%#+#76rp|H%SQF@E?*rg1Q|xF?iNZHq0|y^FzJJa}vqcRN6X z4i_w%Hgnlv&V6oPZ`7f(8G!7}5JFBl&GQ@I@LeDL?3;e;9na>RLhuPp3rDOR0i)dh z8b8y!pH~h)XA@1BOFXP{vI=5@Tp>cK5)AnWx}@5*OxJ9MVvJ%|qJs<zso8Y`bs0 z+1$MO;(z(}H~+`K|22SP2vmfZmlnO@J_`}i_3PJvf2%q-gX5JKU+tHmkLIr9`(A%x9l4PuFFAnF)@Z|P~<(Gy*J;a@@e-dC~w!aw^(&m};QvRDVKR;zivF~LBJfr6d126Y$A zIa3JS*bKAP6jsSh51`jm=4$9a6un6GLbOgJ014L6jbSYImjBCYm9Y4$AGUw!pa1p$ z?61Fii*WDq)BovD+vfDe%YNG&E1+WMxRXb6W%d1{Th}%K``{vtHx@MA>(=bH5h~JL zFa*$5$jbMSuVB#ytXS_FSh{FbB>+=lbPD!#r#_aZe(cZxIqUk=-X2PTZDFR1glQK& z0oG|R$q0A^CcC?*HfC^6IV1FASm0>XE083)P0_5y5RQ)zRWsEfK#d&SPwmEw*8zO* z_k7}?{tqg>*v9)kc*#yJnytBhFh9fisC~CEJ0iROF@r@nyvNk zHXrO4gLj8T^*Gp&AbKe}s%*R@LpRWp2m&G}pNkp;vYS%F=;myWo`{FXCiJ$Ob# zY07Iv-Jv)Ij^&FDwGL^3HNl<+W?bfYPpD<4clAgI5v@C?p!In4Y~V*g188!n?4>xn zi-9*l#rpbJUkgBgsO+?Vov;IoP zJ{xy9!Wmrf5%vB%J$qqE%Az3vO825t1^_f*F)YrUIrG}z`1J=Ld=OpK(j?K6HqHg^ zW8eD(LmnECjp9<8XD6$I0o-{$ z(4!xHogtQ%EfQ3DkgBoabAb#C%AeL_J_fZ!c2ca%;~pSev*$nmK{N*}&Vw@K zP19HF+N*o;!k*d0%w8lQrd5N1azV&;c|bd9;4 zi1K!Z0!j4OJI@E4+u1|2&pj6?o``8T_ajC7lbx?L0lj_H^Qa$cG$nvK1Y+`{^_6mM z@X=%zfBw{c?-dlXL1-Wl1)?vX3Ro#`$#pI7^0`}4X*7Bd$E>X1#46}7mRY4x*GZi(d zGiuJ(e&8HDc+smrbHCAR@rFONslWBhAN(S^|zU|oY;{Yzb zE`7uE+HGUoLlY2r^I@tJTUjkSOvjP-MRkuJsVfyaV!@?!&~_AkUlG zMnuCfF!Md1_Iwjx@x&(%4?bunT*g4 zra=Zy(V_S$_x)?XdgZ-+0-byg0M(jic`E99cBeO8;=J0GJ7><$w8rjf+FLt$V_uf@ z^dFMcR)*E7v6VY#POp){G&)d z0L1j#U;ni)`f2|kqd)(nj$gd#HTJ{NGK9fD z48y!)2FU{?J3m&zw06Aks|6 zny#o?30w+`sC%h_D0U->blDjXgvJ zLgB(pW3AuzZQq7|Y^xf^)X;|zd{{~H-j)ihnYV`qYWJg(2$h=f^ZkGGt)j1b`z)aNTw1m}aD&s5nx4v^Py>ZlrL^x3rnEv$L}}aNr!g?~QzoSH^#hUh_BC z=n_RgLF@u&etw z(5)2e?^5kEaIJBVW}o}vaK1c^lcOyhvomWK$ ziv)ALz4dRbT-tF!JBwo$7NF_%lY{5dOE2B%iZ)KcxOp3|y7DStl%t!v1ubt>B6`&A zTW!ab8b&;WKr{xTD%4U?PYc3yR~p*lg2qRXVx_WLE)`f$>QB)PIT$9Hu zOcSJATU%uaCsqfh08m9Gq5}sGJoPJ|`u_j=e$&mu=*xB}+Jl{F_!#TRu}hVRQbTT} zJ8RITyHz;FjjE`%aaeh+=1>`Z&-#a)$iFoJi4pOiCg2&4jaS#z5J$m$oFZd<} zPMkWmS}phQ-*@|+UM=I$#g`E2gGY~Ea_EqS_;OdOSvy!EKQMDCWgKPApQX(Ujbuep zMaV4{Cuj}k$PcyFOuLw`BchFsjbRu*{h1aA^xMDnTQ}Wwli6Ci49uRkD8ujm-@m)H zwaqQT?L>pgX7*n@Ek{yM&AaAuWO@q`sbB!`&lW}dW~G%U6N_{0_~-}=Rem-a~OlI+Q;Agzkc&!ZO;Fnk6-`QUpIk4u|a3j zKt#UxpMPIowz=3)s1=-i8;Y1;rMU_e^o12?;I>q{<*f0)k#cuT9JXnJP z)LNP7?Ag<%Cv{t_B`p7_L}HJP)O`<~cnHApW5?EC{mf@PYbb-N65)Xd9@yF48EdUo zJk-?lYy-wvIl4DdjAxSC{7U-u{6mP&QcnVGWL}SG&QsuJ$t&k%()j&>8@!D&4jUmyoh#4 zZk!B0DG{l;a0bZHX--J{+3#>UY-)cDRBlD(_CQ;Dv^PKsYia2%ytK8>4R&Z3Zb85s z-UtBS`5g^Z>ie`kI5p|2|s(*4v-7XV#Y+8!1)@%$}B zlL#;K<*^T{em&6y&9UbcHvL|5N6muPZ+`QiA31V_h%92gS4ez_QrfEa?0GIT0IC(> z&CQK|(sn?D)51hYj<~JZs=_%pBsf4K%7oqBoiK4Fyyx6Vju4yHW9C&<%5c?{kG=J_ zw_)x0kyl?I78=Yn(p2}?bh8fKpziC$aO1*Jxh+j!HHSV`1=3JYCV;urI`)?1Y@AF% z3iPj^VhTw{0}IxU$y#uZ+xI*)Hq!UFjP}YB5Y};ThBuqApW;CP&=lZF`?~8L188!q zwQKTu&!sS%teQSYc>Lq9PV-xXlK%N7!)#f+{PN3l8pH+cb0Wrq{eIbd7Y*!|v|l@h zrZN*)No$CQgiw-TQ#idWeIgTLTy>9atG1%In`41ZBxK4#&FAN6P~C&O#;DG5gQz9gn4IrHt66i}Na&EI>F6?6 zblr$G-ubDdM^lLQq^?snxu9z;b-Z<9$n>Gdefpkz?z#I@cbjc%r4rytB+%(`Xfx%U zozk>3W+o=7F4>${-pq{gn|62C6WMfAY=~$aR|z(>pWC|7tbkY;`QnQ%{;5xWCdd2_ zZ{p$bjv*pCdi3Z^zU9RVEJuq&sfK!NZg0Kymbdg*KjP9$t*V8FHJdRM2tmVKYL&<| zp}MA^r_YEjx9g=AFjXMXiMH9JQjdS=#ECrr{`b8Pz|*e3-o8HO(N`{)ORL00M61=x zZUIn;-|&Vv0I=P4kw{?D5&(w^*eL`_QuiTq86a+#@ZRLv#rb43+=TOMzO)l<4ZqNc z1M1J@HM1uq8)tvhS*dSP=XBG)?s+o%t0$}<46pe=UbEhz|FFmR|1aO4g?MINV*zpQ zom3ku5TmFk6)7S+Humhw8?(vzIgS7RuNj%yefG8U`1LuWu}hyf&R*0HezN3EU5A<~ z)xQ_9Cg+))FZrl8>^r{$`#hs0m1A_uQ_k_Eq$gEXf8%vuyaUnykfWIj+7$Y1>GTi) z+xt8LM~Vfz-m+aNFx`)u$J*3dp-QA@&+huV?62D!jv=B_$Rx?J3-+T6F>Hv)7S1C_Cie5;!xOe-!)2N(yPrq- zSWIVVo;L`_#@Ob@=98cFq;LM#Z#j7IV6FAzAOHC4U;p}AtGQn0JnBas6aDCq{Kz9N zyR12co8A{DTNg8e{K0$0L%K}$iKsn)PN*}fJVw)0RqCj{;s~HC?lbZA=s*Oq&3X0r z+GW-uMrU3>tAczkClQL+ABDc=m)+g>r(P8j%F8MtjJhpR^*kY+Dz7Rk zUQZO1z2-q~Q?o3^8F$$drJc6h z1UPKN-6TbnRnMP@h`X1j(4NWvn4T~t*gW9e9Gf0Y|uk-t?w7op|UW5ve+fiJl_q%_iwNX8vNTS_+k6 zASz)9PGk}JxW%1E(w9LGAGVohJx2hl2m!UOtoDte|JgnOL=*qY>=Wj4VE=&+f8;}0 zJ8pXIHy%HJJjbd|uobnf9k+pFKt`}ho}s`{#NKJ!))9|{Qc4}I2pv>g;=HguW|P1a z08D@FsdA3lKm9tDx1bZkvk{%wbmJmr0HvXxPwkl5eT>hl=w3=;P^m__xBm9MOnU&h z_?`A*q@~E*XzErRy5NEfhVTx^cFqK#bpaDybImnQB$~Mh7o7=YwOmx3{;q_x*35yhlU{`oo*_Fa|4~ z**$~Er^w7(TbpmY^{si)n{R&0^S|M_0PcU_0XuWy!Gi!SgA9C~CL*MJzimVVP@QBu zGbKJJ=bU}P(B4C2Hmle5jKpHz^Uikxpt1JF1wVDq-REljV;}R_)oP`od1xRbH1S~p zI^U2P4d_Lo&O5&Uie}6gcN=fGzy$l~{ZR67s%T3x`Uet`RsryH zH~rkX*!2%}yzHg_OjXg@z?!RTH$QX=cI1_+iib|l8kkr1C>1)+6M44MY_&5yfU~^U zVyPiQW^%Tj2=k)P6cWob5$W{rZOOOaSckJE%gr-7Ne zAVlgsDKZI8ess%hN&vRDwiMuEOP^G!h08ZY zo6-OPAOJ~3K~&cM?ZslTySwwb&)sL6&(_{RXXfr9_Q6K%2R=~H!RUt%w?2}{TWK)* zo>cWh+de1w*k9B4^>d%|oEvVqVX?VkqBuu*#5jnE5*f_O8W!MKYaOe@=-Oa(q-)1H z5SgiDXt`|dgQ(c1y;{}cycnw8bPj;S)!f8KyzOB`IgH`B%*1oUqJ)et7e0}_#f_xd z-!z81uYdsh%2zaZhIpHrf1gBN82A*N;WBH%N=BJuIswyYyRu_sBt3ykNg~v?GKR}% zC!C$a)`H+iQ`EF^!?-m|-zn>WpZ~o0omwu3v?){G=Eg}c341bT&B0WjPZpOT&bzAb z$e<*@clOuhvYCj}SS5`zWcE~mm`!{qauiouqEu$?eEzLzVL}hXz=bb7c+m^L>4m@l z?|&b$%2*_$bBvsTjv&p&C>r6~RIPP$YhOR?oJh2V?C@baa>Rc;azqawM)RMvHmPMu zY{ivk4AH4ip2;pEJ$>dB_BsleOAcM4s>F2c*s)OX$b7C%J*ZJvE(B>mjP1O8!(}=L z_0%~4P{&qeASHcQNM5_qlr~PT2>*kds+S#)|3{CHo>e3XT@w&8cw@1#@uEfVTcH6C%w&jT z#_Lc*{M6sF=d$RFky>i}CKBEH=pl*jU7c*S1xS;~UfTG@=RiQRz38UJdRxwQv>W&Q zwIk2z&(}4&r`OnLnP~O%H=;*&{FrH1Go^I)QxoiM9PMRku61ADKD!pF(m(?VnO7p~ z+c5VlA*=&5d(Z>#pgr5QM$$PursqJ{7ERD0pRuGJ$q&xM=00~$%p4~IHr_^wS04P!Cc<@_U06G%U|Ad!PfRWZh1%5 zdc$*Wu#*p+IC1cT3rj(*LPX{<6Y7GPqvlLP_0AN|oxR4~9=caNgmSU(w(hN#3V?Ur z`Yv*x4g}+dB(G!b*{#n9i`m{vJD;6S9=0Pq|1W^G)%gE&c}AS1Ke3lQbAV* zMswrpxG~Rt+dH`=5R-|Jr9&Ovh1*u&K*O7ipcKUlfWRvH>R)(xQ<;3{cYKe*VImTl zxhUBpD%f4cM6-ELu}b9ZQDUOhu51FBMDSJLxn#R?0Ek)Y=*C5=Yk7qKf~JMn_19?G zz|}1-gx>;GVHRMJ+edGOT0^G(n1=2Uq(4{*o^g}_QDHCD#9(5z`a15>K3iL?y^(OA zJ-We_Es6&Ept9$ONFglSQl+8OTOW|aE2Bv!DrI0tFl@j(GG&!_x&@7kLm*HRscB`U z#P24xv8^;s3yKI{BY;q1PeTwPn??>uInbZT0a=)pqk5#hu?&MtfFvUXacK~~Z(wpM z#5C6N=YINUfBxUx1Yo&Z0T>pAghZeu=H)=-L2BZiO3|?n?ikm{I?9f2Y;5F$Ckjw8 zx!0wZv=P`umi14q8a?bo5+F;A6?jMHooSD{=)#Ntey_QeI>O{@n0iE zXb-%@)4R+-4^)}@gtiG}oM~2YgK3&f1AyQBO&>g`P6ZQe2sV2_YZcN791|2kswqQb zznG{(#r$G?Jt88z8zixcO-x{P%AZcp_h$cWHSfnjTjK4SX#ibgcrYbHsrs3gm1%*d zk?B;OaLF0N!yN-b*$M!WFC#aWePh#%Aya|NL@{k`oDgZ-B;kkHKywg)H~$4a{p*6Z zNQi7JMS5ti+ZzOMfYfP^Hc+M;90p)(OJ$HYHrXUX%>90vJ3U?CjUN(JeeLzZnK3&9Bow9 zNn;a9UoCe;sW4j{Yj%@mJT)~vgO!dP;Uh-?$l=2P7>=Z4wOYln!a9;3EOkyMl5QD` z*AKJgmdlk$z2LwFL>Oy5apEMvL>B$6JwzswW1QCQM*~0;K$(f>oMp^3v&v!=Q$K|J zw)Fn*E~ki~Um+0VZC zn-6u)ZEhx|OG4kgxy9>}WO}Z@CMK#j;}1k6ZWaQtF2!=WoZPn#xH!fhL(V06Lm&Fl z*q@m`Ve*Pz;`Jy-A~ktsURI^{)_Yeobe*;^3)(;P2D)HpTK{RbP|oR`K5gv+YO+4q z{DBb&Z>nq7qu@In5b@(eMy`-jhxv*f+)r9BfG(p8yHJ070-^bL7FyMlH$#-{=rWgS zzgzI-PyF&H$P-SVIsNYUy!*kg5m=2g%6RaQ+?{*V+90I-#hk=V({D3qO$nWUUcb!D zk%kF{!7^C{`*v&0H7u9Qn;!khp_HHeyHDZaIee+GgfDM-+axsUwzuC#L>mC0&${7R zvpY|me8@grc<^9SKMccaWqAs;RxPE}I>`%rero#5da;G+UXW4S$0)t=_ulZO>^mVD zPGz_M#m#?_pDp)|UBk@(r|QnmPWq?lUT8?SnLIC#DqU&DSrhUhiL=<1d2)uon6;C6 zd9v+&qF+1naC@)(%OCimar)BU4JVsCi&0Wk5rMLZ=&@saZ4r<+94b;x!|Obj+p14Q z7N0624X&Ih=*A)+58By&0JI92#1aOHDkA+bN;P>=TNA2?QdiieimHw}TA3RP@C)#` zi~{$g0U+wdp}+%xMYP4}DWxbXGpm@?bNgOZiCNT2IBQ9X3J}=K+H-Tvo>{rc^QkDe zGm}E>Of*K^mKh$b$k7FhT^fq-35$a@N<>WLalFlqf|;E>Rbq5i0~#f5ZFWG1GR>2S zh>idVZcd1f>R3gjMex<7GBcD-_!^fo#>!3(!yqCQ*>%06vQlProT^%ozqPbb`GN2I zfz8d$U;B+;12C>CfX$7qRb9e#EK6yb0j5N(#cMoMn)C{At@Z5Lv#PqawZ+WvI!b$Q zqz6yLz~5mQY>$`PBD*)hah~&el(GQ8g@*wE4(#8*Z{Pl}`P#3!=%R}}DTc^nANyrL z^D{rUTCHCD+F!fxzWZyf8Hu8b+!I!IEULL z3R+u>rf`hr6A~S;pCsHyW?5q_8mJ2^z|8YS6R!^{#r_}z+NkGp&{E?G(5aT6L<0Jq z-x2DdDpYHqMtCN@?X)d7B2ufW5Fii*YwgO|NDU=3g1JN$A?j>47TYiF+-e*RA%ZoRAuhTrg$9azoH_JBF-e}H>dHXsm=l%OjCUsXaqlw@ zNU)&Ow?Tw%(P6JSVp;)(c5B6$!lO;7A7Bc7%3-?w4gqlMJ0lD*-oa+!2dgnovu8`;VHgMmB2@zBNP6Hh9I_GD9;Q$^Djf8Y=sFwk zLXODy%>vef5c5#zFbtqg_PuE0)p+R8#ivf4UM?+~HI*WyIhLl@^kELG1t>Zh4 z9TQGj-R@tL=o)Md`kPmdjRdjc-^7Ow9lG|~!&_UMs`|Ol-Dd-1q6|!3^$Gc|b< z-p%DHF%ezU^vrg3;vLM*7l~~r1Oc&}p-ZS0{Tm{^Q8-DL+p%cMlGcPhI2_At1Cq2| z7L1~VVN8Pj+j!(-gMoX^$;Z>S&&-D**yPgcGs3xNm#k^-sJ0ZQCC>d-kkd!_2+;uzvL5NY`kswU)uR za{I|LZJJN9^E}^~!`#*TBAnxv5QEOM-JKoY-d5FfUH{*CI2`k~TU)ZRcisA~Qi>8- zH#ax8x3^XGfd?KqzeQok9-N)5 z7CtaC?_)Z}-27*McIlx@9(C%}*|TRQj?_eJt!ALP`5jxe7E5Jb_Xz2ga7mM8-LE#> z`@KP(dj9LQAaN$5v&Rw8P5jR# z5+S)^54L{c$og&%Y<X1zNdYV<|t{OSKV+&9Yq!|~J*N?Sff<}+AhnCf5 zlSnmT%ETZBWEh5VwQ@#vX-&p)DW&ja`$&gj$g~SD|7YJ_O4-@j`44~a`@72> z0E=M=rG^wO^hw=Ygu~_1)~DQL)8+12RUH6SlFO8qMAcx?^U0OxCGBtpYe=mUUvCqrR_g+trgI_@4ovppZV-1mt4wRc6WF0yYF7R z_l`S!+AbEulb$pZfe5uqDV$Du_`EttCnx(eISnb7_J}*nNVJ!}>}5n+JA79)@e4xJ z9X;=?D$K)Qp{v!(Ra9r3CMKdS{HNn_qYXgk$7MjiimF#>64446osp}K?W5SLHH)9>VNo;0Q4o_4iIHTk9N+d$xLH`#KM=0 zqrZ!!R#6ZXkxk|tNIJCE(KwlLCAsrqy{UmXL)1oo52FKcPlVimhg)g=AQL6E`KIB= zA!K%(DSolWyTuNGV&GKN!b9%(si??ksuOz{GK*BJb}9A%BJEr-4KxR-5V_6M6{I(2 znnq|*zeJ*{21H57WD>F>;JIZgVh)ZGtyWHmX|CRzF+wFM&%*2-1eW=?orzBoP5dQMa1H^?;cPl_C=i z!fq*rnM+I)L8Q%sEo6zL_r5k-iMb2~phCPuc+8`(1o)0SZXe2`R$->Gju9`QNKasI zrz2y)#Ks0ttJHCKV{;?$FKq_pbkrZd4o8jviaYOQRe91^#xGOWb?VCe8Rt1lVQ~z_ zR4Luq*i_YhkJw+OUU0zyX8zd6KBlgvSkl&1jU@S()=MvPdowe|n7YfJt{Xh&Fw`|_ zjTw_ByRpVxZhY=@4;?zBs^e-TBB_<#4VjZ6y*+5yQyuH*=^GGkXYhV(@_4$YK@}>J31S9H<{^_!l!?~PSF-5RAm0h@lqsq zum|~Zp9Kc?&>?~intI0sV+z_`JC3Vz;;#?ZbZm*ADKzT@W#SL@n9bxj=T?ewYiKD0 zKlQ8j0~dY#XFucF!!V><&9URhFF0^ubJOjU-QC?egZDbRp}a?;1bafJjp(tM-+BG( zAGdG+sZ*!S;l=m-EFHG(WD3k6@9~BFn&Cfve&W0u(QnABDP42dG08wsG=$WftF%XA%LozdWn+=4428(#K4YL}vUZ7H;D$GUeiWdtF%K`44qXTn|mBxnFDAkMsjg`t0ixa4d zGMQ7ADN5dvM6kwr*Q$$G)VmPX34Qb}Pb|T7b`5;uPR2hj>RG8dDiilAwGu0}?P*jy|Ecjg3DiuV75&>e3 ztkoA1kSa<+l?sKTmLetg00A)Ts@4)>WUOOh+T7ZF`FDKhzkA~w0IbGwF$~?T@f<_h z1>Kqx7jzn`0k6X_lwxL&7AoOH5Gs&Yx|oLG#*vGgPLzAq!1CobRJIa$Yg@4ff_ldoJt zwJe;x#bR;bz?P~WKYn~hWYb#89GBJf4)?Psik&gnq`pICS}6VA7+L zlV*r(NC6SIqcr8HU2I8<$j5{L&_FN07}6SpE%Xv#3Zr)(H+u7*`?V)dYCmA?X+fP& z&swXg>8h3$*W^rdzMCy`+NtWQhTtdwFu@~vttI9hP5q!nH-`IxG5gwiTUaxdn00Cq z*17^<5}v?b;m#&zBq1hhPxesMa1pU! z(@2ZsxC3ZZH2hjZnI?crArMsu&0Dr|8&0-3FcXLdFEwDUQW8EI1*lXd7Ip)hjN7Bc z0AQjBKXHFgiY-TrcT5>pb*zO+RoMe$m4ipb7V{g8RS>ld^Z+ip@ZuYv z`~2l{`M&qRXLonG7=~IS7|=1E96{D`dn4%zT`hN2br?2=#lkxPiV2bqB3yeN7<|Va z%3MD9L0vBO+G}S>y5=(1iN1ck@2&c3m~bW|@8(P;0&73SF&M zk9frE{`#-~CQ0h%mn(P_el$J_Iw{i4j($GQiJ>_j72~j(uiA-oV((Hqc<{n;tSJ*O zx#SXh(Tf25vFgSWHG=j=^gwEr-B zX8z58)2>yT5!tq=*bdK^ij9gQISzuJPS@zg$) z79E(N?Zw*OKg}WDjgJl>=|p$f+?tpag-XTF)TnO>l9PKtOFBi};h1-b2pc$EslwRF zIKxDE`rkeJNqpt0Q>Wi?;RjvgvSuql>ief1qY%@->mr-c)#CL$d?|X)qFloQ>PJFL z?QAbJi?Mq}c2ci<@9pZiTCINZsz>48&){J=9FDo|?YA-WRs)Me8FO|IDY*2ZSTJAz=4AzvRc*Cr%zj|sxOd~ zUi|e#wu9j4)alcC{oCJq%a`o#o;-149LG=`Wwl!M`ei~2$X&J0cSf5BjbH!D|MlVZ zUiq;f{qZCwX+T(XNo4ZDkRx>Kik>)`emDM54!?ldfKBdMU58`{p;*kwp36@jmP$Oe zz$8^vYgZ;V`PN_DPMXR^L*Fj$@_G`H$T*Ht3ZWG$Qjt|QVHh@4sV+wmF_lRoT8bG& zRCmXu&}lbs{N>6bWde#4cDzAUb-C-&BA$&>Q6mE=L@eN6Ot}O>G0N!JRw4CFF0i~X zRYVoFN@2*GzJEvy@^|b+vK}#|jfzM~#(;Sd~FiltrWzSO^a@g9|`)6h-Z( zzint&0I+Hip=2|#J1&`dAf{3jGzgW#wOZasA%RG(bwz64Ktx1u`=h@!Qorq6zx_Y` z;UBC#`L}FtY^^LBMY3|a&zB5Y%3-XrP)l9yj!Poi-rmp5qBVSmI=zO7h@{r7tE8LMM?LC-gBLvJF^?(COk70_^jt2-W5v7K;Ud2soWfhS|~SM(2dly^q2v z#*C}){;u!Z-r7EM_N>&JQrU+GBJ4y3onSOS6jc=!3l}1y>b284^n_Xs9dU;O1tK#- z#-v342u%pb7kf2eS6$HA%yEn(mT(mVfyCDlq+C+_p=#R?2wgf%-@L&2rfyfIOb)(z zg=vS;1N{u1%MD+jkqNFM*IFZ3A5|Q@wW2U^6_ZR~H$IxaRXxv_3i?Q*c8IAZ6;UDE z`AI%0!lR8q#KsyQwsX0ZRhfKei89l$2t`1IStI1Z!%zssfqiQ&Gu1FVRLmU% z@CY)aO&P_ejit^3B5S;;ntP){R0d*ID8mvei3$`Zt4BpKP7i61Dcnz`;y4p2f>5aEs^^pqznm#HU%4ZMgav=xR+L5oFE0@X0v2oR}6 zg$rs0k=Clpq^gD3Q13}}fI>y!jy1jtn7Cv0U5%z8KrNRE6m=AZ5Of5Q=Xz%!B4lfg zk|whDyxEonuH;WfXwO9Ca07^`vS56%=qQMABqep+}uDfpe%CG#Bot>R-Zsvx6DpWqw zaw3Fw2TW)5IgT_)CgyPdwGTvO`ISm32M!!SOytxg?ZXF$w$ZDPe59Rx&bx5+>JqtL zwzjrJZ5+@H@0)mj^* z5D(3N=gEM3N&<5UP&ZM6+;GnA0kc7+5z;Fj`8Bp|RXZ<<@GpytDF7w7soEL*jg0=` zm~syhN07V=E!!Dq+QNL9Nsdf_kr>IM>RVb)WaA|W04Frz<~wzTggToZAdYH0Aw0Vm z&Cwi(muB6TKdmt$h;w30)LWBD)ucttP>034njt2dEY)MMu1&p6(PHylI`*&gF;St` zqAa0E@OwiTT0e6T?<*;J5I}@hks!QBTMVqfzVEXDK5`hj(4Zv|Q`z3$e(+1b^ve70 zJAL}JdeDO=F?pl5N5!(~Z%3+Y9=?QWb*;U)F$rHHkWwFPv1iwx>rmCRJ3C+C#s94b z5z*13NB{b-{~r-~*0Z0PKYYXU{;8^(jTC_@<7%~9EEb!ao8kqM=?L|&)ZX$By~!OUko@XU`l|Jlu}-Q8O2sybjXj$^I$ zd;j_OJ{&yikDqwut8zux?m%edd8RMMWF5a+tpE~_)0v``W!%x-ix|9SInwZiAI*~qn4qE|jzSYc};bu&3+NtX0U!^br03ZNK zL_t(oSE^8GoiKVI^-Bo+SCjZQ7Yy-R4B99j7}sEp3p=@vcyU?lT~UZ^R|#$ z>nI}RxyGqL-u<3ijktgM4KMoBo8OeQ4#S47;R`lFZFcm2^&&Ml>aE9z#Uh6;Fj;BH zzslLOyM89Mj7W13eT|IdBGONNYLEP3fA|M~XdsL6S5%1kjyvx7;0Hel$09wUhl;%a zc5Bf9$aRNBs%-Du9){u6$&;V`+`Y@?%3SVNtKID7^B<|v=GPvA$pgS*u`n(ESAOMJ zc6N4F%hgzGt)r@E-}U6*;R8|=U=80F!(y^ga1WXZqN0&3yr(3e(~<4)O^0r9@8RgT zWw4LQ^ETRBkvl_@5W+LT;!b)uBOx#LmvD<7%6g4$1C`p-EGooMgLl8%wWaI7x@%gu z8J8`{eFp%e2yv^MEAA-MR@*UxSW{Z2;xl>@ZZMBZG8CIT<2Z7$bV`np6lzIHN--Z6VluG67a*wu0=nQ<-$>*Vy(UMF z07Qqc)zEO62vsC~rHF_;oXkCRN-42V4pl3urjftgFl#2FT1N|jG9=eQlh}MPX<&-% z=st;+$N~eX6fdYTjt0U=DIAkPtaO8Fg~307J;c1nhrxnRjlI;hnls6|h%ywGq+NAc zSC)2-N&%FKi@T8nfhkBG3DT?p(8k6ziG@;%4P*86F+HN~^P@-7 zRW;In0l?> zh*>NaS6_Yg_V)H-W6`4_s<{8Y`#$^G&mKE=%-S-JUMX>+c-*WCN z8&aU1;@w~0KXA{lI;E-KIhb8GBfx%Ze+-Rq7__5mjS>WkVAu4F&NlZdGa5bDd8a|=fjOy@Wpxy(> zmT98E-@R&9tNs;kp-G{tt`AU!GNw+)whu=X-b%Ugnn|x5cCsT!cs564RZRiWhD~Z0 zZd-NII>%?i24*<)<#;p}`*?m}W1b}2Tfnij#jr;Y8nrdQHM&nz#cZWe$hQzICQ!4t zHQ=7a+ZrC>uWE$B_-0+j%*3`^A#fH4YSzP29TMbt4}-nn=>Vc<-~7lAKH)tlPM+}f z45=xRg9Zs1Hiw%w>f)=fdgiXzP8*ZfFqRn2s$y$dN<8n4j(Cmt+vhe#h-hc$?88~; z`plWXL2wXNMFpDh*_(YQf64pAOGPWRr9+MdD(Zq{2!JbKmLlJOwo`MECqq6 zV0SlYZem&^A_Jtg%Jg;+XdG7xc-|JXiNihL_V7i`@j)t<`d}gi)P}g^JWraA{RX$|6k`=RsPtJRy;~9Z0s(UL!Bps)~JPqEUnhqhfGJ zKFb8jLKsE3kQ$;a7A$6tA)fC8R8&!z#0sQIRRWl+q7)`Ts&R+}T0K%m)iwjk%TQR# zTP3nWj*6mCWh=-;q!1a^lF!1*<;F5d1TG*_?@(h^A;MTkg=Gb>ZL4A$HUQ$H3gW^v zxJJmlsw0R{sBnRLRyKtylnBIyRSAQr>6Szo$h_RaF5o;wg4Hu7u*>GaET9-gNkLSy zFm}WrrQ{~{{cp0eL>d!H;!%sm0FY`Os}dMlb%;vfHCD-pRZ(S(^`#_sFHkGX<&eHH z-~Hr^)lmWnw&4u3-dH>IkU$hEXGK(XG=~YMB4n-#5#-8+nV=+N6;Tu_RMf%&xCjWf z*0HLp0L)mF0VF~MVcVuJg)t1QP$(CMDi;DTh{q~b>#EkORVv}DzvkKReb3tg{OQea z`lfGuQ7Pq*|KvXd7{}#e*htTU?r168V!g3Y7q9!Ksz6Digr$HgsDbaicfsv@9wzc_T8P8`WOT$7v}fAe_6+|3!R)XAw_roO5Kqee_r^)7e4MwzwFSVL&qL? zu!@YLmI1ep)!-GAjp@@NqV9en88#s`+)?ax8J;Pf8j`9WQhzcXB=!+=q3M-f#J5CD z`X@N<1Jpgx7UzJU3ICnk@T?M*v^-SL)X+f8qf(5Fl_S30U+tMkpcaD(g32AYYn6KK zVefi0?OYKROza^RNF}v$NlyoJ4_1|`7R0JbrN~$d(KuEj67vsWcl4-LIK#Y)B0XY2 zViH~zgaPJ)!Q;3r%t{2U9E-jJB)+5qU{94|YO9EfRsu;GiYIMd0c93tg|ZS+ zL8{Wk!fCLX+;j9n!9oInhQVc|D2REmm~&QD5{(=%T)2pe<;*hA7DIXzDllnHph8T= z;#8{ Vb0L~I~8D%5?**)njM4+?AA=hQZfL45eB^nnlXoqweOuDw>OR?=dbdB`KJ zNQp{WSpGZpkxd{F7pN)a5wC*GF9}Eq1cJ-3h{3F;788>~Ek}>21@lq~C;72z*e~{k zQmb*8iApId>0;)pDp9d$TqR+1QBhTf)yAVL$|)$AtT#j|dk`E~<0}=YW$h|d3P`mI zRH_OvRH;3ZzTDj%hGFOI^1y+E*FWv674kQK^EanXonjs|9BF%rl;cFi28o|mttkbT z%N>BrFt{Tsg%#Z?rmB4X^^4uz6@WYM%sl9N-F5j2?q_i?!)M2V0|$uc!V51vc<|uC zg9n+}mje(HPMFBiOls40^2*Mi5oEPLzGm)J1tglD?GiUb2?8#lC z3R!y>^#rK;E`4`B5^!m{emEwmXEzIkJqC=f5sA1LX--GO*1xLf#X=a;u{H%+h>)Lr zV1CHAWDh3oKtK`jVxGOlsZE~&hoemh1qQMrphmuXD+BqGo`uvK~4(Fl*fN+l6WKnar^#>cP z?6+u_^U~rLrng&roO1X0Pz2;*J;O>OnqEDD|Fq5ZfPX-6l&VgO5}J`=Nh)R>&gL1E zLJqzJItEK77uD-S!85EMqDoS&YfQK0=Cj#GV#Cy8M~d0jjTdeOxf1Gw?I&l|W{9u|A+&d!di4#Qw6W6XDBu~@8D6~H^*`8ELm=;|;3)IFaB zk$KJ7Vs^oSefQmWUq8ubZJ0sSd6|8%z4zUv2cZ7KO*eh{HBYoG1Iwjt-parDSO0R> zm|yyZU(%?h0ALm6mUHVeSBG&Nr@NXS(vk!;A=rgGA%><&#(rXG3ycz5^+kjNvaPiW zwWuFMLp;~bBxUA=5_BFnxqk~l1;k`~abilFnl(7UGgmi$nn!~>cQCJ3yF_HxF+~Kv z{UoYjtM$tW$i{v$H+YINJzk({HBzz7K*}q}akLA3OOsoYNEMCh#jR;Q19>R+d>L(X z%w1HHhBW;0dS{(O>tGr^p4S#tAp^eNRkTG+hTi6Dm8!u0I3Esaj_nOl`m z7v*^-XPgm`x>w8>B`Yu-K3^2>JVCQBd8Q7IDpsl~b29S`$>kg75Q7+Bu>-rMY& zZ~mXZ<&XaOKPR^r!$vQx)(_)T_8LVHoH1wr{{2KGwFws6Eh)rjcFvjs64s=But5th zFf+^^bTL5Es4xu5a>w<`y zV;X`aQ!_{v@xA(%7)C55nLRMmj>Y7)c&gCsJw7jXWkdzaD6V5MY87U#<0?Zx)U7yH zsbdL|WRE}~ZLo}ehDm{nfKm1{DQnuI7JHmJIa<{l-?A~h@nvJE$rUjV3d zQ%KCcrR~$kq~OA&R>@lsPK8>^VEMw}+yt11QUC>U4bLwkDnwN^w=NY1A+VwnSllY` z1TlbE`j|)t6wZ1`pE)J+J3I+}hUj!zCnX)qFbpx;6=*h*AFJik?!5D_ z>>d!&wTI27DdZl*ZN2{Vr}yxV`K90d!1ngG$w?QgL?UwX|>`-pC+=@JqYhJ z6H-D%i^XEOTr%^Mp7dW%ojSD|S0yq5jpJ$@)3@k+$4suT^T;`6*_)UFy6}oCu7BFo zOu^ff=3$p$Yb>^5JI8C(ybJT1kkY+^(Ss3A9Hp5%Pax4AG--~e?QLQm*~dMF-I;zZ zTmPwR!Q_`Y<1{A0D{LDM8MqM0EZq zB@qPgYo~{r;PB5*qD9981lAT0=qp`sH%(rrO=5S?SI4&+?GhR6#qNAx2jG+C>k<%A-K~2GUgL$=3P01IpXgH3ZxEigxv=LG~x5q@8Ms zSxL%P85l6qgnyVJNSp{B!c0VozGtfqsj=m|87w|By%%x}+N{kdv(G>4U9(Vt%mNmi z0EjMo>y>scyT)J}G3Z$vHz>TBns`xhCW44jxG>W&44?R_4;?>#?97=nF*3EgrN{ly znJ>{lEfA22Kum)fQ-~m@e!^0CXsIcgUNb(8kNit9G_uD4F>^*|{qMi@nlJg1D|U8vEmUf`9DnS`e=M*6`JerH^Q#xp3`954Z-7g~R>@+8 zP-`WWJ_rk>Sp%;}?vs8ZQX$K_Vs5JT91ioqx~hs)H!o~%82*~&Jt93V8a$NS3ls)( zG{;$yn23gN*$iIkAmN3sX9Iz7$9{1~fEZZpVBDVF3y zRhf&DS~(v0hPFiN=N5aFZ%Ls^M2oK8wyKpB>tSXkZc#!$O(K*apEgiS?QE^6quA~X zch2NF@_UDTO{Xx;fEOPCL?lq_6C*~%GJ6vugNAaGRoT*V@ZR^{YPYO`G8s&FZaqI*Iv>xfi;WHYTmmliZQkY5^(J3; zz{rrL$ynXf}>&kv(pV=YGv5xxB7FTe6JSJoI};N6>H)a|3ke2~ud`l7XBijgK4=B7X8y zgo#Bhfp-OvI-FQmZ?)@1t#k;1n59-Wl-xj&@Qx`wRH;OyBA!nd07cq6Ne|1k`H_oL z>wOBT<;#?+YT?0lP;Jp6>ec1&UH85)?U6$Y80Do6ep2&S@sVZ$o*g_*O?L|i?^dkG z$Uo<97l9(!)6;w9gIxTEeMsgU5;~F*TgoEz=QcGgy2sSS9!57-iK;}gKW4u3P7`}8 zT-c_I4G(_^F*8-QvSQRC^IPFwAtEXaQ5Dn8p=z9Q#~m}7n90_Qp$v%igri_qKUYaD zH@(QXiu&c1Nf|l}!{)|@s&4Pwyz8#J9(?e@E}O~ukn|Z0K^>9~)vfJqBGTGyBvD}^ z2Jb9)dnEmiJKeee+NTh)$C>6B-xH4c)i-=J2~fpqwff}WfAZdY@5N-NN^`s!aAV=^ zR@=1JdiB-+9+r$*!~irarMC{ROxheuv3;g+gD@TdZluM*MD!I;eBxDCUA5TSI%9mV zHGmh_y8B6yC*yV6UzuleQuaE=>>*u4LO+>agbx4cAJv{2pBzk&dmBCR5X~m}jR80H zPo5A;F<(M##;>kxG=BkT03;b_)Z38=?a-Uqp-$>pr~AtQ=<6i)%k);7E#c|b)<1Wb zp2%J8l-1;!0RfI>baW8~LaItsD4LjDv9S{IuwsjDc2sC?-14{+a^z_!Re23Nyl5;6 zy_8E^bfR-CVHp)lcBuQssC$(<>ntulfSY)oBMxS*pfM;HL^3aCTlI{${feUw>f}TU z^2j^g*Yvo_(=<3DU@LDvxm(EG^vd4-MGhGb#Q=_(5*1OHiD01$i1mP&F8=dJiHJt9K#8S|+1;p*-uS7LCr{jW z-+jS1Rh=x{!FU_g6PU(kGX)~XTuNyrxZ|S6NwdqxaTVWr)j{Jx>1Qt2@w@i z%?(LY^)#_WgJVqXC*%Z3(8sQdO77vmUs{wFLQ>+_KM{@P>nzd zH$O~ScXyIu7*dwHeI2sIMO*5raaKhHVhbEIxrc%|>X}H)3fz&Jq>WNS&`98bQ6o{ zIF9Bk)E^W5vuUUEHiiIWh#tD+lB=)2`i8H+VRyMy)p504t*V74Inb}-#q7jYOPg6$ zwT`30q%;61Av2eg3Xdal`6HstF6Vv)KO~!D0Vfa>$RrJ zDPG`7#53~71T=l9`tKknGgHOg&Pf4cj*K3$+o@^^KCI?qDU0xxGx=#d2fl}P#}PF@ zj;CC!Ohw^pt46jRgC-dc$7JFsvbrs5nw(S_0owrMs-8zIILK<`L;oVPjGXo6%Yx+6}@Z4ko zB1(?Zs!bWp**liv!FFi6x~lmEqQK876(9gTk`6#wA$0_4txK&VR0*;%6ab51*xK4C zg-@M2^~q1(ef;=w)!HEiYpc>Zk2F(tSS$dr!(?U*DG{w!s~M91fg`yj!NQl$Bf5X( z_x?7zM(@A>{-Z~aK5+kon1py(l{a@yjY;jDdF{0~pEz-1XJ=;^hUyW~3Q!mr=Ukh5 zET&^iGb3ZYG98n*_V0Vb6Q1z6FMFJb$Y{j?98xrMQ3KTQwZT7-P63*5Eo|rp+QmJ2 zI{o0oxX+4pjw=&OnViovy$erIY=18%KLJ2P*z?Jr;RMKSFk5qJGF5e+os`1Qt0^VW zc`x)sw5QN{;r=pWE&>|Bjm^4MKfadpv|f(Ywr{o85#Zkpv%1&3@92pZYVP@USvM4UKcI#E*R z)nS`AfO{8G^A&I)sSRnbwbX%e=wuTTit%3cVc76ziZNigLkY98X?M97>pr1AS6boG zu-Q1|XE5K=^NU>a7gq$PZ&DNlEnE!rDW#O5oIG*jL;v`8X19iLzGGr%gzJ+t41kHv zwytS^o2tSPg5*ye&9dm=7-O9evDNBffnz*(%(%N$Rg`o`aK%^Ek@%gRol+Lt+uH!n zo;_$EMbI>vozgHsX=48E@BHr0&d$c^v-jP1 z-%tM3PxjaU>mPZgh>YWiv}YSyvpzWvrMefh==MdZVzY)OZwuc^Jn^uI<_O0x`2!h6a(4qC{aAGx$AK ziHKAY(^xF02Lw=aICmkTtbhus07L~*Oup7yg;Z^%4m1S_h!)HO!AdF=%)&f?sB8{u zJ2R2Qw~w*`03`z;EnkR=xVU4cwyt@Pm+)K3xt$jb5vQY&QcMWiHnJO3r4*~g>=nwH z24-NvHf05-N*Bu>FvOD~b}y#0wkH6#P*5|iV+Kx#Xyyr?z+g zAW!>x`t<2x7)mM2?WWt!wmHvIfYjqo&8J#xg_$yE4hPYs?I21ufClDT7? zIdl5V|4ZDP2V9m_^`XDD_PO`_z8ZS6CuqP18+=ce;5W4 zJvcbXdB`FW|AmH}bBwysTMZap6@%n*t7K}AM7+XcI%AGAZYgiuI143?8>vux<4!~b zoOH;RY(66{JBYaNJwp>BWh}ya*|Raa<{wNcB9_b>9VL2;qner5uxIck6N65POkXm6Atl z@*4uCr0fa-7;r~OPyp*jPL+%;5z&wZq%IS)-M+@10a;X9c&FW9#O@dXCWN(xi|Fp5 zCNVM!sTiRdQ1Ngt699!r(xEzypg_O~ppngKJ+oEKKy1fkz>o&oGJVVLX*~oMX~5?Q zF~jsS^3!0V0u?D%Oog-KoCqb~md~rJ1tG%_01}R?kTO_%$nMgVIJr_`*84*JkcpTn z9~`Vw>Mp$C;%l$H=x_h_Z$I#X_cb<6Y&T(t6S|nEQRpaUS}vAokc%)YR%ct#>#kEG zK6z4A^_}ljBD((ijScMX?(XmJzyJO3KXdwYv0XxtL^B}mB0qqMlx}S;O3WX+{dN)Q z7G0l*vKXPgv|4>Dhfn`(mYP}?Ohn8ipc`&{>=jpBAtGnaoN>fl{1&siD648Xla@b= zlsNgf0G);AH~kqcO1v`dvj(ROXBm-cLsV-plI}Q2%ud{3l=_>#=)7sE-`B}ifHFXy z%t6i0B3Okgn7LSFcv@etO(S>~EZ}#XQ#TybxC{tiCn@1?irJI~R|;9IYh7c55&;*nf3p%NOs$Bz82TWR5Bb2DRtgHkU^<7kCKerJhzyVo`EoqOK zN>OzRM&ZeRXO58A%ac*FwgRFZ>LQ26mM+~u1ux?EG8W5vLZ6~$l8q^ zB0BkALhS$(v@zX*h1Be$@hhAHa3EE^&`aL<05O=x zqLm>h&Z*~}og9(E*&*H2z)|BBDF)xZ{hT{M58ua3pyFV9qtBEr`h0)|Rm!5y`oK z+wZ;&z|kYeT4CB8WWtH2M$jl9=5tzh;mAShid2e z237PH`my9m&0c@uWcG!KfXWTL`v=v?CP3f!DJ3I{OcvEb^N>yWirEhZl2}6)?E3@t zTW$)joK&+p)|Put^(=rk*aU@Q6dk6Od#tKq7(mG;-&Uj;6nKabbL$f^^szYOSbhY< zmCFFp1fX$=xk+OQAaN&d<(dJclsGcH*kfi{}H>b7yMrG4`&7rxP8D*(*kVzPm2 zoxVjz;%~EgjDz}}bKCChMAYnY&INr2rh56|=GXUe@nNh{#hcCt%dPC~>;f-<7Kesy zE~#@kZ;`y%U3xK$N|w4$2Vuah&0Qles*I2xN z!4saSs<-?p#}e>kZ-gZwN?lUbVaQCpwY?4CV1Hj^IDPu``#$hKB1ercyX>-$ee7fA z+R*g0&Us6~+n>rw@4C*;RM&N1@+DvL;Hw_Aw|5|thn$CDkgWZ%G6y9izo^cz4kT&F zsZJ7rVaPDUI*zREA|B|fz*|HJ7#*rZb{;?tjNWw%D$*nXpqGKmbsp5bgoYtgatETa zgEc%Um^x9>2wQ1WVKBNiXK3j#43^X>qHY^bVfJ(&V#_A4(kyWa@I>MwySmWHDOpgM zobxRaUW7}c1i#QT}cif699FAf?a3e7K z|K&o-%riB#=JJx=W-~=VJ`p!Z>P+M{!P8-MxYR?j4NP}}dC#?mA(3%24qeTPgSETY zM>;O+O-{yd6isX`Ap)Qt$z^7@;vZ0%U&AKWleKu`)0tJI z>k@MshSg%Rfal7zp-|~R03tGTC#&5Q3oyTwg6-E>h(L(XEivaRuXn8q}qi?6*j z8AS`Jbb_tpH=>{@J&J-&gvL&&C`vOVf04pELyN)|aF9!ojaXQH44bBFX`QXwh7k8d zFi#xv^QFbN#r$Qo^)__@#6qhYUL)SaV)@Vv7J!E#_kXQgaetZYfOH+W7B$3y+py~_ z>sa|<%w`ax7#A6-^GYbxJpiKa4jhg=O{AZACFJ2|noQdVPz~;!r_8{MV!!P4ycLOU zFFEK?mU(tI+smP%w3cOUDjeNxm1-)V*I5Umhh+lG%(QwzY0G_GjXB2lD-_fIbQ(Cm zvUT-8CdN;9%YMpEsU$vn7{>l}i5nu_ZsXVqrIO&$zG#N8`Je5SmU_xwvM<>K%0S~% zs(KF~5FXUK43`K{BL>uws6h3TZhoMM016c%?Kq{xM6_5gKJ<_N_O83`Jay_$szIG~ z13zj@D-2M9#=5Q>{ZbibE<`3KoZ6T*ExKpr{Y#Ro@ST z=&8F_xtFZ!xuQwcb&sL92%RdTSu=AorYoYNy|tdYr9nj^I2d|!q|ZY(@x$(O@{sMS z&peaNa!*MiLrTdknN_kvMaUpkA{um171e<#DLTUp@*v16ZlXd&99VBsxCw9Sl89Kg zZYO7y(sCi9C8{;2L{Ks-8+cF_05$&!#my5h>`1Gq5F>0Vhy*U}YJ!8zSu)I9-mV9c zKp6m&XEjDdRd5psS0zNxVBB?r*?FO4j6Y3ktaRrNmpKZ<@WaWYPGuK<97^$s7OEL)vC8)=A1>; zLTdrYgHdk{bVihrjk3FEJy{eDSXKgaYI129M3Ke0nOlX(kj)=bR1nOv;Q(DJ25YpWMm{ee|P|I!kKiu2RaZSxqHnc(9&=4wPt9hOU^99vEfP zAlpn9L$_!a5E@dPCTXrTTah?bth^{v0L&5Gwr}`t*||t;nW;_4p@64M&2?x%UC?*4 zhg4+6iq#fN^?KPDU5d`lq_m%T|&?=35NKUNm zlFa^KL;nz*!0h?sc?F=!IcxE~a-J>V)B#8dS$mO8Y9@H*gC)CXXc)9hizj`-lkd9w z&cFJrzdUv7<62RLDrwC1y;9r?Aaacvo@11Ju~@8D1CbddOF4b2dg6o&Uy*%jTE)JNdz3%QHs2v%Pcei4&?gSoNwh z41Ym=&~hPMMoL7g zLja1QZ3csLd_NuqP&sbszP>raOidMJt~6$i;`_#}%nbM}lU(qB@!mSp>;%wc#)3rK zvRTrLvD6oX;fA=WU09i|g18E8u&cV30Y6wu&f)_SE6Op|y&9%2a6LLq;0&=ZkObS< zY)`h7)(2czo=<`?8Zg41!W*u}(8XxA3ToCfL||ZV%#oua)yKi*f+khI&{7-6&T29Q zpYC#+$_8sTo}*c1amjCOM`O`rEUpAX>pu?sN5 zUjb(@Q}KNQ#I!2?!D@vb0KWBGzUA`EFVFq(ug1|~zV_MA+g}~%$L|7QS9m!~KMZ!C zY_1hyu;cPQm4wp*a+3{lkG)~f$xI>!5wifw8WhA%-;{&h0vm$7Xy%)PgFiYN|dpCX0Hs2Le1n8d0Snbt(a1WVqpE z(GuG<4=OQ6elo-gVrnrIPH7^PPzmQ%MEFt5)506Rx8kZYkeWT9s;0w41@>uXi$Tro zSRZCRAq8`AAjkwkP*qU5nk%%7o6odvToVzYKHN}TYyIr=Gp*XJ-zS~iAeXEy8~S`M zP5V3?)|4_LTH)HJ?E^a{RW!hX0wdu96AD<IlV9K+W@AzHzTB<9!yOEpAf1J$J`& z`#!VqRG5d-hW@iP#$h7^CWbB+3|Rs~5Xb=F2{(Q5GId0H^P7I-7ykXv19Q{3f0A@|RzB&R_Pn?j%9owA(VgF!d zs)EsHqm3yoIHl9OXOt{`TbWPu)1GURUM9PdLgkAz!F=r_A9eL7KU7q9Pw!@tJcyw$ z{V?>yU>Q+*8O)I#rW1De#H^G^Ma>z?tULTpi7o5_6BP=V5(AJt2q46%IP%oZ zW^fYJBd047r#ACrY(l#X2=Po@_%<=nl>=3%=a+YJ&s_AG5jdCJgnD=iHS7>&m)Rf~uYP{`2DpDdhS+MFf z1Gu_8Lz!wk@Vu2&?sE07LzD2{IX#TwTtT! zE(EYuO%P5MT10-9vK<&5h=5Fq0Tl(Q3|V*>y3`#U99(qKMUVT3k9+;=UKhxZHlsL< z;l{{A?}ocdwthvSeZMM1dd|=rY-BpJB0dn&kt0VJmt68`pZ4jTc(v;H_V#uy^+*l!r6mGP zYZPDliMW9YLljVCgeVlHJa43^1j0~g(YoLi(c5o+I zRHEC|3GpbgPEsAxFwTJ*+&Hv)AB4K(05rBxMy{9V4eIbO z{bJ9601gWXF$*_$2y}PcdTj$mL*rn4F&0GU-i9O>uH)J6Pt8CG;N+P3|i|0QonBvVU+xQRccN!Cj>xAKlX(mQs|{O zU!|Jips&gxiRtL;uOQH8EFN_CQ*Ynf+xxq}d#`%5kUCKt%7{6aePZNDAk2n(`;{}B z%`Z)Bs9H!I9p6#+Paz_@vE{M3lG@hEN z$=}4NY=p%C0KVbtp7+29J}8U4_Od!p;zTWa>)$s zuqhEZl?dJ<&^+WwsbTgb+_}EjVn)`t5^Tl3;hN-yl*6368CT1XMY4jK-8wPnY!L#T zvr26RC}-K+h-lJ{BCHnqegX(m1B8{t3J_&x5P9;E=7=2vC~neMCl4I**deb^bkjm0 z8kD?T{!nv2U)_;5cXG6^n$@gsLF1+^!iCl2u8azVFWX_IBy+|I0A&U%y z^uv&cJXr7~6%d=@qPZ^>7`;G6ap$A}WfO+o)4p0*F%c3K2|?X{UWh1JGzvF4RW|6E z$vjw5jQ@!U$XVm|!RWBK&oeVrWypptmQ7efId&-pjP9~ej&4st)%N(Rj=q`fiijxy zsB$W)h3pNzV;zV1aR)dcsL5(R!yK3vvv`IOf-~^1$%^pxyKtkHC`u42ivwQRT zbvKIcF~68{a&3<{{f++|4r_w;x%Xm`fXh~&6Fh2}>$#C$^Zp-=Yb@@by=)@#C;!Ml zoOo=ldA_4Il=e57D*)3zpd#so_v%@OL5%^%lnGL!PP^Y7T8$bd3=R;0P3VT?B!&$} z#~P;Ja(sr-ZT}OlR;mI*P*}8Y85SuK>2lFoMuMH4tyRDJ=tn>L=YRe#cqRvm+*xNq z(i`sVa+X?XV7zS0j_S)aL zO`N=C?iWg%kLORlLvkHWu@*%eOef68YYA+RA!=iP2k6^Jm zctXD7bVM7q!=;C7_UhViM^DhCl8RJ~D;b}KdTORDpb)ro>_BBs^BV6_ndkyFX-Ram zeQfesi+R!63r#-KSbiwKjj1t}lTh9yYF66Umg^s0OL@Oao+dB5AA;&7Z+w74NtGEE zmc|@YmdnM5pYXpv@{teUb=O^mxSdtHSUX=k7bk+k8Y4*uCSz$!^G(^lT)x*PCewI|rVC)d$Dhu^>x9~y z+|Ayc*2u~e0K`~{ZXj|fmf_>!iXsbFG-R6o(yE0S5U7Z6&GVM}K znfO)7R0%gZNvf&EIh9R9bDDo2=s-$i<96W>!xi$y0Q3jOTIe)iQ@U;Tm?JwIZf zyQ-#Il&{g`wB)XeUvT;O!V50=l!sk&?X{n|8dj@SKlHipdsVE4KIfbV$#G+&s#&rC zGMN8>rAacF8VZf*zL~ir;*v}^=WI8dA&hFhRCjm<0ET8Y-IG+6xlI08swjF(#Yn;; zDHKc7IZT4InKUM?9-O5;Uz1Yx{8ClT>q*o?3G7sIuT8K2g1Q`)X_t+^?7lA)X?oHQxwLtQlQEHUJFnj14>z>l;nxP*FRGHUJ{!g65m)fGLo9 zU?>wY=R`!%uIqNTw^PSQcaHq^-~9ClZoBQ&sgH}LzI39;4OQGYVfLSi%BngHb~{5+ktaT*`WW>Oi9gl-kTd}5Uhh1_oe;+MQJXPI{jKA7Y z4*<-aTgE}5nrmc}YK%if7$d(L-bMvMXa#`zH)|&-q#YnUo@fRYYhAplnN1$E?z zDBvoyz6?`QM1-&E{?gQ6dKHX|w03WL9yKn|G{Ww-FJe|2@ByK4QiEo+2m=Bri`5NQ zI-A2ug;7rskj=z%?UzmLKN|P9;zo0C`m+@8#so<5>f5(zOqHIU?!}qBNyUwKpAn-z@w}p^4T|k!#DlZ&;0Z&e*DMm z&#!&<*AFt}LHoTPKo-s_YOw~CM6-wtW-=*mbtocGGMPOZb)r*pd@2!jNrtS0g>zv_ z&OR-!q@_JFb9Z9`sxHOT7}ah|V`;ubn< z`Z0Yz3@tPQN|6ova8#g$?!Cns+7biT!@n;>n8czRmnQ4Pw6=Rlt3s-C4McTHsm`(T zu@qIyCd-%6lQS#jH6_ep?qzAorGF+R3Qo*4If zeR#{B=ToYUF(e3$yq;RsNfA1CJ#OrGj~)ZRG7@r?$__3Y%;U#0gd|prH>h@%Cj@g()Y;0h2Z zamTD_5QUm=nK5D_D6u;hS!OsSVPaw?wj9qP9@b8pn(C6MHPQ~p}se;XzHE4wsj4P_xsnd8hREtkth$6X#uuJXmg!wSaMY^6ieujEHAh9n65H7S$l=R6H1K9TVZ+ zn;07*j>Ww8ZP$}a{~rLuCJu z$oQ2Ibs3Trs@mtQs{6e9)c@;KKl$oUe$$)YWH(UEDd#>0OPh^lsO)Z&lY{suKrNEq zc79%z%8~R;5yQ}1uo$~6jB8t@)b+#g_aFUx5NRZ|ZkA<2U0RiA(scBcjb`xG*Is+U z@e4%c?z>M*&Z?fOuO9{xHHK*0z+ipJ=1;0n?BsH7r-(be5=uo~ad%6TP~}nKaQo0G z*h*~RyQx+t#*#;;@%)1(nN_ zLC7K^-HE^XM@00O|KQdSfB3^DL@*bNhjW>Fqd?ZG2&oC!MMQ)fE|#hUC?R$3p_Y0s z#ijg|QWM-LzxlttxjgaPZ+qLt$B%0pKW|o;xtjXSiY;L=ih2HbKmVs*@$&NPbDs5e z!{Et?vM7l9Y!M$xKz*MDEefNNGRdfU(O!x$Lfl-u#N?8Rx`nm0c!8=0>f3IsG4%(U z@CxhC>YNi3k+gMD-I1g2)nlcRITA%0I6tw^QlFA?ZO2_~=VHOcW9Y06ZF*piyUqWc zw_f65_#tGHHSUq;QNmq*%}<3k9bVQAutcIc>yzhH2uasOd_2!e*0YfHe;!uJ>_Hky z^)5&$t*LYEnnsaLXG95Wphb1t;8EYEO)!YG0H^U-=$z#(ay@*^@`>C7g1M{q`Ho}> z06Q`EQ&vqx0Bc;oF(o7+SQwF%7$P|f5j_b4q(-< zItV8=Ul>%5RR=|sO4tJHY6(EoA|P;-bNzgZNS6|gVRT|zbY0hVPye!~A3uH!!0FSc zU-`;cPV}qLey8rG^W$uk|M<~kPk6%TAHU#&ezm&muG7OXtcIK=OV&Y5A}65BS;W(x zLPW(9OB)iMRaBrJ2fOseiL`1KF@ca0OBOg>&cun?lqtxNONLH$C5TkL4T`)!I@{bL zmE<)4HgwpB&w)x%BV~_ZbbE_Ews1iP$HX5*v;llwhon<`B?)C>0j|FuYnQ&&RznB^ znmymHVJHvH>!Y7qY50!)04Lv$g2+s}J%%|-9}8WCiiewM)=IUJmDeNb-l@{o zbU|HAFJe;pwGB@bL>Mi9p*fOXb}GsiaPN}hmKI1lB`Ui2w9_v8Y0Rib=J3P`%%lQQ zfiRKC(2M4Sp<^CIEUV@hKlLAr=G$+-{p87$%v;0IGpC#_9mJ;nP~y$IFqzWGXTP1d zO-Q=BJA6Vo{t$7IOU3h(Dl_+ezq`BJ_k%hxK}A-bbx@;njMsMxe_eX%r4M|z`>uji&PelpL(vT-=8w#TBcj#re#JtRdkS)m2+t%MX0uwg|{Ls(t{2GBl&XV}8rl%E73N(x3egqNNufuS|R zj*IP0TTQ!mE{l~xk#DBH{^K$hJsB9;f(y-J*{m^F8eef(h?8-Xom&PK*v=y^3qV43 zgkxb<0SWM`VIfm#J9^f@`;!$fQ75WMq8n2?q0XwBe^*FdE)n^p5`?B(1!mu%Xqq!) z!e&A^h;Z3gY7%%v#*6F{$~JTlvkfqih?OMdaC^Xl_>()?n)eo0d8-j1Y*T5ZCbPjQ zv9i`fCm}yFWB?H*QgFu!3qTb8ph}s(^cl}gOuznXuL59L%)k8Z7yigAUOMz1UvOu8 zJLk-ed4)|z1&^Af>;{WBSNayzW-|_+QWGcB;*-&GYkA_tiHCj4LysIeVlw?-{Ka3~ zefQmKUN2#%HWZ2glb`&_pM2vDkL|jyU#<2JdJ$Rm!;l>)&k7LC!_=luRI`+jUhX%P zYif?7OjH;>_5?M-QJ|o>teL{-c7GD8KtzTcD&j7(o?E|BW@54)eY zuz<0e=OLTgXl&DifRiVcK#w_5ttk8?fX#KREpw6bK{8fDCa1S z9@@m5xvgPgn;t#aQl|S}l&N6aR(S6!KUXB(sqWgg)(i0do2%!OGDFgX^Rx&j=14kX zx3zy4B)wsOKnePpXtJQiAuE(kfn7wABk7i0CaEFmKq5oZ0aElii)hz%J3BiMz4~DX z2m62i=kFq>LHct?(tQ?~&Fy`nrXG5QnJ6ONdIb82a>C4uMQ5nT*4FaI8*g~^Ykob< z&nJDU>*N287PpyZ?;GuGZ$J9c*PT+`Q|V9dnp2X6>D?x8?Ur>rN$Y;cVSdGdg<-d%OtZ!Fy^3rVxcfw5h+B@UyYidDHP z4ybikO-Vt!uUhFzo9C?qWhCuN1jeX!xWui^$f$DfVS|i}IuUyBTFL(&kclFb!njrC z8l{DDvZl(yyt(;3UR}A(SiLW&;H&xPiG_evtRESgII%)kI(0N z@;>i4jc0|bAib&O`eNNVn-`+KGLvf>lHCX%v1BxxQ2W8WRDJi4S_xvl4jybbn3IS= zN6CN^Q#<_htA6wgKg0xrUiOv;WyzhUo!4IW&~(MayU+Uj&wuY7cieH?2XBK%1qsWb zFlU=jz=R3s?5PH7I6s_a4)2dbM0Cd;cYMu1{bz5u*<-}q`p#RsuFEcwJbh-(Bu}}f#c*$}zN7v^>)kp^RdaKp z-7?JiTa)kSf1dUG^D0_yTn;t*V2xL=fXfCJ{rHL<)kW^|*3MHi`;Gzj8 zv;A36t2Lae`RlB-V=S*bk()d-Z^cQfsO7s>@{uZqaiD0}6P&x8(Dt^VnqkR~$z}*Z zE$DjktS#jvc8!#8LZR4);?_#z#doLuW>Vum$}DA?w@4{$f{Bzt38WB)C5BZ?%#;!{ zbg^9g@-O||H+=oKZ7sX)o$X;*{n#si)T-Lv+L}y(Djlr$&w0jh>f;}ufBBRze5wU3 zOev+5KI4&}@rX}-_$8NI!eM0~szV;0|NQ6oeZN|*T4yNK&^83Ax!8zEpdBZhw9ov^ zfAHy_@#!kEzZ&u|tX8YlFsPs(hO994X9yS_&^(xkP9id77tGyua-Eq~Gb0sDA>UAA z+Usd~$~Ocw2C?z-S#212_J|PXt_g>O5m-Z_=R(KXx&i>@8rDBsW?TYJTz^ilkIU4W zZ!L_DG6{#m=%Y>+=RZ#eHPW^bx=8(QZ6#BQO`4yaAXN@KmBe|S%-t$Zu;CY~tA%{E zyJSX3OK*!dtz#NYph#I&^h|%k?$}zBlKK`wAv(dBpr^V zkG1BR$}-YV43KYueqTo-kei*EzQAmgCIdk`W+E_CV%lCVQ%XBKTie^)dwZu}``X_y z6v85>@Hn@NR;Avjr9|w)h@)0Zv-iLM{quEs+OvKRK#36(ud7vd?AWo(uekinzx;my z`o8zQ?{|Oq_ez>+@5V@fFI)`m25W(sBS(&2a>>OHdGJG2@v(jw@*sj70pzoIQf7-? zB_V4|*rA)>z>yJ`uZ`K)BTT#)4w~@ETzT}IEH>1y?&o#1cV_jorZg{ZroRP**kFWS zi2s@ZRr4=KYf&H4&4Tx)p6LcBd zc-;AO>cH8T>3%Nr_RdWnp297YKPU4!7u(lU{m~QS9o4YM>BB+N;(MA*Z0w>ynTt>W zl;b{nx#1%X&ZHX-3@Nl4v^sv=vQ80Ww*8h_m3<=Yky%+YjG&MO9Hj-&607lxvMzzOA0YJ^2yYywf z3=wCi!0c3HY!4(x_Hfz%?8;_Y-*Wss3~=qbcP5TTGT#B!5`amG3TDP&ws5goG7X}P zOi08Qo-ipr>p9=FP*9&KtrDl_f6t3v{-Zw(VE^FY$k8K{>A(v2vZRz0di?nDhd=z` zkGbJ7DJ9X&M8l8)48tHffAIDXtyZf7pxd-ejbfPEBed)mDW$8gzWVWx`<&CKPxt+B zaIjkSea?BvIS(p|ENr@U&XNJqi2j(>980rCuzJ;^Y>#GO4UFEh$J~<5_Sd#drA%ELjiippBt3LO^*CzQ9aVr7#MBYnu2(a1-|utEBBH|}iPJNl@l`qZH{X2o>C>mXE=gnX z>|96Db)ASZJKtO^79zS>EGVKvT9V>Ps(DP{(Au~*vfqtB``7z`ttMUGeuF54*@E?5>u6P{4XzjJ_m%|={32Gtyd^U?J3->$rEN`nCSqt$)JI zOSN1Va@}=PdGG;OUYS>`u?$@)bxMgjspd1gyY}k~zUKu;j~@N$7k{t)`3=wezxzQ% zq|YKknK~lMf-EwKW|b@=!a3(W=qeAegwqt?i*-j3>4wovO&_iHL}cAkoDZR>>jSSyBhniwtBDwa9Zd!g&&65BaSc;1ovgOR6Lq z(TfNeTf#&iv02WT?1H+-s)iC8t$MJP5PypS60T0MvRcLtvBZ1Pw71$7!1QO==EUF46OZZ?iYtA{@qIL^g z%#;|aLQ24(i6rTO6=^1A9=5l(UiiWnFPF=gyyQi@XLcu3aK+_Ue#)nO%H@||`5Ui& zP5JU=Km4O9b!2o;JY2%o*7DhFCo%D{qepML>849By)-eyVD!NZRAlJ;EcxB0o80RIGdWg7n|KwK&2I^4&$cWVOB{@Ql)o)_QJGbG)_G8#Rjn+|VNVoID^ zlG}@Uh@DXjMTb5sjE-WG=DL@ln)^~)V;NLzH49eBu9%Io+9@K+CV*mHiRoIDR!a4w zIPpZ(1a@>3c4VcXiW+;8EOgh{#%j(t=QF^ev>Jj$?F4e{w%PP)qmJ8doJu2ed8RDl ziO0Et%-nKo{O3mD7Jx}8(I*XYxr~xr|6Wt!#^!W>1jdhqlpd71=or;CT29P2V|}VXkYx;PUqjIyt{`xK_BSOvLuM1-BZNreAr7EqkK|!6$ zH=_@2->SB8KNM#be|GDi5Rv61>ifR$```QR-}#)+`&jNSfQNMD<# zLp?E;7A{o|T_Wa0re7&9Egt8e{LZi5m&5zSmTMk$V-57$5)9M7XT1cg@!;Kkwnsp$&+ixWKQeWZ4nDoWEdZq z0*A3KsS>e8tTB9_iAadq@=0pnOU{}SFBXeIh?IWjl|S_D-}QZ2^Y?tuzuI1Q-C}X< z=+W=^u5YmlKm3u~@sZmnU3$Tbz6Zb$e*a6C%cTLC!;n|~6w0yk+^>C3*LCirE+Q&A z=r9a@-{+hURtLi{y!EYb%{jO8(8B1<7Oh5@Ip@5yv-7ksdHT-I&OyIg9pu&OV6_@V zHD?(zL?M)jC<{a-i)I)WLy|pF-Jp`Q7zwcm3VErr!e}sTCN<}8&zWR zje0nkvQY>=pRxua$<`hl*s_l%?70Hl0P1*O<2+8W80*#Jw*Cxhe4~^AhFY{rbpszY3ekK3L1>f-gOpOl z-%_H~tbaw)El~|qN!$QwCgS?Xxk$KJIfCUH9JizV{FR@b}B{VUR%2oY}qj;!7^R z_>;D`wvQY+a{TzQ?VTfwu47IhsOW0wRdsJ~f4N+2nnWW(mJv@?ul>wNU3BrCez~Oz z)hzO%4}C}?%XC>)qQ=j3wCH|fIqaby^~h_9=wm}32Fp)sGQ4JwcWw@KDwS3jNZmgo zu$Wd6Y_?alJ0fn5SB5BFUn)BWb|%Wkh&JXb;Oy_|BOaAbn@NbHG%uq&GsF>SyVkaK zev*Ad%f^+=zgpj3R5Cin>yY}%|Le@+*OYRS>;MXORe>IpRvQ|(>*W+Chj!)XP7 z8zwdG@}VUp!`kh!MzeOCjD*Vo2xd=^k!3XTvnU3n^O|advp#Hmy0W%$+^7P1w?^;) zCaA}()85hWmxl%q)&e2unperGzQ!$>R*`$&^ESo`%_pxp?^M4c-+ENobi=Kc%1Lcj zW;|K$X3-J_YK(R38*yA>`*O^Km`|h$@FF@4nNuPjmW$<8S3UTD9l!AO>AO|cV4B7> zkJr<*`0QM)LBe=u>u`URF8W6Xgyft}n*Y3;J|DoVf9=2YdwVdMJFaRc#kkbzGiU72 zAO3+Kz96OD{XGER^Ib1E=zCf9IcrvkLY2gK6brH{WzANzWu7*^8qXluZEd#|%GXAg zI|NekXJ*zV?L$%XNY>QZR=O8uV|2H*T{1@83QqGfxj3CacFQN+c;pjYF1X}!3-%nF zBBZp*CCmrjW6oR7KFE!I09 zp4an_fAT*spZz{q);h6mEYr&zv)BoUS_1?h?YBZtY5E};{kRAIbHusOa@{?@I;KOE zb_%gZtDJ8dVa41I8L440?WkQrVhf|l@TA_?fDq;>eLB&;7b*wf%YO7d>rzd;8V@^;ZFW--}=P zgWvzs?d=^P0S=VUOV@QE%Hf(c41=f+eSfez$V0yC?z`Xl$A4U?>*QTi0{|F=bj1}{ zeD3Fd?)LW1!QR3C{{F$L7m=K05EVr>7#;9DC6JueBl(IBB3VR5Bd3z(5EW5ns%~^m zOx^YCvgW>YbD8d`buTtBdOWtdhWorQ^WiXhJOfgkd?!pM;5pvklmhD%6vi-`ioz=h zSaeC;h>aVwC^sfV7Jx-U>~gWr(H1j=V@~9-COft(f-D5TZekihV~I1&`nV+sL{KF~ z7PrUA`9Z(!fjS}Mq@x!1fUptPBc1QR)NnRXyI(6!nTW-1V!V9;zw|94Uj~zR{wY7Eh=uv~?4N1>g`rY*b!VH4h+1bA0 ziYp%Wu!r4n!<#{WNUmo%VLf%{slWQGzmidU2wErMI*FrTX_sGq`2!yCz@6=#J91W0 zGj3GXECNMVS1(l|DhiV9Wc#QAS>h6StFuhn9OL_F^_i-gw;JDCH8)-^e-_wl^YVv= zUjeH1NH@kab&k-=`5`d(_3N`~Rw;2#f%xD$Z)nd&0&1U`e;}$TFgX+#u?QM%w>C|o zm)A308uh^fo|vMUXRH<3*3l)eq}E<$pq)lqGpjQ#XnbDwv=O<`g|s09}_vG^MWapcqCq|2P<@GrF$|5z!rY-0`=6^Z)0Z z%_zO^`zJp6N$o=qe82-%tCa{WgHojB8=)`&e)1>&pVj`}?%qL`+^^(dbui>S^p>$y zvd|#ND#NN5_fg6sr+WIy$TX#(8(d{UT!X zw5Gqdthvyx@ET!7k&EJdE-cLrjUzfX5|ol(GrI8@={i_t96&@&m$zHGLUgo6O;tdk zgfOzTCGmivP$+JlAt~2A;mhqxJMJuc~_l6Ao^ ztM80GlBT!Eb?eTD-iCR(sfT^JzrZm)m z6DC$vfj}e(i+{lYK*CDOHCj0g)PUHBM68;bc|o+bwFRK-_*MVTqxnAnMK4V$EmHTA z7k{UH^Hcxk=Tk~s+lwRH+h6%lpJ87<`N>Z`cI^18U;Up;XJ7FnKTgEY{TI)iuf>~g zev{-Zs*#q}q4I%LROQsEQ~Ue7e$AAK#-cJaN3>=CN-z|)TvYni3K*iT z(xNsWCO?g40^@$RfQa31+FjXVd&@|zgQ-O}(CPwKCS*gQMYp{C$}0kene=L+mbkRL zwR0@Qw*WS1@LQz@b6#qylbwx=7I|@D1wlg7uubu zQS8^g?sX#e#po)uq2#VyM^GnRbImmuU35{mSe_CYhCB>|st(x=7DK1An^6;QP-4W0 z;)ut3mk|?pM4R>aH=|=a}%Q{TY9CF);4O| z+8k19PHkKBI$}HJSF~=S+O3Epn9ZJ=cdSU=>z9D0Q$`!ccP@TFF=r!3-HmTGKQ#IP zpkqB_(@QkDna~Y$a`qiQ?O|nAW~@f_Yi*v;`Ag??m?)OKZrbvqqda4TeY8T27b;?( zxi;voryHcTwvK7nTe@9AsJ0%*MO3J=6flvhFwtdidGKP<5hx`B(519kq@nNM@zA$= zg3-8)uoo}8?6Rxhac!5<*7kOn7F%13lse{OwgD!)yi6%Mp!vGjzxL&S_WHBV@A(#o zW8VF)zZiyLe}6yc{FE>GV*BkUUistS_MP7W;Id0E?fag>Qo3Bw-Feqt_TR@pu6+_Ol%Gm;pspn}b7l3Oo%nMx; zPUE#yP*!8-${=Co8e1+TT2<}Xvhk6S5Wog25a7BQ&9iTm_RBVxh;HlprfP|hXB*^C ze&;nCD!C8J<3H!gzyEu00`QQlA93c)nf?6((cBrdp~6roM9q*fBhGS$U5;kS0uVDe zEjTeLIwnlX2SWJA}WH8m132@s>PmS@ds&-vRM9P$qih?~UJR>$5 zw$k>zX(>DfkI$vl=d+7+7V1+(G7;sR*TFIC8*09k89=jPMCZ`svKCgfa5|&v$W6gH|hy(4+fV571w zM9OY&0tT^ynL)ZpUDxqqvG~QG`;p1OU;46tvs^BgU0N)bi;e-=IlA-JU;R(Y17H4S zU-|0SRL8)znU&t~`Zq|&$ zg_fRLiW9Vg=2)5`MYgMJ(V9Z55zRu_={CdYa6b))+-VM@7t=YKahXg4XpM!WYT;d5 zbyp~<3a6ym*`iyEm`{riiP$(A*=~TM26zHUBs&~-%OBf-^f8YCpdw1i5&49a^Kj<$ z-K2eM=S+sKKtFifZHZY`2NA%+)|mwfsoFPYQtaLt03sr}3Zu0eC=*1LT zE~@dH8Q#qj#3oC}g(evWumQzV@{+^-@os+m0`aAM1#DqWXIb-7pqNF6bw zOI?>}XL~!P)Nx835%cz9*>%j!%VoE{wRPsqnP2<$|8n%`(IZEW?Cc!b-r72P?AY;R z#}-|;wY^QC7r*31^L0P@w?A!JFA$X3t|8TA<6#hy-+be5idZm5ZO^E|B}7D&RMk!p zGe6=HkJ!5OGLx=zHdsegkyWHIIJanDsw65ZswQ%a?zl7&BrpCeLdCr)=XAo)<*9K@ zmV1q@oV`8&Z-cj~YIBV<@_t?4v$N5<(Ro1=1F#^r>b%BiRW-$HK^qsK3U{@mHtLi8 zG-iA{vsgeSdF?<;bIo1mA!DJn&zSh6W811CpCFX0HSpItEV?2G%c#Af_V*F0UI@I- zknvIUmgf2vEs=B&P^w#a#%SXE^FZYec~gs^T9$oc9COygM4p7cHAtb+uj6@kHL!fy zZk6%2@x4_;#7tYB{oQn(!iK^5Xn{_uFi+9L&K%D62o8NeUz%kAp zEnduOwQ8;6O9-)YYzhS|K+F%mUBRfnZSDRdt@$F~#1(r4#(Y0F~!LeX6ID-*Bw?*>5PxvP?{I?5g8AzPo7 ziQtI~p-P|(A_e8#6D6o3XEH%tKxv^_IFX2o*{=szDQcTe*bjgPHEW8aX(ddZj(mEd zs%+unqMr7ir&d0rwsU|6<1X1}p_xU>p=H8i3stgEq|Kh6HqSazHvuTu{ui!Ux`#5t zD8>GmqQXOXOfyTfAvg~aCUCj?wAh(UECNy;dZwg0!1P{)8JQ!mi23O83yXPv>9(CF zQSDMvNY0tTAWFn{ow_gK8wC=x0*Xv(t^wW+1ql(kPlO8G{WEEtWl8`+se=I7KARLG zTw;iNX*wYB{#zxt|8v$r}p z$T=UZR+95-wc6d?m0>u&x3{;u`>{Lj7=|H8C=llH02s8hv-4S>^;suQJZ67?f3<(G z>ie8Uvh;Zn0f8;#kY=-2gk%@!B}-Njg*h_0vS3CQH4VokfsO)5jkqApj)KJlmKa5W zlJ4BdHknxlK+I;@0kxpON>J9mRN{)6HRtt?roG%JN#l=iNV8{vY6uS-zmO7sSQR2v z?c$Zd+A}~oJ2q#z;7J%X^arQUoM}ZRYwCgvF4$UjtNqh^dwWAaoY^~b=Jc+pyyq{q zOX<;%&ee@e0c6;4p-{?DRfrnG15PP*$)zw`4i$23)&-mrf7eYF%;uB;Kw?)+=(7`2 z9o@V5PZdRns!}S!C9>h9@noIyxkTzV5kXT+#LdG@k81CNI7Ri|h-Kr2>j?F3e}>&? zeQQ)qtW&?zq&!c58}h9-gBn5PWFad?a&TCPXvw2q7@7AFO1Z!7{qGt29_$2&nTT}R zEe`rYRaChn9NWRIw-OQk%D=;j69i_Vq#^`Dk$O!9BRY2M_=Oi-hrC!Uj~qK% zqFb{flcUHMqtBESiQo!iNwSrAlp%#Dy$}##hC1|JxTOf|WANSqJ5E(M~ooVaURY16_f%%Uw#O z9YNFX{yuYBblp-r219wF-68={$p=K~na_OI-tO*u|L(o-`tx^fZEs(=zrVk`w_Gld z9y_|Ty))l$fM+1JK6tc553?(FGy0zQyhlbCSIu4{vdddTVYia&6 zSxjm+?|-eS95rlVM4)D`tSZnW;t1wMHYu%h z2@Z8gH!7xZPi_R)7{?XWSBjn;I)M9dC`Ig~BA_;yhNHmcdj;HKQdJAGLdX+`Q-}}1 zc%)K8%@n(PyMCr(gOm|WKdf^&Ej_G6iJBh^^;Ft9a>Va~G4YzQO4{3(I(DL_yGGP4 z_t_{OKb7t^a6={P3N9k3@uD|NGtl13102v$I$% zR;!)u?d`7XwzjsqE;(C*s^B2^hmYi57KdX_pWfZy-{0NcedcqX3E+pm|A$tq{U7+g z@4fa>kGk!)+sMNHi7@l2JMSzn|J=X*`3nyY_V-t-z8|vYETTN9WiZ=!8Hod$>06|?%CuXz4&rS*5>9`MM>2zGhv{KsA=+q ztRS@{CHAl>d&554#v=u=>JI?i^n{!8zNg8}qJsimHw-KHatSAA zfosUU&$;)$dhbkPK24s?vbKAcSxjhg))B_h2l$F-;h7yW1AvZrj)f z+H|)&j0J6jO%Gwa0YziC!+;AR2?r7ys-7^=IK(VeRVq}&d-aBU?>T#CuC@Bd%FMmb zx%Z8#K|p>|ygK)sJ><@vxpJ*<4e4JZ<$ZZnm64C-U$!7%IY4GstyW={^HsZj#@B3^ zAF7DR)yAsE7!iPZ@bJ~!0RWJ53MK~E+j69Tjv!me9>3&b>2j4dU>f;HmpT*^BUG>N zfQpDJT{1%osxDF#7`=w4SL|d0as#af`?&wmT?*!NLIEIH9*qcg>g013v~C|wnX~W_ z%?5^+BM^w$Qv@?}muop-N}>>$`QXV%?*G|;0RXT5;(NMo0f^mV51EN@y%mzWv)w6MBYJwkm;`RlOn?iU<**DG|6`p-{2| z&7Ax(GeTdRIa}Xm07{s*i7_*xEI-|li{i|+4WguZnk%Cv`7i$ByNsX@fe{v~H8TrX z2!S($ZN#(?Vy6H7NB-qv*)h?d`Lpl%iGTfL0Px5E_@6v|`sN=zZalajHN}`j*2Az~ zuVaeq_4?rO@Sz7E#2ni-(dbsTQ+@l}-*NKPsbL((7+nafxG3U8XbNUx2BNOb`zA`6 zMi-~i&D6W8sAls~I%i}`p{CjVnm7$8G&~p16w=`iEwgx$t2i1S7D?gg#(VE)`fUr8;7w2RE41jY|n>_Z|<6cy!w8qS2 z7)Fm?si9r~`l2s+jmVlbk&bAIEivlH9}on(>ouulV0)($V6JkZl8^#=j__pjn+YNT z0lM|YK6~edw2w=HIZmdzO_+-XIE`M9oD1;jbTd_BG9ZM!u-dj}e;FDb;PO`8HRA}A zo*%7HDmflx>+!P^w+YK0R4dEoRhaZi;r4$oZ-7~u9mkwpq&=dV`@nUY6G#Xq8rR^Z zmk`15uGiwnKVEcT6+{V0YCb$I8&C>{czEf_!~OGwD3aU(;$irG>2LS*TkPOs(i3Sfm^(jU! z7&yBSCNG<2>SwZujxy;w=gj^2(VzsU0hYeVC?8y9cftqiUWNI=MU4sa^ma;4$j>!o z215}}WMm=<%#;~`hynn{G4Ac|ec=~;;S-NN{@{ZT`sU)}n66MO+)9C%3Mp}p<2e52 zZ~fLo4?S3k#ZBaKhiG{E^vhoMveTzdAC999Ly}CyczUUpTo0#Rps=56ra2DXc5=~} zt=nMj?(Jc_d63O!-c}>GC&kQDbrePLZv1L+Z1-*42#=g~d0gEn+GEP?XW#9_ zd6W;h_07@OQ@Yqqt;{&M5ZdgR4WfZV_omx^es)k@F%S?Ji)H9~+%B^3*CBT+ZV%ZF z!veOKgKHVOrTJx9tDUg+TArSua)?gs<7_>F?cRez8o7B>j26Vl-}>-#?|ZQ&^D^lWSQQw_eHT$w43b(3 zMhLsRd-vXZZwUP0gAYFT*kkKq+>K)hp&u5@}A((@M z{r!V|062HRgMdZ`3NxK0ot8o*zKr?jWF^qN2mk{xWFLZJf=Fb=TvsC|P?vY=qtDAdpeZ4! zjHp709Z^gP!Bpje55Mo&j@vu+0<}U+s1hL}LXmWNjHVHC6}>u|%=2KtpJXbR<%*;f zjh@`&T59M3fXs)0foLuh2xf{VXo5Lk8fOk7FJ4pbt`pNd-zT{CD$LgvGeD&Br?UXt za(Huzog02z$87yM?GLi~)3ml7tt53EjviwGwTfTOllO5{S~uZ}t86Wca~;U-cXR4` zoFuiP=T&i;He)s!i`T?c)6fur%@QI50vb7!fkYl4QwmjTmEV|0WG$IAPqQp8@=R>f zJY-e@K?M*9$&*J!g{V$r1M#^>341+@bwSe zC}t15l=n_f%)c59isVU!JZ1%NWzhy4Hi|x>0U(}t(|f|5r~loeZwB0`qbY)}9Rvl5 z_`%A>9Bi1DYz~O*)XKLU6X2o3Upr$XBJ3XN@&!yWXtT^lGa!0v%1(%WsBS`%22iDe z7;St1em+wcgN3VF%5lYF4qKjIrOX&s?XiWw^~to&Go?c-u#p~Q@ih7P{V|dQGiZRA zy2w(uHN9p;i<%HPozX#^{wIqR((?J!M`TGX_FG~^%v(O1Dc5*xX{}~XWfpo4 zY15iyS?Ba7Z|pO)%DZ{#2pX&w!*5^(4I?DHbnCm2QM)`u;vaPej zImP9b+R$;QH+j`Px}4P$7c1)sGunXRr8Y1>zdUE2jJ-5|W5cbMyY6O!!8ZHZpoY*Q z>)RA`NgCJ8$pBGgu8tHejsk5q0`w~#s7NB)5)Vd`Mw12bk?;xxt^vQ@JJVg?kZzGW zn0}4KFO;|(w&jwukZWX zmyIAKf&(lrH$MUaVH_a3?5uR59+@G`%A-h2uh}o``jD9&SPm6dyq%rA9YZJu7m6bz zHw{zjLF0cJS2c(BGJts|47PHyEzCdhvEXicJmlo#zv9(5OK*%nbu5|BSz0rdi6j>1 zX!+m#i5@j4Gj`HtuVw_Hj7Jt`!;Ru6dhM3lZCjlZD;&1x#vGF0H(xcTM$SMuuYWky z(c0!`Tp_#j&KtaNe?)Of7R2d}L^{2qfje*gHmLmKUnDkCQ@%uFUuxlv@)LaMOOXBC z6`@TvYW(nfMMLHyXEB)IxW2Uwr{Qvk1UD?d;DvOkgBY%(034~ub`?8+d%hFXu$l0# zN+Ggj!iW+J=L5Ko!1hz7S>e0y98`aipAM~~)sVR%dzOLR?adT8oHBJ6lUG26&+Z6= zJZ_QuFZTNC9pTk4*3Q$1R|s`UX5TP`7EwBx7Eba^UH;RxOCeyccT^6~F=<|s+h_rrGxBvmU-*A zYvnZn-89rTbICu+g;;2M7>A|@!<&p0X1mTFwq_GHkL(}kIfwKKf621$WaSbX>izH- z9=gmP%^l}HCjR~Jy}ZnW|UdIUh!gBe`n4DNmA;FGFYKPV_0wX*a?162yyB(ead*csz>V)ekyah8{Copcwi4{>gcA;i6kP#APEc{WF@{d zPU-1PF>ofqCbl7omK-Z4F4DwsX}ozMeVXIIAAGPNE+Ky6v8suE3^aHSqI{aGT?E%; z_7x3HsT-DwbYIu8*l(Lvyp2K*7?Wj%S{~)px9*Te93U{-V)x!uSL&g$;v^(x!Pyxi=AP zKHXO|mRGGvY9?mDoC&vhb|h?)0$WMLN|m~;>p*sGIoPd1jAHO@7>NdxgzI+i>|)q# zczy7Fi+>Nu$xx4GH|boB&o-h}2LUYwVG+t=N!>9%o&U~wx<9@%gW3I|PdAw}yn>RU zamgs)uAbmMy)-WOMz(i9(c<+s7}aViqdJr7;-`JLapeDXGfg{u3195(P5Jrw98*1x zxM0!46jj9r><|n@a_V(&~SMxE$vG@(LkT+${}%=cgwL29mJ+;%luyqec z&bH|!C_mBLb8-~#HLcHr`g>IjAF}CpjWiZwIJ?P~#ir;eC0F8I@~=dlwJ{oKh1ycv zMZ>#K)BWt|iC9m&)n>Jb>W{s>GZv~F(UJnVy_E>FGs>SVu7aUJG4v_LBB@A zCHz4#q%-@#S>Ibqcgj;`Y)6UiF)T0$taa75B+umqU!Wz({gWoPqQV99buLs)8R%;g?##p%%)59b~) zGt2AfV+t4x!@|5F_g&X9c|d!+qAH|#7PleB)H}$tUTMQ{iV8OzY(HYILsL|-nS2eL9eL=I4J@L~%D4{oG4je5FXg1~^ z5LrQmIBoED9S2>%3Oc6!_x1R?gK4D9lqqq8H<7(eC5!vte#nC^Ag_PNvOEM2wws7@ zUjKKM74vgGz4XxJFV&xysy6=2tjzG&3rF+-fZJ+rc+Sz7-Nk~>U<0rA%|LU@vVun4 zT(Ilf3mXWUsiwPmBf_n%rp1wk6Z$TfqXM~g$D&frY%J3mvoG`| z%t7q*mqvaa?_0=7KLZ`C6r9-0Te-`Nzs*9KBI=b|j|b2$PYKcdO9G&SSo0WJLn;x) z$~5g}NS(a-YMa52drFB{ncuh5S4$-^FdV%rbB!P{U$bjLHS1n*_z?wd5$Ri#B`&!S zUBUfciK(s*=Pzu|GdxRxgDVGod6N?#>#K_t*t2V4_{ZM-#3^_`UU7j~huWLk9>a8T zfEez~3)R1@ehWUlVgU5)X$#9j(S(go2grj!j$>b605ztkTb_GUZevs|jL z2@8`Ea&Lc#^_Fw@o{g%S%itF_7DLlNwkY8sQ<8{>|2YMes=W$AR+K2{1OuAdP%VOH zIAQ+NN*0~vtXD)7%=tVD|Z&pr!mK0P)ckL*wHklF>WKB}oP!JO( zX<8~Py-P?dCDGQQN@eTGX6i3xQ2HzJ^l;yDbVnMpKJGY7-^Oy5a{VL%=s2x4dnzip zbp!bJzVD*3QDtY?9a|v+@|d)JX<2$1Mas1IW@Ucaq?RE2_Te@zw2jh=a&URsq{X|9 zI|9_!c~le~?AU62^r@|NmEQ1zWB5?0P!3%cs^mwQX(IBpX^6fnlf`tW{8*F}_$&7= zd}kGv8Yco_7}N8xFr?_qAh{SN{y?Pa2WO4YI%|5d725RK2@^n<{93=Y&UI-YD^dg# zfCWh{_5kyApQ}lTfSw7eqI@U0jh=zfVT$?8h5VL+iF zZ*M#kTJ}t7<<>KY1hKql@=&q?)iMm*g(zWN55?}++Os_Kaai9EU*;Op@W&3eSIyu)@kNnf31#Xf#Qn!`1lQ2Xlm$h!1@(rA={Mg$DGD@x>r3;f$}%&7 zI>P*!sSlocZF(9TJTVBiZ{E?wlY8slLn9XR_iLv^PYLB_Lhjj0g<(d^kNuo^9Ud>O znjL8X*BE!{;TK{4Ej|j>uw-{eCO2}ec=`wt+>LMBAS_-_RVNH;y5Vp8aIG($%fy>T;XhYj`;oWGz zsIJ0>4wtD=UQd4GR*_W1cPEF3Qn(GudWu5{dX0NafBh$t;j}l;yowHVkna*+!TU*)|Xk-Lq*_fxsJwPFU zeK&3)aES0J@WN_oBbB7O0s2 zES!SX?@6Ixnff(~o0GiV>uI;{K(`No=F{u%DM<;$#zsZKgi+|Cxv77X<%_STAo%ns zfIfpl&Qalkl(^C}#RjvN;Id9)R*51l)xJa2CtgPD3-5^mFEI zb4x^@e2BI~V=sSf!FE=zw>-oKr20j2*fZHTxY|5VEmvl#Vz02Hpyb-0=cnKHq`5rK zo%J#FN3c}JsN$ygbl8z+lgYE*vyDuK?c0|feg0Ip$L=k^wqi1}weo3se`7AxTna@)$=C#U5$4kB~+ETHu>=Od!(q#=E!q z`K_w$Jf+Ft8bxcT*SVAH%kZFg9RzfaSBey{0kF)e?zBw+(bypOV)8QDl?bSar+sSQ z#kKjk@r(fzPzYmH&qs8IiSiQyCmhqVB*T?+)~>cI^b&te+GoUp*@2|0a@W#s-C1=XczV_%U@^mubbt=x#MPva;bcjWlcb{eUF7G z!JF=%@kDi`fwdReGvn)igoBOPa%pIl?Dkm!H?NCV{GD5nM_NMCRs5^l-@o*G`Fb*z zIrixFZ40J~%mjZ!SXmr|Prb=;yp3SSCMfJM=C>+O@6id{os(;+#KN!%bf#(Ai{f$_ zPaVE{41mBxq=Ko>Y$uKD&YKY~kaj$T z#A*qJLu}9N)0KTO=8m?2f%*8O)|8(t8x87b)rfD{UJU{#yuHb+;sM_bI6F{^s+B=m ztQtg4Dx&L8zVNN!r)MY^-S>E}1rFL0VNd^_ha3$b?;0#!TS@UgovZ(wcbUdS-t@fmY&rvsL|ZjCJ*v ze8q3)l~31!$+0qrs#L&B`xFz+TK5Z$KO=pD?x_r5@#NDX-z-W4tKujf6Ns%;#JVk3YA3% zJY$sAz|fSn<^}SDfHG(pAKQ<&`EB_olJwx7*DtBEquu;e=cn6#l|Bhv*Ow9}yyFc+|R+Z>7*LGLWvtVmY7*8E_L37pERP zO<4`VC`U?RoJc62%+&jPJ$39;LA}SXI|~%XN%z$Z>N=X2fDc>sUb5&djm= zQUJZOtUM0W;G9611ha`#--!jAE`a#lS{kCBIqd(Ip80ck8?FfY*@;2}k&c!2<|kUu zksvehEMoS6ls;UUln{n$qeWj1$Lu5WK#-ih)lEF`-humqXm~5B7lI=3-@BEatg=imw?m!ziOFhHI1LTG3pHV(RIZiV^#HT|Etes_OkHMmP5hBt+qdiI&yG_*V2 zs}Fl#b=xX4UL{v2MctCDR)HajRo-D!5!shinvCnx)M(d1w82~6Ob|MztMu1`2kmN* zHfO>#(ClCN*mLX&+_BETQyTihBYBE?jGq&X+nPaaw_F*%bZja~Gx!augJ5jJ<5#v< zN#p4?Q>(+O`b|Uu(EWQS-vvQNMJ;|kD;9=H>xfdQqFt;5Hlf++uzux!KjC1j zR%5<%iY(-kjsHQFLb+AfeaM69(+Q5$(_8-cv^2pp@4G1hk9!19O}Q>zq5~BA8*iT0 z3);h|I<~k%Qn6;Mb(K@l>Dy+}LLP0C=Ha^u^#NAOKkTJ6Y;$@%MZTd*=;HFvXq64!Ho6eprLuH)hxp%!o~s`C zeWwKLmGdM;k@fYB4qHLvXA1rlaP`7_&hg?`u?6qhUo5X-)c18yql+&Xt7=zO9Bg7C z5slNwMe&bZC7o@?)JHZ|aWHtsD<$`}X7%qxm51QQ&o(nzTdvXe{7w7JhvkHOb}tvOoqBOazp42b0*F2Z4uftn7c$N~U_Rc~T} zbN-!Y0_~Qn}t~rQ#GF;{zMn8H2cw`y#{u(H^E2F-yWW6ueMn6(PAj}j5sNX zZBaEE&P-)O`}rr*e=aKh=7$SvNr*k<;6;+$653kI2cjTH9olPFA_KiBuGzR6f1`g!6VW9{O<*l zj5qguEE&PSCoSs#I2YDv^r{?nBR`>38pO8aC`4srgQDs0r&S8htT^GWKMB=cNmeyg zN}>z{zsl->+duYcW(Y zc0`|t$^rT7jiM`4vqfXR6+>VLm-N6Je3r3%6=jpv+M{+KsbH4!YMg2V(pk^!u0hcA6AE1#soUfKNA_@dcum4TJYsy!7!(m{DYiO`$*Nv7kTP>z9tezi_flId zDA!LEe{AX1K}-ii&@(U%dayPTXZk0$YZI`vig?J8Ei18Xiy0 zZ!_l<^6(Y~q5E2CS+=2p@4mJH9KZp2S8w^{WOExyMYEKEbO5_pLV4mzfhhf8OP6bm z&_6su`M8X9pvmul`ax*J3p$kt*x;D-6I0fgr=m~WEHZSZ^wzQoo|06B~K?XLtJO9WgUqG%1Cr|WVIT}x2E0tuOa7d;A6 z-q#W+`A$}+{o}dtW7*UG+|lnjtBMdoE?Rrq>^{54_p4Dv)zxQEIktS(I4?)a1+tR`MvhKDG^I@2ia9RU?hDD3WuQI;^5xyCi?LNAsqm+?`FepFYk+>MJZ2Q)Q z1%S?ZnZ$3%c3TzaFm-OnbzfYJR`~d+J#4B!Rd?SCcWu4+xFhwj&Vx#o4cS0BH+kfr zQ@iXxm%72hyck`57-dyoN!N-ksTr)aWZ+{-V7KQ3E3w1(c@ve^A0NAz(n_(CQ^oJ* zN|0Zgj4`$^{WG*=Ft&{;K3l1|t$|FR?u0u|ev?P_NL{8$1sxq4f|$Q>H^9Q+_OVJn znJUuO!vW8#b{#rdiqo}LuOXWQ*d^K^!>`D(lAg1;N&6HUR)CVX0O|xBkx)^%T$jYO zawXxKnSZfX35q=J{0I%mvL-zX$RUN>WiNDQ@bU3S&A&>D`<+d%jOCX`&|jGB#40Pt z{I~96%+1fg9H1ZAbmmt=i<9KdeaU}(bOdvtR*)eg<)eur1m1V4Fu;`*K%^|&Jvh6A zZUz;7$oy~z8-;K;3Q#f%yZnI3s+MO!U_~c~_Uo&nm`F(DF}d9@{zZpRuuxuCioxAa zAZ;UVF>R`nqr;<%paRI}E)3uGJ|)Ym_jHq}9Lqjx7%wk>Qv^tXSq8f9`kY+_11H0;xP3NQkqE zqJQ~dQf`i{5a->-%lMiZBlzDmZf&(M z#f|W|!}Z(omg>6?ZrI-}B>oMW$>>&`m(ZkqH6Y!;WmF~bUCMnuzroAuR<6~RhTG~k z5k#UFhy!q)!5OE(syG{gE&Q@~Y496V-eOdpVmh&NG&aV3?|%PtoGR-wPaCTDb0u%| z;S(RO5T=RgE2xYAc`+52&$Blp2kx;i0r2C%Q0D#NJWOyCo*XS*Y&MXn?ss(^&MP`_ z+uihKXA&8U8u&SPp-bg+HV0K0!cm8mej8CIbOXxY{M@KsCzol)>BH->kj>W_!jau2t8-SYK&22I|`h>HsI8S$XNHw7G}x^)>Eo!GX0aN zZ_g4g5vuW(+K%%4Fp!6{I_y+D8KBL$JucYZ1)PqrP1xbd!$Hyn1ZT7UbjrhMuxSes zdQg$Ae7N>NoCA=RoJ=7UNN#Nu_+?UW3aI`ag{H)a)97BKzat6Cprd`)dVXHbcoR) z40br(2`|E{MrXOnX$h>Yd^|*@TVm|p{C2r-?m6_(M(wSi9&^<`JtQ9AT%q`O>VfOC z3iW}Ud$W?K2dt>YYj3g)Mf(B$@TVX*VddZ;Vn#E-qE7^uQDk3}O?!zaR$tng%hQ>I z*g`)8dCzjY&$#{zuIM&Kby<)9O@Aa90KWuz2_!ncqx|-qf9)4I8q^WalwBLWixGpk z3R;b%Lolp+iUN2iL~v1-uq#r?L(FGr5x>evtds!_yLYAQ;S$QY^p$L|^7OF+srtg_ z&!ZV+nnK?waMMZT=0Wp2^&JH$tmUal;zcU5{0n2pW(FC*<$?J5eega>22u7v-n~2O zHq)^2da z93Otj@|SjTbGBJ_dxN>@51uMi*e8x!08wx?`nDb?S$^948nK+3dsED{95*1cR?>)CRqj-IM;p)bzXA`gcX7C*(o zP{D|(JryKdi{S;*;;Rw!xE3xDkPRmrv7i>WTWMXRAjB30NLTq34~4dIyUrzS>^g=a zGES5JSz16hcyBPv?(fOlg9(4g^dW1G#r8RwfzY?-!>Czh(x#I)S9Jq?%{LtErLXJb zjF67V+%y+QVcxj(r6jbvaj8A3sY{+`I9YrY%F%^jasVi^pzO>TI6xy28%aO^wN4j;$iTZ zaKk#x%$G0G`4`VU*ZGz~fZD_Ce{XT^0RUnOCCFPH`<_w+HlU3gw-<(GvO6il0N{_R zd*cPpF{Cc(ejZbG@CHD~;LR#>9@(@bgEg{+kD+t*N)*>)I@Aw0DfY5R1sqfL8ofA` zaSF>)`TprhMZy^i3zEQ0dOww|Ke>#DJpA^RvBe9vROBi=RM!<2Y{3a;__;qcWo0szuBW;G0O2hlV9@sDR+K?z96 z5n}iyRLAPUe;NA@v6qz5Oc`q}CQCsg<_M-qH)#wjbV3=Fo9G+(4a!Y5tsw9P<}?`VT*}n-Ha9e46ThFbg?gecWK>9bhAjVLSPJU==UFdus%nyZ*D@ABTAH z(>yk`2nV-P&aGa4!N1e{4pU`*`H%n-pE^JS_iLO}VlRTvcKvPR9{6Kr>u!v!}TTr1f^f5_;Z5lPTU_&s(T8BU{C$kmDwKt@!oic6uOnxUnqdUU@Irszp;< zjlMa3GBeI~tUr7H5L5SK!ErI3&1abvGkfop>L1)$IqCHWXLhMXdY<=|&)6CGPKewS>Ec~%B5;r+;>5D4LudD2fvc_yp+=znQ_M&G3ChFP^-70Vk-mdtC+^Or;HxSO{SEKKLujCiFOX z!i`$u1@xUfT{L1U{h|r+! zlDC5v4NU9_?B6XL0pp5t`!dH8ssm6=hp;)2&fB*D!x`M6>wHFrm(K_lh&RV@ne3bG zbz`cI$x*I8sOFn-MBVYd)YZ0>5N@x!3Dj8J?JDNqM|1$pDsT-6NA+pP^8Cyx2Gpe< z>}jWYy8g<&8TllFKgOH$0*1=~E#`py%-^e`lu=N0FrB4)9!|6)p$EeTbe+tEY+k)_ zRwz{ux%(4M8?0!_Bn_M?weFEVl7<$8!rv$X%q42%B4nRCgn2AfJ?%f|P0{8b3u8zL zBh(6y=*ytMo9`K^k3!G2k0tE+5A~wjC=`2Hm-TT=I@?lbqZy+-^+BtTg8}eOx2^U` zU9cjtomj;Fb5qlXzV|&A!1Uf|q&wF}U6UT=NmlXOnPlnWgNRTUO^9vK1OPJW z-40EXjxb`~!%T2K0_9&1K?-}*i9LEbk)Wp~cCZ1k{0Rr$F520LQGfH=DnFnLVS*lQOF4;LSGgzyzn8 zxl$@85m9u9E;DglY+7LPJ`-tE0AYL#Gc!LaA=3*J03eB6zNhXW6&6c}I>src|22%Ep7nKJav0`i%!2)&E;y zr3t>78W+9LPe7KIr%uuo0zFOk+toaXrWcwD07xBlj~3&?fVEMp9D{ee5-HR9K)H5REqQIISLWO*Q|FXw|DnSjG)(Ap z!R2gvXS5LVRrioW`Bg=WP?Pe~(1$5HZS>)Tt^#j3W{*I&3D3O7Vf~${P)+DNp_)fc z2j<&m#w}91l&0{5%N+E@?`5C#|EXO+b#e~;?CXO&j8ZjJzN7$u%v}i^b&6-CkL1p# zB)T#wU=lV$C3(o;@88@66vg58m#Vw3MM$73|*x#)Pt^ zf|gaXL@-!^;b{unU{5B5S{Aw%)_40dLLM)Ztk*#t%1Rk z&Jrr4Y8i1?yl8qB*X@g$j~S7WbqgP-4*2yv_^4BT<{t>~_b2i6IOa+r zFX!c%jffuj-sZ4if^R+ zcE3~4&2sW)0~U_&=ZmP5o^o4f_36rtAO<<*QgNNQCqGcB;DH8;}5i zO$d!1X?Ib>)@y8*C-N#!b((QH%F!Ni)`Q+=y69+H0%a+7Ek)CjbSw`cSAA9_lvGyy z-PT{ir0GV|n`)v8k4jg(b4A!+(*m%{fy|Z&z2&=GPZ_z#WPI<1w@(T>jlCy++0&sk zGc04N)gnW<4D>MJWeb4NCT$dO2Rzn?DXkVx;JoJRZvP11{!kz|$R(8@RFHOw0@%m$ zP62SrcjyXmPtLo9(Ye601;} zMsYo%#DZpwO9jc#+K7OlT|HjTs|Gj!Qa?0)41>c|i!&Xm|%zfj##Yxcpz z$rDMOhYQ7hV>cV`%bY(IUhYBOHgM(CWxEIHIzMQaabyZ`_&IDLQ-3joXZQc~zeQ{<1D!JE%UL1ZTo?IlS~*i@sRl?VG;S__@*x< z8^-;IZMa9hk}{v@i`!*uycOwT!M_Bb_VIaTvfB!pz?0kYkS;{bQ3XHE z?FHk=r&p`ou8q4^Bv)^(T97R@I1{G>MNKc>oc=v&}dZ-RK;p zfJZ@@b-^1&gES$=a)ekz5F&;xwD)T>roSNK-hAaSMH;{F5M)hxc`LLd*TG@Ir*qI) z+nx!{wHy8rm&Y6QK?|*{9ULQXTLyj+Rd5jeWU&Bdsl(v za$~#Tw@oi~HG}0Lfh+n?XYQ>eDcQxb@!;}w9j^ZDkv*p-x!i~!@*-IN((~fG;K4*B zI+03%F6p+;BzP!kQTVDi5$fnXf&W+>0zDPV{&3{S$bQay0KB$$iX7;X@3nRNBxLga ztl3!5UhmS^tp95H01O)xdU~Ob;{4A@@u-X#!>QSkl!2Ew#~qU%5~JrRmomv@I#!Ls zL4M~bYlhHK{>a+&X*g}8+v-SQ_a(8OOuo6K!f5+N)*L-KYeD6nYkxy4Fc+dFZC03>;|VF z#A5s)O=!hCY2B0wfVk&^Y;xllq3dY-wYn~LOBp6&u8rp&`!R4Aw94WNm#%pqN)+8E zjluo?FV8ao~6h#-D*-yV+6yW7v`ie=c#A{U4(juVe!JfBsnipNDZa z%2!jr{_k-TU;O|7H>#qxl>8{_E#UvidGh~Wp?Jan*LVO%dw@4YqHNol|3AO?|2z$0 z<4r6Hu^UqUpD(C0IwWeT=sDQ^-@}(h!z113v)2E-p!{JuCDW-Hl>cMo%TtePI{a^+ zp195S)w=9|%vMwdp~Cc4 zG(8ngs5$G!&P=GpF0uH*=_Uvl!o)y$D%E|A@}Wk-u8RfBEXx$IpGf2(BKlTG>;=Sn zyCP7Az8D?}f@~s2+kcQYcL76df1Cc9kj!m2t5c$npxDSDXg5wv3@W}$z-hS!W(Bm) z`UXikH5$-azB)nVXq^?nDucT+4?+?{;RnbMH~;Wy^HBH^6vb|MauVJlz>&d%ZlA+o zFf0J1&*rB#8-D@IO#{kC69@=-LFo49VS4ys-0&vX{X0GYaVPpX{fMHEABee#0zH zEAn@pB^jQufx?P-ab-6w^DS|i-7D2+VhZ>-zB$(=Nmy)lHQxf8wNQ%SGr!+3$`ER z|M9w1gcy#-Te*2!bnZ{xF1I)bU1a;Y=)byP>o`9s2;RCCtd8oOvAP_o#f$*$?;y@{ z;0TmBJaGes2*?j~*WAv%#|tnbT^%LYgme?YD1uJ)3|Yy)=LB9#mxG>afA_2kC392O zcDTuK04Eb$^|*vq@hI$kgF*(2{#!l)fZ?-I?UF5T_w)`v`T4yOahECbvPEp=LETm+ iso0@Ne;^^D`iYh&qqO-Kr|lX5HI(GkAaye4;r|bsQ60$u literal 0 HcmV?d00001 diff --git a/localization/yabloc/docs/yabloc_principle.png b/localization/yabloc/docs/yabloc_principle.png new file mode 100644 index 0000000000000000000000000000000000000000..0d7a8294babedecb153e36f7c0f93496181e7def GIT binary patch literal 959680 zcmb5V1yogCw?3{YDlH)$N=YNF#5oFw?(UG5?hcVWARsL*od={Fqy+>-y1Tm@ev9}0 zzW2N1-uu5}{Lf%8&e?nIx!0O&&9&xy<}=}PGNKr$#Hjb~-NO(UgDKp*_xRDhdkT`q@j7E1ri>?;*Xt_vGIF=l33dy!StT=yg2}Qe#&|B|!b( z?*8YwGi$l@y%+b8{x4A|*!O5^{bnqxmHzj4{Y%%cC@?srUcSSH(WPFPAR4)*B#+{D1ZQUNoJ@qyI%Y|9O>~;KR3YmNXs`mS_K; zs=R9rltlEujOahT)cgOhByx77hK7cM=YMx_&gbb^nMuEpQ`EZhN*?AhihmTO7Ja9*?keO* z$afO&A?eD3d3~Vx!iMrMnREliO=QiC|17B=LQ>$q(A7%w@4x0c2SSlEu1joLp7)+@QQps^WjLae{1>FNP^ciiVBA2hIj=ic277;ES49{WF&xF_`D zp2Sh$flP}dka_Q6EIL?%SQ8OH&OuMq*zfco?@q5p_pb+hvSff76>cB?IQ~nGO2b%w-Y5t+Vhfqq_?_5a5Y&VFXzJNzO-7871;b3^Q zk}ohyux#^Q?(N)*yXBGA2yL1BXD9V>e+jP5s5i&{E&My(o!yHKbvyI@$~({%hQZpN zgr^Tq@fU>Minqy9bP?8HOs5cpVLtR4yVG>=B`Nw}EBLRGobBAr=nhdU(Z5FC2y}PR z%FTZ2;)oW#M!>_;=wiBiBb38BTi^NMhw*9D4-;0g^wdy`@x#$eSGm_Cr|-b*csA%Z zH~%f+&Uo4-=O!5jZm;@p>s|I2&JR~vb?RNt50;&0Jx{x17HbKEMA?57irgd z(v>&IFs3F!Z@Y#IOv}O{7i))AvzQo!lbaXEn-rc$1EO)PcfHP%jAPOFVb%J9gwWb^ z!3+r@VATmxl^~=ms|(*2_|^fbv5~LtaIyNxo1rq;(c>fW53FxRc%8a zV!zr4X2JbV{XomCVCp~@!)H7WL!meOEd|9X?yJeppsQf=noj%pM!|skz0un#ZuSD> zbiK}h#dECor{1Ck^USzxXT|AwoiE3MsXidF2GZxj%u?ty@ZQPSqgVkNPlq=2#Ifqu zI;?|bmYQO7c>QuGu;-DKl_e7hbuD~Y=GhkcPhQ1%W_RR8&+|sb(o0pPZZ=9XU8Sl!H%Im9wMc@$qq<5<`|ko*Z3m z?hu4nx?PVD8OhnP;vI`9Yo1bmUtizOj+L}~U0GW5?@4oO>(jwpTKs~#(o!HW)Snd1 zUocIH;n=M~Cg*Ty_=AF?pRKKcQoayv83{UmNW0#vH3!~|0n-w-LWY>K+6gsn#O8K| z8k1Aqv{?mtPq&4cSv~@>y?p3vp#n|h(oiMX+APx$oVR(MB$Lyu_nVswnUOKDwk}zv zVA{%=H(4ZOU}%_&frTQf=X#8|c(krcaI3huYI56($pbR`MQK7)oxU|aEiDa<`#u^R zrl6`CIMQRtUar6p!_CR5q@tptq{PX|IVKJZ(GYn3`ZYiQ*6C$~&aPk2a@t_6o&C$# zTk=h_i~H!9n3xzCp{5nh6B;JM?cXJaXJ>aEcs(Jy&!5`VO+!-q7x#}&Pi4iju3B0a z7W5fnH00#ul$4Yd6a>@cej2jFVd-*o?d|P`>@~T$L9vMi!6C|>?fHv~L;JSGTcTtH z1rlQe32{6s>L1!E<>cqLw~t-;MGFeTD4;hjWVYxb8KU9jZ|s)#=3C3uNK>$m9Gsk- zjEz@*rwMVWktT&dcwcfGHdbX#(P%}1zee9k4z`AB?^`dA2Og)$Xzz0x8eT)wi?1*# z4#7_2=I-9EUjn1d%ge(?^#^m#9$yF+M`>wkQIQN2KAL|^em(~>Duj{I9zyJa4;%uRF`pC zI~)#|g*MnNcblZRio|`-$jTB)FQj_4WApcq-8_Qa-1xv;9TZ#}U9QI*TFS5~Hnr5D7pOsDR?dfgpK4Gun%{4k0UtJ^}H>!t4a!5o>!la+Q7 z-Bgi__E2-{CZ~g?yg`%VsWX!go_5;{@uM=SUWdOfDQ+6Hp*2qX+t4Kb<3NtMn;m0a z4?^CF@sLyQ&xt%N^-c#vdH$WSxT}lQqU+@Q(~BRm66%uQIX50!5Fe$Hp@1_A$p##Prp-Jv!v#GRd;9UPuB2KyQ7>gt-<+ka^lCge6^e6r&eKH6Y5c@ z-&0{vR>2q-^?f}WMGGo45Wp7oUiqPCcP(wL5k5n?)+*9r;fa@Ws=IcvlCih9*Vays z=!J;Uli{J#{>(&)u=$qLxooG-c7MaJrd$J&U1Iw!->kZBa@#=zq0*pZJ-8{lx#46x zW?)y-sc*}htW)e=;#<38HtU>FE2t4 z85vQ@Q_|4Yot>EAjYwP^GM%zI{rU6f+}yYRRkTOGgS^QRV!xMHx2>(nNlA}f_^GI< z1{sE5C33YbOF1|^^lg6oe9o@s;_@;g9vGs}+qo~*T7u7in{x6d%g{!FJu*}T_t#_J z=I2pec&Pp`${2it5Cugez6BCoCqFM7+=NJ+L>%1UkPv@i;lMGb#9reHjn3}1`!!RG z`$-HxMNbaLN(_KW3x|uY8tC{0cu`@vnL_YQe;12&et$WiVCU0ZPtfDK%Hmvv0&Vws z@VG_B%f{IFk$`YUJH;yN!tbM_a*>R@PC?3uAQgg<|Yg?%PftIGE6ibkmQg$5H-Vqcb)*>PKHRG2AW zb;qe7nvPhO zAl!t3nd~WQXZtcAW82J*RoVFG8|XdtfrtofL*bm99OvB`&$%BybMmZWe8@D&{84k&*FX+GQ;h3 zsc76Y#@nNT8hGu}%Q)ewuv7tZdd`%KqXN~-fz1bw=bIFrJi%%wOCtLHeNa!wf;#?7 z{hbLke4UL1U5}d0j2;y$Dh4NAjqk@KiU=A_a@~`)?e|wbrJdYM+@Di*=mel{p5ORA zmszc>E4RAn(wBc;j-J|4=;H7Hik&GNdk1YgHXB@_xLp&CNM`l8=&%tUvbIXSitu)4 zP_5lPn3_UJx^MhRZR;DI>kyT)sxs6p$y167DCi9y)UDW}wwC zb+yal?VG~dGO*2q1AceSjL!;5y4c-l2)aWXDbplek4{q1?llj#|K%#zDmK6WFRrr8 z9E5HlEG!Io0^khyRoX~X7~)JQ%+AipFbL}UE|DdmMu!)?v$IoF#NsdLV<)z3=c=ol zT3IpNZpm^TH=Qcn+dO{Kk{ux3}SF{9ha#S z*G%cXO8TmrPK#-xYANmQd@3gFA1KdFhxhs9q*jY1u{YpAoJ?CAl4c`DN4UA;^qQ17 zw8M}cBSC7Aa-Id#J+oriysSoxC3TeVMGU5jDjz9k(=3#Jj*4btXlRHOpN<(%*T?Sz z*f2CTNfgq-(Suv_=3PkpvfcT$*HkbjI{KESStJ2ICN7Hm@x?uScdi6mh;>lUc$VC^ zB)Qc7)nm5^5@DhYj%7+)D;79R{}myO65A-?z=a<(uyt|Yl#|%!t==m_2i{}}YSce} zGR4Is+u8z_4AmuqnP{?J(D=W79)#lO=|HTIzWBLRPc*P|@lAXxK@p5VZGcLR>1jr_ zY#YX6v#)NqXy$WUE}|XA-SYT(^>pV(;zru5*Ul`gujwJ=9)5Hjcoc6mz9uJ6*Etst zm|9p^z*r*tS3_Xw8yjYjR9z*dHaaE?Y1zTdEMl=tZ1|EG(e#%nW^pmSj*dU3<@h+_ zFYqT9^`m$!#&8J+Q&U7jgEwX>hb40=XkOCL(#E#6{Z?fnSXz4GFNhzjFd--RJWQ); zXWT@!P!0QZDavPx^a%P;CVq=Oj)MtZTn%V~I_l!XkQb!5Dc|fHf;pPT5+e(eSn^#1 z0Ti=(czk*q{`vFPRE<4ONQ3(+IlqgIlheu12&%j7Plc0T8*lU*Ys1kWMh*^Z-em8s zb;#66Z4Sb+y7J_COlficfj{OsN`qHrmGjfV;+aZrZ~AdX2^DO(fWN;ZOkZ7{C_?P2 zNB5?5tcmQsN66Q^0Q;&HQe^NjaY=M=Xb?iF8>TXXREP@vX547ms?iScR zv<%*#b2;GYukUb6X31dY zG*yeKs$}Cn@%UW&4pY-d*xH&ECk~*BrW1VK)Wb(dUrC6sIP;U`(iiPI#bMz}#1bBx z8wbkDq3lE%)cRk##(L>E){ki$W>j@4z776jidCj2F3SC$t0a;kUp!i%l;7A00Um)I zgS0|k*7t9;kVYP;b#)f<8)@I>Zv&>kjP1o#oSea_fuFWV$8D=a8S%AdY9H0sRHj4+ zs;0bbz$V(ZY=G)Nxm`KA4P4W#(eQ4=2S_(x6H+;= zM@UTEGOYZH@aXb-5i+Yon~|Nl^e~i{pP%%}!;a7nTibK$c+Tlb67)x4EZ*Kw3C#BC zwZdwxFY)RM3N420U54xtVwnngNIo9}k&|U!;=s`#WfT^E7EHr?ACa1x8W*Q3C-((> zNlesKQlh3~N}|Sj+K+-?)>JmQd7SdIw>f6*6P`S$Ik|LFCt_`Di-`rl)t@RQoG2v| zo+zQEKU4Q$y2<+%I1|6ACa&k2ea~!dmfcp@e-m?ZFNy5m4`luIRd8T>dU|S#DME|^ zd>9#B`N<>1nELvy#iY5~JIC$pruyeSVmDL7^_?xRh zFSp7-EM0ujyU70Nfu|mmqobI|Dg}FUr%uihd$LEa)dS&BsKK{+k z%>x4iAgbHn-v?2F=j90*zsnv7h61rDL{vCEa6C=PuhCfRm-p+3N8HpDc*aM#mDO#7 zq<9(TZqsxQHsDl%4-XX;75kIk z*h8DT=F}uVgN?->(?A^3^q8g=*w(^Js3((nHI{Q!>MU=D)QvpA!)Pz4OYKr;-AcF* zI)Q0NGBizDSXu3``qIcki1!b@SqaiP538bR)7Ls~3OeYO46)fU#s2JirePM{Dkt0OClA?qkzXXmm_QY#qV&teH4+yRYSVW@Fve*=|o_11Cz#v0^V;uepEE_r!B_x9e0cvCVe zs^}Cg?gyaIWCuLTgmDpvY9MwtH_gq=HrCeO4$deu#FS*TQsH12Wop`&`ZBHHMa)^4 z{$`A++}U|6-J8;a9L(n3Q+O?B)I3=9+%ar5c!oQ@!2X=!OkM@L1)s1T_H zGYe7@5)wi}n;I=4AtAAk08)^7P0AM%;)jgh0URYi631RLq@c>VKD(pLlf-$l@)JUnYP5K^{Db090@rdPw-e5jgsCJi$~4Ez z%99)~*46!lu`RzbwTib-e|1^O$^dT)#8DDi-KC}Vwk5)DFFxtdEHmbBgPZUS7l`e2&+LoNyi`Hy}w;0F0$M`rQvF<#AZ`B0* zc5whU8DCs~(B5lqqQiH1bCq;v@Mjqt8{53pvpQZ_bJk-t>aZt>;(D#Ju-pY{TLNx?6qmg!BL!Lm|&l?bXyaQpO(0$;efo8L-skR zo!0lh-d;~O=U(}z31g{h6y1-K!SSyM_qrLaia~(}2dQ;9vHpDAU_0N-5m(fk@$Ry9 zQJ)fEAeyrobNBw8TKM>*_1#?v0Wd&-8^*@Q&dlgUKPB!SQOY|K5P1A&a0-sHt+hiJ zG50JaqIk%ZlOaZeC5{m<7_?4FAy?8<3f%s~Iv2hhWL<<%wy)un3{JMIk(Ex0EwxT)~D6MNrtQ}l_MTUo_QWO4iGIcqaZJmE_0WeI7|8Qo?4Sv5K$V=$f} zM(s+5nc8kgN7YbPhAS=LRHFsV*}QDq%7Q;7wW_LOc=MQ-H0rK@<&$4D^KhplafuGz~-r;veK0}kTULQ{(SU~Aq(JW+1c3uS!<{{ zmwVs5wzdXfhaW#a_OA-{cr|$gR6VnzT}i`?;pc3z0tP1LqxOYyzq5gp6CWR+=H_>a zz1*)~2YKYq?qbm|oXm^-n+q_2T0+N{`1W~pObl=mA|r94=_H;%rNff|3o~A7#jZw* z_RvXq;Ew{5kDQhkX}2pA3kyB{i>FVN4G&}}-(?JpSyYO1n}09p**#7D*(2bzMYvIP zfAu7Zo887|YvsH6py)_ym%)Q8eo6&0n`;BlY28N~-GW z+S=3VN^Kf9Ox-w^H^;@*4z($ArL3%{a?-~%nC@!S(Gpp$=dNHCPI@reWK`n_53T}K z`1#Yd-CYXcs8LXesyOVC(BX#d zLrG^NUUdtLgRGSP!OPi6wHKDJp`=)iMkRLdk3Z5|@UyjKn0|3)7^tZsF-_Ek zikAM;(%8fI(V2&$D~rYOY+`(Td|<$*^c?{5 zWOC55yt@sf;)yKrf)SZ#re>vOS;ED`W}L)^f-w>_3C_g|d7Nr~sBkCe-CnU>$|!dR z1}A*{Bgrh0h8a`NFlA-3t{&ye@@jK4Ey4LOVuqZ=FHva7DVr5VpgLcy+2WauITBzL zyj=K?eBW~m#MGH(8H-+}*hLItqn3>q4x1&*tXjC4fm0Jkx&I|dG#))?dZ$I>mnKu} z?>75nE1q~mGqZz=iZ@$MLpJo$k2f41o!9So2Y02Ue4O32tFby&F|&e1B)^&dgCl`= z>~iIGTV6e-pgvB7pPS9VK=v^f+h^zet#*r011^B50X&;vM@3LsL^F$~TdbO65&W(5Fv+sRSXbtLN&`N!(ILhylP= zjGB@{B2Dhh1CrP)LX^QtjKD)13d#cxe6yYy(dPz-1pG}+M>#D>`dynL9TX#Yx+t~C zDhZRn*R2o@aSCJbr1+HHjHAqTvOXT7*@!NMD42EbF}m&#tgyZiD9cZ*b|bo(muCDd zBGfothNWMgA@cK!3Y8S{IEdEq8)ovAc0$4tXSz-A3$H4D+TbXs>(^e0UWQ5Rg`{g_RB4cH%oo zN5hxXmd}(R!vy%oyBHHu5fMQZ2Rl1AvyC5ndj-;=#du57cm(m9nplzI-b^gDKbEiP zpT2fISXx@jY&Qfssr<`}lW05&si4s~JdSuN{1AT#H^`g-H-ECyQc_GzOj>%n(epBv zS+f!*Y&l;4#`@T-FF%GrCbjW)*2JcbMhIABdKBGk=SN_XR_U@Vgwv0GY2HiRIkd%T zL~H#PU97)!_o8ag!RksXo~xOAy|%u5eJtMuvkZ*AcGBj}lE5DGytsZv<+?eNV#m~Z zcq)$;o~rwm!oR`q4>Q!g!e~02((6JjfQSDjE?@8VuMvOTRe}{guUeky{R;|4l9rx; zfM3RHEh`P-k5$txE(NpTbJn;!LQi+HVXIatB;SfqV%RX|udib*0+iOLFFTTZH+F-c zsd#zcW%>Ra6XWjCotc>dK`?N074qEN+~h8D02W`t7XvsY6^?!)82C%hwyz(Yy9$w3 zO5|;AZx5SQm{kxD-`n2U5PXx#n~YgAAUF86qXRQ5~G1EkNfrS(hT zU8D@Gq7C|wh>4v{jOp_8F;`YG#Ix`#h`AI&rYv`~UcLAf&A&oioXgf$NYF>J*jYba zEN8GcI}0QZLH=wl{#V9&-sM=KSH*-?8E{R}MkY+Z6bd*V{Gi}?C$LF zxNBkF{==9*Z_`Ne;vVzyI$=vV(c^hBfwd|(=t`~N+dMbljr!h+n}IOc4m#lAGGvlh zULGx&2E23bL}|*1VDJeE0YRX>ogGMwm6ny2y-L3Gs(Y5dEg&xaJ`FTNibvhUI@>+z zAfDvX>7v?hJ4ul6O<^s*bSbGTwyEHSZX9b@KQ!s7;PiyF%hTOX-P%ngUOW~7c_exb zIG?(Q*clQ;qn;Gt;2iNpTwGiLljNd|i0n#YVo6vy+#(};Y-b;RyAQK);B5N-9YFD! zt0|hmo&ga^x01T!eu^CtYD?;V?{AiWK7E;^sDC`06V! zUubf&7r8Y9jq7Wc$^gN4$Y$cyI6iNG_Vvw_7<7&xG^^g181=+f=jJ9=SGOQEv-+VX zURFk zbfE_)h>%$buQsG^YiepF!<3X9j|wVaO=&m{o%CFQUR5<;bJ2fsjA6h=>meVy>Mj zK+tPyT)!&hzh}RW{V+ran`>L;`tU5X3XOu{0PaE402rmT zh?}BAG%J*K?9W2E+LqHLI6wi^?djRz-#Mu&K~9$u9v5=4Y!}x$@4zcftC&j=CBq}9 zzHY$Q$;c>DTPL7K;)YP+`!=wJ9~X{#Hh3KQv30(qWpiJuq6$kai#)t@^$_Ft2lq-5 zilC7Aact*TEXK4DCtAqK(@GEUoxv<>cRZ(|AF}O!^5Js#ruBSi*P|yDrATW>_vW+R zCVuC{uvgRv5yZ^PIf}geB)hr+t+R;p%z;Jz9kf4g-opL?&4ltVc!MB>#g(O)tHp{qnq{Q@{~aSVA<{sDJDS6o<0F+JeN8H z9UUDL6ZO+4VBLp_Brec=U1 zZp#O+>#<=Z-r?OZmn%QmHSxVk{%|n=vL(^EAzTvm5uC9oP zh~M5goLuUL?25weYBEl*Xlkff!`t=c>F_8c)D#pVV`D1~I>V}~tD~c%L5ltC>}<($ z(vHWHVXVH!Y%!p5xZm8MGUQc>j)H=MmKHkMDn&L)`vM8$KanmgO|awr;IR%(Q<>Xy zw0hf{AsuH~Bk`7~ulLd6eX=FIiOXr{r#%mS{A*&-WcJ4;v1lca_5{LKCmH3hkf0D} zyQ!HD=3p;UA>7hm@8RWV#^1ja0)Cmc2af`AQ7s z-$pn0(dDAw2I~;B5MV@!^J0p=z{gUge;4s{Vk8>_a8P`Bxd2&34lN@r4Ez3U^YV$Z zDwd)|AT0f@d4Wp7adaG3OdLRshR&xA+0~`9eJ(EUg>GcYJO9b`b#!zpY~t@09yXXa z`(TSLF@b|SBo1#*Ncg59keD(7GR(h!>n$IeJiG#c?!zpHNEs4q^FtSYmN>Ly{eyg^ z=Im^2Zu8R5keP{%eU~9KfI*QDnmLE`O(eWPa1U9}EFbVCKNu@FitAaXV>w{; zHnuso_w6qx);PSH+gJ@4<%gC!9q&yHo4#kVn_jEs%GewYE7UBrH(2VECZXlAPMWG8 z`0~BAWW_ag;58fDzF>o)0)v2pY8}T@LQ+y#uT4j1CvaowSysOlHVacbs4Ah`jV;=_ zf|M0m?4w7IuDqZdD&Z51!}tV>c}kdpzQlC$c}lcVa6>w#r zr|24q%S5iMjuv^{RHA4%c}>@TArI9k6FIzM@S9N58cI!qNlAbtc5ZR;?&jv^`Z}A6 zN`4g1x&tpr&)L<)DCH-KZBgO`inp!jOXym&T5;@i%0|<;Mf4Kmqh>0sBhi?3BF&yv zQdekPdwTjxOZ(*Kcd=jiL@$+W72b;~3G9i-M!^!_1X+dAO#oBY_Q~WZnc;?b3j2o@ zN?D5VhP0;-nEplKp#y{g2*isIpN)+Tg^f);ktfG$HYG7ysnN5J->i(6JDZjRgf9_Y zhV^(4Vk7_waLV~0=Fwwq;yVZLk@Z1C_&kJuU=mpdhfQn zT7-Qwy;X{0=WSF4jDVB1HV%Gx3Q4)lh3zvo+$hLi6$>@2XVo=Y-1BcjMf;0Xnq^Dn zU-0mbB6{yWpnu(5{>6)g-sV^>J`z^RmVW-q$zcwn6i)Mj82wTGDo#FrF!jp!kJg3x zcI@#i#KZl@7{Tq8eKJRp0P=)qq52~s*a*>uj*qYTixPWBf?*E?eew{!RQTbl%JC)L zX}rlSL;5rNY>B-x{`x`vhb3RVM8?0Xk$&mvRhy+5TGs(=tZ0cUxv`k|ftcvE%)yHq z(o7gL|BRA!#k3VgY}W+4%~94WM%KFvElHl~)_?(yn1 z1OnmbuUAZSDap43>F38G%d8o)PR@Y}ijNOsrrq#tT91ecTqs>^`X;KkYHDKQjutaKOcU4R{)W`m0S^u{qhs0W>MeheXjMBVg`&FejkJ^ybK6^aaGbgUE$b|)*#JJQlb*$N`U zEo>3LwRNq3uQTC?445i8JM(R9)N2*_%9P9r0KwrA63ff z-j_|caReljjb=vLT7`Mvf6zZ&tF1+U^k9chJ}Qfx3E%}P1sKc8>kf}9+`g6m>8Cp+ zc;+VACFG&=J+0ZVA%AqULcq!{Fixj}CE)i|ouVc+5pipaR8t=GbIu zY4^P7uKe!nNZ#;HgQ`jSDre1i5N2Lp=5hX9@n?_9L2G36E@ zLt}^ujua{Qxzx&Ul^dPk{7OTUuW%G_v<^LH_7^*w`hr=WW;jcTEK%&@MbDetw8LMz zFSy~!p0{nUCZo;QEzWRUot?2m)NlH17tCp2zQp3>+GZfgd-70SUrFne(HvH1H1b|vhA3e%w zHR?#fxrvujQB)iRHVAa~OTVI6H%ChRbVdX@pH1#)s9_r2}@LVMt59gav{?p+lMxntMDn`2;lRS*HKI$F*W zfv_spp;J$Ym3G3nqKo~%C>5LLFY9&fmTo|bG>>_kwclL2{Pfr$(h(Z$vc>l2p~|zP zveCK>FZ}(VRI>a0x*vGGT~z=P0ULU2)I4XY>Shppdl?iIG%L(anhKpG;9cT0F^l-dNr-N`QHx`q zmnld0r5PPA(=anIvxCTe@?mmNENhHv#tiw2?!#0vceXoW#s(=-fP5XlLZy zlRs8vqk;^$xLADe6J$JM64X#EIIgG)w;yAX$P;FoX{ST0tV)!kEx&J9cyr=J5olRl z1jtgBW@e>m{&kyX2$g~XQ$U7%*WhKMyzC%9534cFuNk)zRq5Vvs=LGpDCtHG5##(b z1IZq}^niqS;+Ct4xVssPwdolw`fLCe=<=}}z){LFzcxCWYiMXN;ETbH4SX(tx3maq z!PD78eg-q7YCe0Fm~(j{gHN!{L3|qD>pn5rxpe}EqfqnS*(KmnCig9po@C1XR+eY` zX$-Qpe`O#+zVgDO5#%VM8QsLRbVQ&3UUy)LlT4EXoNnJ{J@$A9-i9zK;|Q?_Y?D2^ za_K|oZ_83_X(ndJ2y=^1$F`gG_NK_x(_Lm=mE`f30~hR9TN#5FQ0<(Y@ME^xwwFek znf4Ort&WOV(-yzQHST;}8@he7t9)auMdERukp)G&EVfY$Xgd{_#_B-Vk( zt*wg@2xeAR>qxOjXlNJXOqQ02;jEi7z7S@Qk+D-I400P+CG5im5FnK6t4R;(w6F0SmgNhpoFx+>Jw|6F;n!Q0wC z`6CCmz7y}HjL5C8*J8p~)st6OSNCsU?ul!v+vR$FfR%EWax{`_%o&(sy@M;9J@Fkw zbt@SfrAACDCd#L|+Hz<8x^=8r4wA1g(5|iq2@)&)67r!ZQb=XB(m7RT!>A~%mdj0| zSCVZ8>e4wYMjN4V%KPC^;)GY^qOm6%2>dcZh04XQ)PNB@dfnE3o5MnyXPfOuV;m@k zCFPB^Opd**Ue}!B!wF7J6O8XyYjgIe>Ts?B?I2^$K%tcUmXw@ zn>1p2BN&D>3UnqZ=|gm%wNx;uJL8+d7j`cwHSg;4ngUxuu>WsU4f;`~0!~p9Kn0JD z8IFksT=&3MSS%aj1w!56LB=>bU`BP zeuNQ&U!ftuFl?hd+*hwV0wB`u(@1o=kyZ5;-i~n zBb!*!k)FN1myB(6l0))JVzZ^l%YoUMnTC21F)_m8GO?nT+^`}Z%ODtZC6t6Iky|5! zyC*VIPSmA0Vfb2QQ|Z+i1H8H_Z~bGJLvDe2l@^4T7ch(w}nlyOXW+p7f`B0q8!N<)cxnWHq?Es3SxLpYVdyk6v(zTUw-9Dz^jTTuk(>K9s(-to zpm%t#n7sUv6&d;I(r|$-&L|w zD$>pN+w5fEfVBMO9*v~yMYk@0a792Txz`PaX7|KP`O&i`d;h8#fx?AtH6n?HEA|u@ zh_;!)vlM$?9_Pi-`HLyBA)P0dHCxV`2b#Xcz2<|HFVFYFQ+|tm=Z1w}O)Bm$ovb%a z^@klEjvj<}+V4tmX2!@KW!~VEIKbMhQ}TGd>~}&E37n6grl+93k>mF|aiPw0S_?fV z9XoISu`7I6XwB2e(;W8i028nQgzrF4mbj3lps)SK3pR!EL^r^waB*Yaj052M69xv| zreb)OcRHRtLS=GvG-uch5bdzhLR8GxH~HRDzkWjF$v%EBv7#<>j5RLsLd!r{FjOQ% zArH2m4p{bia-UU#u(Gp=dwNcz@nnaF)9T;+#dH}`Gr0J|&mNz|J3Y{XM3ronn>(f` zfq8WFeAF*e7Aq^uuM}ofDnTwA6UX;wVxxt)I|Gwjr;0CEDJ-N1u#3Ei9ksFm=C%go zO}6@0``h7n}otq>TqzK zUea6)4sL0tUo)m`>sIJLF>mAqV2#UCEj%NnHnx(6{Ni&M0evSHx!nS zU4uZ1DWR!i)a>z6NSyaD1^>+jz;`jAvDYxu7Vna?KvziTCkM!08cupHBj!dKEMou| zD%*W%CaitAE*?F#`PKBar;Wv3xeValKT%DmlgAU7$%93hpr3|UC!ouY)fbGT>%v#P zSbitZPfj@!LA9%+w4V#v((r-9qkvY{Cu^RXo0Qo%f_EP2RYD=FRk;h;(q~%6R^EgqB34aAKBGJxz+^Q z+iw9zKjNf_om0zq;X|4X)0ex$m2Y?hO{(L&94M*yMH-gcIT@E!4t2T=K|Wtp$kQx7 zB}B(8BU<)L|5FQ=%}x2xel?+yaljW515om@wEB{oy3L^ELC8ZU09o>;diUL2G3;hz z41Gcp5r=>5f+6Fdd3e3SfA;Jd-E~=Z_M>=NP!6W6%Nip=(jrJ3#l^`9N=WX?M&~bz z{03MU?sDc4kn{H#%OU0jvZ=hTOKV-Dw+@y*c~_4K+zvbZd1O=hy_S~t2TfR6n3#zh zcV80pCxI(#;7ajTL+^^!OtsT?4_ke9ur5A!3H$VkaxbyhoOQKF@nTJ2t2YQNLDf*x zNlpk)W5Rv6w0_MHX!m?oJ--QBh3W*xyHB8-d({E%Mb z)|~kQC58r_VkHLoo(x|j2Q2uS37hWEe)};Cr^Mb*mf?RSBgP%nm=pz@#k_QM9gpv& z60B{Ose`9MA=tODLr}RTf+Mnot;Vjk|rxB%gEU9$-)AYKe9v?`|~KWUwsKo1P#B3x!53$ zlg925GJHc5rK46*c}#uip^_&a;)A2lM*!ma)(j#$3#8*(jzNJf9bqk%OUCTE;VZ}I9>F6b%A%=WZhyn4)c_<`Ar!y9@#^( zr#xwAL<25gvV=RhIe)bVI%AG z?DLg!wS1pls!@c} zo<5<o zJN}OTuo3O9?7hVjuL%2Zd=u2QobBG;jF7F~o>VpMpL-a3wCUS|2?UP(!;pl8gk%)H zXcEeJ6qL$L7-LL+RFAY8)ST=j=noVCyI}DUqPqy@g6dXWluJoKFYG0!HQ+WUU%U$&=$cIg(fS>wa=yAiYdT`=^zj@Q@yD zF0RL2nF5X#_j42xDuEg!XV+A2*J_T(FK}!H^GI##085-sV9w6`mvH@zee1`;1=rhk%8oQhW980qs;ptaXz za?d;ttgCZ&ZFszV(28{PzQ&_NZ)|jgoAk+?ibJu;p@P+kskHPfLXVQl?Bq^9oiEU( zLu4c$P&Mo0b3e7eDzGQ-S3k(Ffx=MfU!sT~px}c}vb@@bj-?WZtFbv43eM6Y4>%hI zNV%mnzh;Zf)`WgYVvcveC zNN&sEmh|VmZnTg}Dr5Ke@6%qq>AF7JwH#MZ?@dHSLz4uaqNF5945s#r#t(s&38Q2~ zLqlF)H{e@1@9%Zpx67yNqpLFB&)0dL^H|3s=&$~!KZiUvjo~4F44Mq- zAUK}BXr&l{T3CgEfWpGYJxk4u{Q*B8UqxkQ#wK(xieQ>Pd{tW;)7{;mzNh1&uWZE55e=TEQbqV_$ z))%lurhi8Q*0a(d5o&goCn z7#v5xm7{z*e85s@DSf@C;@j?1bfQynXM`T0R>WxM%`DY~0& z6>@92@_eU*>q*EBi5-d5(R4DBv5Mtk@*s#bx3vZOrc}4^YHQ0ky#vm3u=L9TpZi2*o4C^&lwCP=*I>D2LaC zY164VIekP!movV8eJ@Ux>X)3GA_PR1dfw-GV=w!t;=;$pBatSVxI#%D9_~0#w8^(t zN6E2z$|@-EFmTon7g}2x#GH(cjloNmUwLez^|SkQ4$c zrlBNj>g}zdfF9OPedjhU0zHX8Q(8k~T~RS;VS!18xTXEKFjEo=?U(!rp+s8une@qvKfpPNm z=~Y|6D~geTKoZQ!fOHjIS8s-CS#*~S@NQX`V43syCMPS{pOzd9df9UhoVwBflA-T1 z<4%*Ni!QII06G>lNwJ-ev9U=-XFeq^goec|E~_(qgn157VdxdV1H|7!{rbDqA>;DEw-GUle7hR3V{A9{CR|S!6QO>+ z{g*4SsuccDL=MnmJLGq(#1zXwlBbvjucfcJDqK@QhV=ERYHN@5_4NT8q@h8RGr(KI zIiK5|J=9C`qQX+=%hj+J;1G5KR->9OJc$McL-YS*T~y!vQbfA!Kt`>m;!&%ZB^eFq zo5;F;q&v_3C+lTn-xCt(bd>00?=3ofN4bdlE?e2|7mx>78fo~C)`(vwQu;mejAQgs z2Zx8Rjrs=${4vL#i>f4lG@qzSGo&I`V*(0y^LM(zcAWY{wP%|#@=jh}z=F+e9|Jm@ zVk=#k{82ue*mOXB?fuxsF322xsP5cWRh0SpGdIUmLgI#EFAFQvd{)j#X4cS4Q{Kg8 zzU3v}r4@d7UtStoTKV&>G+Re0LsKvzfosD7tP1sQ#uRuv0M(s8&h}?z^?(`K$PS`6 znvLvST?I5BX%={K(pbOr5=mfblq;sZ8;hHjtz=PtspDEdon(42K5vW&XscdXr>Y@)x zt|}mCr|+M6s(AoW2Zk%M_8KAVv&wj^ldmLq1vBOS=Y{4m=Y}5b#+ct&Dhi4a=HQr` z++b$3VP<$67Tzr{zpDH=YH@K8CKi$NcWwi+&`R0EGci#CWJN;Vi;ja&xk1=bRX3-S zJ|!f^1TO!83fITu$W>jGn#wQM8y{Vt_>;rvF0|Ldxa}zBuDg9Z32E129<~(2!*0u$ z19XK#0}s5;`PRCe=#neO>hHZMeJdj`dES7zc^-5Nfq47ub_vb>8z1gaiEqsEMv!lp zM3+5IuvxQu471_HY5l9xzQ%+epZ(gN>h2OGA^Uj~1Nw)@S&sm^5p+*JCsPGrJ)boobi&FXY1EB$78V_c~OtVrvq|_HYfHwSXSLg5z=CqVi_l-yI8X% zP26u@BK0CA`$lHlO2=!V+&jmv%W$ABg8n96*)gAim`jXD2`=Wlztr zk>1ZR+oQ=N_~)=E;jsqlWtkTDwo^}lB$5Fd8d_TSD)g_K@K>k!K*%vQg?%T7sQeW5 z`(N-34@>r>uDONg1!C9XQ78Npe0)J4nIa?EkB*8SlB1{Cwm&ztwoD`^QOFs9TeP9^ zTKd`Mz)hlB^+ZEBj+se8Jrnl)s8u+4hLYLPZYS1~X<7y*Hxb z=_xuzPhF4l=n0QDbVn}-2e0a*QG&Tl)Faj1K1-yKgT?uo2zhvNQ9->?WzxHjlnCh_ z9^P*H=(i&mzkdVG*3#0#?eDMs>dB+>aHZcXN|G;#yOr<`fYLcOB4XUe8i* zJDapZZ9}ipNKQ+GE}r1ivsPG8H{jR{tLp+#o7$ZZwVI6S;nkKh|7kqt{}LD zM&%hBqMn?fJs_RPVZO(0mC&zR<~&4XvSA|0>W0_q*ozM3!{c6JY;x)-wJcJ%J$pD~ zM%P!#dt5{@>+b6cmo8UsRx=de)1*#MPeDHXgjStA{8LeSl{ruJ&p{}$zkfS?)clz~ z077$6kz)i}^H|^pCw){Hc>TKd=FKLAP1h;N8DzpjnX2 z$}S>%zn5{*(s@GPlKHnFKjFPU8+FTH#fZY%rCWfva4M(%mFlAPF|i;YTKIp^CJ^ZI z&!0cHx92QK6|eP(E!dHla*O}eNuD}D+HMSHDhb{eRU+^;VP21da|ldaU~AC6k+$9+R?i6i>aJg{@2l0QAOR-dT?fVeP{?Yz~6IDr=8kt!bR}c_k@6cBI>p<3^AOP zF$@+w3CdBqzS0;7MfV6YoYFW<_bHP{m_Ilq`X6#}A!i+cLaw#7Rs8MpJ<@Nyy!(Qi zRmwzIsOJfZ8s_{eeSOdUgi=#9()#=c9%c+>Vh6b;zV5b3+*)tRWhQg9vSOJUBf$yw z?U(jz{^@&TRa}sR1HxFcYisD(Vn=rbl=Y5Mal|z`GWON}gsi0)0SAsy-Fz7KW%{e<~k7j;pRRJyq5NaA(MSU@hf=wAC_Rtk@z1YIEk#*#yI zzj**&ri@gUdbnzV1&W`Wq(b=L;0*}|;M0BMK`%)hr;6K7gV@jBAv^GF{SNmq5n$DoMJ zQO}cg5qYYwIk>xsXXe`^L8nJ~n!FaZjq@=Rv5Xx3!6hG_{SDmHwiAmNa#|5*s@^`}kWR`jCBR zrw%nQue`8h+NgqG06}R!qoZ^OqX5a?<$vsn**7=;wc#CoFU=jD((d8}KYue7%#S?r zduRxbqo9ybv0>vC`dNBgj(f2wl3e;Rp+xgbe<n@2r`-9K*p?GZf?Dxita)f#rlmZf~Ei6--|K-WvTJ?6bA2 zD-*7GdD_%&hPT`BxdajMHrCGuUgaFtaOOBR8ymc?jsCd^%^X0ZsaKD{u}OyG|BiKh zw91&L%gO1D$nnmOoiGJuWC!=_*Y*}q4Atho=vQ#?@H~7NubhJyB3)LzZLTq3U;66j znt*9(&*8C(k`k57!PWh=c!?(3~2E|fhv8oKh!}$pDh-WWo{vVb&9nL zV4(-K8MnHEvlS#-VWg#pg}wA}@2P&4b9Scu0Acyl#M#~5-rgRpq4xH>t}e%>4ojYo zVZ4OUBzRkMa=#z_(7Nv>%EgP#O*r0Kv`+h{idnynOBiAl1uy{|hukaX7{0=ar)-rI zR&k2>I!8g}h&>{ybUZw~PMq_7rL*y-CXm@Q-aCj>JP=6;T|OdcPY5;EN8Ed3!$V|j zyfAUM_jojd99!t>sClgPWh9#aBf&xy+I;x(R40MMluLF`&#ZDiiP~nu$3P1)x!Q91 zTj-Z9NcA_eyUVyRM!Ex@(lRM3Fvm*WH^w1v@-2ti_1wR8~-c`C|=| z;I25m^5%jsSxn%Rr%+$`v7`KLQ#_dAlwY!3yqmXd``^|D&bTY8s9(!za-zFztP^gyYDQv)>mT5hrvHal!t$#9KysWAU z?X3`5YCMQ(w0E>r@PB{5_qtBBhRi|nA{p2 zfQOYj>c_zWqy==`x(JYsF3Njo%J(>9T)pe>w}eLAZAZmnQQB=WXlXMt+IMH;PPlAz zMn>M&R+;{=Y<}0<0D4kVv+Qh`+F`U;q#drQi5MC(^K8H~8^{x<@*nS3$yR3;5uvY} z=4LWw_P;^=5dwwAtT?FAh?!)i;B%XB{fLuHdvAM-sz1xg9pJ#+)&A2{M{;udiE-c< zKlR1M#py^atoiyfKUs{a5$sZ71ZCi3Wr};Gx*9)nSUFO7g!-Jk5a`LkM$Li)pop2x2~ciV!`m(xT2|e{eh5wWZu6HcW{y zM7ra{wE4^6I)E<$yg|vt3rY3O}6_v&jAy$Oh&&>ODtu#@@#8}u-u9~!- z&#kPK=&WsQ4Cd|g&~TZKH~*YWy96C=k~0ba?lK-?#`n(p_T35+Z$M<+HJ`@TkcVzB zi;RV_DJp?YiV?`CnS2{55NQ~_3U479VmG`%^`DqwOJl@+BuP9gkAIC)lZZ7de=tqW zaALIs-S`Rq-^e`N>cjNW*2%RfpX^NkoG3+1i>2<)U01X)(Re7r!hkM4Fl)Ed2PmcW5Zkzj>~v zW??9_eOPOhn=s6m(?wfb+r;k9uG|NOoU#N*>gS|~3BiafNPk$|*$MqApsKj~yiWxc z8B9l{;o0hWKX-RyuC6dqy|Nob|2U^uSpXIcW*GU%$YLy9L%u}acqLRtnP$i2js-xC z?*xao&$CJXZ1eRRI7Oqw-AWO4vdgCOS?+6IySN#Dag!J8JGc5zb;0_I3RF#}*RKy( z=jTtw7c5+kTUwA;rMTm}Kn@Tuzxa^JG_S%L8clb1LEx`?dta80#pmU{NJ_F4wkfM{ z{?K})NUK{&_&&GUs44YtmZ3#CWD_ho_!dVDS%9*diVk8Bz%dPeeS*+aMe0=(?avWJ zV_m$14e0Mz37Iem4w|GYRr`;{(}}TAwB0xEf9K~E4t=glY&6mQ;8iE4qXGk;sN-^1 zIqAv+3T=8q$J+tP7yhr6%wEb=>r(?Mmp4!C?B@3B)!O1!J)dafWz&_^`SHls)WQoc zUQ+A>vOWtQ;PEz{T@+{?1A|{anAg!5FcO%YnZfw|@YVNF^fTjgBao|y|%{33{@ZyYD zVp;^==#i(vBL#c<@?S+-Lgl)#&9mPoB-%i^;3;Y-C3Uk5t(}8`?luZ9!w)gYo#R|Z zZ!2wVq!d_bYC_^e)e?FmD@Hm>?A$p;VlX{1ab7!fxrKKi6QXix(D`@hlsQ2$#Q1xt z|ECczzFeH!Z~m_$o{i7wKzc|bWwgDHk99=w`wti$AK=l_yIDlCM| z_!y~H|59imwxwK`HMY}B)53iudVTxCvAZaTFf5EtBzaL5Qd_{P3g{G8;N-{%5uA0k z;(cjqd*yJHQW2-)+3>Gs+$-jdMBLYIR8k~?7DaVe`_klZhK z{m(s8Qg|?s!^0cS+#@>%W{>%KcrLzH?KsrCSX*PSu5@)_8JFWnrbyMsLSyMK?d0x$ zrbO!yqs0r;bayxFzbFLwpKdtnT=CGD4+RBrW^qYmxIaLEMaE75=yZruN$iF+zkg{J zFi!C$TJ}Ma2Z@@w%<0}$edqac5!q<)6pW#G=AX404c~VX;-RaC7}UETLf~q(<^iO< zR%WCVBkHr}5J4=JSZ_j+nc4?a^=_r<893AiL-1`K*F!gDTC4s)1^M}q58y9OJX$)@ zVSMk%d72Aei_;_)sxkn5%1L?)ISq6onVA9hCp*H4fw|I4-yjv>foQQTT|r)+ z?{C*T0nj>iF`!>WabP9rVa|jhMkkky+8pid?tE9RP6_iW**&^3tJc?LoC`)MO1X5( z0hhCvi(jGluFOx%DEN;S;5LTny?>2~3`tYe>dVDgd_%hbThN=hckWWDwOOEA$3iiO zQ>w}Urg;n=q!<8hqvWNt)S>o^{#C?;ZBJ3{5MU9&k~V5JSO2mYvM*+2!)JZ zIt2O`f>**6DI~-KSp#f8O}R-AxrMh@`|fCA0&K^@$A`M5&}+e43K-3|v(MiIMT9>q z(KRP9#wdnIMy3$#Jf`l?WBO(BsFUXxTG}Vi!i*P%70xVV4XNrqS?ZT=!@YlcB!Q%!galF$@j6sn-P3xc!&~2J zWss%yIIZc}6z5MuyReWDraXTBvSSp(cd4|XtKStrmSUP@9V;j2hzA0U{WsYIa%}3_ zPxpH%#JnpCttIHnT`fZK?RYbWlNhF}-j&3-uGxnA zy$*`QJBoJ@`I_r(#=MdIukEhwtFbbIt2c06;T9ncYkyBs-rD-Jp&=w9BHCi;A;LaC zluJX+`;$Z?%WPys1jy%n8ycn|k79T@uAR$JCcaDT4wcrM!5V<{LGP5Fj-0R$`43w7 z1SP+IIZ4kyt=@qA%lonAWo0H=A7rERDk=!yeSoO_TnXO*KXT6^QvCc`&Y_ovhLk~~ zY3r2HwacRK7H>HfH1QeLBO74~2UO(ii22T3Umc$uvnTuFCi$xHBQ6iyb&@_l)6&&a zC=}Z*P`PVf-L5`ebp=6h8y#ZjOYFthyM(>o`FtV^>{A}8;uF_(i~=J&Jpbh)B#SJgm@mptw7nHkD(S(s!$+$(c3b~>p0=C1ZMY4A@9 zVVKtXA8skBJZWUoce2!X+t^-t3dbm#w$3duEyZ;bUC z;q6EqnkQW;rDD}dc*$5nKD~M|R!XFvw_v7`qQim+snUnk#dP&NP#2IV_gz_QlRpSwxnlbo;bTA`jrr3xg)}62YScS7Lj3#?ckWNV zV3n3TKl@Eip7;H`2HBB4*Q<}ciSzdGa?nYp>97Pf^}*Sn5!;`Ws6T3~7jZb;^NPo#u?z^9)`M9o9UgfcPt_^eSch9`rcM*k< zkjM1XlQjV@!^MWluhjdFg)fl4slV;@IZgAYHRbTyJnTNdUOPpan+v8m3qEcn|6pn> z5>vQ+eZ9O}x84b#iMAK}`|-6I;@-CVwxOBju3+^lp9lhi?t6`l8G=ZOP$fb8SHyh zf87QIqYPle-#>+COqOTRf)`op36tvF{W4AJS9DMK$VRtJCZ_|m>4ADwgGya}VQ ztE;QIIpkepopJcpaEHrg=e+DOCoV386Fx$AbSjR74^gHWQSv76N7mRvzbjP!snQ*S zr~~*EQ&aH#g2ZKYm0^AZ|1W$OVzO5@R`x|b`7Q?GpFiAD@`6c0$BGf*j|T@$PV3aT z7%lm_kB^iykbi@twyUj;yL@Z0uTNcX!YwBwM6p{YU7wA}@iP%dpm7QDRf;pXa~2Lm>4&A zbhjBOdL*df5AlnL)K3ocW%rNv6UGsS$^1)OCI*FlDNN(U9JKI+beok9S)f!isB77B z6>6$+#diUN+NpoU8wUDF>WF>WR@f`R$&e5xEx{bhC|fBn!|8{)8C8Whf1ccnv`00b}mu( zhvVRqDR)P!a8US6>S+r6NM(O3bJ=XfhTF~)qso_D5GCE@WjJH<=+XD>6u$VLyPc5) zL^ydvj}W_|t;tw{cdW*zlXDBgo)*5~di5<7LHp5MZN!6VoT&_~U{zJbt_*o!zY2=Y z$W!sWm-mlp6DXl(h=QAxuJp7{;`(CMT=G6z1}#!XQc_YJDZacpc%zI|v1V;j9BC0G z6cp3S!Z*D9hIyR}-q;|Ga#!c#(`0h|O=NuXpUx@8nD$JP!AH(ux-!`zc}!f4^2Xdr zF79s6+2QRaZ}E5`+_JhV662QI`qRYczhn0(PW)Wm_DgN+EA;h_sDdO?1TgfO=6aua>-)*ub-SG_J;|PD z8;=^tt3Fq3>`eb@Pq`HT|L@h1eZ{lX9}o~UgkqHbjaXy-n=M1|_6~sCx`n8Z&LDhg zZ*LC**q~v{=m!ny?JQ*&&YM;|9-y@B=4@3s>YzMw^A_k>l!uXUM1v$2JzmR3r%h*TtUnVU>o zDJ%9;=CB_?2@Tn?zJ6h0;f=oUXNbQJV`a4z+(ZvK$!)KL{QbcBL094Fkr95p@Sga` z87#{m<*Swt&7u|BbQqJ86B2%zaIHC=<&I1|zAx1I%adR!JX6t7M&`}CFD3Dkud-Ej za|iiI3&WMSjW`5}-`z=^YM%=j-MEuTzU+|m2>p?i)R>hsm}K0%y$cKeC~1#`#K*_P z5Ktw*o%r3KAuiJ^n=!IFh!V>TSzjzHz>tY+s4-aenw7r1cR^!*UpQ5T;d7-9%d8MC z!GUs4DYPd6>3z1E8U5m=+VuvJC+u)YO%PQ5D`g3ohX%8Sdhb_1?YU89Rx+ocVTGo3 z;i5@ZBK7H)VJuLhlB&3iJVyoBxI|dczqDOk;g3pmj!aC;xEp_RY2iD~QYR^x(L>phz9T$7js+2yjq&r$=gTJfx2US}|>o%f{-c5Xt!rdYJ=UL!mMm z&x^8A)r^BA6=Iq52Eu=swvstleK5~d6#)FY8LFm?j7(r);NZnY=m!L(7cvVhvIzfH zH5isFBsK06YB#PN+i((``m2?}te%SPqPrE69=H!bI(TTB&KxhJj9T=F8907zPAR87 zy`|d2>a7Yhw+YQx`z@piA54n&X=X&oU%=?JIuXk=G-{PQ!lw%envu_E;n#(`OtglGJUa>^)YG3`j(6L z<;48hMCS{`do=e4PoA$VVGACK)m`8oJ0E|9^)iiJ)3L4%+c=b4Jafh1OzntTow^X7 zD{lXqlChG8nJM=YEt`nAOzMgU6zyquKM7mDL7{ zDDFE`cmHOE+RFfg%HNa1f$rV@j2izKZlG$J%gb|QTJQun^J>Ps{<;NpKym`MfsMYt z51qW-OKqohPl82+9-_Zq0{0}~|0-z68a(S(3cCX`a>_(RqR;eCloa~oeBvMM z3e`eRkC<2^H1I*+!GM@|b!CY)o<0$Nh)4oEhTID?Gc%Cfd8TsOlwd2e%hMdk)Z*geTA?S}{DtZfAu^Yq25A1zbNWYDb27lMVL}6GKHy?mKi)2w zDb;(XjxZ@{(YGnkw3yk6ICii1Zft}!Sy2D>uGAWHzK|~~FXtu0IX*hFDe?HVX^kPM zy5o*)7hI>}lwyjmiBxG3avvZT`JbGTj}YjA0bV_Jtjb=uf?HTGzv=xTLk z#4*KZrTfqI?%t5)%=MV1&yOk3Kb%zk=UWqb7{rwIV%wdDjWWL1&a`K6d$|pX0nzSt zn)qawsPfC~_j~oH(ZoLVk}@f&?%Qyt z%wHSGvGp838X1mlVBhteA+I3YZGC(bXRqhph|d|<-sxF?qs`f%l^f>4T%lOnAKQjq zN-^)X_40ykj{qU%tHS9En(-i-eveIh+!WmZ!YVicevVqL-EII=p*$@jUdgOP2V$&9 zjU}7Q;Q(R;8ZkiPDRhD|GAQA)Hyw!u|3(MIDP^lNEbh8~t*@*59DoXciz}XqsXT4= zeb7(%ZBT#8(|-8XIR*_a0RgSWA)Z_6eE{QyccKSFZoo58JpPP`c$rTS>o(~Kj65x}yNcasl`M6Qj10%L zK82XQkBSc|Z;Oi!*z<6$YLt?`4wZfOK{4X^0O(5SA|b+T09003HGz_OS?VHKvgF}G zSgTHyVM{Mc>#<~6W7doE_xjde^XQU?FTX6kB#Ve_x0tn~dxRe5?+?tLDox}8R<~K? z@li5*@CX-)9Rxk;3c4SxLRSD!bU|5u`I-Cb1B@s8P(_FdyegW-EJ`0H!9Eq#dTF2+ zp>5<#C_uEo&mFV+P8xzd>ztres^8Pr24cSE_p8Ue>y||9$cQOq*-Fj6Ms|brK8OVra>?KnlG75u=CP&@+IqX7|!{z*CEkH1+VGhXH^d7+3Pq- z!5RE2r>#lYRP`o&S$!lH?d+x%?VDggo#Ow#S^<*xVPJ#>6Tad<=V-$)n&p2Pmz1gJ zabY~rQU9E-7R>tTZZZEmRO1_wsKamfKRwu|Kdhmsz0~ZF!i#AmNpfykAhEPq#|`eN zn|@Hu(rtXSQ+0!)IH(=L84qnNU?l*QeEs?rfIrx_BTn@L12fTOd%a6+l_qLEzDwES z$va(?E>d}Osyj^>i!g?$QrQie)$?(2F-7|oda9`O67rhUBAPQ(>OKyizl?RARna^blS9QXr0zm0YADK*XL#K$5KM6WS0$%Q$G)qYse!4GLR9M z7hbqS6du+FVX8gP4hnBM3L!2BRQyg2f1OWW;{Gr$Uh1;>v!lHq8ob?Gd)?51ymD1{ z`0!viSUkNk(RfRod*=^jd)$naN&XDumiz04RhJK~uokFt=4?zdk>h%T9}#%qQGf00 zHF%cwnaf9Dk@*qD?-z#tp389S_dM5FZ~x=+R{HvIO<86v8}DqE#X06%Yp0jYB9+~c#yRP9= zO9Z~~Tm2z(Pn(XL=W&OR*sYU~zds$_bHUsVP`Tl-WXtn$^xMt4i({h1+cRCY*S3_U z%9mt9vr|e7BfT9?9}_9#q2?D~Y4|d(IDIK@?4>{097zcq{~39;ofwPl5YQLMN?9V* zSo8I@m*-8ugJiuGc1`F1ADJ4E2mcEOeFUWI$rB*Gz#10Y2^5VEOHp1P2&Ew%2UspF z)FfrtVk1GV2p^b>8>+pJf*w#X$)Mye#KgeY@a@|NUA6mc?6$pPtMpnw`n^CB5hc&U z&Yq*nz(V-whmm~euMb%PRxe%vWB~rvrX<*!lA9q{_IYZml$=}xrz3O3L%&$>Hma|g z|{Okl=V285y~{ z64#B`>hQ^AVA{CoHc=8{unCewg@nyfYvQTlKTS%e;8lF^?l6V>|kDU`P6aqAmcU_c`5 z{AHF%jD?vfLV~3X+sp2S4@qa%J$v$WEk9SF=Xs+!A8ggTo68U+4gA1K{z%6BK0q&O^bgUcAI z&zCP)7K`9RfYMAH6Z0A+SoU~hy^z5LJutZ2k)i-Yw1;7s;_8m)ttBO-YHWbV_a z0_TaCxw*S}ARq+D0v32=`A3;cC?|_7n6@sMPuX-aC?tP4rP}OZe?9g*;J_6@+3;W^sc>Hwlvr1X(Zt1 zTiUL=_T469phDQ3*j%sYUa7T(z3QO&P*ToMaSvzcl_KS|FMg>;JrM`_GG#1*VQ1%g z&bKqvGk!`@>U>*l6faq1MO4b^iEkXgE{6Fj77`Prn#~H#dq=i<&!HHRBUnrhblXnZ(L{ za!39ka^DZ?q!62&Rn^K;Zup#O<7(CRlGg{VOuvd&$z` zP3-IMV@OrvmZ(?nPT?>%dEA~9l$SWtgeld9whiBUM6e?MbkUqE%j6d-(K;ITZQCpD zu~}=L7XIj}hK4}b>5%&0l-`4KXU@}J$D3awCN~!C_yVe)^ zFbTDtp{k1pi6n9>1f&Bb&WTZ;R0yo>p?5q)W)ElNfCqWU&WfBqf?ppEqB#WIp1j17& zlP~r3gsSyHrb!qEVl{oX;C3j+zT&_(gXhLcklbl~&^q9s!t4e9Ucam7^XGG`{TX0p z4GRmSS4kGOpKts9S4xY;gAjq{3B~ZTfV#PQZjPDBw4wl0_pKy*e^%B5s(j#lRuYl% z7`DpBtRT+HtkgID1Kv_5h%iV)z@z&v7$|_ayL?~&9CkkW2+1m7=hZlzhFJ(wj*iO{ zh}fRhe8P(}#$R8p^zUcZF4C`YdR2>d`LL1wO~u}qqM{(tWDtUa6ab>q@iE}hhHzzs z0;o5%wTVn(Iu=6OjoD)LY%AGySsQ7dT(oSST@7loz4n?;CF(c76uMp`LA}H;UuTKt z%u=ry8Y-{Sw=OSFIy?kY7DN_wso_rc+qQ`1%-l1u)-v<+wK<-%Yq3B;}a8{h|qGL&F$^Tpw=8A zp~e)Y2*n5P^#)*fGx-+ZLbERu_>%a5S+bcRZT6e0-EXS|aqM4jTy27rftHU~Y7x1Z zFzOWXyfZt4)FeAcffEy^@%)`z>htT|rcnl9`Xw6ij%PK+V&w6WI*vlkjKYqmD)(zu zK9(mpGyFQ!yLOX27Qz2iZS%VqYN;VB4O1t%A;YToZqTp2NV&VT36(E8B!=4x?p^ZV zEt!jbUubwKD{&rVDePxvaxDbmApG0)lM|e@7V&b^^M>E=o*ahT7AP+=%v9X(=cjAG z-QYEkqx63Gi@em(b_~uU**4wvDTh3MV9T*c-TtmuHr~UNy&lKgRC^G-HQ`Dj_56?R z_3p#tX#h($Q+cM0>};=3gEwUie{^;V)seUsj=A_N?ud}D%*1{4dB|>y_F}>O>$2Dd z(hWz$%ROx0MKtmB%BP2CXJ<#98#qKzPOicP)-2uJaJ@%9dej)M-uGl>-%h+X67=UY zIDz&rpqR>Yn9mXKLqn;zSNGWuoP#c7#8l$S>-|-K>VE!fYuT$&A~ByCsn30nb=+JA z-V8(?x0#{v=x^c*QyEOFTFh+W)ihk8n&(n7Zo1#kp+xbsX$(x&>+Qcc@;iy%$MJ(` zksMSVG@rvA#<~A@^F%54R}9(!i(7$S0{2L@zJD{4vLftSWQy?{zq^K~`>e3v9JJ2S zKWTwCMfQ~i*q)Xz(VBy}OqUfBrb=|641t>yeuX}&tPJ0s$(XCA6$J(MyC{2a3l;tT z{p*(^hJ|$NoZT(t8x9PFmh1i7rnesez?YG6Q-H1vTSngof&L~FZ|y)*rT2m9p?#9` z&*zjBWRQ*wsmK_?t^MY(`IIL~ndVYfBX7a`dY|R{HwmBqRJ7_ua5tXENF*poCwswFq{|98jq6o&mY2sT+zq|)%9r_6Gk?KOK_DTr zRF^wDBM26Ymne0Fs(jL@8e=*S&o3cd7+hn4Ew7B**9Qjy%blG3JY-?Y6%YJ;Mg~pv zPYCV@fMuhIUL@-ljsI?$GUfrE?pr`MVTP=(e)ulbz}!YrAj!FwoRrkOeAvX&`9E3! zU4U(%g+uk1&A36s0{ru#`=7qtygW{ufS)GFLUf7Bm9jbE8HJiEr|T+!N}vg{W+U2- zRy{0bn%_|1IT-tEI42rXA*s;U8$hd9IAj6#aA3BXVxTk3=>M_g0OBO)T8KMQq8qR% z2ht!<)1rJlTRgRS+jjRfTe<~ACh-1JF*KQt(cQPb>U(N^+Y0s3pQI%J+#$ifE?8>v z?v*Uf-8K`ij2be_;*i&EZ3(u176Q<^l8}**tZi(Nk&#(hTfeT>F9N-JYw)fmX1)xN^eY#Gg=EQLtj|s` zNi?Mx#NuFRfdiowEk5#&qyzW(@Yxfs6hi~BhLGpp{RF2auA8?f+)m)m{jWb4iEeYr z;jnMdOpFckz{L|%(a>$eHDLaRga~4G5Ms06e43u$Kh{4ABO4C0TE-RlLTO`laX)e& zk%Czni&7VRItlNT=qJUuQN$2ChDN_t2*{sKH@Yk}HN@OJ*McJ=Qssla8IOtWNUzf+ zcJZgtn{3AXgj0-$w>2?tl%f!pL!;uQU#Ti$OH z(uQ`gJCFBHy4)05t88$zyqSgTFRjLKae7YS(6f@gb8~TLbEK$8sVz8NPY*-iYBb!= z;0(Le!yM<$&T1^*lgq}_M0?b9{w@z(+Owk+pYia|RpjG?*$ULGLOvIzBSkZJ0=bu3a z{0DMlgjK(SZy9`HkTJ@|1r8BFoPC)Akj@!cThp`{`V*d@bT_u3cj1*&ZQ`>cx&y-8 zyjM;Ff>=SX2=`qd?9#?Neb97k_%?5B+OB|6U6TDBw3Oiq7n<7I=kZ-6(f0SF^9l65DNwcT+=c|_pSxCBIZmE4KlP)i`TzW>c82;8&OpRy1Z41q~{w6AaW z_#Duye)A0*n<8$~dcv>~Lwy6 zB4ZTLdhhdv%ICqgINx;>Qr_>E<$hW`)QE`K*jF;t)#6Cjc)-eafp7oO>Oqgx>E@E@ zC4oCT5@83pxp9g6A>^kv3QL%+T3 ze3ZgU^O>1lT^9$a?(d~f<@imJ9GU0c$Mzg(Yt$5 z>Y|DyW0Fb3BO^Degca-hXYk&y@>B98jlF+MEq}mgh3R~Cp0jS)HRgutH|8fjGBR>~ z5G~p=a`%bRLdd-f^LvQP=TbL*w?)r4J{_!E`Z_9=S;!=hW6K+i8!qkW@wLTc$_=Na z+M1+pQe`wM_LyN#Hs4pnR^hdB#SCUhQE_8QwhV2}jHf=C(Ed0bPV9aWC4PvF;UR03 zd5@44sm;^b#NtTX8-9sLvXql`Wi5$c85eJSE%tOhH?3WhcZramxms}Cl-KYhCs?hNVK z3)`9pr=v%a9&c#+aW5wV8t?p9#w{SvM(M##->hitcKk2 zDH~{az!&l_R0!7EFH|Fa_5* ziJN3Ar9T&68G8M)a<(kb2$Ul{-q4*a{j-|pPalc@Sy=rm2(1_G)-%-?>7u(iS06cz zQ-=$78}mKUzF7}UmwSDKZ@cc!Ip9MChhb=rnedaWsNk!eDjKqQ{xYl`QB?RWw7tmy zTmfw9H#D8Ry(!ingp$%jMgxb2Us1wr;;nlk6e=R5*x1<5lWgK7&=eTU@W3RIE5rw*b>F1q~iM$pO25&B4Wf?@h!Mj_gc^C&i15Shi>GHVzK$n>Nz531F;ylbrem zUKQ0k+=P#sP5?SlIBbq=;{60bwxJYcam}A5B#!V7w~tva!`v8pm0Vd zvdq7rfB{7EKtnjwxA)-3_i#K0X-0Xgx zLGi#^n-POkNT81{LqAB#-Rq}clt6C7W5H)(1~ZuhC}rbsv?g-3&Yv))sE?&;W}E!Z z2}Is-R%8%pUTNMGi1c{ZD*Eer@wd26bJXPm21k5{Pnr*E&dQv;?x-1WsDD?Jg(i!0zVazW)nC19#=^Ry3g1%_dTITq5VP<>|W80~)AiwD*3l zU%pdvT}OK88H`~#&crR!to#wtOnhsmj>J=QdcMY#wYVe-6h%J?lO%_&q9x%S=Xgo}GEHQ%J;@x_3 z2SHJT(#4qE8A} zaLH!e$vYn@A_n6-kdS60fnB(B>G6ydVlv*8Q6vF+XqoKG08!KTz`dzg>IcfAc%BW5(T#e7b!vo25?iOw@;0 zI&rXl1@IG$BVQ>-*yvc+g|+h=Ur08M~AKb_>@Joe9e#BfcDnwH_9MMQaJ zagZctVId?!F*ncl+qo7NSmtHCD9SRe&UnF!ulr|R7c)@HuerUVB3_(IsxZNAzGNdh zvUl5k&q<;GiSE!7rX{8rhd{|1rJ}lb(<-p2?esDl8yl8YL!#fmtAiDw>L?Fqv8FVv$lZf`N z?7Q_R)f=$y^g#sB%Qc=aw3L=c?x%Z81gOtw@W-tyUSukAD6Rt;xW2v)!>BYYkA`O+ zj(YjuybEqb2+XD8?17-E0ZYE>H*oY!tm&&Vjx2s7i09GL7+5~WjaRbPEhORn=3-yX zYHS~?_(WS9_ESSgTdF^;q40$!YEhWNbrS4|H^X?p!5zSv=YX@I6k?ApW8FJr%+ab;c=znkmX}fmKRT-5gS3d34 zV_hlygvrOecZWO$K77i`JT;}NC3fn4L(=Mwq3tW-P!i7j&s@+@mu2NtQbg+kD6FZ` z)zI)SkQQqwKJ0CY67!eG_f-|E4Uw1zB=@_-=ejVPB?%`fxoS1nD=~lRsP74A@L!o( zrjZXO;+bKGAh!)`c0+Z3c)#4tBYf8TGc9gnsyH)ey^h#zXw9ZqwZXpxB%`Wy^E8=J zWPZqEg&=ob_FN@8AKkOml{*h;z(vTEg%>w|d{sava(HK1_3D%yHzp62%~qiBZ%r^A z;z-$)Kfob6$yr&a_{*&yKgqHkTOklR)3Z%_?}OQ1BV=>0Pwd99-{>Np7tn@ask}V@-uk0k7tn4IP_EthRAtak5d+(Km z?43>aCVT%bpZ|CK&;R`Xy*rLnNAi5#=e>{n7#%-G8s6Lwb&fk@9XLIr{42XxvdtA# zaQpw&Ux2~YRya~1C_iC216J}%jExG3JxfnBRj!SK8x<(r{E-hc`piK0ppfOeF9crL zyT@Qt);tU0C}d;+*v&jpq{io9*4EY4RZ_C0Wx%&HlS1RZho&Y+9|aCMz6u5GeDjQa zgC*Y6NC9;-J0>@84yjZxw3>xzJ`he!1m$cB3j{3#u_?vfvs}A~ho4_iP>`4R=JoD-2|4tMn$WV?xEwMc z3N04hI26b~8t4AnqH;H@iC0I zgrGoKb)pR_>Yz%M@1Wm zkjI);fgGZDdU|?b;Lh&x*W6*uV7k;1y!M6Lerd5ix9+g4V$fNKO6Ls8(S973`-@ce z{W-IhL}D)VmNGdwMRBYqAG30!HTBqtfutb4< zQBc}LAt69PAdNla?~cXq)sCpBr_7mfyv)m}C;ag!=yCo2dE7ML;pX5#O7_eCf`tCL zBdj9ToS+DrianPPnGAoPy*~%m6da-hO2-a%S z3H!AYcxjzmk?+`)lIm{~#CThj%$?-r>FMT5-Yn(%H9Fjn<@m03<2BEy4AaayrdqJ$K2(L*oG&7uG9y{ zb*N5cdBvn3*S(lMbE3s!R>uA}_3wqj90mQQaM*UAh~NKhLI6gK{^iMYpCp)S!FXc? z%;%7W$p&9aHV@H0@dXK6&0G5^drFg;l$L;1IHDZg7Gnq&b@jK-qjbRrrt3X+{qUa4boa{u|8v!n87KBiU3-P4=ux4UJUs&B$^{jp<{QKq*7cuSDHaQjb-Ov- zO8Js`X=a*PnQxzZ)Wa<{IH(5p8a~BS(0va=Lq5}}!f>#zXK94DIZ^|MpdePHu@wPCu``BPmQ1CVP z%=Mpq&6zk~2(W3k!S<+mi>1vL*red?R}=HzS58T7fFnCTkyh6}9s zl$BkW*v_>2qS#)3?;6V;0T<1zNw1_1QgZV3&CP?;b68~c@?Y`CNU+6^g^t>sot%D1 zC-;Cq2jCDeJk0I5fB{-zD;M1i6$>jrXv+HQg`b`t$Zw7hxKxTYcJ6Gu{krgO0 zzQdN*d~m=|{>+psqe7k5JZm5{CguYv!uMg%ocLQ07((!IG>Of`0r02>sbqCEATKAU zr%nGv$U+x?^g?-g$lZVc{z&xDD(3tcf~7V@!Hy2PbF2=3-&%%#q*wTfHm&^`b-!Plgk z>N<1l?*h)3y~Uh5SW$#L>A&1Pq~>c7&GSCGsAc!?vS}T9R;OAN>){}~r(l0{pkp9a zCP6ehMt(;n^j_a|7fsUh@o|~@^Cc=CYJ#!D=Yd8YKhYb!>!Y^2gmTpvlJzj>y z;d~empjO|47kjsJJt#|ZPHYEUtgv=S$ETc-49}gv68QP2wp}7w^BGURNnLYJI@4*m zF#ZE1p#Q%%9%94bvPIx8}&kd>TXSaphtzvli7PYmF2+#u`=>u^-f z)<8~mKV;Lf+hI(0o|ucLx_i|r^8`+ZZWrBm44;iq>1S~9MFzKMt zUN|_22@5Oh?lyk$LPjFhlDe?BpL2Smwts*tS;5!v5NOp8$bfe?EJ=FJZ&rDMLD}@ye8Fs}L5@~Uk z2;-{~kdxlpxI9$yie2b@&xm;_eZWzc_Fk0`ZEQfyZ;?<_N&2qs%GX3(T_z@#UtUx4 zvLH-cCa`0Jl~6PLKlH`rWI2SI3*tTFp}0sC>qG7A$@PrQQg1-^Y!)z5J7Yc#HR5p%poE|&dSuDB9J?O0H%bS zzK?V3UW2U#s31C1VU6pM3$qzD?j)`RxR(%w1{M`94SkP-eYbT*tU`ck{g4^<9Tp=8 zZFfhM~Pq}Z^IY01`n!bAH@P{6)3L^NMQOBnZ+BbjioIX=E8tv3qx$tQ4t@`UC zMfj9v<$j<&9xh)avTyt=Bz^-Nt2=5D@qVw4MF-y4;>SmzC@1cCAPFV|U;82x_YiK!|nGF~cL-(t9A(Sa}(|DXG zvfNH1uL6%<0V z4W1?8=XKb`yB8rBqeP~^K5qo+hrW*?a-Z3WE5hU@7D|)cXtCUaAE5RfzS~ISbmMtO^jF)K->h5 z6SUrt2bZnZZ^jL|Rm^UPEJlr^6xwZ zT00Oj>g(&_n&LnKe(!f3v<~PZ48-4~#c5!YDgm1pE_k@+=kV=C1q7z2L`VboXroG2 z_Q(kc9>MPl2w;`BLhA0aJ|s3;hf6MIWxah5=)z-+{&>yOOAUN}2X%@1Dhj6Mui?_^ zuqKW$3vTIeHQWk){+nA@kbJ8~a&4`^R#T^}44})AP=8?8g0!9RWeSzvQRO_HS*A?( zGEiibyf2P}Q-g@*e+8Qk(3PyX`g$ey==_MuTUuayMWrQlwvHNJ<8m~5yp$C0e$YF? zb@LUTu(0QL!9;Be(ru)hz^eLk!XBuqZ3_{2OA?V?^FD9lrC(kmEA zMOmtCMI6ulgqC*yq;v?Y;MS-va0gTSj_5v0XO#@CZD626%FL$HH$igB4=w&5+an#^ z_~OasX#EKSBh}0~D5*ZQpc@rU$z~K37ju!UW21w;ud3w`)@}?+gV-0uZzvq2e;Qw>kkrJsm>Dc zsQWs3F3kx)ETP~Lo%rjYbg`l^y>kK3Igsb}4~d3-iP7J!hcBn4Xiu0Pb%G-)iu9$= zxYwb+D5-{s=k|)ccCYd1%1ESV8{b7l{-t=A09p3MX@bo&bE?T$(({uivU?5Qy0Mqf zPcIg0_EzHU@&Ahpu%mMmw~bh7G34Q$)X=T7k?&ZB-tJxHTW5>9Dcg7PgtqyihD|pm z@Y>W5KRfX%f*WfIuzqVA1w;UOtb$PD+Lc}PuG{m#<`KjWo7cv)4)0f9Y-kWni zhpc0VT9Mb4^|f;14)GQ#vl~OgjyExv|Fn&#PI>Vw)yox2w9WQbDtE?ay^WGB?{%-! zgonRn9-Hs+`n28}cz&ofGhMeEWj*VBxZ#d;bo7eg@{`cvfj)Mi*QWiQ14;QC|NVN) z9*gX}O5k}o=?p$zAs6#Be%GuoP?avY1>5q0O*+^x z1tbFTJ8oT#8A8H9a7q*Tm@zj)r3O!QiC?1)+zWKsxWW9>5?w{?IUPZu7`4y58-#|c zWCMfjj})NtEoP-G2uyTiq0WD%^VaVQ`>q9gLuUcA7OEzQfbGBQHe zTmtzENP57aq*rmdsVAeA8u7-<%L~>PXz4(5-Q`)s4Xu_)x4s`chke49=oHjdO-*3R zCVoRVi5OFnX&xXC=+9=#gInj|Up8&T-(>Q|b$FsN#_rn)wad;xn-O-&y^VC<>JL{cW;ylYF8t%{VkvGoyu#T!!oUSki` zx3OKw5dpMAr<_(JPN$eRyuG|GBt6dwdF<~#PGe69>E*k`R6{%p+QiWne|EJ|8G9cL-8j_$1Y=Z}k> z!=8G7V+;Lg`G5gi5^iiZwN9|*8|CU^7=`wL_PkZ}aNyfce@r#e* zBA*f_-IrGui&cD;7-=I>C20z3zo=_7(?-r?`+w}xDAr8v|2U|ssBs6g#H62-vO-C_ z|FW}b@m$nw?9$i&RdROv0P~(3??=h4-D6~@Q^_ZGum7VL5 zn&DFZtuRr+o`$OP_-|VFyV{*}e&edqbbhVoQ5p0k_pgV&1F?kv*0j6SWBvunxxPsE z_X93r-N;=GROsTxQ)db_k;$IP(meU5_Rx{hQ%XL`qOS>KYdJ!Hf81=SOSbuFN?x2iPf&NfhO_im zUi!EKuULN8fB4{{`#{o<$eCln&O2goXYmyE*y=;_$;qX2gw@kWrR5`jrIlIr@mUrQ zi{}edpAN!>HmMh_LU-dIq$t+;Hn=ZIbFtWaT>c#&6?f-TC*-+RQopm`S)(u>;Pkt} zvkdK!`pv6&p@~27uJ#&cJK^Wg77c$aibgDq@J>(J-j|R{77qyWy6AFQ zntuL_bfRu6(&L5tD{p;^-%MR@%QloMcnyPH9WxuPziWN(SUkU6SZux5*J*>);Bm?8 z(;z5j|8xBG=7~;@(3kbj)5}@k@ptDb^0`*zo|+XG^43@B9!5;{Jo3~-*RE!t>Q(k z1@6;b@e4=FCGs2IVLqZy8r%k1~9M@~^|%wlq)$ zL!{%Vg1XURJu0H_@A%_Ur6h0#At>#@&7y1!yWtjUqw(^N%R7Z7G(Yl)Wpy_9ih3__ z?MhRz)2Z#ZVpATZIf)cPpn+_7*3CwQ;B&*C3~>r66{XWli!~KbPn(x7PloU1OMi!i z7>}khSscN{C6YbLz{=pRG3qGvx+##?8db1=d_sXJev;X5QD&4H(PE$^8=pokl{LV! zedL$h{B%@CWB1L-t$)>;^1*rcv}K*LFCMK+a1rzV@bzq`r>P7Px6;9s4k+s zT)uiUNynq3$D>-6_IVALQUT|Vfy+XH21Z3dLhx8V@(}S@o*@&-0AmAx1KY?Rrt2&p zkb$D#^o^{|%6bKtR9042P0d}2w8Kq{b1zLUe@SKPe?2`F*&S5wNOsgTvO90jWn8kW zlGB9t7P}It0)K5LKILu}p0>=SR&v;SpzM&~eF;X`c-1X*;huAN33WEpBUF45JvqzA zV$nD!(RH_+i36udg?E_jFjhEysM6DE?tc^kGUs2B?ZFU zE)L3+pI+Rrpse0{+q&zR9_x+sY$Bqx-r4zp?ee0+#%lQKKdK%MrBZOYwA3=V*stSh z_VzB)icgJD^1f)4c+h&LICb&lS-bwa)$&E#94`BzA?=Bl)Ar)l#TtX^z0HB?$A@;) z5P!2IXyZxUsn__wCGj*~??Zj|Uvd{lFgR*W1nNjg ziC&tXjc4-o*>BCAVo!UQ3US65)?d2u1fJ@dhI8H_$UpC40COf%&-|7M!zMG&jl1Ck zjugZ;JH4F+7|FAfj-Y>;r}vlK3K(E45069spOpK))i1zV&u?#Wu$0s1Ns;!DVJFsBp1)xwr1L!_#qS=gCvXye4BjG3ccU4 zBB*c0cKGSKH|Bx|TD!>)-+Q)!uxO$s0Ob=wAbt2^T;xxN^E^mR0pY;OFnDcoa&zE= zWrktEeUplS#P0Xg`ga2d)is%=-kr*X_y3-WAM*rOKBILAd~cocg2JdCbne`XTZxmP^lkhM=7tcs4W!`l z4W0znzq^UN2~!-T-j>|8hTOIJBXzkN=WQw8Q%jR1cgL@F)uMre5cSII?_XY*bjQ~h zkVwEl#H0WgAdb`q*}x0Zm2yq$HcB3pu2?)jar|u50ks<;;Ji~Xatmj_Q64B;KiBF^ zIe~8b#nPugwYs0M64>LpCA5pw%AlL@-r7y*;N7c2>W%TR=UH!Gd8 zPBtm24n$@7SB}6y<<8*bH!vx#DKuCfl?bgYjx_e$=l%|H0SR5OYX-ag+c#grKL05A z2FokcJ~HeuhUA&0`4G{1?}L@BuVIUwg!80?L4Exnp~81}D{%8-K8paCGO9{-ADMuN zzKR)aiUxHbNl>nHewyFe$x&!sX=W;5M14f3z4pp-7AI;CcARJ&}MJ1 z^FEpcrNO4vV%X?tOM83f&W>MXBrFmFcXptqifHNIoySWk3H#R3F)M>Bq5?TeB6IH9 zj5nFY(saQQI=v|3UIT!b5?S_7Xf<42FPl*66onsta&*beHR0r~iIF^u<(>Xn|L!50 zNCmP!JbA|$t=>R(wbm8#zWBSqJALw#HnykY!2KY1y5W3{H($TrWA@+E5$}H;!fjhg zbu$ckM^}Zy+kGu2mQBC@=r_Cf`CIk#rGn||jU>4AFIu0o>({#+mnC~A-T%kl;IhE^ zMoj;7<@64N=(by1==3GoXk4sbRdB!OCkm)K6*iZ1IRz#MJ6TlGbH3vz$u{Tn|5|p5 z+3No-ih5HriBuN%c(2*p{AxJci|HU{(|0}hz4;gZ)=8dz!};5GyyQ}=hD)o(JgsN$PDq+0noj zU?JLlN_#tXF1QOv$`p2SA8^PWd z_;DeHmS$$MSpx=fiSut3b#x$L$H~d5JQD05fIl<^j+!t|!CQEwH8uah`v3#Jw(?Ap z7t+zG2}3CLsb>%o6UWBJh6gYMh`u}t&&PFhq^70@w^*YqJT&0MHfLw{C0vqbQy5LH z^v6QA5jRllLEW5P0H4Mi?a7yh>MU#fz|Fd<*dVWr*N6zl-u}AV@)fKol#><@{M_@c zEOo!GLKS&HjrbP2*EL4hq|4tMUvD~@0_xsNu z@SJv^FZ?X25*^DM^GW{iZ*G;9zkmON_-JB+T;Sk_%d)ojrMAtM(W@l~`(1JMp=!N~ z`-skuAB0D>uxW0K2sVm|hP_8dM;j@BC$4-u(464O)6_qwjJof@qt_1klSud%NKTHxp#Uy{Sq;p=kWpvG9hE+^a#992eq-fPpO`+G12h#)PSY z{{ff{eB@!Ur*hNT_OH4&1887=;uU5~? zB69A}S8Gv8cqFn0v>to{)G<(U)uSHVvhO}$WMO^DLGnhZ{vxpTG>QL@FUwkb1VH9M zR0pQ<;2;9^cTaaWq_8nZjvJ76d1i(+S^`W+#TH1YU@hA-8(+8fUkAGifrcgrU z?cwQty)DO**Pv{J2_CxKta>kS?Q{&(t8uczBR*d)r9=2`zD%cjO)OQHMx|GY6aJ%% zg+Wm-G0AIc17MTG&k}~DE@sKC16f0Cz27{^4?g&aej6Ba7s7G#jFtWKjHX)iL6PQJ z{m{u?^5jumUQptI7TqQ@^jP`OX}Q zZL@)osqW#$lK&u4*1@H21_{l6c_xWW+#E&=$e?Oy@CKL5{Qw1dc_hrlF;xI@O9lpX z)YZq0`Y?%h`C?1t(}#iIMbxoAIH;$yyxQBV0L}TcF0}{cj8O{3TE4VK`;pB>?>zV; z+l-0;$HC6^!5ayfOyPLIH*i}qJ^O>?Ey^uw0t#A{JCq~p+Wk6VRJ2iK-w+1B0T~jb zzFMIp5D*w^3Y(_+d2;?YvPKA6#b>fr@}P|4_u11P|OJ%ird>CtQe96K=e1#{D!A%lZKGj3q!nO<2k^#q0@_TkR+z+Sc z7X}=a-y^oLaW>Z1LAPFzn+y7!4H`hw%YfVk=Xz7QvTA5>kH+@^hQw=sDo%p|x(wjO zX*_>kfpWo9CxXC&FF}l2>8;w8_DS48&QG*uZb$RMCwcl*KT#5FWFf!ouSH@r)uYjN zfjm5Vb9PR5$$)pRU#6Y^q83AFk4yzg8qRFrOX}3+eLa$({{A}Wi@ujLsUx809O*6G zECkoXaTi8S$(!p3l%b}9;(E-iD}y^;{OMVZ_rZ0k^oqG_FY|**@Hq+hB2~V zlZB&k17cqfdSx`?WA!~T^XX?)fjtC(=MoYU96}Br9vhMnT) zkUY7U!K1Y+cI@(s?A<-dxp|Wc^jVXec6HWbjRh?+QpF`1$TzOdix|%*)-cg{eoJ7r zq+oH5s%ozaX=py7mwA%mhE)X#=Cg%2{oZ}(T6C%bCB~@buz4AN2zoLT@>?Ypm5<5E z-h0c+mFSc~_mtQ7>;tf1A4ZvqZ&~)At^-bZGZ*5(;lB~q8}e`2gZ~R-1<($>AcI@L z{a8Fx8UwXPunGmgDd2EbKQ>Fq6c0vL>*GdmBwdX#%|Yz+{IG5xDuH5+@{$SG0D!-C*zc{Ct(e_mQmvX>bak0vxe6^`fXPi`FBA}J7m&)lcwtqh zt&Xv9czW&=4)%iSeT*4@P*(g4>3ve61|Uh?ldCT&*>!l}R$S)z6a;w=Tmi|?WN26% z$oATN860e)g+9}ZLbA+aUs2IRpVV)>2-{_BmF-1cEiG4j=fl#GsK;r{Ljsh}6P9GE zOszxTwTZZ%+&c{pTWL1|Agh5}44Gg?!PXb9^2&Az)LC0T5A7~P9#K)o-b&P;e6>IWKU0OOhr zklxTmwZku3WMiVE;m-JR4h;t&B^ank>5%`hc|%B!8XwGu-pM-L34BbD9Vov_7q!aw zMd@+L6UI1*Jbe7m~evrgD~j57>9O*XuM-(K#$ID<#Tj&qKJ1zAy71+ zQh>A}KIC&>-@@0g8)kdQK{Nl>*Z=;d;qL3{>9Kh)o&z~Bl0xh;oloh4-;nAq(*AXg zchJh#)L_;a{7#o?q@Jfe@a_4~ch_u_cddytyWO^b*j*>GczDC9MC*a*3+1}J{L@P0 z^kf${-sI?wlPXxEmXz41)tyTT>|0uGK<5r6dv%rBp;uz!444QC97+taHMc|j{OKRV zUR&kd%NwdfrpkKpsrwAO*!*cuE31}%QHnSiWqIQ4vZ z{{l-YL67Q|pZVmbK!R0B$BIdbk#2rsQv?m0Y}-1rXt5-XGII=2t_wyI!0vUF9Lw+T zP9+F2NU*Id?tV#y!=C%vCLBzGcZ1zeVXhv5M5*U2!V>aboP@vFuo zIf|(~>wnJoVHL7-kmR)cmas^&B2A=Rq}CVswsgmVU7WpXkhPPyoW$;WEB8bK}FO&+iO+|L2(d06&-NhH5a~9i2xIbh_EiB zB5EJXZN`MI?w8-N*Il5ojjFq(F}b_kcmZ*;l)%t(@nKwR-H5 z?e3A^b8}G((LDE7pyO1BCmt#0NAipSC3d}K84^L=y_p*X=T*~(cCveS1eTRKu%7H8 z2_Nc7PzgsU?OoJa?q!CC?y@a?8-GC+D(*vQ=|!(9LPjz0?KJbFK+dDUj7A_Uz^XY; z{vW0vy-D{2K-KnGVK_k{NAia=3xc6CZ3^4~pn4vAfC`M`3Aj2!Peek3CH#+rwX~?{ zwt<<21q+`9a0P)1SrZ950se#!4ctN=(pk^=5-reN_XB_O#BxDi9XB^Olx(Yi%Z*Cg z@53PK8V~f%S3CBQurOpiG<(KB;)cZ=yG@OQZL*w{$xk!AoX(E48Vb_Cn~UeII@Q!9 z3)32KaN3KGS|WUlBi+2o*b^orqbS(hz#jKgT3UB{ReEJHrnswbyP7c%@1Kn>5q-kq z4p_rR%BG~7!X@L=2i4l1kUFDd#o-+lc}N;)P+(QjT7GSQp8;<{y6@G)$ii~E6YlMi z?0sxh&7C|HU6vk&g8^Qn-ujabip|^-VvS!D{vWR#1_F#ypuKwuZ z!#-to$4@;qeBhDk4cZ_~6JxXHT>r%dNGai*1w@IPBCyt|1e%$3Y}|S?&Lm4~ zKw3_u8ZZCJR7u)A)j5&>svI5V<@1)tgWLGF=T6Irn_IUgYiNkn;QcBv8y80aY zIf3s~t_mGKiMF!x!xqDy*iU~EgNcG0@vq0R8;JR;oo~r|7H0iEEiTSXUV^ z3NRzS`u%_$$|A51h~pOE(%WUb4;m#Q@`1@nE862Q?-gMxpH z%u%1ZH`Y<|L&yLc6=P{9SLC}$1Q<~Sw1TVuc#=!)Wjj^=qDdk%3%@V>_*byYmSB!S z?!`VZbg@aXEQR_=jtew0@Rd-bJ1T6>FaQu79|Lk7_*J$AZ-T+V+zzxTp}bQ^1fI%9 z2`5sj(1sjh_!;E1AR4b;5zE9I(E(O?|NBG>tIQ}wE`y-s^81iE#fK4YFkCgoLF|`tWgRM1hS7VNNiyP8f8F z88qoENn@Gbf?QaDDfRWQEJ$l=1R?4xZ>W}N8>}J0EFDVia}A9~0k^+D14~p@iFLb& zY>$vRpE>|90uU3xP2kUvEdfr*rjaQqPoLa#lT8`kL_O@QN`pnFcyj*=cO1>VI7)%^ zR8PvkG4OcA#(pZVsV?^qfWPIn^N>w>Ii&$a9k0wYZ;}ML$@Y02*WI$w>b!$1!%DEO z2V{=(f50GVGvJe;=fU(#6{DsM_G_MfTx6C<-NPQqn9;Apr`9H;oA&LYR;J2ZE<}Hn z(&Jt+*X27s__Gex`T4kx{+k<-)8q8vKa|>{0eBaUl|PGW|3i!mUs^u#Vg-z|{jU%I z^#Usm&U1VFla#BpHgHu2g2)W59}^Bkddvvg+5V3+7X_YB`9+R+a{8#&IT-zK1V0L3 zL7@dyv^GWg@FsGdRzQ{P7zy83@WbcgeYLzJGlKO`VMb1IrsHce|DT|3d%Yg^y`N#UEemYRR!V3nY3qQ2k;* zIrjqFI3-5dXMvQ-|0T(Y8Q9D=r8F6cH3dO^CvvaSwN}oS$MSoYjyY!eIHAjs2LQu3 zd3c;iv890@4Gw+RiQLs&(E20Ae2R?)<4=t2S4Em!^1nJf^2d#;ei}kViKQIfj!SLJ zlFrMLUn`|@>3uduAatTeOI(Ci_-E-nIs$Xsm+Xv$_V@31Tzf`=4-|(noO3%s>*Ukd z9zBW@$eW(sj*}ND8MP^L=`w8?A}bw7(XcQbHEP$*)%cU>Gf9b!-jqNZ+yXcusP4j` z2ZypEA~JP1T$JiNK#gsCdCpErpOf^o^rj{!yQuqCR)Y0<%(>l&9;b)qk$HpXAI0}UZqJiU3o)(Lz_JU0>2~;4k^Wh_hPTPPn1Op?W8R--% zK61Ru=ap6&m*oKW`M&s6ApJ4o`H3B0TwF9YHSMEJw=X}gLLD!s7yy+7s;uO9H7 z`*Y|2`PKEu>UFUum1)&F~FvcIp%+MjHjwpETx^!1i+CBHD-&eG}xkEUf47#TO( z=gn=lx)&EggbYdRfOfw>Fi~-4W&u4Z!%cL+VJj*sdgPzI_~*I=D!zaKSlFgoP|mEt zPtN*bD^bY*wt3f@M#{VM$=P{qr-~)D~1Usbj;-ShGjmx4geg$ zwE^TZ;v1JT-2_rysqPzT$sv-;_RCXfh`@RtffHlgoRa)}NMypzhC$bc|}QqM^rR9DMqTN`zyIf?(eQ=!pD;5>EYZILL45swzZXJwHcN1J-4!l2$>0W zZ^p>gsAQ`!8VDYHh-hlek^$I~ui8RvWdY#0^8W_M8_cqVEZzTe8T|K^;2a`3?K$$4 zmY!)oPLo_Rt(r@C%e)N2)N+QPyYR=Z)@2KCRaI7=-FGuI_@Okd{(3~{;raOAB9P^0HFYUJh zMwPBt20UQsx6zR)$hsHf5ztVQQYn7njry>H?w1na&KuCxbou6(A7G5tW8M#&ci=k=7>N6M z%lK5$va~*Uz*qQ_0Y~*t@T8b&AawLd1d~%!7tyi^x{PGsAUzOgtsd{Pt4miC1cDC- zh*K-C80;9R{npN3*QU4dPR@-Tv~T+54w=WuWnwcSZJKB7xe3dcmyK`09(8U19U94` zYD$1XAR0F|M=5aVp<$`2a<%axFi;vK8iPD6=Nu$|Tx{${j^14i0t!i$K!xbJY8~zF zaVv1V&%wa~GZ9H{0jAh4%%kjAxaw40nM#ai)C7`^C_it$qWk&bAqJ|Ja^&Klhg`T> zDN2&$-OPSxQHd0Y!19U;8xGPHSybU++Z2$>t!t#ZAj&W$hKaDzft1_EI4MtD3y}BP zKB2hbbN>4D%5Ry}4U28FtIa)9C1E7tlranQvc<);T3TSOHkj)BB3$Gn-;u)$Ck=Zq zy{C`8s&fY)Q$t!j7o`nDq?#-b+4@X^O}%S){b1qH6yEXP|0D9h+nTe6%frh} zC?tnd?&Rpr64YwM#6uBJ9FgBXPk#tj+rE#}`+(<1LK~#e4mt@q@DQ(5CPZsNu~;tj*1CUhFm5{ID4^J2?AY&D1pxf@Q@T}Lg9n34^YoxiT*A9 zHYG;~5LUYkA)L3^V6{fui3h!ap8+Ig0V)l3kvJ#EEq53;L0VdY0yM^LjnCQ=@t}#& z$pJxu3L}-|_|jdK?7JGbX!#&vFt?xpcyJfF`3FN5Bi0j@JO4V^oA)~^R)(}_<;WKvolHy#E9JDhd=G=zKTVK@v4J0PsY7)Cr%jxLA^+=SU zP7(TpGWGuLUNpY1jQBD;j7rLbY#@I#7-kK*36ys;YXX1_N;D01wH*73_KJR}89o-; zGFvyZ=G*#Km(utt*+%5EMQ3}ykVD~R(RtHSQXb!#?#$>bY<~X6D<-PHWD!?yBI9|Q&;z`7`yx{D%_=KRL(M^f;Avs!(aw&_%6 z*r=7kVQ*k%(7Y_B`H6BHaFtZ^(0#MuoIAN7rO(Lho}NQJ2l^>D87%y{$@^{S{m}jKx3Vbr!r2Ne6^_auVmF3#d85_s0uEl!RgWD{m z8*gN$86fI5$VeE24i9y?V%n<(+V&Lw_sGL8UP zMxy~1EO(tN71eH1q`B@Sh|2gl!2_~o7!g?1gyF4k3Ey!c^w4U*!Tz)N0iF=TfRVcc z1slznaf}J?LW!Hn3pINwr$7GJv1Tr8)o5=_Pxbb`&^2La2cFS{j-LXCpOOnSvRMNl zNso~mQf7=&ys)KXuz18^kwd*D`FaOEl7kI_{X3%>>$p&N*t9Gu>VtQ2ohRE2xIcjX z1Nd`l4}P_p#<89bytp%YN_xWT)x=r7syIrQqxmk}!6 zdn6!mLUp-Al}vbRDmmPHA?7)JBOg~3%)8GeOrI^*3xjrR7ftB4LBjk0^#J%V*#=-u zpwYs3d>yv~c9@XE^~-1_LnXK+O(SRD+)NB{1sKO8L*HXt(o)4z02eGO0tCvC zouJO@n1?6Ge-MSRuDrUM;=5UP?)$EsygW2b-L+ku-x*KxhF^1oWitpEVHF}rx7UV( zJ-LSMSHajRjNvElPI|@E08-k=$#JIX!NI**Q`bRqu*$hbDu*JQ%He>Y4WDdCZMAZU zGgoDkY_EZvG{Cs%`}gl$CPp%zo~I=N;B~-C{`r_V0+Q_vKFWTotv#Au`WuiOEOIKp zz!lG*R5N`nI;SWivi)<8utzxOcee&5e;S{M=Ea2l>bj+;UJ`jgLhIbrpD}@OYUPv) z6cZKuzM`*x)4qQE3vYj=8Snd{#dj3_sD5`g_U`QSS?%ZAboh{MNjY^x>ar$pJU1(W z0w!7%@&!pO*KfmcTQFx?r1lkQOF8WOCTyZ2NI9aSF{Z6C_JnbZu~mi%Q6`C;q>EWh zEroSHDNajpEK7Tf5)5O0cXU8y)->`yC`q22jU_(VJJotCibF7of?6mg|F)nQ8Bg?# z13Y~jd4+|~y9Ku38_d zf<{(2{pEbJzzG&`<$X86jQY#~ABD1hUn*4z=qJ=7N%Hinj0kdE8CYwfB9o;yFYQ7X z#sBf?eFPTx&ADu*uzYm$&TlPWy6FX-KD zFpVe-)03q?iFC;{;SB6XhuIE47nME0ln5RaIs#1D$s5+UQp)LxYJklMWE^1nmY1>a z9fG94;m@e6qv7mofB#TsCW~!drOQjZolHN!5(b4Y{Pv6MkfjM}2spl86J2#ed#gh^ zyiU&gvOmZ1y&0*Mds!*4!)*Cu1QG|#z+-Gi2bBaX%ox5lFnHie7+68A-Z(r(c`L?< z5KraGc-n%mf(fT|OuJO|qFD%m6CHql+|=|qjtC1I@g+6b(Q)a)qT>y3|MqWlwrAq0 z@m)#L9bT`wLud(L4ZV~--|g>z@Cp}JU}9-d0GkZdD7vgf&UBahCf>gBs1w6~o-<3J zn$1iYB(X=)%n+{LBx9jSG=6c!I+#D{< zxifetN>RA)a8LE)5Al~;@ulBnRWuoy9z;_L(s%X{FD&i8dBdlr^`llu*{hzKJzQ1y z!EG$Vj|CozkKd5ZC`ZadUV|Yn5+vGi#>4m;{QLwf`S}HEjsLwqoebntV%3>^rb6#a zFPM4@ZGf^ju-$aJ`ViLddIis6s5L2W4#2xSPQE;T5p{8^fd)J90<+uV&(r^5Pa0sI ztq_8csI;Yf9gU#Cd+*R&cQv7QN=JX){IKKdHCPrd7Klzi`oPP7X*pArk z$|_hi{CJ1Y$*cwhu|$OrP7uM)VHqu*4l+ZaZ-L3mYF~Qd&7|Cpb`1gyAUL!bLH@F^ z3fxcB`1lbZEE!K20CE|i`Wb&JqUV6gbL-8h6tgQF?CLtt=l5*#zOULLZJ>ebhlsK$(jGY1?qe>>X@WPW&rz6Cytl;!?9z^>B?EDLCf zbY{1$?RVi~>S4YQ{BVzP>b^B9b*g~JqMIPKW2+mUD9s-kqEUx9&#OpmlLigJXZKFK zOvSdf^N9SJVY-7%Th91g4VE~2VM@F)db~OP|HIaIz*F6~|Jy5B387=p#0lBkF+%o@ zkd-6}$==3e7_WobT^ZPyj=lQ?>_p6sz_kAmzbA3Ob>v~`B zfx*o!p0=t`;aFx@(nf$2I=baj?9)@sTb3wQfCxr@Z#+LZc#p3`cH`X)W^C$BesboW$6T$X(eInF z7Fc>UvNIcvqdjQas9WExd}4U)E74l-$+E7!9XxcGs??Y@;QGxMq^}#_X8O06-1ZW;(G^7?lEDmtB*a<_=^>+Kffq9nI z%b5acqRs&p0&DX^KyZ*h-o3o@%<>Y@g%85jc!!7rZe84)q73AvBC)c<07~IcC@b%J z@ARcE8yi|{AW30h2%e%Y8GeL2+ZMraxC^QVe&9x zDlh`oCCptnxKp@jaQHrtI~6YgA-;5&{Kikfb?=r|JBp=u%s#5YrT9Ai2natk5kpw} zD$o#v150sn@6lLkXpFp+p3&kXi80vJFNB@=pj)U(2!KeO*wM|x`fs8 z&2D%h>&jA8Qwu*zU7@zL>*eO=em^oQezy9x${1J80rvg znL?8P4(on^WKg;y-kCKPi3;Y=)V+uTFkN9bNE7e^lZ!s`E`7jX0*nYSbXZ*`CnakD zg%VmXz>MHO0cr`q2Wm?^j}ABzfWY3(-938Xr^Sa{$?MYRkZ!Ow1NReRxKYacG2iQ= zHz6KT-~(JDII8{Xu6q9dvg>N17WdZ#FbB4OFLFK#aB^Dp;`GbR1y_;XwNPA$8c<3& zSzp^;8Z5e9^P~?GqnutjPN|AnGA^ve3_rTT#zIO2dpS@7;Xo9SUeV~vBMF?uB{!)u zwOat-0@%j!3#2BRw=nF}t$iI0Ns-WnjDcL4uJ zmDer2LsFT$oBDf}O$iu4Yh*iwk!C83H5HFF&DP%Sjp3vLDkeC-t=zoH(W-K~-8*67 zzhhMsv{o_dFGwF{prD+t%Rsi<5<`aU!+qaB0&JLbzw$Bp`g|~|SmEU7!=H7JS>d6h zhq24v7>+VHtwT~8Q~8yiUiHee78WAM58rqTq#`ilc}5%c?rr}9R8lxCu+sV$tor|K zc)3r51?%J3~nf4;f6{?>W$sWMmdVldqdV z4GF(*yoaT#dE$r{=h%=PJtCxFmcWT0>$2PI?(SCm)Le9w+Hf#Xq^hRYBnAO12;b!r zdBHK`Eou;qXx-yoZu-Bi69`7=2v;d+pzu^}-*F%{znOukkVS)$ zk+5Z~u^KM~kArqcHS3WCv%T^YB5x2#bJ9Sf5j-wbEEH%!+~L@Av=BjvCu_(S#WsAg z(bCfDba#KK{sm}#R!9(IY?&2g5w+wG2;b{X=X%xSGPI$<%19Ch*7U_LN~)4tr%`Mr zl2D?()ReNYeWmgH1e^{_CVv?d4cwj;u6Opk{sMGNmo5zt4FNg zs$b=BXXZ<~B&BEB@Y}Wi?O^I9#*y)%p&6*Ek#}kQSRRc z&%s|RILaAn2*(WH(HTq=VeujStOM$>c^m(#+{E%swR5+ue48UN*X!t=dBv^gDV(56GXI{kWdO>Tv(HffCP)m z+VXL}i*SOJP-1HQ4IVHTfNOyBH)Kx&hhlUzF+3!!wJ+bWu=m3f4RiqR&sCG>9*qjT zD(j&q4S(y8_`s{6Y?TUuK!8C`Duf9*tE-^f8f&$`V} z0Ag2FGR2+7hDH@B#c?C>LUtg8Y;uako81oAe`5zZ4(D%w-bMfD; zVr}?5pG2CR!WX9wTCS8XI)|s`0EQhPg2CFZz1SN>RWTb-xJOtL^!<7{pzK zEWZHXwR`sl_e6YO;6iuYrWGh;8gk-gSKQ$V70 zU;xsw-Kl%Swt)Tujt{p3&~}_nL3JPdqTRN4lwwog7nN3{Zx#DbRXZ2+) zv{@nKCjpg-htBKlx-Yxs*3pEI{f>@SE3+sA)Q;v)c+$Ln_hu-oJ!fwBU6u6Feola% z9#i@VT`^#T0IUF$M=b^cM)BX;+r763jKOm1oLP%MtYJ{6GwKAsO^3$89BR*Tm|^80 zRJ)G%{d~iVbAv^eKzI*5zRJh9|Fg2*{S>h$>-(GybGYLexgzoJPO8z^49l1X0f|Ks zBxM6cUSI^Wte|(GGqFM{G}QLYg}zMz3u-qhSiyjX?HJ6$?!}tzdhf_i4_zAFn2ESN z`ogi}#Xr0y@uSieZ+Cx<;+Y7HWbRhXyO$8woD--J>iG1uE`nX(09s-DxJ6VM&^A^ot2)>w=d4CRm<~A+eyw9{0Wc*| zALv0`mStX6ewT|`?vB_$OUVmN*?qTi33Tt|8jjeOhH!8|rP`HxM}Ivpwer@aEF(5O zOHbTujI=-ujsu~c%UNPD0V5g0zPT2&9Qeu2mlL+9O z+96^>v#-Ue&us34mm4_|90oCoUWIq%lcl8m%MH#Iqf0KLSA27 z?DD5G8TvUVLiU1!)QO=gK=w=p!sDnJ5M=KSS<|MZiowqh{IdXzYoUSiH;Vjw??) zTxte^xLX%GzqznLvBLy9w+VeSbj=?OZ^eBpH2hpWMvZW`vI=UO1|ywfEsyS{W9g!M zd^EwiMFz>8uEspQfzhhKTqUo+Uv0jcrOz`mO7^fI`TcROzwd<_Pn8P!CEvdhKm8A1 z@2<_sZj_d&AsBsU*mkF5?t83=I{8ZN_U>xR@1@<{Ei~2Kl9q0SoOCjo! z;}(805r8iUYs8VMXw~U&-$?fMo-7eo-|&;Ogi@>ti>0#?rHO#NCy?qV>G9G<0!j|I z6;{v#9%aFjZdO(}of*f+$5ijb*v*NEh`!kh!)hdgfNc;CGwmF;MRnM_cLP6LP_R%( zOQvo5vw5MHj0JxJMQIXl0Ui6F6_1*ZSuzs=1N{ZaY%^(WP~uK~*KcR|@kY6ipW`wG zKiQvNU0#BfIiPj*@;`fpM@C9vKmbOu{_qWY5ntL0;sZLU0+1PR^Cz&<)PbNaZ(zDD z2EHId$_*>c0h(3wtk6{(-9R=b9CXHU2(Kc~zU7(z!&tAy6?V@B6!d1arRGsLpS(CIZE$)bAw0>!=RpC&?JT z|1LhcGx&LhL`v$Ui;cifiTF!*k@m;DlM*^V`T2t4Y2pY%B)r3CYP-)1;cX=gJ7-*5kJ4m*KIPD1TtwktVy9 zD$Uj7ctP&?$7D}{SlJ!4)u`C;^Of)8HKK>R{hq4?HN0!NJlEw<;(T`tuWD;#KWUkQ zoNbZ^Hp0pBr~5q(`8u-8?rZp1AmEZBQ3ccc#@mLILZ^R)z$+AoktnputkP+m#cJzI z#D%ljge1KAc8$kztL0JaZQ7L+30lCDL)UID)BGpjM6R%LP9>AYe~UU;Ar>Y_kV6$+ zEAcWcc=F9L3qw+(L`9Duy&210WRy1*IMB=3V}%4EVE*H3b0Fv2>44Q7R!NGbT&Q#6 z1qXpCA?f80^i`-PIx;6+*b8J~tO|Lz&b0{W6>sb1{+O(<)5M0Y6&UgZv3u#lg|=$u z_;y-yBHV~4s;aCeq_Mo6ln`R(UH&;U7B(}+L@qt?PdoT$UzopQx=gsn(@9Af$R*ku zs`+Ee1qP~OK>#Xz>mZ@?$Ph5r6Wt%bqbq=byzbcCbf<&?S#K};S_7QA^)qx$EG!BK z93Z9%MtlIw_BN(_iV7{F+k~oaCzidwvakgSo-k&V>n}()oZ7IuVAg8h4&dA-93s=x zO!iSclwsBTAwgMGACB7QAc;upvDJPfu~9$nv2?Jlia5xLv*%z_@uDqw`)fb1NB;D+ zQX0_8GGZYBa@Y~nt-wGeCsMx@vOvarO6FH%&x-Q~8Il3u!iH{@g8eHN78ZCdscwiG z@aFFy6GwmjsIRB@jsE3#!tBiV`acandRIGI2&Tl}n4A6dQNQHv*oeu5;;n!9UyZK< zEf$!B&s&Y6zG{h@x=Osd-f}(R(_8(US7?Q}D=hJBV^|fDjCmMP_d-i-286}sl zh*=q*ws-m@zEZh5E>htc^YB#8w?E*XT1{moPj3v<>grE}+~=!>IE6w%OXn!hANcw% zAMQ$;yOwgl&${stXp2Q3MgJq9HxN^#dK!cyOc7r<} zGE13*fxYf>{*0Xn{0|_Aw%RBT%2X-VEL}$;gIcCQ#WFfF^5n@A22^H!`Srds`H?YO zhX>h%BGw>DZek~k8xBGxE~%Fp<-z!pucP&5auXJy&~o0&w66R0s0Q8?avYV8q+yv1 zqr`;oBD8-u-A42xyp(x)DJj+bL0>>3dI5)5>oTDu@%i!RPolWhPk`Zth#~e_tlK6d zz~hanFTo&2R&Xnnv}A%XN*Too5|(+uF9BvU_*C@g=%h<~u7bY_FmN~NHcPbZU?p?+ zZnkMbAsrbSKlqOJ-14#`cf8{J9|iS$qd=L0AhsqJG6FGXikO&~Ih$)UH2%q`s-!NZ z-$w<;mUZ|MV)}X}&SQP*Dr+WcsoTcsfhU9raYW4FaX?PLq?nl9=iBfsIg|qh4p{7E zjO-s3Sc=E+$W=IL-(L!95=+*i!wbHix)Y0%$r+><1}oEK0J~kQWyHnBPus4W6#;wP ziw@C!{0MA5z|~nlS5!pApv(5XX108k-_7hlGHG|?7ZM!ls!`yP?3m&5sx{1$YPoTK zywbD)%rSnuXgP>xPfd}Q`zU4e^Cl36XMWJXd-oG>;!-w7Ms_@6r$Sw)G6wa%qOv6S zho*UV0f$=m^TlBFtB%>DiX7(SV+xsH%2~;GKT(G_^U(Tyn`xX>$j_3+{NzvUuqF#W z6D0WLie?+WdV+5Au8l&yppC#IR}E@<>LM{MW1-LaU7eFO80Y65o03}@kY5Bn4Qw1N zg|aXbQc?~`hUM+hFJ83_>GIvv_Y*Y0z#97iV6(LThrkoK-bB3n^B$K+g(V;MBAJ_F z9m<1;;x%62@nGP1e?PvJXiC?~Z~BHRbmKglB|rkAA$U%M)Y=0_4t?7^0A9$h$1RC( z`j=qi>|>P~w%ZyRABU_t5U{{H2SmL@cM1yzI1`zoRTDJsmJT;EJ5-KBo)>BY`X-WU zJ0!!IYU6k)OCo!(w53N$c4foJHyy$EA7fVF_sLJ7f5y|e`Mm#pLCf6UW& zF)W8^eoA$|^uDJ7PLD-$a?q-rN^}=u+F(E3D+f2!@0Ev3n0c^=039eRrk~yVo!nxH zA^+vMO?D!D(Qf=sLjJ{EdMYizXgsThiCW4mPMH%QpO^R2;+Ey6eOW#Npoi#1(?3%_ z(6qHpKdKpr*{v#PbcHC4_}#^~2pPgs)D#3LCk`&Dd?U9D3h{;q8-!#KTL!vYcutCo zbs^#|yAR;`k~?kK9&B}aSTiqAsQNa~kL1p zwn%E_bj@xK_+0&w=TS2`b#&xcZ2^+nKyszZ$pvsjQRqwdfhPqXBZxrIPkjcMf}dQ2 zT}kchjyn37t19f_K3x|h6Zd2oI3l^PHYVY{tRi&0yh>Fi9&`!-Q7Pmdv@5w*n-z#L zkrN+2;*XdSx9DL?NxA35fq@4z{111jHoE!yBt4B;sK5K?ASG%&eoz@fE9(}&WLImth38_^2uByPfj}y>ilNj}H8p}E>uM2&wJ%mB$T0pN6^~R5;U5y<^ z2jHJ$H<^)Lc5r{-lTEu;16{(l7HC^9UCu`gDX3UC@{;Q>1IZaO58xGDT*Om`h1X+{ zxxq>RR9&E8EUZf%>QlP!Oh36{TFw0A;?DNA;^Yg{0%#*(E&t~k2vK$WPohm6L0195 z6OeuyXJ&5YawcnmAwC>wZmd)vd5Xd4Jg7Pd6|9Gsey|ptAZOV*t09@1BC~p(###&k z%s~qD9Y@DbxG%K0S#K&x2LIk)w9}7i!-pkJ^PZ+Cfd~}|4!_FO!Z(tLzSyIHKnZ4T z?)Y-khoBdMpRcnMD2C}!l@MZ*qn#=RveM!HoE{cgA6Tc{y*mrd6@ZSn%*;CMO85Qh z^>YE?o^h>qlRD20RwC!)=HUVaKX-C!8DQ^Mc-crD|NL+=(;iRXe_tV!UeJ6myMN

<% z?CTS;zrD7?-p^HKd;4!ME*kbNXi%tqnf++^k%RWHQi)040Ns*16Z&Lo3U;{J`nap4 zMEWR|Ce3HDyv^^SJA?#Gt*i^%rj@2ebFOP&?`TfBfQ&6cBM3FU0a9m)Jrmp*yszPU zM977Uk~fqysJzfnr$CQ3EkFh|Ex4tvE|tu0pYn*Ez>qquC;Mg!_>ex9MOguduuf~- z0EVfN&|X*AfJ697<#DfBJhRn7LECh&2{NajwBC+jD{l4@1>v1*j$&qw3tB@fH_#jl zE}YC1Wr)h*Ba5|+UkC;toDBWXKK^@CXv$_D0gq_QSged_E|$!rdA9^l{%DGllmO4= zt84X9&*@Q*r6TfRF|P=?&l2sh`&tXwt=Zj>b{!Nt54dly=Oqu5|8lf2#v)n}2?T$| z5c2-^$oK2NT|wK#$qi6Z-T>JX;f4u$Ik`fkyjfS+i=XX+0Lgu!&Ix@(yfU2sQ5Qh| zj}$9uXlTemq>n>751_cPcYv(|D06=NASe-;gy^6(&=R52#Nc&X5(VKK)2ZfCq#Z@J*55_L6}Bd0=cC zTujAbAjQSQ6UMIsu?qNO>7+`zpB(K!-j?z|*lG$T#u@?C*F*R^2&2I)6U6S1dt}AI z{Y6yPUn9>uSwoT|{?!q7+n8ruZvl5-i6pBh@B_X1XFDS74=S=?9$WgJ5at(wVX!tKcsMX6Y7Z3b43+DAaW`Q=d8_?G2YgK?uB z{Ls}XJbckgJ9~$6HK1Y1QL1CZAoJe>F_8rPt3V$e{>nRy(VDQc8b^zo0d{tTSr8rZ z!?q5Bik@_N$fgGlteBDz1y?7Y3y<_epkx%+Wd(xeT9RW1uh2v^65!Z!!yG?(ok(?I z+oxx;qIb@Dx+KLtk$3S}{uzraLo~pAD;^vZ*L1z0ROKl=g>iJNCYraIsxZNkPBJEn z(;QSH(DuTo&26&XyY@z`mJb;)Wo}G-z=dm*1wf6f{K49`aa-*CZ8gLYE|}Nl;K?6g zVt_u0Y%?v`DLOqUvZO}(Z2VS1x8U;p92+}YaSl9uY_Wj9Hw_g&*dSW6+4diu#~zAM zPKf4sd@W$G%-2&#Q!`MFxIPDcgY(lRazsqq+$OY~=7KB;1n7JKAL%_Lzg%@jpH(!L zPU(8pZVNgG`}b$|v91}qd^B;S1OS9)VZf{cByGaUP@n3YO0_gqicPX3aBG938k8^w zgB!gAEjwJa(9tlE!}9RVp!TfW%6NbL00V9)BdT>2H+9l!*PFgbiHQ+S^D#a4g$ZGA zk1>u{A^R)VZJRt^pZXZimfjTdD+*h>_;Nw~1SS|}ef#*`eZLRqnQzjoI2quCD15i_ zv6Dfh7Y@QfGSz|(eg@bD?5+nK%3*sS(*~kdl+^9i*QR+!#((CFuO!S?S96pM<&o{1 zneVh;>i`W7RvUt+l=24vy_@xPz{O1n#-|`~^5@t!Bc|Akv+6-G_@EyMn=P z{DkA%ar$6RXd^t@bo?nvx9N?0>MghSTI=(+8o&1q?%P6%;8*}8#aUM{Ol7_Nj1#aM zV~8z*c0$ho02&3dWUp#n9L|HEIilTx>Ux&qt|Y}de!;IUUU&ih*r3) z4d2Mf)(F>iO>~GtZ=vrr+YEo9EZE)&dy2X-egSO4U|kITHk>`lS{-vs!^>YL71a4< zRdcS=MndC+25>bzoNzrFJfftL^G6zlQfdFo1vrw~Q?@?h&2Is9fd-|ML6V>p#7cad zs*3ArSbQY(qy_ppVDgs6$6s+0w*}QRU)c+=;A`h}#5E+FKG#cyza@xIMQjsbZQpyR z^kFq>Nu73Y8T$Z8 z(r3OmLtfHMcsoe9^C)62i6PjiAJ3+HK?kp z&bUgZ_n=wtpUL{+a>dvK(V42prgYfqTv^Y9a?^ERF!=#J{gg{1JLqG9uH9q>a(qN+ z#usbiAxD=KC25&rZ2%|p)p(l74eZfvQ!daz3uMNc_naBh0pd;;UX15^;JIcRsak3J zhmzR@+-GG(9xF8xbMQ2(*^{Z>+Wg?jfaGGhjZs%aB9*FYp&)e`VIJs5JQQPM42fud z-Andq8JAq;MAu~|*z)4RYrP%`CB4b<2XAsB%;Q^a9zoN*wYWI5a^fjkKojzW$}@C7 z18Os|qsa|(cB*GwVi9=O+Y2TcMY`YaExPl?<8qRfq9%M+%5}2RPp3U>FRNS;cm8#h zZ7muPP6E`uO>>)|E@lm#R7Q1x&UbTPL(B|gl@zb>5&yWg2{&9RLqB)2B5ptvHav#> zJdv{*{g3xD!ZVt}l%_Vkw2_y-aUEbBYXb>T#LWo zW$Wjf2>gUQCFNn2g=!Xc=L@*7ksiJFqTmV$J+ocunYW)Uk^z=VtW@yWR+|@M13X&* zSljw>B|!u13_SF(3mI)MnR@U_w6}k%ngyxY+q=7z`FI}tGW!yV&?&B2ySn`;Fs2A2lBFPeNwv!vG<+g?0O6$aD4+@5v9sO;KHH9JM$}u zh0Z68&6adI6L_fs%tm8Q;!?shd`-$P(MHCV-Syd=_Xs!QSJlR!l>?Sb^QToUOwP3%yRWAJPOX3W@&%kf zS@n{}p1n%;0hC9J8@~fQVTjqn#R)H|D?aN$`TbZsm7m5i5mUVBb+CG64`kYww`z62 z3U1()Ff4v2PQMR@IdonvC>pK`9AOO7VBSy7g!y_i2U?g)-z4PH{)HZI1MaJf+xBUE zUWG7lJVCL z=>1LK7~hYo0Rx6}2ZAjW|E0&8<%db0H%>h)-y3i$QARfH5nJK?;{cK*ClngWZfzG| z|6j%-FxI2kS(9L2$Vr2HdtkxsOyeKabfNh*_@eD8!(FUvh{wNi=lmdRGPwX?HxaNtkra@rV1WjdA?P~_1kJi8Q! z@9W8dD*nPhY3!&Yb!|mPMc? zx?0DIipcd@qm+XFjPw&}0;i8UGW(jM4jlDrEmS8{EGJVP$IC4i$7$GHqjYLps~T%E zKNZ@c(tDKa8lg=t3w_x&B&y(2m<`Z6F;;>3Yqx&)V)e}7f+*}9bOP_#@WlKZMFKV8 zeKJ1_&I61Z3$SEiX<>!j^Q(sqT1pzItW5;S!fn9IM<6{&&02H@2;IOX{;4TI2V_G2 z1Sts#h~oKT1E^;Bj(50H)2u5%DsaVz@+5YEdJ4u96nk9DltK?Mfe;V^$IMJ10dx51 z#02FBaBOB!$LwJw8MobX-HI)+bku>xCNDpD`ydbVm3scAXtnGYADfDW^DXGf_>~mL zY?ai1tayyBctCfCWB|=`uMRMSyLIPZi!+cnDp-@^tH!0f0ip!tdSi<1KlnUBO zC`m|VULZfyBC(rbv3u&xieF{z1D^=qA2LB)l9aQnW~N9tH>)%AqPW*IMm(KzWHF*|9C=ha**??}66WvcYrve;XA*X99q3XD4}a z_w4N5Fci}Q&+m*z9j0Wy#kXpt+iEgtgU?!x#|m3rykIBh;PBC0Q0L}N7(i|6$XN3H z>f|VH#1UVJFZB~yspEaZ$KODSXhD{=a5`Q< zxMwYfdyGUUZi*K3kA1ri#F!3ZyhwZc?<0vTt}%RH+r6W{)i3w5WF=h%>j$P&Mp*NT z7!_O;c)SDxvqr&(Vx#2`2IY7dWIb2k0OW)Z1mdFs%i{t3%$f94>=}BiKB?IMzjj)Z z*qv6mE(dhspkTJA1)>`-Ezn;S5@6Kyl8K!{kOB5R2o(u0EF;A7z5o(TvKC%2QbK}c zWd%nSCQ}qU*e*ebt*280_fjtjeCMEPOw|S(b})Q}vs8;)Bv}hO8Mw6xlza$ zLX-B=5{|i&Iz?wVK`4T8H-h~Uj&_s4Hy4RFyZa7COXtLvA`BfW5aS|pa`3am5(~HT zdUs?LiXA%P_;!WIyO7XXV00z118mTG&A8*eBNXL*ca~v*fFhlBnNM)t@5|O?`TWMY z;lu}@y6*9Im-s|&i|oOll+#f3)`~$+_qTUu`9G&`^)KnX?}yDeba%kAOx13)DFOP} z=Kiur&9Eczw=Q401ThsZrO5+}x5&KBv&rt4cRzV^#dZXI>3by_6xg-B>joSy`pi5i zXSBVdSb7A;<{%8#I(K|QhBo>_c!FvXFF`N#HIoH^^MfA&bdsPZ{_TN_P|*yd555Wr ze+&~6-sqo)7bD(fVgf197SdkpQ2_)=ASsjWvAes30;#()k6e<%)Hp#8pQD=DBo|H; z9>0oCMsn$-q{{m{IQj6pq;v%w%{1ZrCToXEpEvK}Z8*WIMc1lhG?&8~q_B1YJw2#m z<1e&TSIGP}QzjfAJivdxu;GQ3tDn+Goq(R<5Vj)g>&4JsN1$pv*G>)w8v=~G&r5&H z;e*Ni|2wMyc6oSs=U3e@esOgwGiG+%r>Kigm@&)lv5)NxZJbLu zN}^}(pRrZGPsPr&-&o{bHAN*A7yZ*qH;%TzN|X<}{K70kE1$B(hld+)5@ z+@G$>iGV|GTA#yfUMldrhbGnTOLV6DRr0hC0q}g@Y9kprJM+}3^mzep1UC(-LL-2w z3vTQ+g}`86+Q#l^OT5k#6^AI*OXf?bc7H{~z9B&|{jU$0@BPbc>D7{Zn+C@Q!7kUN zo(XXvfbY>B80dmk^%OFN2JS_?>bN^ZqE7o^zO8Bg%NJCM3Cgfcm$$LSPc9}u>qBWk zha^+PkpVA!N>tu}!!}+@LQI>r@O{BVWkb+iJE{@ml9RO&_mP?P{(WBIzaEW;B$U4| zm##*S=SW+~p56nJlcpb0b}`NB1aNS+_G}QZ>jFe6>Kgp8jkb!1cCXvBzJFkV&@jqa$^+#Z zfE#!JHBril96MWd`+ zF(*X5`#^CBJUzBN`c2Q`x84MsYOk$%43?^vd4J2l9B!72oqsm74uCO#xo7ryRP@a+ z)9@lDYlZ0jn01A_BzSLfbo_Ho)K_orY39ORfx=z*=odJ#k2_X^WE$|Bj8zZ$EM&mV$%!I%KF?`TpA#=x^Bb4cts?!p z*!#52MX}Q~jqL32_Wcl&s&Tm@mna|!=h86=xzcSDld5mCGmEaULHVLj{hNT{*_#{% z^`;-mpljKeaamUt;Un`8Iq|n;4SxkH&|WV|K$DP{z~Px0$vBmUDzqh!kR!3YYPoeC zicc;`V2BHpj$IQ+H(@2o+U+HCvI!ZS{f+Yzr^geZ1aAf)adxAPrR~SzV}3X}g$^{& zOUwP6#SDhfiJAYy0>i+?OM!;eV4D&XD{4Xn6e!qcfOBx(0F^2jT?>ne{ek?68uKg+ zWG6AukV$UC_}-a87LMl^2#lHMFr{vd}7enyH<}ugb90`L`J`znkvrCOe#(oay+^( zD2FEA_;Sv?8zq$**=FoMl4(w%J_vR$(W*~P!F~XmW*k|tTL!pH;eyTYU@EvnD@V^u zgYnXx(P?5nMG8fx;D9ypD$%GsHSpT9!+-cuOHk<2tiP1#BU+8j+E)pm% zDvj_sKC-hTvKoGMO(YSBc6bQWTthIx0zp$*Ps116H}Ziet)?q?(|5r$?O<$78nIgg zyhvPSjIw=l;NkY*1j|5!E^jSJV1QKK@M!w$gYD1oaes48==SHWuT0LYk9qUQAVNpE z#a=F+&s2au>d6JQn6%5Kog*tQjPMLIMnhr&wDxl5aL@sjg5cTL($7nT&g``rI9b+K zd7~>9_pWsWoI=cigt%VE{$;x!>E@S{Y{GYpt|W{sJG%RP7QX&Z^6S@-XLcpwk4E-z zM1*UJg!HwN`=z&g<}4pcCUV5NR@ZU?)1un&b*CLq>2NM=vQw_!6`t>b-NJWU?!JWx zH%5=7@3U5w?T&O6I`8^h4L`DAOW%`kqhl|U4oEllPOfG-jbG26nZQzh`G zV9(jK1)`nI8F)n3Z$c?dxq#D(iNKR+WHvy?c;pa`0=pxNkX9SmC!Vn_ff5YoFvL>0 zR)bEs$ttPKj({C36QF%_k%(m8SR2qrUDno^U232<$uM?729Sz4U)-moGn#^WLH z+6HU6>P-8H7xPmR_9%}0M(|+GisJre5Q4hwathmZhjQ4W0Q4o8h(Ez4+8ufaPAn%I zn@qS%X^ujRKHb8q+bgO_qBjTU<|a0Me)&%kTD|oYXyQKD8Fg-Wy!of-$4Bv0in7^) z%3mR>z9yNp+(T2TdB#GwYrTFzMGg9PS*P#r!x`~&xz}7!Sb}P=Y2x5y zr{>q%@y$u%K&HK^T@HC4iLG@?eEB1waj?7(+%Z|)NdJmBepHaX|E+iO&t&6ISNrvK zh0~1S6J;PGSJmVD*AXB1Q2ss;BPMnnzkNzeW-&1&k=@^16}rFgjczFslPLZ*itk&v z>sAE6w%y=+Er5^io=vX`?mANni2L|f{9FpG*a^<@@uk?Aeono9Z(aFuKwyQoO57dV zvG=^YxsPV-@3_i_jX0l2pGW&spbh!Q>-`TO6xDgOp{aMMVC8fLN>}F#-H@tQu&;42 z+-gbcoOlO7KWNzRaxS!}Tio2Y(uDAOI<8Z$`fBJ`mMwLL(*6^$-;Kpfr;iBO!l>2N z)xp3392aO3z6JqYg^1xf!y3&6(V`yl?eF>*0M&HKg9#~49hHT7ieiUblZ0S>8s0bd zKVYh2E;#2}4Wi|iDfoXt^_|;^I#<6@P-5~7+Lo>eOwt~piSU#1H_E%! zw`7SSXDLlG(B>h>#hJY=NI#}R#UAt4etJlEhSI%eob~dzS#S`T9ib(2n4XRfR)30a z4#H$-bBRjQHuZuC8EA*0?K2w4DlJaVon^#mo#xmG|JvdUcQ^HsQLdF0vnvlDX8tsK zWHvffku$h`pvirwLT(D23xMd17u<`%V9bmB4|i4y23MarfOFUS@V)z^l?G|vM5m?c z)aiaSr(Z58$H>d=4c)0yV_6B@(i_W)sgTb{pgUIRn6@1Z==(cr5@N{uh@!Z1_t z(2z={p3G;($Q`Y>$otR46{1<3PMauSBYfs_AR9;W3V^d$!)EH5 z-=m_Zm-o*$vPC0_tR8azS@NDLSk4MG#<0}%f!WW;2g-G(893_d>5#PoHo;bz;2a0r zP{uhnKE(BLSgCG>#- z#`9UkX(Vx5z0&Dt8FlP&LGzqJMu3sWRuh!b3S`3;i8`Xbs%kG2I%H12EPd~uIse^o zdZ+1L`6GYgE$j$KIqbo^?Oq5w~0h=cr>6MHXr%qyhpR@t~m zs$yV9Lr-|yA^OQjfj{KoGAf)}ljy(4RRV?1FVuN|qlNwJ+E)w5x-T;kwXhvORm*@_ z8hA78vh+0Bqsz*3cUKJ7MstSBH9y}$+a7vgM0(UcmvvWv6%5t++Mdc;YCf*2<|}qC z3S2|9mG($f%0KX5ys>#fo+(c#74#Or>g!6YtINyXPrFlDB$jh{cpeD6Z?ysU1XyP@ zH!1#^jwuP;shZE_@%Qy0-d!uLs9cbeda}EgxH7~xUUJ9lG+^UbotusNJ@>M zK|Lk6Pq5u4Khh8gf2s5?EcPL{{`hbg_`{X(mB59jtPExPI+B0DjWgs=JUeoP;b&Oi zO2#7ua~77cV-w*4aqG2UP7BPd)7mR6)WeiQsEW)fON zW%{QHL;CjoA492BZ7^>1-#}hyv@69WAvELd)qm?;49>quN?IHUAVtZp;fPW@s*Ga3 zX%eN*L&e61!Mr)WCf||ee%n?57S>$cZE-K*PolXf!7m0<3}{d>MCSH zaYKm*DKaItHBVjeIBX3%t?lvrvIadfm~S~%jyj6PL`Cr?XrzK+QIDj`|8fBa8~~ZI zD5BKkC64;K;4*Zl+yTpz0}qV9TB>R7>IQt57_ax(&diq)L@;nn-XZXdYt_>GMk+YS z8z0+SyI~}J4%yCH)*&SCuX0L>y<(h)LlbBl z6DKPZtA{bh%XkeEP{BUwxb(}eSfsfAI~Kl+Jd|pA{(niaSaU<{GR^*89qT0E8E^!H z_dbMnV`aS%M93IzS7pH%{S~$djupd&SQY>))!8Ry^e;g1!ny)LkYPu!B5iZ=Y0|ng!zYi}rWpP7oERl;L99D8KY5 z{i*6;YWKyImENHt_H=P!;mpA$HP9EakowF4j1i=Frp^cUXtf2503rU98Lc*#fU^6O zNb_lmni-t(wp_U1L6Nm56^Bo&sAC^MjOV2mBjYLucI)cacs+dV1u#GkD}j4)lJgdo z5$v6{=1|p}@C4CCW>CjkaS+jSLq{-{(wI0wtu%r$>08bYyy)vlBV zL;hcz-tw!YbuEI=V&~DSEwDaU67w|@2#LtU@x#4<-yB-`73$R<@8w5YHwg#FpX}(m zFV;e?L)XO~JjkxkFS*sv&KBehyC)Q{L~I8x{_$GXJ0G+RD+W%W7!C}Kus~ZY_qi78_20EkY|nDvsV zopQa&N2|zA-Qa8qG@2?D9Dfx7E7wFh+oo)6`;LZ8N-P>xH@ETnp~HL7nXh(VGohq} zpfILm_I1}E%hQ8F%iqK-JAJ#KffRep-+y6w3|q6SBG?ix3cPPK_g^cxh_e-3&BQUq z=LbNWg4GQ`YofL12=M&tz{1~!W&X9N1hc{ho#z@f!oX}(V1-==EZl5LzHLi}0<+FF z7WTien5H5DOKC8r8g|Ukg^bo@t@rt>8KJ+tk?0VPiyomXLD>L-E!=6d=yfoP2$M*K zLV4i$GeXJQ-TmV4YD(>!vTf6F_5!V;e?eypTANUWLjb<+7AETh*IVP>w3tTT#ph@(Z_yJP_l=fXY|ex21)G<;9tNP; z3sF=?W0ZaY_h%gZCZd)YuqV>yy?^~A_>hMi^TK%6# zmH_`-nt1iB`K~SgV|(uSOTtyokNN>f#6x&zzuNov&GWeSQNHH}zE^_bVx~D!sV-9- z@3+yR%aA|xv+7NY)>mupY2H+i+{#0J%bv|`dHZ7<=iTtMLW8>TE2w6gfNyP6j%0gk z8e9xCfUGda&jLaWP(3I&-c@GZEif{>eOp$y2yk^}G{sdxLBKEpZ-%6W5)-&(;22;a zS5N^5*lB^EAlp-^dC10awkH&0iM$H;y_*yyq`lWZSN-WSkaKb{9i#{ zaLL1#$;!$K0?1o*Tzq2#cE?tP0E#qumTR>=0~4k zHrm&-V5=vJ0cTE<_wrl`<`V9U%>Zf*4jP{eFCOoc^)dcleGu8!S4J715F&v*rTdoDa zV(%PO*JS&H(7g{jXk}i79(z$T{|&2bl!YFFDsb_U;qLZI=wIGH44_vI@@+206xgnt zkbhpVPKM(K8x3u4Vj`he02p){C81@JQJ{qyHX&(MdaV|}Lv@vODF_vqpyhYOH-zU! zOWjuxmj%r1=D9B0(wzJ|vp&T%I5wVjy2Ui#jliQOpzc@BfX@^3xI?*SHe97p&-K(ld+^UT7;2Em305tVFioHHN8+vVE>DSai#0iM{3y`8@cVD3Lz3Tus1(eA| zK!CB5x776zX$cf!2Ur?H^IL*D!`%@ zxoLuIF={#emCJVKf?#y1 zp9=x&0DrWfUUW{vJyskecqRO zK&&Xe*Ms;!biH>x*YDdtj_eAFNSRqlRzkA(%8E!bqEac6>^-t7Dhrzt`+Gkg-=9BTz2C-bJfGKfo#%O+$9Wv`7C&mQxmgXo@HsM)|L#(X z;J&VJ-_qsRu&50rw7H^p(b7V}E2-u0A|}R8I_k~%1kl2?R;jrrKUIr%W+!Dz=T+e7 z4?Qx{uKy{h*W2Om_jOdodX_(_Z*Uep$+FfR>wyWL=&ZPW#y9}SahTaQ?fu;t&B)Nk zw@aRkh`M%FSE;!fZhvdKAUcxoptB3zbr1~Ag<4xaKNS*|XW!NH zq_ZMwB<@HWx$+)*Z%fYYMUd``&Q5^wRtMWeB2E1Fsj7E;3yAij{iIWkZGVXm1=s_t-y0-@;Cb3*P818)7XJedWWfk#>q|3}iw3`j8l7_yUi=uIm-cERuS*rs6O} z3-NDnweR3!O-+>t`VuJ5AB%OPUZZBO@O$1OrY#qJtQ zrzlMCy@C7(vpsa&_4*p}Ar@}HCitLN4bg6h6))=-{Bz661=PMWS;1E4MhtOp~Mo2BoA5bZkYg~46RXuLyQmBuYnNUnEiz3 zXt=A&%1CYLehgy~;|nV*`j9$~=9(8T+-h<(iw&;~&573bU6H63+?S;`_{{8(g+s^i zPEQ%$B8g*ibuwa3Jo~EuI{Rs3Xcm=(8m3>BtiO#49y;{K@NingNYgJQl(7bk7?pRWulLG<^=odvryCa(bD~wjiSFd#JEn__i>3vk<=awf{{GA62`3{;mu8tTw)nCQP1_IFOlp*n=8M1?oT=$ya94TWu-~i z4>OOA+*l=Rz&HN@9PPy_d$Et?6i}KhvY1JtTH$#scF!zK4Kh1>n1kg!R8$Yd#_zMQ z_%uKir`7w)SN@ySwx3s%mtuSv=oVtK4WD;oNe{>oY}@|-CdV=&&T!Bv_&$a64?*gN zpt3i{6W3A(c_zMQ&%Qq(TLre@g{9?%s{%W(T^U?oGlo`yvL zKi@y;-k!$;jKSY|22$G&BekX}Rlx^zH08){J40JL50VWCwT%~Mle=yKr)wG{kLQnS zi=1yes_QZTcl)8{v}4$oa{czJi-tj`tjS)g^t%tIygGMY_JZi}{3tKtVcdN-w^YNJOtCf|NRgp>U>u=?xv)U>KztPej41|9O4f5*~P~WYn zF=uA`+cui)fed@)GCzITL;gQwD{lElj}j96cx;6-+A{$p9B=QMSW-AQUg1$Y`|g0{ z)MfUivE?$tsAQ|(PL~q|1ljT;;qd-{5i>E-4xwPsQc)}rWKn)xEhl*!G#d&tZ#Os7 ztae+KOh%GA1>WGG*9x-I(ENQr9vm==toffw2`&Wgl1@CPkOlWCONvgQb%LoyDMSBQ zh&Nl;Lb)X5jrB9rw!6Nk1go6a7LLEXi_Cdy3g^_t46EKzOc|X!dzLtU#O#?=f7g+H z5#ZE;vt&UvId-EGnnnyFEC~ugp4#mWva;f5QKurM$1~dd@J8(=7!+uO7z{sqgE#aF z3i<<7WCGMzMx&Bx&ZR4|m4Cr(@LOerX_<7x1Zirv56CwTfIa*|(ci!CnY|Y^%M7tM z*j%So3_fExpE8|dFJ|bIcJAEP3)C))4$nNZRuq>cxvk5!Wz2<<+?`=sJgyw=@*ZyE z-?X``^NkSqF}kx`8!viueqaZzaX4NOV3rT|5^n}fOhcA;4qezk23sy#I4vL8t-aW{ zsusbYnK?io{LX#kk-W>qcMQXSqL=OalHG3iU~#U*^p@{MG##}=u2W~^8io$-2hjJO&=|%z6}a%=|2sO;g}hl@TKerMCBp{#HKtNfF+vRH z_HCyn2dL+NO_lXTSp;4pO-QU<>GiT=1n0o=y-_30g@wbrvT#Dru(3`w?bgN+p-F~5 zz$qAa80Mq<4`VHtsh*d<+glL2>Z_2@lNa(IKNj5Xp8&^5v$nz*ZL3+O@*kBgU@`DWn04mTBNhDX74$O-*|as+;_FS_Nbuv0~#lc;!2-2XI%35n>>1}YIuWU zI(Ia6bwz0D_@dyw!pHA=-*qxB)q3Ph(w=MWtIAQjw&~T|b$c+l(Yq!QS?4?=6=678 zb{V;+B-|w}Oc!K+dAjKwYL8#NklC7XQo+@4il~>kYKJpL-EG$I6x;=CHPqD9up@_D zZkgFp!-0&BH-d23fo%J{#UE$EiJan;Wb1 zmyO&F4L)Jtf%deyPJ1tqL)fH-^-lt&n}2CEr9*Ucc^jaEP062|WP2sY#{d5O z3Dg0ES;T)xBH&MeIcREv&xz_21s69x2#P7XCU6neHos=CbJdnRupu-&92|2Zp1wtOPadGspMs_2%O%eL7$ITxWnl$|}Zx^egJu38IW`YhwRAzT92S3f-VrK*{PHM!u+ucpnl`_k3!PyNT{=K}BpqAO6Tr9t)J3`aOn*M+G zhrjnkeIZx7@Ak5*K%$Bv24Ct-j* zKAz&}xoh;puj}h`BADcp)8q|I2!rpE0Y@30oIHr3P6!5{x3GW<(AfhlW?K6iR2fcx zwZNop07DTy#oovyc#?PU9a%|lHpM2VO>kAj?fUSFI-*ug!vx-#?Y&A8F|IC52L-(3jn&2mQhkJL~P*E|;-Zl%$dvdaXIt_YD&)L7K&)J6~oF!au6X6|IBCx zK5Qopa~K#HG|0)lDk|KxyGTZu`uBkyhLD6BbR^wmB$84R65yD~0)0;g28Mn6_U+jd z9TinSJb$wdzPB|sGN^H-r7^xf6yYhZEsAHgF6<1Dj*i=uUZKs}lE1s=D>=4&?alP0T)fcv*PaWH`tq4r4nXWo zNZqIN%a^%E)w!Q0^3419H*Dcj+CmQUgdjwao@=nTX)JiI$ZEf`B}9Y&EdLqr5yHZk z-(Y9^%WH{Vx*-Nj)X|*HPLfuF@C&4OCw!b z;yC-eF{JbF=SM8@&BxDL$~WIV|J)R*=yR|FlsbR3wPkAL{o~Ty%u!jAoHzx~2cmsS znJ|OVjG<=;rMyeR*tml8-nLPTu}4+(I4yU0Hb=T1oergvC|jR`F+}B=`F|(SrF4A% z9!lw{@~%3cYh-VLK4}YrB>n!wQTz$44OvnOZ)H@n1~O~|*vPZev#hePg5fSYZes)1 z-FQ}(N$*s@y#rzHVDxLQTg`t&II&j}k6ngR-Ln&Nb=N9o-DdnmzG6ej3G4s1-PI90 z2wpu&s@yv0AGA?} zlz7%icJU|?`b%3|J_?5KRWDz<1mj>tS79C=Y@_cdv6eC?gSF6ZJ&tB~d3nlJyA_kb zE%VF67`}=^Bg6Fi^`n0t!oTUI9_}WRAi$E)xd&h@!zO&VFQSW2je*o4i5N0 zadQW$8bekc!%Z;DNz}p0MpcIMA489hjwN+H1N?QGmbbG8|KNaI#|sXcA_EU zW?sLsjHJ%Ul3g(~%V>`PX0J4QRO6FBOKb74(9_S2v}aAfu{2#fUiX*=tM<0YBP>lE zEV#4;tHWX&-&R@06asnc<;qwS_RAvMg^=R?Vc))e`+cavR_uc|hX#ap9|%qjHlXbx z2_IVcBwN~MvdZ@i?;k=rI_Wxu_BQzTqPnOVXfJ3L1_pzm= zSD9PuqPx>`&J*3yu{Muu6h+UVqRwb|Qcys0@GZXwpm+lV*q(nIb*2vHl9gp;3r_GA zK6>Mqv%gL|wM2u6hnG@klUO1+bWn1~Y$ww=-0Mg|7fBFtLa+5oNZ2$Y+hH#9V~ zuz=RVZt@+xBls(59(bun7m@Davf^jRdaK)EFJV)|V)S{``A0suQ4pZZy_`*NoyF~!`bYSexX5XYx)_FU@QA7Fy&Kc~OaDZ*I&W-ze8(`5 zgtO=$$({7ftz7O-JVv0EuPuxM)CRjFq+||*8jztn^yUriWCh|~2rYX+_|~=4gSRfq z-6zN!VX%4FNETZPGB666X>x9kHg^Ha*DMn^{jZf!T>{9Biu{q|BR=YkH%u%sk*1`W1n1@}ox zSB+0vKGJ!NECG@;BjvC)z@3fMe7jdx_Fwg13tb);3Pe_%P8w+;Y0A*3Dm1*ZoAxBS zy+!n!&0D?OH0CKtoB~UT$Pp)N@3&Zf-`kZLJ+kxq>feo#FcpMAi{*R0FKQ|WPg zEKi*mtmEYlZ$Z4(uF;~R@9pWyu2qrkcV-Fmp{SD_jsL&Oh7lUCXFH0+RkmkBi^{k6<%H4`$`$_bEvy#nT5!AD4EB!T)I`=>ro5wXc2@*T*y|#!cH7Rph1_Fby$h` zsRq1!Z~GiU!mkStBg*r0a{#Jh#BIN2VANZr>xq-CLaI&dudmPjaO<=yC+S%vM2=ldSS}; zm+Vueh`4hO3`=g!&ki=xvdi`S_(4LCsf2{&WOLSo8x*czA-jzH^%X;yoX0{ar3UA5 zZwv$zB(|aO)sT+KR*2{FWy}XL#M&MHBk0a`$ zwwuz?M0fN~?m5fE!0_kqU*IUfqtOT3yEoCO5$V_4wc-W?*=nGhJqd6|e zzGu%KCe}^QK%cG~=giHM)6&wAXk%xGQeM6jGWZgi6m}C_?~p_F!TEP<3o2?EK>Rs5 z@l9}|E}>au#6hQ`s*0}b$cP<)g~#CyRw~Ho)zn;SHnmA3ez8-{2$Oo$ZaH6iXJknj zCAPv_;Qt+WCm&fDj-5cx3Fq78hs1twF841lE&0q0G%#(mwI6Y&uz0>hoPIHzasBo# zrG-Tf1Ih(}2=iO()6-p>+XEEx>BgDGeLDF@c#;U(9c+iVxGcPX7WWY|Rk=>54qq{? z@!6~z{_Vrs|H_wrosWknTK3s*(=3Nv2pPWg-b>L^Gzqdjr z&I`D}@bcdIV5`MVAFO16czEW_of+rSZuBrkuG}BEjY&-c$Lk!f5)_8$twi>up#nJ0 zzoBewB;t+ly0}Pa*dg~s^#vxJ4sY}4&*Zw8Gi`bQ9_soZnww)axbZqXJgNe5735^8 z=ge!4OMQPosMI2PS*!(n;%PoK;m)C8Kt+kisp&Kw9lO)~eVoMNmFNO8NxFM6_8z1wFM6ktF!c3VB=}!2O-k1*QQGx+#~r0JVT^6oMEWs*wgTiB zIJLi{vSXz;nEQ^njig}Sogf*pn?`qW!Mya_#wB}U@xi`YPm`zSXDuxHu;L=d_cOov z(Z9ViH`FS0o@8yq`}E*3+Bkm29MZcN?r+T|9#hD~$%b;+j;x2=?_@?5Pt=2KBSoKx zTN5sxxLiR6RuQeTt=iH}L-zA8<5znkl$9et8LK~j3`N(64~dk*>^cG?rZVR76!0d{ z0pWYsE_@cnmmBtmzbpJgwy)2=+;;yoeB(6JkKeaUoNnFk=-5Ea_}MP1*}1T=!1r9{ z&)J5lbX*D0R`ZQ`PxH`G!gc1(2#UO@SKu6cw|CLe*%jHOt)UTm|GtZ8=8&i;axj{Z zEPbKvTE*?Q8;4F9AhF!L=T}Buoo$btpx`bg1GJah+S(9c($mwe3Q(vxe*+B&W&xM7 z@b3&K*{*x2!f9z8e8-tCm7Xo`dZSMAt%{M6aroA)OXTFdc`R8UZ@I8pIlH;JIXXIi z7%fv*tAU##1ua{R@Ag*ZxC4)OWq;nkG|Gx)CcT&<49o4e6Bu&qD`s}wYXU6*kbK=X zR%UUULBNlM0_T*aB)#mdzq^En!&J~83TQ-HZsKlWxz+<2h;c;j?`g^PgR>=bN^kd` z__gk(aH!p(Lz2V$*nia(g!obKbK8nN$_~*IQiW1Hnn-2PdqX%VDWQ9<;f6qUcZOL!9vp;e;@$*OfeKV5d<6+SwZ1j_p z=P!sh%`w{0Pz?OQ$%mkle>xY=vX1SfMzv$?*wKmke%&*>#^^0`@pkD&3m-W&J8P+jlVxkd5 z6dB`8zl`nG!dt^a%nN}2A^7UJgX8dgwrAUSC5@d!f(eIbnS*;T<9=YctpgiHnQx)0 zFe?lD*+b?iVoJe;&H9Ds6mQCX)FzAi&K?^z~~Wm>_zDTx8~>%Y=J9|P=G8Bif*`G|q{Jb1FEn&y zW3l)X>`<)geKTN#Yb7$l*`93A(SEall95Niz%7hs_wJ)z-=s6SuZ?_2$Zqxe%`yAT>0irQI1P$YUEslJAv%( z+!;M@0h{5B+i_ZP@$r~kMkS-e8>q$bs11k&jG$kdr>YyDIkRuS=I8W++}z9V?yGR@ z!BA(?__V74gY1?3VY72xd1mmTMoxO(Cb8`*-$5EFPDmd?IT*sZPG~ZtLKBKF%+AhM z%de@w)b}vF_{bm0ImXKH&U3xJ?7kbb>PFrhvrUEjA_D2}(ZA8+SK~B!%k^$J`tY=) z6kU?8SbS8HN=!6I_}c^->wL=70e?!-S$|^Bi{~RVlA9hhpKVg}<$p_-L})-hfg>cZp8FL@>Y;tjIE+RT z(4kIFPR8SYHo26CgyAoP>sk&eYfUkKV4PS)ZE|vuK2@qN9esv!f$Y5`JT(a1HQ8RYZ9&mk__a zxOnmOr7TTNO~HLf0A!;|@yWuk*h_#!Ck_8uX=#=+aWS#yo0FDG3%l8O$so5bs_E%& zP|Q=YeyEi>OtmX`b;9X-(J|?<^956Vwd*O{^IEU!ySj+6T~6j>u>ITkA$?1a$`?I= zapSj^T1_`}^3$V7(%L2G9=xKY_a07h4ZY0&GS<(}&wJY~s>OFEkUgpeZCcjny88&z z@qnw+k=c2BTV7uH{J)}#Wyy|pKNUz`h=w1)yFPFLE_E?6px{TVaA`6|lpE%sDO7#p za?YhfQ3(9yP@|8?qdtDr($iDd(m|S~sOWE)FZftX8$u!i0s=}2^b5J3HO9QhY%l+G zx^?~K%Wuia1q%zmKk1a4-7|-!By7P_aC06$QYQp;M8#WJy1x>=m}Gc}$gR?tF}bVT`b) ziAhKgn@$UW?cXnne1T{pVbnhrkR0Rgo~|b*sAsMvOUqHk9mO!K#r!jb<-zy6bqcD> zF~MkjtgZQ}gni}DxJPL@Ha#tGkomIU=zex~3MH_KQy)E&J|=q8(`Cukdl_5eSH7kM*H~wWImfYjWj-alCV@Wvo+`IlkDmQe{?8 z<&5fRH}f&RyMD{q!NCD(2ui&NHHaM`SAL_zQy*|y->&#(zr6HWR|kYzWO3}*ubdS& z0uLdnMeX$lI&-V~FX4pR}8nhp(@ahn z+=%7O^p@+u7eX*GR6f-1?J!z-;|(^1tm6QY=^s!hMor#k|T{nKTgNAmY2g2 zE(MF{4Xu2Q)7A#|1t?FT$X8awh8pD|;s;c&2}2EF>U)WV#=-6@a8vf(!QB~Lou=^ zKF`BH2%^zKK=<_>q=O0pplxGIO}V((LjnBBlL@l@r*ssku2ud-os9*(;2}FOfD(v{;6;!e%KASnQ> z62+4_ynmOPxw*NsbJ@El&!cVf#{>mAIRU1HP>^ounruadn{Wlr18}^H9!GsWp6Kp} z5R6p@1^IdYesu<5F_t`9A#`*Dn3fwKKfuh)Oixdb!({97+?@A1Rj zX2!a3fFK%-@!z;un)9@+s!;_lCtZA~PxW zSxcM!iR(TAi}v?lKQO`t_iQ$;1_g?mIZM5T#QzmGD)R_o1H)W^0Hj1kKZrsO{D2Yk z6S5ya7BD=WoA^wG9j)#JEzPH&J__*j^B+BGT-XT!{a;TtEFYxe&{SbT!MB25*4CWP zS(J|5(#}GP?yfnup#?>+ve?BuwZ`fC(s%+ zGzons?2S{L#i$LRKE1Q#Xk|4(07c>V)zgy;Eg@VCIwhXU!T5sXQ&NHFW<@k1Z-$%{b3*srj&CMgpt7g%)KAxu@>H6qbX$A* z=NU0gHghse5V6*Af=ZrNN%z5jekWFF+gn7>p#40K&N%3rJ55($6#ce-n=*+S6=QHJ z!*BgOt+0v(vc|mJ?h&jCYz9O%ycxoKxMef=XLgW~iKggRH+Bx%mDh+x1w_x{dW^NUjCw_ z4T|W!z4w|>rOwUG;jDzL89>81_Y~LaG#y>Jt5^C)rc!Y)Q&KjiPHGpOA=rJ|+H%Mq z78Tu-uXTE>?&;i|<_&t(?#PNXG_1rDXJ=;}_uPw&)WiRYFc0|?UsEJbw6@0PW=`II zRW(N;ab%$=A%%VSPOAC&os^XLB_LkNvNV$Ay;iXI9Z-+k+H#9$0}FFx0cnN?UsP0z zbf@vk$jaQ@UPMN=V%w1H*pcM3REZCr>VKu=WAEcAi1U!<@iWf?0|N@g6rCq4_Pfgn z=ig^-xKP6snAaV`DEx`P1Kh^dZCNK7@~5iX@t%*2r_d~0jljRyL%P5ZnTsYrKv z@P78auCZ`WvX7%ueJbe5#2|6^Mu_|dXZOAcq$jiH+^=$Iv13lH(`QeI{1;b*&>j39 zPcuPFkNeR=xpRCMZFAON$3&e=hK4aHD715ShEaj2VN-GX@P~H`&i|A{)9Dd76yV!q zgjx0+Lw^Oxs}S8q>zi}t)BE?|V?%j)xg24^#SL_Q%Hkha1p062*1m1Cv5*7ACAjZU zbbel*Mpiom6B8KCoi0aJ`yx-HrE!BZw)?|$u$Fc;#wYwK*3`f z9=NRnfk1N>3sG5lhi!&!1#8d)y8~2wWCCP!JC>gm76RUmx(*9Eyy$_$Tu={b=MRWW zry|oJ6Gw3`U2-@~mrE!Uh+tdPYpVwvfWA)rr_~@P7BC(V0vXG@k&#Hg6%DD)#;DXz z=5qy=!3?!@90of zVYJ@bICkyfSY4gmuH4uto`Lgr5E4am90gfnVMN<7AdNjKH_8=Gn4A4DHRvdcDJXUwHhTHSnO`qVK*PUX%->Gx-i*}bm6tSpwnf&(hmaB)S>wR|Lg098or5}?n zrQPNL$X%)QmP5M3M9>!&HSWYgrX%Jb%EI}CT^YHxsU3Y}|9gp%W(9;p! zyKJgZzrAVBgJ+|CeUfD#{m9VJKVy%B%*^myo*o{iaDQA}EF9QCxqCNH)&klpeyJi2 z^^SyS3vUEan9|bNC)CgRt{#iI3N(qV(mbNkN%5h&QRYBKLJFS-L;e|00R#BkGp>$X zZa>%FmEYT4|&tdjdx(}MNHFqWt(a4r<}{+9_6Xmg_=$MX1pm{)||1o0~Z z8m6G2U}tCNVl|+luVC!V5IHAFTK+(jTU+xW_v!J)wVTl;=3F0IT8#6JFlWORo$Y0z zpoD`95)0_4#Lk^KaRLTQSSQDh#kPWb!|NoK927*Fp`VbFa<6R_YabJ$(HdXAeudl} z8nUWtnE5*L6~KgzFx zS^zu@thO<5<^u~*Hp~YXj3*`KN}qIK-koM-+&4WA`-#=4g1yx4foC98ZG8ZdUv)wS zv@$wL%X8XG^9mFU(Rs&rKz;fp89qO&BIb&^>;51H z8IVpX79dH{O_gy+gwT!`y6)fr8ke1e(R{4l6l_knN80&vb!CxWc8`ADcHG*Kzj0j_ zjs4Q@?#PJ>^ewQKP^vC1x#XR(t^_p;pI|3ND?&+WchA?arCp|_?xviU54G+vI#p_2 z1RvN?AH8g@Qthnvj@;bhr3E@}&?a;iGW73UxbL$%FJ1b4&dv6Za`pARva-seNu`3a z0IhJyb^s18EQI!Q+{1@pWz<^qBT&Jdtol3~Ypv77_sJ?VJ?=-iv6nqS3` zdFya1`I_XIv$Fj|1rE9}6-Z2oibi86LB>s8-Ns8!M#h}!U>O@dHx(r%Ep7k zz zl&4-@H{KMQnwkBWm@FqJBVS(yVs?SQ5A2?%CW;_&KMyYbEBg9vC{1bs4b|3)o@Gap zhn+S#xqEa3FfSypomXb8+1b1tjbo6bYnb<*(#2Zq@pYbMw?tIVWx}~IiR`3k^R~p;7l!-&K{t@z8Xm7ol=86u5lMEeL(HbhZ z@(l&zkQifV51d?Ev65``F)>AIY6|#MBttkBFvCYsRGR)gZ-GnIvu8*LfGxw#-T&P? zHa4abAdf{1{H>33Q<^p8lTtc+dnX;GLch;zTzdC8`q0n)qesUR1Bdr=Q#Y&r!7DxnoB>%RM=3PB_l&C$St=_B!Y-%V-Y-dt_;L)D z$9rwS>gn|5-Sz_+CCX%~JYN?aSwN$L^wE2U0R13gYcIBAf8X9_2xvny2c;Xq3?S<& zNYGN~etDvChoT#7-=(b7?uEAw49O2P)Ipm>r?H~4(m%-o>V0#6KKwN5t@R`fOJG3} zhIicO|29T2P4`wWBcBCY=E?5so`rNXI8S^D&RaG8A1wf+d z)absnEG@n4IhbqV@MWC9#dm_?@-VjlyV-?*U->#bCXI|`*qMGpmQfPZ|w<1BbQTyFhCU5oK7FC z!l0JPoV?5sPDmoh7srhw4k|H96UMJH(DEh4=-zL|8 zsA2!10QfTz$S@4Qj`j=;gttZ2wb8lT@dq}H%rB=5xcU;`09bn7IF1f)7UoS)S^dG(Y=E@Q{-+dGwr>1_%M3Ix@%dTpJ~ z7#qjMo0ynDM>*TxzbhH_tXY25u zR#gpdutJNQh+I|Z)WwTD{@Kt5#|YTfa&Q2MZYW(IOMFSn9sa_7SD2)@I7j*DqbOQ( zYJqT051B4a#%}=7USR7TvEnjF^|(Lz<|)I#Z7gw6G_baSj1Oc3>VTpt?l^@9$cf@65Z7T*DQ zLQ@WmX>0a5R(J8U5VlQ83DH@8#Y|7?3k5`Kk>V0UOa+cbSdr4zwWw0!AEmIfu@Ni+ zM@L2fv6phcPI`ZOoD2OQ|F~&dni~@0yB3x%Jn}jBzO}hIaOs4wupU=5hWmwFg$=K~ z9(KI08TNHtUr9;H(2zc@b$HfI(}ry~se<(6#rdTMFBS1gc217<`aFmDbg`O?zXKp-t{p`Ri`(jRqW zq)~7BH^2WA5eZdB5AKQ4_2#+1AtBb>YmN3iFA6TW_;lEHc+G6VfG&5dTGCg&P{nfN zn$GqHAAw^mOcdcT8i`#=WQdkq@fJO{Qn)O)W83_|xMHUK=BVDyd6X1?#)?;*>Q)wt zijLZE&!KM7v?$(hN~dN~e*Pd||&Uwxz06+lAG#bv5< z2}8R^0_QIu^Uq07J-|d=aO+mX-9Jw5YHD|k1W;naw+J?LRL9JPB#$0FB@~b5Su;U< z9GD!G$3be^BMcJVBXve|6-)r@>e3h{ILeWa-8ADgPIyj1lVtQa?aGzz!<{bQIs}D; zD$2`uOG@bS@{Tx5!**$6k3R>>9I!VZmv!4m(9aHac1Ca!|LwmCRRuKuvF-t-JbAKf z!nn8#gl!JU;85P=ce^Byx|}t(?BTc3i2xK3|CER zxwAutB>QzZ2*($6Ujaf3&=1uVy{KoDM|b|Ue;KH}>6NbbjwRKFJH<=D414v8J<1t@ zW{(c4ewE;GO|MqL^@k7lseFNHEGjo#5ZG^n0`VV5JO=<=PoAJ~0x|~A$G_McD3Jgi zN&%2YiipN-g@=c(agzF-5TwH{)W)TOfhMW}C%ex|&NF6_@36R3+FZ`5`%M2Eg-5~1 zeE1l;o#bF>6g9u-85BSkVsq)zos|%HKM@RHi;DKd@kjC3sC2;yV?jJcmm*p);R$qj zua-mn0~|kli5;OPMn-7Iqs+wEebE^V0Ia6Jntt(9R$7``ql#w$kTYg=9Mc{>!m!hK z0$u(*_0IgGhi|T~`Gq)19R!KYN(4Re3pgsk_kwWnp+l$k{4&ge1|dXUqca zuQsXfsl1Z4+}r>5WKQ&mYhcI5n8_=WOeCW2izX_E+D#@nt)r2ky%;u;k(HE;HxEsQ z0Q^1GqBGk2mWMcGWHut=n_F9(E|{2f)tL`fR}r2s%ra;}w*CK3&5C;nycwJ|8kUEt zca7Y)PI&W1<=HbTDk>SaX}g2XcH#ksql;_SH|XhyF@l9CqN(YxY=@wH&=@%{%4tqc zMNFOM0hB|A297*>J2Py6kO)wXre?HOjz(g<1~&pd$d^L#z|fA@_3MGljJpMr`=tpe-k9@8f2C2@ycfpPyk(O2diIq&n%tL&tWS?w?P*rU7w@F8< zTI7wTrMIqLr54Z-tD>nk3^?VlMa71KMqO;()Uy9eef_8J-#>l&1Y+FSm_R1bh=&pn zAL_QYrkyu8PfbJVVu|ZwW-e1+;o@~;s$*uR``53%&CT&^>kcniMBe*eb#pt8C;1a!Xc%@}$1?c0gQ z)T)<=7sbV`_7d>Ff-h~k85CTh6U$1Yj)MEj74R*RQ&ZUv9<(Ri13S~yq@Sz@rP_OB z0D{=B9VNDeOtGz)SL&*lkCGAzhRJ8$_R58fmzlX*5pB6c6XPw=0mDW#?ehb)Is_O% zl;n-w&&YUua`@Kv>)^;!jA*vSgD;Yk+I3H`T(Xz`k6P-lOG*cMo6zw`$KHybVpdC4RTT~v z^K;lgAaBnaDGI^;Nn|4x3moSaP_F1`P6p~{e34CWOrL3R1HuO8jAR3J?vi~iA3hlH zGcf0%Lx*hq>w-W5hQib@y5}Y(xoVY9c6Q=?Uc7yKkftfyh{WJBvLummxcVmxz$BMgu`0K!1M+Ok#zp-?R6D6HGJ+| zq_eZm{m9nVR)mfxLV};}-M1K-^tLUPdwy1!W|w(t;t6>f=4oUhX zo3qQrlOpf2t1n#E7M9SvH9MEvsk(S(yhiMmaaKbT*~$$OW@jU7+q%02C<}HQs~Rm* zlEoSuD`cwdrdB4})sEoh!&X$byv>KAD7=$y16BTe-3-NVSIgZf7Cm4kU@Q%S%El+8?CIk0o#d+D)|szBz)u=6wY%5 zczDRjs~uSghaTAbp`jwGK|c>uSnP{nq^B4AdwZrYcxRf?BfumWLdO$VP#fQrlf&vq z^FJy8%$e1d6}r;~*+*G3KPCyF3q@$ifJ{R{ag6zHULL>3X=^JMBt`r7eOuo;8A`e1 z7GDjU27`=qK*9b3RDf#g>Y6oQ*qA%VclP;=PgeFnM!;A+Fm%oHJoX4z>55uW4Tght zbLTJK7)3H%Z%FXL-V_`5Z9Jin=_@``_xs?Q$@X~)jg{)ot32s5gxVxdn5!M1XM0L+ zd*Zg!%h#`!?B^gv9MvfA`E&ZiUeq$>-qr0)ng45^@iU>$-@R+sF0B9EyFrt?d+#2^ zR{yg^Nc^pirS4wjDf3kB$rgJiB`i!EHjm~mKf?tzsekP+K5lLdE?^AaC=+KD!U=Z9 zKk^w?TDS_ATv}^}76;t`>52GrEyLq(gz=U<6<7-sH~^B78y+BhqQxIwTtDFDdHXgD zUz$gI_>DRXm+hGRnD#sH*)tr1*R{6+R~ zU#tZoS|Pl_8rbdb?Q$>@P`qZ42kS7_bY6Hyw^79%fBrAG!ea^zYMJnx>s3|Kq35i* ze`qoC4srIOVb~OjUZ&OSnwsXJ*C%iZ`HnYMem(7(tjn)}(a7}62nQhh|H?>z3V0Z! zeNbgWXF~7Lsyn0?QT#tGE=C`x36f3g!=0VJEF=Bq=c-Z3cNUsB96Y%M_3|wB$fdal z_&G8%2lYF?lE>YF<-o#Ba(iRumqX-1_qy86jk%$w0|%;?r+r=iep0{OI%O9Q2!i}} zRkT;Iac-arg9Dcve|_0-HSlJR_8Y{$AMH~CLc*#WIAr!!e}Ps54<&6q*V{$$cDM!r zAA4@NqJBiB28KSyDUw=5O!*HV#(-5D2}HYb@zdg6^WQx`DOED+#A%mTS-C8emXwe{ zaGp}K2Bln|A6cV%%$L!(Zt6F0p3@NVX&jsdJK&%9h51xp=>U%z^In@MEu75mGHelz zj}}gNxn3I|q#k_x&xI?>&d@6TAEw+7C=3W08l0#;f(HHkh}v3Ft{;^1V%8uOau_uM zQx1g<*fatH)R9PV0R7M<3SpSlql+XA#KHiT+{cdx_}6kYK+18{$Zg*46vnE)y%o0o z)FJ|Lz>)42Iuk%mfEaDh$}R5<+gfXp+KX?^E{xVu#~y= z>P*QtLBoGzklm)WyZfx*)JgiI!oqyT5k1>5aN7qt6m&!D%D|%8eCm_N)DcW(Ucg7bz&^dnQ4C}!XG8yVheW*l7 z#cZU%{%ⅅV7k`DteMuh>8muWTLAC^xD86qift+B>aSjiUgvi(0+4;YJ zflR-9r*^kqdGDChOWiBs4!N4xNtHiOIVD0wq`?$GSH`iT;$jN6>-P3cE_<;8#0;Do z8JNUkSm6J(|5N3Ceb54ig6SkH$Pe9@QVNRBe{8vu-6IoroLJ6*BO`lWBeChd3|lqX zM%c%X$P&SUe0yXM8@0^XDljwW=UFzI#%M#*U8hwxjnhJ??gTAKM5GOV#m`I!*sh5% zKhU}e_LJA|lP6<~$5}D+R1>)c*4DSEwIy ziY|FOr+ZT2AmZRzP88?oe3N4Q3#Uk42%-T_)j`@`Mw?VFPK-3_5oHA{s| zw1LsMm{If7a*iq>?4&uT)mGmnD5o>E2hR7;JEWTUtYS?Y+RwI}CA}gI#z=F|7pAkF z%`)S`w`evOa<{EJKraZcsM(0LJVuW$zFU85%1QMbPL^_1wvw%ZAYa%|O;786d**~K zm$o@^**02k4&v~Ou zIF9WlPe)Jc2P+Snc$D%*XU3B?R&)}l^9o2DNg27irywY%(;a)l)ixa)iZoqWoSK_@ zf0k}8dNWE9?|UkNeLZiJqqhWw49D!z-5Bdo#0wD&juL$e?TB9{62oK_6uf0l?! zfd>&uj*pEEkQ0gg097A$w5WezyI8Sy7;n25bQLK{(Y7s zBlYZ3)O{E6g2<4ka#XB4xxngq;kDEP01mh}aGl)`($@LqWOm^CxU*Q9LzohFJIPAwE3-b|;1d1_lNc3I-&h zN;f$)bel`GZ~j=IO?9tsjSA?AHH*7m?T$=@Dnd`fa}yApGig7N+}OMK*%CH{E4i_hub?=iFScMnCWW0>pA} z4;V*}uy4(TV4xZaDmyz&X+^eob{>FRQ22eoRccRK6bj1j%#pVMIBsnf=I00HfsT?C zSJ6)nyM~}Zq4Qo9n@52!UI0^*wqnq!i*G)qp)ug}lISsABGg}^H6A>A6mIQB6`32O z@#pMW=H&Pfwz&1Uy8?8A5A0C+yJ(feLkeUDn$p#~Mux~c^!3vrZpWlbC-a^E()Z{L z@iajXi*#qhz%TlNN-7pZ&pg0mvl5yO1Z?X1^_1yJ*{T{D z(D_9~95FeDvbOQ@Y9>%+$Bb^dI44`^9BuXh_1W)i)mZ>F)kY&;N8Yut3q% z_?#uvJu=tPVQ6Dh`iA%hVa`a&7!~z^8&XSfG(q?@s)wLqj^WVXzmFP!&p!@VR}RcI zJC{Mv%EF>l6Qh)YyzM3flS$LF)22_b5T2QOiSt%*2^XIbA>tZYSy@3BQ^HtZjj%&i zRU4a{c9I4pBqSg!ArBNCoxHu?^HNWT5ociAr5j9);apq;6fC$O3=E`9?bs$9*Qu_| zafh*a7>ejavJTmqTO?O7)tn(}o7iMhIv2fj$2B-kMc@h`L7o&QXK?ZecdZly<&6C|<7dnj;dDdzay6s9E zzV7YTVzv)C#P=WpOf$@{`cfs(&z?kn0Z(Dg)9JVMbD=&rq9!UwyWANbPF>o4SH#0K z`2VBpz2mX&-#%c3GD1T3JdNyR@9e!2vXdfYWzVd1l1-9%l8_`>Nj4#w*?aHoEj-8B zec#XT`TgmttY`5DLYKHek#W87)XxT+Lu@Q`MQxH!0vUM~CkmdZ=dB;46SA@Y- zl=t(G$3s8*f;G56p!kE$qVnMFr^0IEr{*AmgDnjoEi5kd&D<7$r2usRUM(1gc(}X6 z5tqh5B_<kwRsVt5?Nw zZAdH~n6a<|jX7)dA9{=S1b(UVPWv!3GsA-^1Ne)C#F(vMH0SQV1{=FH_^85Bm2<22 zMOqqLpv>P(m%c0l)ylyEq7bbi6cm?*oBI{moq0*l3*4f7b<<)~yDP2gJr{t?%qodD zNJ(Kg0ICI*6BQNGA(vSC2*Xtu$}Q;Z8`K5ge29%D2@DL>(Pdy@U?zfL%8RM|LjLE0)q_YSb8s_ zP5rJ9Ug)Elo;X(EYJRbPng`VW3318oHHB;_d%RkKpW6QPy2`grmAxNPG{b48kW+8< z$kjETyYI3^FYJbMoZ6*j^}heYhU?G-O;u4sFgU-P1Pm33+9L%J2ttH)b$g%dTg`4m z`v4~;3{e3pS3$s2gmmVAbRrm6p>$s2`Q+b0oi#s~Y(~Mw3iM9bemGgu!0!9n-4K_D z;L55G1IBo$b^#p&>^mcaH%^6fcJ7ww#e@3=)!B`YOT~%?OBx#imk;g(+BASBaPhgj z3$>eKJsAJhey*vD%K7k9Nmtj3Nv#>x+I=Z>gX&bUtpo)P6ngKG3#eE9FV^Us{o^6V4rfZGzSi%!d^);4K7H8Jc&1V^Htk z&*2|O{d(0w{v#KK0^VZyhhQkh;3Yx|&A2rH@+YgSqpPbxO@OlmtSflCetn!@i09_U zdiy{Jqb#b~8&SHQI{@qj zsW*&fp_KruSk5HiB!PH7MW394;={ly2pd>j98z20iseY|u-Cg=`GJ#xXfM;&5&Hc! zIQ>D>);-ms@Du*Np_N5!KW{7M*@E>P4TYVY0L~ir;zgrae=;Y~T$;j(Pmhjh#odNgqPIlITqVQDWgy6TSG|-*u<^5C|IyS$SY-U3{@g;~%!^fTn$sZ_Vhu6$m-c!{1AYBzIsiMH)PW1y5RvETX7LRa1uxR;`pX2Rr2H*D z?W9kI0vs^nboV6eKeLmdP0!2b zV({P9Pl1#FM;43|0r7)_qhkRJ$;Qfxhm8d~yKFRksFL_k)Bv0kPV6FJhSS0nZ&Waa z^K)-vA{l*5^4qrnyn|O8AYC6s({MDmVc|T|bSZA?1ze`D$Jv+}w;MJS$cf3xZ<0j- z24LL)V=)jvQxm=@%5DrCBpb^Y_0rKLxToV1|B6LL0EJK#y#9C?T8&@&arePpALFtH zi4=(*==F!zK!@I&V$A)zhAJ?;Ndu*t+UcQypmnYW-;-cnEH|sPks0UM9`<*Nm@j~n z2-v`zeXQZeei^FF%bnP3l7{9UEccg%Q(hvi&CKZj%G06ktzgntUp$N*L-Zj{%LZu0 z;Edu(%5wbt9hfHo#S^X%D70Y3v=uXy8d0d17nPS+&VPYT0|+^Yo72#=tlPIQC7{Ja ze^`_^3{n9~g(+-S4Qo+|3D+-qu-;%Ngk}MjK4%gq)E(e&dQ3 zIzjPorUs*W`p|#RyNY>nxMjhe05e|r1~U921E9K9H>j4~=bnC-WVP-6Y@nzsI_K)u zX%w*3O|W1-56W?E(4%Sh?VaT!S-T8)!D% za=(D?FTE>j^J{II-KNWQC`tQndAI_>y%KZtSifLbrMrXK&r_eH(E9+4x_4nCpw~ap z2SG=9cVTI1X>&6W*j~T7dFdrQfpo@~=Bm#T_!4)5)3XsD?r*#MbKCP^bNFP8F2i%r^wau0XS_qlw)cx?dt1|KOSFC%Shx9VWHu|oC*&?v zM_`LT-_~@SENXX4Tfr(GdVO7aG?MT491RIVsux9Mn87UAK9ey2vmuXDxx~-;4tFv3 zBgj{Y%(_7Ga%L_0HBkc&_!QHPtH|NGZK&+LYRrLfykfyf0(6TY+2_+8IvjhoL%V^# zQp!*E5{GQS?R<@+EDczkFgf(&hdAL>Jn{pR)rN~l7J&;y*)-Od!Ua^d&{7XYB9La68H7!rwxxOt6Fw{9xtwa1%q zn3HblJcrbU!!#v-lo0@|eW6yq2%?Fpy4oslfBUtnqM{{FkBqTV@s9?@Kw{R;TT*&~ zI@2#40CDe%8`Pyh+X8cR<~Z|W$X8X$*}m6hn`=ZECI?&4y5xJ==PljbzYvBB)DvK7 z!IFK-6bP(+>L`F{V9vyBuh3)(Pdr8AfGy|H%7SkXrNA1|CO{d&j8hASn6|e0fJ}r_ zOXOu9x1>6q3kn7t?>u@wH%3N^Gp^u6D$oN5CI(vLK3dRq0zDfHD1i2W%uqBC560-n{s{`(k}1FY|oz zuok#13^kyb>7(ma*^A5Nhx2V(vkEY6r=5mtjD{Vz-|B@s>HQjFt7HWT9&97`vavjqwd$2%*n{sIq0rYH-O*Wpid?N z9))0ojh6$eA?3zbDaj^tz>2_#8>^kk5Zo21CB>7} z8ZyW~n9MT_(&A-nW@=`gw1{VsUX?Mg1uuogmGCKH>d9MF z=#Rq77Kv)SUzB)Nn@@55Q@U^43p&QNDKP1l8$T^EO4G`NRt%W#RpYjTAM`&+p)70l zZYFme@dbs+P7k5BlWiUY4ogf#1nf;Gf@8Q|z}yPrK{CHk;94&-B>hlx0(_zQgIweTg3y0fg`Dl3&^m)V41 zKkygmsqD>z|DRS`R*k~u@!hx5Temqu8n67iah!n^ju2TxTB4=%49LyhEOwmd4kl_3 zmE3b?Zx;7>@&x(uRU|sdT-tjFF>*YeV9Eb7DJIY=mfZ{5z{_>bL)JKOG5t6ssfqlA zVTSn)>wi}H(dxhTZC$ILtJh3*CkB={@N+>seEJ=-+Tl2gx%@;O;BFs{A_D@6UO2LG zLxSpk%4Q(%pivbx4zi50qlCsUkP2k3=>H48HZ#sy>ZqAbNWLPo!E@FpVS zB|_m_)5tUEe8Ek_h`Vu^%vJy*Ny0xcCXs}b>aqu~U<#_z{$8U$)W(Kj+2DaM{fvmj zkI3A%FNi_p8$8(U1qBPx?Yg?QY!-XhtkHM(b`KA`qCUf0RaJ$Th&BSJ{H6woE0799 z-}z$82St!B4MN6mWD79aR`CXD32}QBKsO>qA2ZB&jGEVzKdS=_@n1=0u@iU5IwpC2Qnm&nc`)8~Y}xaMHS2;&D9Fo-MDiGHm7X3Pdw z6#yonWCg$#`l&0)Xq3*;QK?jNT(Lp6_dYSg=W>1q>=fUF5pdv;K4V+TccH)J`p}4j zB#Fb(($h1U5oX#~>wDn4VJmzXvOhgPgf<<-t@{ui9k?$evtqNAdv98F`sghqviRrk z?=lD=$6$Vd!T*`mU25c{#YEeEY_fPf@8uaS;Q2V?(Z_@*frm+Pzba4`@-i z>k1F#@R1y|sov_!yHde*lcE|Ay4T0 zRR-Z`#y9HQM^@;)HNB4f%wl`UnWzAP*p1cK|Ll%9y#D%9DBJKO-ej=( zZYCB??wD|^4q%=)w7SJ1Rl<6C+?|(l!GXDC#^c7#40YaH37wA7F%}2M8M~*#Ha5jC zxO@=AR0eLEnPSqqc~$UNw5 zd)sOs#G|2DV_qCX4LL>PByBpn`>~0^w&8M2JDiLy^g)IgA7uv!jQ@Nyt>8`W-1WYl z)~hPa)%sZTRW$WY$`AUSKzkc;pr@gURLU{YT5{q*fWp4Cy4s|0z;Qc<@EPh6#T9If z9Is+KL_9%_6ucb(hSk*6#D>9s2dK;4(-UYM0DnL&1C|exu;xd>v-IR_GvMeaSK!Lw zp9!i>F}gE-N7B$tSl`RZPPVqP7LxC>08WF(2tLA@-IM`brudh~bELg+@B_$S*FvW_ zNsvgqaOdhFMOheiOGnl{s^jK?4m{x~qL2)( z(8WWS-Zh3ov=8Lr38zMpczYq4Jv09Gg?$i*2m>*RUhvsuOAzz2na0Rhp3wm7*VdC$ zVh4k^Wdnf}I0F0n`}b#<#!HQhAmbibJfNT=!xs{Y%?(M*_gt?C^cbFad|R&rsmkj1 z67Gp?U4c7Xo{S`njq=qo7;zAW zd_D#4V5!pf`Hkjgq2%3f1FlggRd(g$&ea(NVHw(Ne7xNCrlbWD7&gNp*cot$85dP3 zT}AK#zmR**6my^(z9ZEJV3dSTN^7<4d_U)LtfnofoCvOY&e8_r-h3iRm=i~UNL zjOT_56+VHkfEe8Vvq@XHU`-c>`~&<*VxGmO&d%ys4wdB}>DwkF#bZxTHauaP2`VwP z>gbb&IPsD<42t7e`7&SV9C{Ukp!rr;P3zpI_^W({``R-8L-KpYhkBShjdATYY5U>y z30irZ#uqT2YXI+#Jx0E>&2Qmg-0|=}EW?Kxemkn`-unZFXao7bpRTW*Wqtx}J42V@ zjT-#_EMYi}U*1EX#&3MHADVF{1@AyqCjU$Fo8mK`J-|{uEHes1*WP;>cDw6$s%CmR}d##_8$z-gJUAug~zZP?jtLLH0#K zMY%zi$rw>{U@eEpW%QgUldZ88eEUx673mZDnDUg245c@u{ppM$I>>m&9I(20H)&IP zKfYf9ksZq3C`{&~oujxx0ODd6z2wb`1fp%QURSY)Z4kB6{=coIrv zb#?RaY-fiy%>Y%jpx~w#5_)AYQKgLdITyz0hzl7LwU<8&Fs2xa;)p`*(-8*&4#I_L zf?kqr^I2QAy}_CV*Ftha`_xZF;ed%G3`e>-gpB$zek-dD!|<`Ehorv;#J6RWIWC9d*@1?bc6Aei#W$NJu1S9v%2Xtl6g9G$~A^olJN%)Hd-xj>ujW zY`LCf3xh%9xj42M$z0G@O((*6nr%TJ1J237?pWm^qLEC@S74%6oCAZEr9=30aL^;F z9m}z?TAA_Lv2t5tO8VL2uix4-notF=S5I?!NWgh0Sn8#4Fpl$m&ABy1xR05dLU{9z_j5gIMcu_oP;O-*qTCTEBpfgy~vle4f%} zt}|3FF!v1CCE{z%{;wuRcYf28oLgBcd+4ZAkbUA_z6`A#SWsqmGtkjN=ML9+@eml< zw(&sh(lV1N9T>zj<|yUBBnr&8xyg@r0DbJ-L43i}+-p`Z0dI|fNN5t^mI6*;jVJCf zM?yQcK64x1`8%M;TuOEK^*uF9b-$S;PO7M-wc%a{l$w82mvTOQz43 z_g4Ou_p1q0)o0_+HYMm_4rs|0U8Y8FTwE}nnqusAQPrA)4e5My3+Rp_sgPc1?ft1__`;&-%v`7tO))+ z&V=P2p_F}iaIC?wFTn*polK&w--Fict8NU2%~jCxeT{kc1mVM=$dU&bDVYUI$8x8M z;XGFIHvm# z2GH~p{~vP*P080i(hxuB?kI_;Z+Oi~ zLY5IVID)h-xRw~b3h;J_6Z<_h6z)X@_Cp~pUFg^}X|{xs-@h--DQ4->3d>%VH8E7a z9J>sclohi}=#|?k>i#uArnWQq=R*rUqFw<)I#10GyzVMLzNXQ<>QO^~UrIQ&bH@33 zggBbV0JkC|eduk7k%sXrW3Y{k=G+`egz+NJM~9uQAxXS{;e zp}AYlN};CTw|p0px=N3q%igv)I!gW32<)TH%oOiR(tj{0ghRKZ-zfVBmJrN$V0eW` z%9Es4>WQ1h)0pKP4zxSiRfVd*pVXotp)B_e9U=aP}m~T>{wZBQdHOXAv5zW zsJy}dG@sMMs1Z^~4SoY{h+~!)+wijG)(2RV(syOavVKGJ5KQ#t5E_i;t zJkB^c2s-dkvbVSK^;K4G-MKzh>+QT%+o39XdGgDfdzUWxNe6m(99TYCx#2SruGaFb zW+K%_>yMP8dAN=YCyzw zEvXeCDIN-fAY~ZYTa_^Or~s7)Lds>IFF%E*h!pwNlsBPW!TLG`x&c6!dHHaCZS5gH zA_g5&L_4{FH?Mq)UJW!I&Yn^S}+_WIh7a!6_KahZIH;t z6(ypx{1D@k&#Gug+wm3pjhugBKo zk_kZ`SfR(g_^e7@crE5=9JZxhIsQ-^y!*yQxU+bq5j>V070~5bzV8YBL`#E_GYpf@ zZg6DC*UiSA&-UVdSHMvDRt1sWYs(xrTron?Z%5oxAVseY7W>H^g(bsh97#Rl7V z3k`-03|^;cHC0~x1;0tCW@x2<)tRgJsqFQ>yWM;(=JTl6Zn&*rR}sZ z_QK5_`?IM@-W2e{&6IeOlK|RimIp({*sU}{tyRdulpwvxtTow*&#=x z=>4(mlEh&(do399@eRxb#*>0SQYz3q}WL*N|Lgo~8g?(?+s}ah0xSiGlJt@r2$ma2f@$J^p zpXg(51UFo&*#KPb?U;}u$FE$yBoZ8=LDUuIsQavZA9C3PBoQfkQck) zeuK=~76`^cht!ywBJ|7rY-De#2`u+YWOgjXDnSqz#EjMsxSBJ?jQuf>VFxBTRuFiQ zz%+I6JIFyH`NQx&%V#%dpc;kG@gi1H5cLKK5XO6F0sx|*ho5mi@{_g=iu)So`4wP1 zTS1JRXPg7Yf*+RH*&&t&O63n6Sf3sKj|(uc`V@r`^pIbV66l520x*Fi!>?hXsNt7% zLzVhhR&D#4sJlO3Noa3mVM(T{8M=H@N!@j?JMCwt6i;!njj*r)HT4M%_2}AKa^0>? zpqSa$*WEz-&*^u1tNE+cCevs2W=!kt$AXSRX>mf8H^k1pGGDPR#5-b&WEB^F z@fUKd4SAD6exCL4Og85{Wn?dI;^0~2@oNP?_!aW1N<2P&`Y=FpL)YtutdJk1_|}g>kulTtT;&wt_v%!O!ej2yMv$|v^eR!iOgtgjiw}zcj`Yg5XIJLO5mHSMA zApn-SPYmN6f%H0N+;Ye`5A>Jsd@Kk_S#{t&pLT?j+ye&bm#Z$SyP$|R5~d}ZLxE4i zdX>{+zz}P#V;$_anZT%CuD<`B^8BljVq|gXu}H%nCp1`si3CyjZEO5^q!8CE zMn>EqmiQ)IPDHJ70gpc{av66ZvIcb20EbT=i`gZ1JbK47p{S@E1P!vKRqSj_Nr`(6 zuRT8^K^5|Dz{!UY7p^d{@B_>a939Lb#=xBlsSsu02LdM46ONZLz|Se5Zfe1mNgh)E zSPVK=+!{$SE8Z>lFwoFkq6EPy__G%eN&H&88o5yHHfo>p>)=4xx^#1=>NBn46rdQ} zr)S$I{UaK8N+0D__}jgFOpOA=F5VlK>w{R!=x{+>lSXR~cv4L#FZ zG7s++@|^my7FW*izdkz;vviiG{HT*KV(n^Y$C=O$Hl1*V&MkmTz0xQ-qq{(gTj78? z%K1ZP$#FmNK}LY<=KNjtJZ%cC%vS@M*WKKiFg`%x;q0s<%Kv%Th>r{(4dTO}laup} z&GU_GM;Py%W(tjgM<)GN;e}Fm%;MV4g|A_zQZ{jA)LBU@{pk;p+B<+GGJIKLV(y&^ z1d#_FyeiGrF(R21^8d%dEYJ-}?`-v!Zb z-FLUilK)LUCe_W%?i*LIVU0G;fDrtdC@nWL$rUfj$tyxV(s2I3t^2LI`T-@npoRVr zZp5LX%k=m~9Q+*KZT-CuHdkHCD#Lxgfvo~>wVBF#5Y;12Y91n@tVfd&Z@rGk@xs9N zI{Eu~*Qy=T_9DHNa$S#}6$LLMpUJpymr9m~)34!&VaTh#Jci-{N+)GMQQGJhE8EwH z$9|9&{;&E1>a$(}_S+P#JQs|UqrM-0&85Vo5L0m=R3vmhT3WhIhoMh!15k% z`TA&m{{?M*mNIe6+=6V@s_Rn;S`+$i!6bPh35jZ|E9=-;hO`HUe=3?BUT0~{UR67= zggA3tdDVAOAobL=BSEMUv0T5R(qIH^;QxuPhRmHi*|sp8fzjQ|LngYtW-M~eJ+FWc zR1Zo?s;Kwq?A)qkdG}bS9bB#o2Rz8Y?!!_-IO`%zjJsaMc#(+(M{*xRMv9Zaf90ov z2<^)>tPOi&;d384j&r6dsh6N92Cf;8^bMX}Bic<`?D4sK(J(VMBHYXb`m#1t9Y=zr zt60aSUsR9lD(j{uhHTc>%RJpvjJWBOP3-NCI(kG0t_CV3!I3>Fm}(Ri1t%92`x2w>b!L8ws!aa0r%eRMIT?a2{ZB%+b(NP z8p7SjyKh@dXAX;fC26Fm7KbT~7lV=xE^R+f8HzN(+j zD#=y6Z48zd#T0X?dt^e8qTqZ%`Aqv;hqLkdBWms^i{uZP!L;NZ|^%m@6d@&PUgg>z)=t7nAZyrUBDwD>+||4Yysd$ zgmrdS*sPgqMg>J5C@7yIa-3Yf+L*|+R1tiyE(4eWXcCBA)6#x5TV0ki16M&w$Sabd zB?2*rK#GbLsa4|O(RZ*!u$Xsg&42&oC3Z*yV{i+!594TkYY$e8`txX}gw{VEmmdAF zDuH8O`1qgL`F&pA4GIci)`PsldF9;PLh65C6&Gfw)T)&XUj$Wex z7t;Ex6xV^BsROXVzRxr2&Rwn6>Xf~xc2&tWIB6=Ya-ebk;}P;nE-qpYr3l+5=Jbp_ z$E9!WYM305BJtB2%y=Ye zGfIsP+(rr5=1>D)xXFGIUVT0M@lhQA_}F!ugS;2Gt>UBm-I6>~o*N8-yQ#(Nt!(~t z7U)vw#8xh)JH&Zn?lzcKNKvfbCO*|bd>F8k*_}QegRF>GmEqk>P58jg$ZVxq1SYak z1sE>gI2q{Uz5B3-cIpn6CH{x?^1lQD>2Q2WY{aO16tIGTDGZ(f;3GW; z1Y~eFjMJ5e;Y__5*uVM10|z%ikXn*ld6AFl&mk8JZ2;ujkfewDz02wHWV>#Ff-(rk zzd$!kizc#>_g^0QR=;xhp^X-tVY6EO{{AH!pO67c*3YS^Xk%Y0fZPR;fBg@^8V7#P z4&L5W-*>L0C^EywFt*F$83o!wCqC~BExXc@?~*?Qob1mX1tYE_7s=S(kOcgg z+g3ryDSl)?;$uo-%HA!|m!uD0O}L`6`8IYA{GA#$rv#R}?S*d89qgKKo(~V}vE6OA z_AvWo?=e*LlK!@00tc^-g1KH#UA>3Xn-A*CgDS(#_KefDYY7>0&!sIZoM=4!G;CEy9scGlu zgS=S+Ga$#ytX>I4sCXf9Br1>$)J{20|H%h|A_)P!$xWpa@y^j-U=j$9Z8A6SlxXGs zcC5VAHCjIUMx_ivk>vL6c}J4F=psB^9U~Hab<*v(`d_k!l>KT$J1epVYNgx2*Fo{& zIgFivEL|vGR9ww9&`a;+s8(5d{H@wr<8fAX$5`*iAKOEBk5>cfNkSqFXW`BD&;O?6 zO=zcE0(uJJLjaOWgGV}mNC7|$0D2eXqIrVi0FpT}L|taV_}Y|r$gTu&|Krh?vz4{z z@X(sWlMHIh*WtKaP4Wc?75tfXjdNWc@0dcEfb^1&`TK=`j7{sxxO>$HrHAH>FWVO` zx@9hQm$rhG_>SER&@(1YrCo25PriQd;l5~<^Iv@6H3NypQ>JwR>EB-x-$2Gcau=uD z2x9DoUoK$LY@)RbbmXSX$#s8OwKmt+n={ZN$ioswe|$9Srnn=S>r8UxKTNQpk66T* zNFaYg6dG&@;HClJ1=zz$9QFA+9AroZAiL!KES;eaN1X8|CR);Y{HF!G5d0SRQ-49bLtMnq}EyzpM$Z%ki^ zR0GKT)~%Vt(-~HfveHlU2cN3bv$h$eQVyV)O2@7cr3dF%Oe?HyQQ8-)x2dDp zZu;I8L}~-Oy6FLFEq0QvAax5q^wR&7o9i(O%tj=kWK8=d5|{R_*Ucz=OrTre4@GCNCO8Xia zZ*fQ6h2lOfKUrO)AsM)$Ru=HcB47OO|BRKVWLC&SvH&+J--D5o?0TQHQ@L>i&^QX?vS&ylf&*q-SZCDv>2WkfQaf)U=RdUk_2Kqm zO$mK`a0U5A8C=Bk#jizBNBsaEF`dws%w=F6aV6p2JZfbykg7w8qAv0-i%W}4VK2Wz3o zAd=7#W&>h~Y*?v`Bxob3!$Tlkz-WOYa^Rn*8z;#X^xD_y{+CbxPb#0!l}Qa!puDO7|cvs>Mn{@?Q*O^0c!#VHCKAKx{d1&Gk9U9RwerP(hoGrw$0oeG%Aacw!{6 z5JUfSx*l$lR8kj7N;f@^Y%r*RI6{bnSy=&3gDfQu5b^jmSUN+{7=$6@0CF~>zzjKu zu*$(zYIb(^2$a)IZ8A&*nz?$6sj)f1h4EcJ z{CBquz9hU~O-&ISev~J!5fAKRL`r;ru%uSTR=Yagp(O{2Z7cLF5@59YBrDjtKxJaCR>!bD3$v zIyrP-W#`d1ECYwNO`DOl%2Lp@^o{4!!EAHT!1S$@buV37hUv7`1JQO+06<-slZ9A$ zuUtXuy7~_>9bDU|u$z7wlE#~^bz^pyk7_TubOfl$Z3Zyhs1Xyu4lx7P!+sf5#Ja|h zlhkko`6wcxTm~JHTJF&pTB#Bh!*&_2_J~x1H2ta74 zBY#?J1=Zgq5k2ywNw!~ber;@G_q1r>_2RKjH?PQGwZtgS+1bxpX+@`EM@!k?Q^l)m z*AMr>>KLUnJTL&6t%xMG1y`}~rl1p=zzmp>edc)j{Wcn(O?`_?Lo>3!zkcH5_%J8G zCcU>GZO$Ml_)eb_IHYR1AZNJP;k(#r^CRpN*%>H=L;pf2dmD$Afhhb=&P&2Ag0CD^ z*ij0qH#Z)-riI3Po0(1cbML3*ar5vz7y(+fE5^b2H}}YO@A`Hq)sB0W86MpKLgpwj~A^?|C;3lmV#9RV~APP`w*L`APOLIxyBI!F&uzp-;bOagRL z4l*KQ;@bt7cQ_(js3|ESPZpN&p946+d6RQ6Er1so29g{_<~T60#Seq-xpfZCGC(^W zBL4a;YlGYkBH7^4sO=qZPXl?p#OT+8>$cZlp~25-t`a!vfGdJl&md;oYy6J~M9h<< zk@GHv=Ls~xcnZvXMj(SR$33@M{`=Q2 zg&J-E5V@%3g7ODMVlk}*VT~Ygfk+IYoCj}b-vJfvY-c$-T;?%2e&U9}tnlmV^-*on zlz3t9d}UDN!K+1(^5Gvjxr$XLMwIJ4dEn#2mKpB8aHw&)Oe{T;(tle%AmJ&=Cs- zl2tcxGu~t%2~kJ&5H*QV%#+RRs1O40NGS(a`0745)}RauYgkxrxQ%x1??XPIU3o-m zotQxA1wF=gsN8*M@M34X6&Ojtz5V+PD=A)oj-8!t{+$E3k(+*;fF0!k+6j+bl=OR+ z{?|tWTRLg5I_EuKfYY~1u6T(NJL!`!xf~5)F#*4Vq6Jr*(}Pl*%GEAWlefOUG4sQ) z*kFzay`hdD*yR0P3N;PbQ*O$I5rPvaq@hCr&=5YtsSE!Kt~Dbtk`~d;0XPH3Gw=}v z`!zLZP8SDGn=_Xpq(eW|+Zdvq7&&^6u%f|!mTl{|NZoNK-?VEhpYFvUr%TB9->RcG z^Og>cFdMJNXm4zf`--iv4ip-}Uxm|(_PrUtEhOa5$2Hz@3sRo!KNS_t907k=s$1%C zyyl}U!)`UYAnHEn%s%`t#MEN@Uw<$;NpxL1SQkd`P6>&&di7_#BDq zxpG0W%oL?ilPpk)3kWn?@&la?W^d>=unGnN1^QUTs53K|lF`GB04>J*z3irt5Dna% z;>u(R@t;esj~qO{osa81^q1xCTH7xsz>%SSR5LPl2+y{2a)ay4KbduQsWk+sGT;pf zIBL39-7Ud-6s{5RXv$UbbTt$|H6c;8nX3D^Nzvear730CC%+sZ%)@|#j4=k_UL$T8 zZ=L!{hcrwdp30+0`kG+7yn72M{N`a(Jy~BroE`5HE@NT3jleuYpHm2$2N4m&!U0Ih zvJhCd$#kC$YIT5jWvGY1)dc$3ca_(VkLm9xO@?RIOnBylIf@7?sr zI`t-*DM2Le0?Dbr9xutE49RvfUt(WAmL$u9q1(F}x}QCBM?00H-H-}l{Kr`O;#uKB z(%D%^$R(2Qq6@K#f*^lru3HP1Vaj60Pi8m*fo2vKfk3+gdb_jx6&1sLOgzM5RyH_+ zy-T9^N}T7zL>h3Cw|@^KXVKN%A`AIrM|*&a3m zngkPlF3MPwsFn*uPr0ioSw`|mAUz8*+gl# z^cWOiVB;}53NGhUVCG?|MyGcHZulo$=QFBP=gIfc@?2imZPtwo(zstMzyOw(nib zQr*imIn#^a@a7=f(hsf>aEst(sTJsRk*#85;iU4=(Z7y*#bLzFlj%f9X|%j9y1wBT z-R>18+ON)tGP6;GSu_jh-$3h)n-8fcgGKE6uYi;P>)n$F+EUH!k7@nVg&w(D{jHFsU)G`E}Epq8rl`&o}DR`t_8zn zOuE{v-&($s0Q~UNggvv3rAE*HT!HuOMOL&24kRy7NChi4iqxpqWUL_1(BLt>_9SO7 z_@#}wwQK}h6tYPp%><|&Rhykgo-Rcy&aQiZuc6yZDEpSsJ~%qMkdkufKgqy4+pSw5 z-P(eJDLo^~x*BXHO}W$r-&vo{(YnLU0uzXn{WXOwd_)AHkB*E{Bsi_o#+b=5NL{(< za)Y&KZ^6~u!{c>x4-6ADL(cgSvnI3$i5=ub;SlE&cd+3m4&6tCr7WMMYBt!ZOuq|_ z3XTX?|GD5Q*a0=#^4nf|dP=&9yEh95I5)ui5KfvpfwtzUE1BKlw$!VS*ArC`I^sZ3 ztTL@_Td(Wyb1TZ}%=ukaZk($2C{!bH6f0hOsJ8-&@rsHUTU?B~*TYMP23(#co}rY^ zPzrmu#LN5Ax)%RpWMsOD$ao6F*L( zY`Q;*q&@R2+dVn?T2u3V()?P&&1vW8G_K+GHM*xmG+hI=hv}W0fkP+r#Gs&h|EIs8 z;%?sC%z$sZ>myx@IlT}9u6z~5B#xP@7Lj3S+LF%Pu5_4EcBW^TOx-@7xTLiA%jBki zG`qp|&CS*f!JS2Zi0*FRTw??ggS! zpz;S&@r9XCu$9lM_`QaX@h#y8s7duIu~4iNF!aH%3tA{^Wt7%r#Nj=NlBQFt)qiO-{Y}EugQ(g>ipQD`1Z_G zf4oSr=)?(WKo5J--USdm0gAf?S6DHiQe{t0jZx?W#>dPXm+B$fXd1f#&7>X8bPv$D zq5eP*0E-W9c&PR{4%m~`*%E+Ol&)pSNzTEVIb?_LC}KTyPxH#NRm`!N!m2rXBf4}iIV9?Ut3av-TO{vL(C_UV%nfB7 zH-cYQpHoppyu=4gge2|i@nD>6Ll$v0{Xm|6iBIW1A2Bg++as5BM|i1vagTtmW@pj? z@wes1tb>I^xukrGPoSMKN4>F%a@apGU2>V~$q$qk+#--Z)KuC`eKom1gL-2?li2>( zszjc-R~JicN4k@$s_pK8Lk+{lop0)6+a^8s35Q z+Tro91HaE)@1D_gUhS?FG!yq-{o9`Rp*y2|FmrBjXqTE=sVi+o+I=;_;%s&8&|6(* zF5Cd_k;%*bN2c1|P-n^f-D-lqV;)?Lp4If&@M;w*$dqy))+S^%%_aECoE=R6&bzvs_3&w9_!{6DIGbbxq)Xep$^?BozC=I<}`_Cfjk_7e2M7@Mom z+WY^w0BGUj|BSTt&?9ZdIk9o#2Pgok*g_jQVs0!t$6L9W=e`w43D(N{r%bxC5=}{X zvqbdg9L|duSn~1>adFdaFO%B|pNYBzG3MxZQ4%Iw_i2Vm-yno4dM_kr%FoJbmV<{q z{e?KGc#oU7REkQ!U#(D#&BWTo)@h;RVf=)-dv&iOG#=`Xhvo=qe}J6FVa-9-XDi5C zQ=31uG{5tcrj@S?hi4kasX5dG*P;^%!z0a| zTCCp=+Wu6U``+?p)zxe$zu4&4fa!)%>b_9*pVeWbawF_F@^}9Nk^)#fG%+yj*h${v z22CVe0?@THGBYiVjeYJEr*0o-_i}`0TYAj(gS*ai5nIkA=smHv($mtK5viT#C2u;& z3OgT{{@ymDCJ#U-_Dcq53r!ZDg=#%%aDl1da zTZxf~h&S*#iZb9#f?Ak^>`T82TS6)C5O5)Em>Ytd;&OJ1tx70q@xGfEk2nmjxD5w; zF^^v9)2*HW5C%h*X&hm!E7%A!5WbkoCq0nXoAW3DtV{y}&Uw17orMz_LlRXHBu~V4 zJ|@0;73c%jkqs_#K>Qh4{i^UqT+qv$``Z)2zbZ@@1u9$egImIxB83Kd&9huZou5f? zoZ-2BW4q=%4+_tyG5GN+c)x80=~2!Bw$9<*)u`XKE!KY(>U}+9k2iYi%V$txRgye$ z%}0OpWwZ1-k$5*5Z<=yn;S4+E9ldz=>%1l4hd^oI`y%&>8lH)PmB;*~X6a)~tGpRf z?nN^rib|PIwj6@|{6k~6$9glI99_!=FLv28CDk%R_iFrF{*9#x;O!|yy&EM`FT0)`1tS*U%A0%{1};Y(E~q7QiM;A z{Q1-~U!pe<*8!dC6z~7HK67>=_tHU}FkEai7^iUeb*m6v)pAuL@SFUoBHFURjfcb4 zudT@|!B1VWeh}YUYAH}eMQB3N@oD1xi{AEkjc+*yPj8Z&sI^q6Rpsb9agx)x-oM8^ z+VkWFUGxVn!`sxA+^^|UpAOAHp$(sEmU@rbO>7*u0B%` z=vVipf!XlSRS8OeQ{Ky*|J3H|evF@=mePsR4NZKyaaKE#LZzellJ~&^l4s?C3=v1n zb!`E5HSIov7(A8beYJKcjJ(T6>~Hu zM<4debE#Djc>Wk4r_JYxkfFPxAdga~*bUd)u9yJb+KeR$lx07Dq-lYpQn@itL!@yL z#fwssh;!jSvqIMUtFqxeUZa9<<+eDw>>oV9?D2qIa`oVf>lhOsD1qcq5JM=-O#$T3 zSFc`e9s4=!g~>4`w1e!jzd(8Ny^p^Zw>df9q5G(a=z5*y)w-7DvyNzk?;|=1(3EpA zqayJi_1Tq&hC|;&qBpGzV@!jBpC9AMQI-~YQY2eb^p9%#M$Tc6aZRKb8vlU>)lL;f zfNhXVO3t{Eiygy!2|wxptgHSd#}Oo(SRO2$QjKJ6Xm}caDi-PMrrg}XcPqOrF2UyG ztHDi?+;J8jcogn?`YJmnn`?^-&FjcfvV)Oeehu?sfQ(b^G20BXmHn``aZ~IIq!QRe zZ5!LvcCRhtavCVvs|WwK@C5`(L6)FbeGBAmz)1c7Pb3V?kihe$z!SRYc#VoIy`trP zd$!--M!r85e2>l?j?>BmlK~yGnE)$f*|h&*JLcrzovxPyfYtVr|Z{hmJc^IH5{7flD|&^mp;4wXrryCI^>tgFw2-) z%Qqu^Dk^izN8Ke#MEqfoLkf*o3#{91 zxfdX&``PkSV9zLPuJH~98&r$la(UBH6e@RWzUdvaw0u*6c|Zgz>DcAbu5C%6*-1R8Exa&x(x(v>VE? zT^-;w(P&{;=g^t6B|yXgI0@(#lzsjBat!*k;?ft#e$u}@uH`h(ID_H^thTncJ||L# z7J}Vp&Y~yh6kz`;&?UA6n+IeXr(ehK5E#++sjeSyPu==pG#}S76ByxeGH3Ex_oM28 z1X%=GW+v66;$^o4)2^o*%j(QC)yy*}gVMYqo?Y)}ALGOZRaCfNIFnQBS!Z371BMg~ z1YjC<1sfU`AZq7dqoI9C#NTxG%2|d*pkCwP;A?gD1)sRfdEv#`Hmmd{;62&BLGzwQ zxm-67cdM9tH~p3*>i#b9$sEro0H!{!CrN+#BM?Fl0}|?%+MN96Xc+vqFbDlkR`OgB zOz!}Nt6MTXLHT|JAi1u2Q{trWzhK`b!=Uiz3Jo#QmwJGS0cPX`*yb?nD!kWSaF37X zYVm!ZSeMvz}8RrbcB=SeZ={7~83j-dJnAQ97Y zT5{bjEmhGrHaC}+D{Gi$jq({=NmI`SY6svs(wT5F1C1HhX=~;c3~0K6zz6MxZ)BuM z@WV>UjdHhd`kXV(z&@3ds`>iW2#V^*kAE%*xJ7<#g1*7E>Xo~JRY`#Y)=iDC6kE42 zTj9{70M4(=yWu>&f)BsF&2qmxRHnx$@FGZ4OG}q;g@4^S9kYqav$qLyH*^U{q$xgC&W@g!B@9gYQRz_C#uB>dy7DE2F{{P?ef1c;M z&Q<3sC5V4{kIq=8`lX&ht z7qMOySCNq?9oxE0DbNBknlob#NG#*O{t&RDKQJIR-TR}j`f7iDQ&{gig#;sn~OXJV6U2^VXZqc$%rYNIKW zAPFCnM*4z9j41@#p&$^FPa5 zUc112>v!YXULSE4j}O=7#QS2cMQfc+?myMOGj?;vztUyy;w1C2>uI(&=2d`mfV{w{ zLU(S$CWGL(j*YF3mCcPH7{)@^74!EaB2vN14Kq|IUWo#RU>Q40VEO_q82qwTRqCM2 zS>|D|didkh;bBtF@X^&jZiIinu`ZrkjKX7}4Fh$vBM>@x^;pP=dE1@lQef^X9jms_VZ~FQUH| zN);$&tat!^Xn}NSvTHciP_OgJ{bBr^Tp!6V*bX>I#h*XoA7WV z5h3e5)5=t=)$!u%Our1o<~BxFYt~22KO!*!Imgh-W6%%wWSQKR3ao3xae{%xh*}lP zal*l|nG`a&Vi=1;G@}t|CyS?!!@#0YGnsSJP(;3Kr9UT?^n3beck|O#52iCQbxcGtz&U_{ucgwTnB5&=eq(yt#G~C3Cw-UZaJT{sBRjX z0c{J&SD+0ixj%Q4#=ZRGeiz2<4c|F0+4fYM@x7reRo1{N3L6bH6sYn$B%&k@bB9AC z=x)9p^@#7i7tEM5D&zd2O78f_P-}n2yD0P6$&*G~$7w=3x7=Kxf`SLU!r|{du`huX z=G8;5Ont92oP&A2pnTPm>%8=q0?3jenwN>kLq~3G8(e3na~IN?wuF1>Dw39I0THUn>v1jQQ=1A?|qL;)1{=KnBk8qq-cb+spP=lO^>u|9#QU9BEAMJJ`BnqBs2&=A$r!y&tYFJG4SPm+ zM7Tk|R6C4&fX)X$QI}~M9yZ9Djz1!w7#eJEfzvPa5qpHpqMbleABYTYQd9e1FMv@R z7@jDhjyAClPxRQkW0HGET^`;($_Tj_J$?N~2GY;u;rB{hWY|4Ewrpc=t(6o0xp*pY zF30e~B&+2MbuHCZi|S+&b)_#Byn?rJZ|CJ2zlGLC!Kki_aER>Un9YpmdA-v6&drwL zv7IE50i5r{_d{@AK+J^Qv!?Ikl|5_w5lAE#R3#+6&ey3xS(p3!$QUZGP&!y<^@3Gm)U+<_AIFQm2943eO#K_g?m5IgI;d?NGMj+F0XVj~E_h9Mo zXLSMeJLu?OUpL(@>D+vSTMGSPx&4593MwdcTu}h2cQZi^E^EI4rcmpTb;PQn9D} zGC))poH}pfjP4pX*26>*+^yo`M(hbB{m!Xf(~uz!JK5vMm`u_~!a-?*9OC@^28j6Z z&UL8;DWh#@*3>3ciQJ1_b?f7~%&2g&n*9aW~Cl$3NQp%)a-D{B*71G#U~z5lZ0 zF2LtvRPj)3zM}7wF(2tP&)OU@KiC2| zSfV;j?}p2WlM#T-H1-%KwD?r`R`r#Yl51?NStAl@Xs_qTLmCHtqeL~G3#5{eHi_g-Ml6f8y6rS@n=ma`0p^)6hPTuAA zG-^>T_Dgd`1u92YEb}gFoEPPOWIrWQNO_S~`Dx>JWYv#hpasb6L2EHwgXzyj)ltT9 zjDgl{9aXBe#b+uQd$v!xw@z=ppOL>AU(LRn<}@ImU#zZmdo}H`uFbOgKvCRdqIoPq z?y0LHwn|i<6Z;EKbZo_T-WAUXbA1(k1C7HppY7?oKia3O7qgGc=oFQy zz5Wyec!k>(P}CL{tjt$H5d@Y@I|xjJaKYs;wl?`y^z`K~lj#*J8c?J0v4yP0?Qq?)E{-Ec&mz|F{ivnoC?V8gt20W#yPS zIViHgg!NuCylXODxZ#cS7K`xHPSd{(Av60!N8d7iQb^5m4|KxS{qlC*@fWTQkWgj`IId%C>n{z`7Qi)XDaA&aaw zu_X^6q6>68RHWx`2CeMAhIpb$=bSFmy!fbvgOLpw;no4SmeUzk=OXwDu`PcBpq-FEe;j!4EGjunA)S5D65F1CyYl~xzXEE5o5^e_XqE&>7Y zFu)?ghL7^6FT9RrGaCKPU}HCk_O(=8kwp1X=iZ~&`OKQ&vz zlbQ7KP3HZ?G|i+`vv>tiCcwvWJK;)zlHeI=-$C3* zXZ`%JlxdiS-3jX^)kE|{Iea}eHFPOO<`2k}QIH!3AthI+ZxIlC;I$e2DJC4QbJ7T&nxq2Ae7MfJVUD5F=7R$k!-|4_3=kYk7uJt;l& z^dSt~T6UuvJtTp^tOADlW`uj;BUUxAdw?#70=ugB_Nb7IxE5g0Wnt;`I=F4A@;a)$$m`FPtn12JWr6U; zq5tcG3~pAIdrnS0>+AIg2ahUSPcS`#ZfP^Y;?^{|4p$∾E8uKrj$per;_5bJ9nh z2{$bE*4ZqZfmiqHEr{-Qb)~$A921Jx&oPFDNtkw4Tkbf8!lnC1 zXmwEx!|i{}B7WW2Z&fCCsCely&-=q4R1BNjoGbpSOa7P=IS4nlXb$o_gxNpo30}#I z=l&Q1-vY`FV;Kv9k06spbN<{8@ciHZWKRRHbwHR9s0xc7+zg-Sr;yy_7SR28-$mm$ zJTajSVF6OAg>HN<0@o(mYWW2OFm5_E=mTk&mM9S0IfwxEua`HWZmk)ca1Cltmy!7; zW>hlyO-~0m@)BW8bv3a;pF-B`Rpp65W#*_o z+;jXG7gt?t&6adZ9Vr&<&Bfmk(7D%9lLJT~9U*3EFnU6bZq5T;7mTnx%%~e*20lcmjJW<* zI`1LN_;Pio!HI!(pnCGVeO=%3hVKR}I3f3Zbx2_FF@64A&t|zYmqJxcZLeeT&u9Ua z<>1K3DCm0QU4HDJa8N3OB=a(Hlbtkd%1*#aJR7a)O<&WSnAaO$L)sT;ikwNJF8R5< zRKh&E3d~aVqO{N0m8|*PWM#i4cc|(Ajn}F9V)4{GuRl#p_f=Oi^;Ld;YOG*tKB!uSid z+b!o!v;qWke}C64QZsJcq9>KHB4ro`{s!i5H8?N9EyxsuOCz}|8trt`5w4n77wBz& z-rx{r;|S6Y%+DL2VN(7yqdO+|^lM)*mOCI3%d&UsgH0a#dH(7Q2QQ6ju{r}$t%~E$9ZU+&Kb~1X z(doiXXF+|#5R8Eue!Rx6UX4K~!@+NOM^9V(${Lw^1O{<1r-V2y(M50+{ii#cIc^R5 zF8cNiNhPs;n0Bsr!vw#W+{eQ*Oa^2m4CDU|q(Do!gQ}h`1$yK?mZBbWcz-;bX7eVK zs&x3TzMQc?`b;yXz317KF24#;q||=6D26w5FeD9pGh{9~>chOTJ!R9nGUio4aS20; z&_zKqSTFxSL zs`MnG)6<`M!zM~O{-O5f+!tSc^L97sBd*5bX8u!z!FNe;S;*`>nsJ-^rB6jQjYEn} z7tS#3BY5#F1PS};!b^)MPd)`h(eMekIIt#);I)w{z^UffM+;0u40r#GX{dIpe*ROp zh<-JUZsnG~-S!(Ch~N}QCvEcQ|ALumPi!nl?q&F^{j#Q6lwOHJk!wjy=}Mx%l#&od z_DY+gaNmWfN}~VygmyyAkMWj1$qE?ZUMf?!TgJ zTa0k1r=cuK`DC?N@zLYEShg{e%l2CdS8)8BI%j+TJVfUz=hQV5)R?3kd1WWawjh@P zAxa(|oQNq4ZKKz#Gq@g1%dB~)9Cz_`Hr@QNTc_hSY2Y^FG$>kUO}&$-$$p;a3JYFd^ySLMtLU|xZr|_m^JCvXC^0%` zPa~S8%W@~9KASzt!6T#d-jU?1`uH(|LCrboSxX>;+Gf}F{Z@t}w3kTn8D^4?A5!UB zqt_T-sQ-F)3Tqm=*=iQa(hYb0#7d=Gg=m|6*sZwWMwc)Giw>Y1Y+rr27@2zvM|2~pt z2T{lBI#bz`M}2w9pkBGm)=)13nF>BufM4eb2l;yi=5d85t-pvmpjcM(5d3b>N2Jh^ zs~{8QH>XhGQt_q}OX^+>RmXz2kkG)HH+BS=17Q>cTsshY$8^i&!`|^|d4*5Cdzgh$ zElFy)O!M`d{&sC!Tkg=M%&hoGHx7kbYGUcd_MU9bYvHswge#oFC}!;7=YHAqlyZeM zSFfnOSEdikMiti7kjFgC%3OO2Noaz!vgD-cH-BuI(3lpr-iz7b4M$@7YX>d_^acCf zwWF=7{T#B;&MuKt_=7BbH{_L{_5o!W!W#!|n=u=qZ>U@9KL_&`HMMJn9BTTFVDPr$ zlT9vt-9xqT9H%}_fO0f<7#i?(-v}w<=x;+vXH92Hr|G>de&Cn2sgs0Db$SGT%9{Ks z8AeMQmNK8(YWn`(T4)IdFJX9REv?GU5VH|THpm5r-@gniNZ%Z{K`V!gA7mLytn=B1 z<#kzE#%NJ-q`1S}9>Ps3Wpq{3S>01et?|;y2R60ut95CKLSQZq&V`Wn*Zio+HUMYu z$>+6gZmRP%yzY7PWk63w{%g0=t)4;K{Lx+>UJhMd)K9$N9qB4H;g~`tMW_6NVB8=_ z(&tOxr>A)fCPy?ZV+Zf6btg0k4UlyStqwwiyd?m8V0%0HRav+P6ex9rf?`i8-|07C zh}hn`{_=9CCQS53kV0>2x=vE(IRCB>-qs4_8(j{YAV3w;wLf*kHTsk$WElnz#twjR zm7V7lHkCV&IJ+v#%^ZII+mudl3Dz{?%1v>y|FO2!w4M(+N=cpo*%ne4HGwJD5$eGHl!$`>9r83Vfg=Za&nBhaap?kLsZ^GR+H|=s#g}P4ff?#lRht>)`y0Q zh6W~o49a2^j(Kn)+HQmPr+8z?v`JE|+XYFqjm%4olZ9{TC|E8!VLD*vZNqG9W&LephJ)0_=L zCL#mMj2=arICRejdMa0zE7zS1gO~s`=-n(q@36W$`Ih-n`h#!r$-}DoH3Y%wl!{U9 z!`r(DA7_;F^P`2y)Ksw0ul>YgVI_Yaeq9b@Cz#%?@Fo_Is$c-|LTGpyNE&wVzMwY} zSo1C5c6wylG=Tj@4*w=MHk;J6&?g@HvE%)mpZ)=dttS3@jC^>(QN7={o{NV8Z z+{W*TN@~uLEJVjPr({r*BgUT$bbQGu6|O=!8ZAi9b#;wfpZF`!(nZa;UjlJOetrCX z=F1$~Npe%~hMjq-?c;iEY6Eu27F6gnq8&fM^C77Fz>Dox3VB;_Ilw(KioZesU5@%w zL4Af-+7j7qTY_LWd%=EoT1vr(PCjC8n3l5xwoTYS`_oVSmfNhqmyO z0tg`3hk+UHNyO#_xM2bOj4`3c2xo3)PkP@gPa0pu!@moDvV5J*ScOB)VtUc0 z1EXe*i*uaZU?Y{x6b02A^2+PVie)C10qj~5*@)rwHX7wXLvh*GBg?!~b&YtzG)8fw zn9RF9Ju%D6c-7TH%%t&|{!+70WwtNWJ34+HV1Az=HlFV6do{|IEaE5aYs&JvJ5-x^ zAvgMZ{gwjIC~q_Rd*%2!lT#2m$^||AG>*b4g55aayW}jcPv{HcU@4$+0;*1O1ckub zQ-C-ViM+L1c~OmYJlqnbXbuEJgL`|9-T3$!lGAbvuQ9`ee@U}rGHVAX z?_#J&hcZrc=-Y5pVX@=u3(_cTI}23k8j2Z}Yf?TJZ0EE2I4r2dI({jKgL;CTf&xbU ztugj>H_!@UPY1YfDj`-bi76P(fSU+NvA$)5gdt;$j(pzN(Sj7!bXxDT;Ucm@6}lI1 z`I%-AF=*#woiyanc{Cn?(-g?Z2I-O2IrMSBv zoJsud-*={Y4YP+V1s;rTU<5K4*HTW~`Bpa!Q9lJg-OEdIKRWCHWxTKLL%`)Lvq$mA$2D85!Kb#WILRdZ3hxEi#`DgP*eC6 z7GOP=tzGedl_P>?Oj}d9TTj-APDNh95uOr7+#Vu=CgILdTR68$klL?I`(BlK1d(77 zY#JnG|JyUdN35`7Y1bW!U`ZUCx^Mkngd;u}Ls&uu?F&OzeBhCXW{2rv{Me8=Pn?oP zVo#}KgD!h5J9&!E#uacjYNdjg7whX!XJI+D@TwRLV^DX&%7m3h&+W?WNt|eap;(*t;?Ew#+|3RpZmcJ2qm=VD5@Ov;9{HCX*ofC6a)?COXp%IGchX0bU>U{nQTgz-7bPg| zfKsrIHUyqum_=01KBU`tu^CfV8mV~F(9ZtkiHwZF)2CpDvsEPc;nqr~MslA#JG{%A z1dk}E8%R@dErElFBnULlq;j|v4~u1~aJ0{*eT1G^SUEa4hrDn|^4df+ zB^vfv;Cy98#nAQ<)E6XrZPN?Re*B9ujL}xi3s`9QA5DNGW@btipK-Du0%WYaKe0X%YJP zZ>Vw>70V`A1^PJ2ZA_oC->H80mX($W$l@PowszfN_z&Cew_jHRCCjuG&6NLf1Jp`E z1|WwbkXZs|>c9Rb91Nk{*MupgdEGZjbo?hj8Ej_l1f*5e5l+NL#sGr`ij;7AzeS)E z{L?oeA=ZwQCrT&!u?69DMe0JS?luSOxvxt({4(IJhT?wR*|oG-y%EJ1u59L#XbkBB!^3HDz3vhLq?>&fCSe7k>k z2gVpGtw>q^Tn`AC$Z}-d&Waf`j12vHh$R>B6t4jF*XO6;8jt z@=vL7Qw7C95YpV=E8F#pM9$O3WxyMq4k3Dpd^R_@OLOUm^k9jVVm`o1v! zNleA$&tHY_w(M*+ic4%uN;eCOtl2rA78P2R6j_&+NMn@=klV1|DJdyLqh?Jje4CfY zuFWe-OLU!_96(JrNwxufy1j#`gFS}5eNR^_N-+J4C9(v_Hzw8-GsQN9eZte?r27Y0 zEiHa%s5|uZY{tj$^pF{JWzY!vI8sM_qmSF@?Sq0w@{%-5c$H7g^rjr6#QmUee#C9& z63@_ZOulmNsm3Sq8a7hnV$n-{Tiwq-cEfcKIROCLbz71@ghE`cz?1+l}^A68HuRP0a&mB`V0DvGi!{e~4@e^bI3 zT^3Uhdt!6{x6C~�v(b041|rCp)`JAtMp6(ck9fy-REe6 z?tw7pyj#6~*@A-`VoY6M-#`tWkI)&4GT1Mr2b4P&H>9#Rre?2E$S^~>BX^tOoJCzf zXDqX@jhJ4swLfbMxhm!I3hf*ELC^`@2zIl-lME4J$oe^xJiggSG9RSMfWz_~RCnR6 zcfPY$5HI`&5S0O@0%v&JcuXU?y(qWB)ZOq>Vl0ds4MLY^2V}G7UGK}}=`bb#kQ^pC zs|7_0qk6nB>1#(wQoVRJa-X1@oHZuDvR&?**KDHy1cXm)A0^#*r7V)6$gJMQIM>&` zq|2V)w;B;D)35jRNhvGU_lL)~Fx6n|H88D=r+$@xMH*H1yJs0apQljUD}O|)h%XC; zrB%$B(3?B%nLmP2S&!nX`{@j3ci4!>ZSr~aRH1bNC%Q6if*xrG#iD7uD|*GlRxtU6 z(Yj*;n9u1+z~nCo{8W&Chw_Jhf~Gk?`#1u9E zq8^drvSUb6d)?k~$0jOZCLwok6q$%wbZ{gMdl)4kM~AK5LHeaV@1c+&|>%w4ZPE4%^H$vanA!Q2n@a6yo1dbz@WC2ANUIz z%cskoA`ab`Wk#fcFRO?j!?5(3SJdc2 z@fUD)xXJMuxu;d}iyQ<0ICOqI#?lZ*qFBENl>`^2nqbJy81Vpai|& z0LBM3l7)aoGOP>j~ws~~pm|B|tQYoVRx~x!2c46XZ@@6&(cC|4P zl*KWIH%bCu?M%*>pzx+j2oF`3GnNCBf}-MZSgT<80gh|bNM68T->c6wSK3)fAt#_r zjxQy36#6}nHF%3hUH_buR1lNjXue3G8?4adzeCv{E^{s0SeBV~)$vMEJOhnOsBBZW zsmfk`oQQp@EH4YW65jD5hHr_SW`~8Bbq!jC79&ZJhsgD?C1z3s=GY`zr??(p)@md@ zf-Fo*-@XVnWx)gTDnc6NbOkLgN*tjyDd8D;Mxjt7X6nr)hc*$zN(mG@d14qcpD{+h z48YDrCGb7dm!40$f4^=$cKIlbziu7hvpA?k`(njZdxbuMM}mPEb-Ug9D{i2eQUM|F znzZv*wBYX#8C^#U8Ay9%7#q6H;T2`0=Cvg9DN#j+H2sRX9*B4h_VL)H0u^O`OLNUz zFI<<_;s{m;4V4v>KP}FBogbcyR##|U?&qEr6^o=cO<_h(*%DMJk;WawcEf z^6M5FDS#SxzYuM_k#@Kripa(nB3<_1BXShOz{JMD^`C03hKq%iM3$bt0dCK@29;eJ z<=XcnkcZyB{1M{_5&M%^Jdq$x{Nd1k_+XFcYL(Htmw3-Y(USEfEEkCs@H zJv3b>s;lCiPHCn%=W!e(!N%e9Bp)f5#})*7x`8&90os&ba0y9Ez$OO^oSB zChK(6?irwlC~zfybR!-)3bqLwd{mk!808e+{AoWqj&gY4-~kzq<>k+^svNt`H?)g{ z1viK2cwpLd0D=ZtvnW|!p#I!mGGiT$?%}hk-VEH{kC73RK3iu^<~u$%2)^ z8|G4eL3#8GSe;g9*YLT}rLgtF$BHB@78p&0Q10=HVVQE&4_yLMYdfDy$6ZS7F ztXy54tF}RH!;uGi>F>fj0bFe(l!h= z%gNOJn!Pf?-cn^Wk8XFxhpPp9Be{NF$MeEI6GLxNFWOw*ztWN88{>fD2zbO9p*6TT z{=9*cRK8lyS&i$lHaqKBF?vizn3O&JwHu*9Dlra--?g-SG$H*f4Amap<^kpUErxTs z!&iHs@Om^P?Kv7|#ro$rBMUAca=DFifhsi@7zvGWapRp92J?;|gfE-c-O}u$<$DPg62HA$rksvt<*~O|RM#jM=^^fM6Qjxf%*jtC_oL(6BI8v^^; z9)8CL zLUVPTxO*vaqDdLTO1bYHh18fk7BufsJt0@14kk6_zA9p9Fmi`HGFizfIQRht zg{_Yd0Rce?w2(Cv9 zsZ;*?df%rUmJlD!a@#mL8jr>R9sV6FLzU_V1@>Rp@LBucCKx+Z*EkpDKWQqpD`@nd zwEsxXk;0R@Q8ocZf0rR>YnFL*?*xjyoh%D(Pbw+q($dOajG)}-XY{3wx}(M(Lq7J) z^_$&$$go0jr8+fGp8v(peD-PeFY;?&8YSSUqOP`{wMeh~#z^$AG?Z9udar_8X5?=}>6eh$cNAT;QwJeX1mTBW}1it8U18$L7h&lii+TdpQgy*a77cQ=Xh^}APb{<3C4_(AwlV_7*!6=@i15NEcH&2>Iee0rkHJX;2YjX0gZ{JSE#g(oO zo;X(Zb(>E)QYY)n=O$<%@++@V-DQah#|sjRsd(7Bz4F{EH~^liGMC0E%=s+7`mYP{ zkJ{9a>Ibh2C&b=6+`B^-y_O5DB(cO>do11iyXoI{@uYH8#m}9gmh%D80fg~#`#!K3 z*5j`I@WB&Cwk*ud%&e?AcQU~hZD1hU>XaR4dh_xC)A;WILqr?)_wS?a=H1@D^2U>` za&fY}UuODC0T*Y(mMVJ+nHN+};+z_@&4>plUxxX7C%@hDk!d-v6Wa>Q?aI`OY<6-Q zDex$uA{AXyEk1vGfp!_O>leBSI4g1$BJ4HjK80@5zop9ym6*$-jGnaOxQ<^E8f3_G z+m0up*W3`l)4%;>{XktzyxX)vp80;vT0UyiyIGEz$4Sr-KR;UGuwt4r0TKt^D7}R{ zBtP57d%U@rNiY17o4M+LisHws!^A~?o4=6t4DG~s5)>1jd02o$b+tqyE0QGu2D%~{R%eHNUwB)pL`-6=-t@e2X;=XYj;Gh^5d;-} zx3FAIoaV~{4RJ!SER%3d`vM|S?n-i`Zircak+rq6vweC0z`(oOI)L*l(pi5B!+I#CF}0pYLsKCsR`Dds-C#9K$!Zj~dneaH{m0fNf-#!Kn45^H;4hi?3PF?okP! zG@{cSGKPrWCP#MU&=pjV{`|GMNlQib253{7y(|fiYDGGz?xeBeC$%SY2yO`H~mXu?pq*_?t#Vk zF!#i&1}*TKY4y3YCwlT`$D&DvpVDjBHD~d3!wz%GN*(ko?WzT*R(y98Hllp;F_kR* zKHn6i&^p{7&Q;!CCLbz_tDK!1GL1=9}Bk3DFVlr{cRYcys^s9?NqS_3( zlBDfX5FI@d$n%>fvcr-f_|>TCE7Fn&#Jb2HuUF6klw+2beJLhtkeOi*k!<<->m#F` z$;sj#0E7BZVf#l2lP^kS57)R9Bx*i(grJ~ypwSC(H}%Hx`4B}k)!_Q;>-o`KW_0up zpo%`p(UVMt)ILr$fAYk?_R_P2_*(@=0Ko?j2$^>>f`O6RT_;xtQ2L+{-tcf?UDVPDuOfW}T|U(9%2V9t4MuB~eZfPLG*XI}$X zoo&fTRZdQBPxFoqXd9AcPSG#GTno)2p5*WL_any$u*jHAugA>C^+Ynp1oxE63D0FF zOoNp2urfElE7OIWissdoV#jtzIDzxg0LNw6isM?C?4ILwp-ts5_saLK*-bvpWltMQ zY>TR$;MbC>Jr}y8n zEi~IEK`B=LslG~#{uV`;zIu^i`Q7Ng$9TsqbZ$+p)l(DihbQaA1ncW3!RoM$ zSgOA2*`Pq7T@qp1Km*r4$kB8-Uh!@4M19)@`4)}*^>x>+yu1}S+ z*M86}art@pUI&xvYj@UNfVta0a(+lgM&R`n(2>;ztFhC3dC^Jh&SDYRy)5XZS9_M* z`8IOeo2P~=`NW#Lq*g7=p3baO#rO4s@1^~kkztWeeoD=^>#3=$W&|s%3xjK^<6B!M zO=5Q3Svg9r(lhpMWJ$baM1!iT?Yi^ikh%(#?%KjaH7>VrcDql~{q|iQh4!_ysz*ny z{=zF=T3Q+!8md>)9vOD#SbUjQw|8&YNuYS`g>I+`^c*UBSg6h*c~B82*~ z26@)@?IvjB?hRUSI!r0*50EGD$g>{4EpRDdc4J|4VNQQ0=2LvI+to%aPVTve(-|eA z|F>h2B}$aW_c*(%>y}0wq)wzN-T}r6ebnj-Es;Fa3JrCtc}#U{4;nT zAmRe@9aL1_W(rBGDlM_HImN~b%F74T@X2c@a$mlCFuw7QbA z?o1GvosH_CeGMK!_5=)nKZSe%31y{$+HPY2ll%!!a$yE(mMSzxA$8S@a02GW2>eWv zFeDYk_;6>+F`H6AYGU_iaK}}I@7Li8ifQ!$^}v_|`j+C&cg=Z(=x*l#=6>;x(Fr~k z*v`tTN4L{g!y!10(4R~HX9k~gSC8l!DbN9E(xjLXIU;I~;&r3wFZ9i*#U?NJV znC-Z9+Eq;@BK9i&3`Ne&de%M}t0*wLn%1H_{QcIGw-1~D96p=1GrH)FVOrC5S^A_A z{<>s)@PaS8EAzs^#l`iox9`PgSK^(voHxftQJ#z!E`9<>A;^n~2TkdO|GiDxD&a!& zDp=N5S=pK;4#V{$DDDE*9YAVzzY&}b2K8sVHDmrA8tGA@jtkk_QDUbD-r6gg7N2z# z_Bz(%cnefN#4AK7S&&4yT&9SQuREvc0QeCCF_ve}p^(~`tnJ!EM zgYE4Xk{o&+%a5vc44Y;x`Sds`(Ow9omgyiO&7W*>Q{Snr?aR$ojKM9{)6to-dp1Y0 z6OtTRp+G_5{&|SOSOJc1GK}vux=Z-^6)Uw`r6fZ?2y<7M@kQ>`Ll4t`Je+Zvq0X8q zwKi{@!=N7R6yqgs*RPQgWtv)rY(K3m;^1Wip6Qpf&`#4|)7i+!7nDeU_F?4PgHmk@8$J-p(VeoQ-GojKdcI?umCo9B z3*LQ8imd z15Y281e#q>u%9zl3N%ex0M?lRzqdhOhd(w0jQ=25O1VMv*}K`6g5qxT@sE=7=0AF+ zO?0*pO#ZdxZqtFD+mVHGe@92h*xDLWb#QNOt#@kbM`r{E(+v%c)R^wiW10v2 zqD}Win|K7?bMsX334h=bYX)oF+0Kp<2h-EM7V(kE`_rSm9t&+qw<8_P)we2M$?eUb zR}Ge*mpckQs!vnoSRsmg9@g3T#lm2rV&Rvw#b+4JHx;Nji#e69?>@Xi=TpBB6XL0w zz9#rv^IK&>IGHNJrRy8)@;PBQ?cVE>J`eND9Qd;4`Fp(>=N95*piZ&H%jo#q(MFV* z%$Gq`d3i{XR04)lGOs1LgsK2a=i~&PM>v!2p8#f8f}Wlf-#EV0)J4>(bfIHcr|2Y= zM;$36&rC``EE>GlFAmsP>vHgN0rXXooB2b_LxK1B(3@2|$i&VJ9Jt@SONjQE1pi## zEeP@{i@Ju+RKqW&#=~EUe}Rv@KH(NJ=Td4f?%dOLOT=}PimJS@&`%4RUtmW$CTdJi zz7#=t{}Vyb;*y>(H?CwqAlo`S4H-W#r{6sMXjJ-U5P5I?Xi&T9!+m@?KEq_H)1@Zp zG=C+FO}|hfe@%C?CqMb+?r&}HzZc$O-e-z#zN6eHEm27E{^rmBx#2@0baC2p@tB#k z$DF4@pX*x0iAV;^{W=7%^p^!_qZ5VXq7dFR{fLCBl#CCFG1||nU3!;6!(?lH`$qEm z*`@m^_N@MoSyHYMs6A|y&06TBrvXA^~flB6CrQb!YcD11Rt$g3=>iv5=b@lbf z#mGxPki(w4pX{g&-<76Ws)!CijK|5ZzMJ1S;$3_6NIMZ+>865Y!Er6U%XSt|Y6_Tt z*62Mf?Ix9b0QdWGb3G;b53-DgN0c022Ja3G0_=L0ucE?%h1}a;#kQwMfaWU64Pxh! z1qbpeJ0H6V{$%H$ZNXNuBRZI*z$&Qcx%a%&{s!B;G<(9gWend9$cVGA8(rrhi*Va> zbY*9^@0B!*elGA*FzE^opr1K0{6$^UCG1Q*Vul4fO`avhe;MrmG~xFQzsPZep2u<|bZIuew>!pZ)h|kDoh@S~xlJ8ElS>0I3-CW1uDjJp%j+&*3%<#H|BB<$|ID z{~3Tu?;3n?7MjR{62@tLgyl^OJZY$`{Lt9gSW{D5`P|y;v^QVz5tqRS0G(IY);2YG zTpB(=rsG6r2w0BceTb|8=V;kG`*-EfO5yiXJ7?Fwn#|tP9G>t9Zl4|K&k*+TX5j4H z-cLx3ud%ItAf!7OgA0#mqFx7cQ9zVtU1Yi9lO*Mvq2L>)a>@|s8|;@VnmTp5)^0W^ zHuK_lq$WFLPXhTwHut%iGB~8oc}kExZd+eAr#rgW<8lXSZ+QG!8`4mfOID%_;oUjT z^@$Sy`e&2(>zVgIKM~CR|B3yuFwnv31L@+WF>=gTL1_~6stn^&x8%C^xxnF9UGrht zgROeA7ngF@^Ak=6h6OT)VF~&QXm2|#g=CO3s2v}`;2u}kckN7-PY0B06C!lP9LUev zfv|zZh>H)KLx(`T`TuqZFv6PeGrwk+$~1|ZW86Mljy(ALfb8#j_i6U@Eq~;*s`|Ne z)6Rt7uY!Vt?!HK$y7xQlGHu{##?u*ZQdmN1z z8U2+U9o`pfsdlnH8qb`u*-z|o2)}N4VjMnxq}T0sK6CR{81iCq=DzsA#NS2BVNUwf zQ;o1$$Nsv;^YilAGqo>@&n`Nfn)esi5=1V}Qn$~4Q)1Q~QvRp0ILAeL4yn4W<~%Zt zG1^5nwt%9WHRB`t@x1TEqs0BYsr>*x*NazjI!vS!VL|zQCT;2a1 zH$a>w%&@o*MUP=YwNZ*1LKYLJ(j=ro}_OyQA;?sN7<;C%el~+=R@&O%PR1{oU`IBeeTmcB|X3+k- z;-Xs?tZf@J(;T09R3+L7M(t`0-s?)|DJh@jJEE1Y5J*zebf&0SChIkIEWUGbWprWd=zAE&%NxPZkI7R6 z0W3yTzaFHU1e%Ol>7Va+yp<4u(yQ~w56Wzkoa3kWa0wn3j8dbDKEHao{07NK8iqEC zWFPJf2)I%?Wm5}Dm7z&E34n(!eljGF*MH-jo%- z$w&jEKnfuLB3q~6^zPYC!BcHQc!@hHTUpP{Kx+6=BD>z!lT*OyF+fK zzgERBPA-$rAn{;dL9y@i&d%P*2*`^7B?t_^9c8rKA&Byvh2Bg`<_l|wod)O`{qsUT z0+~3a?O>;#_bpj2qvpn&w%q$Rr2x)$x|DV~F5@>gExZ5vS_@2bn6>IRd!O_s+)27? zbY&^L_2)`&Z(EfDZmBHnzgkCg~eY5QVmIVCUK8D8^52VZB9oXtdGSH?_0u3r4@9^xmemwDgEMR z(AdAHzSrfv7^Ugg@nG0%;Cq257W>8o^FQ- zfuW51AqQoE)LnOuAL17C1a7{|3;Sm;JHsvY{51}9(hekv}Iu4DrbV*55%U3l5Y66_q+dl z@9SVNKtTkbz4zK{&H0<#uL#p`Bz1cp?-j?yjgP`iE=w<3iWf#zGvNjg7cvrVPZj>E zOP$Ty*76e)9Ll?;3i!F)ufh<{*Lg+)Imoa3UZ&o!qNUyylkm~?UeewgcyjiSKK5DN z4$?nw8}p^iUVQOsfxoSFv53$Ajpy$r;V70PkMrT93vdZ*(CpxUyf527U|bn$q8w7b zn`xOo?e%&1AJO%{D(Y(K@j!$59#bMflbkv>FC_3?*0PwE79dEBkE@wjT4ptQf|tA! zo5}|FUTcr@ieT4tx9a=xUeK0J)3zaolOu}yt7&(yMX2;pSGaxl%b+9BAGhE@3j>!V zlDxbG0F!8Hq$w%Evb|(Ze3hC8B$kV?9AM%~)3qf;*QHU;lArwbVOWJpW4+QUJ{}75 zwsCVSY4feEah}=GHLLnk$rT2L07~H33eGysef+Tgnpq(VS5@frQ{obX<`BQlKb@Vk z?d?XcmnzWepGG*QrhE;$Iiu)Yl3~5;qm}{B-<9YJb!Hl<_LQlsvkwk-6oR38A~5QC zdL}Y6C*;Ot?Xw2!yr*d{Mb#iJgwi2hN9O{E% zDeL8krIh?M*EQtQcjAk3aaPoB#6ziHSRh06VT?8edOLYcJ|N87shinlOL!OdmH^%y zDQes|WB%NKbTsJOHwq!#W7YBF`h^cU$JwLx9xI4_l%af8(LJ)>_nB&ll_M$5ya`IL znPqEczL{3WXVX0S1}&hB+MXXDkDJhD$D2R1VNHX|GHdr|g776BH)u16cviK1kDrJo z4e0=R3s-kcIUj88@y@cIh$BQQC@ONKgbM-R^eAb>FAx7rsY2jwI@;bQB`0r&;M{+& zpq7&DH1OG^4Gl>QvI<%F*|6SATAL+Kp1wR+6koxUROA{pr&d zg1?XU=1@#Y;{y-~@I)lT^RQuWs!SMcUsI)e0YXk-OT*SZ2Y&|MZSuLlIXq<7Mht}f z8m0Q2Z-^H`8^D8qK#}ZS!h5HhzsAVEMbyA5My-gCu^=WIKlnzHZXkodD$dI%QOqM< zw2daQWX2};-Mh7ji0Indw6s_L?evA~F=~};#Dhvb_d6E%7KIVoHgX?6K)&eL zgH3}EB>%!;3BP|$qM|aSeA7<(23jwBpF2?7+Cazi$B!StpbmZxQ*96D59wOd%mcuk zCh_?7C*Lx{1Ysm494`MT9JC)Pd+jUJo%B)YE1D1l{%vp*w=`awPK4|caULcOVUj7+ zYr4?T@cyey$(OCh+@bc*D<;<2a=D1r76~K(23MUV%Q?Z6KBPb+ey>EiI7IaYR$-t& zfD}BBg!UOGjOhR}J2KiBLiSgx+CpJ=^YzDGS69)2fu5~dn)5p6qPK0{=VlgEg}c2? z57$sFqf^utV&zG3SBZ=eMU&SDqQhiu6xkFq(r#2OBk|`O{13_G-LQmkB8&@-!9&E zY{tXC+sN^7s$46i`+iCDFcHb>VNv;Z(;)89=kKP^Hu@JB?scrC?_8T6-HovCRTo`i zRkj-IjThkQ0McD_M@R1F=Ej#Vg@69Q4eb?JzpXl;^?XkVcOr?*2W6VBEq)@|>Zz4! zr4WLz0&AlQS7~t9D_U9&@1WC{+O^|zO@F3&b>6>zugO~yg{#aoXi_MjX}dcU3?Fp-aDZtmZKi%J-$ zCnmuPn!uERv3?^A^C88wy}YC)ZV(V^otUW6H4xU&dds$a85=^c2DD;B=$rsI+{WBIx58m@i_G}t9;s8JI@ZQAwQfthQK52SL z%b|+tM&E$^-7J_SPmGSn|N8Yd*1=ESar>Mi60LJWv|P))>iw?Mg5!0OEp2RUw7?yp zD8BksRDJRre#IOQ0P4VlS(!Ab57JP^K=>BO^_(m&_7!-0eQ~~L*LLp`7x?QrR5Isx z?PM_tJ6QieR~Hh&H8A@LH!)Tl_i8o)eq?36Y;QP~t3Au?5HkhIDONKG$c7b(*>Y2CA?0)Ze^Ue`BCp zrKv$uVy&)P#e)ABB1-wDO2bU}yVRi+K_L{`6~ zrCkfi=tP$f!7Y`drL0+Biv+&{{$ZU&vj5h$wo;^Rbf8fN3IS(rtFiE={Qp*54=&PY zuENjW3*TO1U`TQONQ^o;UZWaa(!CJ4?hfR5SQ!0NOqr~IT32DYgMoqZ=%nZ}c6d9s zm_8-|5s#hhP1!;&b^U#hE8r-P@4n_eODx!*NO0J^HoUzRL3YHJlr9hxWq%ZKGbl*q ziA8WfykwK|Rq`^vD9q^Hxc*W8qVGr6b>A|-Tf0)vub|Qkd$i{+4<)x>OWaFfJPJ+c zDW_=JU%I#LKC|y+^FM97{_xk!`fJ`1n~AV?m+U>#lQi@z_9UMuFxgrV{{7XSew4Me zPQ&40Dpr~9oBeuE*A`}3bL8tK9ajmxvxDG$jZ3jLgQNBZ?~k1eOEfO6R}U>$!;e)5 ze5Vpuh?#o(O#%N=HrkQFABG=c42&c?+LL{K30*5Pb)EwzyCfJ*Z}-17&tnPDe9tO z*fG)`6{IJjUkb;$_*&jEG*KlEZ#(a?Z*An|0iIim1<%Ki921kJiSh4d4`^j27{j#E z0NF=Mhnr77_r$S*2oTt%x%0+K`CbeMeJ+Off0Q3@SXgWY&(oR{PXBj3Rx>0xNGhia zAshdfhSMT4!Vo){628~kIhd8DW4`I)?fpH|u+w~dv%KF;0P+e){?(6BZa7Tb zb4{tOvlsd2o9O5bIQ+b_lBu{Rxc`_bULl{bR}8S?r_72c%u%anC7Nt%C->gW&V3Nl#^D>A@b?c{(6`}y(ujhEhlu-3 zIwh#HpNJ?b8)Ew`CS>THA_ofMxfpebI6{C}bcXqo`45ocfrvndFTt!_UZt()ElO9d z$r?p8ZpbNu_B9@IqV_|HfK`epcKN`xtxS!^Ut4Cj1yulaodTbQ2X%HP!!a_ml}#w& zRLqT9`it#rK(d=Ny8VjO1J?PqvvX*7cgNms;>fqx@>agDJVxZ@HQp;oa?eg0QaumWI#(HA*>_hWtzi z7e15^OiId0@XRexC;bWhY<>o!MMQ+7uOM)lXi>vVWhF8>Gt8ZLWj~*vEeV&FwCKLS zR&k$^+c4D#Lj>}ja8Y3$%`1U;uL!>;$#$EMA8kK=1WkWquSGv4PCDYJN%BaNYXu9f zc-XcY@Aa&#y$W;I&KDP5!@ux+dv1`H;ph9fXIIh^&D5LLMD~z`ldjJ~72aW{kV#@|nf>T)3p^c#~wMhuy239f<{r+79kd zMx2IJ4Zkr^)3z3Gb$N%6?jGug_oqBsp7ly5#OsD%cx*lc0|9NTvh%|O!K(3^og0$}eT*z7v{nc@_p7!+!DrZB z-Io1AnNi!%eN{`WZ>IpC_^wiebvGu&Drw-)wB~90!j6Lj4Nh?XMrikHU(3sLhYCTl zj&kjdz8>_=Ekz;{el#@vfJRi*Uo6a>TFE#OjZ!qW>-K=qH}LW$A5CArJj2+jn*n*y5 za3;{DDZKGOC-s1@6YQb$@C>hmT+z69x}`EuWJUKLb7agx-Lz6E))O<6Ky=LTS0df~ z0_3c0FI0;6X7;h;F}bt0|E2@WOR)+t2R@{dPyOXYmX<&g>jvGNGIbpjuJBKooRBfe znI!CtUSuA2SxS%}=l%Ni0mg9@v5XW1X#`d_6IkRyK0a;gX=pcGja{_V_{mZ z8i6rG%s-}f5#V!L2$uWO(IPD~eb1MAvun?L7ZDL0JI$A6j}R>RfJ}!;q_HphQ4zOY z2`>SW0>$noN+p_{gfX!n^!T(`50@Qml9RnHEW{-wE@o#5O-+x!bOH4wd*iS#NG#Zf z`Ic6lYQB346L`}20vpx;4FS&C+7lVklee$AotkSeoFuN{S=4yeh@=wCp&_xXSSXx) zfW5H-6TO9R$FiaXMFIBZU%a2+myIH^A;hSS%H}`)zKa-(Udpb!gj#RA=`HA*ZXAb( zCdb57oH;d(Zp+K;;D_A0JXT-NemY~_v8XRF<{_ri^5%#G(C_l%zouF-wi zC5|bIY(eQTn@_S91`Vixz^0;Je&(9`E%`^D8ai(WZ$);e4U2~22x!`C(KMFtj}aT$ zz~k{XZ+33ub=pXx$2Jw%xDXNEYe>-FRAp3V`!PtemE-eVjzxZRS*$(d^0O^#I=8@* z>6Kf2IN5^`=&jim#oIi30K~rUv4pIA_~%}En$Rx_b%*n#jlN6L1fF#817>y?B9dS$ z%exmZ{Mto~dG!r^xhJ+0Wo{c%`Pl1tnV617sFBjx3BzcWh3I4M0?=%lT+bO8rZ>1g z+Lq2)Mr_lJ{+`>wtf`hKJHw&4ao#cH)$ZE>c&PKeoO zW>2r2`7AEJ`~nx-syWw`o#j(pzXcI`=*+$~syHnHm{r=(e68;-p4hy)>hd)H<)rQF zehss+v3G)~`2%wv^V*9SYtNl=Gc9*y#ns;5>N1;_w=UL2v0=Kg8}j-Z z7%1h}U<6%TzUJ#8i;zt1V~+pYXWBZe&9U+wH|Ou%hU2@q`16oJcOwT`M=mY$P=V_B z?lbL@q$Vaz_}7RCcfwUwiEQv6Y(1Vi7Vp5j=I#z$ixV2}46;3P{~b>*i+N*w|3&TcpA*>Vj=kW{->g27mvt4b!Z23T%|U z%iB>aAz(sB^mm|%f|_Jx*w_kbX?rwQBE~Qw?9r(zbCIHCx}R+;x2IKAMTH2(1YlH6 zh|ALR2JXv~PCI>uLeWuL;RMR&XuM=N!65FL>fM-W7F0PvIqHl;MY<#JbB7^d*~}cQ zy?aOK>>TUtyjD{q?(R;@FlK0LTc*D>lvzhPy_AwPl7hE%zTMTbNBQY)CwcK;&hq=8 z^l)rN)v+yb+uBc)h{$FYp&li|i?F+oYV!RX@Tk*%YZq;3{rkf1-b}+P0G+Tmeh-#? zdvO2+TT8c#m-a*8-MR&rxq$)f0aR%K{O$Z8CWiP7&PR@8-nRBtTE)2NM>YzSPWJvp zg;;ZqSQFg%ukW;cKT1iZJY98M^uanvpcJ68XdFOJ%q5_gUix={``{nKKBG#TNsJTDI6H`e!EY531?Q_tUZ(&`gnTvV;o+gHf(4jD9?Got?SIafQo10Uxe zicVFXJo4*d&5f>8?c(h;gEX@P*92xnDJGx(dR!SSdqNPwy5@Tv#n7DXM?#WBCj!gDN$ipFy(-mHB*yx4m6> zM*s2Vdj0Mm_@s_QTij?AbOMBT@72hoWo})MioyhwhKzE#NVVVS^Z+{?4Ia7^2FAi% zojd7Srv6r8K?pL@i|2^H?WsKchlX;JpBZBugOb9+$%8MYgb+@3Lnm1=V9ceXKg&lA zxjH>*e)n$0AAt)4csG5@T=SX*e#%%XgbWj6zUnp#(0=+^$uG--`8|^0sJJ3_viwTz zo3=5GS0dXo?H{v-hA`4&ssiRY~?W%Yrh2KP87y_sPh&^jb&7C zPh#&MC%%zbF)sQfM)7Pc3{GK-~BF`CguJsN5c9VE*V_F;Bjpl7S_r_tX; zVBi9Y$aL9$u&|3?*txlH$#LxK82N_`Fq!*I=&CfgSvjaNrD0&;9XfpZvsa?s%!`ZC?(s$ABWQ~ZPGBnOd-sO7#bdfcrE^3~vr({z$ODLw*&M?k8G7p$jcntJHO}w8Y#DJP41J8ZQHe zVBi--M7X-}XaU~&_8E|e`_XB9X>`TH+G%ofwz&AVWO8wJH9b4KqnaC6a5PKZd1^ur zRGWQ^Gvm-sL_qT+daO}=cg|McUS`|$w0V<>uJNu3J|3g16%GS&jaf*sz0H5tdBq_F zHda|knK`MgRwuwh}~JOEM0Bui=6bwR?9W_q$z(epGJB--EE49!yilk2SJd3 zw4Ck^;@+f9913lWPN%=1Q6O~d@%q{ogT0xVc@#Rv_C|}p z1V?c z0*@gfnL5Aw^x*9o$@%Q?m!zv}U0K@_pykJmL=C#g=1@cmPS;r&_xj&6ztQP7>*pm0 z<9Y@)Fcyg$-jZUNA$wIa1<*Km_xBIc(bA>#b+<8A*F8PTRTcv5wGX)^y%iO*#By>! zo@A2s5P+P)?gwvGjN?~tXIc*rNB-IyT4Ot>WpV(bj*fhoTQj` z*7*8*bYkt7*y)wNzV>#%rJbM8IL*up+I*R3MiTK1sEG56CVs_1GLzTCC2Q-aX|X*r zOV~I${R%VeQS0Ue-|GpcB`GC+`&Kd*?Y%Av{g#@VYRbubaqyz7;BR=i-;1a~qZp5j ziCJ)HXOCw7AY#G8J>v}9Vd8LoOYX*>`C0yzu9jAd9fzS(gd|dy#<5b_)ZY3DA)=5Z zRgnLadW4w9y?hX+UHRcbahBt!**_Go?V2j4+&c~YB#xG%rN9PS=KLvU=J2>o5 z+sfO0`HOFq41GO4Av`lt&k1Q6%B{bt&vj+;tZ%*nxY?STa~Id!z1_u|Pcbv6T?D}oH2}orMdJxN81`c!aabSDRXf=CV_n#k z)w>>e#SeQ*Q47;1wy?#v(#NJ#?~c*a+jFEM^F)gHwoy91lsHxoEOL7rLbdWQcsOc! z>(ou)%DO!jV8pt*x{#2N?(grrT3T{SO2ln!?ga%OuYL=wUkqhSDidd_W%r{!v&v_@ z?LaFK$)56Pil&ZX35zxd)ETGxgEur%M=FUO&z9*Z*pu6Q3NcEjzo?2vf^naDVOd!| zIQ;H+6j$t>oVbg&h(3N-&~5rZNAOiX4aj@mi^<{P%i=(TfBty0(AJvT^6@2C(+>h~ z{u{a?n4;cO_-unloV`zpEH|S3OLdF04U(@UKhyVk<-acrSoo4p@Ysf-YtPYLmz|?S1YgcwAbln#hG!dY zqbQhM<13ueAI~O@Zdxh*ULmgfCv581R^-7FkCyU^b5jeJMPd}4;YE;be_H_D!WCSWr zFbzSF^bgQ*&mWuNv9ZU;91HR!yC#f+R`W8mSh-pUQ~QZh8wdz6Vg_Xg{Z4_h=@Edk z>??3h8hhw*h0znhzpF4QIaX+ft8sVANM!S9$)nRfrzZj7zZB1(SGqc3A4T{VU|H5Q z#tlaXa+PZX^5X2=oM&Sb();&ElT*pl$~1@4#`87?Qeis(|y<|KgLES8A#e#aR{=PLS`8Xg@esM{}g89aN!^&NJDh zl82K0AD75?uI}@7G1D(fO5P?XdqhZIay*UAF8BEesyxjuhmseXPzN>v0sb+4;qhp=&2zWz@?7Zn zs$EqP)xhI;dr|QBMK}2z$tNeff#{?KDI*ufgLxmX$JQ~7V>_;G@U+?eAzU&USu%SG z!sjHVq;A3AMbfwQ_;4BDQdOWF2UeEHfymmNFrwSGZy55@LrLi(&cD?PGMRQU{a}%l z!Vg`Pk`MlM^>K-bUD#5Q6uG13JPS^Q3ib7;uWOo5`dBz8DvW;{QVn@6c}M%^KLDNF zXJW8V=9lgesBLX%f_wHj2ZyQuYg_+4sq73rFYoHSpKmHk+1~+ORN_#u1q2;w(%slFjPI@zv zJujuarz@bShQ_P=gFxbIGp~;FIJRLRy)hgIzc=UMHM4REedBsdi1y!eausQ(h_*uY z+WS4p?8iOdw;mpnO-;X_KhFa*jFy*3Wa%t(HLBE*&!MX9@kR6mX|NcYM3Sl*q&a-}G+y3H5fWBysBHTdf{15@0G3hSHr?nz^`5r$j3= z6YQLO0Af*!K)aH$qhqNOZ>Bn0W0SH2jsgP9pJSQc*LvGtSV)j)5q}8 zuXb}nMvFYnd*WkK`^}IDg3e^o#aGN~Fp*Ha#W_e~k#IB0}NBe3k$vZ8UGUt*ppg52NspP0l^Mj~={%NeFO>fl?jFC)?V5 zE3;RvJ#RfhHs;n)+HDjR3c3H=g-gq{)3tK?c81W~8zAK}oBKCDkDo4^;S7K2-$2|k zg+fjMg0k+`M0+=dXydmy^^=^i)6ooGhtEH#B{Xh;4QaUqU4{DZHdy6bo10(B-x6G0 z4;9AQVO?b{G^Oeo{4nHF1$lA}x{7!41A{$KR#xtmLEwqt;25@k15_Xy>gu!BfD~Sf zlT9wKAT*PWmN$R(fogL`w>*xTA z(w>|Q#=*=2K1m8Yq>q;zC35P#NBnT>(QCE6RkZ>w@+ZX^bUmZ>@u6=~YaH5#2u>`V zPE9NCCvbJa$9e6!tMh%5XEY52uU9VH9`6Bxnuli!L{vIs;^M;>fd!NMxy|Y3Am;~t zeToY$t=zgglDySpH;|F@;|DfQngXM|H1%lwvkPsh|7~m8-%E36TZSX^Ycanc?Up&G zjaHSWDEkWI@LA`v4gLP{W=4?pHdq76Tm*@haJSlJa>|Fa{245!) z2*A#ek&yw*nw2=ee5R0GAzE!VI%ydmCdf=M^zDQ;{k-5=^_*Z!OZudG{@~`AWv9I4 zTwcWW?IrL)bNvB!8B_|6wBK?cs-%oAWhxgo zp52w_5=>zzr+}CTk_luQXdy*fKe*ZJQhU!TlJes*Gc~ZZ2jqNjq@=n81xxets01s# zFH5;m#dB5skySv($<0`y+6;}dUFCzj2)3DQn9_oe3q}U{ z#5gzNLeo**)+}mQ?Qihj!1a?PaSXl92vqS_*q?m$TYf%~Aq-B)Gyql)Z*Qw-NgDxZ=U4?|cs z(B;KURa2jJX(4c*TI~G)2FzN`2QJ>LMS}-11rf!`P@lgYXh(?&`;2Hc7RPbkH4@k>>T>9QdD=-=dy+ zTyiw*dqpjh-S?Xo!=$iM9xF-)I+^op(PhrYewSGq@*9x=_;bGy!(jxk=V~Zc2RQ8= z9SO9-93m4X+T7TfHnr%-kLJl@rTex?u$kogxHDn>aKO?PCWt_P^@>7AD(C+1R+(m3 zwEVV`PzC^YFWTR-RqNR4*}ZjyU+Q7NeJ-Y^S|S=t+U{+UGat5hScf;K;-49!sb3unguf*aMR*@tCEOoKc_a9@Dye zsFK_9kkqT2f<~ zdpM^V|x})b?8PSUEz?Ucu6k>c!%ZAftr|Rz` z%*T;}S1}Eyf4q~%!+$sjsVF83(b6issb0jzp~FXJTnt1fGbfJH?y${BkQ6mOMp#e+ z5MlsY|E+{WHspus6Y&Ww`uB7IK2g-Y>L=}1UDT%tG0AizC4Yu7G0_nFbm8{mIffvE zvAn;|4J=;P}Fl?h#h!?@Dwo}nMew84 zmN0Bgjk!IOREfy2Kp}r@@7!HranuBf!4#1Wv&%nLQlX~q@^Gfba8}M&%!3{ze=^dr zWy(T=vO{3_F<(fX=p)g-o=QusI3O~5B*Rui1h)@&{4=xhwYJ3&;P+qg4B==8b-Dl|hYXJ?7 z<^=dDlarsJb7C^V^UzQgUh@ol2!OE=Ui9h2S@oE+GvmHXkCd>Wp!a$Y{&*lFhM?m* zx`^UP1mZDpElq=#GBRlp>&3`Na7n+R)PhQp^bMSy=^C%i0diC?ss;gnk4dU*i0`{H zPg<5&P~wORErmDz{afyC^DY(jx-^ARz4H}lXluAnIk$rZ^r;hdSn)K2IuUUIwssg2 zmg3CUro>5|IH*~Iw+`VN7x$V7+2q5+V8Y+u<5w{Ra6qq%UPczrkIFevEG6kPtLyH% z!Y-ix&Y7@00_wqH>rk<5jh9353JahNKqv2wFL(%neR6cnR#>6NrX(j1Bu-^xXUDny zkr@*okD>~wXQSrTjOlKOH~}40LtmsJ9M1^}13nh^S^k@({inizFPcsAxXJTy?eaY0 zBF(wY?Ic&zUyXgO+g8tai%*-bZRCwN-dH0NLGI|}g7YI1u7KChr^l8yO(`k?@ENCQ zYemofuf}{I0{=Q(YeNPS zHI1pb^+KbJMynSQlDA#0W&{sS%L<;Qm7BfFVR`l4Y_crvk zUQ^pDv9fk!!8f=Pyp| zEsKV&)62CPW#t%2goaX6qtDJ<7;=0bh59dSW`Dv!6o@VqsdeY&p5V^~&q(`{novZG3l#&P8=!w5ub)ONdhCjp&I(6ejV{?)cH2 zmY-_B`})O^kW9*4?Cme!lE)4XB825CGS~<~5;KwtqIyBzDiz<^&d|pymYIDD00e!t zmNbF6Ofc3j(!F(x^6MA)BB_$bXtB|Zc$pvh{z?f95Tft8HB%=$RaW5V(VS}eWo4zO z+dCYGsHt=rNm$6e#IXPl=dZF8G?1HcrjU`afH z9xE6_;pcye$keHH_7nH)Z2G*>3;xrPlL`q18&d}SThi2vU(8j_3353S(d|AbJ5|@1 z`nf-9&TVefQ;vM26mo_s4LN-jK{15BNssFvhq)n#RQNF~qqAX#H2d|Y4h{PIQ;~G5 z$!S)QK;pW)WgB!0)rzL}a2bEr6{y9>$45j&*x1+rQK&-7ftubz!}0N_qn2Q`v$del zz1vH6mZ?^@I2V^)5%x_BQTiBv2vNZQD8bFj3M~;4BMY;c07cK;;isnj=g;-oYFcL( zyvL7%f9>p8ET{aAqzv{w`5<(I((HaV4es9Hk`DGBz$Xdr0&(Np?{L*1{Iqmw!1a@s z7SyX)zfd+cNr8pzR{^YOl1@KhZ)YaX%?i(*fw!-;6y5G=&|-N)v$~pFpNf5DyFhfp z?u4Zz7S;US|iLb%n7~p$C@E!z% zk%3!>sfWk&JdgG05GhkCJijiW4@`{`%Qg@7wG8@yHWvJvwWUp*d~&bdbaY}}=$_B@ zbh^_Vyx-oz#|Ht%Cm5?c0RX$Ak`zMj|c~4!lQGZ?8(V}UF^f$x|FN%-~f5J z_T$#+R##2s)3ykEC1~A3LwfuQo$IX$jql#)g~OW~qq`Us_SD@!2Q=j;ol2eQB?c8+ zK=;$2bnGt-+kO>C`Dhut@|TQ~f7^9Y?Dl-jj36T-@2k1Eyk?sb9iK4p_~d^Ku4+4Z z0t;_=Kg#PYbkoVgm-io)O|c(r$B8etS6*H|Zhs-=`p;xFNu5dCiR0mgO`aZq@y?kU z#qh7SnfiGKocxzey&ix4=*@6JKGEql9wVeB#or7BrKgGqOJ-afyIry~CcgR}h4yER z;nXoWKGY|<+JJdS9qRGE2yol{2ifPzVtuxw41Ff8(NgjoCL%>a+Ycl@7i{O1nX@)46AJ?q%ahP`R&%H@vLu}g1VjZz9XNWFwD-0 zVumiEbKmzfo@g$#AXJ3^}?S(xHH?%G7U!iK6Ge%c_GH)Af ztWqdVh~6U&S}>p)gUt+ly1mj6!ruW#kd5rB8Le(agg_}OVQf%D&=Ft+iB)L+AVf!G zWw@D@+R*x3pZ)dl5TSvUUPxbLAR#q%{?lI(8%aqJln2IJz_V#*SJq|5|6cFDP(%B|@mi)guCcnywWX8wfDr>|;q&GZFv0XeY$7LmGsxE?1GE6nwZ7wuQNG-!XNru%ry7?)mo{J-bs z6S_XYW{-&h$r%7Vf{tuNvoM%Tl^!jU&Q&S(%8%LJ=8IpXQ3a{w&h}aA^z?jvJ$Sv3 zgvN^fCBCcotsAEx1B1q#?!U7LC2tO>z)42p=b7Yasm?(-{j zwE@GQFt2PYdN>kM;zOfkca~4*2^?}%v<9}wuu=WMI1B9ZDT-@@hQmZ zkihKsiFp3r9;5TD85~(~LzED6Y5No?%v3rzJh)zg;X9B~VnYhe4Gj(dm{=xC{~5Q0 z6+_h}IKiRSv;&WQ`V_iBd#V%{;*s)=Z<;kg9(7dtD713vA=L`=1mXi}k4=RO8(59ZfAKp^q5NH!@`eV|Fbak85ipPzt}Ccz7Wv_XpZ=V`>m!!M7rJS z)&p7Zf{SiqO&o%jz0#)khnAL>u#cIe=EDM~@{qzGg@yhJ|Jvx_va)&JFw?Mgd!5A1zIm82fEdhS`0*7P>|(Vx+Q~0C0g|qPSVc zw!Q39tdvhkj*IIx>tbYKVoK>BTs!>)5*CGo4X8N7U}n+K;Qm2E^lb4@?BqxUueY7L zb#3jZ6nF$jp8MLg*a%^`f=>*%|@(IUwgi zArUHYMAB~gcOkGeg{`v=r04=H6{g*M+u|c$9e^+cYIvPK+SFPN)EwG2c zY{XKoVO}9C6Ue^u^74R<157~c>ZTSKeb`^EwdBrk34@UBs4$3k1LN)0fIKhc+xAZKn58}u zX0y9{KyL0mJ^e*d(P&W-t>erOHAgje{!$eMGqdp8>NAjedVYR>d5Qb<>A%-FI3PMZ zGCbTc)t^>-@MX|lh`fhb316Xd#+&UW1x5bY=m!PKo8+@#v%2$`37%yU%2aESNp$&i2v?ADTAo-(BLi^8cYyge0oh2jcy2i<{(Q);4kvz z1z-&zyTe)-{nY%jpd26&wQ&N8x|=lGo(PN;?q7D`P$`e(A|`j+^(@lH_9_LVFCIr7 zleed;7YD7M0M>hny0MD0`II^L@*5mPnHK#>%MqyeHX{COzv@>p>w0CwD$q(usC6!v zTvm^AVP$+DcvCg2C$2v$y=WralYg6!nqOe@L#=fdrvbyO9j9w;n^yId92L_Z6AJ>F zMzwFu#2@=M0BIJkX1QUn@)R{^G{lcc1}dv{`YgQT>G0dymeu)+g(e;bx4-SMyDSjQ zNv0yRPK)109pB83Pq}g$y1MpZ>WMgjDg9OAqJFXJApV9-7WVSFg_`LfOE!KtLx*g4 z^XUE!dxH@N3K{5Czj!VCl?yLw?PBpb~yl7 z=CiBcx#SJUSeXvU3P9_uKtn>iK*QO`?WVx~-L3G8 z@|!7_!m<0uxX?$X;s^0uFR4N|9d=JWRz5c37Iyp$<(?(=p2#F7@Jz!cXU() zfB~oUh#~Q-?PAfu6Yc+54)i{kGrnoI?>jTq+7c&xf_5Pr)eur>cTHK1TF<96)t zD_?St%}7R{dzM@=QORtR0D##8m3?gQZc@0$n$eO87Y!xq{ZrI?HsaHF#HUZqwag#a zcNqJPaKSephlCU+MTfa!HR#mHI3t2X2Ry!*G_tVl=&p{A(ya`nYUadV%-EROnIEgG zt3W{u&I2&o12*5*MSWM*vA0$jmJ-pSMoOcnTf|;6+QGLC(h~Yi9nJSx{XI zxyMFsyBx=jzSjpo(Kh>w{r?_I#I4=cAVrWl{`~Tk?1^LV#!0dD6T0lJZ48Ya@ic8~ zfBNX{SHlA0hgzDN=yiVc(xtS~fs#!NKIaeX6&i(W)f~-#5hEn6Y;1ynR-61arl%2o z5t4H~GjV1V^t@kA%P>L*v>!DP-81x3xl1FP&FvmKyl>BkB1^|3EguvAsSm8~-qlnd zlpzwBR?T2%)6vsA@REyUgZNO03#l+9zy}i<(N8s#08E>DctmwVeU3A!>1maLWwjkE zTM}^_Im06<@CQ*)6=o13vtt8!ND7d|^>3&YLS8W;#3Nn0pCwA|K(%Nvou7O&K}Wxy z#Mh;{4-6NldI9oRd*ri_l9k0uU8G$CNg;nXjQknt%Fvvd$3K|GMI$nU8CU_tjG;=c zp09QdyPSZlx_jURH2}dRs~|SW7O)~+LJ?Is(XGi9ENZm(kzxTVG@KlB5_N%ne8oq! zmLB*lhjITpx&6^(CH8X*nTU#u`?+Z8Wk5vqhRb3-QAJq8Jz$>@*GoY5?V%jNJ(iF?iURYSbFERhP^-QjV z(PP2j=}lWM-DAeDxE{t=YsO9YU9OAQe+QC#fR~>p!z5sMLk!m=V|dG@sYRcIHwIj0 z+m?=8nqC|njG^8i|M`QFF}&sy2?Xvf`arM8%?)D4s4f2d{0R#z)h>CMpMM$9+E~z& z8XcWC2EYv}(nklM1@}Aaw~m!r<}N)6$CV5s zyo!s8G+}S@L*=~Os}-V(%2YWe@6w6?GjyBJ1aqi|PLNbJoPPW5 zyW|ws9=k5D@8MkxMs%sGndRMU?f?69qr^kQx)GH?$lnzVa0!-+ae4@*p*@FBl4$A( z@KFA|M7Tz@VX~Ak<$4DE0fzP}T%2wj8F-OJ3v}5*8-eJA$LWhL6-m&%EFQTk zm@MBTQ(%_cRn+lT12@A+ETSfIJ-nW9nuc$RHVB4_c|~AIPb2p|VT5g$-;y8|lM%rT z^8j6@cO+pz#K8s(P%`B}xZ?P^haf3JK=9`_0Wn2xd`xM4@|=M;MG__Iu|S(+j%wew z?9wIJX^%##fk26h{u+yE^JOWbp(}WPBgx5E#nGc6rr)3Jfn31<;z+R)hy7kd*hrMk zO{P&Mj8%?~K`cyAVgceVe(+q`^XjsbpbOJ#O$BtUnVOdMndX0wQRUiUDqQ~#^Ae-E zXj&jmCt53({9JwG)h-C;RSULY+5xOb={EsF@ndiV62fsyeZJkrhc zWF-8Ro*I{OI$;JrOg@)~5oA0`F8LYEEBMbIz;$pBR0um8o4 z=a!e3gFw~R*48+vdU4JF$JTd1Q{ngj+bi28+1n+X?Csin6d6$oMF?4uO-RZqB{N?f8uM`?cN$1t0CjXsHSzX|1>z$;%6k zwXy=FiShCl!6(A3F&HFrs|q5g;m11tw_&~9SEq6$Oz3fv(t*Ww*ly+eUZwWnZ0OBE z!%TN~0@6u_DjEj6-spcx8NK@ZU93j_AFuEFD=RAy_XjsaY!SCG%VO-2k>HRU0KF#7 z4gVDBt`=PWaj3Y($6@EE?tc$f5&CF|v*4jAMyB=Pf7E`q2CyM}U6F+VfgQ zvHKr9Eh1ioW|i_0LKG>1V}j}=avbPjG5v-+j+)mdK&K0^Foc+eK1J&(4GbyXqi(>H z?VEmw<@M@{iZDJXu zu4GR%He7M;f2JfW7Ss4itcCd71)Aypx!cNCzHE8;41Or=M)82K)4^_sAd3t$yy{-~9G8SFkF#u54&~RkM8`>GTT>x~~*&O=OxHaeax})Q-$z8=vn}$c` zi@L%q!_|)Mkz{}?^g_LT07sG1#zz`Ms=ve-d8oeQp$!F3FDq}iKc?Y$CV4Z8Mek(A zO(4kkjl=g(v&)CxjyJe3DoINdF=szom0^gBq@lZbQFu5gBTl*>0%GFS zPEW?qn3pVu-#K6Of-pI0l75qve?X5C+Z)|D&ZBTjHntj1T3%QDHxAN#gX^&4qAldd zV^QOu-Er@Olw>RpQ5NJ!+KApYECm=1-6HTYznD?oET%nATuY^j>dy>SG|nS+Vs_sz zYSPB@VI{p?*}t)V8>x}tn7koW@ckKDSzb!Kk?`T|ZHs>UrRgLF?QJJkDb%dE4m%y%6sD(9fR)EZb1a0WbkQ-Z$kCB1Ca< z&tC>c#xU!xb+RaX2L^4?X10sqi4jWcajgZ+0A?YB7))Gz8cNd~IitalkPuG7-63=e zzRxPuDKOcCfv0-@Yu;$%Bh%XZ$?``6bJ4uFSp8<+&t*T_9d^VHJMZ`?6!#|}!ut$_ zc1oL_oREdWnjN@1OvWfFf3#c;i*yE7WRCAtv|y%GDQiH>+sT6ujiM{tA6YV93(NR% zao(0zXsoH(U7u`+DPwQ~LO%x!4D@qw%-wqj>Be*LD7Kp-g_R z_cAmz6od+3#DnlMD7P#AV*tC##XSD2B*Fb;BR;6%8^;>BHP3_<_nOs1r6@XXlu-P5 z%zYs@qKj6H`VT2=;`q25Ha5W;7?6FpCpk~eQ_NX|v#n3&Lp%ndOn-|5_8 zOXtbpN+M8S!+Pp1mzZ&BbT`U>sVX~r;IRpBC85uwPn z0_2uTmC6Zcu_KNR|Jf_Mpot<83XyA+Q8?+J81WL-S~pw1ib~=TgsZcWiy&C&eSIfd zaUVb#8>5Ao$=TQc8H2Mo;}PAkgVM5wMb$P3&?3a`PPzk5W{h-Es2op9GNu7?KR@5wc-iB(2J>x#vVFV}Mmn*k1zd!{R?S;-MIE*Sb?+O9*qzAZ8 zh9wArDDTnXM22R{%h)07dc$}S>&OpX?d(zQty*>I+@#f#DmbD%$pAe={^+L6i`Ro@ zM@@}auV4T1;|G8}P%wdURau>okPsAsnwpw0eG`osT=2r6(4@*C$vEQpMZUEoWHM=N z9?1P6IPUOpLf{Sq_B}LaQ6a!%by;4u&s{(m^%zJ_Q0F@4x2}f(qKo z98XA`Zwfpr7h7B`a((}o&Z4)ar3K`00Xuz=)U1lJb;kTyJU6+e{bO=F=L|?p8(R0Y z*$1wizO)?Pt+*Kdc%$PY)NTn+2oT;02ylvFt*aV(V_6YZiuB08RU7lmGkUV{04tt@ zk=q&9Smp^|5?h#ju8H0A7B#9cRYQAs%4Ec0n5Tl4QP(`pOyLt0_5+Q(>M98028vtG zp+z#(%3h3wEO=a0jSI$C8Mx*DrNZ0o0Ul_}GJt_`Twe#@qi3NY zVk8-dxakC>e8|L=`0FVxS6DEzSQLNVrClT$E!m=|Ta3Pj^H4>oBW6`^R#{jJnG2=W zeq81=<=5vi1>Gp~IXMXgfL2|2`35Bcf+Ge8_ua?}JuQN}5N^)} zFIApGcWEY)h)~pqulz*H+TPJ;*vOMG#1*hSUh>%dVgL;268Vdz7nhDYy;k)@=1XMDNp zANcNuZOM<>OK~u@vIBMAl!AtXodiPPXlYf52H;Bkr)1;EA4msiDJ#py+8V+`D$Mv* zoL$ZbOfYxW!fElwT=EKufSqKf`BKi|p!~SRg=27Q0l^&nsk})t;mK*OmivzD;4rtK zGEbh7(&OX(^TbiXVVPGOH6yMNATF{fH-11a1Ihc3_v(xLhP?KnA%|!y*YT!6nS4Ma znJ$;K$PGAzIC-J5{_?OTLCzTo=;IA@5S(zj53<+?skIBE(2sx^XBm16{FFd|=> znn)heby4OU7-Lmzh!%W0lho+RlhlGUm4C9;E7Y`57Ua-}Al_j_l-T6q!#DbA+7T{~5^*A<4NNl4_r~JyVYB*Cc zQ&p^`UU|XlnMv?eDj+o`B_Gx1_2|B7ytAXfCRRg`=I84G`Xz@{UR>t@`h=p}MwZ3O za-9ijC=d!pklM9qi)K*Af5v6$cBszK1BafSFajdN>_h;Hfi8|D;v`e*QgSlz9ssxb z`T5Fx_y zAU&zSJd07bs!K7Ve!vDVU} z3=Aa~@7)*K7T2%et+D{d5p;dM4&q!Y{QUggy}fw6J`lk4&JsKOmSq7HQ2`ixDsG4+ z189(!mse2mi@n%Yb8}Y3fV%Q>@`hRXFUXM+j5jsfSlLPpEUZi6u%vj-^_Bfk#Z`hb zk9ZJpoAH9p2C)?j+6X!vmlqxfsF^oKLC+JtMC! z0JV8lblQUl&bI#|dCn1hV-rUO|53h#p;Qz!$p@YcngGMYMPohDT5>4?87jDpwc4+& z9%31qK=UaSffkVK$jwm}#|{LE5}UKKmdcAKGTov!6zf-dYr>=4)zk3?@6TYRi7-CV zhG>*^eP#I;<*tXlIutEbS@Ve=7zPBtvPeiVPJK9fTO>hX9kKubeT(LuFiyv#xeU%1 zPGb=wzH3`&UasWk>#R{LZ^3ktvF7E_ibn7A!Kj*mw&WdwDW8QP!- z*o}l3G5V)7%yMY?Y%t^L>woF$;^XIs8u%V`nvgYu!EmCm`H=R8ZL%|(p=wd>qGDoV z|DYervLqN-EGs+yup*_Ivj4HM0nh|vl@`2yuXt0w$aWCBN2dczgw0r1PR=SCg3gJ? z4wcPSZZh0_t(fC!HzA?0u^)2sd3P=IcjM){l{=*tF90gY$ha#)Z(?c+N9I3JSxq!j z%K$1rSX+Rh`T5Dz^}?a_uBL{LmNo@GKP3goN&q$>-u!T!a<9dbUITzSHe%<5^Ft z!j&r#-k-WRA>Ra>%ksvJXM$&M1al>JARHXJhe|B|)On?@({s^!z(1mOP`wgpMmXO& z_z!*fBLNBAMD_559N1a0EwMjxMFrwzu*_r;V#Qo)6Q!a-k*jOo^-3nBCpjI=WyB94 zo~NPB`pWv1w{9LsAGh%)`k2yFIpjBDbnd2Vi|4#Q1v6VJGS?zETnnq!ibm{d|7YBRXa}o~8HXq0#Vw6kW@O;x1v&4xr;h{s z#e`AFUOh`xw`hSXzjJ*?PgmHhE4Esbm zIur5;haEqW?~|Z9!-cKs>t0=iA4q~J?BnUxXsj1PQbEGz^+Hpdk4@c0^J}#B98>`x zYL_4gO#?SD!B~|LD@)mUl5r=GQVaUDS1Mgzw2omU+aX5rEus&ykO+MPgUI{v1I~Q7 z+P-RO6x%O?yuv<@tq6Zfh55>RJ3X%#gkhYt5o*2;7%|sY_TuQtOSnV6py}-A`Ujv@ zo`HE8ZAO%FsxwCDSR8to7Br#KZ!f084Wsd>X=q?&z6BUe`HUfsN54b@Cdpaezw6=g ze!wCn`$kHlaZct4I>*-VBV*Y=0lKxrE&xb^*`S@j@XW}X?UXVglz1a#UrmjV?^NwU zQ=Ns|vdURromQ0E15=lu5}8+c>9WvIY*Vxibw1`LB~4D=q`VC#yni7Gur#0mgE9;o z19}Q?8i31#c@@Kv__T{(zZ%)vj(`1{@OfHA@SX_$_CY`{f7}e{Y8>7^Z|9+jqUu!M2{MzSk8+nQd)c=CVWTTH} zb51lZ{2|Tl%c}*qQxD2(E9#1Szz{H*S zHtm8aErPCYqq1wU)W*sQ?sO^XoqE{U+So<(>0_}Fe#n~KMH-r6+`Vw!;7;^t=w;xD zTlb6H)$QslO`)K3506sd5byYk9juw(gq^L*3K3?rs`)Ax#*7O3k%Ss|kgtLhV^r~3 zSgI@pD2ZCaSh7VuV*Knj68u>j7rM+4c1Y>IYKzxEEam2`CqUXz5^X+5h;q+d>3Pbc zg&=~wqvQ8Nv^T+@F8ild>8_GJ{c{Jtqf})zyh_b-QngY_&CR*F{VuClGI9&Wd5bvZ z>M!#aDTr6Y2Uj?!-TnQoG&DT#-80pR5#;W0kdQ2TSyNC5(Xq_K!zcLo%-5WuB7=?; z{F`pKZ#x!-%PaLp))eBqjSb{zmvHq`6FV^0?tnUC=rs)A47@m|7Svy~f3K=$1HP4#7w}C*`Zd&z?Plqtgf(P9Vh)*VFJZTj7x% z0s<)poFLe`V$vP{WWYj{vX=kGc77M0C^FR3*Y9sU zc=+dZb8)mws_*QC-*d9WQ26-o$HDFGrL|MqOpcT@`Mtx@?Ll}ssBov0@XYUYc_H8Q zyJr69$M1#;In&oamO2UtFa(~KC6O&TnJZ&*ZtV9kR`h43Kbr2{tf5iZlbTQe_rYr` zOnm}f%hdEVlL;X*V2}dfmw#Eb`d52)-W-I z=?2?hyb#_`#1S!O{P-dK2BA-B`Ex}gv?;?dtO`UddCZ+`0l0nb>-orw_(@NURT2|0 zuc@DKp%zh3pQKac1_K^;D^PVEl$ENfe(o8BA~6r8BW`yMXV6Ijztk>C819T-ghu)Oapo|6N$7yu41(grR^b8{$v$XOLf z0jC0n7X&>*!Z|uu42p`rI5;qU>3jaAS2`)hPk@(kQGDUu>?Wn3@7r36m+1=Rq z$D#U)load?$*bmjT)gp4gITgRh8`YK*G68MT#rtI`V)F*$xP@idVsEd`bkF-G#;%q zDTO~Q>qaF?%!hZ%& z>+i#`S?lVgMe3BZa!gErD)X?ZW_*czOFfXA#V4q z%4clyL8|%h96TCcT{hxyWjdT5f~TTFzdlLU_0({c4lOk9@!ZvD)Xg7zwDzsoN{k?r zT28r=tvs`Izc+# z12ZplhlhuW33Z=#RJb&H5rg4Enx4cYi+AMt(waKSM`GuRm69d&(xERc zu{pDd64G)d~Rf@I|6kVOh9KHvogn9j7wV3O+DR%LorjOVRe zIJe>a7~t*VP3I{$+#ksp8yn*1zp=Kec-DQnqG5ju#6NE6l*Yx4h8M|!lAM8WA;!Bo z2+r$!_wM=oKmW?<7(zLc&vgZD~*_%D1bEDUt4s{Tb($!~l(a;X24@A75N&WAfzN7`Np zttn>4+0#c;i!?tMOG}@iWS9&<1BKH!w{?+)-9Mfs5K>23{AM6TukOt{ZK^X@79KNQ zw2--7g>{rVW?5L6F~mw9X9A!K5p|Wl3%ZKdm#NH?lZM5 z7wN&I?p?ybD=w0Xk5S3jt*uP6*C^!!*EIU>*D46y-4Bgl4zqKAdH7E_-Rf5+!?njx0*~vvtg~kK>BfcjlxXve z?~*>N$vG^46rr^J=Z)K~dygOAeEjNaXuG_B@kG(n_Sbg^WY=5-s2e+)OH#d$hGJ1l zXUCqexJme9be_#n7(Af~HR=>s(TaX(A}dc2R(uP;`@Uw>JpG+IQ-3*ucw|?WEZ5ja z+Bdo!qmftgOg_@Dn}+(}IjX28PU*kWaM0IFvcSPH*_10xrFnuEiWd;RO)ZZoSxwh+ zqGq07PLQK`z2IFBITg(v*eT81gVdPGQ2A(|-~4zadx$o0L)1w16IqB_bnw1pjU^e#C5s z;{l2nn+J^n0Gc2#we>$@qJ_(gnU$4r_{FXi+kok*Bt+I)l1OoJHBToJ@g+Z}auct(ChO-M*UaNcTUW-cu*@?XBJzyhbE3_4peAxZ3BwSm*1 znuc0w>$)avj}^JhtiSPCrPPf{*GKWp;j3C|SOV5tOUKD$Q57sX_)Q=1xIR2wx`va; zMDDmY*60gq!x!roJjh0B-B`2mvi@3T*vxekRcfJ6R_<`R$7;`Wf2yy9p)ND*3AKxlXto zf68vVfHHLqY+wCVmpHA4xzYS&E4jHT>tuO_i5$Moo_$We{O0%Jy%GGqefk+@Mj!Rs zFM={hb2%?pPi5zJD_r*)PR(6#ZRR3JBrnwqQ*9o3?VcF7=QGN@U}fPyIvD*iw;b;w z{i0%gqb&b}u)*qd4R+HXpBT+~^a+XWCRugre9$1vc;}=Gd2xR7{{BKx*1NUC-{x*d zH`?g+vqoGLjx*IUwfj;(zPSbg=qMJ;{>GF)1#m$1&HU!8}%WIQT{ zZvuJ$@>Hu$JdH6H3t{LEPCBM+pk6d6*6eB_T*5lI$(JBEl|9(XftEHb*|0A#z-Upc z-r{??NF&V7%)*vb4ukK1yGXX>)8m?RyK7UL^tOqx^#R&DI%+Ks@(9q*0~YMjd_Lq? zS2usz_c^&i%)|6P-2&YXgq<}`leFNxV2HuTj7x+s3(!Wwlg6b#bdDuNMH7ijqT{9l z*-L~soOE)E$n87Kw4f}4F5Jux3%7$a9Agv)^s_}*&tDJF4F4%MGtBxkVPWB*EAj$-e8jB2 zXk3k4O0oY}KP4o*PHtsxRr$jk7RABY$GBbb{HcceZ!RCLidx&&N9 zFJoE38!>NATXPvDik^?>;4D}4SZV&SU^U*>_>=&@{P=EKFzUjE3mcLrOUPp_rO)hvpweWuOQJ>6IxIH2t@0)Znljz3{U_F^@ZuDF@ z>Cv7KqTdSXt8eDb+IE&FKKYXPB`#Daw=4dzQ1Rt^&Ze~YqeazglBh$HP}^u!?WaAl zOG|~Rm2t4^M)rIiguWXFrJnd5(e;^2kAK^v$ZCZrFQW520pMC-4C<6UR)l)_MZLVIETs|U3`D5AXT|M-5S zFZ!-+l+-&f$|68bKV)<}PWIngfE91k9YYcQ<%lJ;bk2es(lH}BIZWaJwCCN=c`rP| z$)BghsPh7`$c$ywmd4gl=WNoTN~43Fx9x}X(t@9zz15)_J6>!lO4Uy%;`&`?O2>u= zzMdO>Q#AN0qQywBd^>M5GX$%W>I?gnM7SXl6RnVB!iT#??lHtg>yEIfNTbkb`dQ2KVJV_^ZPmPUE`;|5zp zf8#=V$9JTIgKv)*b+Q0d-`?AU-=;TU?Ejz#aDV+A8fs>t)mFFD=Sf!019%a5%J5py zSx`|?4V-!(?{7@xYsM?=AohM$rME}jCTE>xRw|eA_*m`i_$ArUOYx{TqquVp!;wQ1 z`>M1QJN93?j??WTrLu~(?#zX^pv~=AIj%T6tk`*E3gyIsg&uIHEk6Y#P_1fbFRf5~ z{dWSEU>o#j$wk%PWuZQq3p$;AZ40gskAsAUldGvLQi)!ha>>da z4HUN#iZ&lf*Ut79`Yp#}u~N>=uGd^93}$qV-|G@oIw-ABMMkNGqv_J|ml|-QU7ub) zR-KiRlRGLB9k5~Q^I2=O?xxuyZU`Ou_TA4jaNXhg9aLL<`k3(7QqIr;vu@S7QlKT#`@MEWAhu{Lsb3dI=W zD4W=Y8IO`kk}UYeHWp+{bTas6g1u1Y1K3h;Ez8`MaVYWj!h30$XyVZfhI}h#Q#7v= ztdm|C@Vo^wD0vgR~uVfRO3AaqkaKQ{7QhvD1F7BS$^SEfl#~vSo)1 z1`HfX=dDVy75tscb-YF;UmVn;_{z9fpR$3Xkn$$SZ!OH{qu9kN|HkZlVw6@=^rUdq z0~RL1@ZQ>>`+P#cDzSTo5z>r5MI*me-TsUC37RbcCSD`yV>Cna5}s_%GNkofQCELo zXARl=-qOG`fd~tF8C*SCT*p~&le&D$}*zrPRQJj}%I z>?FFE1YN%^Pu{6SfU-%kX5by2#<8l_*6P21-JA!Te-;a0GtZIpS=}BS%;@U!6ckhv zWf+^<68iL6Uz+*H>9t9>Fz=&S4K<&uS7Gl22A(hu7}Le#ui-DA0pXXTQ#iB)k+as; z*5S?SfWB#Hzk=eXVh;uWa{zz4z+S^hRCTD57=?1a8)HMV5owuy(BrZm+!F z`t4jHXtbosZ`?8ad8qFo%{%E~6l#OzWL{J0u+OKdebSu;gu$^Fg%`a(6#hBg>4nw5 zgL13#gd3pP7U?a*7?LTBvqTr&cly`-k802*{hXLB!bhqF(b+#ul}_a1_n^A6-Dy1R z%zje*#P5u0{GqU;f$PD>=j86FKo5hZ7cY{HMsxb*SV!Cob-bEncMOXHJO1oF|w|CqQPQT^dW-qSE&%YS7yo!9o4MO`^{clx7qm&Nzv%2Sd zp6S*8*;=nod_MCgJ8k@W#i7xtbS%oPNjQhLF8>aMbTvHr9s6}2xKQ7q{BmT5z@+RA zxY|)cdNCy1+II)II3xHe4fT0wWX&E>OK#ZbqZSS(oWo63#uG9PFYW0K^Wo*;DYX7c z-_c-C^?Gk@7y41{z9eJHK)4V!DOEU?qz)b)HrWPsO!ySlPi^Ep@l@Aq%I>%6yi?jn zv~7kAYQ&o;En`8nFY?#rXhRzzbLcTgR(MW$W=eBw>(UbvT2SrtVfdyF3L8eG8kB6N z>hrnu>UGQBa<^jl+JO9Yk<>{AX0!l@;9afosPqc4VM zJzTc}rVD{M416PIZ=nbRY4@vM`1kbmamCPum&Av}&xuoD8ufOGX_1i&`Yi@338X4X zZ6U}_pkT6Z`p#+7swE(%sCcTQ(h3uZV3u5wVb0^zgE?E@Nqmd`=J}1|dJC^am<%Y@ z)OxE+*HC!KsX-+~IPygU<)w||=xL#%?{*>+YPuV+n{QQ}Z&l#?d3bmvBqUnKpRp>j zAP{fC!VJ5DMaIKEsu_mAI*-)ck5}0Jl`3d;-dUGf)viLK2s~+Zd>#x4L1>rP@jtt6 z6jA|Wb3h#8$|yYi*P_S_t&WN1W^fKTUj0+w`a3)5^uU?r;X~1>EAh3(*rktzW3NU} zl|FKCnB89Z9{b@7KKa<2JGx-cfUKd~gbgSow9u)}q_L>x?a%1OPK}A5(JhDS7{v#F z3B|LnPfc4jX+|#F{@HJA|MtfGcy+zHn)S-Z(b=P#(aH_hcba>M{o^N!yCls^Tbepd zM;t56T;w~-6=uQH*T^uMviCx=aG5=9LZ@yRoXes><7(8eg5*!`LhEpEXL22cFObbR zK<&@m?Zsn2^7z%((Lj47%Vj%~#ROG*oi>w~J@SZLkZLAJFQ$rRFkqV!scQ$2B=V_9 zd9}<2&lSHd?6ME#{xIOg#Sr_jk|^Qwn`XWfrf@{Y?Do97G?6BbB1dNS45reOLte)| zxjRhkDrQ~{t&_T~^`U6+k#*E>gq679^35A-9`7rK6HP_**^Ec2Y_Li1#3&O7C;g!A z&ZE{XlvA%VQ#LU(#TV8fPzW)`{McU2{e?v2Z+qj`PwNwUMxhX_EI7IM-Z7{eLr0v$ z4b5?i4lN1(hEawdK{7XlhapH*RN;(OQR;Hd{yhEQy|rQv>yjJfAm$l?BPXgoan_5j zpy*tFgw!F}R>p90a)yP4K_s-9xfevqQF=m}%a{(HhOsf4pvCd7OS#H<`}?%_@Mh5M z=hC8|b7UVbzHQFhsD;&igev*-N4Suy`DH>g*F>#_K!o?B=hv*Ln9!`WfMWxqeMbbJ?gSQJ7vRBkP1=m zSMa0b$&maQhT!#TqjjA-HrHWW#DxnoyP#isx-owIvcl>28!3U)#nK8P`#aEEbLsS4 ziB!jwo|b-Q365)7)UdPRG`{6`c2aslZD-+?Q%;I}RQpDVfo+?#K)UqN;8rV#KI(H3 zb)X%-8OD+9F{khS&nbS#TLu!3vS3>r&7An$n7^!Vob&6@#@2py-_>YIZhOjqu~N(H zVKegQ!fH<>6yH?E#g=6n<+6E(>-zFnOMkFk>wKd5O#Dr{u?HePw>VrMYLnr5q^^#b z$>xJLUlT8CVa`I{4gFVS-Mwj=Ig4i01nMs(>5(6!DQm^;QsSR^e`JV4UK9BP5+v zmwm_GyTHYQ`xl(0z!qd>WdWZ7X-iv(ETb?ewE=6vjyBNOR}s?L-CmC^a`B%)EP_eAMr!rkD~F zKmD@EQzFtzjfb}p9Zh`Ug4}~C6lge=m0J=yHFsA=YKO)l^=$*J(5}O8{yqr8#r^Z< zPS5!Zu75tjYUIrc*gUrgZGDj%T1cDKcXweMXpVa@wlq~IAn%hD_{Z27meR!q3(lqB zh%ddpE@KS`i<lFSy5vaQd@k-Lp<6BqAqdWtI zq;hUpUIfVXMnCJ8mG>$nAVN|G)2ukO8`u79B_Oqs!RWT}gud55?&VQj6=e{@NO1i^ zmYfA&*XGu7f*|tbU_=7qDvyd%hDF?{FP6jxbpjI^=R5%)3{l4+Rws0B`+GM#3Gwb? z;yf8KKMW>D%9Mq1sj3iLXusb=QtRNWWh5Yu5e**M42WNe{HYkVlBF%{6s=1-%BgsH zxuq!81s4mFX=3MZrReDRdbTkg!k5!js@yxsk~^XV@#sJbQy!#7i4)&dal4<7B4p{^ zm=t9w8N#AKe-h9HxPLzj7E&?J%-jstCV~Xc$qwXV6lBH(G$hKgvaB^CnLO3XlYqRd}5PYQc7jMp}{809}7sIM1I0SBaTr&i&Man$?=^`cdj_E)JSB76XYJ`wApfX0& za``9R(F{WtnbqLxs(SC7op3f!0p!dVq@X)iL?FAC7t{#!O0u#aT6Qj8c}jj;GP6Qv zqv>che`CHYtsGk$oCCK8T&iiAf}nd=BTOKO&D z3{*FmSW+SNv#|QI{3sROr}%is-8}UqX~B8;TyK~_4OA|V zA3uKZK=j2=AY1cjxpDo!`KnTqoY%4vsC=#!u1EeRfo-|OKlQ>ji7WfKf5zVotoy;) z!}3?NRS(?2T%~YpYkk=BZ-k1sh=`Kr=mDrbLos5LYDMXuH@XtRqKdbf9hN4v0g;b8Rp{!-siegkg?WArpM3eHzr zT)5xGY&UE_T%d_Qz5jG;q_2YOxt})i&xa^=ShWgXx68ih>*?YBfF1JnO8?7|O}vEp zE1Ko8*h^a6I{bZ5mfwkA0sn={6HoS7Kmyo}EkB70P@jBbHQnU^Mu`_^2@!pIFz)FS z^e2bl^m}vZ>A?o!jmh>GBd(96AAa*WnO4er=eE(ML{VHMWcB{2Wc+hlLz}*B{Yp&~ z%_kvFqq?_2)0vvx&BZkb16E`=DgJDg)u(pdxC>}pzuVu{)0b<$i>b}xug|_*_*6DN zGkUPnnJts>-knSK)q9XtQTCqfPgh6kp9;#Jx?W%%i`(aksumSl`Eo^1@oaJce3?rD ze1g+iLb%kl5NQ>3TegqW^Ab0aaYTZS6vzGR`2!QOeiOO*M#x<8LV1686D^fIVtg!o zT5irqlzN>q#-lW^X}+m`3rWhLKu7j2VsbM+%Ce)b(37Hr-Ks2#pYr7yErx4VGI zbtWvnF=byZil_oa0#y|IDUqQ!zq*bgHWM)?PKwxF&ay~yX&xF=j5S|jt(qrE74LWI zm=@$pM0ZgEMaN5DogHQ3S0*tESuf}cz9&t~FVbQ~awsCWMT}mF#vofYb@Kkz~9^ z2?)(>c}`EsfSi%>SPyUjvhb53mJp_fV05%oElQ{G%JT(yW ztbdzmX+Z^^0GT@Xr`+7sbgZ-2ms5PYcVYq}bJo}0AvLbHdh6+D@r>l}uGLpd&Hg^9 z!Y8CaF#THd_lR9QJ@OrI4%$;|+U zd9KAGOf7f1Z?r+rTF}{1M|lnZG@uVpD{ucue~vL2mJ9B(GB# z#jO)|(JAO{u@U4X+&n2RE{@Q%{|B~vdJfz1H+wC=1nAn}AL#l&bPJh}8;LQ`?8UU7 zscA1|xe28XJldu3(I=zkx`RWC0qi&TY6H!@zN+{~3MHO8~tpAc~uClRm`F*nU_rZ%jx19lJb;7kj6V)EFExH28 zin5YEA02W9uc$Shw{sUPV4EB|45-*Lo!!w?koJq2=g{9?< z=V^DJ1^%20eqLhbv0XmSJh0>woA_P?aTWeY{l#4iWwo%QCtc12ZCM zu-Grco#65Qg+xKPzNkr_5msdAqojUnQzjj{U5$LI_q$&oQhyKkpb^?C-Y53Z8Ojq4 zSEBwqar*+7^=)}73o|}^3hwL3m*Pt?s-;@;h;X!1Nyn|5p-RbJct*O{cJP?6FWqc@ zmQQUJo;2uMOJh}VeZ8LWBf#KXCfb~$Y3Ks2)X%0&PsLWN5R!!(ABCzW8p8L2xbAfL z&6C#giDeZ{<+YU1lg@D)*|dGGJOth|V_@KmX8d+U)WaBcGHq>rS07D{Pr4fql*ow{ zndxNdFIx3Y7v6mb7JV=+503|5yBU{)M%z~pvnlZ0tQc@Ybs5hLW$L};Y8?AAR}|ZE zSM}yA<%BPPuVs;zD^xb$8y`!`GE7c#1rSMqR3h)^&ywH2ySlq;wzo+jkh|nH3Hd9(-3$!#$o;)P&Znz?&b`v$L)aHS z+Y|=ZJhCAF{5mP6w&@s;zMMEe{z-ZZUjjSupv(Rw_e=XOAM)E((|Ulv&+vlU`E^!|m`pyT28_ond56_L=k zRw>20D;#B8`VM`kZHe=rS@mR(MTR~Hx{aHPZkdnMsS)3-Pq%V+Jt~T#*c9WLHD|Dp zvH)C1YRUX7Sz`qte#IO>pWl=+EFaf9;N`*;j}VFI@Egzc;A-V9bLy41%67$PXD9j4 zFfHcMf(jHXQMouc6D6WzE{Y}Gn#9ti*W3DwVb&o1*$UQ86?x-Q=)5-f@@P9mlG2i% z(Wa-DXx-tkd?lgt(l8+wB5sVd_;pEM5(h*pid-&H>@sDkqv_i8r41xfjaCx#LlWz@ zTB$tFP)-i!Yc-m;0O;_5FQjnF1+8NkesPS$9QPc1I;XfCB0`;jq) z`$xMq@{MxS`=TuI7a19Q=C+_&0RN#$i3B~VcfA6LjKsyOA-Mr2Y+Td*^5qL;F2HU9 zPbge3#cRuD`bO%5*HDJ4tL_RNLQ6S>i#bL(H?ISpR^j6 z-)(%<40#vLr-w^Y+of?f$NW_LCR~TLqJ7*-wEFJpLyEL_5|JnG9yj{?%I5^ z>pZ4=G{9;1q#icX^RS`Q;D_NTFyM^61jG3qiskuvBpoP*u1`#va}3}c*hdKp;s6ZS zZODH_4OJKWxsHdr_vl2}QK-RVb@cMZvBTjby;oYeUk|oVd>kJKOpeA5(M!T+QCe$0 z8?a6pP|ER9tO@blv-#H5JXf?uXWRDu%x^F2LdAk_feDP7TSltpnsnmVm#W7$tx#TpwwgIzm9diPCD2XOU%gp%ioDx)a zZXZRakPUjyCks-~VAkJ;bfTFuTFQ`N*_(eK;Ljv3bmDy_P9~qzX9=1>rr1=sUu>ESLkHXVg{52B0 zVNYsbc;g_TObg9PDV=3dI|5B z*cu>`0jUh^580ElMsR>MHN7h@2Pa+W`-2yHhttKKQU?t=muJL@4cx6dwLmf+&|6zk zkzZ9+TUG{668JQ)P){SS;|kj||KaAoU-%d4LxRFlCuUw@-#c~P(}VWv#|7QrUA^>) zW1#Rs+&jso)%vw2-wlpf6pUGh+z(1W`5PzIDq7oMR5E9M|H~W_W3UfN1pSI{q8mbK&hIQ|`fkfh zWTIUS4|am%3pT?2(FOS}Y2i95s_g41KErMHGt?`&Izg~H@roMdT6{~uQ32>xOhO9u z({USeP1V4Shvb-%Ct7HoW=5Qp7J0_X!7$%o-y^Amx_P;1|m=Z!r=#k z2oi$Rbai#1GJ$5`&Q}Twiu`R}u_^FRVv9noF|aPmT9XZU50LjFP5v5fW<{CO6y#gn z1ccl$Q71mM03h~a`xw0g@EfZH{S2_RWtAwXd z!d(GOKRkmAxkl=mU)-n1Q=bHtC*(lN{1th5MQLeK35kUrgSe-9&kpo*fRa5so>QvG z7w*nnE;d)ec$%TtDl>kH!6`le#_riw+ZkA>1o6&JP8OXv$7n8`z5E`)l_q4r{+qS> z1OK_VID*rd;o#5OV;?`qC#&judi+H4QCqVIlyQiL}up}71wf$vxUPr zxKXKj*)(kI@zL&#sjc!r^YJUIeKlJ}f2ZAxR~5|>cyBVlsKdIAJ<0#_>@4VP?aW4) zIzk8W7X?H_F7LJvFcWB+PaB>WF8z_q9ohFF|reqO;%R2lD%c`GLKyeMOImnSs}9$ zvNeoUw%_A^f4@I|-TQJIH|3n?^NjcNe!m~R>z?RZgVHy|M&IH=I0-WC2Y>o)C@her z$j~%IbXOXOUf5!6A`dCYy20FK8F9Fvn}I0H2=KPCT^H6&(_BQQ0E3;&tH8Nk7jFRf zc70ptD@fXTa|FXYT86BZ?t2GEG(hPAF$0A^;5cj9Lr_o<#F*}l zaF-SY8*^>7RY1Iw&G+|%)CF9t&t&u%8Nu^DAQGh`Z?X_Wy@Sp{PL7>X1w0%FqSe*Z zqQLV&T^(^K3dBMY5fQ)|6%-VNgb>W9?tw>FIoWQ6NH%Hl59(<4zk4T&!GxOBgO1l- z8;DeWHm8?8&dJR!FIuSHHR#ZHWRlx5dS1-Q!4aJ)_d-UHZ=qxn!vP~M2#M$BtV2Q+ ze`KB^BZDySymjx0T62dk71 zN0RxzHP$~&a2aP4S{gjNW_0cx@Fo?GKNe2a%#Fu)jHhBMD{p?dGo{lG79Q8Xr(B=S zR>NzDvbx^Z0?z-I2uE^b%ED0|^U0uR3UH?5sUq(r0Mt=Wz2gTseyEnD|myU?s9W<9h)Ln}+~ z_a^1f)*RmV8ojL3dwg%{^tV1bZe3OXGWS1B+hWn95)A zAC`h};jk#nzAYms$4N5RUefHItu2VtJZ`P5{r$@o7SbTzxz16MuT4PvwrY3kv#2u z$J-ueEd~GI1@wQ0VMSkgI{4~Tvso_3AlC%a`MNPz z)EcxF9aP2QGsCXL#f-xE4$L5BijfLLX>BnGFHkRmCK$h&w{{T9kt;V4tow18o zwY62R5@ zq6>?Tic-S@y3|ulf1EbJll!K$YK9nDA|PSN(OHkaPoB>%sEu zKjvyN1jv83ZfrsZz}xWim+46tL0#T}9u%Ke(ihUpYbwAWewRlu7*;k8N_8^L0@Sp$ zcAIc-YVy0uLEP_2i`&k`?+fH9i_UU#wpTJPbC1Bh zsdn`infS%iAS-Tn`tc1=ykHVj^gf@(hB)Wzlh6NF%oy+YOZ**0{MT5X4BAr{cmnI0 z-T8lbSd}qciTSQ_}_t7tn?i+#uN4Ms^;=dTwQ-95p5q(w# z)9X`=yZbHAl$}c&ytjCj?beKOy1g!Fud1Mtj zYMBk&jLb~%6aur*)WSk5Q`1;sDA7Ice(JWi=H}*sfh}+5foVMmkqAb{Jp{4#zz%@0 zBZ{@=N25{wOH1cR;NQ*s7*Y^mJYjjLtlTmKV3j|<%y6&J(eH{`4tD0W69XB_s&cH3c_A3veX@)tDa(=N(~L2zQA|iu+O=ee!LH6Zk2E7Y zEU>ejo;GYnViVODz@9Mp-GaPl@3|L3q_AuutH~xTMa~5On-LCi%fsFtFN;Ak~owo4n|I6R#FMR4}RNbD&q#oT>LYPrnpTM$wjRm&M?W9I8Dtz~m=>Uu(`7_avFRYI)Ukrk)fg1)pGNO z7V~1K_;|PYq{qv@_3w|*d&12F^3#FFLTqKrANaojje;+36Ox%(02#-_%gc>|8>jG- z0=jwR2m}I*wJ0cn*+2>3K_Jq8&KCOa#72L}#-Y7WPh0WFV;OC|(#L_=YzP$>l=85w z`1&;|a_1LZ;TnDuSCFAcZ!$1x+Gj{fNDNO-YJAUxc(ruT7g$w!Yg^ z{aW>qefK!;B?t#PzCGp|0bw+I(X(gnb@WB)fa}&3-}vOu6!$D@*8MM)8;Qwz$dNZ? z%j|AFvp$W*_*vw4zwh7G@P+sPo=xse02WF@&t|?rn84^_r!1Ho7z;)HM569U*oLQ} zcnzFUZJOX{>C6MO_m0jjW%HBbxXwo-0#)WH0tDx^9fjmyg0I{nj;3HR zvUZ9nlyQu4Kz~=7yQ%T%~rbLB}Aw0t!_J@7N(%dq{YSJ z#=Q0yTxJ9hK}%>nE_FkM1E>A{=TB&y@^f-zjLg@i_hLb`t_yJjrD(!p5C*=%!SCss zgLhkickQ5^xFeK0IT){^B$Pqg#iKg`I0W^8@k#lHcnXhb}|Xk~7W3tQxwqVY{`C>3{U z;3<#ny2sb%w`0LXeqEAnaM5_wAZO;oH2)tiqqf%8R&Xbp{p(bJ4R;v!I+J zEZ?ecX<SHR%k?x)RQ6t_HydM2UB*C^s4{=q&L1FZ#sDZd)=tt4{&InZ@j6v zoL`zSQShfL^9W=Qj>JTx@CJ(`fDd0K@x-dgKS;}ox-#w}U0Pz_gk?2sx(wF_7ORC( zh*ixn{(dF67Qk)ya4|15E%ZKEjf+6h>HI~J40|ku35tyCdZ19D)(WAUnq<>|Rz$`p zsF%7!g#76gwK`SCpv3LUN1wKXIIu^wPVLCR#KcDiYQ64dd3@ZzBOb0Nzuiq?#?Qw` zf0tAZWJHlBgi@*TG%QjCzEQHR+Ui;awlQDqWE zApn`QwY4pxh-yEi2%)54@=zHn#1cWd%ss4+dnpW}Qe^zE)*HA5kn z6!+hZm&IJd_&m91r1Q9G8wV{Y6B!F9r*ey&~OOlgS>#h2XL{2p8G+k$WD_M#ri)#n-CMXhkN z@ku%nu|%0MxW{}+)Zb^&8j6f0`NB2FRc%*iN`UFK>{OixuDxk!GK@Yfn9-k_HStbL zOb8^REv_U@n&Fyw)I0jDuD#-TQr$m-@<0D})z?!Z_P{<7;6R_7Gff}O*8TGS`O8%h zB{@1cEUm0W#7}(wc~?a_`lIGEEjXch!xRt>;Dobl=ea!KY41p)(!r?e30@js{Nw0B=OZ#KbOMyeJ~_13YkT zY-|Md3aAhWmAaA8(9jYx8kE~?`I0wxIoxa3Jbzx)t8P3lt|2!UCI*;MHYH)hqjA%K zg$F7&$hf-@6dXH?wWl(61qI!S--}q_XK9V&Mqmp6_46lRHD;$6P(>)-uy3kOj!~#@ zZGFVPXmfTJ{&LV57Gp*a!OYdw#ifWAV4O0NJ?il8XJ==_s0{@G zQa^MK(0#yP<>ABq*4ZQXrFK35&+R3rJ?BmS7EZdfw|jELr)JAu%sDjPnFOzpfp)*& zzCb4Ub0KN`ri}s4M|KgtT5SK(?#aC$OEX7VYWUM-sb28*DFPn3qlMlFlA|@n_gW(+ z4nP{;A5hyC0<1HB3e+%m2mUb8P9^|>LPJftL-Q=GE8#wAHv<-_#2{x3g#JV7b2uy^ zb#Vh$_SKhJ0z*O`NQooYqEwW-86qo{An|+Z~$o(e_fT5ZTji z(4oPB2RGEd#wHfF^o#Ldg7mcsG@gtj#zD!ynX6S6eyzpi3F#el0l8$XP;Ot1hO!}@ zl7A7{#L5zrPtzC>j88J6vo`Zz71S&fDi!M2e^ktt^#`MPIZW$;TQ!U@cn|( zI(gFs-we`PHGm$KRlr&}2gnsXp8(&1NSzf((VrTCX$!2%wW6RoPE$Z#!$Ri)#s(?U z$?O4@YLGJF&JGj{NSrU8KiB^;zT|!Mx3T?ZR!yy%C=t5F6xEkhLB3m6Icz_Cynemi z+;}njK3p|pelIz(+!w_=qOsB9dUs?#k#cSwd=(yJfr1t_b5m>**>#0B&Jxa`QY1iR zGD2jE9n`S2aV zsgCT*ZU zEjG3SE@O7J+_1?Wed}87srH1NBI`+8K3De0*fo_i;6WVdKp)ty^bXV#efC^!~-^A2Q3z2T2K7;9*w*7+=y2FW(QV6 zMO5ISq|L8wcw2QeS2i;z`t*!Ig!6liJgh)mNbX|pV0g@6Dn~VMFkb9s=Yb0|} zlarIv(D1YE7Zq_~GzHfR8gGG)G!7k8qT1o1gTsi6LJ4C#T_z}2=KWK)Nps(VE42Xi< zZc)%Tjn#El(zE<|Xmz}u{bct7>y6XAd$45r$x@>G3TLVd;ubJ%PJo}gG zJBH~0l9^1M2kj+yd!X^#3FF^FNuY>R1V7Xp^V}7X3RKF)48$o+0Y(6r9hDEAW;qdx zjzLRr>=!mmHZn`6H=t57QN0B2qP?TvGSSx_O*f=BEHbTBp67|m^I~W0(bjiC0 zeyBAlYc9nz=GH+8SO!YGF`>?3?SR+gp&G}a12e9`c^asy zNYlknx!)@ADkYY`6RZwx8-jlVDU`ReSL<1`61rtx*lI7rn99e0_EKA2nt(;vYxk?@ zz;E3Y_&RM$NuWNNe|dI`30BtMdy{6e6FXSrI^cx;_ITDNZZuJNMdhn08);dS|4p2X*(h zAf1pkn4FQE;cE=6)$K4VGo&CD=GI-+By=H^>QwCvf@?N7v2z4ZlnJ!Q2`b42FVh&v z%DtzhLgWjQWa`B5!O16Qf!fo}*!D*+jp3G2!juST4C#1$=%lp#d(}4em2?~n0CQC7 zB&^gbmM9aXOF=GmKWw5D30LU9zD6BB$`mwRJt7sa7D1zN-RPq}oXT?jp5XhrwC9UU zow1on6l^&X_@+;>LTydWFpi60p!?I8m_b$GyQhrx9X-x7iR!9l*S988+OsTcCf9tx z*N7)oi5fBg!dM7kFu4$h|AgciQC1Yn2i_5aVX$~W4?^I{q0uDbq-12!F@pRKAa3}^ z!oosNZzJpbG^JM?hwHn<64mXd(xh20?GUI)CX|yu7i4^|2~Jx$n)ot zdF?OpCJ@pJNR5-O-44zU{@dB4r36I?eSA#j$5&24GXM|8>njNx_%ac2lH;c!} zADPEP&rykLQ5hn|@`4MlZ~-jyATsN<)CeRfbC7--7$%Lf9bfyW#F8q#@y(mI_aLcjP+OvC- zfdz-&019GZX#y}7TDe{Jm56XW9={u;kUf}~knlfb5P-tW-X60h?;MkB@!09JXBV}M zVP=KN)yRn0k5@t~)WAs&XwK^D>ej8;6II6kKYjU}Q2n9+WAn!t11j=Fwwro|m@+>Wc&5g>{f z4=1HFy6n9(xA)%rxv#2Qwd_VwGUph3^`xwVMYZNZ@LDI6cdCgJI7v}be7c(itCqBo z>Zv$4k|}ZvJrdZdKsAL!Hm86$Tl6L7*WmgNdo6hKPX2|Q_{sbAzIWj5P`4JvTEpt( zN2Wf7G3+&1jm5GfcnEXSl3xM6gafwx1hmlAX@#ij%6rLLV?(ut*y1Zf(~Psz=Xf3D z?c@w}SEb?t!UR;tDEbAOKkz0#l$?!A;b|{;rb?hK!dQutp(Urq(()V7bs%@JzKZh5 zVA97WHp3EzL|4XYlnP07!m!R%$SE)I3hSfOxJ@W?b)KnmN2tzx_!joe`C?gO+@e4{ z!pTX3Wz0pICv?bfsAsyUsoRr7@dK2Y_O_wM zdIT$@(5oL~5S-d$$V?o1Sd!OD0k$O{R(gASC`iHq>6n|FqYJt6%L8Tvg`U+^-st-W zO8RQYj^q?^^Q{qoFysNmywb2cWpcO%<9xI&z5E0pbu?O#E@Lc3Fp1J zha%DG&zF@II}iHuKKBJbjt1qrVZV8bi8 zLMtcZazOL@B_H_U^aMks%H_YUNgr=hTto~ZUdDRo5oGk47G{5-(G+y?>ms8dp5u>H znz!_%?2c8w4Dd~ylybVV8t@)(N2(%cOTC|kj`_FKUD{NDqqnaK(Y>DqicTKpSGH_Ogq+`>)ki0>&s;IiHeK zS}&)T&`4*eGQLp94AZm%bypU;JwRbhNzU%1B!CY#*OfK^TOb;%swgT?QMx58tVBAM zQYC43C^+JUA;Xj%n*eAG+ZR*QobMjf$62tz%+G(vGcx`yXRvjnEQ#7Y6IXHV(fU&IjCcesuz_S#PG%Xd5VkE2zf;9)TgK!! zZJq`sU&!3lYjEbH&tVROizMP;+RmR|{cL{phR5s7ygZOcScV+^2@tRcD8`z%Hkj8F z1a-eZD8f#JClx1_oj%1tKuJz9-AhnZ$q+y0j~I1OoBMax6194O;;$n#x2N`n?uVo zW-n{j#%jL}FFLqB zWdQVCIf@AoHh2h@7H4*LZvfLPZR_(nziKd?FML%Cen#IoO1Q4r7{An!(X zGft%z2^8Qh2$p(?AB2}EpGBnm<$ZK%fB@C$Ht@P=U-Hr7DTM`PEY(YGEj^V&*bBZY zEn*R2KXU+SuF ztt556)}#G(zvWk-&6VsY*@M)GC`imO+0s&r%J~=BPU>zQ9|OJ5s_c(<(F(t(fhJLO>qHw^tASWEgnG5eKHq#dn9za^K8;YlU>^5d3NC=4m=? z3M2v3MC+#dFBDtXZ)|+jQ-m1{T0iJFt}AjJ2%Qcl-_H{P*as?Cs0mmegI${xC9Y8B zM6I$ktuoK7m@ZumN`+1+dr( z#!D6v1Q~Cn6@+_-FWJxwJ&X%13ax-eOO1WgNifg+)Fq!b5<^kQJ)= zUVi_;kRZ}aQ!oBG0ZvpSOgB7}pvYe@%z>VhouH5o6T2oFJ&}X_4L9c*O$jcLs`oyu z)F#N${bc_%g^Ny#V`}4m;N(~_F-)ojl(Hkv5~!6G=9QIf6eM%l&JJ&wG`HHfWe2XQduLSDRaBB@3O0O}FSGAaPz2CuJew)7d*NUvlIwUU zxtXRkA7Srj-kE#>+|P7KQ6R|6iiRHt*kBIyu#+|rma}3 z$b-R%h*0ss746NGloYrYp+BP3t}n&KH3tbWhUOdsuxJX3I2!6qH8nFVPer?b_{TLJ zxTax(QqYD<46PyVx`&%vr1=Y2uT@l#Y3|J2p;p-5A^(T=`~XC&(a4t#4fDvpqut1A0+u*cwSo-+d=|Quz9JsO$PC&fVK(NhX}` z_I(9BL=?glXVGXnb#mTFi7phKn!Sgi!C1?84w?1UeOK25H`nTF6W5-XE}#FoOg<^O zU;X0KMBDnkPs=CGd!6%XB;+X)J9&BvJ73c81h4o7|C>m#3L(~8Z6%dJ{ydpA-AtMy znj*?Kn*-_v;GB7vJicmh-nU0@S6K~#%7)UuXck{2dqt9?m#KqEBA@g@1eU&x=pn@~ zd}vu3tS8gbxa>IseiIUtev4ZdCp-)yNqhS zjc<|1+~fcDcJ&#RMO8oNEz9U4T7(6y-W!ue5&Elq%=f- zEr#mlCOIKKD%jDHU(OMbx=<_to8P2F6%;Is^-Igkg)#@=?#*QoYsvhGuB^NjK{P2D zUO-J{`i9(`0o61x>ruvezpQ=sg2LB9=eC6Mdl#?%dulBSFn6h;GpvVveCn}0VMt9t zp!Kh5Ryu=;nBm8womWa+P~530DFLX2X$c%JKTd!$0d!md1-&q(Zc`9mt*8EB?Y{=a z8kRm#svjFa1`EEP1m=?U-}<+lXIk!pa|7Yi=9?dVe|@3&n%^o--JGDpSPu40CEhv` zoZpsUy+#`JqPaOh<3>a-SOL1ZyMKLon{C)I=cV(<@=W3D?w{%@{8xblYtVNHPQ??? zZnnBjOX7lCg7&s=Nl~+_0lDUt=X@6s*rQlKSYVWrQ!6#s7L_PY0w0-WMaLIhzVp^+ zLlh39raH}@?d{N7C5n?(_+f_a+$QUK^J{7OP~pPo=`XJeH=>f0Y4v+x9y^{6guQ00 z-Cr*aQFKe-pLGR9_aJp0fjXZ5eu>RIZ6WF3g^4&)v7fUih4)YX^`9JB3Cyy|z6$ug zZ1%zt9{JaM%a8WG91Au4HojKtV_@+7`(s-5+ILWbfw!B2&nn&BVa$y`m(uC;#IHLtb@;E6fd>g9aYwF^Ir zA1P##Sq7IF1+WlMXv01T#c~t#?%wUvBhQOT31}`?mNg(x1qY?8nwo?s`kMkk?usz= z=Zb?TCA?~0xX3$Y3>nL&B+unQUPq`%N=~jA7DMEx`igdweY+JaJ)7!^)>l~^jQgS; z)*l|ji_bOALa;g5+lPvyF;rB{+~%UAWF!m$k9bBAonxW=^!`!(IK5$Zp8ZZ&M#d{D z#jBpCTrXo;!vD}EkzDA~t3`Hb$cWqK!};kHIs#p?3t?PF#iH?@F)x(-uRMHksM=}8 zA{Ew3g;08Iwn-7?Q{ShEs)MCaL0%q}9*vwXuqy$bQkwcGO})r<2En}!SP2t6F^h}# zAU;a(2fY*O;TaMz={XP26Ms6~e$^~91jtDOIJ_FJtk~`ZX;F)hU0q#~D%}1N@mL-Z z_~M-bM1p6cv$IozQ=i%Y8mpr>T6xCvbi48tJ+=CZ$5Ulp< zYl$ZRQ@LTfPUcw#lttFLRK&(qP-5j40!^v~Qno>uOFgz)I$Ll{@T9^}AeaP1lxtEd)eMDO82+v!m?pX!85}u(1gM|j>^KduRb)Cpjh9@hZpoJurmJ- z8FPwdRdr2*s|N5O+`Zd?6B+!CU~Igo<=@J*h8GGZJLvxPhF)*e}R;VLXo?M4;#x%6%XS1 zhDb^OuC`Eq0}dUfthp|VR;9Vi`nro-h+YzELP4HS38SQ;jr>Z6Ton>l>8oi^`;(Zu z)aODeGMJpzq-n0%;NDTZjd806J`bHBZG<&p2Gd1hVM<>Oj)uNzrmoNPNyN@kGo6oE zo)3gSt`(GHOvyv-)6o>d;n@I2AkT5@aCi!I`0ex&hQuIsLS-&UN-D8hgcA$e-wiDc z{X;lAxU>zNq{zrf)2pyb3LS(I62l;#sa4DX%XJQpqz+7c(#r3>IZi}yQIJC6;8GXY z;o_D**z#RY+};bSGi7IBAf~_oFbecxfYgdVAr~2MzVhFKB%Lj8)#kl4(BL|GnzvJy zmft;Uy#4u%rb?%Q&*Zb4`WC_ee$C8@#gE3RI30pb8n^5*c(FxT;OXdTdol<@!9~ph zkkVlfC*CQe*z?2v)CmvxfaKFtcy&D)NM>YX3Q)ci|s6Yf!Y#1JjLVyBmfLWBfY!F0Q^odgNDx@(HFdi4-@gkp zB_!VPTmyryy}dm|6#jyQy)61+K>-I7lOt+D;`M9VCYj@T`xji&*UAi`NdwG;ki@mlDUy<&PV7&gr`Ji%^phyS{CdKh z>}Z5ZRE#J?v;yy(I774;GsX4DI1~6cIxY*bJE+#>&^63xgJ0?zHjhJJl0SEN3FcNg z7Nwi>x8VJOCy>j)lZ*5dO;RBwXhalIv(Otm3aeAd(}`6guqaP5R|FJ}ke8J|LOM+u zhD`u@N^(L1u>`^r4+`_H6MU&@#S`2RpYivf0(lLBCRm2FRu!)FO8#~c@wlgb$5k^KI0Zfn&IX;BM3{I_c@xO^< zMGkCSsTr>h_TetkGxp%>{VeP@pRQBIE#K26Ht{!MQuMEvj^aT##2emgEUvoh6g;<4ibK6UU=U&O* z3$6<}2?p{*dOr)5`mOyOnmAAdvJ7q@Q&#nojM$`bz=Z~n{4bM}P7hSRlAY|CuzO z@M<`{{+yhCAGFv?cuqAc`W02O`m@l0aw(2vq4Wle$n*P^ZY-(2)*7&Ss45S9~rsYks6w@a|Mst`awi&~*OABYn|q^^ND z4v2Wxn4%A`{sJhj${2w|b?V1vpSnywc#z>_4$2U_{2JzhKI*{?g5>_|w~z_-?es<0sN#5-N6ZR7 zp2_S|zrIYbj0X|v+W{U#qji58AI|zzS&%8580=cBbd%B=?XuIz!nEsogMioI=3DNa zzrpt&e(rZx?)|0q|F{6pj$3B`1Vr{O2%_SFj|DdRf7m0_gr8Zpx4{D$r9yx9?6h># zStKrF{^#r7@wM6)_p1!ypJ);!xE1AHxJ9Fmm)~#ahP&OSxD54@e*5PjM|po(a<4RJ z!d^C?16JBBP8oS;&)L&5p&#btkZ%ntm2<@^K=kKrz@1Ba2~sk7PkPcw1Z8J0-6&Qi zR?1qu;|_$jIsGgYb@D5QM)o}32!HxY&N(@PsJU|#N(`Y~G6vy_yxqlb*p-4iTx@7; zLp(JTvtvBHG21lSbeco`{b4`3W*tmSnAj2X?{hEQ>LO3ESVSjST)p+~VN?pHLE(zN zfv1n!pOVnKhEYlgBBi{!F!IU_l2(KoF>hsmf3eNuyZH?cuM@Aq$LjG6*(ZVxCPpsR zqBgZ(KcyW`nWl1rVdl80`IxD>v6;@}JURONLi|@Nb0wQ;&^iq!)1RcKK2=H;R{Sh~ z-`IG&zVWtCt*cM%ja8@i;eMOqbk+11cIhul1}4fK2kZ^Y)nnif_%o4p_qI@jOQk{D z*su%YGQ;u>b7Q?+3&ru4{(hUPn9s5gJ=AbG@bDU=C$?QKsFaLb!5 zPG48Ia4eCsX7Pi2ko8%R&`HD(ZiY3r!EQn10)5xnN8L&i7 z1wi7T_w2ZUk{yn5(FWGK%u@@om~C5#2#^O?|F<0pP5G?`x!pZtLjf?otT+O zmW7xe_*bmt`vq#LDZ-g<7*_>R2vz(bY`1l?wZ}{?@o3~-Uzu-C*R!%55oq8gp+Pam z!}H+o0SI^CGe@0=I-0BFD9*GlRy^WlSOwVX02Ungm=uR_J1~b_l69Vxu1**K9OLoz z6$Nu;L|dz~XRFsj^n}Gad0Gfm$HI_fGgp49^&}&{Rk5(tLh0%k9wWXu!kf7*yvEKg z<_7I*va2+P8atnUufSVzvb#_N?C`;*!N!B_W}h|R-VfE<*;IQ@)jZ+{__s@g?G|l^ z-~Y{?{Cz{~7ks$&H&b|ZD?;~{V$ID~--Wk{u9MH4uQrv}+-wg%I!$BGESi0PeuDSJ zW?($&s_V^O@%|^mvee5(QIj=R8h%Wc>y6SsnXeu+R3A-D{PJ;Y_nZFprI~ovi23OF zU<1Z7!hkU^son22?Z*J`-oBE4f4wZr)`|6j>k;l8)07mENe1?| z+%x8o;TGDuYU^XZ60yX&5HiOu9KWB|m9UGRxUT*R?k8txl_8?O^)OpW<;A!CnYf{U z9QkIR1+Qahm=>4f1k{DP0bx@Ad*WVq0>=B>rlc(KFs$mUPSGWtl_BFbAf{H!f9v>y zI>^21$Tu#6mE$|WNbF(J*_Iyp!GgFc=nZm#{kQC5FGE$2Q-E}xd3nQ zN1J&sKVxyy|}Shlbih`zI-`R*1e?-hc?8Zpa+FV(&(1;4uCiS6T|U%`PXLUs(4WBA>+C+jy8e!+Sh-0 zPJZ>y=f6@hawqQjv>N~sK(0pJRwieR13CNyEOnizI-Vs?q1(eSND96V!UZUlBf+Y8 zw(mHOeL#E9o`|`iZPA}ZyI2+(>QgE|Pr(8vmpa2U#nm14$KA1Vz8N{Z zPb0_masYY-X4}-!J|PX%nx?YhRQ1!%$)4oCUg2@`+?`kD|2_)>PYh+TfB5^u-Ky0( zyI#o)7hu2^ALV~Y69+!Z%@*z`2GW3g8$R`|=kJc1rw7ErU*O}FKe6}Xw)YO9t1MuB zm$FC6B(l2jgoNz^waXyChAq-W_ZEo-h^c{Tro&UOHcA3In4 zVcxT7ZWR8amBv0F3gi({JPHa0J+^Dl)_v`9Tq6V?8+-4QR;mT$6H=WT{p#EK<-XxS z+XSz-5lbtejL9LJw6f^HljSy@Xb+{1yokoWlB23)+q*mw%e_|H!JK;W*|edg$3dQs zn(Ps}$)@+c34Awtvi{Zl>bKuLb0*{U?;GMK3w#kX@L>NX2EBmx_VA=t$V{moF|;0C zXCpkHGa*Si0>v-g($t^h8k<-Zf+_Y&I+)+1ct^hGK1+TA&Hfr2HD$=INN6gCh_g*W z0ipMS_dSh}Un7BshtyZab7vyxnVBo}F)(BM!9;Q@Ap;Z&zF0}gG~EpcOCu%x+j!54 zPs;yon@dO@kOkhWscU>~bJ_i-a#);qoUORQ`s)j&C$YQ+AZuUprao`1w*t-`f4BG~ zS5sC`f-T;#sXgFeYW^o1P_M|DSGB{#!TUCg^T&eb);3{nM+BKbf<0IuO1n`+2)jl_cp%hjO*J6jsh{1eLq`iY#P(StOU%C4YY=L1MW>W$(($49F_gS z_o;g3z_qL70rq}SP}4(4gq`9c&bYemV5XO|&F|Zr8V^PLje%mXy!Nr{zWkr}dTzH) z2;V;l#~w5_aPKSZ9$B|#N4RZeJ8fI})#P2?`ZdC^QZu7r*YtbS6w-M*&q%{jkE+*P z&@5qZsCE(0NJ*NL65hb~CGj)U6O2SCZtTMcT6R%p5z}GC80l|fP&r0&EE z=sZYFl-6ofYf0A2eKPpZNWc#LDYxMur@pj}8Az&dRPV9^91sXgb&VI^t|r zi~LFd zo+UD!9+^mq2pqG(QiQW8p&u3&(&CJ(jA^>aN?bGHz5S$6e!#>#5;J$5D=6}~9-i*l zOKSH5gYD%5s$Yw~o-J8Ur5U!7%vJa5U`OJ{CVK_myg6cfWP*mx7hk4U;_Acz*sY%~ zAU;ZZTZsWCdzLflM@7g6iQ)`LM!k8Us5^F?N4#gbM{ZopgiMqC&W1S> z3q2!1b_aL9w{1khLge<;6$+L(Uw`6xO1H3Ir`d#yv8C}JKUr(dZT{@$mK>tzRIx+c zVc4~=U(23}t=#6X86o*UG<^k7l<(KJl!7SW(n@!?G$OFT(%p@8cS#6>uz+;8OACmE zbO?xatfVwbw{-K}{QmDZJHs%;3=8|*an5zF7|uk6ANq*?6~1w8oC8%PKxM(^0tdYZ zBdCw`OEPf+>7G+iC`;cz2)^vecp0w-K%c}Oo!and0$H(Ou7r)9&w=^)vH1ocLn0{w z!HU9B816^q{43;gmnn~+Ar5CK<7lm_5|DGTa&YYJ#jZHDQSQK!2I;p%{`@o3P~||H z;L@dMKFe_(S!_D%c6WczCR2CoCEyS$b-c6A>G>{v3vAMu%Ar4v(bDax8R>7K!waX4 zDCso&Cc=Uyq!!}O+395re0~hgp8CoLo-L*FX3GEA!=F8-!gLq;nYCJ6OEYw*z8Dyk zOfy>TnUUToE4j%^yl1RSc#3}F5gzFvoAEKJvdL#X*MQf5$ZWr7@aJVu`T0i5<;Wvq zV-_q4S^j!c%@!ZEZJfmmI}@!e+zcr^+TBg&fyE83A-orM)eSLJgEKMCGEXS?t_Ddf z=4UwX)J=qH*(TqrZ(sMwDw-9Si+iqG#E0h?A{JY|y&nEb@|)qhD*nypucr1~XUkzD zXUDvb3A>YzDs^j7J43Txq^C(}O(%C(PR!0vkbc6v)o(0$*Utl9rYm?nF?%JNlc8`t z@|M`xF5)ETS6~z+r5HWkx6SPR+1R`F_nbMWl-&Le`w3%P+p@$zd}1#^O zbZ6p0ge!dH%8rBrGm~hlDoSY^YGmNth1%j{P+0hPEVojif@AzKUBvq8N!7`U(WwUQ zBR;#F$imA70dh!kpT&LQ6MV!+nM>wf@9s#r{xJp$a$x?a(YbU|p+linvv@2#6636 zC12=Ptq1~6OD~w>{r#y$VVVnQz;m<>doB_-bs=0I4Hm4&2 zf0rXzyg2jdFWxWy$fh;+?G$Y~`>#td<-JUTCtmfIW=ohMq3`F$e-$MUtd9^j$C7Vm z&m`^729r>f)zU}AmkVL9a%hAk$Y-V`@Xr5?Yma&~6u8=rTHmL9-Fdk>Kr~_Xl^rw0 z$1U3QD$Hv>$X@R|?WdJq+fVL96}AgaX1>V@1wXq!2wChq6eB)NAE=yob8@C-Q&%&3 zSN$m-%rFwPrY1zK+m}Dxt7F6BV~jAPCF?vQPAD?gWI5rfU!(8YNYc4K2*{v8@zdj?6Z|nIFAe?G%3g)a0c8eisOXU63($ zCrYpm2@pIO1X$VKw+d22=weLd&Z(-Kb+Oa>6F8Ox5s}N*N3zp*Owo~bxV?L=3-?T7 zz}=MXudl5=)+aEY)&R?YX0g3;>E=TN_{A7S_#m3baiGdzxA-BB$9N0H&+%F6F=`~3 z)&Tl3f9AZw#LN`Z-ydNlsSwU-!(;<)R~cELad}M#0T6hd^Y8VAu1F{lTLcR|x$eVNS^gq z8URGnfq{XMk&&Sx`YPH#@WDK)p>X_8IS`x9#+EfZ89AeG;Xy~6CJ{LOM6SF5L^Ls^ zatjR#>KOuXvrt*Xib;r?>|th>%8kp#+@FL$!r9vD`VjVyR&Hr#&&-}7pDE(t2lNjN zXbD$8A zIn%m##Bc2D8#_K1%~c=0c%{^we0zN}IJUD)Ct6_}Uc75kf5IUU9!rI(q845)i5n=c zx2e)pK1qfe^t1WV;m(5ubv`w4DmymN%Tdo3mF}C&L-=E$xwe@zjRjUSz45f);!0R0 z@bYC;;@R&Y-J2#(IE=BPegzdhS$`cZc00s=p(IktuuK|bRCMI0P{}-2SjZpMJy{Kq zJGBbEC^)}yw7;|e`m}O4K8C6ZH>*9!Qz3foosft@GIigY7?)=_TFBd?-+w8(uV$=o z3)=!pdL7Xv8V;xO3komm_{Wz_v%qztKIC(^*5UuLd!&I!AV6!Rou1AvGB+34Z+Ldh%@>GeY_sz80%UejSTYqv_ zAH@DHzQi@2>0q>e!LKaHnYQr-sN9&5B%w#Se7wA(7O%#Ct{FQif12{>!ab~CUdioy z|Me*wq|gtJBl*|kQ$l^cKyo-}-oh%PZwWy+c9+p5f@6DshWqd2YU2mhk_k*rboUkl zuja)|8Y(b7fUYLf@C`9t5Vf}6v^Z}2{FrF0;ZH+_gLr1(iO>~avVi9h(I;~j((~6A zV>qA6p3j=e%f>@r)di0>tz)f>vuPAVIhku^y)s;uzfs&6t6NR`h=9y^ zEY7~8@hq&MQs@0>M)EYNX6V6g(GM|=d#s9)$>l;X;h>8zUQ@$4qH!lbyb9K1Y!;JXMi3La4sJoA1D+GgGH!)&rP*| zn0fxmWm2XUMu3#r;7V8g(njnaC$Y#29o_VJnAx$yCFHMc zRre6yk6&UD*Jt+gM>o}4gfM_`!rZaLmL)6t6mc~07?@Z&rFhkfK?#ga2STUcSs`%T z`o<*@RajNYTFExgw@9ABhglgkdhEUpw?Na$tnB<)WDphm8cgIoN@P*H_s2Ar(IECqR*6k zt2<$Rx?D)#j%EI|_R}(q0H>t+1@BfUsCKodW1pr^0N+eWPilf9Pzg{@Oo-an^#u*@LAH$%J zQo;eUkk1u^LL9|s82{#RMfPj zpXOB|zdOJff}ew*nmU+sY3$l&L+UKwy&((Oq>^M45m6K+k38e>rEUSbM&BKC6jz~_ zm!8S;S|%pq04uMp<>QZ??DMd3r}gNGSKWz=Efz4i~Ch1MCn! zBY;{r^4IqpE&7`o(~|E7zwg ziG!|{4E+Wgw&6a}BvJjWD8u;=d%IX`0zN&2-|k1rI6rkf#_#Fw6ZSWMb8(t4@(wni zx|fT~;h;!|ZwNu>c0iypn$_9e+{SXK8VXF8xd7 ze9n)OtrFdF36ZweF|lI=zIn3-FCx5)(ug3tQC+sy221~jL2qtj%}Fa7!=5(HW6 znjD4dI)9g9+hP10_sEvXN3w{{wR?ZnTU~>cpu~SCvgOk^HKk%vCkHcPTl;rZ@r<+{ z*J#&`hA3n1gt-mfPnD&^K4W}BeOUAD^OF@{hYBwIC1MU76&NgTv)0Ac2lPRpIOGwo z2G-_s@jpztQAtqd@SH&92pAkdlS^G_xo&|SiW*9;mgm96DM-uvz7x{t1SZb_Y}EJD zH&-{e(PhebLM|PNC@PX+lzU_3WXzE`G=3A2{{!rNSvm=XC?61ddjr&?gxy00_ zTT~b35RKq`j9bx3)J}-3N+V;4QlL@ed+G^#yF=_lq3bppD~<@cnt&y+s5`v&^2-B_=@|{+;38Ug%pBC8wBOq6$ zJlb^uiIFRdIwBLUbPz-o^eJD1egN^47^tULX0tTnPRwY>N+y~@WW zeB&qdPD8^chA0))2w=BYs0w}e(A4B}!js{OGW+sUCp#OT=keKk7&YfKuM)eWQ)H&b zCz;dkm97 z!sC*NX7iVrO;(@sXoA%~dN}0+ue%u8>USdFB!WL*q5mv|ErZC`_vH#efgO)2<^Nj; zU)~1G0LcVPjf>rPJ7LKog??j}0xO(1phBh|}9m`pKaMGwpfg->- z{K4$0^>|B)80ixkef1S5z zMT4|5(fMy=6s4)4aAHV}zm4|%Hm(AkECMA0l^)z6#>OXji(Fs&lAuI|N`FXBPIXKd zI$EU@B5c#t(UFy>!6?sT`XG+Vq==IU7MayhR^oJ)bz@~+0Tz2{SsCCdfd!D;ZAnkh zI5Ek;QY211BBF0xjmrLs2K?hQnwBgLQjz&T{LD=BeABf99H&vKkw2T72!V*Q?O(i& z(_ZWsoc$wTnX_B!|8Yrx*y+*Y0ErLlsmtn-9@@`T} zawP4yXTF?naL`%&=B?R&ahzmdOoQA=+W?@`m-vmWMt5|Y;K?JjboFK##D_=2)~gnq zCojRAqX$M%t-Gadwl#o#(!t5dN@{^&P@;{CCB>-R>su@(+L}X-Lul&;uhTM+vcE7ZZ$T&AYM5_zsWChaNL?7+;U3_9uqEmG~LkA`>4(691 zUXWc|&(qe~61qxuei~zk>`HT}MdTMdg|l7%IGSew3Py-s|mw2YZ_Oy&A5RY`*DWW(L5l^vCQO>En zA*Lefi44h##2OzjCxBeW@aU3kn` zF5m5bme+iiEjvMJ$o(n!u4V_4!vA8w>mPYko61Y0EG=?GQc*@=)l=S3OGi zkSU_Np64%qD`>uldKVWWXf>xaw>^a{+|od=sEEV+ikkv1oy~!|E|+37=@e9pPOIj_ zbuRg;8tdB|HoE?0cb;mV<4FcdSW=%ESag7<1(18t)r%ZKx?$rs!AAvC6uE3u_@6Xb zuPd)~h68*))ga_DQupR_?@pHAR%REb;Do3CD^@_2#Y0!RV9+y_)o=|2sMUpRZ2-kx zi|_66dOeblRIF!+-Tf% zLyB&TO9HTYjM(T?nQ*e4+r!^ic~jIMtrN5Bk89997CinxUUcr1A=jc9D+p6K@C18aDpVIjAguY}A4W<1~$XgJ-n!kFnFRx(wcP zZc61__tIb`1u-<8lYorIMj_R1U>F$m1H>{fc$Yqu({1zj1@2tgMVm$kzZ5uIK~5E> zpSp+*;q!4;6x@t)P%PmjcvEV>DbZa5Q!gwEid;p~JCy-fHXQsQpH97zQ~V!_xSh?r;bC49!9LRaRDV`@0- zlvDF9yu1u&No6{OSh}S#+uoaAVF?qiD*;$sa5H^#o)!snwbk2rO6iS zi@!gq1}{@DPlH7dE3I*&i$<8)R5UVdc_gCIt<`xXwpL%ZaMN85I<-aAUF{}XiVjq* zkzOOS8 zYlar~q?(HLDFpqWoFrMauJ{Q-v?_PuO&WLmy2bp!(C_a!ADoZGif>X9Uw(N?tIpUJ z%DQRWYe^{6bY9xr64fVj{g@i5l*v!3=1`9SyrVE1E5K(AMtgL8dnaQ4BZ66@$YH)I zS(x+$mrU^8<@{a*Bgs8004HaPa?%2(yQC(AxNUni;lz>3-m~XgEv;HvqwL_%hH6)W zX5ol6boC{>JI2;YlT+=>yJmHwyPAq_OC4E0lR|ZH{PoDdr<#Pw>$4M(0B9H-_Gi{} z?HY=YguZzG92`QrWNY+qx8Hw>SuTG)iWgV%xz5YPu3ss4)4(Hc!y#z#MGQYBFWR@b zjgY1$&#*971^FB&n+M%2EUe~#%o`kJKIQJ~SK9WX?!w0BH#3@#ay;mTVPK_34M--a zJ#vH7RF&}3#n}Kb`uo5JN~M27EYl5D%hd%H?dJAi1nd|L z&b%0A@X@*bL!AG#gl*RgI2+Y)iFeLtQOVqXtU9OrW9paGcx|50`e7A=VbDpx(P{pJ z=KxVMLsj4N61q{R`L z%yigr-vPPA2}G-GKd>po`coA<=QpqJ4{H?$DLR&6)AplZ9Xwgf>5@e?cCBQ9Rm0bg zi7DJL7kWZy_Dys(mf$5!G7j%q@c$FGe|g)QI613VlS43)Z~MI{AC~r4S742Z0zE-pQC0EgTvp#ZE+ATM3Z30CRC#Q;cqvlviqS_(|@$h~{!Tk-4GssseJqIfN`Z`wLO@IFH!iFJwJs^HE( zWA<$b9`y17oIy4;z>0UXW#UJ=hjT4?Dws#~`$*@Ux2E>E$^TIfg>ud){oY;+T|SvgI_42?BQ$?y{m9;k?sBKa*Th9vwtze8bD0G9YeZjgV6NcootZd>BQgdm zX86UoX}1q1`)Cst&cVd~J3jjxGbgSRh`e!syuP8-$P@#an$+Y3T+#Bf{9(!!Q13}M zF`3iJw_3_zXHk+F-=lfsO>$s_e!0d&1EDYbx!8VqYA(Greww9sKb(5XIU7*NTN_T$ ze08#DUvNt_K3Z+2A{1J{-cu|(ly+4!>Dy?kMT^eI> zq|?-KCWda_Tr71e5Sm+rgGoa53ah@8p)NhiEeUtswN}68$$X_rMf|0@qsXse5vL9X z6Ln@!Yl9ayF5mP6{=WZ4>TnhBSmfh>Od!#7bqEgVx0;%Q~$o{uX70hsa2meyA44GJZ|oo$jk`O$d- zFll7RDdflH6E|$pYFN^qipr-ee{-?TtRV|KWfgRE;MPHn1fwZQtM6AFI9j!&4)PrL z$EYy%UdrwYW%h2#N(o>!Xt7-m`*jlYC%Rn=Qz2UhkI!g2otvjCnV2OM@E~G;1wD`W zbPBY}Qf-um?h1>pGxus-z21_0VP@r$zHa_9qTnHIyGiv&N<^urH$8X)q=J{Ki(#9QGsH(6U=(HYpMeeT!gxwKohlCw9M4Z zm~svNuEwvf<16;5QN=(ihk6D3%tcdEgxiPglhJ!#PUxX7_z5s_^FG)_BX4bl0#|23 z=EoK3F1C^1eg7NN-4ile5Tfl=x$mIpXF4O{1PK5AOaZ+|!O zmJ`XkIlnHP%~rCdy!+c9Rzn%&v-S6$NyE}uQ}I;boKm1y1h(LJlR4Mw`R_V)5pZJe z>UU>8?=RkL4%Dn@9LIjaN2;eRanya!t9=&?^B6q@D9PtkJyE{*n1P@0ZMjt|28csH zas7Ga#U_DA^WsH=KLZmU-7x`tIE@R1ZbR$!@}DP*+LxE#(b+lG&WXY<#BHs-I0e=( zR8bTufJ&CpoNlqWkZL)9aOQRy=V^K#J`vHw4>v%Zju|58wL?

mg&Cf#o$xdstFr z%lwW*_T%%y%q>1v)@`87&6oN3ixvkr{hr5*)1NA&ZFiu*goGkIgvBBVlVmghsg(WO zHYC3&KXpjcfBneFD;S!3d9hGkZ@4`1>5r(+cO(24M`aV|FY1Ui1$9B-8YSs%NaDQS zwjAj(P9xO4h6ji4hl#8ACq$+I#TJ($zyD!Vbo=HYa!(IW#6L!*W;K*Em=PK zv*JVsRw_ufY&cU_W6+<~^QE`rP-B6xXBqUax+C49q4CUlyrFS6plixvi|Mv>#h8Q1 z6)?wbNTn%w9JI|{=KVG~bH3Z2Yj$qA-kTzCoV{zaISvdV5u#4#eqpE5dV47+P`c2X^becrb4SjlY9e1WA82TwDq9-Odmv_h(a4*SBEaKL4(Zw zH3rn;hVn`e8%n=jo7?e3e|K$DQog6UC_&ULHIE9lHB+PoGk#Uy!$AyKgys}ayCPt9ovtPV|Va4M~ z*2n-%oQUCi0;%uJfsBgbf6Hu)P*rICROA;_{ii7P(My-Mh5}tWA~D{sBjUFMyybaw z*M@Czv2hz8LPE;M3{}Eia!X49GZFp6-4#d7_;+6~Oc7pIjY4&!)3clSwVSMmv7HH; zmUeEEJ19Ymsl|FZBrgk4p!T5S>;oBvpr#dauk003sLa@;zjF+529XlMsP5l7|t z=xAJ4M)Y8eFxmz^AOR-FrM-*aPz^{YRoj2mPC1w+FDetQr0a&${o&4cKkB2aMS}bY z=KSHd%p6%%=l}TXrom3}8&vB6!tgL%j*tT$FW!&%>ikaZrZ-eA(5a-O_;DrJ*QP;F z%cTt%w*Wp8#yrmD!=iIob~A;trk14mN4U4AW};OcG{Fegf(ql_^Hr?s!!)-IDilJf z&?hIUdK$!^xfCF6VAVied^_J()A~x&BUP5l>I)uA&Wu(gtQM|+0mYZ5vF}$tW z1Bod)D^3mtonHnr1U#Hc9avwpW>UeF+?zJoqCs{qj0JhsPDneN9O&phB> zDab28pCRZM#+*fTbIrI950B0fII!b>zNs9}VIykfF(03jLrCP23=~mKr{}3;|HXJK z9*8WwoeLz6ZgfNni7XuEU^?1{%C5G3y-eBBwPC2H@1e=sje> zWq|q?j-&P!p|cC(;eb8RISVy4imoouA4S_xt7#f+N=BkGctk-_M8F~J9eQAjgE`)r zbOVPj#>USL4E-aMos^@)G~bDMR$s#-BmNKF@N{(@nBjMP^$Vk8WZa*wLQ?}!#=(J$ zyZc!459oU!F!g(xKFv*82KVYQ7r6)3-(Q49c)kcF@+pWb0bIzSJn_UKsA>0sGT?!( zjrTRJCa3hT>X4V;ZT^+Eq_K#o*E~$g{`L@Fw+^uk|7y)Lh9fI8=TT>%W*D84XNVvs zFW#a7sXeRB2^%7N%1toM{wFrBo_?H)5deA61$*jWLVrIv-OswsqGsLTz^6n0Z-Jad zV6h#>z2NxA#|qH8kISwAK~h$Dq1$QBemO(V?Pa%xY4 z3d9q;p1gUOm0?#UE+gqF5f+wBgN*q4t6KfD%f{dDzFcf3y;Cn^h zIi>b*Bca%91bLZJaZF$g5C`38wRB$_einglgSF*yo+T9KUXt-THxhc4robnWqdKqM z7Txp=e7pzr)1~s_Ej4T!D^5u52;17QaKSg-%h=>^Hbsm+w%?0bfMrY!M$>C>)W%YZ zJ7r}nGGGANcW-yxi^Z>IQlLYBMCpGJ`taH_3c5P1{Ep4urp;x#jaH5Q;b+g^v~*2e z-zigi1gGEoi5)`1zU4C1{aMOP-#l}3cd}r*3N*;|`2+6?$IZ;F*CrTe1rEw&PLCuJ zV8ji=1pTgd>raLS=JOhh)FwuUIP99{t1SK#Hdfb@5?#B1%0S}2NDD*>j5d8pLo2rB z5e5xtZO;`hop~$#k}ivNi9@r<$iv-_R#MTD<{fm=mQHFDReQ|$OJUslzJyH#mrH_f zUrlN0qKf-X+<*)qfZxpc{Son+Jd80$*#9ZGbMu~joK;y-VMOr!aCW75p(;D%ICxm$ zOUzU`V@n#IO7fzv!Q1E|VM`%umJ&3`N7HkY48BV-{<5mN6yYFSz2EX-l3zwlbg3X4 zCw4ne;KS@0*roast)H?L#-~z|+BAc@!AA_zh{lUXAn74{CCiXnB{jYAJ2PD%@$&k0 zJ0O>_GAcOB%nZkE{OOLmI;Ww&Y@p!WZ^YPJXbrfkLn(~(;~=g4-=f%9K+UEG%?s!> zHjIC~9{K*C01p`tlw>FuTi{sMiM$6TRr<%fm2RWC_#bNw`3olKlAk<9|#Tw#@9uV zK470C6^;XxfX`iNrJzdbJkmgir{wlD{{8wf^1f<3R>0jC|G{>!L8aCt-Z~`;uw!|1 zdN5^e(k*Bx@F|U*65vl<8?{2$xK?TO-|J7?FmYtKeZQCgjYXQ}_rA?lN~@BC>f2r+ zI5bg??lP)%wcqz>6!IETO?Agf=2!>rkFC!-_?9|FjZRrFvDs1RgnLHTn_4I2DD++$ zizOzCWIFi7Jp(y z@dQPexwA+)2e>1^EumWb4hYypkAdA3352l|*qgk26URo$ZTxBq%5L{igSK(!$6_Z&~fh*NFp!y*G?$ER8@bCvjeQ5DrPG#VZK`7?M<+|PFh z+|N^W*V}KNa)?JKt0#k)hMO7nJpQ8wu8WC-ub|VF7tm?oyHtUPmOGST$N+|ZblWo` z!E->@+lcewHK%_Ri$U>>PCg$Q64K1c8v8xPiBTO=Dj-A!huSXW{?=m_S%a(|2#r9c z=c?A-p9bEyPE&KZUXa;-)7(`Te-llDDnv2gy@GavR@ zSJ5!~^XJ3ejS`crBB$X2spba|rN_rteG6MpqSOTI@zThtkcF$Ol&-(W4H564(j5|4 zMU8>$e1wj{El_c6E5ia`=TCx&wbk`P28NxpoZFbP_o1ZkQefuv1H8N(ZyU1CcH=lq zose^wuh!ohL=p9r%J-LsnJ**8lbnm+wv^!uns7q0>N8Zi-#mxlWTPq9)wB1sQ4qq1 z%hXE&=qN~odC_YpsVLk3#2Dd>g`ppOR0)+e%HV4noz+kfOzZ*&1ISnH`O*E|->%!Y zI!!ASv#$e2kdEr9NGxcguKo+-zJ~P+-t)DI7gDt$icH{>psGGL%lz+3h<3 zH^KtjtjQg$E-ujBXKIq%&a=X})l%oPO%fQ@m$T&y`{SWEeBFj+_t&nXg4#|h{oGar z6o3tZ60f4VT5O!ZP0go&W`{#rSzqCW-J6<7KY}|Q95%dh_D$(#%FrPodiJ3OIyI7h z)S4R30a1E#csJU8tJ8e?8pI@5z7;gdT$5+7OiIlyj)?L#%h;}u;V(tmZTkYQjmwn+ z103!48Rep!rrL5o8M^b1$v9y^Y5fo)W8(3)$P-6My(HS4&c}xRBvz z!4TdUG1TDn@-|OdIHWyFQoK5&q~J<*9Sw5xv)fF~l3puU$DB@pA=Y>c*?}lNZTkOQ z0FcJTdk;C9|9xXN3?yDsl2XS_3b-&1Fub(!m2QO1DVHJNKO4jz?(ajq!X4dzMArno z6JFg)#GtKT*}QHcGk5@ArV)CtvEit=V!nqfc)|})A>>=37{~hR{44Jst&lq}41ShPPo`dMrZ7kwfXC>egz#L5$ zCu=|VGN4NUWjG$XnYFbyu(*Wsngm{~g6juZ2&!2>|CP&S77`UT0J0ZSGcxRY{YBTQ z?<-2FjhhH9@+U+-8$hAz!{me5ltvU<7LK4_P}bL{VElUKZswK-ssQLT=j31UF|4eS z6lj2W_cf(9e)Z<=YH}Kx)d!k?g1Kj9*%&Wfj0@F=GQ^^Wtg_sy4aDcOo1_&D6$3m^ z6iS(=#O49Es{P<5BY)_(X?24V)B{}-0WAAt!mv!_l0F@0EYW9>ZFv9eUdC-*O`apG zY!um5tLwob9%fgJOm#Xt72Vlm+ufjVdL`{TfLxo3AzW7&kf-eoV{M)DZW4)NCKUze z0*~}BdKCd9x(s|m*M2{@y*E19&9}X!%xn~JFmr* zxsvOF_1rfwc3ZV*p8PGL;6rSTcu1qxL}^qOeKp#&!|#&Ax|E`mw0-yk4B%~SYrlvo zWhm6z)9I_}Nq8PRm=buvwF6X$LqkL85-q?z4il~}qL9MI z%)|upMe;d*1UR6y-VeefTGy(Y&>R8t44y#0#yp(ay63${uWxKz$I*MYqZvgfKSA{x zfo)DVl~uHtr%8_*M;DvOk+W8ZoZyZ|eI&<;9A6<$AncL6z_zz5>9w8Q(R07?zjd^3 zG!SrUt3K3)o|6+d4<(fV08 z^$#LO)_>=EnAX2Zj%SD7b=SFqToj(Q_l4h@816VH%Cwf#w#dRfjQ;_XJGYAOzD;+u zkx6SXP*wDzknY}ARs^37?x@1 z>&q99l|o!74c^_$&co*nAgrQaiF_L3ndU21=#xtd@_Fg>4YZpEa*K%JukcB4x5wow z72e>D1rHCB^jVhuvvy$nb>m-ZP{6vf50?z8$u8ff&)8MD>Kj&Pb$O)@`K_vTk;1n| zGxXNcjC!UJAi$zLErTQL)*n-CKvp`KGRJ`&Dn#YxLR0XOx%N^S#V|4XEYO%YlozZN z00XNr>N(aNr)HjCNFvV@Pu}Fxk!F#gEkUh?sz28thV$<5U(+rh;r-kM96ZS7&Msvy zS#n3qqzixQcH`MWN+9U33`-Lq$VDbz@qW?!7^DSJy2l1^!Vksk z$x_#fUkKifzbyMVl9a5r-cAE=6LCF%C9*rC^pFOb){qw2ABpgl1`KLoaub*O;P?lq ztpiU8;52^W4$ameg)5@e<5-3JIm^W51J;nE?YDE^}vRT-x?k3lt)M$-kYYgbK=d zp+pd)pO_&Rp8)o=ETSal7pm$>PeKg8wYEA1q`O7;YKov8?)k_gqjku{A!I@l;XR{h zRuuo_5jP$j!MFlv%wb|;dTlkel{H%XyT&^IqTxOJgZtgh)W%dbjAj!Y4)~on8^PtT zjb4v6#{*z2ZbVZx)Ig#J^!dh(+4q+39KXs5q^h$MejgxQTFBfES%HOlu`faqboRgfudAsZ2 z4W`fjuMxy-gV-Vuhq3h}z$$5X@t!<{%zsjBHWM?;&Gtg5qs80!oBM-Aqn1CuV7XbY zTB>oYZ9qxjG#YuzvHh&15%>QdvV~@hS`BT06+Cm;2iPkpXECrs(Gks2O3#V`k_RwBS%s@^C}P;$f7Xmc)kV$VG%> zdF9LEqaz(T)W9L4d-YbC2veMl5R0}Jj*k_xfepbB>LsAG{c{5l3JKQpKC2oal|r(Q zZi!y))Bu~uu5_tVqPIy`pl|EY5!3diVn6swqXvwFrn%Y3Q8E@hg{2TGsYxw+B2ty9 z8>n*Qo+437jg9&TUsO4+>Q6%5`4f3XCQ$*$cCHZCwCNyQA&A=ul?owEbtvBPbVsnL z(13AGVn|%G7twze`BYu9&gat7c=|p(NC5Czb#5)rT|*bwP(z87Sn_A-jhY z3Oi0TUDNVjH%j{M3yA0HT=t7kMuG$tl@LAwAEZOs<#mkH_FM-#BK@`iHe;*15zC+0 zR`o4SsxPmf_>fo*5$NLXC!h#>npFuDII)q}{dU&|bu+Nq52PLwc5@Q0f?BVrkY$Oo zQ+{5sdKPnxoa&nE)WqFCbzPmG*9N1@Ch<=l*70Km9*P2+*hD)qF=tMfo`cA370RPT@F5>4f%U>-9Ku3SORB@fo7fHnCqQpf~NtUfHs+3_jeSG5`i`d9$A;fC;S=00c8)MPlTO|Zm#m{+s`+$vHT-@0qOh)pJ3NvG zs-Ug`fZNXksT;l`1I{}|KyjNe80{``tG}AOwY8n{18S7ZbNXVyRbRloqIi4gzj|sj zX(cs#myq238T4yNTWyBRtobp>O5b9i&Pnl`cbgl?Mjs{~Vnry+1ZcVf^A-#Iac)59 zKx>661>eV&Si0$P38eLzW%Mcle~P_DIiH9B-JYPcorRD^$~$)uTvZ z;(fNoda0SY@aqL0YOqD3!;Dp~g}`q*f)|S6aYwgDE!O@+T+jOm-h6laGD5bSU1reE z+rR36s`L8IZuDke5eH8QlxBY3l|q~V4)yb4Rr~s|vv|U8zQ%e4fC8AB1kLQs%>P=+ zlirOIFT|K*P(eJKG$0)3eJoro@ivm?k}T}W?|xAnrsQ^cr@02gCI4x7grc#k5$&$- z4AykCp_7DDVcOAe@%}UYYGNFzv{iiAdF`zmO<626GBs^+?Brz2p(uAQI_+%ffgVWQ zqL`ysIjg7V`ikcV1w2wWdO`J$leyF?sP4SuEpc;DwhTJ-Wo! zi!IiKzv8&q4WvuKO2O2~v-9**m`7dTF?YBp4__V=J<4|H-y^*EgXVKmbh^)zB{e(^ zmC|9q4d5)HA9ITto{_Dy6Gb5!Hj>)c*I(^TFXd6mujl;Bwupr;D!f_r2ny7LVzvdS z8J|k<=l6^R>K2Y&jrF*`< zb}AdRGt6G^$d6S8<<1jIOWqKRXF`EO;+TeJU+``0s639vU};sMlPB?Sh_eB^7*D%+ z?CGwU?^?Pwi0ND#&W?&#l{E9dGXY6Gqd&u2vy@RHpt;|L9u<37VaSj|K-z^8?0F!C zd{N@q#irdyrAUeg?}at{>#Y?peobY^x#slcmFE>?;U0KILtBj&aE|-xU$U`t4qm-W zIJAczpw1e;R!`T=AeqHqGTRq)M%ukvvOa}|RXEsoED^Y52{8UN-ioDinpPIO(b-E0z5LQM-?_P4+7cdlgGn`pyq%q?=P>Kk;%pS>;z_%_N%9$O?3t zup#V~Y>!AMs3G0rhN^AY5c0vTy1F)^x4P$@Hw8L=1lkB6y307yb!>&lCl6a&ECj=MbmcGo0~c4d8wSRIiR)(s zomlk=KPDyd20G0;C{YC`Z{$?}sw^ozKLD$kpVwynssf4y^C;BxW8gWa8+N6jLjFn$ z{c9!xo)5QRm>xV(hW_rY{@_*-@DU;fH1R}Cm`Bmqf0TV#V#^ZeKV|Z(s08e#bVr+m z+b{(22G^=Tt`>^_fCluMJ&W5IY?;e#H43VeLYN!R2<5^lU36EiQ!_w%EmSDTJ_QIhp1#z`RFihDwd_xq@c#l-Xpyh4Am+ zZ{S6$>hEy0UTT3iZzxa8!+qa1YU5a*)}hgW4IvbG*0mYJaq{ux-8g;`$rE^8um0DR z2XH&j8M8sbSXo3NVIl4t`i$(m_;(Hox+loi`f(- znm0sTgXO~*y)i>-lagvO;US<69SV)VNY02DYY1 zB)wlq_c^oIjC?6UdwfS+Nmb(odbZy%|6kFJKg=RW*3PMvt&IKV#pcbX?!O;Kc)g|c9Bso44dczWxwDBI_K7*Immr9*OQq(r1cmXPia0qG9u4v_}w z#-&9Bq`N^n1*A*q?tU+x-{<=t2Y+}2yDRtHGuO;{o-;!l6vz?pHr0D3&V#o^0etQ6 zy*Gmb{1)!5+PF>2f0mIw=dIg0haJDAwp-ksCFgxEPG$-Poezy~OD2vl1;1lxH0+Xkcr>1*Ak&O}%~UNX`p<^`=)4vG#opa7V7T=!(i$QMFCvyP zR0;S5gFKQxPlfjTq(<5?ACj#cvC%q5?75`{$NSX6Y?OtH7b}I8AhbP9QG~U~6b7I$ zWo4zv3RABMexk1+c?TUo)CpUa>PZHx9K3gDIK8o0WBxlcS5F{pckdWEtYR%}^lVgQ zAgPi)ZM}ztDB^JTVzq;A`6Ytg5yk3?Hy_4+k%5hx-VD!o@lcJ!JR2!6kLkJ~5^~0;!_lk|?2w zv71iyw<3-cG0s{~dp#)V@>!Tq;SZTJnc!4mSIzaJ6(<)Mp3@Gq(jn+gbqQQ+8na;S zU-2VcKFcjjXLTj5!JrRiDlNMcq&re|>X*G1i0&bb=vIq;C>_arIHM`hgqR%;d)9ly z3Wqs~IZ{HXep%CX_Xc{;74-VITe9ld`q+kQ+(^uy$}X}67lOG*KCfS1Q)c0HRk)Gw z0o|Px{Jkp@L|$4ZWo6KhmLzQZlz(@qomSb7zE=LvCqEKV58^nBciLfhml`G2+Or^V zRHz#vgVU_b5@jP89HKc$N&(M{5n%9KgqE4LCL<}h`#&^%+DY8+FiJ?6udW7C52|xw z@F)Md(L{zp`>IH z$D>Ay#leW!T$zHz5PkZ@dxl>ZCL$y74`g2A*mPG>qDy2HCI%Ii5Q$gAUX9+X8_IFS z5!px|GqU-wk~Xy9Yu@QJ5fV4QLqEeN#wT3RuN>*`4ieM^m$*~qk-L$@e|~wTY$Q9Y zqz1*uNF}Eig|qLRgml~f@E4& z+u7jmO3U|mN-!@Uc~l~wi6}%=NWuB)wQVa@moSd;pz~pLGUgNA>WSG5-4AbA9gH4S z5Z!-ju?8NG*CP2uUoD7LiLw}>TzpR+5YQWDjX+i`uE8g|n;Y@jUw0T~eMws?F~v1u zyv59P&&2vU)}Xl4MmP@t;Zruz1vU9b`|eXP752;KAk5{{E1I#Y$SSEQm@|gc5jz>9 zIF#QBho_FK2;o0xBj!UFh4Q19V<3i62)JTSzSr%f2`#v}36c?g#@XxP5J93~T#%5m zcKaTyoGlpT0tRQmz_`c9P@L8XI>Q}jc^+G2bNY?$KjoJ=V{k}F00Wq3{5p8QJmS@3Nd3ikzbupSHed{_5iy6-GYG3tcoIPyRA}lq z1)fR3YuIL7=s!~MU47f&z0rdI>_4VOTr88rHc>%cyT!6+jsGK9*Djr!?pn2v$D4W9U{&co)KLk_1oXWa$Acm!dqx&9aT^f!YU7p2m zt@p?o#Ki2lsnWB@_Z_O*yky!wOGP8!U~-XhwX11Z()P91-jc61cl*1sLgtntx6}i> z+Z8Ub)!{a}4XuKNNGIelq$*Ib^ebB1u%qxtXP2&zBNgY;YPyCOB_mxI zNKG88UMu06hG0MjmEvwr^kbEEh)xY z*NSE;B)u1}E}i$U6PV zUQrD(RaJEjLH!ziQsa#$hAZ#0Q0q&P{`Lu%ZF9|l^JTVt=IzLq>LJ@6S|H;rK7rb? zrG2vPSH#Qa9BDN+FA>^1n-9Ox_4aAw|EQ^}RtvJ6IK{pZg*%00#776FH+*V9-rF-A zWh_i_X)5#a5%)2$T5bF)_QuC{oCFbit)XzfRa8EWeC8fLX~c8D^6O#alxem}&qjTa zyFd&o_>L~SS{9Ib>D7$PgP;U0VHQ@5ywP-l3ePi$!qYo~S}wA*EXd+=(mHQ{Pw$-s z&q$P(^6XgJT=LHlQ7LPX%0i!OmjZDFkGi_SIdNrD`K2$*n4f24{Gj`c797m>gMUL( zT`qf1_f3uIs6XgfpKDlziA6c0`%7wOm=NiAQ6r^q*5CGO{iWbrw=Uj>p&IZ_`%3lp zp=D!Q6L9op-dhBdJ=TwpN8ieS^+yj26jGd<`-Gz!Y!4_;4wZsGFup_~evTLF&lgk=_KASTX#ImcspDsygAZ^zPuP`$j%=dG6KL z`s)c3&%61$BGpy1IVSpM|<}R^p13 zpo4|^EhL1SxMBA}8S{7~Kf9-7@Fn2g5)X2p^`V5S#Q5cIDCu9V?D)lU^`0GeO+EPz zb3Xn_;5gxXdJ)^b@UCo~2(&Qstbr)*2JN3o2Q~ zF>U=bdp{h1n1?sTr#&8ZP5mSCMiBvw$LP!tg9Dcpn?Z13ZovqoO8lMpzL4%OUE5Ov z?xNDNZVle;IL1tQ`?x=hIIz*}sw;`BnRNeWT=>0L-_R@n$l+3o#iCY2BygYFZ-p7E zn5yUBUAja2hnCGgn7-EsNg+_5EGLIlKLz%Fph0Dvr~h9hp4SDXd}d}7ZtP}P7~bO^ zrFaI#{n=`aInn^?#R-`Nf0%BeJTfgBoTfbm9HlvTwWf4AcOWZ;)QF41ok2fBQ1~GS zhd|wnR1Nt1kcEW>|L`w;AC#VmNR@!lyLh7&_%a8H7de9{42&nIFQmtl?z&q76v_7N zc3MN)asTo7vC3}$%U}7GTjy&W6Dh|U^+J-`Q}eg+t-YVhMcKN|INM}S!>6C#oXRv@ zH%tis*m?T|AQ{R~e!6WD)!Yrs>dP>ETXYYZ4!*Ky*rl+gzSRfZH@44)Ka79i`Hiuy zNkC+PdCb=)FOCZ4JpZ_$4oG4f?tl3r&ks89hRMd`(d8O zbu0E3w8d_|nJDCS$iO+iDeL9^&dI1&zS(-+a3|!8LfzB`zixQIIz^PODyl*=vCvFxptA9m90-{H;)_Mrmm`{xT#8?3l|LT&MBsC zKboA7hzXzu=9gT=nCGg?aTYrKX~F|m)nB&O+l|AbVNm`9(|JFiP!%XvKHlz=|A7li z0Stv8DIHcYK$GSc7N%%>%{u-Uf=|L zTLsrCS>A16d3??y`%kD#r?q{D*s+`YKUKV-vqn6WjI4F|+pR4X%FySCUx{rby;LWp zEO!lQ-=ayEl-DVJ;aKYxWe=4;)ysL4wT;~c!8#V$;jBSVZV8iP&;%C0tbZ`MPUz-E zkEHsg_w}$b)_)j{oA8@7Ylj)?R^qw&Q3WXgskB*9uTq<{*39Lj+bB36p$Bw{x1lhL$T+FQrd_%cP$@zH`Hxd&U#@sj~H?$ChO)_CBxQ%TecQ+a8ZN*y;25`_ODM zhm7g1kNzi9lhdsBcET@SIEE{93k>IKz*#3{PH*0$l5B|NDtpq3*Ua({kMNL+{42M+ zYAm(40S*3bg0bypzX*xunh$kFar1!n5`gs(6pMw2YSq0tI-8q6JI^|%`pZ?J?IPc9f7mi7f{?BbA zGsZVK32DYiYW&_6zgy0vWNjXQAAJ%-85W-2rBU*lmSqjhQ-^<{+1(J)i#`F6-&Me~ zWSswbCC-n>LNPUKeq9Y0JB) zf^=i@kt{AkAWMg3= z>p&}yP-O&#Oc14Nd9R@kqB#ui_^dP5*cTMUWe0gbaQ)u?$n%BrZ-v)J_^>KF+YTKF z|2UVfVhp;lbh(V-RA!&!A1-;lt%H5yW-kD0f2jo;q2U~##4mLSQp!VS&XrXpG2rI( z^$#IMpE$oxTVwqs1S$Pm;7huD5o+t1KOd-9^4l|EU@Hopjz&3tE7xT|3L)k!Dhef+ z`W5Ps$&=VkBeo44e<@HR6~=aVhs=_wK9f%9frl}VX~Am+4YZ;$LeXP4qu)PFP^=xt z+Xhx)e}a|v*Whu+c?EitePcd6X))0MIOM#0F&1~(k6n2MP@%vL-p?@GuuaU*uz;^D z5d+L@FF#42vitCN42eHxJcvbY<>0myslHEWWc}g~la-Yflb4V{-js02Xe~@EdYGv| z5Th6zM4%NEgwS!wBSA6~QxHhkQINk#=dDP zg4pHfuLVDkJ^@INRdw{YQyC^deHP`)Zasb7sH=M*@3b&;EdcwMTAgw*OJNWE<}C9} z|BGXokB=-GD&vJ71(iigVv$g(mpjx`eg>gvbt%g?4cy*#nbT*W&4_uReOL4yh{qe% z*8X;C%mnOp%_+-s?b}B_p&AAN_a?ptlNH3t5YI_hK=FdEXjs(tglSn%nwy7*u+q5G zXQmWV$#!YRpK3rjC} zhiTDNl=MJOZnbUApFeI`C&Mh(?_)w6 zNHsKW#uMYyE5kjCM_Ga|7W-wjqh6IBFP0Gi@2oEuv(r!1=UtlkUY0}luyOWJTvPGz z!j{h7OXFKw-!LFTlJR|$qcaF#Hu%;D^AXJ5Q@{pBcW8m4&}-3NJR8jaMY~)vkZ?-ziq_v8f7f84 zvd}7U^3p-|r%ICB%48KT3ImNsL3r-@&54X(1B4(#%CR`J!SX4hG;wzGl0`GC&uB3t z5;yg>!Rb@GXX$}N&W zd{wutZDA*pAsaiYUO`n8KGm3q)!94Jzxauf*%ISWAS)~>ge{<*cI`Zi-85HovWIcB zJNg#g@NArF$%bpc`9aLZ6mn0$HmPuHs7IV>*w&K*}$HgRKoaqP$xo!96bY` z-dN@i549zgTze<2GEeeLd<-nfpx;(>pKJi-Q(Mab(K9bT?Wcwvx~93gRXV8F;L={O5Z3$&DBd?Jjj z7YIKeevqQ!i)sxn#4%b3azh)ydO4}1V<;5*9*2{OX-ioSvDZ8B5eMXo7Oq1tRBqFb zW$YJ^4~+_aOo3yI#y$-8jkLewRcev-%m+2YIW<%L`uauCt?&m8;j|>r;8e>aD`aW*hk2J2UyU*`$7ZD)~>KfrRV`)~m_?4_lF9`l_bOs?nUZ+L= zP5jH4ZyQJP&*=xM`*$m=j#_qBHhlWQ%Y_l2sY#1}dsI&>Ni4Vj(R=lJJQdUV@UoFs zob6h{+foMK_gy#Z^_vy32dpDQ+jN6xT45AuhtH?fRyG#&v>hkzkin5;S?!vPpMBy~ z;pcDxSSDQ#f0+6nbEyK$mwAA2uH$bQ=LG-8riFka>-ERi^mDO4FQuM{3f`{-9>3Rs zg9G@b5LT53rgW8pQfTR(*aV9hbemg>N{{jX(n%|jPWl8otgjUM(nu$?k?(!o7N=4E zS;&xLj1`0p?HI9$fwk8ngf$3Wkk{Qc7oeZMaD80wh#hO{<8#+3A{I*f^yyQ7rX)7~ z?Q+ELE(VY9HyKJw?w7!{43^*tQwt}ig+C7uWe0W55ORZ0K;A_G^HyM_>U-#a4z+Jw0r0ziyz)9y;{G_g1f z_d^N$=||RUi}gC4I~-tpB|rBL#-1;EHm0SgN8S0+$M+dm*c6pC@4n9R2d<(Gu*V}; z4<_aWD{D77Qx%qP%&deMzDGHc-H`6sB0Xw*&02A2IMrwHR-_Rc%K9rDg2p*3 zj)whCnQ0N5XcPjl6Fz#$B9&wE_1m!I*5jC6hedc1w}+S z>Hvgqp5^gx^sD%?^5aTVo2S0f*udm3t{suR?&$~|z@9835kaQJ!}V3MM`Rh{s z`3r>GrynXC>o%?Ydy{KRVaQlW%<(#EI#qS~e;b2maJa^gJhIdBhvvDb8a5Bf?)Tjj z5g-c&+GAv-qTsybNWZ`*%EZFap#__o)%U(-+>(RBgF5u%!jf&h+$Td7Ko>C@NtVUz zjQ6dOTcM{a6mVL83~czrztES^B_e15G7 zC*W^Ft~ZV*uIg`_I+}j=bEUqW0*1#vb^Q$UYU(M&IG3emSgVyYQj!^v1-0wD_^0mb z;MuFtB9(}eNrccShe{`;_TYzy1bGZS5nraJRpuv?NFt1&qh$#iGI{eZom}A*;Fx3I zaJkXJO8`wLQSuf_Sp7=}zZ5;x;P7sYlnQbuOOfF)0g~NE3dP~!KQm`^PfVPEPJ2+E zcL~;kt3`f<3KtiY3>iV?l)sl&aoV!!-NMGDrKqxursWEB7@Ter6?dfR}>t<2M_LnFTWx^ zT=+e_IgYc?)0=n5SL=u`0}Sa0e(m`W@f|?S&7EcT@wYa6vbJ(p*WaSVqU4=Irm*1C zqoPC$yJ3$Q0L*ho47uAo&AfS4FkCHPmN&75$$HH<;usuxqUD)?U{c6d1-A6sne|{T zy-P{75I1=u3O~`+jj15MLC5$<97X&yfn}X<%TgEKVRzlQq7G&(8ybn(Yf&MF4gb`t z(a^jTpx=JYY4zQlCp}8iL|#7%sDr?R&}lzj(~oZB{Z#CmbxC(vg}D#IP(+yVIXDhu z7G|erjkuaS*9=Zm>*l8}4C#}%ObYL}|H9MxNm}zT>Gu{Ap!i{nk`+%XPkTXyX`<)K zoJRF|$i)1w8Iuk{gpTgR3&K-p3k2UsoGW8GSe+Wt2EE_BVu$U~st8;D98hKpe2}sR zf3%^~IV<`O13aj{cxJcp%En>n^Dv0P7q7*)EXwYYZ~tFGgP^ud@t=ibO^?_65K^hp zkX(&oV4U%aqoP7Sq-|i7|4Pn3cVCJkl9Srj08)pWLM=4ArDgL#(pF9ravmzt!LSh# zKh??0Laj>^Q$7nn0Nba;IozD@c`Gflw@A~(QGm`3Ro3}(qoC$w{#YW)Z;3D(A(UQ^ z9Nl;Cp4EV9zX(dtL^AasE$>L*UiKBK20hXnnwIc|TaPJ`WA}Bi792ZnlQqKB-cBK= zmlrJk@){4dDFC8^mcdBj7*6m*)aTR>;n5k>*$t?joRYbY*y&?yXkjuEQK6tWP9fYd z4@!S#0Hz2mx{aH$p+?dseFnEh*>db{{q4<+CHMfR5J46pTNAYztk!q`dAyqD92o@= zVYwwGW=Xvoegl?Q6#OdyASCkl1kV3(pU99s;ZAj3y^4s0k&Oi+r=;aY8RO5^^7qUiVqYJr; zo8%0X-^J8kR)LpEu^$Pl$sd>2ev6RfGZVHJg1d1bW;{4cTcN1tH= zHS7r_si=t2e-I?rGu?P%a9v&-1kOT*3}CRCmX>AL=X?a;`>S&llla#JE-LN;&wK`zxM1{P7j>$3ug70^2OnkKF}(IWIu zQ*HUOaqPu)4@${z9erJS^NCdQ0%;nZsqt~L?bbn_An%X1)f`Ow-$%LwU z+KmuGdn@aAftnWYkX=`;l*MPTa)N0S}j^^J{zu4e}>gX5%o>)gk;RsQJ zY`@H)tC;W6T>Z#Tom?JLe;iC}0>DW5*>$Poq`}x&m16w4j>Tp# zL^0=&ACVI~?dW9Aj*+@1$SF|^h+jyn(Z|P0Lo2krm)j8KMi`=DU;t>v>!ROQHb&*k zk2KwNGQZJ^8Kpr0fMdrJWNKC8=fp!pzmpI?CYn>|Pt8$2X1HBB^-S`iJV7jL8p$(s z@N+Eg)PhqZK49Ub*;{LwbCY5m|MWXb6LrWatgygJ{M$=XH4#UhS#vvPRZUT#e1AxO zVtR|o(WpmVSP5`>)v^bwAoCd5t5xw**p^BkCruiK zGT+mU)n>@iu~zlymVP&LOXX^^Y;0^Z@gc|z>OiTd?Bv>EE69c{$qJG1U^L}b9mK0=3{zgMstDlu0>?n0^YS4;PaMeZ_m*=Y-m_9`BSjHU3E~g#jh)nAN#_wo~_7 zcPU7t1+ksY`7fq%A2cOsYygfh$VCh$_87Q&wWMUIu@`ORIbZVK0{V#Fa>5IU%#g2G z%du)3nu@nFYIm3vlgGQXn!a5G!Ng=-N)-l%U}tfCrnrw0H+&nNIX;{yUXEddaDDsC z^ESStKZtKQNU2oo)%W)tq~qhL-yIL8Wlj;}iu!Dv&>XCHtSd~HF#x{)BOZPD|F{%| z5`fw&plgt`rTfFgdty+3;SB64AOt>~OsX0J-3t?;fmM;;SCJ%(wROf(N#T#^DXZ_O z#~w5^1Ceo!0ej{zHd0%830B3%I#S#aQjO&}u8Cfh$wmOpSFm|Da&3woEp8a#RG*5K z6GXodm|DpVO&o?leyEpDM~DasvLrnuDuV1D|KzDkr;JH;P4(&)3S+ul0SIAlO&qLa zU;=~xYU?vVqKxXC;r1E!CMo&cGqO?&u5ELT`n(e?$-aht_|jk^6SK8Dq260EN-qH|A&3 zlg1Smv+6rC;lsg~LnBgqoI6iH0;(CPOdz==8}>jtsIL;4T-#97K+Snhmi_LJr6Nm=EM;k1OfC}D2Km50L4m1o0VX$IMD-ZShu@95mRbUCp*f(Nz zX>LwLX-#!ifOkd=gddfWgAAUl7%+tZw3hdY5_)WMx9#V-P4`bk6^GxF`!+Vbu>M3q z@dOMY{LSBto&FpjQ&QZ{m+dQLUYHT0U;e&b{5~}6H1^KO?f*Z31s2$deWw#})Mi-vq&rm)N39+Xu#Pe0}eS$Mlaua!alxxGE-Y}61X2bH0T1C5Yv zv*QyJ?FuV}@sBDc6XCUGm*F36XfSw%V?_*OK7`_tjTtKVatvV(ve@MTdGg&K?N(0( zjxN|LD#Jt{e5P2$BhvXZ>|*_&p2G*av~IJe7X;_pDz~yV8XrO4^^)$aX`^l^`a4X- zX!Kq|AuDF!*N1AI^gQ|W0@%V~=BcICF~SrlF)_KMo!I_BX{jL{11}5?&|tqa=dvzj zK4fVZQ|DKRVcTcd$HyulYL89JClSk<0A(O)h}hQ(i?*ed(5mokvxt;@&t+eo}LnDN+>5YzLV`6|s%0{&4uJ z+;j~CCmd$z@i#G4kPF}#(un{6gWx{@n0e>D?_T-IS%up2f)I*MyqZiW@m|ggdMz&T zC)?P_-sh!g1}fLMSn>xPoKfU?1G}Q$CF37EJ#|{6qWD52QU6GUNanGzfU82& zRi@jla}!hAXPEU`;e$0U^qM;JI{ij#U>(hdGbdI-_KvabrtmXvU|->wMb*#LC9nD> zGcsR5xIAMXz;V`Mut@M|5Gb$(sIKySk!;G?+Cc@62~|#EyT!8U@#UXe?8IZc&4(RZI+D(H~o#SOzrB2m;EnKQEuGO{bvJNXaxWXe~$NuvlU8hcH47ey&; zyty(nddzH=^Y6$>%PR_I={x+#%0GQ^YB!Oii~m#&AP#`Wpx!mJdC1SC$440|n#&Fx z1S}eQ)~i7u6X#b^e;BQRrkEI_Ud8O5D#&4pPDjTx6_&bLPOA(UNqx;dj?Qu5JAsm7 zpwobQuqa2YZD@Jbkm5ULTv0rwzXOl(gSFf|AIZ{DAK2?=2?h_Lg-ML z_tAiso4j=by2o;qAnGwijAOCnjT>9(XVRzkiXvDocTGjOHsKt??J^06dqraKU~??{ z|7X*?3KVl61xLzp8^R|YG1?34zHV^7y?opXmZu8xG2Jy)%zpAM`{|w0n{7@6yL04NlDqc zv<9TZr7QoZ1t=@)EZ`uTxLceE-$RnN5pQkacVgHh)nS9xiYNTgcYm_k-+Pid^ zUd2LF$CGZ)m71284tR8BF|ftX7x<;qT;!o-u5w(Tz#3Ln>!7d$p+(HE>@g#^eKpzo{kQLzv|ZdVLP8>bIjJ8O>Z5;7!R{79 z?Fi5{6Km1fAoR+dY7a!A%L~+mfs+1bBIJiOQNWA8eExaz6Ck6vB?ek5zg8T}Nxcz4 zV)c={W9UEq6JP^#l|To^hAB&M;u3P0-QRL>9!L1ykWqaCGT+e)U-AtxqCpvefJyuEfk|k5-v&A!*6IA*ZoeTw z^uH;c2BR!b(1Cg^t$~y;^z37747V@J6f)Hqj#i|Iw_dBl=k8A03K;9V=+?h$PK?~5 zx`qJ#7aN=kga`huer=8h}6U@ukr(aF(HGZRFuvFwMj<+ zXF4A{W23kmo{>KAjP#7!w@5lOa}HC4!ASy+odK$qY0xWYV)oYz@xv!-6p z_+BLCfq2wo^p>hRk~-?P1n10P;P!5l4bODXI?0VI2UNyL31C>?Ni_VUPjW9gLUjLE zAtClY2HD+UWL-aZ_shO`hBvmer)qwqijc5ilJ|i;pbZ9b^wfI=S;-^@_MmNmKI`6m zNdwx^wridxF??%+JnXEIkC5a?Z~S(hqBbh@NOFKl5+%QtZ|CUGWy5TjnFRlT z?dg&d*B;p4JSc>)iG!wYdM{+5o{t!-9o6VqIV zo#%I4D`3cpf2IBmW}Cp1nD-Bf{9yuxy?SSEBJUJ9)08NzxJfIWDnSsHkpJ?~1%tPo z*B#~p`w6_+`Q7*Y%`N?k=4*f0-{TXp#Rb#+l&f!J7B;v%RVS}nu#dGV2|j%Udn)v? zPYR|l%hn1^bR}_Ntj{Am2~vm@R6<{ZSPypf0o?6 zDqn;pOu}Y)hk;l8$NA`M=@sqZs3OD`$x&NBBGvp_o^&9H>KO2|YQQCPIWx1d4Qiwk z99!PacD>ucPbM&tYbve>y;dTOj|G-f2>C-x08lgqk;BSK|F4QF1O5|@J&fcUmyi&= zgxwCG01Yst@9DF(SQRkCc)DRhai}}1P0=T#GWZX}ZO6G9pfDQq%IL@xf*?zxfsB|k z3;#ro9;C_>+Ab)e?W;ev^a#@jT#1QYv|=qn`&?+~wusn?&Q6IjF#-e4WF~7{_IFB{ z_bPt9m#*Svy0^#~5%c{g*C@}_E-zUoM}KFVONq20-xSN zKC^A&1{zFVS=k@g3O}Xb9SOmdPnsIE2eC^vMi~+CzJe~~8P9=tjjzO$jaObtK>o$!5)arBgk+}awgG*NX zd$6|-sB6FfjLaU&X0X2EaV4d0{sJ(Yft9it%;uG~@aga&6VT@-OAx+@+j`@cv6S82 zx-YP`b4ha996`6rC3DR1oEiipdD~KAjDeTG^mWuddPeTv({mQPsmlL8XtDDWM>>=> z&aX&XH_gUArKeJ^{Bx_~`j2nq$SOkyz`^hRFR)^Wa3+c`&jx>LVVjx>#;!Fj=4>4D z0vgZ1#qy&LD6+nMo}B~9fKqIcN^#e?$_nMt9o1txqpWXKlOj7Ht8K{|2jh->l+rxw zep~X}ii5bHxxYw`83ylk-)#H(KlW$2EFV}c7vU#n4Kh-uw>z{UB?G-j?&J(P{$5KP z+p4YfH8sUNVdy9Sw2^Rhv7t-zY=BcV%#bYC& zlVWf-?+>>U_wm9$g@pKAZxsTvLC|R(4UJF7&=6+|LF6maMH%>1zfxMl{qwH`#LuMh z<%?nR-LK-P6R!Afc}&xhFU{8Ub5#C6;hUThu48z)nI)Sj+_71LJ??QbRmR6j0<2HHt_ab}i z>Xlb6UxI#zM*;?`@gT{F&V{!*P%$*9Y1E8yVBFUS3Q z6h0Emx^%A}veZZ?v>QpAs^Euxy0$O-)Q7zMxBuZ-9P$&(De73axmmh$HSIm*xtYKheg`JgMU~QwN{wLBBg&3|_?(zo0$VJdyrD}XRla}T8d_L`F z-~AgWXMQ>Q?-6}AX`LgyJDfj!bhxL8smAo%@2B@-83U;rPn`VDh)dET61jhxd>?Ts zvQyCRti<{>{w*{-OoW>SOa~6(>oAFllw%OVg_ME@bY4ucTz}jRqVKjA8i0A>V-V@J z;Hs&uHQz9c-}(S_3}w@67XpXa7S&pVPj3lx)^5cqP~^+l~nY{3?eaB8MJ(#VC*P2`|PZ3xKN6)ZzhGt zC4hj+S8`{X+1SZ*Zz?wqt4sQF>|DMywxue=C-)sA95x^`a#?@C{HwQC3O7%C_Ew^N zDe3cj6m0EtfnjsK3*r;R_wTOj*SiynL364h$nS~TfyOi~zSde27>uP0ZEGQJ6O_a`cdE77cr7N&WTK>wjXH8X>^4W5P{;HN8V z%%D|Vj6xjV{PiB-g=KBpzmT8}1ugq3{tRO>RqynM^L$9~&Rk*A!o!Tj;_w@r2};m( zpvI(lE2 z^gd;@yc=Of$1t7|ZfVpC`$xF`?YC9FO!34P2NYzEC+H`Vl#th{a@B!49XKoOfiTdw zYATO^tBWtJo2g`=1=#`G*L3P&2a>MMz5`uSD=X7@Ktn>YL{UVFG z*R{a;d;NWvsuvqNBOV;c{JsZmm($m%_1@>?Q+NG;oQeEIod4?K%%X62k}mxaoBlK5 z)qHV#wus?2i<#i{BTK;T?`}Oyvk=h_!#amMLC*zIjE%B0?D@d{9inSHz0K_0+5;4w z7Kb(OhYeBoD(@Gih#@D_!x#K5o+E|=_I_tMvuEc9dxodKWr^7C99PCEH`o`ShR7z5 z7&Q9cUq@j)nI3Anf4fvoM)bpA2RU)N+}>WVt$*5+O`mVV?dmjyrI1}u*oWd}M!kba zj(1Bdqy+J-R%Ar4&Ku=!yFaz1WP?q=*=eQ!>_pQZ)7zkV%xy0wV)~)Zg~f`_enDQsX@!AbAH*y_?2_A=ZJp&sPo?V)lTx*&Uh*d zk#D2R(P^Tr`40nOuf5|x)|$imt=|8vmh6+qz!i~StM`%I(r;Ozha6Ot&Y;o4SzV;RIIXeAQvN1|I-S)8t^{({HP;=z0 z^>+F9zF(ugK^?-60iyf5`HNnH)sGmHdV7r@s}H6U1(JPa)6;f*h<;=qG|$dWJkVSi z?CdrB-rq*GV7$3ui!AbM>geW8ek^107m3?50c-&pm0M;RFI8E+=o1p6r{r+5 z5l*@|PKe4UL|_yl))L2g-)g{vk%1s9aEZ6B>gKVHXoH_-#VWfFNfGz4^`js*v|SjV zDjjqM9@U}axPk6FA1WyS+=pv3&p{l6A4854he7dM>(g(M*xVzx*jU@*Wt8r%bOy`z zO{!GkX!;2g#=fVn9s|m(V^0z$WdR^LfPS*L;<%)+F~muHh}XCNlUe4tSFC0GJ7%T= zL;OG_eXbUbSplcO?5wcacuaXJ`ZCw?QTC;;PX@65~jDS!c2Xnv}8twnjp|H8rE*27LPLImrM2zJKdZi^w1T~}mjYzEjbsFK zWb1P~rn=wKc@kdRFMp=+H!g+Jwj@!|11q<_i!pUQF_Pvff}Sj6rnRqf$3yGG2q zax=Q3&$&h~^ z`tx4VBUx_h_jp~4L4)@APYIf(sk~XA8kX z`z^Po;y*V(9DCDe_3d{Wv5VjATPz+)-bBB7y?{FB)||g^^vP^GeRf}bTi+fYvR5su zv5}&gXRTpoA>gq+>~a<^w{YyT$7Oc|zQQr}85A1@C(2p%YaD>cmZv-O)xd-6@)Ykg;N)W%zP>7)C<#Wm-#ovwi!g(ggNujrA5 zlRnu-5f94|2KE51x`jJ%6+I+Y7Gu6vmMJCRN|D)ovPnMw+N(D%`h}F4Tdtqj8e?W&Q(3!|!E!R7prue-wL(BfkCG)Jyb0-XIO7V@Bh<=O#!<6o5 zSzGm#H+kb!im$)4QAxg~x%Gg8>42U3fS8ZcjgG z42MSrMl*ZlN^lgt@CEsD7~V~0*E^^R7#dM_CNLJXFpn2ju;?mlIP$@t4L5AnX9Ljv znTO5(vc4UUm{?OUo!%9m@-ko=XJ%%)^19S?Lrn#h+((a1MB$0A6NBADiq>u?H_N;i zo`R{?ihoa2RKFr-Mn#<;Zh~YpD&r(|#=jC|r9@yiOA`PM1-EW$Yup4=ajbpa_T|2A%9TY4u{x z$gh6f@DLz@#j&R&B@*bgd{|vw^Y;XEUa;dHk)PrcYDT^$Y3^47s=w__&M*r)%`2WuBdT*FV0we&Q!yG7^yfdtv0476-HNb5^+KuRS%Hm7v9 zYWTO#uah2Q+&3lZYtImO)Nro97N)kZE?sqBhD*6|GlEbG!tVl-N3v*5bIac|nXzj~ zd(Zf%(%16(XN=dogqZ$gw$AtgG`%T1*R-DpZR$A<~BI z_PgKW&z(o6GNVd$t)TzEuZRE46fBjE?@Neaq0XM6s(pK*Vw$YgTK0P;Mj#4R z{nMRo+W$w>R|ZA-zHJkdg1`b&N_T^lq`)q*Eh;-AGD@bji|<(v5V( zd;k9LJTuoU!_4lm!-wNOucJ;w-Z6*tQrzj znqZCsZ4Ml~t|hm|1!1Hu8wuV66dBo$)&TAvh);Li+Z$?+oz0!Gm)GG`Tasy=x|i2B zRBw^b5$ntXXIo#(ibCrj|A_16$ZeU0!I7Hsy{Yp3B;Tc4oHvVXU1+}KDYJG{-pv-S zEw1gW5~HPRg9h1fT11nZVT2WYg3#a*$IVj$r!U}@iRuTb__2lCQ@fNPf6@DKfX%hK z4uM^`$_9+Z<-cYA4qjmPCiu1;M_1>pn0#}DB=9z{Ola4uxCj-JD~t5liw#82&_A4_ z;Ve3cx7e*lP+8*v`;UV@HA8B>zxr+|E`UNxrk3knitI`ye}d;~G?)xZ$}-pV8h*Ar zY`oFEhBqF$;vDez_l0Hm18ay<3hzSE7Jqti6<6vS1=1qiQ}2!bI`A=Y=)vY2%B%{D!5 zr{;qr3yH7h$=0!bax;_w8Cr=UckO;ah7?-kdh04zG`ul(6mRQmbIs2y*T0^mY^ZN- z0Cu^LP&Sz67P;rj_)koDcYU9)!gnB=$$I>I&vX{AA+)y(s5S^D968FZ3&I>f52*k( zx`X-K(MRp?4s9R`{H9f1GZ)Fs7AyJ z^g^cmjq3R0{dKO8^ZMpcvh8dIa%*exhNv| z7Ti%e^9$C?gx$scGKHt(+(O2`X`$4EQiW$R^Pg5eO8V-vA%HH|#UeA5luD+q^LG;Q ztXVXy*-C;|=K)_Zz3Axt1mbK~l&kq>g>RM1*nmLzJFj*l&Q}S5E4NSnH)o@3*3Qnq zx7(9Hbl3qKMXZ*(ruxk4YL(zFkf(AF77js<0GF~jJ3A{YfUSD_Uv)ip{})^0EN7+@ zT>uhvK<)wf*gZ=)K@`wtvUeeT&jLhT)BD+(S&>ezN~GYKWxe_~8AwKlR%vI)=zX(` z+Z>uo`epQn?vs@bz`O`+MI5=KGUf(;b|4v4%~TC)E0^q0ny4*>wl%9gcsDz_7Jk;} zurY4|vPV@%m&^hyYE#RO9?_uR$KDIGHdw;`ehLyM_6r&;%ZNafS%)BBD>F75u|;a* zY~$uE<67ZPmtxfpj0SXj*-FW<5=myH?;1YTPbmx~l|dTGtRKz6wn{ zhQE$IarCbn9G0e9&Xts|Y51WKyu7b@B5Mfqp*rHc3s#+y{Pos&=lv!Ct^L>4TY~&a;<%T5S+WGlZ#5`SAe2Z&^dv>1{|8L<`1ysL+Z1B_{Ygiq zxLeP|UE|F8Vp@9Nh~n4?$7G>5LMqlIPp?K!vq{JBIlAmh6Wrn-=eyL?cy#Vo-7s!o za21`})|=8c`0XazvfsddS=6s5SesXX{r6HwS&ffjUx(MBdr<+TJf=m9#FGnZ+)?Xv zgbvwpDX5*&>oBzhAQ2cSk-}#yjj446JGcMzZ)>+yUQ#4vxPM*vM0WoEy=}CuU#u6K7zTKe)B4HBPfYOEyd5NP1;+mKbcsP^c$vBdO9!OVvR zo2+Gv%C0W!Hck<7|K|nZ+o5;PP)W+%Ty;&F7vFh0uN0Gx>!Q_dWMGQRYanT}swr+S zz`QHo@yf+zt_2fj%~tB~$g4B)k4B})UzwV715MWcau=gRxene^M6P@;eg)G1p6U<~X@ zTc>y>@tk}#Vz9#y3My4>Srnp*0vkr1&WC&lYVWZhEtcxmggwby1KcJ#Uq8E@#6`7> z&=GF(Y&_%&hC@jHwW zcf(NE)@dNnj|O%j%8NA$w~ickRrjI{pBMq5nhzzSH4lGi?$KsE{Xs7dCfqkuXvfUB z;12zz@kHJH=I6!;zAp2>9#oOG2%4)ONKB9#M(P~#ujZkgFJ6BxGWj-4!G`g42Wxao ziDj3rS`Ytx)LhsoRSP_Ou{3DFxY3J8(xRF=Nb$~_`4&mAMk0O$#;uDZ*?>|ZYASPU zTZ=kMyu8~6^!!V|5E=!eMiGz^GpNEH`t!Y)n?-P}%zeYfP}L?K{j&yP5;5il`GIJ)QPSAVdncTH?3=Z+=oiJ7=s~KU#{wqpXdz*XTR?sXMdXz zX;~t|+i*nIa)o2>Q&dH_G@-9HwPx$2)Lq3g&y#nkF9nb3zunS`9VknOEgI*miRqIuOn zNRW_Bf8n4;{n3x{73VA_Sk=j~A<^u{+vn&d*SD3t;kfZ_Y|S*yWsB4cjbY)jo)JCe z%&IocUk^rg_*s>qko3!kg zOrc7>h%z$2)YdBAF&w7})*`msBUM3`WA6Hn6crcLjJ=={3Ms?F66Kg1E#uQRdCXE< zDeYLTY+udq{P>RgmG=fm@m}1N8%AQx>Tv@n#VU60@8u&NH)V37kFk6eU&k}1wOJd^ ziT~Bhi|3_<^R0g*@R3uUHC8^ckQVU%BpB*Qx9%AVW#+Yl&O>7N&&MC@ssrU}CxH&gs#MTOYo6 ze!xwX8T42YaNw_XED;TUZjeyRSGk^G`?p7jP%l<7)Hzn~N1A0yH#fJc*wc6GpHd0>j$JKRr9>JPI?Fp> z1Et=?#8Qd)#?i(>;M2m-7crm3|2_=;W&l-IRBWF8wB1hn`|oFTbo7j|0cm*Md9C(y zB_NaBKV%tu=3Y~7aulSMU|LJ<^?YpU8UfvpSRm)n4ywmF6Pq}h|KgLBNJQPtmBX8W z#ov=wltBIS$Kx`uL+QoAl|PzuplCH|m&(Ac&>(f3Oz$2=pFtm^sw z)ti)7aQ7p20`vS3>Iwwb%#0uELQIDfR35sTE=x*XC+$1I&DX1q*7c*-If&fuEG00y zwwI=gcQEaKcsQc;3o>t|@t~k$$)7-tEs_JKlp-?RgaGC4jD%%Aw1a-)j0BmYH&hNS^1ca(lSrNKQ|H{UVXODaIv(YTA@)qLW2|LMH1ubY=JO5F<^34}p zn^!NWnHmx+gdZEId&ZTr4a{ffpA5ab+9Ypvja~67%JD5XtaSanH7-xg`!!*=A!fsK zpCE5{r7@2g&oBrqO-gKNL+_myEn@=-s-$$DrL*HhYC9(|BSVLLIiFKid4$*bN4W%# z7kDz{nouHeh$2-IJrVLR@F3S_$2VP<7TkPJ`2wHw8?W`Mov&hJjtm>2rTNfVb(-V) zNFP=PvDBnjgq;Jd9vaZQa*JQMF3%Q_>hI-w1uf!Zx~bDZC7r2`MmfwnD~QH8e`};PCzTg&s1mntr`}yC3E- zc1gM7{+$@oU9u-&&0!-MetGrXg4M*~be~+BeC4N%K-JgZ8T{3=8AcV8*A#w5K&^&Nw3r-MF{59vee@h0(R~l#RpZs?Pge`%~k+d<*y|-EU_=1 z`#7v!qd?`eov!`zWz859mCxbttXjOAWwYO+A;$)iqCgjWl@8V5F!=h=c(STW=btP2 z1#<4al``2P{+|c6CUqaR^%nO7ahY{d%Piwq@b&S^(%M?Q*x`P!*J0%@ye+tjozAQ(atAdXlQcVV)5zAd&-E;R9^a%8S0YqnA$@J_$0tr&CTs}Y9ok3b>G=3m zN_zOj#>RH(Eylugyg1JBS4`xL)*DzuY&A{15zu7+7*jfwc!0Q7@o@0+T9R>j;fyZF zM+_7Xjzbv7_1Rxzm0lEP>n~lObeDzF!pPJA)rl<`E2<$y8kZEtgsFl zEQ&z(4o4r}lB6^>++hv&WtcS45CZ?bBp41SXx@eY$S(dDBJiDB9t%qZM8gC9{ zILW*}Fx&`;aZbY=xWNuV*53xG*hzxk8}p5lG<&Uo%rXDQ<$TWY%h!QRdYv=vXR~R9 zvhyhfNt(c~r0Q=`-dtbjRYR%cU1uzIxedd4E@yhq=^tu12gn3HV$I>lv|%BVKT@Ls026Dr z`~ay73h59Tn8-GJ5z6=5v|Rn_OO!z}^ggtQzwpgB{b+3zxq6R>aWz>On3H@jLw3hg zB%0GIzr34y_yeloanb~YyT$1fLa9^rtAm;kho zfeal9+Jm!n2%v<|Qj6Aes!>Ic-@o=&a$ReiM$Fg~FLB9dYo2kImn^X!^S$(8?R|8| zR!QzzDZ$+MnjrEmHS$niiHC*u$OYb4|5IGRM z!iqfj8WmLtDC; z@va>sxZKJtMQuiy?J!F%2!*$@blX*}{G0Uxw%`I4$)S8nux1mTUb0OdL%Zl~<=vvM zZV54qk!Y0+UY9>F_Omt>bfZY#Z3LWddmdls7Yf3ZY-D>3K=P#m$3I5rV0Yjkh}YT^v?!AI2N0(Mv8RmG1!Q-Jv%PthMC0=F!V7L z&=dW6IaxOa0U<03&qyM!A|gX=>d4xgT2G-O0%2yaHUArom_e06e{TC>-uYNpJ7z8@c(YqI~IZRF;fuVhkQ_wKpv zXkqD;1OT5In@Yx%2fKrJz~z^?0t#4g|Gf0?Fq@(%Hp|p38&q(6M=G(@@t2MUkZ2SO z)m@$5!|2I%<=vjR!olkA)aCK99*youtCWEr15P^edbSoO z5xnNqaqbcnk$fSdnt{dGXQ}yeJxSGy>lTsA=EvN<=Myi?-slDvUz~rqXv?KLuVJ85 zOpKtB0;O*TxlnUm)>#-8eNHeq4*x73Zk@t_ysnC$SU`&UNuieK6;g&|4#*m^hr%T- zBt>$gvreso9LdxpBb)e*5iDHx??qeOM6gP#@P<9YPPg)i&ca9ZE#4_eTSFrYb%Y-*|rL!`vy-CPbg2n zeT`A1k;iuTr-G5M8gG0r5bXA9w0r!0Y`j)`ELwDk#SS5irrFe_gHKLb=HAUxF>W*qWo=(%>`Fr@9n=M zJ@dftUiA&Tz#OK{&=LyP{x#9+^MMQYB8t->S|bXsb@wBzPdPu5h-g`1n%Z2CS_E-zJF7;E8{Wws6-&j!;lF=%8?F9lJ28gbQTTBzrVxl^@Qd}~clu3sHh z+MF_v(B0hQJbOQsNBN+$bvr)0Ohe&3I+pd;ToI4Q%6@sqXq@6>saM9eWphbQhOj4r)@Sdu!xnPcZLrWY}JAhsm73)Xb>S z0;$Ff5Ygs-IeGn+CPP(~M-nI7;h}B(Ns< zf7);z!QuxTJ+X?RUsC^FzC@9^-ivu%##YL}m256m@ZNrt@ODy4-OX(jJt~qaA3|ha zbB|NRi9VO(8h0k8cjz%J>POxqwu{SN9T_`ohqh&fB{ON!!5AvuNO;KoaNtJ`gaVDOn$VD{!_^LysC9+Y7rx!C`Z;%3Lxf5; z{EZ#8wJzVVA3u#uQDH>^x#x$T2Oxif6Q#DNkv~ML`QO@iahw0FhTIF=Oo~~Z+FY&jT7${>LcjmIJVhlkPsR`){UKx4M)z_GEGI`Z(Rd9i zdDuFG@fmdBxZPfGgHe0WU_~$J=~72f<;qp5Kp!OfVV~1YxzvNHVF{IddYtEJBQm>E zg1zq21`_(@o5AJ<_=A#aG}!80@&iKD;o^guabM+E_&Oq3u$?4FVAIs`SKPQ~n#g}j z(=I_ev7c@oN<`UJV_))r%p-5>Lks0&4-64)j_5;{OHrgqKuRqUDBwo&E9vLMVv~g| zCcGJhSn(IJ%nOy)2AX>{3sCdq;Y#n!poa!!Sn=Osq4h{3vo?%&Z@-WARpdM`FUV&t zHD*ASW}#A#YUfQiW}#3YMrFPI2BlPGMX8}h8bM`!!Z+Sd9+D-l4Z?OGL-F0y^!ueW z&5tLwlj*QWAvvAY@z-+cd-3mI6j)FuBR((2Ei-lKpZwgJ@C3QSKX16F?~7-ULu2E3 z7deZ63G~vfW#=D^BNonZ4d1s^y~*bIjr8UGb78jf9t*L%`JPDa#rFW~@S^t+L=xOi zDQxLogP~Xdv2d8H)G_9e0pW1Rr^~K3hu!FIyf5eOkzltWq0SWX&M(oc6<9Q8=~`|q zPJ5hKeQz!>L1^6fSs`%_x^c@GlsK*z1q+9WmB&-MrLj zxT__)Skfe!5wwP2$61-Pi9cg4PX~Ve&2#0#BIpO2zsAU!kn&wr-W@t>dXJL$Kp(Ti zI$AWWAifdVL>2OGZhu7Wo25xMgkcsX;*F9d>ecUI`7x#MvK%UuezuY3kraK%!;#6vocdIN6MwE4=#(>+j8j z2?!iDIA75m-=x{%H0g0@bCvbzMH#ca(flX7oSLedmS&Kg?aM>=S52meE1wmhZnK43wkZMNL14TfLs(F?qO9FarqRZ) zoHbN`%w(FYeh&OyX-u0#(RnumTvRDEn2&qVFmI>EOhl35Fz zMvv|nM*t|`?O=P1>qq+$^`nUE0j2?o)q>GSbi+5lUriKdZDPgloE{_i7$k6G0$98Z^VN+%NM&y_OD5<+JW zDvjc7vF&VNC8&a0qWqfJ+t!4ndX%Uh{H?ojjzl>=VBaj5f#6@5#B%43Y{V-!4#%T? zQ{E@P0hzhgw|EX&+GQzZ3uL6AvC$#=q$t4g5)GC>`>*AUg%A5mJ5Z`nhy68YZe~`_ zD5sTv*fuG_0(#87UOnhZ%yJW`$)Y1W4RW!F z#LG8Bw8yz&q6v7s!c4oa+cJC8hiSN(7t@ZD7|(#5cW%eBXhsxNK<$NvH0yFpNaXVTP1QOWv=IuzO2eq17B1)iU2>Vs`>SA7xVmw)?8Ev4 zH#_BQWCVZG$I9Ny#8~9fJ8NMWf*wOq%F5Glkj@{%)j4e2F^PpB~b?1+H zx%$7a*E2e+Dmy<~w^Ww4R+V?=IkwF#t{uF2eN+4wh=RFE3HZ;Dw!x_~VG&g*_r6X> zBvPMudlgzfde;#;?y)sq5o=$pOBSect?sk)iM-^H^Mob0zwqFurjVRXH9H;_aJSrR zt(83Xl`U$dQ=dzXy&$gC{#mpsMib>HwJ4F_Tn>UHFeByb^h|wjmLmXz8ofaOD?1z;xaVCn< zOOo3+okZ#yXH+L)kfRc_pNluq&V}X%EZG|JOqxk7&1U2dSK2igoV5|0xW8z@ucLvI zu~%rzg!7wW++`rc$!N}Dxu61#7v6iyZ>lx$LoJfMw|v9A^AMr|1e9|M zzAhaq{nt=0I@58aGzTkuZ)=8ZB43Qsl5CxcFTZWN3TJkTXSR!`x9K&l`m`+=4Thm5 zeRU zkR31484ML&9`m7rmCuluvj5`r=Gu6WRg2Qf9Fq|8`26$_87JRl=fuZhC$qJw@y9|r z&se*6)TDBsug^xZEiFP&dEn`CVW6$G(R4?aX)|jylPQj!zP~zB8-*3IC8xnofJ(0y zT+MFwxI5S_IG(GE8b!+rJ2?FX@bzA3UZv@!KneDF)mZWkylkuA3+BDw1aMz_(}vn2 z(clB3XiravJLSXEK`ZUGhzjK=c7d?|of-8!{^X`Q+pb z?pA^xKo-2L`ri6lmlKc18uSN}!#b*soa~csUXNowMzBuqvk~l|Hv8;%J`2P zoNu=`=}%9E<-Cq675!~11asSuU)=(N7#VPBf?=?hsbL>QMlQJQcxRva88(lH&x)sTk& zrVwn!(`}@-&&=VTf`3TVqHi1^tsNk(?+Kih3Ct2^Yx+ee!azj7zKPY;k&KV0Pi~Q; z22qYWhE+XvxW5re))ckB*LPCf(Xs*KiP(t@pR?F;sk-t(y8*I8Avyu)*WZFXJ9M_p zrCueCYMC4jy<0jP^_ciPZMPN8r2KzgfDysPGo@EqeJ~Suz8*hy*888MuTyYFZ7{ao zq_uGYwW$DPNEpSL50A9)$K{TWln(g@=5ujL^FfJX{*&`9m6BNoW{G{n5)IZ?)C!w3 zJ0Kzan$SxRW{4);B(Xo+eIvAGOQ3rIw-9%$6L88$G;-T~^J{Nxwf$-Ix0LsluG`V) zCjP2Qp7Lr2tAD1xRw51stUrobn~Tfmjnmc-yJG9NadgKUZOqDIt!y}UGQJd(+a@0! z-TsOtd&J%IQ%Xm*_oCx;nIFp{GgoXK{7c!^NkZ(&?p8hYs)$v$WfENQs!ifW@M@Sv#qxGQGFU|49QH za00_;X4Zf6X7O*uyi>rmlK9ih%MbZfkGos}w+j0D6fw|874bBG6A5qFDT1!^yW~7> zn?c}x;P3WW(!UZK3@wbHM?+V_Vc}a}agRlQCK!E-r7m1V!sb8R%gL2N2*QbV%29Gr zK#xS90Vl?CdxEuv1w*2gfg}iFlx}+kdMuH<064Uux?(LlL}I&$e}kViRY)8%o!!~? z5TV4{MZsBbBC%(oi1)wjOJjYCsGR8AgF54j!8>_m>#ME}xh>yh3= zmh)pm57s}Tk2G&UCH+6uxRS*bEndNP{ZJ?mNlH;cy+YOKZy`(?{VWas23YIcA!;=N zGWir~6ii#Qy6$~#T7sMyFoh2cWs*esHd9|FxfukNMmXv+KuL9>CTtAzSYW2aUHYVK zb0}BTvO?a4q#HYStZbE}W=_r_TSK5&*!?E19 z`qM!bMW(|6xx+4bptZ*LT$>Y;2+Nrb?Tf!&hNOIWXxw~4)o96VE&tm32dt0A-vMR} zm`VKxP8DrT-Guo7S$5cKA92+vVcmpe+L|=$LxwKX_@9SL*1MwA1-Fc{`L&*UGlKaJ z*QXdeNFeu4lQ*sYz?L_*_0$ix2z}21Y{EzA{eu|qE(yzyOW&>`|1OB*ZOk`nSH+Jl zL`GCYI^7L6!Gbm@g7_=Uys`o$zqVkk(OnaZg>w*k@}Ig^#{V?iF6=iBvlUQL8?kMf zhIG>>J_*n1k*zJjc0Y|CRznYung40@d(K+5EWQ*4NdLD#6SpfQH};Ck3L5uQu3DyZ z;XDHA+w8t2r_C2@|VoT38M+^SK94=zQ&$D~; zxeor&2J$FMucxC}6~*nXDseD`Cct*&-Ora+v{W?w?=-tN0GEcP5!J+Bv4oZ!I`nViXT6Jvr+W`XDHdubIVp~+s`@x85X=2PKQpvK`*$Lat!6< zZ6<7fNSlyy4v$ocJ+z6laFV3OtdLe=TJezuw0aJx;7P2pq?#T84Q7_!(3QlHWFODh zxt&W88ak1D5d2~DPe-Ty19>B9CLb&>=+TFF{rATm6-9aWkioemLhW)e7YIvYxy8Q$ zSn$Mk^SE8Sy3+i~`h8v_6d7cgpJweJC$KL6Ba=)Lu!K}>&{ z=J#T#2m%^kYO2`<AFZEG-dPMkGD||FayhKIKzZnkdbC)DnE}BJXlz^LxvpgQb{**>1yi%WAU`2p$WpbKhm%@QG!;ymAvDDUxUm&;$zIb)mKhp<-NP2Fg%Dt6Ie;Q&m1ko zK~t@uaRJySEtQ)(sRltSC+xLXOnC-3E~t(C!_kN%cYPJ5nF% z?im)ScJrseq~Dkoj)9=&*e+{-s&{qXpr!Dfjrd$ytUY(O{ZUW+Y;m)V`r+H31P5VP zUzfXQ-*~#tBEdoK#?aj=C3k~D#@P_F7>BBpGw)CZ}LkPo;$?J^c{0-iax4Ilb0atQ#<(x$T5Yh$$*asP_Qp`|If zWX9C)pHJDifNWip_s^0J&eiu_lMl|-4$jmloc1_w4o3>T(y(srLmwP~g>9_+q0ucR zH=H)|f|d0V%DZ`l{`bGA*dJF(9~}Wbvl#^#oicR6*S$`w|)&Fu6D^^Q7SZ-)gt9IGP9%_V=KAR7-K@BZ?3|s`9^G=|j7+L^bo%{r%vp*Gmb!>i zrN09xI?wUk*fxf`g{AoBTw#Jz5Pu3!C-5zNnBrurWOq)ESDp^+f0M>h z^$(|JePv&-F_u?oP9*K@5vmSmp7U_Hy}ui%=>zO~O7x4=Ab+dpoEbSjIuYqS1Ir(> zj{QJ7L*dkx8kU^cXPM{HbB?v6k}XbrzVJxcI*%UI|2=)ok})%im@qSe=4`)u+Rr;` z^<@+}PWa%-o5Ke{C^!py=#`EC&*suMLVw86ylVuk*gvh(rw3BLOoY;D;%a=ud%lvNym3!X|>Pwv{kD0(sm4#2gLT7Z(O+_giSdq(d{-c*N9RIrx zy(<=0XwT%B?dCUd0l@iL{UKg5SwYQ(QSNr*j(i9Lg1 zlbQyLh6ao3z)`c2O=J#+zI_oLg86d4}Twh2tli zYUDiTT?TA$et*#t0AK);^%v>e(>d*6E(uoScA8)!la|TOmoUBvg=Y+r;LxeQiv|-o z1HBbhv~{RfZbaVh(f5?emqaqhCjWew_FtQyD;1$?%Lx6rkugIVdS8giuEgY$z!y zRR-qmZi}3>p-QUS*&Pma{JJ#09ZrrH3#T*+cv{BrJ#OehaZA2gUd6jHP`tm*OZ)sU zmCCzpH~6>ff8!pZpD6_I=|S@k;(u!7yPa_Zxu1cFak9el$||p;Lv52XWFx>L1(U|d zYmaK9FarXIzNuSJM<3T~fdjp!3(L_TVfGYS74Ztu$&?ajSK$LE_F2zr=3I!)i%nh+ z-Exh)$BhVMs8W?t7?>+Z)y|zXpGH{#s3gSw&C&j&+lkU#t1OE;vogN)iD_zS z=~ZeWXA9gdkFVL^kbAtlmW87?ANEP#?=(3Mw>!NSd12oJ$PNwP5R5o%-cjUq3AdD>vRytkYD$UleF;VuYR z9D8sf3M;nn@fJ3ff-snc3T;n5+BuK>vNPfa+N*`@%fMJNRRx zH=j?{2-8o-D^$2T^=0)77xRyGZR@6b=~;YxVF(T~aC_a$rfbz8qkB+>M|uk6}qb#>3Nc{hb6B=0Z#`;MfU zjv-lvcL!;*DeW6cafvR^FYhMW#QCbP60-FQGM)UV&@F;C<2GAhK8vdROJa zh^k#WpD4iLsvV42YRJ>)2hK;gT4C=e&cwEIQp4VqTqMs`swhsVIxN;^6PMccOSEuR ze0>LRVWzL~B5|;5Kc)YS_kUG{ZV;Ns3_`PW)BBr&;JarXx#OyhC=(?o;2w{e?&9aty6v4L z=oq8}#SSy%yT~IYsA_(w{8w)7UpQTje_s$xz~h-Pu+NddxZ6vq_lXG&kJ;*zk%F^_ zw4`v&uN@>MYeOR!dn2eAXJs?90!`4*BA1R-t_q?k&gec9IeJYs`34O=y5w1)NZ7@z zQVmv&l5bS`LOQ=YuYWDzUjRS8Ys1LV_WQAJYBLyWO@& z)vj2M9x5;IrE|R}2mK+G02m^yEnfy;`terj& zgAEPqsSmPvk8}OiE27TRCVUg=7a-H9KGTmsbQvj6#+%;>Zj1}=y3M!e$xS=obgeat z7K-?=c5+Mb@DsGNapo=+sXjQI#5K1q%e^R7Wqq;7vbNlA?{cCXiT?3-9I)^1Wa+Y< zP&Si~{160m{n}p(>@TQ)gZ@|Rr#618Jo=-v`k5EF{(T|YSetK7_ui)We!AJbk@BU< zL~qZ?`fTgfrUvZxd7ri+`twAPf^xtC9Rg?Q3*+iDzM086@;l@`90f*4?`FHZ!ETa9 z`>t%`*~C9NtOy4BXilK`6%Z0{)Y=fAwHfZxW#K$L*2OWufeY@;Kfi>M5A-+lQRgMj z;tXO8Kmsd=6_%eDsv6w*t*hf;Vo1V~3z(K@yU`QhU=q8l4YlKx#LH8dOFjZW^(GCW z9i zx0r}pYI?ajn-qT$pW7T{p}USzFq#*!c=d_eWrvJSIU#qH5k?e=yZm9lRxl#kHc@En8ed?Y@Q z`ya)2h!$Ynmsf4o(I82-DVFviZ^kIz8wX}3a_@;ms~Qp;AN|e8DW~W9#n&mpLlxV< zG~rD_ew2Un8e%}O(AaPX4w7h@eLlo{n?hOnt;bSk%ZPZL@b&Q-IU@BOQ?17>z^~{@ z+@gEXCT`c>LQUZ#Da2dOB;+2}c*mFa1h(zFt;#TO-BT?8OY{LAt{$t&BDPZaRMuOy zU9np9r9%O0WrZQXL4N$Mel`4}W2E``%GV_Mg#BOrM)=a%a^-vJG2IZQ^vASM(oRi~ zgA$Ef90gK0-QTJeUM1%8RMD7_k9#Rlfqb_y>kMCF3%T_+SvtViW#-Zs`9X*s|7J6Z zr%)7$O-fHwH6%&(hcV05P$(sqV}kMQNYN4*5k>YiZfZTz4&Q6b*_~qGPW6a?9 z2Lv3m@8lE`zSn6~X9wmNN7iV^|FKPm$n5aU_$m|?(bL|&sbZSV_^G{zF-QN9yx%@b zHa0f@K0oBQ7Pk9b|Ho8OWmNu`Gy*s(H{-D1GwJzq7pqjV2v2~y%14REjOx$%0%@>h zNlwhFANZ&wtEE$XQLk{D)>) zm)>WoiTEV3)VTwoRAQ`T8V%y574|>0dF^P!afdYMbIWa%i1Q8|L9rqyVPRogv(>%6 zh(O)2&hFh!!Oi-lY4Xs;eRk%mu!qp3b!Q|P@5smN`YI{X2p-lKma4Wl_HyT`{&r}l zK~L`g(R39sZ8lsN#?YZ1FowGhcXyZJI^5meo#M`5Xc<1--Cc{r8166_?(jeFm;6aX z8bTl?<#6x0M-*STZqXnq!_X^BGt1p=7ai=`#-Cx1dC}IY8}{c>0b3Cm0(Zk2^w8&y z(~}a@zhUqrRppn8lypCReYadst0DJ=o)G|EtuXm% zrEZM>lGV(jI;h=WXrv(el<&c_GD`HLvPIX>f&g6qsL)t88{wE)d4@(TStYjN!MgD< z7^}-PQCLFUa+%?k_{-k$)i4^AtBLZ#(k<|ZKsZ96SB>t3%i8Wv) z>Q*6LY$jrwad@u)#MBY3-nKE4v`#YVSMZo*ty2l9)@Ld9y$AZhR>JIbCW-8uW9MML z0X6tBQPq$6rF$Ue4|oUCR==>q=XuahXw)B_i>&4Bv!Hk-^I3@sTR7i~7lNWg1X)1U zKRLdZxshd>BUH6O5a^+wm-$L+r^;_Ws?Ie)E~8iZDkAVg)v2SD-W|!JV&=bxij;%W z79;bg4Wbt1i|!!&*0HdfD>X77v8}~S{Fk02a zj7So_*IQ;Q?mXbQOD47w)(jNk(g$E!_)V_trA^R=P&sQTLJ3N!hAN zB^wd)9e}JN`WeC`hlQt{G)w=JCl0#=yv-rb^r5mkWKm1@q&w=J@}mfjX-zb%_9S7s zG1@}iTH_`T(ODbG%P_y~Gs@>bIF&u28o;n5ti`iWa#I6raa!>t!b%0oq)2Uk50_s9 zE>nD2XKj{T8^!MRq#KV*OOIrRkWs2?K|Mc1z?uo zCr@q+nq&!qwg+(uhzXd73Qne9Gj@R<8qBuH@9XJR#|GR4p@RGlXDd~hOffvtqvJnV zhr8+@j*@|MVRpCu##y(})gWiwRnFjjo`atlUOk?wArLw}ccfkuos#!7cIEq@*~U0~ z>9`?ceqh7yS;}3`gc7ue>}BEb@b}8nP*&+zccfec-K(G3H&B|WeTvL$+r`O$B$GrU zTWf4~&X&-#-$w5Ntvbr%7l42V0yrU%?K|J5m+Qj<3%nttloh)vxv$njE}P+k{83ma zIv@!f^)kQ~{ut=!kDwQ;_)em)x>+Fn7NjVnL`#-xc3{pvI$$e{>^MXiBk%?S{dqcz zs5T9k)PV5v>JgL^%%G!zJDhUS^3=ph{Fg4d17@T?jBU9mAvu4H&nKe|F&d zGby!ij!#v_%HCa)$RlDAmnJXTl&maBHX9qm0Z2iw@!;uXWonXP&`~xAH@$LQ8Wi}% zK9L!zzZXk+|F1;^Evf_tJv9{Ok%a_7ZuW9;y$}!|$>tMMjzmg2!EoSdFh?uE;%Fd> zcB|~Mq@9~bJ==Zu0mKoM^Khm@TF2&T2{YgO|56~p{l6AKy*S0t;(O}n65}}zyKHq> z#FyA1jzX0LSq@W^9S*z9C0&aJV7THbDE$tHs{S$YdolK+4rdlmg7%T|OW1%wVa-(O zhYKP}Dk7N=&@+%2Mv@s#NEj6Xa+LUA%IFjcXJyh);V1~7U7UG{%?E!KKce_Kqj$MU zMh-B1{&8+~ERvjDwugR5rQ2>KvQMg4wiQu!sm16u^A|D^M~eO8H(i;cK6PNFTvj$;Ut4q(JUT!dEQ| zZgh^|K79_&I2iJ+ueoWe^&c`}8%uoh zOGfeA`e4Z8^^Y`IB#88Iwn%>Caj{ubWctam>tEjo%=h*iT`wtX{o=e$jg2=qONO4U z-!S&9vw2Ye4uj}_@YLSHPBBzMe6(v!1|1ud%M^=npN;J}Sdejp zl>U2(GxR^&y}*&-AiEGVT3YH_xuCyRz(RwC_LmqRLU?_Mr#-+kp>7-wT1j-jOMm zOa=1V(sa?chc123sT}KAB#mJo@as}~$4Cp@;cc z^{&JXvZUw3nc!~wdwLHSI~Ru6zG`k^YaS0;CORfw!Ow;vU*#0Vk`CMXxmWHz!R$a8 zSl27-MB0B@w5PFpH1U93ORDv>s2}mQW2<69Ehba!P%W_3`PDW4Kfm_e<$B}c(h2aZ zyx;YzRgd+@FiPS4cp#iB$HBlY4_{HkZki%PiJwQ9my~nC94P@cfOwz`4wCZ2;teL! zx_%!g+-Hg4b>sfQ*;j;7OY6@8SNTs>D!wyuJAwzcO5lrnLJY@8azz;A80no&>G9nl zUGhpXXsp-3EYqcOxKM;wECt4gd1Fcr1gwB^=@m8%aXeZ?*t;kmbu_np5hi-{3k}#V zkg`@-*kdrPA$(X763&e);0*7|pp#O|6$`2zd)X6Xj$v0YZ!1&a&t1z6ZPueqGhXH^ zVpZsiki|2b{93M{W>xV(f-@L`ariPX#ze)EK|cU{Hkc$9tl61CIo1IzqJ4u3mc$Iob3 z(W-=AfafNfedQ9Ez$l%&M3#O-@Us_CC(3<8wt3B$QX2&Q%2?fO?J4nL#m_^aRG?@w zsCmlfq|Jb`AsTrCxvbSLVIgFx0{4ifm~t?RrU?-mxh{G3r0DpvSY>|@A&k~zovsY zb(+=FB2z#M3h+PryN)vF_S2q*2rO5{%sE$1&9Aos=A$qENw29r@pyg zuW!!5AG(H?=Ak0D3Jynu|E#ehtDz&iup-O3GHSH@Q~iK)X_xZH;r%QV<7hF>Dk^1r z(y4Z8h^juWt|NS9cZiU3aH2AHkS6;d&M%(!D^5ggnAg0sJ-rbnN$j&>c3jR3G5i?6X^O zW>!AF#{%2`vZrL*(!aFSpWIWq zHnCRMU~-k?2lnpu+h64DjF;=Ad~Q1A58XfVT8IP5E-_ohm=xu`ZKrSVnuX$gB4eUs zj5q<8^Tzqg?Qj2f1Rgt7E}bvw9jDh-;!hjvwMpHnJb7t9ij?WgzoZ|nWdkP5L0r=m z+%%L@i3B1g8ClXqr@>CrH%ismTynR)fr#PlvOCRa(>ts z&H*DOO5CH*MD5*@@Q_fW)r2(3GtlF=VmE}dHM3skM@FK78%P{`1*oy!6_D}@@?QQx z%n6(ycxd^_Q~RGd_Z3OE`SuKP{b~KJ0DAlV~R5RtN^HI&N4m?82Q^iSN+$OVH`6o@Yq7|ADL&_ZaX$BYS+n5B5Q95ZU| z8&CE6Y(gTB+7?K@=!;pzs2n!~A0y=@;f;@52Ise6mFd=?ux%>aH!@ZuLxf!livu5g z;}lf#&i7u9SxsOp`FjpgzLdywL6fbKvh74f^QHt-d0TQvCmU5DA$PHAltcAoQc< zJ0on?DT+!-MgKt@e=l2R+249nl94fz&bTK*=3PCfv@E}|b~@^1HkQiqziVJj^wENH z(mms~IKv$m;y22EcvZfNHbAWUW>r0*<^mka>ExN`rD*}53E-Vvy%V73KGS=<*SX4^ zE}zMjCHE@UfBaow-e8;BzlVEVlLlO8!i9(*1*mAs}y{mHG ziUBHOKeFA=6Tqf?93~>rACv@;=tkj`KyPVdz0fiP^S?yC}uj7teR2^{L^eHb6OX;oIrz2ieX>xz}d;rGi-aoq!#HG4YD=JF(`{Rn671uQ-^KPg%0erC+6t_#&PtC9C^9)UoD z|JI9#(T33r6KbrorzbBD_B-1B`!RDODyx6}YOvzi0ba1%&c~UfIs$A6-k0)SfX zC#d1d!i*Jg9SOAqQM26a4BRI>pAU5G(mBO6;sSO!xw$tEN-jb>ZZH#RM`htD8!|+X zOp|?8C{ZRZ&EJH5&x!slx);B!bK0`S|7|J%B%jW>lD;RDah?~~XjdBW$Bl>cDt~l$q@+{|`8vjxe?Ch( z1d&e-XkS7eAH3Hsvt>V*G{?ae(7Gr8;ZkxWE>1L^$#!xzjS9mTQS-(B71D&6@X@jd zO=QnH9wful>XMIVE@P?97M1d@mS&_Fk$-RwyH}k+SoG6m4cRD-mXPe0_`0`jG`#8$ z3$hD3(n{srS@j<(cn3 zVu~zb*70_bxKBNag=pB#8fLj__|vo+*0oy=v+sStV~zEoJ=Cw<%pn4oauoAo^IlT0 z9k(BXQu>}453nQD*a%r+er*33A!C~tOI-t5lZPAWSjpS|YP4^O;}a{0Z&Hz7rKR8) z;xWwJX0YISZYh3J?A)QxhjeDRHC6Ea=FEA?DnAHW^g-r1d}68)?U>cbc^T{Z>9^hC z^4wwJrotIuAn2zn#L=H8P$`qAHl4FHk+Y=0^*fYS9M2TBAWk%uENV7#MheOESlmi2 zUz5Z}S<;FT%SQhDETJ77y-G{Wp|YSAC7-$@Dr7;W#P9x>$$hMeQ$(QDHmpp;TyEPe z=bh5|Wa8mu0|XOCKe}K#tU!K;N)`D#-A}x5_d@PXs2*jmt&$#YqycQf*N+)%(3pah z>Q1^m{}^1^q)0+MM>s|1Ge$H$`F@%!zai7Ac)!5Fo2X9ma^baV{?kJyd>3`J-wZ%n zor<3KgeEb8jf|vBeQ(5P5^7>nN(5wN&p$1>X0~7!ZD%2Fs_o(dB+wpQTB!sJv-r2G z@y~KsvnMRrZXd$!FUwQsc^DVJqEG}(wL}UMVNOUCm6cAAWJpbo{Zd1)`IW=!qk6PB z{xmOcuPDUUyAb4ob^Q0R{OovJ$tV#qYv!zcJNI~debvNOyfIyr3ODQ}k2)zvPIjnup$dCpY z84g_m;%>>a2f8^oK7Duho0qOHD^Jr^Fde`bx9xMQcvyPCJ2buX!~y`x4{56009K;w zdq!S}1Rcj%*5s=Y1Bj7{dGW|CQ^6iR^mRv#fVzTSlT_uoRy?E0@!Lo6trf>x>-ocn z-(0^8a9=B!U&qsF4$3Rom|+u)DfwO|&`l^*3Kx(h`|9LowlUSd-wmCWEJ;8tF*+Wb z<1k*X7?}I$q1$yPWeW6KBb;#qfq~u|MQa~zNui%S0y~cMXbk#k3FUymxjwj70;@n)&Qx46s-)~klU@AM-@0#);c z={Vd_u4yEPlnNHd_GvW!Y%Kn+J|tQanVwmX@ySQ_m$q$(9D5U-Hiy3Go|t#O9QXV* zx&CEx+VRMTvmmu!Bu>{m!MkwE>;Cx5rEP&#yW&Fu8Yc1rqRJx+!uv^#1p;zB_K_S% zWohe57_jP(Q2RJ>ZBA5$(3>IBF{D8TYZImwcS?F5iksXduTMVN>>2#Vlx@^FfaQmr ze<`TIDM4js&Q$}}{eV$LrG@wC@>Y%;RccF6-V`Z9N#6sWIsUHG+ki6=%pVZJVb#yW zc;jG~^HFgQxzZfVR%bbRhn3hB7D1QSjv>JsWA!F7M{uyWtFE-uucg~%K%alVoQQ~= zIuwmPwB=sp&rcG9X5^5+HlG|7#uUM@7>Y5iiEP+)6Y}>y;ITR9PAXw83y@~z4eoIv6| z=cs+GK6V0lR60t9FqU1X&&+STI+b;7SZZfQMdgvK}Q2T{q9klZ=%GXsaEv` z)VY!eU3qD)15hT5iqq2;o*1wh7D^`o<=||Ygy@lhS3frVP!2n8NC2Y_2z-t4_7B7J zM5z8?w5lhglTI{KG4L!IQNI{Jmnr- zwn!CXeH{So&imNAGYN$E&5S4OQ`7pDAVp%q`vb*<4tJ|SYS6;T4Yk1SL3>lDt6!V} zL>v=j-<5=stSiG*@XzrF$;*0DDEf-alO(V`R+T+Y)$_kL+{mKDLFSI`-v!7@%4*oB ziIv?uEj8r{H#3Zwkd4Drs7$Z_A+gg(yaO?Qp~H?2qi>X})GSfC5%%@5EoR*?sRi1d zBNcA1CKL3~NlHu0L|V9DHJ&_FdIQf__9m4J`ef#>F4u(}15$nTZ(747Z0Y}S90PF= zs`OJNUVDLyFCTAaDl)NKY8n#94V!i;5{%d~S4-_{PE{yjO_urG^nuRO{C=IC=TATZ z6QkK~P9Lb2uk-Be_P^fn#!}sTP=1D$hK{$!!{0Iq0vR-^6s(7TJ)yp0RC1^soCu@4 zR<>781iXu@0t(hdMZx&CwkSKTqNtuoajXJ_Z z-KZ5^aeACFGS4i%$37n>QmQ5AgLl-8lbLei*;LJ=(XM}rB%$!$1qY=v#;AoO^L;9n z_-*yk{+d!P)l4S+@`Sgp*1`jCX|*(xX^0L?3W;qbqrT$N=iZrHG)- zyGqHl;yIL;kO42<)c~b3JxuW5G#9PL2^}g=O}cLja-NN|`h{*wr2_6YjyXem)wheb z{#H38l>`Hah^%d*u~P|}?OC7Keik2uG@U1}!{UQ&fT_xd8IMp47P--2R+stMUhC$z zLidEK^6zC&s*9ZpuZt$@MV1FJY@HGs751h&xf!tCwNblE5j(n~E`08@q96tGYHXs6 zCO4^8@dkDJtUiWGR98q4@QTwi5^@Ln+af_YSu@^AL4rST>6D$v4)~TYrFEfvyF$W{ zM2JcthRwG{$Gm><{BxaX;-efjsqrjM68Wcae1_1dg(yt%l$jZB<8SMql5o zlA*DXK|hR-yS6GL#F6lw_r=dd*l3w|UH6)sF~YJ$;WCF_pZq%_g`nfwpx}3p$Snsh zyxMc<9)wi^N^67Q_GM>oU+WW#;0qXjbOagJ9S4iGmsiI?@blJpA~UVc`YI7zZ~)k8 zm%;TYlGw-U?e&H7P`LT`OG@7J?jrbLBZn7=jUrD1(x30rbgE86{c^NOVA1LQIF+S+vwfWU{~iV(6u3U76IS(LddgE}X{9#50~b3j zCo~E2s%b{|nqsP^s3p$1-1l_b{dRI+x?LFZW=^=9v-FJZtlK@E5|C>@2Ld0w*@FA4 zS^{GR*@F6Cz2;1ZEGU^oziv=f}@@qi6LuahSXq>33+V?eVDy)$A&zN1_Etzbh zjszu55(Epcd}+;6Tv4FNi(MF$y~--*42_#lOKoGyxi-H@7BDF}UTW2KTy&EnIx*G zqAdah*Qhx=bUl9P|DbU8bQ(NxjZEQJXThv_@XLo^FpK0;6ka*vU`uJklT73-3P`D= z^4?(+lpseESi^o9{msC|Ts~nby4~TSX~#pwo}+SjP}IhY$?a(HzD$kZRpF1_0`d+dD$&- zjwH=H7O;B17izn{w?&6#LBYZ2IV|LnM>3D*C@s9km7!fFBrgqS!@fTWZY8$iwLvv* z=yzBd(HR`kktAj0W4Ovq_fpc)ccM^{pv?kHW6|^ZR$3|&qnvjPA{4R+g!^A3$-wJN zSGzHWs^l|k#7B~7doh6LT1{wz4IIp^kjpJfeplzwGPU>EfB3gW41%9+3M924_V zk{f8PLe($80A@NAV^ACE$Eoq}&glNpqu+NGFi?u&Ld>+YQDZ*JQ>F?ZnaA;zVd=Tn zG_%e~9^#Rr7kf9!e)Pv9RiP>CYA?5=Ay zSO=Cl|IXUalVyJXY4_ZC_+v4hs2|Mi4-b3?^zQn)$iP3En^mMxis5+D>}?0Mv5K)3 z!X_DVT@^pFZU}Aj*s8d}!+s`(Xe39jElktkMas&lQ ziQdAD(&(?_YCo!k>c#tX(q;SpIUs`#96d6@Bk>5Ae4NZ7BYUv2KDXhY*kUy@YED^B>U=ah~(z|7!uvw{n$=j+sZs$)PXY zuZZKFKlFY8ZFdA{r6yYQ_JHKa;tT&}I*>3ek=(isvK?a3`2r~PgC~AfRWDj`$Q9KA zE!1mb23H{RT3X?qlu$z7`hkaPco5Zl*#RTC#mK(<7)Ir$VNn z#ru;+SnMUk1me=tW9F)wPwBV&nyb;}r&Ntoa@i!}gf>>FNm1fx+9XZuapj)#Tm;7) zx|e1ImJy7(;X%|R61sBHT9lb}lmuZEurOnAozla4yvSKjb#dJNsXuw^c)MKUF_x{e zN)%X%kR#rQOP|!VUiIyQH@F; zBNGDOkrjamk!ULg3BipUBxFXkm@ebOkd&(EMujLA*bnF8R#cZnp{&W6y=(0Jn4-ptY@}G~eCi_eu?oYCkXN|@i$drf9c?*KAB&YJ5 z@@6q&!*$)db7#h(E<6zR-)S<0SUWg7^HLv%k6_Gg${Y{s&OQo2%73QHn9;!(F zGham^HRc8^G?S@O(YU)q*0nS}&QCgBq>i-oDCjXM#cNf&?qWmpnZyf7UGsI7bMr&*D&HP#M?E=Z)%+}o zy%|l9wvfg;kvW%ZT@kVP-e4Ikp;QzLo|b=oTIpK+a1PnA6`7lxwMP-%DJ3`d(gkFo zWG^~vpdX!~P_4&`GJMe@@fg2(xK+@OgpWpb}ki`&txrFl*> z&)b3U8!uRb&+TyLrCoW2AK;Vz+w^?2x_j$ro{p<~h{&OUDVk8o2M-p_(-|g(Gc1=B zt`HhE(!$2MVZD=U2d)ba>t@#2Y_cDFV3!0AwY7nE7nE zZ#wE*GKMC;miII{R>I5g?4sWH zF1zxVcENw!TQ!OBW3wVg_uW_weq3=;CHxr`P(@qB0a);M&WQz6=^i*T6$qIu@9&|& zO2tugkU7!*u2Vu1lHg(2p_-VnLZHr+@j=;LD{tckz>b>bFJbn*j%$v2>yLq+_5}8} zlA4@wU?CGPZ%1Pl;?P0mG7Z`<(PD+!Kn|AI3tVmN0}H58ma==jsp@U!H5nqXTUDby z&rppJGg9>2VXtVppyvtQJ8j28~kyn)YaB4Ri|g)p!4$cOf1#a zG0=GBC4)|QQ4t5~T*eB-tmo5krX;4Lk4XQwNat#RU(tlahVNBw;50a=E>ZNH(+V3F zHB`>4G$SuoS$Z)Cj^Ob0VJb0p^qw2t&!Xw2ox>~h*Rl-FnMKj&IS>f4`Y4gWAm;#q zp_oB0R+!jTn}0-&xZYRq!*jM}ESKwaa_J{C;KWcs$L7cpl#}6!v|6mPTSeNWF?33B zf>M^>L8Q!k6&4TlPNZ7MgB+t7J+x7|8H%d+`L49$0^?dmu)6TP^2!|`VNuJWvRIzD zwEPR>3BGBqUW2F4>2A3ta;|2w#a1mzxVA-4eklDR6Ham#JdDlRYPwUf{JRsBh~UM;PYpd?|0cdxwiy0T6w-k0D=`8A)Jxc;BFi+U8N3N}gjW{Y<&{ITYmj>m80)#+d ztFPUrG@}P5%ghOs^GV3-bLjpH;Iq_-tO_unv=cc{`6-Mdwp`` zr3DoOC1k08uPDTuPB}tM@2G)v(>S8@mzT(QRB#HGtiYEn{9PqPFSXEY6>df|+gnfW z`?jcc^bT>YIYx%FB%GVE7#}nE<0)0okacc*lX&+UYQATVAnMIWg4v^96Nn191Q{62_RFIOWnEla z2q*(VvqER6%PtmvYpEnYM>|tNu#OK!7^jg|blgWzP@txH;Vp*eDJ<_diW%Vhq^}Fr zGYlr;_n4obPn4m|RPeYxUC|5s(JZL=1veu#b?x!5xuu2HX0CoPFnX0Rb)3dDdK^FQGloj`?d zKf!RqtNUF4Cqp06s>J^PLazwoq!`OCHVjvN_XcW#KjM_pft{;uU>I`;O0xhQ;O6A! z9oWtjyqh3I_*1k*aYvmpj%{D5VVqqOmepN+?!kSvbGnW4Fg_W z^2!6oo=F&RdMftVE?bhe`Zt4EQYh4d&E=Jfl0NO#;^bqJrKjdTq4+wMK>6+OqQSu5 z&xb5UjILeU;~2m<5eLpJ83lwP86wB6riFO^srs~cnM zAz1=J)(hks%B#xTs_@UK#>_T)HnyZ&Fp>`6UMoHF+kP>3uj;6t&{w!&XXtz=Cn~zB zvQdjNLird+7D5)q9S+VhWgKGZ@~%PHsVqNYuCB|_T$QWodK^-w2$L8^>y^qTiM-ij zF+g37>Gfi<;x2EiM%gQMclupi+CfDks2tQct7M*BCc|cCUF8=|EmI$SV z&jGw~9@rH|3AI?KwI;9B>C(RprZXX>)eEe6vGdQ0)bc(Qvy0%O%%)F`k@ye$!QK}gt?F#dbRa=;_TchFTb-lO7RpaxccKL?(k>}pqb)1eCG=g6T|9Z0FY3~ zC*ovJ9SBN#S$_HiC43)Yz`7=0<1AadEM5L#NcLN-Tf0aF6steuX7x<3n~bIO8e~cO z-6dH5V&&7o|Ko^djdX6qN-zP|M;9(}s@3);XJXjGOm%Fm=m6?gE9#SPuu@odDCg1! z>pkMt9{tQ}T5W5erVc+lcDTGF~+(A2ga^Q|~p!~2yNbpx__ zJh=!6ktjN1L|z#)owAu>oYxVw;}yymG~y<7=c|xb#AV=SvY-h+{jAIaf)7O<7a%Nt zKXIunN_VB&n+=@ua3^E>;bLn-xsHu##FN$4xjrT-VIWf@w$6pFAv2pU%ig%ZLp|mN zyW^ku;1p>}f)({0)Y5ct1_kT-m}G;CE5`EnwM$}Sq3HWw(oug_+05+FKI=geNwKwe zM3q7Q9Y0v1a7F!kj>@6b>F)V!KW)Lj)QI=87{W(;B^}?Ch1O#;gm?CeU^aG(I-VOM zGj4k<*xH)S-xSPDM_P4i9K;Qw3dP@rnhaWBh z#c)rLkAU%}vz2tEeXOd-QujY}>g)Pb_vz8*7l2OCX-<>ZE)fX3*BY~@y`FuxC9%&< z`)@7@&+}~-D+Zaw$mzF-DtjPnW;j=$#Ln9Zh&y45Z0o1 zKECb`Ytc->QTm*Y7;*{l+#SoiglCHtVrP8nhbpk)@5vcVHD>Q*%FNqw#SB13L#u&x z3-&S24^zJ9_Ua*U<#xBRBU>S@RH^y|^WWRU094q{x2~oE6ZyNYD)?;e5_)?>CxGsq zPDS~+R-b3*v;1#%-ABE$*T{(Fv!uBsu!}a8Z#V1Z$*eC+YZR%jP$q9U__(<(scF!} zlVd1}Eag;`KVPK}Yf-2GyjI}aedUMW+E;r_LX#TQI&3ps*mb|BFVtQAG_ujzvXb2{2(@^} z(@K^@C_`~dYPa2{2)}X-s}-+Y@+jh!#O!-Tdw03yRx8vN)eAgyi10EiE6v^4O4%gS zIVsS7IY{l{$JkQ2g7nn@@3ELk%e}t`z@aakeo&>QeEv+gu|#vHQVngsRFG3Qv0T06 zX7R-DhR?BcQLp4`;RNvn4K_6Z(>%=VC!ZmKmO%BHzn*O;())s!pn&rBbuO5KL(WRH zYrKUOCW2Ef_ongHu9#f9!CitZsN~)$p z0}NC9>qnV^OVKPd6Qa}@;jD+1Ju?d;uAIn{v^19#H3xD_$EMZO4Q(4)DN`Mz__@}% zXr>)ue4h~ZhKv#ZrTI6S3#RRLYV36`l)@5{&4gWGvJeaSzzkhfP|sxx#`=gGJp@~{YhF%R5jE}!Q2 z);;D+>o4M3YA{HlO1Bc9>>CQ<<>C;NE_yy~i06eRZx`I=FD>N15H6$Vxw#}OoyC3# zDIgZw%q1p8QiOdRMQoWHmw)oM77lDhcsLRjYPfm~@S4Wg>ye#XQlU#seXOU4Ru7T9 z7%r-rB^_G!eKtH8{m&J6u`>*`dfVFCe!+eE*N-9maj_$1^y9~ml%S)6Na9Dn>cHET zZhVGBNr>TMhW>5a-4V(f5Jc>>*#kwD3*Rhn=cKKs&yb-+@)1EW403*5)PS&SPdIuw zpmV2al}a=MW7K5&@U(DePO}^pelawl`(~6gsq|naCs6n9t0n!I7Qq3W!v5DLdra)T z>P_i^Y}1YP#+}BxWSk-I(BAxCWsm2I3AOUkyC}RVgI~&Mjh(fn3RMP7{MvsWb`r#0 z0X{+IO^oi2^PM;hUW4V72Wp7(A@CChO<3u73%z;Yn*7y_t;uF5jXr~g8jayWk_9#o zhz0?UPtmBE8z-^e1+s z+C#iFms*w$?;RQmV30%q`)1W2I&w)aGcQ^6?B374!S6CttW27rT%qw;w@u>cx2v?B z25@weCQvO5@HW9e{J4ErNr+D;@z;Usdzt>cPCZdb5l#_G(KhgD^E7jF4Rc<2UPC&{ zu|t8rL%v0e$-(PSJKxNCv|63=RZptt&>(1{*}SVpU`{*=FL`W7)Pm8_1$VfjwD@d=7YDkv|fIc%70W91QCt7V`YUNVwX%2=L3Pulm*gDsUFYS9q~_ z{CvX~*twoC`=l}iv&s|3g}_ow_614jQq3zFK1fJ3c2*LTG*F3T0Dc#llgS2+cxLIfGq$$M(KH8itK>+=_1SG67A0+#77iUPF0_*fi;9xsvzH6 z=E)kxbb>6FF4_^Ja1u(b7%TeOq5+Ma4odC+-Zq#ax>159on@7<_e5GCKk4ugLeIm{ zwk|)<3#gqK$)VG`IntZ^SzGcWU$M}v_j4C^3Yv!p!ApA2YF@%60LStWrA>k*7$lCd zSz+f6fKHkwDfXb(#Q+&-NZblFS{q=3Co5q1ZMxq-(d(YKBI+7&dz9$$CNOGYBjUHURT$c!Ue(drl81A}R)T0Dh z|8BC+J2AER3T$!AM*nf)x%d0y>jN+K@0!697^lKMemadAvNLCkEe#NLN?fvQl+WK4 ziV;-%k1PD-m{ssY)2+Fr<2!Yjp?cB~SF3r%>9fP6Q9$iD`nWq-(tM#s24%`Q z>!d*B|Hre-l?eMf(t9oME9fV5Su?VET-)ERcPDcGVVXQ;E7*DCDp2RG2k_B^_SSek zj|>xZJ>14j!%>b|q-&-EmwcI?z<(2JFkp)Y&#;{|1cUXbNJR!;FvQvF2hbbqdpEJ^ zoVg+)RS2D5^m%yD4_tk=5|!-*Zev2k=aJ0k<92J-Y?&j9Xf%eaPg_my5iiU~9QbK+ z8v0r}hS^_>)TYw`vD1;BV|p5Cf?ch47`btt_Hzki0<%yjk*nWl@HW)Fm zGl&xpbr<(CtJ~lVaMa{IpBrZC54S7|RB>t{Ugbu|+_fse) z)2&jdR*g_h^bk&L^v!QNy}#*UK{do~Qp;X6Rz)g>qS(TY%R(0v*Doysi6kU1c!Y@$ zhPQfg6K+gu4Zh{nqr29X=SclyDRYj12~r7W8`M&OhKW#(C6$oD(>x9lS#oJU2v}6-E@fL z?2j1R0mM0O*fD%CzV^|>7`8mya9VtG&5)kc}4I_srFY_4*%1 zJyTDt&v&-JYmSsiAm-0X>1K=M`$+%i;a)A#ilWu|=0O-9df(117+@;{fLVLZkY14(3(3Nlnar~jh8sOWRX zgna(B{~%fFY?+Vx*oFHG^kTLnF1-Ba(ybo7mMm75XaZfj6?nM-63*4ilxYLnP3NS4 z=PH=vZNY-5IO%V@p97m5ov?SaPgA78B{6hpQ^zWVR;ur zeMTwNsI<%{aEGGfg_-Qb554a(y~gS`IF~<10FlO)#^W#WRUQLq!KRV(h7-8`=;k!# zx4?M2CiOB>Pi1JOX)UVnjVBG6@0dV)*Sk(WuHK7&!IjE~w79%-yJs$q z%~E@1T#?8`g}YO=>9^+5GE?-mg|Uu|nAbQ+_V8?4nX6ibALdWqHOhSr zpV0W?oUw%fTD(A!;O_2Hpt!pg zcc-|!OR)Q$f97WLkjx}Ad0N?f?IolrT=1?1+$6AxBswSMR2kN{#xK%tE{T2VTQbFm zFPJ*Ks10~9X|jZSgc=+GSA;OfMmX>l=fl*e4+XI?*%co~6swF;K=gFEk<>8!cj#vb@qnCU(;J_8x;U@w>P#c>!H*f3Jn|m2 zXf8Gy9v?|na~`P2Mm5UiUca~{I&3~F^d`B}_^>SWKW<zl z(5z)T^zO2Sn?-W_$Bh8z?{$V$!eyq|wp%XhiB zt=i9nM-YeQ+DY|r@}K+-B#AGuGfUv^Zol-e__4E0{c_(?w6~2aAl~cEh5M;OEb!9- zkt?Bqu|Kc47%gp@Yzm?Ek(h^V!ic(=8P!Y-GG#`Icr}HDOTRrH?pcR^SJ=(p8v)@i zuwO_GWfP#3`vtlp+nOVFSnDHpnx=?u%+rrAAzE}Ot+T4AEWft*R7&|>DyzLj#d!Mh zNLu{gHF;ZO?`kxn>sE*te9wBwp9U6d3e*QKRK5&Jy-GH+{ouqkPMBC)o7w~pGqa(y z(_heqlvG)ZY;lGv{D*Lepj>#^tUKs!1Ulh>b&UMX-j<)1R?L*?1n3`e5yMI>iETy3 ztE)(t5U34uppid)hzV@1B1Se<%YQg0xqj%&GK;fJo?Ekp0od-Kp&ej-^Y(t8uh6*2 zv|S&@1GM4#`s?HN9Bo2vP!FR3QGWP(Igr{hW@tbb(!)Z=eXePZQ-YgkgM^P+F-JsKLf=)uGC zhr$0ys{IYU4jRYW015*Pe!~5RgPhm5`=~VfX@D-S0lloA5eTkaKO$iV zeN6$nO5^Z@;S8R(R5Hl#+{}XlM2mK@_sz+t{RQhu(okvsK8zHSoUZewE*q;`~(?yqZZk%i8&d| zBJ+mqmNpgdzOw}ZNDI2U`eUYSK&oF`9TkN3+8n~3z z5eOFy(twf2II~)8v5ez*{)7SzQHH_c(Cu^A=cWJ<4}bJ>?V!$wY9SwOO)AI}nbKpE zqS<#deWi5`L@;YxbX}|brPmEiBY9i_$dDoVHice54d0-WER01wj3!h%S+js@#S#TW z=LL6IxN=U5?C2ZTas=pJG_6i;vx@npNGRP!g7C!=J`&EYqo3%$TJgFGl z^2s&VstQ0Ah1p*SAwNQpcXM2F@k$X*XM+M&GBBk%zsZ{b0s;hlf>IF}`oDD5nb7cR zE!}Y2Q|vm~#xg3l!-NJkq{>B0+dNgSBDvgD%HubC7?r0=OpC;cx+VFfj%Ba>%o7PK zq3L{qj6``0RZ=z<%?%85D_9{BGekwVpw(6iJH4%i2}K=^!b%32qv*!FeoH+HpW)xF z2WM2H?K|lUh>%cxqD7?Fi$e$#09r>xDN)fCt(~#}=d@1uG)K@{b8~#6stW9VY)`G& zz@CWkTkG^%HbWEr?TGm7L{C?wFA$mb3F1=Yn*iwoXHPT=hW z$*{T0f6!|{{QN1#rm{ZnSl6j0&~JKQglT0C(5tCVl>1ilX1?|$in_sozi5*VPCjz0MJ4&gb? zkl!zmF$^zCpK|3tv(Nh;hwF=5(U?YEVB)w+fA+?r@*PobYpgZUIOCl6T2&Ggcyu%n z>z4@UNtcA^NMzZWKquCGJZ=unj=p3nO!7^jhWwS@{{iQ{G7>CBTL^mxudH9{6UhD> z7N&f%Xavnq^f%jwTpCrwKWLca-;#ci(N6rJ(}oYn4oPlYJb*t4>LnNyGn~{#E0tvH zK8&dweDXe2czC{02X-|-GCG4@-}AMWx~i&Z5V;k5`pv=Q2Es_Y&XD%kWC#TE&G}31 zBEW(l)chwkc=!Eoe(@-)7cdzP0=kFRoj%F?`UQEDfZcJUHkjxjN9QGNnBfx6Cg!rB z!L8SK$XxN1%j9o$uskQHPv-O~tIJ0+%2p;XlW<<7>~+5S_r(*E#Ey0@7e9HC=-VXU zu9eHnl`9!Z)c45{IB$7EJ&All^qHIt4F7B@4PS{4&6!k>JfnEok{rByo%2^N;)C8bR;k~?$X>>@n zw`D%Qb0o)z1Wl@HyqfKZ0d^Ws)6N0otk%4;cpf% zIb1aP)r-_C!5|}tAMzsdN?Oy1lz{K1!n&f9S_-hOn19DQ1KN32dFM@8%{p5yxiP@l ziI{(}u2;qKfsGG+8NV{TL7Q;~3+Ks=; zf<*kfhXPk9?lUE~M3|nFgX@C@JpI77{QtL(;W9 z=vLH!V=hED%pCl<_5?a~ct#z-kSBoWj}}no;(3j!6Td&AY&*0OGn7s|RE)9X0KkMU-IhEHj9pvH;B zfF~nO-Z8xB82j1^RvyrDT6mMb{`rINN;N)Y<71i3LIi+9-K-96NGZRY7Sky z&{C?<*NGElgOe3TxQKV?^O0E^#oTW{Dok)4h{?1=oRVo5xMle9`qBzCWijDc4-1y= zjcWaVNq-#3M@c|p(e=ipv-L(=6kIcmoK=vI4v+;Y3}f%Tu>nGgLUb5WCB+NPgY|%> z4tN4RjGyM`zY-2VuC=cqUvzzp)IX6oI1!;NqD%GDKgsrnTk*7`Qxv>G`veZG(>qIR zS(_J}-`I?d>qS(qFY-*B!L%8K3B&yf`Up$)2>wL!<$%Hv)-g)Nc@;j37uJxLZ36J{ zQ9s(Ih6nmQQ4xo0?zdRgI7-ZM^*cYMnh;O?is9m*O+|sHhVxADTMr|!6onR`^tT9F zjjXY%@K(bT2%oX{lpaDy8o!83(M&RPw@aE;+~HjGTsiS2I?N*$ZLVgqra^w-is9Cg z{Fms2YS$~4bID5WGe#%m%|zXvs@^A+D2NzK>puw10ekmZ+0O_cX!*V~;OasR=yAKH zONVpB2+977-J2zHRi-!?BPwf%c{x=ylKD*+9=sXYL(6}_ixq5p_cO{o?l1+?1o8F1 z0xod;r9-dY6O1~IiAhOuQj~d$sWL_9*i-E{H@`&5(7~?nOt$wEbqpV>0de{I!$$ft z+@rC^CL8HA^fM}vpzGJZu1ti9bI4;I`7|(BI5R98YErmC%m<$`;<6NusM5>O&*o0P zVeh^^SA26XPaLltPutg;$kXU*GP&tq7dTY|-ylG}0ouhiIV#9jGL6J=;XLJ`kJZ&A z7ys$f&26}wInj@&jm9dS-?SIaS3Q8fK+|u6go__{OSh?{?i0;FQg z&|#$NnIb?J=`x9;1uuG(h;J!B<-EM5>Pzb_$JGY_uOm7>Jm3I&+Uo6nkg}>n`Ui^vwtV+orlvq{|F^2=F?%+z*ar(j^7^5_XDsn7Aj=p|<)9yF zCF-W%zAPaQyi&1hfalc6;hf~|wEa5c3SN9(?L#FtDgP#`%KrwWnRNg;cdDSGW)p z?oikQMllurax|zaSGx5_2vycW1@@z(h9XuZ2!lPAJIB<~f~OW!CEYZPj2GN(=P zD79dvX`si^9&GJNe$h{@@JO8?G`fe7{S)%5rcEcws#QRQ$~r~2r@ZSMnQeuBf{pn=LqPDra)GGD6Y z2??2|1o&(xiiqOzemW$&W^m%m_OOxYGi{Aa>J-b2Ev}K0Wa^v|HOEZpXR#~^wzC_S ze6oRac`NTh3yzvuVAb_sIZpR)g1es(Q?2)S)B7NnCm;Zi6-;!?bu-=f$>sXHiKF~> z_%zgc<1{lDMa?ZID!Z=Z9k)^u}T?=X=4@6o)D^YtV>%@@HsJ0pY+QB%I2jYInSC*h9OJw z@)&n045CE7FfHPZ;sVlCcp!E@9a*nfnv?!2ZWN1L&ZScc?9=SW9#!DZcM$EZ+4njp z?2*t_(c^;du(+r-576&3#GcY6&ABSdOJq!kYKbdzNw2N=O*IpCRS(&qXFir7y=Gx9 z;_bZeEEc1s703&}ruRR$}57dwFTIC`)sTgAq0(J6xScR|o zTFs>257!J~VfA3sW&3YbrP|Trg>|k(rF^W*C`-h0vei2$G7P5mZSW~83lKTDeF3A}c-#56Rg3Neidk@ae zb(_v?aRKHm;DC_BDRd7=zDRF?c9|rJGp)~n{z@$rp*csW%_P`KpE`vj3G4k~P;$L} zy&Ov|)MBrmrUQFyeEpM4LmZ`8-M8zCUktg`bN1*pM~x8O#_kd8mzK z=GMP?C6x@Kb!+z`6ZI9|YbNl>@#EPP24BtuSX=q0t!XiNsMErg_cx-qR4DIM&O=Ua zKPIke(Va42uSQ@(@5v|>jcHNWVujnn7<WBX^bCW6DBw3-*q7_qWUQY)RdWLX|U=%H1 zdkQj7PhMfM+4{v#M9-#5!+Pj{fP_v2?s_?e)9G!NVSl3MRzpZV3_eyNpAS?_+n1WP zz2Y};lE@ciRA&rJ{45HC`|~_M(1^N%hRMNSk4~0ZD!FGrLCiE47P&E#FyB2?hc8rH z0d^R>`YWcx8NT%yLX*4XiXn!t!mk;OqFbcd*1=!lv%)0DKO`67j1wbY7fBaiI6BV4 zTOaJi-m!8~8}wk6WTP3@t$u=N^k?Nd@`85uX$%&j7+!hM#B$70<(rm-Zxl0mLYjWD z0HSzHn((?0JN#7wfepe^n5CdltvRUz&PYxX1X&5R>R+5eFI4$t<40*b%QP13)3dcM zh#UE99<8Vn`2uLTFsm&dtz_tkF)0oIv0dG*6LOlKzH0(5Eo`y7&y`V~_W2i->l-4t zB)OA=luA0IiZs(UgFnVog=w7DzUSa=M>S$#tgVQ{nn$bS>}bfrEbUZV1^mT4l-`1Z zQZC%aS>aP=9mGuG`Cbw;d$^;z!kxq`kr$=3Dxtj^BGQ1;q$o*O??i7BkK%xrfV7X9 zKxE;BK`0+MDUB$s7o!RVM4RL*)MbRy%{ghaf5k=kye-o6DJ;e!y16v2Gg(-pU@?$@ z*$8$Fx2?5YLG5GT6pE5xQ+>07+CJ;tkFT`wLB^r22tCBcz#zA_hD4-hKYPUq~jq9X*49|!Aj0Xq_|Z9OhJE$;xiEgQc6UXyCpt;2u6%7Dhcf` zf!fUcEP^m5@e!6N{%6*dp^+s*HWLxnpLWpID4d7)lR*}<&RiX(^t|jmYFlI z87nvzTDoy<~I6)DA1c?5B zK;GT$u28grLmZfp%F}G)8yEkJyPv(eHJZ=dY75O<>p6jj{!$hg^xZr`owhkPr;Qq2 z9B1#{^#nNTM3Wy(()|_LnQ{-;6x1ib^$euB-s>q2M7DH5M9IDqV?By@?d6&-mBUKqsQyO^Nos z!(#C=ie9Ok%7$KO>18SSEMrqrIJQ)&EVa7YyRMm;O?AYOo%YxUr^z9{1L{`|uyc~v zNL4Q`<{cl75d>z$wrNL!KFcEF$w^@UX9!G_gY`iD`|`4jxw|Iuzq74Z5V2&xue?-! zeLmna&{5QNBa$fT8y)uij7YLDOaul)*D& zi1g*_7jlkY2}r8LnS1DxWq`x20_$AnC&;&vw`+S{qP zP5b2@>)Pw)(f27c8$;KIsqNrX+X45Ym#F0=*26&rM_P30>AE&7U!_&xuV zaLtMVlS{Hkh|WQ9IgeqHMp5$!y8;i5V#$-t5=YMV-yK(_K$OB8>o z#62rGSgYU&DK08!gB`*W7JaThI!)p5#gUt^palLvb()nt zv@!QRQv-VOg&-YZ`oBXlbhw{p(vRasHu2_b{uBvCIQ#OOE+iEFpa$4Nzw|Riv7bmR zC4Rv+OB5rbdWb>qHR->^Wno=MBccezr{OVgS(r6`IIK5*{C%3a28fXbY}^<>Bprqy zXL-XVN5AP&t_XM|t8N>&2`uo>i4y|q6<+XL!sDML{^NYuHUeMl-(5r(4nxmlsfHeX zrUoZgcyIVkS9%gV9Oivy#7?z!EQ$L=6ST$=BU|Eompt=-J?{=Z$Cpl4z+8724#z|K z8Xn`!z^d*H3~9qE0~c+XDLY?{oyD`nktq@0xf z8x?-{_#ydAI+OZ+DK@*zL4_+HdFQUq!LsVBCX*n&eyMMC3yXve@nZj?1li2HHH8d+ z6EH74t+KqX9NSyfsA!z9&v_~s!}8UL{d+V-C9|~)U;3-W$FpyV=iV6AypsRQ$YODl z8p?TYCI>OnqU9pq9Dr``M-#%sqznp73$t{R!B1uRBf+aJTD%_%CS+%ai?aLTBD*w) z&(b6@Hcn|%jXFFDgLNQ!J&=pUJS74^Dfa40Z*m;hWw-x@15PW{0kd))w# z&^Y(|>BReb!@toTGSmp9bpfBvrjxg_gQuh`836q<|8-gcG4l}v*XDlbIb1$By`2Yu zpBl&Y{7f7}$zwx!_P^rGr3=@}h33IZw*RQ=_}Z(7uU5sUI$0?@py zE=ah18A?b?YKvrH6T8?5c>?EaUXu`B?Y}AeFDQjvb!sP&#=m@Mm|K-a~ z1&<35F<$Zm{$ah4gXhaCU(b@FIAAuD&?Pd?rlj;}fo83ktDw*mh zaC-W1mzVi-*SeG&vP4i-BSeT(05aU_u#5fne%j&TYP#rl{=~0;5%t2a{->69xR^>S z9|T5rrNDNcpjDj+9^pBNR8%X?gjVFiaXyvcYRmX8Q){WDjyq}+bL!cclVg!-7PEoR zsP#V1`v5g>SRl<=W*(6@v2t=eH_&2bz=;T{bhtnbpfW^;g^uXM$0h!ONeL9HIfB-p zrRv+7+A0ewi;DI}+T2}TKe9ZYEHQML4@$i?sNIw(&4qo*%pabxLlEIua5QO41Ci(>YU^1_JHsceAPk$>=RNAssR+)+R-E;@Ei^LnOoVp)NdZlGL*+~iW*3(oOgH1g>z9T`5su# zn|zj7c5Vp$&aG@eL{+7rW+dWkIfbm&_)kq~74=CIDsg@3ICajy6&5;(j`|~tXIfQU zG$<*HzAn-izlW&idF7+l9nyRs7BIry-hI{tRHQy5SK%O^<1|cUh}v1jVeBJt#j9Dp zHnzG;>U0)WW!s1|G<_sy6sle}54LN#|o*<^X=g+5l9F z(k^R+u6Z`v-+~z!Ro<@Hi2~Lq7&P&AkDQBErq3xO=`U_i-_>4J@dWOEMR%U~;9>=< zi)g2`Z^?a8^{@Q1$sa+PAZae%9-f2)9sDbS!EazS?IoE^WcPbNA|HJBChH)D3w1$VZLSvkg4^Obe#e4Qqd8 zM09_Q{2Clb%~pr$9x%c*)hy22HMW_87l^2$m`C&4ABKg;Iw}7325ja!BK@~H%#(}f zfVzb6@e!TgI1M$!qM-39%#O)8!zOXCWZ}|^i{+$f_hnA>r#=!BwpgTbsuDaScCIJY zNY!BT-6wxGx;1SayUK_ruKrbm_%q}qd70J}tc`M6iVQDvzqItm8CFhhcLdO&#OP9~ z6$6hM85FT~_n>QYDhh!*mdc!He5OLYGlH_9$Oz4Fu$!|{ma<%Y1i`Lzy7q)31D+S7 zY_%DV4Ud;VS2KdRfNX`uk=vgf{n06FJTDHh3iDFKjN;_kIpuKmmE2@b+5yV4R7x!L zLZ8T3@aC-1i^PYF%Y4!M<@YNM|CbPdMNS-cwo7e1OY-TaNY3?nxVM$+*Oip67qhR} zvXtmq@&}^;f-jNnn+WCUGLhind1{n&c;1X7vBw?S_~LOqaIsxZA@L)kcPzM{4QtYK zNPRjr?890A)@C1D?SX>cKoBKl>3g0hr8<3mr{Q!K7nPjHcR`2&tOP8`I8MDH7`*h12W}K&-SU7zH*-#n!2t-_ea|_c9h_-z zH1OLCju1u*Bq@Mp7V_eZV)LExFrTgUFq0$7Mg1@tb0T@L5<6_vvz;nRZx}=UGiVkP zNCs97p-$>?GBcDrCsBe45a?jyEQlD#MV~#sEL{_#MMWwTIeQ7~pQUlWljaW^*-V|| zqQ64E(d!V^$oV@vYH+f>#Mcrn|E8VtHwewM)hs|z{D<)I#g~>gs&)OiwonVnQc<=y zet+4D6&0(PehXXIlM*$-7aKW2)V}Il8qO+6rq)?Z)0| z7R5|LP{G^}^g9cgty7K6_256$Lv6(DU5KViI+$;03qhO{t#`+{MTb$nZFJAUSFbnLEs)Yj6Vu}+N1c|QZ|GySM3Ng8+g_TKT(0p`B7a`-Dv5T4U zrtoG9S%hv%2%lOOzUey-_Tdol6Y7WX$>xO3^ERfu6+ zynbKFB0L^W*e$-`4s}(vG1qA`G9Ob%hyssencCO_;yvo`Mx&P^uE{HUjWx8^z9&0|GOTUYlt*NK z$1V^pF&)mtm#wGSv~x}~qb?cTT3G%~pP;w%$A*78yL%5*RsFRvYv~l9=}g!nbLnfU z$t;Siv8P~7`yczE{^VGt6CWQdvb}CIz5dLMR5uJ2lr;!Fb!R;q>m+3|j`8ScX*lXV zDDf*RE;{dGgkWjfI!vRaf>W79z34x(M(R`}WmJ!Mg@zd2io**buAj;C_^giXwHq^% z&koF*nlPuo3s5wH#+MG!kc!N0=OVGfB)G=<3%`&oLgV7kZyWQ9s_IF_)*9(D1&&Hy zJ>lk|(d?P*`eZ7HDUF=m8po?kv)It73-py)@Z5cE%HElGS@Vik8Fi+&a;F+EE9BY3 zY)dr8;nXZ*Z%f=)WnGg=HW>eWEWTx~)vgz3r?K~}GxG2Iz{M9F+hEpExP@jB$^Pb>Gv|Ydc;eQnYU4nv1@Nd7s?} zW!QA7Tcys_benWMOVdr{xWjoHjW(}V{K!r4cSs0?cxCd6kyNQn4w3Jj-|?nejr%=} zUa76;vLM-kzuwWWy)9^Efp=qGf>KDA3UW5-?`3GZ8Sp&K|C~gk*XzUF^(_B9-}QV5 z7g)XE;QruN(fKwe9 zf4<0p7+$uU(B+e`G%=T`(u)~iO$xmQkO)0AL`bO?%uj(I*SI<%)j4mMW|UsM9G-aK zkwSE?kMAi4Px(hDled{Ty?s*b!&@&qDkL2&oGY72e`HjL_FhOP1zm1$EsXjRENs2( zSB6aAn!fpOS-S6ULtxQg`zHO2F|R)Y^|e?jH#5Q;ByPGlrK(Y4W9D_3!R^mlK)*Bd zXNdx!+O~(hpDO}1kAHW&#@^iF(Itaf|My2qDTss*yhO;m6^k$uYywDocC(!}^6^&8}p%elrF&7Eg`xyjTYqY8x;+0H$eAH&bPd zG}X`{w;H;e!FC=Fi}h44`!V`H3T4HwsJ!9yP+}uff96)J;UlFwg3vGibk9$E++Su1 zkbC5G&yUx5TxaUFH!uZ!R#eJslLaP2xM#|B;`MGsD4n>Ja0X^zSVd z3qN_irm$3-CgB9H;krHaRTfi~%~j+okr*gN%4qWwi^hr*2jW?ERLo^ZY=<@Nv{s!5 zTk9t^M4^-i;-q{j)kzSsB+2K&pU{+3{fNPdp-?cCU*`2wtbZ!1R#i^%ICm&i-HkL5 z2lp^={n+EpQNGY1fVNIButTww6N%y}YzV1O{^p68e{iXDUD&l+XoI;8!jq^}d2yP{M#nFCN3ETIo(ab>4367GH!p>lh%!c5xz z-l(6lRXle?_%oLi)>Q}X=}k(|&;>e$#YwsgVr6c(q;3f#dG8GxQyd8L=LhOPr#Nk~ z*);$DtZ^BSC@5o&+_lwROqhxcM}5}6ulv{<@z~3{OeeO~u{cjQc70_wbWULE}Datw8|IeM^7vl~j=;I4xcsEyxp zH0kv7GFI}b6eSPZHD}8yJ!<0MP}%@#9X8G!Mxach4ic-gp!SG(IAg)$+0r8`>t6pr zilPz&t8tn_Rj!JBSh$yz78lD|Kb3}}(WtEtOp>N}iNMca=C5WuCh_8`HijqKUJAmF~!0yD=;I%ygGe3$0CSKt#mJLI0fuwu%rFe~r4XiuDb(i?i~3 zcU3-}Yi;rRHX0zD>t7ZI@Vx7K8}+w&*;>j3Mn7}5DNz0e)yj3q8SqBD@%&fZxfp2N8gYwlco74QAPkYx^JC<^7!4w4N|)xx}BAkXMC~@ zGWy5JzXs4?phT88$j^z2-#<$~-#Q9nTw}Mh)btZ1j;;h<%5w`5@;tZke|_%qXmRXx zLV!xU6yEYl`uXlJbl2l;@S@i|)?QQFR=xVV_w8lg!msV^kAD7xSL-{(h(WM=l0@nHe3;Z@|EKIF$2dr>rw74upGjcX0^b_cbm=oGFfD z*AWMK?Ulv6pPIaDRjS+6r?&+2Xm&iC$Cav=WEuRN3%>B9^r|GfrTq~}Ki!!pSOfC8 z`rhLLWUUP5e;X|da9Fb8o)A*xMx{_U8*X5#Y}u{Ob)r`UY?k zzU94vkH8PwTkY)3rQwly32co>Bke4xNs|K)j^s&jGK{~KD(s_}?p0bE$qsF8z zPdwjkwZ9P04pO^bA@~}v)U#N~kK-lOh1~IoJE|TNeNvs{qrE{H_7S`8CcP|v2#U_< zrwP0`{Ze%Y7I=li2|PL6=4ox2V9KtGu({afYXjL&NvWQShpoZKwMiZmsfHA*^>~84 zMX@sLiow$#st;AqM@4w}OT%zZP=2LD=dE05?WmhXw#TGBi0BBhU0C1*tvM$eL?Ku^ zO`D6hH%wIad$h!xfFX*d{Aje%;^iiB*P!3LAI+}IPgv(`K%QTfh!OTep_XevPG6NW zrFMsmpHM;#O6rc;&9g>IXK^|33na|uj>Z_Ny)y>Zjhx&y*Yr3YV)|B1Ztj;}^sqg2 zM(CIwF`uDVYNgE zlZ@znb;h~*{?HdKn7emZ85puiIOUSTISlTxr%#>oA$#eU?DbZ@@DIWW?-M zg&W+EKjn`6Q%Q;z(MBBgeaZ=5H+2H5;2R%(Q`E4X{j|bxOPCf8*#VV$U&K6f0bwEZ zKq*F!`}U2#G6$#{&MMUY__O*^Rq~AX#3mGvFxk_+{L={9#-8t)ha#IS{c9Cx|qU=9+4S%(Z&+O zQ$9mo3Hl2RRQ5Lypz$4)Snwyh(U7%9qNMJ(L&^$?l5|DPb$_|>QKS6Iceye%b;e3^ zHgvH!o`5E%0YEnyC*EDo7%KsF>LWrh;_m1dY+ZbVC?^{yd&Zs$Xf4_QLUG1J-A@m_H}QPWBL^N-La!xVKXTq%)_h(JsG+}8LZZcKVjczs z->zaF9v%SxlQ^cSrR8Zh=k3-GD#c;L%E0T0iahS|NWmX+We()enZstA{x?^qJoQ== zKMRg^pO8)`Cnq;fG*-EAY?%GNY&`cQq8!=&!(;$KAXNehZIjcv9Nujl9lh-fZ-mP~ z|LjoSxo4tKD$zF}Lr*@eAC+<~Z`0!zZ2jFHLqvdiw0B?O|33YGSG&``zg+$DkLIoE zAQVm`YH-l_hjUZOv%lYM*QwwQRSjrt=O#oV)bN>(DEM}0Qt(ERvemV6ugibG$;H46 ze>x^LEhlc+j5-0K`)h~bxFKcpTEynOA+uxI?)75MQCp&G#!0K{X0= zruF&w`PLrOw}F&wPM_Bb)KU%q-60XK_)cw8yNfXq~Q`x!wW&e3w~$ z&XaGQ_el;Y_XfKDAHjZ!fIaRDxSZz{#|zHDlEj&=0T?Z@>yTnP?w%%JMrr&oppXr*D4LK&U}4Mfu-SK^7}1d4hzx)}=^} zClBG=)7U)y(gyddN-(=F^hEgb^k3#YQzu4`i|bX^ zKT(aQrJ$cg$)I!Mni2)9Y~@g#xh)toL;d|M_27L*I%8>aZp`u+DhLJmTndU1C>5hA zAvD5%QG85=5o*KTOblFePBn-^v}Q39pe`Rud+H9KKh$mD)%ZPOR$;Qdt;xBXB3B_> ztd`;AHe7Gawqhso96wxRtFObtr!h96R<~-jTF7S2?iD3dp=70oSSgdIUN(mqtWBj- zfvFuO3Z#Q_(051_ELz?2Ch3#Kp{n&-r|U{@*;s9xC+kkeHeSzF@^_?@&(G|7h14b$ z*_#bN^FXY^U1_2_G4z@V2HImO*T%jsMEAFu-7hqjdg;tgg{#}!cr?dViW{UE!UY&G zZmH9M@=j~k?uBO7re69CVsli3l1fzCWkKv0{un!D`z4FcxK`Y?F>F{}IzTM$LG=rd z8VE(a6T|9I6|ZBDPb`0^`nSjyzt_MrTDX30ey-zNyZgG6VCdNq5uE?wlFxMd+Wx%B zZ*)s&nX+F;83^hEgTIF~li)ixDNU*}thqlUV7k2OkNdaad}4bg7^7!a%RtyLTUO6gUtxb%uG4h9@VnX7 zJw`|WMj7?{LhSIDIVR7$3c=TKg*N*Hl8FB27stfT8VUIogex_lDI}><4ZfOUd?)&l zZP_|4oZ?L?3*EuaR3##^o{*vy&fyi7LS-Kc6&66;zVz{i zpX3;VOHUB9{8)eR$=2<%HbIQ^+rJI9bNgW%IzX`L<8DEuT z+*n|Hf6961iIaLc*64yTNSoZ`k0bFX|M$fm$hCF$fp2^OP&>e=;TOz*d#9G)B}&=) zSJ!q5J7c`jv;pX;Gmm(hj-&NymSbv*1PxIS{UYCjE?55Hn_km=eOHZM{c&$+pxaIN z`@Jhw>X=!?-gZ=gcSe@h(@4sk-WiaAOP+)jgId5$TQP3UdAOs?#GN-h$K7w;aQ%s2 z<$3=7q%20F>pFPr$|yk5kTWCAc7N_PvB%Q#x2+r!EOe4QvcVIitG(5+)1fq`?_l?^ zKF9Cg1jie^V#`@E-#TdYe)!O3=yl)I`{c&?oFjM>*Y(nSKyVPMmLG8#eBq|c_u4UO z0LsUh#ZWHSzgJz6asse11O$+${*bv)LW9?9aY}l0>B5AQRMdYMbqkdXRFAZE17j51 zP1$d!LVm|VumvB%BAm{$#c`GDCj$w6E-kt!UEGh~x5ApU1Bh410nvEC&WjCjzVVex zl%oQY>sXWcgEFTrIn3*{3g$~WtoNQ`rKrLLK{WX{0f$6~W_8P#^k7i$&QxSy#J!RZ{a(vRw)veyGUI0y?L%_ww<))h0mG?E}#r#R3 zYxhd%ePHs_IWgElk(f|PV(@mDPRG5cUa(2GyK?u60cMS!Qbd=@P{hdnW1IG%PVG(W zZXvZG8ETA_53s`Lt_hVRe#b?3SvjmHV_`sz3h(&&BYX{7`68AT9uhU;6BK*lle2`Z z9U%&P+o9{tH5q``>eZjEUsEEvdkl*-x5{wyApP2LZP+!oL4%4^PN9;1*v?y<8=VV4 zt+=5)R_0Cafq?pqm!>jOMKo2b2^ggm#GvHP@|Ou#Q(UM5_h+nSm=4Mfy^$Xyd8uUZ z9WKR*S)tFCnaPgmg7&}`6xF1M&L>g$3qv-KBkDi8x4?L4y`!{Aal8>dM`#uqOExw3%VWawSx*wzf} zv*Lj^t1Ef!_AKnP?l^RN2l!g)#-je@(;JR+wFD;XDUfS*@*1JK)N2P9pErHT}PCQ&J7gXj8jsz&Kz0o03v?cg(%=Op@ix`39 zg_bUQ^(|!UYq7Qgu?t+3cW%S`A*OsT>U5}dVv~ln{bKXaF!M@Uz7~>rRZx`S(WM9o z0w1|YZKl3p@#YT>)<1qKME%DcuR^W8(EFEhz9W#a%aVq49a+X*Z029AtI*dC)Zu%v z+J8TBe;KszVAy-Z=;*&CXEYt{&o6Sj;k2C_FY2BiqR<(3zkJn}WKE|)GHTa5K zszt{_(PL5g_&YH+d2_~CP9l(z=}RL+q)dqNFxvap#oKAh%ib*i%WLL;oBP+)oh;Az zjmM~sALlIxVN*b8oj;_+AJRxZO5^CvnelIS_GV(t{iZ4%??>W)*!ukRx#{WDfegAj z7*yS$_pEj#X7u&WTrEG$uOG@>q~Ha5xrQ_lp7#H>@5!=Y{&o>J7q;Nfq-6f~GA7f1i( zMZF^F+iqx;&kl`(@96@Le~M@UZX_&ciU2z+J1+}FTS`@mTCMYbFUM!U0O#`o(B@&< z;H6p)S6=}jRcN2zjfbF%5*05qD=8YHdek6^{~3dj*ZFcpwE``=vN`qp>9R$Y|CL8v ztRDKyrb&W{>deaD_v@yeoOdAtpPMm#E3eF1$Qp_7{!SgvSrWwilPI43>B6NygbTaK zwkDH8sZL9@8)%0(cstu6iIpi5com51-vizM!om(t4sA{udU$x?u&?l~=l~CGoz2vo95`(~!t>+# z3L+w+tgI}eDa$TqZGDsahK8Psm6eq$J>1QggMyBZj;^k*%1Yo~U)0cW*IWKPyRfjp z5W^o58oJTza1;^B4@*gZeJ}kIRJ-}-EBEj4NCFjL+qde2MAC6s43pZm1n)uNCt4g# zjl%qXB?KSGtE4YA^KuqPM_U>1KpyJ_1uG&Z(id@d1C+oPA7%pXBmO~$e{d`cEj^4~ zLjLa^ltr~;rR3rHmu4>zQ@0pZCoveOc}&*FSD9opul#Q;J#T3^lFd%8r~y&dT>n11 zQX=*zZ3msHU$G_!GYTGpLSivNLQvn$^Gz!x+b=k+soTcecVa{5p3%)h@b!i~vET-ceb(!2w0@ zCEGC?VF%@1lmz7tW2pGMG7OHNJrq`{zj7bG7@Z_Ak6!{jM2`;bIPCK!ApnY2qGETm z2A6ai;8~@1yNbd$VkIZk^5si?-fX?in{N$aI(81*EFg-C-2U?71T)jG7fT)rk!{k` z_M(3>&`zm>+oXHkBirzd7K2XXQ}nN=8T`DKWf{F`skq7x$q%ynGlNpKsEReN%COd8 zF;7O93XwDZ7{@cD-l^F-!*tjW{jzN}GqaA;dziWJn1lXyHZ{brsbsD`ua(k_ZAu)v zOhdMy6y`>_wFY0Kkbg?><^C?#cG9A(eBo{jt?ZB@8EQ8_NA)^ER?vA`a>N_#$t8Hu zYsamqg(G;#kfu+H%zJ^qp|XL^OG$S*|TE4ius-VLkEy zh$FQW76-0XX}dKblT}IC+ zZM=H&EF!wHyxd>-KUN>9sf3Hf50S~dg1TaN$r9S1J~;^XWGOfvY-hG`doT^AMY-&6 z#;{DtWwH^NP4+LbeOXXV6lkbQt2Coc;-(^@di%HWb~La78uw&_cA)={9H7PA(QDdY z^nYE<@!ZEFM3JOK7a*Q|=zQp)>1N33rc&3?h?ClFJ9lGuXif`|_>UL(?kmQD166ceK@OR2F z5fGD{6P*rh*H}ksQ({Mbk8*o(>q0>pW{x>KLu?jC_FT1@V}~w`H5rXs3{<5XL@IU!m)$;>OC4ThCx8h zHJ{Mu*}e)p4HCS#4i}t>u`x?_e1L+%b*O1;^R~1+WXVR8$k+UO&ysz!T?QbgA*Gko z!8bO4Nm8ZG&tw232K9+5bbV#c507N%D=7c_%jo~uddr}=x~^#$5AFnax8UyXFu1!1 zch}%fu;4C(yGw9)*M#8i5H#<(?yBee^-)ud)yx^F*?rdP?%gY3re4@id3xOyNkO-n zE56Zko>3}?tE(VZ#inS_^SJK9Mn(fuQl1`1eGvvLDcWJFcMjzUM=y+kvRKuyq$@++BAPYyVq7LMbg(AqBgv=; z!me$S)KOh0$pg74Du&mdgA1?)xa{h(TUM1eD0@ytDMi@8kkDMV3A4gq9d+DUk%ibo zp21RW%zMkWu?3!a(p8IK4}yS{nYAKjM`#ziq$o!Y2*PdCde0wI4scD%#?_#cF2s+7 z(6(Z8C%d)Cz}=IOw?p7k_-3K)u5(1Z;w_^ey2rdbo_<|1^Q+GFk@5VU-zg}&Pk+z; z5d6U3=BuynW26mKr`v2f>x^Qu%~AT}5+m}|1M(Ps20v@}=YR<1(2gPNRBy%l1CH1d zvMrH&^9j;&*iCzUV)H(mp3*hD8 z=T-B{BD&d?{*L>*!{I8twB2)Yn8_!Tnx$&r^s`WGw&Q7GM&Q1_;3IS1-_I&gaabaI zR0GrdIJYrchKpwtdX{q3EMOe^WU}!iYVRDp3>+)wmvHYo--Rl|2b)o-2ylTZyG0gq zW_eNi`VWsU7CA9GN8IOY51Q`&2>9$u&+g_V+ZDf9F`A~SwLrEeEs|r^yI724CB)E( z`&a`?5E3D%*bMQJvNqDKY3Y!~$gIgC}55)?|dve~FHJ~n2?GHc1^9B(!j(^Ty0 z&`{0!>oflObg^#p^h-U9SMK4D#_np<(%~?8Kh!HpjFq`CF65o)5k6JkBdC>*V6UQj zR8~koA|wzQTLNq|akNVTsLBnA(d~Gdufgfk8Az68;j6g$cS0Jt@D|&V8PfJ&ed4tezlfXwD5(RrV$a4?Z*ESJG6^RG*G0y(w!F#3 z$xVfg#iTHCx@ zpU@uB;!%MX*qyx7%E}rZ7cN;AJ9ZeTa>Yv(TaDxd-+fk^j4y(RzPa7GF+2nyd1p^s zv1cxQ1r%|s1|9W9^+C!(nx<&^Vo%D>x>m#R;^HQA3k!?e1w2C1v(w8z?;jbG#xH-C znr2\~A}Nb~WWdNwu|Io3Wj6-H^>Uj2>-fw!2$!^bb&y=loj>B@g~KdX|lwzi%v zonKytMS|1U)AJV0Tep|~LI&J)=FRCh`H`C&J{;bM%RSCtvj*kuC@ zoft%FFrU&2$#tDYKNEqVo{yrqg-em+<@}*5$La-H>F&@bzP+2NBrdHoK731heqEkd z^>CNOBAlllU1~5jbTuF(U8EjGCQNzR4-;l9jb*VZ#&f_fMVb)&5t=zcZ^>dHtZ@_3rw8vxyh%Z<>ug@~&FZ3GDqwS1tZGU|2dT&eAQm61qe19;Ms)hnDo(is93h=VHRu`6>Uvt#&YH=_px zvB^~Fh$3;Ziy`6$ZVcxPv8Rk9{`mjvpG?Sg+L%$wB>Kd%iDuNAPYhLKE4o~KRl985 z=(}u5`}|W5YL|?JS1wZdc9$TknCmtfX{az#OC=f)AEBw}Agv`QG$vD<$uUY6gPUe# zq(jdA*<>s@qhopR%kmF>p~L0)NQW`_sORGaaethq%byO_80;jjbDV^%GcZaVVta~X zoM($FY{+}XjEm}*KC`!PFQ?)o;hPW#k9Tqco^FQi9ps^=$69)wxycUs&opAfw@Eba z0w@*0LvSY&n$D$fVyXc^q~)K25V#{x}APZYUElS|kpglQ88qSS0O2e)UvR9n{55fu%VwK@vI}rU+=~ zL-X87%zP{^hyFp&+OPQ9pl)|3=pP%+%+tBVis64hbsE2jBPUY@U2Pu)i5@ zr^_CI9BPdKdv_V@PjvXbo-I91xr&f!tDFQieSJax{{Anf z(DUDdSBfYDkcz9issLyJYUKGpoG#ba)?O+=hls`{CQ_oq|9}RN@Ac*NchRBU zYHf=l-uCvk8W>2bMngkuGwfi$f2i{kdNNQ@nEd^lEKZ)VWX-Ax7~2yfYQl=giZ=xW zB6W3jO;D|)xJlo7@(ZE zu3ti9t#GcjU>&{J&(({$T_T8^gS@r&E0t~ZO^hTich;+Rvf=AZf}s1;dt+ia&XHK zI>6l-_Gw3+`t2)8lK~CyEsPufLZrC3>gWCcqSDCb$YOrj$72en|0VY;Wi7!}60B1e zyh;@Bku(Ned0(kcAtDq+Nqx&O!+~5ZiWelDd+X)YK?*NUqrjEC`rxIDedF) z*}K_!+S!Hb`43uW{yMk?PAV>OckK>2m5WLV8jzv!jpZlLNyooADnpXl5}Z37OQ6LN z&=F{8_~|Sd)!8~aOi*|bcXfxx+J!W|MI<+yibry_hQ1ELwjbSOefU?27;)sZixPF9 zbdd-VWhqgD$%abSupr+m2)PbMm0n#Ih0mKwljiX2hi8HjtTrNr(WX*yg?6P>yg?}@ zu_Ru_BSIAjJXQnWh&{|B43K&rb%!PtS8p}4Elalfx2|%CUCD#)d4LZ0AfiFEbD_JTx!c(GH(ZU~f4Tt!@ z7V*6yqK$eyA1FBebA9}@UoCC^>iGeS-cI&y$J_OS0d#KYKukoC)4^F*UM?doP4K-} zTDw1eCB3z^RpB@4`SIy#=dYmaZUwR}qI%$%cmD3~?#*p&gLHKdr|*HGxCs#NFf8@G zuZvaMb=;zxQd`i*r7nP9Vt80cNC*g&W=KOtMK$VPId~rCFwWu8GTK6z_4DNfm8%2HfU&Q6t#5#s8(0K zZaN5fICwrGKJpRGNPS*eUmxFfCb|CJs8>_)BX^n`57~yZ6QJapn$*D>!l+b;j^%A_ zZCzc2z2krj;Q84nWn8jUjb%q?uhlqcL9(bWKR@yVJ494bS-CgdUgX|hyVd}ofS^%_ z$>{>6cZHATGN|tJj8{~*(09>%PEI-`6h`sl)8jC1VM}>(ZA2LT&uuxhOb0iUeBI2k zun`JU)!f2`$cgmg=4$`y83fB>RgU)-A+oJl)3G;l#J^%;HU19foMSKgDc+i}~43!(WSx28}`wihi`)E8h59Pa|9s^Jt4Ts3vmE#sC+g01vKH zIV9A8iO?v-5S0@9Hm_=EwpA}|E=!>#*GwPXR03bwC>@M4g}eBZq>kySKuIFCRTuS& zjnL;yS)m|XNdgs z`cP4rR!?c|_KJO<%~s%e3n^U-NrSTECMyEo|oPka|4&Z*-{`8aX zXK~~c-^uzY+&zr_J=CTD`*S}j|6`wdolqZ9^XM#RVUjSmRy4m{aAYTV(@1Y!f|&;9 zPji^winIJzPc3N`1v(d!FJojc6`Z)q6?pd(pUfuu+x=N-ekfP{O)qfaH_MH!EBNlY z)rpnwim~XZHli^8LZ?g0bya@wEjIkO8QTz@6a;dOB;PV#8^InUbaV2-x*VFX846z` z|2L1R2qi3ATvGw&ZOFzsj$b9YOg1>ag{E}QDZj=UJlTI52lf?&Zbp!#LtqLq*^;MK zJXTZ-G1(dd%{Nik3Qf2Sjl?& z*ZaSh^cdStH}xH{UqfK_L_ufW(I$mlUOEcrJ8=>KWM1~It-Q*1#2fG995Aptd7(u|W} zbYz6U`ttJf(3ux^xbT|ja}|5$6ddNo@i9=(mLw(;@;LV2{R zmd(x0(WpD>g3@ATvBRO1C6&^S&#aL@5-)Bj=083@09nY*SpGj1HjE@}EEe6zZ>Tpg zI!G1+F8r=@sF|zDWO7$aUeY@4v;stgGa;XBQio2&)g2h12N3il)*AElnik^3_^XmM z(}Z+(aMshmnNDC0&BXr@qWisu@GglIz@ySj3@-c(X5g=kR*`)#=&E3VX|KeVl@Y^L zwX^_X5G26@$NbXJrttY(J>pZ^t{Ava<PQT$$R;YvUmFe~o- z8-@T#h!X;+8pX@FvHzhWqlTW^SdrAWydOJxh;q*gsdsUB3&byH*B{q3=P3SM$y z@W_GBP=Qh48DcC~8)eSCOCRuIXvvo+<~f+jc0B@bxfpi(Qt0)P>*}tXt(d}AB*D#< z!$Zt<2DdUBg@rbt$kMrKPlTGQx9j{#QXp~_6R+7`Su&nmy*xhkir0Ud+I*_ke_~=q z+xG8o_Lyz-m_=3)v-4^WKWlt3G(7O}xG*5q6Dlui5!iqZG_#&JCSPNu5*45PyA1Si zG_~p1k5Hbaiq65ULTC#C}%N}3*ZsG3P(LzTr`)Z`(5+&L7aj?n{#>5+7*!t&xA z-|UYhpTFWu?DaC{0g9M_G_7WGf&gbIoTb4-g@nPY+MUQkXQcq>v;mJNbZ+3ws&+Yc zY>3J$`#RIat3yd#os3472Gla0_*hH_2XWPLMjA~q3|i9i3bFJEBws{F>oC?LY^$n8 zD9+HvKNZCk;sw$5;~SS3DCo_z&qaP=vFCLmNm;W@^aQxbkvRSY>&ATP;s1lGkLJW3^6P?8|mnD@wO{HM_=$aNO_3+Ax0uM{^W(EPz z6H~6^o2e?!P+`L`N6;a~m7-WavzvV@1i1PfmOUzPRH@ z149fs34{a%f$vbAQ4hb6P>luy7r`{;sl@K9za$kuH+PvT-bkQD2lKK>cVkXaZPg z3WWhbw8xy|L^03v0vmL4^zSA%U+ztag0!H>%s8J3UZbe-XA}*$<#>U;ZZ%h|?w3Co z)PMBS%vi9r5qbR((1_B%r@TDaDw&BBLn}!wC(8x+ucV4+F4`y%SZ@8$lp0Ch#Q@eY z30~?8+>)v&Yg)1xwM9k=JPMe?JZ7$9XqDxbOft{0u$-`d9@MwCN&WcvGe_g}N?k?< zf)xdYUP2;fu7Co@_j_gW;OQ|dT@M<{$=>3~Unn4{cO*t!le=od%4dE|E(Rxr&C*$% zFq5m?IpNlfiF`XvHvwjHb+~GE_>mBE6a~E3Y4M=b>}uHTO98VAIxtG4>!{GMQ zMIACkHCR&DgS_TTi9@uFe$lW4TSaOe5+r80WubuDVM15~qosKN1~$7qk$kkomkFC} zuV!G)0~cVI*^A-eqtM+-EZHebaE!O8lrfA500KIGMusr5OAxwKc0gvAZ?w3EhI(I> z047x%?z?7Dv3vwUH0C*QL%cBqAptY6Mcn=K_)1K$?rxI_l^zuw(7Iqi#~p@fVP`Y$ zx@I?DBZNshfz3wE{@qpnC04psW`$!)>uvLNtcIbNFpihJvXdf>j~V!)SRaRtz7S!6 zjhQY!`~YH9vk7{Dy&I{WaJb=EoOJY@%L^ANuj1N& zj}0!bI=$V~FtVKS>>6^b+o!qIKHE&|^#~WJwafAxc-LcGpiR_?-JYZ2E74bka8ix~ z2?9Fk`+umvFyUb+lJOA31MiDT-zy;wQu-WuiAMHruCBEgyL-F>;qn3=*C+oy z=KstC&b<3h<%a`SaH9XId?8v?+)yFcqO^+<20*?HP#6Ft z&Fa~Wx8Sk;<~(_tJSR5!_#q1PD1d4Kx(uM$DFgv?<;%*-c0wiZC(;-V zzTmDgiuFil%Qh$PuI2+x6f!ER@W{Y3ZLs90PoIEN#`s?c$$R+~ydSkJMNDvWQIb6N zJtncX)X46J&)`cnbF9&fxi;e81E@g0NW*dS8ru@n0D{z68R@iSHcJZwe0&b7GUgK> zH#l2m79Dn32Y+N&X#&lN$o+nDOA8GWg71G{B}u}V=4c^XZ@-xt_l<218lUa+33%J( zit~t{U*Pxvgfoe3%Ld~uS=c2>A)z}#npl8rX|J$Py)h2{!ida6w4Ax?%J+dE-*xWz zfnBr$@)mv}HZ17Ogml2ZS$w?J(c}@2I2U5O$>heb&&kdwl8wF$URz1fB)$@-ycl(P zQCbl1sr-%*tewch6S+J%K&>zeo(g36hFy$!q?W6THTM-t&rozTEUYM-!q-r=2FXVM z&oDDvfP!M=HJ!Q4z}jbyQ*qyL8SpjO^4aX&=iyN3?lD#i{@dx97mEIq;wFn8_Z5)! zt*W~BS+K8$*(hV>(uUiZReS^(3lF>BeB0gWE91tbXuseuwIz>#O075aCBI5i%x<0? zQZPVstP)<=lDvw^Buy4_O$R|^davN;QQL9y*}_jH%l$HTS0)6(I=QX++FvNcDn`1{ zviHjx_Y~yeM*!9F6nntJjTZo7^xg5kw-+%m3!))|rFkHG>}^u>H#+iy5j+e|Y5$Z& zXG4yNB!#vj8)^Ee7uJ=k&3Y>@EjB(TOHU|n78>dHJB`t%#!?x25cDBx;levY6pux# zz6R!Wq*3}YiGFm)X|FV*)P)kdhDdWjQETI%6+c+!@#Q4PS2s>#`)C2Ry%}2gy&X~l zHaIL#+(mt;1B{-pr`d+bC(I{hJvzS3TAKI!C(W&&&yUCf1 zb@|!Z-&O%mVB)~FMK4~u_!rZYj|3GWA)Oo*W{aK>D=UO?Lrsl?qoXnz`muZGq_MSC z6Mo_-fF0lZMT_Tu&(s)v(FQ2zhX+IdTA7?;5FJ7MN^l-PlmaRb05ZS>dNt|dh287r zjs_XZ<=Mb!9Zb!tWh5k|`25~aG)|E{|HaS${P}ZFst8cGq>Fp#v;G}B9Rc_SNJUOH zwu2INw+W&}P+l27x0#)v#-NIC=fWsBzn~>dgaU##zQ(vAfYd3KN7B%iadm#kCt&#@ zoJ>gWOg=;clB|PAt)!&v9162FpJ`5LwybaEbflJX*R-wjDX?w9jZR+*CGRzn!(zfO z;!|RE_ep$@{n>Lz!~iPBP*WaKIFtN?r!joW24sNy53V`Mvu2ys87L;VADpOFE?j-1zl4_UgBH8ri(r#L zWT?vy+Z^^g91eXJA->TByIC(A#D>orMm;sPI}sIh8jfh1TZ9FkMH`f+{washp`g&7 zC_`Yo5uwwxATv{qPkWt1WLCxtb8*!;TRqPX*jy`X;Fwi8wOXlW;U^U?1= z9h5N1=E+2hXjw7ecQOsI%kne8$5jVK=$HYp>}8R>C%cRZgW5a6@!X)3$F}qZTKPI= zcsx3nD@ZDW!*)so1+nodM%+7jX=!PFT+BU#YGRhAne63a)dP?LAGRj4wA3Km!e4&h zufzf=6jN5wZax(3Dn@i_AWMd_2{L=R4*J}+DjdJ|=9ho7JAQCH-^;x6+%Rw(TpD83 z;}oY(EMy2ytST$JVwe;@L6M1}Lm*&=J*9^|?f6|mhLVKw+*|5sTC9_FoLnYL)40=a z8|5_fI}B~vYHz4e+CEMib!Sp#t8Xt>p4Og%Z9{G(AG4!}vYmt_Ip+I5L}rbrc0w!) zAtK~`yh`4>*daj?4A?${Pygoy2#a*xedi#lOcm6SC#gJ4j63~AKAQ4e8P`Q_p!3Ha zvAYK6#7L@78xlnV;AQHa7R07uGRCj8l?rm{Gz|KT+48v1!ebAvI32vQR=SusbIT42 zYW=PfERXVp+nFDmpAQkIHxJ^&%UzO)1?b&krvSo8&P-;-z{tZ#!0?m3|8*Ed)m__lNj{$_fliaMZo?Va_`A;Q z!3fS5-`frU+P6oD>ZOx}qQ?igUyOfDKCeQB>-1t06eN-?+pNQ6@a3rq$FXl8(P_Jr z`g5!)mG9mN3b2nfLQ<73wcn&(hY1i$IFkB?{CMG}kZlZ?&@Z7Vg0v{48#5+Fa-+nUPKCein zV!}kx-~^0(MnA!AN+;9Gk5T+vUUdv7LkeGRx?Yqo8=$Krp}Ir$49EZlTH6Kf5j z->yY*3bvznQpciB6hQ<`m`k{lArY(6h*pR(i!A6!p8Z6I_rNTKWUHJlhYheg$;|U8^UFQhf!JL)=~&II<%+P2KQy*>h^>BVA)jN= zAQps)mlXR4B7oG zq`D*^GV{{>Qya6zmFe^_7T=a#^jQ$zsvRM1woPXqZge#@R#ZTh zuLQ>ul4_$sY)8IcK2>i$H0e0G(Ak1%2by7Co$6(m9`pSR9)#daf8x@7-%sf)e{?=J ztx%uilgEQ(o1;v-1JM-s1B&i#EM2;4Ov?*v>hMpmIKNtQ6MH#cKg`P= zsH@i0AeoUqS}dZxrLp|fagn50(i|YaBKhlwY>TtSf*`U${zMjom=uNnffw$xfL-JJ zDL$G|gK}u)o>I9!hiK7HXTTr7U6UuWad;o?RQZ+eu7Nm_$i8kreCj#LZi<-FAi@C!aiuxk4eYb&?-Hd ze)!%39CH#y#^EUO z0&+5{wAbw)ttE6SRI@f-G%WgJF!*FmG_ek#(zpGA}j^#CX5zi;pE>Fth)XNn=Y1})6n(36SPb)iT zl$3x(dgdb61griOH6NV#o5|}g`59krM5Z92$UKWv?KAP5II6SunQuo*;T3F=D%JW)aHh{C(PtRX|gYcA}N2U@fX8LygLA&-Mv z#MCK?-n-4Kj!l*7-13!+qw>>v>&FoZiMztW*QJ&4VB51~@aqyVpwp>p z*)oimwyxRaUi;=qaq&JP1zIUO>6&VHW2QkrrTMyNmV!g_{%) zGXLvb&|Neo>FkK*^l{?t9K4$dh>Z^h2bJux8k7jszC`QTdUE z?+8s6c{;6%wR+BWF<_LHOs3SWeN{dGuh}YgcPGTcdsHy@wP7f}5%SOFD8L~r)b2&; z0}GM_HDpCg1<4BUWKP4)mj@d3eC=0=BXd=7PZ7m5ix^^C{TO5V!uH9%pn#grl0tr9gkBy0(LF)NP;-t)Bd#&4wTvq5GraDHMV3&eS>ot% zu^1)=Yb^Xs5hb>LjM$iql|0n#22@w=Ve5T&Yu+kUKD;&bSXXV+uGM=VYk#Mpq5~H~CvdQPHG9 z2kzUhGcOfpv<5>sb!Pr^5ewOTNC+f%c7Tyrv?K*EY#`ANdSi7pQj!AT0U{$JOnB|u zHkD|w5W{^TquKG0zx4+Xo6Vm7GIpH?NCsyg;mE;|6I!T{g2fZmNC}!0K-K8o7tHr2 zNEvtUFmP^o1Dqwmhc`<%;{CgUbW~^1u^>@Y_Za!l_+wKfGvnsvPkU|f3eJefGs5IT zvt2HcgR78brGw8#qoi}S;_Jk|X!xNKb=T_QTQ=t`+_=t9f><2~PsI$vZ|fBp6_NRwNA-C2KcYpb&K^?Iy7sk(3DVO+lu~?K&53en?K7Ap~$7R5n ze3U;&G(7M4dQsqybIKk)$E_-H7XiXp??CoSAJ z58aBwXstYw4iXV(AwJh%>&wLMXXPVASsQntz4v$?bPhiV5UF&pVT!$e|`-deySI7q;}_%%v4zbjS`mfz6V9 zPmEH{f`R9WR_7Z~wh;U0MC4%!B~*=ReQlDX&p?@1g!ayg*nKDxxASeBrn%=y3}#0t zQRXT~V0Y%#6r}!7SW;w`>BkIQx%d5Vfx;I`1#XhW8`CGM3I{q3u6%6!YP%tvo^~sA zP4_o0YCBzNmT7f|6ovF?DXic^g^?R-B+ua(;|8Ug^|BRWb<0nt5+dr5T(|o)isG>M zsPNL-V_TRFty1U2Y<}7UkbmY=5kY|?-+%g!mlMZZja{12qUdo=E<^Kaf7UHO6+qO zw^2b>KPB2vfMFhGa|ja_>Cux7RvF>l0SvtraWUA{7CNsVu5uuizXbjEdd zit1vdWDJ)`^(%(NDsa@x5pYWpDuDj&JN^5!{IPOBb7}e80M1voIa2Z$k@xBJ*5uF4 z%n%Yxp(pfX6yW4v_20>#1(eOxv-#^+;;@+m_vXOBz}VPWb}vz!IB;R{p?jw8xQ`fA2ocS*rYgR~vg3?C_@p{`Ec8UXrP8|l zl(6$v%f=rg$x1+)>Jc^7D2d9tZ>jeS@X#nxHy1`NltJQYj!369s7kp@W{ZDSll8IC zAtBKkMnC;q@g;nrRCVNy_quVmFd(hNJA<&6EoF1yK7n`RFft1&C>%*$RfqKS8~B)J z)Oh!W(LM+#SoMkDW4frl_(5r(d&M-(wtt7B?PBxbds9?@I;05D<6{pSz2!yy(t6tv!;0b>`Wc@(i z=$han1>oZHWY7<(*CDxl63spq%t-OY=Ec@z6(t7_q9CU;*^s9`Sn4}u{d{GfCI^JL zUN~_ISyzb?a{v}dbt3|kcdTxFtV-=R1{-_e=s678nnGDZhQ8Qz!P(jOXC&$ME}Xx& zMqHTOd_De%Mlwei6N1!VsSzT~2(q+|Ve!;czc zpmG3Of=z@P->Or~-_w=_0A9Svs5^!9Am>;BcSORCyB{-5GJLr1IfR8jT(tgf)WK7# zRxKk|F#$rN;g^i%ua>NMJWe}rf*EILXM`jqBm@MZwiqFzK-wlnGJKw=g$1xxKG3Xh zCY#6U&&^+sUx;^d@Cli!stMU8}xm;Tl15j%MR zGz+T>_jiJr!zQfK#SM{?|CSRM3B`*L!~awpp7(V|X!94=)uDxmBBP=8Em&Wvf4TWg zHvjJtdJuD>o849~YYAs0z7%1Tpud&>peiW<9pOQn{)3-usUR}@9`uc*VnG~5xqpCrp)Flcpg_IS^_y$WRB4cQ$ z)Wy_Qnb}pYWwE!G#nmztGfo`GP_$O^qc{t;R>sv->;cck@HgyVH3krS`f9sB)!qOD zthNmwdW0T|B_@?6T&-nX>bd$Bf0JI?k!*1ZciVNouI=!%w~*p@&7RkoV@Zl%=+B<# z(xyL}V`-Q5}i{*k||{sRG-P)fZ?ZE<%KIk%u}yv0c&w{6NM-V`KWK78D$Nn|4N5X_ve`>S3le z&AXvS{OdW(yP--C*Xaa(uiuk1U?tp!!@L?lSriuV2|3qPYI^Vr274#j4}G&0Ze$5l zLTUi*x}XW^AW0BY3qd~{0a}1Syoi7d74`*$7xC31vE_DDZ`izQS8ndnrVxz1atPbv z=bgVqF#HpzcQ`$EjE$KLTUYEL2ROQUY{oS+`jg6FI5jP4p zcR^&3mKvrT!-K`hBSf7+{uEuDyxss~Ng+k30;2uCbOU3_#Kx0X5JxNa{FZ<38~yk( zxa;=c;s-j3>5%fBsUGC+-2VuI*_*lJo|cRd7EWN6+Y9~MpNC$UI}l)lY}>T9vNFQ8 zc)ph!c$5dEh0k5gOib&RQP##ME7PVg@$-va5dV>U0iv!_#1Qr_R+0Vn9L zGYGtd%MT5Rs1E-AMDf!3+aJfr6#xYhJDeXS`TFu=Wo32l`FekUzpg*SvWGQl9SUlf z0*~$$&f8#NVe#iGS1tDfu0|5f_o1nvmwrMX#{y7Alkt6d{@eFDV2(to+VdgI>QTo( zg)b-S%6>>m$7n$X(}~AOdl6DOwZU9p{xDB2uB6c)y~LFZ9#w&$xU%}>5msyp`L~Tr zeR=4Au9Qz-YgpGXdQY;?7-Thn**&lF2JoOm_~6TIrt zUG==}=<1yAlJxlUg02fkxou#l^6qi7sHgRKCgIOY%})ZT?o!`nh0<4v6Jah)6|S9 zvs!B%QTT$<1WzZ6%?(N`@1u+Tw$bN)vz5+t6WG}h>1duWjb zoP|v|i0pxDvqaiVbA%C{(2y8aP;d(HcUz+;ug_m21C055Pv7$$%l)M7m6>rZz#iD3 zMfc{;Rkl?c!R`FlUEEJT5S?vLXYl=hc)-cdUZla0t4y0Q`JRI~onedz6#}YS1|Y%H z8%XDJZ1V%^c*T6JSS$~gNZc2qfJqm zf0yHKZ?9OlnlDr2>?4pkdIp#$&(5;*@;o~XfIt}*mdYOA2L?cL;3cv)dISdVn40$6 za4M^)^t}nPY~4O@CsL|<_aDtZgGu@j{7Qi$#EkXF>g(>R4JQC%h=~HJ^N=0{ z4ov8Zv5Ol3C}nDSLGbf`k@9;h10N3$6Ibx1LyHWcyoekh%6_G0pL|aRdz?Ry-loV$Gd-=Wn>RccGff{<=Chr;vEd5edl2=H~Z>!WKIPVyyS>`eo}7B;lrX%c`ZF z1nyoy!3iI+V2Bb?CFaHhiHXv>KI!qOmDXi=bj1z(>TnaN(71?gzv{EiP_A$3wAukY zbR(pG1X|_i_RQmNC1cnKsXEN(?@ZEazFTqy7)BF_x@Vf#lJH}>WkHTD6Vd*gmejj~ zuSWE?;2|YPR62=5nYKS&VW{K`FEcBndV)jDwCz)>R>nO99Jdpo1(*0Vf#66EE;R57ELHPG zc`J0Pa?;98@}?I5F+PLUl`Jnr#FuMS(Q7AY5{7o9GYPRH(3rFwR}hR~Dg>Gk8%Rxo zG&lSZCR!X*l~1&YdoTqMQe(nf#TSysTQ!h;O21jgQohk^unK*iiVIg8gCHxk!Ta{2 zE-RuavIlQ$KLo(QFh&R!`w#rs!-ny+%s>2=wjPeQxs7UNb=)nP)?F{#elKIaOMR4& zPDtNg?*`Hnez7BNl#!wo7od=G-u6Spq$mGk54JgdPD&JXR;;vL)8wiuvT$I?w1f?i zP}VmtsGR`_19Ti5<)e-vDC@E@^3UF3Ot_M$$k(9X>|5hZpR!F&7thBz?I?zas7@;I ze5g1%Few7BM1Tf?@vZbC_eK2whfoOE6`R|4&!Eeh~>Y+GMVOoB)E)-OE2WW4HW z#IQ7-_x1`4lCWe<5~D`W+ca-p2$Ib1I*%RP&KleJlSJtkG|iq`)xX3ZlUd z4=5G>7eAQ!j~5dMG5kpNYVs{~=g@5j9TSiu>Yna?{YNS~KOd2Ph+>e=Td;0Sl@yAy z;*?L7;y=MLgDe64uht{R`rB#MoVbTo$uR2DaUT1+aUqWw%@Iab5B|SEHZXOe=rsr0IPJf}y8Dh7@DU;KY4Bg^xlm{?dNZhM;`D3?U+& zgo{Ql{``?@7P5G*)EJh;U9vvXZuae3Fokf5GC7k1-qA~mo%uos+|)r0bq-r%!x!ZZ zZRZ)T&;WcV9ywTdF8Ep0+(NI=Yg9YcX`D?P2Wk&>>#&-y5IHdkth&dsJN(pb7A!67$2v{ueP`M zVF~grwLLfzifUpViNh;2uBL=60|QPQyBlT`r_jf~oojQSfync%^IZ|2U;klhr3aMR z?Nm!l<^`3i9J~?|b*dG-(9qOMeZK88v-5_4*3ME;Zu&3Y}JwI)p!(7a7P9g3bt40ME`y2 z|Gxx+|2@z2+L_rl;HUr~0aWu85CH*9qIn|?deo8*$2(1Q_(KXXx*InvpFMQwGGaz^ zFf$uAYp2K@z`sr?WE>55yAVbqA|VY(N-|?Sc<>{J@9`6zpPdZ=$HcP(g|Z8=qCgo{ z@?ZA`Lk6#ymmBWLXlNcuBlIbwuWxk*?M|*vs6e(4%4xh={(Pax&V zmkF%l<*S|~HoXD0+E1nDC5}de*x1>WZkmW2-w-y-&;nnll*Tl124OwXbN?}vNRiS@LATv+Si zbqmfW=iHicTcAwxjuoqbTxs3JWAkzYXY1^~t=ft=!;YI?+g9#Y?QLgPc6X^m9ZgSX z5kFuf3A;48TXY5?P7gy z=WF|^+u{7H*8Qx)1bDo)pG^`$O})nU+o1OsDH;CwB4I8PYA%l76u?N@3@$%@yz+t{ z(bcVo9+-x);QG6c$kGDVBp;Fz%_?T()fc!`zqe@1-KKLK7F@rRPRmzDS9<~+UPWU0 z$q^w(6|K3X*Wg%N`uN8$Kx+03FTk)zHw?B3gvswA!bU@%h#je`kpy-MsMK#0yito` zeSLC6aOb6NY}nC}Jc1d^hOOPP=Vvi`UkbWPv@K~cwc!H9FNV%NxY;meiWF!M&|v(b z2u6%{C3Jy3fKCo0tyDHzWl*Bu*wMN{ni}&aloVhku;94sC-!dJNAO{6%q6h7FDn5* zhp3?x{xV9~BWCRyrJW~CEB|wr{(FGES09(aF&QGXd3bPfA~GxrC7CF(t2Fn02>i#j2l*UQfrSs|6S z`ztJ|H#R6=Vbc5VyQ<0PUSrX9cHlb@brzlwUuL-?(|SU^kNThau!c6XMZe5x04t{FX-tRfI-JJ!B0Co)uphN`s0y5)th1b9e$Z(s)KQbyfOH-hDoeL5N zyc}6?TxVlTviEsSD~`5qV8k=;A&k*8W>i0-RZ9DlO)~cDn87h5^G9J+PYQV1<_%wH z+3hoM%V)c@OwUj^6|tAh6Fb(^J*{Rn`!&<3Ht@ucR-2q{SG#%6meV-|~m@147brd7C{TGLGhb?9|uAb>oyDNY6S0&Zn2 zdt6r^$c-KquN|RYz*v}Xol8^=4uxwATV$)$1}bd{0kK`2h$%F?E2Z;pnS}N8hRimw zdx%#pa`s%Uqi7UFserFa_#2$s1RDqjq+#-j6|1gmN0mJEERbxTY3b-BH>n)lsCTe+ zDRXsELA1%Sc{%EaTiBgyTF2vWFXij4)6mJVwX(bmS_*u>e|A=ui&+1etxshOi=KxSW^ zw50L-vpT9J=fRP56QQnRz zSfC+m1_IOoKr4Fg>|3OtQfz?@$N-6Klu1Cb&e9o2)~8$>5SVVH$>AdZKI(~dI~%H3g1i8d+oXty0xqO%rIH9RZy=P1fWi0xpoa^ zq&Q{LN%Q<98Vp41+Qk2^sH^}Tqh1B@xWm4xlW|*Zj^M$6x;FbgOO%0Rwi(O&6*c{< z?XfWNua|Hk#ZpOjo?^=I#eK!s{*VfBW=7QUXqA={Ed?BpiE!K|hhP+2M>IX7@{tFy z2Wm1+3+=Qr1`6QR^HV$9!R7}KC(PwUhG7y|p~#Jz$WE7))oeX?0hEB)@B~GSukCCH ztC7Cs*)6q}k2EGhf~5UKcwHpe(xDjF;Q$wAVJrHLk(!fgngmX?^jQ-rcbm~ht2 zemN~q<@Z?YIcYuI64`hj;nq2;VYtZ#R-E$5VmBZy;4&)O9fK!891u1^7W zHXN$*-7wZ2RTzKt8&}&7rO+bgFyF2;d>7s9J`hGGEek@T+dhs@UY$it~66)u{desd{hCcIw8~;s9!j0)}~2_KG_&R z-vlH;-t6h=Bb1A4&9o3ND>1pK-Vt!X$kLG6+R$gi+ZQ`A_xhOr6PiDYi+Q z{U@>lsKmoQ75hVg7@ho2W~K0F;6%0wXn(L!le>HAy7GJKG$>qq4f;=@WxyotX~ap6 zY6axen6pKS1K~bH@O3=}8#_Bjfa`q60WgFvSTCGC07nqX|14fvd3jtJKY)Zn=S47} zRU&D`6f@ct&{=nG_z{Y9Y}nCbdLPJaEmVOQ4K)4v34isT`r6N=!{j&NesYAC_GuAe z<2T{Gvow$8uM&WrY}u@yDD8EzO04MB!^a#*lKBI(Le=*rr@@^m?i-R~vdlo&UylcZ zok9C+Mjt(=9j;<5KRMr>G#jj*!}e#6t3d+|uD6#cQoKk1KfO1A zP8hkEU$+B9<-!7QZB~hv`k6CW*FzFPj*g=ZyhjXk8)i=BBJlIne|Q;YcmMK&VMm5p z(;K9i8)P-qp)k;S%%Lv!$kzwT; zP__sM=vJ%!MW5?1c7)13+p46;hwn?2n++@#6QtuMj{Z5vmD_T%CadS=tSqF_2v)x= zRR~>BI829Qd17edSuiN8WzjBgn|_*%>g3AXI6A%Et#rSTDn>H??c|?>8fp0++dSCt z2xe0OVGrIMUv3G58Wn_Dhzu)d^Bq+WM6yUu1U*3!xq;KLC=M6CG8025V>c&uu-JrlAv0Fc{tO~f_7{6SRZ*ixEsU$|>I$nH{0Y^|i4sfE~WUYl(u6Z=f`Y?yC` zcq&Flbrt-KL;4j2_Ci&SAn=ZyJR+tFRHLX2P&_Xn@5>RjBhjA-^%sQ`{T0q8cp>&W z;wxA*IUDUEEvS^zk7&4{YV~dWhSYFM2?lkV%?OUo3qCO2VbQWf!r|l0Km_SQ zEdnK@lm8N@XoZr|L3+N_gAs!vDJR!`BltBLT(L$bGD$ALEV;!t2y*pLKe z1A*Tg>a7qN0dZ(OF?t@_?p;ttp=BjVI5z$W?6oHVM+WtC9+dg00%~EiL%%>GjpwQ( z*_}xz`is-|tSGtDjZo2ka1kBt8w>bk2Md@NkW}xBFoBf5Kdp{c( z9A0!g1E!9u|7k>D@sBUMR}ii}x-PCMs;sq%x4&kHK4!AIm(%PXf&J}!<{gea9xiTX zUY>iq?hnelgEvFJF!&sQS$`pFyfm2-hbct>yAGTlyaZzY6LtVjvYou8^)%sc;T7xL-%x7V-L$;(Cy}k49lOzVaMMQ^v_8hHlv^K z=PuVWFtc^s%gyp(Q8M-NfeZq_-M(M#1)2Y%*Qo?avXB%-(+w#y*OyiwTesJbAW}Ro zHdanvesXg1mozz$qgJA9Q9y(nD@mCoL`8CN<6(~;2_zqN)qXYt0X;7xPpBUj0pd~! z(UxIQ#tqqy&8n@n=fwW)qKqCKh^=gZ$MQD5Hb=1U^Yr(d!Tc8h$Q$NmE~pqATM zgECH+R7z28gknN3rvsX0RM|35Mc2nJ7UD z8knZ!pvKq7iPoKM*@_qZW zL9mcSHoONNH;iN(Pqch_X+^lv%J043v7xr!U9{zAzUFti?00D?)Zmh*<-XatrN$`0 zq2>;m!N~_ldz_K)Mz~A|I%ruv5$6W+hhaigqj5U4sqoMk7bxPA&BB|dOo)CpNm+xh z8XoE=yW5?$^*#nBFYiaG-ZNg2!UPx~AW;+Nbpwsu3kJQ2q&)u_D}pQVsh=s->qcT7a+|C6de4G7+j8Msi7T_S(h16-le-472e)j>|En~bvGB^l4w7iu+ZF#6u!)Xsd5xVP;1r#Gh%E^)D zXT7ag3Vt*Z$yLosIJJm>Kd?YuInl%=lG~jPU1`R3Z=}#&&8Kh<>1U4&yhHG%cik)J(+~d z^Pd<|Bs}G8KVZH{Ls1xd!A3G8?-L$+N$>p-`n;EYf^2gaGx)!BuLfaiAGWraTfPT$ zy_-j`j4qGKJTb}%z>d&)Vs=dZ) zD3D;EL|=|qU#7kN!-c@y7QkKi)7{cini?HotuuZ+YG-QnjQ793z1?_p$&~zFu~DvY zad5aEip8VHJVW@O;ca3`Km-jej^Pop1$Hk?UtxQ@b#zRA z!QLl2ngLi$1_0W8y?6J;asz%DoI+pFNJIpLzR|@rYLBZ z-(&t=JVuD$E!Ay>B$kVlzV!Re9HBjj4XLQ8h|6bJu&*IIHM0xb_Y`O{BPuf^ucN8=F0c?nHmL^u~^%0BvVJQ_^ zQTq&P=F%Cs%Ee*H6)0v-;)&Smz{)L-Ks12>MK+1xIl3$&mSu`x& z45f7g*RFkib71`Q;Ji_+3TMYBBT$VhCat*HZqZ98Fs+r@HMIV%Bpr=K9!~o{kN@uW z3-)#h_AYD>ZUp8UO_t`!hJ)9_g268)(as*(@{un1o89uX5Ytmxfmi5((`-R z@qM=3jkv!HQ^0}ICJEtW{GYqG$_1z#2tg*^Fh=?JmX zU&-u6IfXQ16t}!5m%6u{f`Xt!UR0M>F9d95L%>NTJyIm7D8r_Ty zGWL`v8r_J$AtoGcC)itmYZICLB-t+}_aa8a2N-kq(YTF7+S+L}En|L(h_W)& zj1!McWZ69v8Xs~NobNw|=0Xlwy^Bbwxt{6F4xKWTbTh^nQ1>b#HLXc|e>kqv`HeMH zm;7>H7`2TxmNJ0}14X5guu)p}B~} zU=0mFnq@T@TYPJ-?MqkHlcKUQPHR^zqAS}W-6N$pF)84CFN_PSie4^Gbq*mKAPVyf zR)m#PRATrf9Uad*O8mwX2olMrjQ~Lk4Qiv#pbgS9))$X-J~Fn+NTi=ez3$Pm>yzm+qu8uRwO_Wd=P|c$KZLqqCc(fu&jd!i6_fl*DJ_Y^knM zlRj$#ic9DG>WV5+TD{8E&F!&~lk=j}r~T{p;HQepUo6Ev_)e$x*HyLqgRw7}P7v(K z- zI(wza_<{JbYajLBpw?f94Z``639WiCP=3F~qz|UlaWBLWi)6ZC#}t3j{=SwOct&3` zo3BdSTfYgDcgy0T$JC8U4j2;^fHFY&Bluo0kEIhAAV3x{Mq23b#18|n#e@ITRcQ<> z^~UUs;(u7y!dyMNscdFf!3v&@{GCUtEG@0|@_b(YmA@STir_ST_zo`q}71(9$`$x}m?k zYI-%_{`7bdk2s+~xSGdbzqPTjzM?M3+r;l_>F;&!f58L25oh>>NqIG%60MnGA12kii!QFb*;4g1z2ncJ=U7`doJ?q>z_j27m|H`-iJ3#T~H%`;pcZteoESRHc;(>UHsp#6( zqT}IA)vJmgiiNVT8P(S=W2jY59Ye^g+HEDI;|&O}bOS-AMcTTSU*unoa_+K`s#{B_Qs0k)Z79YY{R#cM<4>1exgjlM6@qu!URBY!X2o|gp zB&FQh%;5yP4*j~++~>?$XonG9<1lI4CNa?Idw#sDJbe44-#U)M)}6rxPb0Ee&vWr^ z6BPQT2wpeXLV37j|bq*Q{^g~D<$yjD)PPcYq&1Py62;m@!Bk}6&S}nkni2L zETIfjj(gAj4q~FBLV~V*>y}_XOMY(x<|gEXsa|g&PrALGr)r^6xnkP#9*>lRsT%Mt z0fqs3dU|erKpnu$%?*8`uZ9nUI;jl6{(pRtU_>(AKbTaynw6U;8v-@ zd&m8)ecOu57nM_OW3YAetC_>~a3VEo8V@i)FNftm{5s6o^j7d8k2$l)5ckT2T}4AlD?n&bq+jQTF>{6 zYn^p?gET{Ax7M{WGs)U_<;Ni|*4xm0-P&F^SA@#ytGDNVztgxbOmaXbi2+1D?GZQs z&uX2=#%9CW3A{C@_5wbr#}t`(s%B8C8K4qy$Lt*KN@rMP74M)2w%{mi2~P9$2-)?E_N#&67I#w7GTRfZSqaA)c$Mj zTm%T2QgGEv!WM8sc!QZShvg_@Y6HNQMq_a?XS@`dgsPj`#01N5*Gg2#xI1P%$Td#*%~xIpUH#zOLhTX28ex!WYY=;)b7Wkq{A}!-p=))Td=t+daxP zJE)ilXj3nPMI8MFI|pUm+WU+u1|nTUcWTvF7o-)`3N56Yz*J_4Bnlso^$upd0sYKH zS?FDXO3g8#`azA&CGv+5Qy45DA_%-l2W~UILiKmH!-slm1*Va3RU+DJ3U<%LtH8k1AQ9xQbz6R(&yovukkBf7GDIxAWhx$=GX@!sZ-QWq9Iz{V?mF`WIdNrI^E+=e^ zVvDx_+U~W=826@2E>@E*3ew3Jl8Uu|smhM4o6H^jLq`vBil|5FtI7NaOEX1tz)Maa z9b$&U#$cQ}Sh^szF>}7YAdZCD{{|1Vyi_Fl(UIfB!z&rhl#c|Ud0Gq#&WZ-mKPLXo z)e4L*XI41EjPN}9A;OuJG-*n%0=r|XFF8JeHcP6j9U>Q95BupM8ZZ*ofHNa588gAK zJ!kB|%+PN>xSjppzyHh0TuZLfJHw36Oo=BeP5#JiP779$i4vV$#S;YxgEN(A>*qIe zG=d9pIlcOALm}(4?rT?J^Xt)@ z$md#P>+4N{?*dK#?d|I8An$YJji~FZ%>Rb#>x!z&$Lsj2_bbi+{?mKQ?`oj;nVsiM z$mh%c^EQ6->smp`wQ`Q;>xSs-rta(hup1!JI(+3bIa!{ z_(||{)7jad{XH4~)6@7F*l&kPfe0JAgbbw5`-R5WnZe%uA^=YR6K47r;c%-&=9U#2 zC)P_z7*JjSv>;F9IJ|u?aB~t z|7F2pBMcolHE32hZsstpgOTT*_r71s^$9Z-3dc{{*E7C{o$oTO5qF#304Gb0UX)ZO zh$)yoD#U7ax}7hJD}e#BipwVZ8XWI)$Y5K9Y9b*h?{8fm=IKh4JV(n6uJWhZ&XeCa zMwOw>T-Dv_eg+k17{Ne!!xB0y2Yh(Nx?gZ`g0Cv{Jl?#Wbjz!`%aX|GW2LdKEKL`A^~=1mzl7+L~1llXz1CT&|^-;bFJ!qud_JOf?b z_0?6{L}@@ZiW+HSYsF3uYOx$*0024mIBgqodNv{LAUvVP|j|?6nS-$Sl zgc_xy(}Q2C3rH1ro$J&2lxgwncH`CQ$}(dE8L34GtzgM)jgoy~f5sa!h|Gha+t%K> z(wJ)>%n_^W?^h-%aEx`yRjzPeh?ZHm$Z^b7X4n`BB|(w{!SIgM{DMZ~ zq1Qk}Fo^r*2#Br4$W=m2V;}i;=L@i1saKKqW&$ZtlUWrY9F>g_u6x1Z`5pcYNTW|C zE{UStts2%rK})c|QJ%hvWdlJ?}J38Ko&IopiS^d&=c2#gT5N zeG872%-9f;OV}r5aswUpm$R~O&&wx2zndL2O(s21k;dPpTcS-py1J(iw%x< zqx6X>jXeq?|1lk?MlcMJBm5^C$m;T~5~l-E0}+xR-QO<(W);M3E=-$%+(urJspB|J z_uiIkuQYY}doTO(M(08>`Rpk@l-tFSaq4hfbCK8;BJ;=a^bZnV3TX?kXPFdUg2$V;cis;~_K-+qfubRbb&O)67w+j@#<}xI?;O%DkVxhgr24W@10q3zF)0OF%3WS zytsMdV`A$3sN&7rZ>zE-FS@_huq5Bclr6lE`3~MAm;AooP7dqLd>&*k0{4B?)4$&K zBa`$V^FA+!(T*FD`jx?gy`d;K?E3 zX_8xQo)1V9=gu#jvEufhgwnllXSIDK`PeWT0x_T zZJB@^J)3mQA@K>TP1GUfex_dD?**xBndN$xcGlunsc(@kd=S3?F~Y+mDIEl;z#*qT zfsKg?38*VxI0aHk_o}~JS<$4(0DUt+11SXs1+z4eH7Ll=1p#*B=qF-kX2zQnCt9$7 zh~%7E&QWzTaMJ9Pt5?6C^x_gurU`GPU2o!-$S9xU*% z#Q3xJqLRrV`NAfW$*~(WZv(3#Mu;ls3AYuy7XHT+ud8teH~s)$5w}#fu?{Bd9+;$V zU(C%3+!ZxhS6@s3ZQ=DID|T03ZZEA+fVhFOp0Aeo1;^c^LiL)^cO@mwH%~s=Oj;f< zVN$QZD!nfzCYBofwM5SOCM}y0kSMHAA%+FzuqZ8$j4Mhke7M9)bhOq|!-1^m;9MYL z1P%jzRNiF1gD>T{{jR;bB~OJ3JTD8SA`TcQpZ$$*{zh z+YDnnD!I#=*p?fSEi#7d9Aig$8s!_)55<|6J zNK7N8{vXyMD@4Wtm=LkJVCBiEg-_5Y$soa~`2(@XMaY=n)3p%1Fk`cZ16zcXp{bc_ z;58=Up*gWzTybN>yWbbJtcI(beDyb*%TI5r68&8B6c#$m#TjXlk?}6H6(66sKTbC# z)ULX~P*@GcykZmpPAwm3vy{MKU3kwF>@7t)SAAlv^u|(^o=%Q{#6T5RqcB!lz*8&& zr)@HblwrphEjz!Xd-GvM2Pw+7D|h`|Vw#h_XPlZliNC4`Ftj6n@s|KQE&*JqU|R8U z3zsiExtDX-ERjh%G#hJ=3L}S$-(BKW3Ys`>v>e&r13|FujS=m^p20T&MURvea>oBX z?{ZBRwxt%_d=Jmnc7}5py2?$_@650v%$$xj7@ppOrt+x-`JdBl%BkP7PW8S*NhYz&kH_)JV%d|Kpnm1`Rsci zxMU1gC*?;Ij{N)gJPM9c+xjbQW$kUM>Qwpo^h*I!?I=APy9Gum0C&rM3yph95JO-R z7x=5fBIRp%Anjg=Sl7zYX;rwNhBi0fzCI2u@!E#Ow&82PKf&`FtB63&gp(Ilp+c@S74wC{1aB3AYVBWmP7QzuW)mjW6B zFK<5b(WATQs3=x8Hoyq!?d`2byTFo2tt${9S(K8TynlGOxUc|VFA(k=oHT#-02r=^ z83`OLN4IU^A`eBFfN%x#J15qxz{bzD+c~7zz{m8R`=q~YQ%#$@&k7&4-a+EP^YZcW z0XMNfg9;Bu5nqme@EI8y{ z%`TPNr!{ClRN;rt_El=U3|h^5^!T<449+=UyctB2N49=`D?0z5^H67;-^<_$|c|dW?Hg`A`^TK)(M%hX+`(hv5~XUvm_Ur8QnUVT z$W*gX{tnU27#4RR&xd8Gnc%>gZ?uZ9@@MDi&omB=R*Xx}m3?@)r)Zg_U!;^c>%|KC zhF+YONk5Y#)o!H`u5>S3nc%S<1qBe#?_3tDQplTs8wr%OOA=_z9o~JQ+)z-pw-RhC zVJ{TUd_fSei*WQ~)f)(&8tF&nW&jk%bWjc`!zi?ah5d2_JWf3*13&h`(miC8;hDm@ z2sAsjLt6(@OgQ3qn}u#a23ni`P`S1Q6!=U~ys#D$aLV#Q`UvkMGaxhCSbp}y;OmO% z@>Mv4FhM_XtwtC(l2YXObBY~RKxX1HPFw>Nb%NXT_5}3;^v_|Z28M;axv9??%?aIi z{g>#BRA>bdd9Jr1KkbjVUVjm#`@xu)B#vEQ4=)#7p}cCIjKrHCDQEf1cSBe1kSoH! zY4t+|?ythWZv~Q^1ZJFnT)J9Jm;{JYhF^S0A>93oj7c&WY3y#Z@A;C*f4g~8$Q=if zW=~Dl&`0ObNKCvrcq6)K>Pp3Zy&K5{{z-gZekOgrS*@1rhuFP4roFIhMi3q`?Ys;` ztpa~WN_Gu;?8e#}I2Lc>%|iGZ_=w4u$2kW=(x>2_`QCfp=Xck`F&u+8DAr8=wav{< zXz!~&StZ9|HGz&v|2ywlX@IwdIr;F9#o(?)71++d%2%QhdeiCvo3+Ifj1@-`i;lnV zDJ~8XEwF6XZqR&>d^y;O26{0N!&Q`&9A%p~l*qM}lz>3{5mRkD^koXUOa>sH3i~E+!TXXslr%)YQ~~ALHTS zadmZVZ*OPKI6n^A`BxE~#N$UKSqNY(4LP8FA{otgz0}>zAYup4d|$X>Lz2(+bl9D5 zO`giF{IbzHxq?NV7#jor6FBHCiJjRqW4rJY1PVVtORJVB15f;s@<}BQIOVs{Q9tr} z-!nLpr*IhdV=x_tqn^ z8lEuM-HvA}9A?yINn12+cKiFDE+{Wx`0r`l(nv9|t zMQ1{!g-LM(JS-FPL(9uKf6Plnyuy4ZqC6h(0EdvAV2KitWC?f76wX@>S7p4X#`2mM zB%h9gB3Xp(+#~a?SJ8(DOA}u72?`V?M`xsh!=|?BKq>(2BYo)HHxDR=BhW+dFp|9x znYP_qU82l?>vhJetJdJQGkdFh+_ZdMbvz$_?Y8SJED)63p{{vG9(DaASlN9Wrq5yz z5a+V0b)~iZnS68b8EA&$tOcX3E36?GFQ#=DeSS=u+_>L}7|Q5`nVZy^tI{TbCv!w` zc|cTI*HzvA=p{-4N2VmrVjWyw4!KG>pFhI?s?#GNEickPJ1T2EH9bvix3bx4DiK!m zuO1R7Fe+RU2<1b=>l=cuA45DJ1%a|5Kt>QaPIlj2%6X0z*)7HBw)x{R)RxS`=&2lW z8^I^A%NXA_M{(+6xTGvSKd=sJt@uiTboLv%Z+c8WB8pJF5c;8jhCDOBu!(@n7EiK} z@f1>;&dV?8_ep{Q$C!J&BZ|M=UmdjDMTm0@P_iKtanBg)G?ar`V|=e<*>GZ-Z^+7s z7{bbk`GqLbKX3ze9}UOOk!D9e{eJi6p%yEFsmkOVbc=g?%7URDwWdGHg_$JnEE{`3 zGDMHs<#h~~i9p?#ClI2|gRA%`2E$qX;Vg%=7xO}RhPfSkrK?UM}kc zffOtSCS55331S$UUIBFv%D+&MHXafIizIK{9~#@HDrDOCJnx%OiQZl={JFFA<+BDo zau0oi(Y6Lx40M^m$vpx{LXE;li7Mc@H5azwJKf&e`c#G`u8^~=q1*GdWsggIzhb

4N)u%R8`p80- zIT&JEz`zu7(Dcq#*bS0}scE)smz?f3Fd_?F2!DB^M+!c2KPjXB3etJYpg9@~@GF!= zyGIk0NQaQu5$^@-4ZS+Ui{It?m8s(4Z%v~dJ|KNx`?IaJ)g3+Z(-EzDvsM10=;*K7 zrYD`AD!P7D@ESX6_ZpYj>z#KySgUFzVPT=rm*?t@^BIQ%+033w{aP$N4Nc%ffoQ?? zo?^>d&e!p0c6RpZsWoPF$$~Y|E=WLZqpvRr6$~)A92~I#&hXu_lL{q`8;@3)dSAMO zLJ53KA6M9GEBNX-o;qHhlqmu`H?LQ_m^UpQ9R=zLNxwviG7#twREepK$cM*uY^)s~ znlJy$6V(n+umn>sF zEP`S;(a1A1GFDbrJnN&*{%i$l*8r7g@*kU59fz&>Aj6@)?|1n8o&XrT-Kwdos_N(f zEN>oow-Yd?IyqgwyL()#hQEG2sTKZ5z|Pt5#02tFpLQqk=|Wh$$ECtjRYC5lMV**$ z7?*jq=n2df_F6^0LG0u_`1PR!j1)fRGpF zH`A5!wH2xTfMyDd{D{|ZTo;(P$JxlX^u;wB)@(^My-m%(#SfoyFROa)lE}ejWR$6 zY|3_35cIr(dAsCP!WK27RMSSNyxtJ2(FDwed=IniC0VTlP4)bR$vGMRy@Oc!(!7a+XU1VgMFpzUz|>sGg_Zpd8!=r0rGO$Uk^$#`-9B&;N|j>wOd z4e+2;E3`C$_!%O<%=OVGEfp~t@5$c zX=tSA@)0rCJL9TTggVkX%TB!GU!sV!2$w6smJTLga05^xpba!)1IHtLdF){m~M2nGRl|sB7=#(vaLUYmx!6!z? za8eH;{tL$*5jEtIkJbtE^7emg0rpsT`MqM`=Zjb(5-1^x17iDSl&4`E1KI_}&yZ$c z#n`PQN@Lmle3V*zM3^0NdFlu8my7vYkMDj@O1QQf1j8J^20;aI4@l}R2Yj=B3+m`e zAjDWK7=Ze*45O_GSZx*KBh#;C%|(|3;PC=<(V>bW5naN3LoyT6z?k7wOT2#k3()(G zEX;;RYVK1=abqbQuJt4R^6m5b%8K0UZ20(obFcdUHHE^&Z-25R9&`1?2|=)Ly=4^L zkKsIRX$Za9Z~wUZa4UTYjA8QIslFK;=(_FRQs5FwaJ-H7eAGblPtKfT!qO%j|Hu8Z zz@Ph6vPEfDR-v#nNkr20Iw6IM!HMMeIxIIzM#W0#o$Y!6XP`1dZj6mk;w?c2bMjnML0ZUt&p zfwjCuxnbozGcyy(`&kM*FD-3pZjKBy+Kd$^N8aAjvW-HO*PZcbWiDmqXjRddzD8Xm zwF=yfktqG2pHECk<8;MoS7R5Og3;uA{>%Bvsj~%q{M3oIjt*es6=?yI58HI@05-B) zv=HcDlO}fqW;bCba@6mni9q$i`(x@FP_D#|D@U2cg8jq7f{MQsm_h;lL8$0|PG&MD ze8eGObv%7on;@1x-Na zpZ4QZBlQ-HH5lBBMNjQi2xZU*saBo zQ4~Y3{||C@^}0xZ_dd&=tj{44Qsu2{{I;dzbyk7})B06#wGY zBFCvUKu3cn5zs?$NJ7hk(h^XcuEOKAkajc!t37Ir`mGdQXpx$ed$-GP$(>py`GwI9 zj{X^$5zQK>-~R_wZy6L<*98mX?(XjH?hG&?*q}iJ!68VHV8L|=5D4xtxCMf1a0u=$ z3GVKid!F~!t?#QkML`YBA7-!JtGm}~dD%7o#^tlMU0>dd5+3wb(#2j!qVUeQ5fs!F8k|Ndhkx!Xa!5#sej0?|o zB@?zBIf>%i5KxL7zYM31x((}~VDmM@^x2jdhctJm`26O=UD}33@GX;dlYJ*wuhG(_ zRp>>~-XfSM>Q9GxYZ(Z|h=4u~kgenOr>DFjbgbX|Ol06ibn02`ll;-}NOS-_f^1xT z;+<{W$C?2-%Wp2VgA;%rjGiKjpC8#qjl9xr#&Prx6_OrzD8l z`%IgQ&$|X5^53>|@;d(bRp}3pr4M#A^P)BRffAk4oD3J)f7hKqo0 z#nXB82OA?}dv7ls?-NgU!_~DTHpzhBd0}GLaU`ispCo(wG0Wi{CVQyAkq^DjU*mzK z8n138Fl05~KrpPbP(y$O8e~r;a!EWgK;$}pqmOgL^rkem1rvS}z?g%*i?`EWQuWki zF(KVUUCdz4R^iew<4k{c`ukRi=>yf--jV(^prb#n4IN*(PNN$aC@)pGtfR@xE z9~hOv?e<;a@Gqc9tTaBXH^C`{s8pxEaB={8EDa~)-~4-l&q!la09T^G9j-zzf`RcZ z0_$CuV!p<#D$Ovl@C>$T@yT zK_2cdxFQR=-scC=^O@s+=BMVhZ)QW^3?0T&Qf{*fyz*?(o86!9Xb;aT4m?nO3~^&| z#{SU!UL3;jmiN(4^=k$Qb~awn2`5zYXGGGY(}~(icq#9E|L$vK07^D67wBc$Ys@g! z(cx8{@iu?Biu}FU!~OvVl8$7{6d7DUpVC z$QzKr6Yk+X1dzszaznH9fV={ftRijx^wH(zWnn#gVMalS&Bf z19To^TdNzPinXRXx zfs+81>Qlr<2{qyQui6@blN9pvruGXA-kiOu?kaIY23%Pe|L7k(zk&Wu030GU_XZZR z0F_T=_lFHo(U(>Y@s+|f`^|3#LnRqNqnpvfGp80AkUvNTGV1l;rJKg@$KlG4l`nMo zVJb4mbTj*v#j!AlWy70##gHZaV^WLpoS^A&nZ|=|+w2U}=ea181_FaByLKZXvtC;6 zy*Q#PWz`l%=G6^>TXXhV)x}We)qL&q16TGDNFP#?UIZ7Z`D)nEA3@Yuh)%}eo)cI^=d4SA(B>Id7(ZBCY`fqREnV%~2nvbs^@tU0fFN{TDR?S2JAI8!{fF#FQysaUK=gE_f#`h9q z1UDImeHIk0Kt~K#QAbyiI~Etu$XN>NEgbN%vW=gFm;4R?Gmw8JYW zlf)}k_JuC1H76nA)8@7yvB^J9^vAnpb9VD$Rsm<9*F;v$fRo_IrS~Um&G?FeSMx}> znl7bodEQ06U?KMBusy^PqfWQYVy2=3@a&8y?fr_xr?!KvF9H*fC_p%7B&eJH^`Sj+ zF8%5LvXe&AHS_ zCT-9@r}an=n5WWDI$_aWf0g#7?IAjBP?;Kl>mg7U|L{(y#z1_9=SE0%)${qn;b(=s z7-WQ+188@@uFjO7HnW?03Z`Eo?r{DjO@?iz!19%9p5xm>M}^I;J}>u8@qh&b@z zbh>$k&QwmeL~Pq+CB!#9$(N~45Q>$AjAOrpraIx3b$`Uc%y z8m@qfg^4a)HNh>$@pz%Bh|^eMkHsC1h@ePPWTD0w&{t+!FpJn85BoaPyFoEXA2vRUAA^s2&+&T4L0Q`ppjeEh+APd z#|(zlG<=7nY>4ksR?zx}dH55a`f&}QgAO*tUv_){6An&i3akJf@|(=`njq673K$-N z?84GEuk+uyv1Goybs#qpbMB{qqDQv$4J?%eFSoe$WpX72O?6F8sJgH}ukjpH-@-t9 zQ$boJ*MAE6I(Cv|WC+4FpSu0dp6{P46=N!VC_rXwfL!|VU$=RQvDx!ggJ2cGi|Zf4 zgDF}UO2p^=Ik`rGe32L%Kpjk9) z%$UVR+QNa9xRW)-aO;X6SP7)5z=hUQF}H6BoVucKZ&nk;%%7{2BNynwpbk@@WN(;} z6ofmyGC^a0c=g7O7p}m;CDA^A#Xm>9gEJ_eZNfiTva!2tA@ab z@B7o%J9E_GcMKCmtds@uB{CX(18BR%->n<|kg<|~@V3l?i?_=XYyK@W;l@3}{VE?f zF(iV-HGNO#XOB-3U0Wc-DF?$`AaZ`kEK$qZ{;a6=_S$*i0T32DyV$r$rAu+8qd)}{ z%<-j&)S2eZ29eF~(@Q^JuX+n(>3enoRWZJXe>^SIJeJoks!nw~27#aPESLg83ql?r zj!;#KAYP#`VP7N2L1hOAWy!=4Rg;o^vyu~Ha@8d^vFa(Yi`k{+jVZnfPp~$a z7h}q6Cpr0<7TP1MoM;4*Q! z9F`<`OEHFdC<*FOkqS@U8hJZm-FByf6xLImm|lP|ddeR17=W=0Qb zPT8MA$}cdGdd;EiTqEB0XJ=$Y)ToHWj0o5|x{u9#zK)!@dyNg$w)(?Bb%4_VN;JFg zD~l^3PzNbU&j@)LaQFa5)kA$*@3RxWi=oi<=UJ89D-8;0z@kg^_5HUxgh3GONjFJe zU1w@G~B7Qa&j`T2B~D`lUUaD^fWGWw3J7=6i($b`N=u8x6;1>BdjF7koDqv?!PsY3VE%j>PtXg8#9eE)xH)(KXp>H>s z7`6ETvn6!rd4uBBRXDJa0GRr70I)t_|Jtx?u*1@V41r>MR`RZejJ`hqzDoDMrXkGE+-;`TB_%92G(8QF-W_LiFt-VGH4CM&_`=@)v(qK=(g_JmAsE z4Ml44GRQSQ!_$<*8$sys!<#5*37j2d&&M4RJ09u!6hr+V=`fUGZxk??M^q-2CjqvP zhphbV{Z9U7KAvFs*d-o1GM^B{TqvUH2gJm9^qe_=FM9FUIA1@wm~5(DO#pQ9$Tp70 z7}6Lf3c83O%Y!xIc@E^?j&cHPjOE&XQ@3|nsF3D`G2_)*QR1AOljItB|6rF|$KKih zaXySYH_-v}r%xzH^4rE`=Az!rM`cXY&hfpE_lG~|U*H~@7-2>IsG&9*3=LQR{?&PX zfXpS!Hz2HD9JENm@DXcMf6oe|6GyQ6G+T$kmN<$WSq_GtTuQ}Xu%8Wq?anS53ft(1 zrz3-jWUKlnO3~^#HrpeFN?5QGzk`9Q>O3&cMN0&$+O0m=SY>ghMK59&eHm|hmiEgWoQMzAFCX`2ptnYgpjYkLZ&V(yKK>Nnh zC?`j;_45OIpfus(I}z^%uVgr=GyGQjmeh<-4zkpx+`*d|L-2@x7jvr9c5^aSBpDml zo2~eXm!Ooy=8q*@E9`JFEVJ1`kv*aEsQc1)==Q3L7?A?~9}9_9{$0wIQ+E}_UlP?W zhRzlPCs!CLs)wL- zKAkP_x+s}F&*d}T-I|GPX92Y8S0fa34Xw>*|2ygYRk35zz<&$XGIzt0Lmg*5k7HcA z3~OjIN2q=--$eXxQlM9~*w7y6)qjHfZD#M)>)irR=kr&8*QZbM`+*%Vho_gjBPu)> zC8qOR03-WE15Q%y)aHy=hS6?}F!=vgF$>;eoFXE&7PSBOSpDxYq58hb!yI4^XxFW6 zY<72d8|&+%`ak4rq0J28dfrD;XC)^C@=I9n#10c$`t72| zmi$XS95pD`kQMq2=a>3Ezp$r0nQo$6vlf4mh#-o6`m&^|5`I6%Qgq=DS4DkY`_KOeWcKEhr zi;Kux#2*YAW_3!koTo=U$-bzR4;U}>#R@~87S|oLU(;BURBc*;>MzW+^ z@Y|F#*PcL4cesRN&iy1hUB9f&aMwAZB@@XqxeG_ujN_95I_n4$VHfEHCFe#Qu{*FW zZ;LntsygmU?oy~GWmuJCpVaKotZ1FpP4EgX0%FEQ-wk-CU?_9QQ~ub-4Q8RL`rdNL zyw%`l5ZW_mmvMG!Vy=0HR^k=*1olYYikgbCh~}O?i_u2?plh7;0UFO`0TThkfr&Qr zIb>bOD!!mGgHur7s2(a6`trj|6Yjg?Z;$sHO(6-IhM}>SvSGxtS!HQrDD~25qGRYF ztowAy1%IL`iVQi>+0;@b%F{%|i~pbwsbojV_=H|K(Mtf)!OA7W>o+uDXOw*Iek-+t zGDgHmZV7rJpdpCOf!k^fHm zJb}Ga&jQU3I*QMIMTiPg!wufgoA@c+^=NXfEL2H~Hk}-mArwST*_LPRPhk|65f#so zCi6tDLBERg|Fn*D^HZ%69*>OQCy9^R)Tc_@j{zOev{h<2htIZU5^3Ps3wi5R6hUt zv06%tKdVx)wdwBkC?{o*HULe-qLs7(bO)G!3|ujOL*70%;b17aJPSkwJifhKy9@Ic zhPVIr4P;RIpE6Dr)bf8d@~q0jKORuvdQU}_vz{v{H&GG4e4YOC>TA#RIP_(v{bt_y z=wRUyh&+U$mhE@GtaSPdbe3se=>bB1nh+l+XGKj7z!w;EBoA8&5MkWpcm3h7c5{6v zFE6j7Ll~>9!$$N)rn9JsSyr~Qw6yfsFPdN1E$%+Hng+R#G8@;7B7c+qr5s-C{C3~F z#L3xaBN!VWKRrH90y6>0_NXc}CGWMh74o&x)QXi0AZ$ds9K<-xgUs)Nn0sz+Zotel zC{8I=+|pvml1QKMTZrK0S(@w1?%6%CqpfV7DuOXr_}y;`uH87f8n;4SF*Ev%%J0n% z^;aj4{XD>&PWOW4Ib&?Mj83V+naVrH{a~?WyyK}+ukzjHBAuI%A&LjJx{s}pwnd&? z=VTvaro=IAgNo6$QOYuNToU)lxA&IJAy9&GFuiRv8WUG+imOVHb&jA(4{i0f{GzUi z9`}vzl`I>M*KmAzo3l_xIh4mab z1p}PIheW~FfktkKo_vT1KnO%d@D0)AV=0#@@@H_*<1)eE>)n1DG%QwJ6wLmTNyaUw zI#dbTXVMZRO2VGImm6+h_97%e-X;nu0cuV3+iAcY>yZD*$6*K&O2|P{4M!M}TBJzj z>yoGKhEumALY>W%!;9uu1~`6Xur6(P+IJ2}5UAkY3ouKnR{KL6rIG9wyOmu7L03q% zzETTCguF|Vmhq4g=r+;{VMvx)R;C3jqK3EFyOT;ePN8LnGj5yk&ZD_Bu|HG`JaK_p>F6GPFL+!jMK4 z%1;v){;Uz3yYQF9;~ts&ll)tw$pli5Z6)e{+kITJvH<^oXa@*ZS)B+Fh+SsQ=$S@c zwOU;@lLM5cY<~>y+HG2<6Y)f|`2bfNLVB_pb*oh1p;E)KQH}XwtHR~9tPng_xKnT$%A{%x_YXAIV|_Dyd$t**$|$Qkcr5{{J_plQ}rFjk+KDt zqDe3_ci=NN)~|9XFAKk7V_uCn(NX{K&kH4eR5$b)|S?SoY) zXYDoK{pkuYJ`bwEs^#;p`u@nSfj3+YGj84=zZ`hl9*A}`=WxiKd!%$<$d{=19)Gz_ zAS7q~bzT4AhAyUKZa854wkTnr^=i$kX$Ad&v>xHpO8URLj8D(Eak7ftN4vG;_8k8W zBn5i`mOnt+CBjhRN&O0f0c*cPLPEBv?h^)+l9PcTDj*w|09yanq5J=N0f0&J^73*3 z+FV^-0RuT3&oDqa)|7oCc9V8`y%4D(T`c=T^mtsilb#+)ebl4~1NH}%l^w+2ypGp} zUu9EJQYL^4O?ZGobYWp(z;Xy!%v**G0s;cm)yE=3`T?i~WNNmxNeZXet6sa`{yr!F zwKl;-aMHA^UG<=*fVC#-<5 zbyNo^PM=nUT$69UsmL0g+d|Zu=j8zlw8V^mjR_z_+PTY@K98A{xE1ROL9pqkv|rz$ z$Ho{B6c3@m`gnuj))hUl-UKLzWYu^YxjzqeUDw zk8@nuRe8WPBn&yTOAXY7GDz`eQoRKwd(x?=uHz>Cg9Y0aJ`J$VqZtx2l|OqY)0UwB z^^^~h0Z&Gv4KPPrKtINO$9@a)53`HHYmmxIA8I{m`nivAY@royltMm&>RHD@oCu_!_w!PZ@?z|WglbtE)MGSjZ`vuf(& z5!R7}`#Hm(*6w=e^Og~LXDM@9^t1CX6P(h#rR_PM4~xW8$*FSy1MGLu>M05ZxoqaU zu*BQ#vlbxAQVGBJ%*dszHKY95!RHY8Y4x^eaZ%6RHM8?I`tuWO3gR?GPNONH@~--= zN-|++^Zf(*)(-i_u2^79JHM(4H9Z&ZR%+y@3&XO$Y874wt*i2NC2SkWSJT-|5>KS& zhig!0@V4mp7nEpPo4kmC++Tl6N_Y;RNIjE~xyk7uhay`33dxEV)^_F5Y=tP{LisV& zxLi2l+R4QP3RAjD5HcuBqbTDPW^cwG_V*KGx+zb(1k%4 zAA!r*>UHMS<%Z+`lT7w!{z!vh!11STzq>8}#k#i=gx*u#DS0uuL~(lk^^B_HddzR# zpOM3PD8TC9@0ggU*H`GY*@;9_RT9OQt%WwkzS_{GqdVz)kaWPl(f7z6M#5eigt~iR zq)*y3I zf5R0ZSVOz*92`P;Q-N;G$Ote*CuEzRAD2Dq{J{@Wd#J|E4hVTVE^Bq)!|Bz!uLnwu zLqjXD3qy$>cWh&S<@osc^78WV@UXU40R0-MRUBMgVY`Xh6uF6sSNIOl;)MOZhu{rC z|FhgTOsYS(Ax;k-el#xiATdJ@GE{MJ^a09}ZZ@Eb3a>d_-`VZ8d0LC>ZW<{2>q?cOvX#v z!U_7pkx-$Eh363KT1yZ=`BSwU)Uc@6OU=H6m3$GwDF!rK`2^kGEpQBlupx>I5OrWF z&~=T`Ruabwsj?b12%;r7DQ-9?#ViaD9F1N{&ye~Ew!zX(r)C=`-4i5RRXvs80Of_6 zsT2{ZfwmfD>Pk!Bk}b;J=3?aar@k9}Jvo238+M^Wb5$XDE4quCw;R;hXizdLONHCM z8)kBg?$0)=JkjZZb#^{@)2n#D^EI(}MDRQQ@HCo*XH30>>O1m*LDZl8i(#;1qMDm{1Md!BO6!go>+q9BmxHvaU(o5RM;pB-m$B`$60 zlFncf43|4u)uK_>Za{)X{j9<7C4HUQRr>X_1?Z_=9sz)<*!+Q}Y^y|9B1P@kz{|rK%j_C zvNG%`hGXe1|fAXLA zQO`QAcE6pNt{b zqC7u!33xoLko7rg8nW-*lJO>8y;L!tTQNOwaR~%CT!BBDd<5$JzdZJOf5=5gzh0(x zK3fG?=k`<-CfH%@t<~yiX-%%JaT7rQYjYwcDJ}y>3S^eYD=RC9hgBI8O0~;?8iEqa z&dsg9G&C|i?BIAbkzFQxV>*8ji7K}=>B2rCHS-xK8q&H({EcA>_`8%85;2T}G_VlR zr~y9$9Pa;SfXT5?03TaoqB{|^M|HZrJ#+M_DU-5Y77&nD{7~+nSEp!GL;`9@t`}keDVS?^`(u4uHX(AAZjS+JW z3baXMvy8a4e0xS++aJUECF0s#Qa2odUs0cjFDN z(6yBMhdLXdHC1YVJkkYFO`}F;MvVzRl9_JHdo5q7qst4<9!}nhoPR%gfTBiT|?y4Fz1D^FU)Jj=;{^wUZ_Rl;tuhO{-X{ zT^(Kv%ywvVqE^d;ow(q!hMDo>K?1XJKBT;^z~Q5R!~D9@TbJxA1Iw=m%%siyc$L7c zL(LXdjLEct_`ESPMY%75@tLxI+~-tmMh@lpWJ`a&t>4iQtA4iodK(1br8%{0{n(q} zi-Ox<;=KoliH$aCIX`QDs z*sGf~Vf}h&(D`T;;F#M8l!<-nAX5kgKLM;;F{fQtUsAGH&4DvEG-U7SNQeG$YpWofCMi_65w z2q!0JqG}PK^Z+G7Q1A-iVTOmxOH0`}I9jjJaRY#sD!0=%tTS8k70_>Y&FS5NbpqO> zl$<+pfZr5wXm#|h(On6RtX5^DYa~{yG)?9MZYZ>ZPJ^bPN$%@+jCPKNntMknnxbzz zZfeVX0oWii$Cg=6>gPZtI2KI~r>N&nUH+hv-OpTKfv=;zIxFI0W5Cydm~lto;t?y+t{@xe zRx}ctr-asuXGS|XM zov-|k1Or~j4h{pMjLj5n@x(&iZgU&1q=!P=P8OsKFB?8rfFDD%S>pN#cr|R{@UM_o zB<9)`MEcGF(`l+Re zvD#Q9u+sS5&ZttDbBAA2d!s;U+`A}zK^X^TWv9NVbUdLCFTOGFBQMBnWT?kWdY?Ry z{w76^UcxhyYe5);^5qGo%?pv?D3Pgi;hT5;A77EVeasZI@|@f3Qg8KOqibR3iRcbc zjqVH8QEJ{kMO>!wGc|rM(@{*-x(dgT_3gf9uUWTZg)+L-E*qg7Z8LU zE#r#BC-ifj9Da+;+mavFUV9o!G|$-{WV*$ui=)_7KUV?S=@bjKYW#g@DSEa3vGWYl z3;82XGd4~3wZ_7RP8pS-ois{hniMnF@+TZ;b{g$!DU$axlG3>kkM*5!R+ojuxigM! z^lTDEO1k6!nE$R8-JYYoq`-Pm--X#&=cF4P&Cv&m0oJcjyJBMzN@kRgPjqAK-OAkC zrO3swLZI`hm;M#lxSI%I4>qCyut#ThWVht{P;L&Q!z6FOMdb%~+UQ?*yaCsD!L%Jq z=gZXJGy?C*%>Y69#p+kde?wB6&uD%!d%8lvaOGx;uB@bFTTM;;;Ff)Zkw_+X>ZO{$ zuZtu=aR5Za|Lhz<)FwlMHyXQ*t!SbR7eO3nVFf{*|CFL4MyAv;IN${;5T-5b|QBJBM$%_2{3OUBO?Q=mtvIz zBRY|1bpCy*?6M_<;t>Cgi2m!4la=t{)w{(UrY&SRLR&=;Gsm$y_Sm9v^0CeN*T~qDL)6@{a>nJ-Pph3_5#Q@%-jxNul=w$q3L-{OqS#Gsmi)qWT15 z)DVe;9>SSX_cCm2r+Oy!rDhOz5;S%wwYw_vQDkH*CpbYp}BE{>=Daj)d7Lp+wLGYT9 zct}+}=m;>PqeHxX(Vz+~<^pu6 z?7*@7A^aL}y>gLOX7rgU|2aUdlLds)D?p||4`HVDR`-6DGlMjs@@d2KXy=HenHjtf zui*R8icB|UAa%Q7BT_9H>>(tt$UFwgpLe#)Y5YhM5Anf*?h+2R<*eLjwSBOJ2! zDq>E}hI`kwj*iz63WpB6lh`*$ri6oe5mdf)cHwH%|Jm+Pq4&%*VJZ2Ui}e=zamdDO z=Q+{fAy*RdL(3{mkH5%NelKSuJ6-Z_y(QG$=C@NG1S<`E4AfqkfNHQyp#Lv2- zpmxr1>9EqyD_=6ALNc<#o+L(nhU%w|-2MyOc`fRY;s$rmn*^-FC8zm>G8gMom;QcJ zc=M#Er>4t@Le#5oZISLtQUq(r`J(@J6ZT8C6hEPQ&(!5g=xPD7tR|I)#?FaOvDt%)e zozT^V6L5V^4PLmy-2D9d)4*L0U~K`i!2M2=F)%R!nu`W1L-hv{_s&!*9$X(-ueSe# zKs^uSoaE7JBx1^#S*G)3ob*dMyyVTEi)e%dRz8kS;UK|T0~6Y=7=Cm}J4_Li$e5xU zvw=hET~W3EX_@{LCDFRXhM201Y00H9hkvX?;8&j2d~^{^R;^IW%N@)vX-2P{VlVEYf&y^FExU2DYm&*v{P`3WJr{9LYnUi!x%#5ETa)b z@;9w&6SqL+SF9rf#tLF&`dh3g0zMPBA8zJ+!zk#=28(gTah9aeWrHQxC}~nOux6Ka ztR&$~j=-47oL`RUV`xczj?>Ous@jC9U}y7)qNvNNRe?AdgK>&{p`q)yV?v!v%&Bxv zQ7M>1I}OGVJ%w4lw5LP(>vhKLHJyF@F-s4JwZMv7EbWTUfkqy7EzZgK732hb542;h z0pkOR$dePVK9YerNF!I%HBH*n)2Tx41bC7*A0lqH|C-Np$;5w+Q$fn_iLC*)(ys%G zm1AWR;Bf9%278OMwTg`a%O2lfyv@DCGE3in|GAD=OTocGR}oqsMNckV4hti`4(lPx z3fE_zCQ7G0CSZ+%i6syoTcZrc(4`X>*M#UghmB)srw4F2rSxD;FIq?l%2|Y$UDKs+ z(@#EI)uO8Kxk^B`PLdg&l6$L?700aO<}WRj-D?{921>{c7Eo5vGgvezt{aCGq!|KH zo!S%l*WP3wZ{CCb>+XZ;azs~{&$k|JjH)s>rz$9V$-_Mn1+r#_QkXZDF1oU`>Y4Dl zuQPdmU)wU53wO)KsHQu(pqkfH(M{3o4)PT{7Pk6THu}|no?IuY!8cGAtErO0y|6}@ zSF6b-sL>6nN_SJ3%5;;(aqA z6Ts&9#bf{I4|kE{?)!1k@_70LoQ-eoFIMYdw+^XN3AM&B9{S{V}%z0IO#=U3j(8Za&qsV&d0ygZXjJBbM_sf&WFkIE#5<36o|ilU>5*X->wbCy}X^5h6f`EplS zOjhgdzZL(jp=3m1M~ANhnbqSnoC#eK2A`!D2$0MnrD}F~W-A(w0;AMZ;ku z9xDRh&66yU2M<02&<5FcnwfEle)-q%XE>wb&p$4XD?aWS zc`wZ5Y+lq`}E3COI2NcT%(4r4=eAj!+|}ndB7g--wHjpu<@J&A6ngSR$aT| zGfreN86iv4c#hpe!;9ospC7YgQyR5&Y&ZZvXR%XdQgV8un|ljLUgEz+l*sv?*R!%y z8yUg%y!IOi6U>Ct4u#?MeKmH3aY++4m>u@~ysKCzDC3N%8#bBp@N|Xv2g;xTafUxJ zY`M6@X6HC&pWJ!XTqgv#jFhz%zdEv6FpI;OB9lAd%VY#UO0x@P{VgZ4D@V>?P~1}a zeQhYvt7(B!IttgoJNyCJu97aBCU5##*EdKtm$|M7%O*|ZYGyxx!2;_~uU3OTRuk~( z#nmS*WxlO)+Trm{?EE#^2eaSf!F&$xCeK{OhO*FYM48EvITdPn=&(qn2})DBh{k~0 zP@koxG~13;qNgex#@_t&nL%NkflqZpxc`!%D=LY;&s09u1FLru4)cV{e z(D$Nf#{7u>@G+3DBtZq%Mt8mY2Ph1>UszAuhP>7Tj#6Dt>Nu7cm^z;(E9GdQG^0-( z-$1ftFYPOOXvBKM{ka?*87eSw8?Wd43xH<~mNVxg19oQ_8yf?C$?36*F*`3WYvK?_ zc+W=>PNHaF7%e(Fy5sm}A2$;>(AeMRaS=owI5Jk0h(grfjVLTNe{Z|Dwa5u1eCBb z)UJ|4Wg0NkvaB{ns@sNlvTHjAd;tcoK4AYk7a~`XE=F4?I%w$o9Y?g516%q|#HL)s zf*vP?AAM{0e3G%G;e=O$?!nm}>!w+?7_03|Q6G$>o~L-=sQ0uo`>KDTTjgDAV_vAh zXN1CvUiICtoOy;Wm>q5IPIp8~SXEa4pc;Z)v#gaUvkIhy7~CJ~22>8eFToYH54jnz zOQc`6iW0)c^_sZy8R3!-QGi}=Dy*$RgoQr?2`!Rj;^KJHz$0v)#^|uQw(OlsA1*jX zs779EA7`UFqi$br5r;80lP6wIFE7O88(U^(8Evjc5W^1RM>pBEc*{(Xmunv{OSF-n zmxF?8!E8?gT_%AiZs3L|a4<&tFPKr9jR1t(D0hi&i$A7?&*zXGDO_@8xKdR4FwJn> z85TB*_>D!(Dga#>78Kp1Qp-dX1UX_rOof|B3|~lT0I*WUTuNO6Yn>N=^tlNuJhcF$wmPcYxST z_oy0)v2#jVTNG8T7KSJD30kr|9`jibsOM0ywnqBFrmJf3ng>Fq@}nq--mqdUC@SDF z24WIWuSS7IEHA4{KL~RCi3UzRyV*7LhsGtZ=H2^ZW!;#t2$Gq2MOC+VN*J8z@}&hP zZ~vbcpiI1VSE4{T>#svf+Ol=AFO(mzpf*J4bJRe{0jp%6`F+_aTVE{AyQ%i<;ZWb+V~6MIDP1k4|=d+kEQQR@3zd8$IlF@+G;0Md~Lb=3AX=OoQ`A zl#fUNzXubi+MI++phK6N#s_g${@i5O(2liU&#K1Z9|?zX^d5U?D57R6X&;$1grSkk z(;5TIWPwgeoig+PJt7!~hD@y$WZ_F}F2s1+aBu#dXMXwn-2J?Dx07yE72!*lVB+V>9jjT8t6KFMDv8DYFHBI7!4sA ziG=Gt8DZ0B$%M_IwAOdy9O!1-!Hk6B@Z$E+3Oa$h>EFc{N+AZw`S zOQ<(1QlZ%ciQ6%jIcwh>_(DzVVqTk^!p8~x$P_e?3=%h=PC z6zaSazrQ}rL!{fzGtW!m<6`tWVQY2VUIxG6xSA_mxm-5He0@tTMG4EY@ ztkX=$Y2MM;SX0HsWW!HGPklMZ3=ix%5qab|B~Xu(;mFjD4L=bI!%q>~03|^!jT~K& z5ogMh#bFklp2H9q?yC~g!6^Sl?H4hL>9`H15+7UETOp)SNFLT2H&~i!If}C}K>)kz zt?dAkB~QK|SW28B^RpnKkt(QL<7mkq(QEy;TDc)%!EKlIf_;@mY=x=Kp@CtBbupdB zR@lKY9$I|KW7H^KHh!U?qDO14+Qs)$8G$(!*gYE)Z}>hvzSO-$K`lgRnv2|pDE1bw zJ)6zzZCM?v;Lt~OQR*i2v!+c9)%N6aFMxm4ui7n(g>%!ED;Prn`f2sjc56rK9zG1rS zUN3aM-gHY1e)9sTh5weZS5#0^QGqJg%XA%-l=}Tb+HoiI3JVMK^MiXg($rY$mVjhj zVqd#gU=97)%o$~jy zMUWYaudt+7rl`+>S<2^r*~C_>3$7GndXV>Yw7RBxw<_-|Ls!Wzkc_0@v381P-VHJ7 zZx3)tRjIld|3d>-X3U~c3MUv@!xdqfC&9-^=oVlv{2!*i0w}IE=n@aXgF6IwcXzkJ zC0KBGcXto&5FCO-a0{-3yKAuE!T09v{<~XsYYJ-M)-c8N*M0iPXeUh=PVwE6%`5V% zNHOm!#?JzUE~7YoPIKIsJAV+Sv_knw3=So5AqGasVKYY-@0scst?@)OGJKjul$ax2 z$tcQHMN*44RsbOfMxZN>GVH=c39)0c!~dYpoUK#gkd*MG`9=oiWEl-#0)NN>{zeu^ z?jkWR@G)^F8|fQTY{ube8m}W^9Vn3zQ;8rtbYfsk1q}yvzJN5H=Br2o1%Ngxu%J(x zqrg6j??n1|b|8wJEW%2mM6IR=$zg^UD)dU>Y@ef#BS;iGLK-MAY>zZSu|)^-JYkHa zvAZU7JGTcsHMl-C{PF-S>TS%mDSxlFv%30>j!HtJcVXj-LmfS^%+(MKXl)X9T%+!3 zy&0d4Wt$w;>M(U%i_e$h7&eze3-xTD6>a!_t#}xDQJdcsnKMoyJ)^Rp|;TkPYamD)PC{*R0G$90qF2SaU3_${O@;N8Qe?R7s zCLLUsc(%*1=S~2)fN{e>>?ZA(8n5y`p;aT20o{l-n!Vie`o-%)VEPA=ZLfaXC7O9Y za=so`@4W;*boRO!J04PaB$H4$S&UX^68|X6=G+*~JNc^6q&BQ4Q@kAIpJ0fNZ>Fp} zDy}s2mu88b7wuLSeeTt`eAtXUVR^K8AXc_&+?I#aQi#4KCq;K!zPSqe=T3MYnD50? zFfmez8)U9qo~Iezs==l#PEmAf0xhFMu%Qtf4W-A z8z%>U*yU#y9(_UZ-NqXEhyMit_@Cg&VFWL%8Yozo*6XyU73C1*A6x93m1GG5fy~S( zffL%21HkxbFu6E6HwA4lO_>>F)MtMg=NO znp_EA?vLVP6W}`rhE8&HMrP*Ps;cq0W(T3xO90^f;JL{WPVIZS1CO!spN^(g0 zxCSXH7RcjSrurC{{jJdbRHs$B1iQ-lhTU8{h;|W%P7y}J!!T-YZA6TaSPsyscnqlX zEEA`jMoalMx_<;ES?_44t|lym*Oh8F3auCXF*co}8Fei|ayM3e{Eao|rUH-CR;?)L zpbr`wAo>N1@6fEA$mN*EESqjb(e4Rq_Y}=(`qXqqY}dJ#F_e8s6V9=aC6qT zf4o5LEn4TBY$Oxh>jht+fDjq;VJ5{$?mjCSMhzXVfYcxl{#&6VB#SHLcjRVf6J^G6T5)Lg_fJMzl9R2%V`x-Sz@P#m>_Lf0N{d1o0hXL-U>Y(UqMi30ZsB)aVT~Jc;bZ#5 z{|5^!_v~C_jMVn#yTM-nLjk`46~y@GQCF>GdASs&-*Lrp8Fmyl4h}aL*Y%@sNMC^p z&6|Rf9N=Y*jEro{rB}5;Mk@ypKLMV>L*3xsv`~o9%flJDA%XDq^2AOLr=ZVI#IVYf ziwgiSY=!>y;6o810YLjGb%1pskV5Y#g9-TyP?h^wnFFx}#0k<+FaPco=PykGV2iqj zhCQt*ep=^iljLCG(^H zu|$ZJ5)B5cGk=2<1Chc`{uY-_<1KO{jufB#w=GT5S1Hs!91)>Gp#BK!iOE&a3du4S z$arYg_Qz`t3fUAhjQl{f^QC(X-Kf~TS2fceLb;JjzQruu4gdvW6i89RLJo*}&GM}D zjQKQ|m6rX8(Nra95X!K_OpbWTE&ht1`VCNfsil7h;D5u{`kg@rbhk}9Ot-#7%!1k5 zyG-Lii2)1ySXRW!1(gduI+mixck7E%a(8Y zizD0N`FvAYGMn0A^{p3y%hZ@mW`!&}=SR@4l9_ zod*;FA2=BB9-+o*!;RB*@Gf3T{j6EvPa?OxLhpAp_eBl<)9O2=CMl^b^BT8e)g*Pd zqG?xMBY{ampZJUAegdVWm2Q;Z3iOj}QV%WcokR+T)GjS4tZT-)zxhvywMj08dGoNM z`_(a7zx+0Y)&;3-FF*d9`vX=4n~H%6;s109!lw^9-8VpoaQ3ec^-*?5UN=ixsAOj#oEm7TI6+9;TFKsW*(M*{ta9IC$ikF zwwmWNAvp8%+L3HL(u$CD%VbgwZ4sv;2lZ9EV}x^yESElg=C8i@|d9(*uKQPkhRog8fDfXNOcwOR*|U zp{Cgc(9~B`cA5nS8OBQ3HVH^9x9{*^WW{UV5%J?(tCKG~2%4V3UgZvt$-XB=3@#`z zQ_MLyWwsJ-)#Hg&SvcB@l0WRCK1{MB(*_HDye)i^VBRj24W@-vFM8sc$~fbkPWtpf zQKyIj`3fU-0}-Be)cXU^yqGjnND&5nb<^uL`i)E%hi0YRi-(YyMXdm<|R{#w(4m_1`V}hHh=w5PFN_Ij8=5_5HDWn~~kzrv$q!72r5jO5}Fv zf(el%<9X(m$|4Nz6S|0nd`w`#arT>zeKPamUxH!A2lOa9XjC%to7@IK9MDs(-KVndROu|6p{Rl#*awgmcu?5SS zNU2VUMB_y|k<(g}#!7qdUfV4joRng6aQwu>v<-zo+CV~Jx|EZEB#4vY`WhVv;D)6? z@j=}jrurqr2lM3_nD`VClCA|#zMqNu_G%0i|Kqrd) z#4GwDk~4Pw;EKF-8@qH5TuPj-2@CG=^V=JW9EPa${bZA>fAaFCu72n?7Oz_N;TD?z zDDH4;>aeTUw6n8v1UdEPrO`eHLQ55)WJGvRe>9&$@}${gR8U4WX%8Xk9Y6;w#kY1j zG)3^wr=00!ULaJ(*ri!>hY~j~DYUKi&*kpG_)X2>#j2ni%*~7>Sfl^%P}PaiohE} z>ISf*IUsl~#N+rsFaZfHy5Doj&*)9Cc3j29{;LGQLY|gUxM+~-#?78I@E&)AtImfO*LhmD-Pr9RxfSj}JopH_FFeF>+(5Cgr zf2#(124K}daqBxh4qy(3?{|i%hnd7LH2GZrj{DX1bpaNZg1HmGD^yuoSwmxic=E98 zYQryAGLb$?B3Z5k4QBMf8K6#i$n>zU$5FLaayr9sm~MB3z6 z%*F+0!{*t91!>(H7as9yeGg8H#!6P=qzdj;>p|F2;`qso&~-_$4H0 zs%8bchvKxaxcc7>_|z&g2FpV@#~`F&<>CM|5{1JO>Q2rumub2Bt`%t#Y@!!FqVcNj zGpyjUgrLPTZ8RyqUJ}zVh=?92F%4Z~IlEdF?|z~xp&$HJMm3f;`Lpc&kYko*!skuI z*u#{ra2VqGJx}t67!lQFC*mnQgox>~z%TPKr&5i2Jh|nxu#R+=T+$6pDw8b4l3(|C zVvBSrtjAS8wb6*l*deNafcKa7q=^*@;`wH6IHfvOouZ23O_rr1!Yk_3dv(pd#=uHA zZo7s)-Y`NbILYx1-<-CU!NS0Q)Q1hx0df_R=A~GHYc2C<4)t{Yge2* zSm-9j78D)ZPW#8xCMZYc>H_R?0swHrEHox`nwbaJh0A(XE~t-2L6T92E{j7gd4`b^ zG6{o9C6EnsF|nUb)pzLDVI8?U-k9NTq7bzE0P^PHy{rWsRd1efUC&l3Bf5r^`z$nVVd4q%2i+dQ_>) zdApk86Nl14;cOwCf3;FTrB?Uy2Fa!AhjyJteHr8Dj+HlJC3xzXBxOaUJbV&?17ZPQ zAx~$dK(L-_Ouy4DL{vO5zV`*>3#*d@U;Jw}p8v?)l8~P#2qUyV_nRaL>YMtXo$94lDgaCIj6gb1k-OGa{Xa#!bNCV4Zk(ja_% zS_U&e0^7~UiJiluemRDgyy+t#Q8;^Yae3KO*knUFo1YAPeeFz@V#SsH$x+9^U~_%F zle^W**!VMk+~Limd1Iym)t2J57dOS~?Cf=SV!2Y8jf2BhhXe&WZGyxN31|~-e^>jNF2icwT8wu&~vk8?PyasaU{UY%g zb?I$x=QbWfz|UueQe zN)U|a3$4u{&Vr*!$nVrg1vH{{n$}}fC!qYw#|&#=JexF$daZ+z+Z|Jw){79EP^KGq z*M|OT6dMj_r#50w%Ir~mhw;!o$+xp5zV{N}k|tTUkRG#3!gM$icF|JfD1IvBMYp9< z4h}1#;K`-=5t%lwU2$$xv zG=!F@n5FQtN`j-AhQ20b2p!CatdTj;T;p9%B4ztEDni6BTy}WsBJrRqh^QYoil=^u zDFD8iMj?tOaYY#L!KyNd;NpU)_5fxTue-&-Lwwp3dUApX zIi@4@D$nH|SLuR0FTnfxXj-4oJn+Hwec4<7xVvNzww1`!t9qL;S>Xu*@nVzqY#S%9o4$rp$nS8E4S*&bwZJ0E{s@ zI(ShMY`91=q5S>g4+aJR18R8hQ$%b`+SF(JuUm<18O=d(sXOGN_IDT4sKdQx2TTO`H01tg$D zn^&2rq&3z>bHJdBCo=Avdc8tdQ6_d+6UulfTGu(R_VJmvaGw~UVXE?}(Pmbvdsb>R zx>c@tmy{X1=B57pDko@>i)b@P?B%VVL#m1m7z(DBn|@lJlxHV(%&S&LL!xcqQkoy~ zcKaC2v{)6l)5Jk5m@3>&glknvZVqc;kBa8(|(6^3u{wh(DO)aF)py^e)P_ zz#^baqn2BS$7V2pZn>^ILWix_f|B774{MBpLPsDxGNwadi#BhFlCYB(5pU0C!89)b zssg$iY73$(8ZFvyr}F>d0_4-nEAST-_3C}R%4%h9gg}Rtx>0zhW55qni|PM-BSIGa zYYGtRoa^qz=VK{+!EBpG^d(3>z-dZ1Y_#o@m27q3!P&|X@R{Ujw$n6p{@p6=N-z+9 z4m#p=cmaf3+|G31Y#G-*J~Fm2uVaF#m|9&lb?^HuCqXXHubmEV-#XaFbcl_~>u(U1 zhJsTvomkl24?E*n9g3${0wMiY#b7_(%B&1XIV8nrLDDJel?O>msd`b8bw^2rKm`gx zeuNbRsX#%ecludCL*w*0UAb#t`Kov?Fn6OT3LdeTEn8vHR}>7F#Qw~IrYOQ!(%s;8 z*q$Wtx*6*B3bAD4!VJ_XqV}4R&3nW&>={F+^p=z*W1d&c=$*CDv)WAScEq7xmdvvs zRBmB?>4N@fJzQR4X4zzA`E$y=Hpq)+@vyvc#fGs3Kc#KRRO+-4zqm%qI_WO6wyS#M znx7dWs{FEO#-nsA#$^$G2tU%qEfj>QzcjX!h!<<%6egx&n~ZbPT#|?o2x_dHua-tW zr5m=33o0~Mj=acS@_b}fFznQ1St7l>oKwej)1VSW_2Lc*3G93u>pxeflS2ecW3XN~#GVFAj! zk9o*K^{wu`7yvR7;*|t!P+lP>6TVN1D@c-f|4YCE&(8KAIJ@!X>eiIboje%%`gm=< z&d0>W&;w+utSoH?>|}OzsuUpq;GcJQy*aqvVm$xR_ybym5SQ1!O$yLt2)O(#DKE#2 zliG9SY1WPVqf)gnw&N%ycK#bE8UJOvhLM)n)STaYJ{A=f0hI|z0$(}>lpdG$C_v6D z4d(Crm5Xs%?*w9iJ?+G^E|dyvb3SD%OjSvs{vFIExqz|GH-Al>+dO(DeE=WGwD4)7Ltvp^b`7^j8p~Y%IQN$R( zdO`B^&Z(M9*CvuvY?O-zY#-ZfB{qrR&}E8Gj!REMNT1@PQVF3;)KBvo*gIyfvRmQI zD?_YXmNQ6aLGWFznT%Ub07RQvjn+0Uxpy#ILASyoC8WXVwiIi=995-q?PX(Iz^r7F zb4>8Xs1Ap;0A0VGMyEZJ6ePPUmzhNx`#i!|fKCZC1+fKjJD(^j<6LcuH$*7$hfgsI zaM63e5=+cMS5Yq86Qd+X1iE7KFqlymK_o*VQc)C_d!d*T!2+#^W1eMR$SGcfT~LEf zDa>rFx#026SrI%|vuWU-K(GX3o#i~-L^|3j1z(+3Fi~0}Iag>Xlq_vzbF1m`B5b?e zC)`PBE`+9{$S;_zxzcRFNrixu=7xuoA2FGZ#*#HyOuanCDIyu6bRDjIvw;KGl|C3V zUBT3aVAloNRJ2$7B+ZPUigT7Fue2Z;v74jc!}<03s_BM$Q+_FT&GAg22z>)C?KXbA zR%Zthl5xX#!07}F(RbZz2kU0l>SPrO7+)GWetmI<^eKrA$#a^)A&ixz{ztHcpcoTL zq^ZU#>93F!bqC+ti}-QP(FA^%(H7*jE0oY$vASC*hxr&c&889>dNDK}0{>L7t;!W| z@RVct)E{f)(;ncW?&|HhKBz#KDa*@9W&F#m`g?M&s?#i;lH7ozO`8>whXH+7eEW-5 zPT9hYl~AyR8@+--c?^c7#fR0*H_dBTL9^0KmKB+sW{fi3kxhH|NRGtsZgF~95mNPB z9~OU?x2~SnxK}S|Iy6GFSl1gPsSxd3y2ZAB3a9u2FI5ze2(<-Ucv&>!(H>B`6!tmR zn5Hz`A75{gN-bS<3_Ydt7X>rhNWuwL7@XV3@3ib8c5NC7c&!T`YL-t57oC{r=+7^4 z9G9VO(>fIkYeJh+%>~DbegrmYV1pt;`POD}hFqWo0jQK3A{4Mz>?D)Y0f5qj%@_$$ zCa^yA69f9BHZCnW(3GPd=DVYw0_R3gS z_wZQlBG^fNFCxL4cco|sze>3$oFseSW(erKo6N*S;Rf(q(2W&12JZ{B!v_q4dU=!5(sG`;aDD(&01#8K0f(NI&= zWok3PBFwB_8!jYh@au+8o1C1SwT+EK$CelawoixP>jsrS|3AkVxo4(D!%1%gn65O0 zW8hxlno|tK8wP!y&V2Fp&Kb}?P5(|a0UO!sE8F5JitzP_S%&S1k`|HGjuJ*%_6bHZ zzu zjZa#T@eC;iMp=?k15|CQ_MiQNO03O(*OEi0amQ`t!5DI#&m$*6ziO-fa_d%;!&cpZT@Jz0xs9-D^&=#@ zKCw9faRSxv&`w>YdftnG(WKbo>=vm`H+bNvX2lL){kYe66k!j)}6RiLi zy6KnqR*t(c`UbQ(w^)ddE&@Xa9Jd%ml#uXf&)K0tV5mz|IU&px^+9ZCY^FLy6b+5_ zMJM*RHlUk3jvewvK*uGHs!F6}?305qxE0o}()DVl5X?a-je1!vtJcNo3>#@X z?evNvV-dXtEGoqk*@PA{$%uyXF@-U13V%mX+lzt2#@Vw#l4Wz=xW z%J9lUa+F-%eqKH}yq+0#%iRrR>9h1&ueJBL8=x86s=*)Q6@7K~$rr;pt5RmtW3EWx3;y_UJ^cTai;5GlrZirRC#=tl+);5+)RvBj1- zoL`w1YkNR-6R{LGXvpMw=JG35Z}hz5GVjp;Xr?&-J20uy&go~RK5A+^=WH-Q{&C>R!^JdZ=NTK9|wih3F!J&J(Zj_Xa%vktWGA6hQyOg%`hVA>>lzWhm@_SoQ0Kkl*1o(a(Zb8P7A z;5e3GR17kC(mF z{GZz;7aI)-Z%4axm!|gj!Ja+mjXk4(1^g5M-7izj{naPY=&a|fP!1o7CumS9|MC2Q z^eF%lD^WeU0|wohg#|!%?B)~su)(vj5s!m~^;z>8Fk1U((@2%8w6wLAFuVukJ=neC z2tFe{9nUol1lR~XrO!!s8w&#xpB0NrM8p_if5*qqZ^o86_;vIOXkzIw5rE&>ka~w0 z1`@IXm>&q?nsVv}nEzc}`V8254A^X$oe2@xSXgcz9ssup*eQw?UI^|2#6dt}@U{M- zo6EzU1RbdPlqsWPg)G3|a+N%p{}lRPO^4k}-94cLtA|-ODDbHPE4b8dT|l36P`e0o z$`J&oU#^2=%__0VDBH=X=*p-Xkw#NYef)zmnm3Gns2!=^ok-^MY7vt0K_e%da8 zyDUIO%C1P8Hln=XTaoB;Ez;$S()9jqn$m0%lk-c1=4T0b+FhsYiu&&^d|s!~Au}We zogNRfekWn?2>J_Y{>%?Pm!Fw8hU52;_9r%qy6L}|4gxhRxsTnA7 zl7@sVT2!ZrSuSxdFS7_ziP$*G?3MbM!2qdi9ftVFP&ZioBxvu&{!AcNny89!m~OZ` zIuNuuB5UwR;r+VB_6qj(*J)7FQg91SS)A4|aH-=ET{mL$SEFzI-08e7-5bk}pFF*n zugz%mymdQWB)F${;1eO9ve4`r1{^i>CHXs0(6?RKxJ27(di9QlSda zH&A$(qs@&|%O6bNF{cbx&6p|V39u-s6vHGn>^0NGuJ@#@3Jr8@lc9VlWpr%S3AyPK z2s9|A6x$>X%@#EvY0Fz?tA7NlA4n066-n!HrY3f3*H+Y7(lZuu(UQ-AaXveX!vs2s zcfG(zk$kR#M8_gK_(lL%yw_`Yvah{p_wncSfZ596>uc@%R-bR`p|lr`7Qh*9w6vbi zM-7pv{VUliBzDCu;xRpc^XTWBwDU{&@~l^MC4vPV{$Vn>$MeOqwKWnV@`dvX!49k4J7=`JH21KuS*8rZu3j13Mi zGv+TqfAh_GnBUu~A)aZ^!RBnfz5;9=nf-YY?=J3j?w?^_3WI|$jV7OlY6Y%wwsMW4x8_{ zAGOQWJ+$kLEH3B1HwV#A+<&2Th{{Zm;14O%%1;V*z!rEKQ3NQ<9oWDb!SxE4Xq3Ev8Gh?_v761{MB z!}t?0&LFn=cpl;8Juzbn+~Y`uRQ#O*&g$0kCKN_qWOA@afSWg(!GOa{ftt0`vw(d> ztmAF1XnyJ$Mw{WwEAv~oMtlCoKOV^vpday9uf7p_)*%ua`&zG*%jd>2{a_^JHIiuQ zut>f&OXy{LII^@Jk&h|p^7CrBelODH6L1z;H)~dL4vX7yWv|$l zs?d1cu(iKeT-dD4%oM0rWGDb^GAlc~^UcDxFBj)=04}3iVQXdOH7(gefG(N*@$B@` zzQgA~LW!1Ex?Bl*lmtLK7j{_l%}(%uB^IH0GJGFxAi{}FeMrERFRL-|N%LfouJn{j)2rf$VM;RIse1``u=YB%@q7c( z98dv5q5`MNI3QrEo`4=uw~RmeLPFS4?o=H!f!D&dSoP7PLOeIiv6X4PCgJwDc;iVX z9s5`+=q8ydJY=ER@vmSW?)9{0^}P&t?%>!np_Ric<6=zeP# z>9SM6|C&$PaV_e#_y{ivNKEC!55Ji6Yw`TRYVk`l9#xsV!MqVz$SH)Xp@}RggSJI@ z`DW=@3L?dk>_2k(bnA#FSWTcG%6iN;*McN)42c@XOZ&xGHy!U@P-eb;!nx+IZSl!= z-1d}hyrthgXPZySF=Fv4nA&T!@uf|%;DE&NeM($G#B)4l@M6ta$8F7wU~3Q8B2>wNGy`qi4{kPS3w2^!{o{bfLd&!pJz8xKZh68^sLp0dHB z?W2CWL?e!5w|vn`%1cGx*Uax?pJ~;qs7IYLFh6L)os|v zPWTF8sYQxR3o1zqDv2^`iL#9%HT#`WC&*xlpn=(Ch#Ymy&{^hXo%c89_lN&)uJF;e zY;O*ptwh4<0-@)VaQ9O!Hm2{Pd_?zM*IP^ndWT0q59?n+hz##xhyI^yJ){0T zV$d}AqnEz#+V3ZVu7Fcu?%|st5}_IQ$q`^4EL=O2=i9VBb0jBi0HiFwC)B>Fi1r!! zrFeNKkbp@x9SeGpaC5H2T2}r+#d-%v2nYyc_OJ#vWR3}!VG>(#{cFMEcBR=84i*+i ztxFIY&tvHgP@@k)5|_?P{QUf_AEwAR{4W}(@wr^&yMYNonEC_hUzNQ)+Rv!FS3Re~ zUC)>hUWAeX%>~=F?^^GY+Uzmaz~tnsoYDRG<*n&vadlfQ0s-NTn7tl{Z0oJF7ip_( z?}h)JTk&=CNcedKL;pv1-SvPXv=(NYmXp6dB5x%2oQ9=l@A)&(gb7zOZ67?z>okah5=(`026`{^)aSV)v8bj z6hR%izNP`6DCp4OWhjz?Qz3h@t?&aJ+&zk#h6W{e3^E)vaYBzEp}&LtcYkh*Xcgqjn9JF!q2kWK_Aeg*b4R(Tv*4QbL{vxj|8S% z(g1cJ-~s~Zf2dd*PWV!5L3<915vvTcot%=6j4Ee05;j@ey5EtQ)ofjO6zgO!DuA6j zRyUtUfdNr@>XiDZ-$GzYIR0G{l}YDD;;{w!oz6qF-}Z$(aZxB*nKTzu1AC z8-&6RIW9HkZ2OdH*HJ-z1m%d?wZdC>I&;3%P2xd?h}E?pxAXL+zt_ie{dfm3z894`KN2JcNNIN^iL3*P3qr>*gN4mI+ zKy=7GvYW{KOO%rVpPA=X&fXyVJVH@Jb zP7H1cKV^|atVeBwcn)ZQ(yjt%-)R=w6q=b6^~YWH!oMn|Fu3e9;OYZR;>Huv6Zh@p zrg8D0b3l*`U_zTv4_?deAJJ6*7TA4)P%)~2iI^V9lXo2_+h`wYVr;ODw0G5_x7IP$ z#>P8@<*UXrgA_o3Rskw{+v1TxUo&%K(Aq4*8p^n2QjJRuvu|<=-xdiEIg0_&oIOuT z8Dp|q;%?`plWwAbu;bxy)_AR`9;xG|?}6e`DtB)7l3nDN+iRPdL$~omx0?g4!pS8& ztxeZ2o-02uj%wqbgIbeg+Kx?4MFIsV?O;KFXxVA4s7h+S!BS)3G6ntd@*e8TX=OjO z<)A1KGNYo7plx)SpFwBuoIqk^D;lrfCL{MVH!^rG&TysY_!;zToO~^36y2HdSV~gw zGuZsgYk%~?fy=-WGg6QHqLbZ5b0Qu&bvS&~r`^tMHepfuxFqrT3tnzN|72d_QH9vV z9P-VbUX3HGxbw5X1CD9$aMYR`b$PNH*Y&}JPFpLhx~DcHIKv}np=D#sL}(Mq4M zXQJi1BPv4|(nRJ8^HKr4AHWm_k|4L0_3hR0`d;q;x)ccltNIdVZpnw<;oNHPrtOn< zJqV0Q{x^;9=gdJIY|@eLg_ZleOcWac5I&$xG-wF%H<`^ZrQ!VSjKQ(nKt)A`x6UmA zwPC9kn&N3iIxmr7ecul#tMBcB@76$_ep^uN40F96e*bA)1!vkQm5TiMzRs}muGhv>0J^U^ z)9pm1@J{dOCP#nWW6o0^_ElrIc-ZX$a=`6g!N5d9(lnG922Bs0ap@2DdU2^tZ(Vho z^$7Yq)VdJJL1G_w5SlphM0)zCZCWtfWYWXO`Vuj!`#F0qWLWq;Q<}tPaVxk*c%5Uj z+ufaM*NIs$VBFy_cPnhI8)>B5j{iAw>rwGL@e3OwOOc+Gw7t8-`1&Ln2ESa!^pD@K zjQ$tb4;p~A%m4OplJ4ibEW-$m$P@6oHp)8_jlXsz1p}<5ygcF(RV!dQs7W6rLPJmQ zqnxyN9%{dp1n9RG7d0t1sAn5RNPEB51EK65K*Z0PUJg{Ak#j5aE@VIHpvX!PgcT}pmU6EK4#InyN5h+AbUD1QVhg{O$O`l6L z+9YdD=9U9(rl{nz!(U3*KXM!BhZ}z8-{-tPpSHN-XAxHM*f4BfT$MR@T=-+E-D}N|>`DAqpZm?*Z5;L+Rr{hJ) z*MXv4vJP`f@guIWa;=inD4blNrZE`pl@dLu())3_Vy$R*!P}o3k2+k}!qf>dntY}Bz5R{Cb67bS1 zEn?JP$Skp)X1l}U9kNnmyNFiWP^2ees@1MTJYI`7HXVR@y&D`)AB@D0Hprc{L|ojd5HKd2Ter9yFWHjh9Vwr%jH_ z^W88Y7NtpzJ0^gg2V|m*n+Q~KsFrgc^a(IPE> z6kN=jPWL6Z^B*^3)93WB!IBP)4H&s@P*}N6EM<17+mzO33SyrGO@{h{_bG8~Rwwh^ z>l_DZY!Kv5@YLLgv=Lp5;@N#0ydAqM1LEg|r%!T?r*e*ztsIbKp~DONG;R|4QA070 z3Iinu)6>sArhXa-pZdO5-%NQeogQVS*DA;|E6N(?B<2xe*P?+P!P0K#89C7k#)Zc7K zGmu)6DJm2cEF;e29*xb)OCzH zZdbuoYmYiGQ-<@5BUo7_z6>j9x!%t^-y=-DAV_#@O;woksN znp@LuZ$CdvO32(&!}=pdglm#?a%VhH_RlGYtvJ{f#T_|4wYYfli52ysBpl~>h6(M2 zO<(= zqe1a=U>$R@$ur}YYv~3#7;4&0K zb!LaBY2Sdh>o&Ch`+#u3dGkTbCLi&$@3YtF-Q+v9Ue=oPO{?w3!I~dMJ2#0L@Q!eE z-0WR8ZleIqj`8tvpBwFmpQ+O{=#=PDrfj@aR8)+N06SfVEGc8sJXh%atBa*z zk_-?N6&n*XK0RHgS^<#R2Uv>1u`=6+lBuIplz4o7ji>F(}N?#r@hZ9W0 zBcu!1$t|nqPM}nr$AbsI0$x2^Z9WOjoMdEBunJCX>qf(>*^>ZA1;`s{`iuGVPiLn< zu2Pw16%cjcu`+`q(^Oq;%S|mRGjGJAuAzbV2Qc80mXu6QOY>h%Jod5?)0Wt8r=4RG zMlx>gF;JzH3Z=y2>UqTd@H*-K`sYp2$Jo@wBJt%^~TXA!RGli+$j5%?X#4OvPGpZLEM_hF*uyVh@JIDaI0zG z&lErp-|@p6kjZ(k^C)Dct2@~Z=J6@*W71lN$N2Vs)qn+~m_?l_8SMrO`rPN$Zsk)h#^RqAHu0$^?b)Xm>H5+*?>CuY=pTlwKE&@Gg*x>Y+qRvg}>|&6d4dycC#7; z_<;Ovl$`gz-#;~++*h8IV9i}OEDDUX#ibGq_X=Z9>(H^srDqP)#_Pb*g$_H?S?5-= zD1XZy8ix!I9;Sh{6%X>%tj>-Qs~4C}3>I<)ti9~mk(vURX}A=JHS&@EP~=wkmL9|V zJsDnId#wvM&2kMugn+(Dql$q7ZUunkx(OJ+W5NqEzJ%eK>5w-}uF1MO-i#U+XyP!h zybyw@T{^H=ykFrMmm#dEf~YfS_$%^q?2qg?zI5v^3ms^(3DYVP0S8C-3qo(nwf388Vd!aS=(+WK>hnVxLxt4Ut_{O$ zD<-cC>?#t|;Vj-CWaNgkb^O?KcEYm2CGBs#N~e*%bJWi6iwO)G%2u_gdj>@#Vy+^d zupcF#!_wi5x&Ul3dos49-QO-eT0er75{ABT;a$qcqg`^B`=(sH_DL_Q}VtzvY^VlodowM{z7a z#d)v>DT`jfa+4AZa#fygxzW4sMPi{6%3hD27Xkropt^M$e0GhugNOH);eol=Lm_1k zBa)~KN_6C62Dk)Q2nxRs9C_>D^Xkh@c&y&95H@5Ka$oJo#HD|CGKW#LZUQv7e0{k1 zjV8NSWU-<(_<8RRw`_c|53lXWD%-+)K_JV?h=4Zs|3%YR0JYf$>$Vgr?(Xic#U;4A zLveR^DDLi7g1c*R3KVxJZpGal?)RT_ZYBc>frJdqzPrypvQ$ySI7uN%Aow~U7M>^M zdTEFx7`!w9lR(3J{L3hfyA@pHL(anw5I1T>?jBGb8K6ohFU0p77V-)fxVgh~gqYCQ z-4`4=SK$wq78i+pFVF9+N)xm*q>%VtA@sHi0=_-2H9CfV?v2&?P?2(eFo(T-&JF8% zxTyV#)JN$XucoEd=|;7ko$z}9PR!)SJ8o`k($e}8T;v`Jio6@Jqx^2$(S;N6u>SS@ zHEplw)w*~<%`h(+!~OM=)bkJqnaG!m;~%LM$L-Od#fjPPrY$Jf{ThCUk_XAuNoDL-Oj3)2A_6zdc`@KRKl7VoRn;W1HK0Y}C@MVKq z07eG3r$GMZ%*@O$Qm562$fzh8Y3Y%vDGRntAnLAmDO--JUC%&MQ`5j8FE_VqAX71i zB$QBofPJrvM)m!#(P$*PvaU{KWTX)bj?`#JX!wdPSEy)WQc}ZS0<}LrCT410oVu(C3}*bBFZRZ(3lkm z0dQ?xKL7-r`W4~VKS47Jdm_khKqhowfdA(P;RpYYfRCgtNu~OxJ(&5fixDJ7Q8wzJ z%iuq;2(yIlNVY3%=I~XUW1&E>RdqvBMOBeCe)$R#f72x9$j$Gq<{Q|C7Bz97tO|Ou znamnXMNN;r!)LfyvEr~G<6+1NRt1+B)tKO?QMXi@P5cRm7<5kRuYUDOX&^I;s0MoR z_2d%baSj9vI-g{qYmNw!Sur*xbZUsxGLpq;4f=fpTKpxwlLjenk=4MbKbuBzBBkzO zQPDBi{FY!=d#aG!GD!bRWnmq+q6WcDv!sMicQv>0Y;wlc)Qi6u&^yU8HQ6|1$)`83 zl&gYqsa<9zPV9~qZnF-&%&>Y5wIH>kXnE*!Mt%x}%|BkY|5IQ^sh9RKjdU3B6&d z`XokQy~PAqaMKqDMwy1(FQ^;g8g7_mcY+>mnrtADU5FdBUKPdMDR}RtOgU`|^ob-R ziXvCe7Ru-z?fw)lEdK@(^}WKKapAUVUNP^0*&wy5yXePS5q{K-(43*?gyXsTdgxLN zwgJ1I=fvd>A$fPq#xZkeiQ(BUqnC{$*W#mC+U2zuO4JH{>1hn@rN7xY@3ITiBnSp3 zp)8pl-emznZJPbXeA$ovv=3_XlI)j75*2GZ9n=?Bf5Qh1KRrJ;DTuHF9@s8^k~ZM_ z17?DJ@DLMH8U~~Z4Z<#U<=&6sK0sJfz^l#WSm#+_@u+AuuSsQH9nw3k$+a^3rCU+) zywFA1Jj-lp~+AQ?CLB+`${EEWaZL6a^j5;@tb|FT;xokL))M!Sw&iG}$87>+{16 z+Im0D#irqRUwCJ$BKGVQSIef5*}nsa{!z!0VD)S%vrmy=&)Z%W_>pg|9N2%Ou!wlS z`q$mtJD?U73=7(-y(utfg#Q?z6|{f9neu%K|Aa*JI4rhJn<>7Bft5VCQ-}6b*jJ45 z*_#|TENL4VS7t}BfUgo%&`8|vVKF``C)AL*|E_k}N8x^R=Y~87G}6d~&kmB{hYx4z zd^l}&!>?ZV;s1)j&TyDLy=?rw)?Xqw)VfhbAFqR|3ce#=?yvfNyu*D#UMC9?bQaw- zoo$RLnB#)&g{g>FfZDV+~Ii$bw8k;9DIs0FMj&B4CbfWN$ z$vMjbZ{M~fU{~?5ALLI~?W>^%20Cm(!S1#;pbAC~8dqynE}a1NFnNT5fk93|Auck~ z%a!$o{D>e?3b@Mz5DOcZRm#;$=YS}kVwDl|MxbGzo1HZ_F+t_|6z9y$k=?5nNO~h24PD(|_%D-Z2Wt&sATl#kQJcrJtKRY+MDk$s=Cwl&Vb|yG_vkj%&l}FTZ!=&jCmw0GcOFJTjz+R)- z)k|}W?7@_)-Q|69CQn`w-_g%#(h|S&cG2(#gs6VgU>laHs824i-oVtph}-cp4(ayH zqt;l<0lMdu?%94Iw4*9C4Fb#&_*e;kx6$V zr|eoP%a^n#tfrc(Z`BZIDsBOnQ%bJAoLO-`I{mPR2XlSr*B;ibXJVMQq}#nllG#Jj zHC@wX#%7>wLzVVul6DP??^YMN*gdZM&90-x^jF9CZoyh1AsWFsdY-wlo@wSbR@z@~ zDsQvW3wP4zvEpaVW;e2x`}kiY71-r>F-x4XtYWMQ?t+yAi^{D1;YR;eqi`TA6t-xS z%pa)S`_sjCm4IGJBVJ6A1!vGavnAB}!mIqEv&l&P zd+x!O_$|W=|8SSys%zKDTdT%1gX)6{e(^rR)Vk7b|$hlarH2=4iJ#AbD*W=*7Kb$59-UTRB$xtJ2tpqbKY z%~lOK7@XJl8rYS(*Xy5`XbDQBDO0sJ;>=$#2QdrZIl*IJc4S@lHO+6iCH`TX=TyVz zO{Q{9HPssb*5{p7;$51|vo}j`meqR0JNc=%$Y^+4BebkOx3+R}-oF1^9sD&CPchPq z9NM~4pr?R#a}G#jn#tI`hCp-kx>=LQJp0nLSU@1D8aJ1HS}ntYl69NR;PFX*=SxR*=nY>P2-SaGn-Y&- z>UC;!E$f1HDJ>y?AagUGd|k?`;|rRZuaC|D4wDE8=b1o1#ycs{dQ6K zc&@A-*8k3z-f=(h$&b0op+Zo2@OzkrKN$k7)WR(9?=52UqZhi_gnmp zLPH0^Yd=9GF%j4H0YDI|s;a6Ct@bGf4%~W zqpz>;>go#AP#F~&IXMOh{9GQJYxuG=@s0>>6QA-@{05KQi-;`_G~(+}RV4r=2_A_$=g_u@>SR}5Oboo4 zRx`7xsNj=dPAxfB(0njGes&IwLc+p%zKMBzvR52QQmOlwn!`?8Yt@XsHySB^9#QT( zuEMpZ_svJ-W|VeLR`xkPEv7byE%&ye^bB+EK1v+>%vlo%8(O}D?Q2dv#;4|7N~_1G zPdh0c9~{4wF;B-MVCj zrLhKP!ywZJ7kOVrx=AJ6w3&MlQFkgc?Scpz5dvMcW;w}f_mhmM z=qChCrsRG>@J=Pb5_u!@js4n?`qSOO*-IzDM9W#>%(}&Oal(TI>sQ8ZUQ%Kh_(kJ_Ez=dK*bwHF|Z1_w=~k*5Q}6!M+jwT^eO%RcY|djOxmK*5=lj zlQ&JZ{(Q^1UMchH_J}*@eur;UTpye;xZBpkq+}rX$hBm-syu@db0BFV4I`Rz#8P1z z_hyZ8{{9`KeVNA2bFbxDCjJIo^Z;%<0Jr(H*J$6W#xjhPe5*;%XBq8BXkaP4%}^#X z2ZgBli`G(Q&zmNbiPn)7DA6Gv*4&p22rU=bBu@>S%0eWUL*MiMkk(;jXQb5 zO?sYzd$*(v_$>r4k;#KrtsnIJDG-Da19}U+5$vO_b;LFAYe*OR$@nqH2Oy>n-D`e= zy33N_d=fN79KQW!E=mljC)+S+uCrJf47B`zLR2V3=ahJzuvcwo1=1(j%>}^5j^ZDu zU2FX7Wsl(;dI6dLgA@l#;OpGjWQc>En$FvuJo!;{wsp-+UeI6S-44kGB(V=hx*6n) z%@krUDOdF^ET{yUYcv7Jt%R#rvH9*Y>Y$u5-vf=!zrEsq|N7Im?+OzRVMphEY;1@( z0w&UK)ggi$Ia>J=%syCuT_G9pwXC~;y593BMH3Gz*nH&mF_R=6J9l`O+-M3vuLDvP z_HS$fEM}ZTXmU|olP7%Oo7eTf4gOKZx>Ut%nG_HiAb}|clHdOQ!@$OdhlFU?s~M&) zR|9x;0Ote{BNL(Cz0+JnpNyC~0~dF902?T;tW+&mlPE+TU;%wOa`kq0zBUPE%jFT_ ze}=d_v`9!EDK)^8-n#m!7fNl8ph%*xWy)2mXWL&e059)yL3<-7CuSXEI~ z9W-_dY=Rz8YO0#CoJNn2iv#RaBnnxDgosB>0LBIpHdA`)CpWqkDPP(k0+OY{ zlc-_UG&a4RyqYV8>?*n`q4a1ThnYu18PEx%4cJlKbSZZZNd<97ZQ_iCFVRTbfSUxw z7Zbs!(o44%m#G*AY~VX8f1B8w^EzuhTAXg&+i0wifJW$V;pLxxU{VI2R@x< zrN@t@?ft5EKlZ$5oO2yD4EaoH@Ho@&xMy|Kj$zV6zsQ2SDMhBF&*jAS+S+Yb6f)~o z)BI8oBp*%4tM0e27b8daVHIxF)K6U9b}4j)WH@7kWae39IOCKM1`--gaTvvI=Q)s^ zm3J-M{fjV=OTuZq#wakeE9&HTjbv0gRyhbY6oj|Xx-sLkhtUt57LQ87E!t&?ty93$ z@M|086=hNzeYPm{gqy=4^rUfAp+FK>zLWb$6Lkt&aybYJ(Xq&A%SeG$!=M18a9;>8 zTlJJ2b=KH)ft~aBb<9ZuHw1^R1qST+1{$Z>g1uvnu|e+=&- z(8Tv{To7}6h_lGx7+2;^15Nm@{eO6sz<%Ci}6TdBe6gRM}*Hp zywadMKbJstV)$@E;i)*830Pzuzf6T(!LN3e`2 z;uH@f%(4Wt^%q4pl}S-?jzCJ^wn3=j+9wb$$i^R14!f=Z;sUNQ@|Xs6Xr6x=pUW&W zM4Um$N|=)1wR*UBElM!>hjNKy3?+fdQHiyNj(BAP53`OHR=&ZM2Jaqb{*31iCrM zPuQ_B!MVgUD5tdmxq4f9_cOCH#r7JKBI?X4ZlvJj)_T67p?-H=`?I&*S>MVpyG&9@ zQJN?U(bAO~>DM{uvl~*yGBk08S{4R_zmU8aA7;hS9?)M&W`yOiI@p5>XmYkCKQ8YM zkP5>e4;?FfdfNO?G#@>Jd+U+)|FU6Z=u!WFEKdBgPX~n7+TCCDo7^9`KMJ^y$u-aaYoGu9 z*FM8|pF5s5k^dOj1^|cC371z>-6zOIOGrV$cB<%0u}V3xKjbG;q)G-9IMIW~KwuwM zv>cU5<8pg@`_@M-bbbbCl!Hf4vy#;UldmS&2#(TjFz>mwx$pKX3K#M*PARRy-r&_t7QQ2Hk zaXj)|SIh{k9+Q&`m1tUk;$Koy0v*XKO@Wp_B?;0hol~Ys2~V0}JlK5a0yLdeROT0tq{^^nByjiL@WDr)_Y;p@+Y<*U^;6^W!@m!N16q0pfSeN!Y7R+Jee=+K|iJ zIsCpn0Lg09Pr2&nenTWZ@TfT%#bPgjv2kGLgOBqY3y3QfMIKVguI==bcJ$oEK9}_K z4Ng~+vh2P|@9Ej5rxa}5K<@7&w#c&JUJq|>_GzV7domL7i2l?%=4P$hM)@~548>oC z<@JS|_a*>RXzGJx($DXc26Rm#@McvY;-Swv%`RO&axwX$U)R##eg%;JTSi~bdg8<1 z@*2xP)L*eD+5`S*J^5}LR01DzKiMJsU4#^pJYOfT<2z(mmjcWaX(V>EdX<|NQMGr4 zr8weNQRr_e|LCYTCs?MC+Q_QAn|?++V{VC8)<@^iqm*Gq+8^Olf!yGcc1fz@)IJ21 zL{yP}S34z;+BV=KN|AYlAlZgVQ+0=iGERwEEN0s{R1R_2EV4mH)&@Xbsv1+osr^uuj)!|{miB&U^Tl4X=U@HlU#ctwd8DK_HI7|8lGW5JnY@qwha=W z$=PXWZ$K{7vRuRtd7~(F*n^w6|ry9Fn6(QXWV(M}DTcc4CLYkx_1zf!>3% z6Aj~YsnrKiUzRZ6mQv&`yjs4Mm4xROKof@-G%_Ge{cPPLy?f8`?u^)IR`Z)3*Bzv= zsM?v+d50>0tdQ{1FXd;(%t42*vBBg84<_C1gZ=lfR} z%U40X+FF++LDv0y>M?Q(x(>F8gtEuypN}hnD5YQ$?5HaI2Ac)8Dp!S)JTBB*RC3o^lmTb8BI6O3x1MvNnbb+9qidcfpTbC;c)6E>ZASHg z1icQQZ1yUA7h}727+&xMpq)QjbM?9 zKl-P{>7WD(q*9Z={uM0~e^M-Ycg+%f+Gc=iKMew~_`2*{obO6GAwT-c_}9v!hk$v5 zMYkWn7A1xis!)z5b2zcgGN(GbO5X}~S4ypOmchU(X@^dkG!7&}>v1+<}LmI;D$J+iPk5dTqvzji#ZvA6I6!B^rUdR_~O=_u+Af{+w z>t2El`wR9HfXkvTK1^SF!=xS>2Aq@lC0_11m?3V*LQD8OZ0dd|fVhzX;VZK)VSk;{ z;INB{x#;nbCVG;yJVYl`MyV%*tXkcQB<>Dqjeqao#_qk?dSa0!$-9efxwZHjV)0&1 z)0Xexy7#ipcJB4O#7#h$NB{yFxqPSB7&hA+@=f@PIGzslquw+jxCA$<1aA3w|lJsnuyqC?ISo`Ex# zePNRvKL zk8&Y_s|~z#P#mym1-933C$$8yh7`8t375Lz;V9jA%xmx>1{{af2Z0VR`88Q+pUA`B zZJY)6&yH=KXb(RzArtWYK3>PUv5nU3@K``lI9DX(!O;-iSH~~x297UHyCUEp=gWs9P2tem+RWbI?@{lh0*}NTSo|4Yu9hFI}K8fKFCku1ARgb-80$mdSAE8m0TC(1;g8^ z9zrcz&hFpkv}uAIX(qr^ug5_F{H|nFwBeku(UpSAcBIFzSEtXWw} zYVk6CPu$G|w#{alWIR}C_)Ae5tJ2MrQubmoz3}B%;1W+O*@hNs-PL4D2Srsk^OI+| zm|)6#Wjd9}ohuoyib)PLpNb|>&XS@@|y0&G`y<+ z2x+6@IQ#>v<+8cL0l|Hxwe zqz;^f{Rw{0rKW$C!hk6;=c$9}J)}4_&-cxwJ$Em=sGem~DPaLWEuh{dNxO&DB3(OzP=RRYQCL?3AhwHyWlsA;u;ShCVTh z{z-TlrJ53QZ9f;X#XRUjvl>BdGKTde9CG1{s6>7O>rc~o9Ib)p4pM!q@RY^U@?%FU zy=3E?It=`Jx16P48km2<^Bl~q6IW;GF>!gmt+jub@;0YamZl-EWE33m_D7q1uJHj= zV6oKP!q8YoZ6r+t6O)dGG~*!^R-1~!EK?5ZY+=eQ>%MC|UrPDhOuS#>dtLsja8kFf zXV*t7$y0pPto{MM0UOB`l zbZE0SWpBN3=VQ_eqKZ?*SzoAt94Z1BGn$lfn1n;M37Ke9O!F)2M$=;Hj#-K@-e;;K zTILW2QlgGi%=?P_#KR5W#+S90hIkOS(&6*00h#g#4l5*D)OFkb{&|f;Z9CQ7lM)2! zZDnH17`~kIR054-6DCfqAJDYc`PTm`tZW=8{@(ZaQvL;|Ja0)kpQx&99UcK5df2zB zym7$nA9nYpJkIBQk3O2$vCWAlcg4Kn02WCeOz7LAyR}gIV6h>$~?|Af?9Ni zU&FVO?irzs`wB-GLvL(sY-+iwLUsloe1qU6o_IC-w=KHyOT4bCjzdv!LfOy6*xP>G z4ZPHPId9wZzs1&}<*me&+sMWVp+k7YEZ{y4IbWm>LE@AX^WYd3xVQGksyCqJf3Q{2 zUfBjNZ5co@JK!2zKu6Y8uj`_1mw<)fGNJ^%xX(Y#K6~^~`iB1=(%A}77yjmdIR-=j zVqi@l!mKzoEbASn*nLfG6E6x@qI{SXoj`pgySgK`xJH!MUw?c6v!M9B&KcSFKDj<{ z3q4|;IeP)e=7i*mAex`?`BT}KQi5KwgM)*IeOP}you^0O7)S&dp(s}|03RqiS{5+5 zk(U=AyZ}HpfVYnUR}8TEJ34fLLlC&F5{Xj`#5IqY`U>_`R78mu001Ju1_DV+!pyOT zEF}D6Z%ciAeEj$CUsF@l>FFtOumM#4-!p(gk52WXbu-|kUZ4~KB0~yS)zQgHPDV#Z zzkzJtUTrh@eN{*+*$8c#RhX1s)-x zzP2`?RRByT0J(7X#QWoacx+Dz^6KrEGoWp$T}A75-BOb1yJ8l?+;4AIj{osGT39*R ziA==9y=U|xOcGKOF$L+b23RtR4OG&oe(5L@&CXxMcVVJaAvGARFhEeJkXtKy}9nijp z>_P!9L(|PL#E+7Ll5np&TfnkjUue|F^VZUm$RG*xa5+CyVbeNmUuG$VyVt(d6vi-k;UEl-$g$JpNr_RwmSH zM+GIjU9;zIJ*Y`Bad}vNMcZ8ZsDnuH;s?>Pl6Z7cLcbhfOTUswVi~pXRd~FH%1^94 zO+afO3vg$h@ki9-97R+SfW4H1qVmK3pOrZZM(L~#TXl!D20pQk%!*T)rTaY`7b^E(30ZieRa1^MJ;|6l! zhxIWv-T3ZLy56*s^qP5pJLzMN_V@N;+POQV=EV!X1}5@`O|^UdZP`Zcxez z*T|yA{Tf*#HY)>fAmfk=J$htN(>l&F@k!B0amqONp=sPhVmqr=r1&-sS1DVkBr^>+ z%`3|)?`lA)N69tKEc-wX=U8!Jsph)vAmoR-|C=`IMO8w80YfJVYA!k~lT-+HaepP< z5oM~adX*L?tpe=cf!XyK+>ChUR+NgXK6zJ3nx3j`jg2X{>ny&`h&Hyz%49|ZYYD-r z^&pQV*Jx543*`XA2#YGhs8We#1TBH-R~TV>y0x;b(wmo~*Y16z(aRWce1O%u6vq6| zT(<*gam}#bOV6R2PDD`z;F6_y-jCtko7n8%_!b2FlB6sf(1EUfq+tI*apZ2iJSt90whKPkH+g ziY_Hxqyxv3fzw{h)h-De-w?cRi4^08Q`bL*-r%}Rrj2FVH&SLZz%1 z?wUsI!;t(@Ci`8f!V+VCg|=Q5o*541aFYy~+GwSe`5`ggC!B+sBpk_wA+8G97T$LkKehB6fgB*!e0QVL<^vI-YmOu3S4<-VO$f0Gh z6Bk6`4s4u%hkG;TK>?%jR}E{l&qQ{q)h&M%xuw(bKS%D=_7j$ zq<$n(?)P&>H2q+_{LjkI+p)YP-xHU2A}10BeIh{spVdELK{NCARpK)$>Fuv!xQXPR zweL+fHV+?l#($u^qe}otEB%<%?ckjl%i6JDoFrs+b^7na##s>WtOvwP7!g@LjD1&h zRGaebb77b(vY@BWvbF**Bnl&o-(EXQh41mi_snfWd+$SG(wSR;sHG=}5wUEXkHmE7 z&p`3K72IlJ78ykUD*C69wK#$DZad%u9RCi{ks;i*8h)`!sE!GV9Y^>oy`RR{(&BzG zaa4V$w<(}uiFXscFS!occzuM z5nCR1Gt37W3AXja2ZjPp4M@qxs|g>fgw>a z%2sgsSsLaj03X?pA(aNuHvq$-L4HzlG9W&1ad80-Ilw%Kj*brSZ;+Qqj2}ji9t2VX z3zRIIb-oA!uqU8APLu+|0sQ;~vL|ZF%4q25Mn^`Z<>h0eqs4fq?_4B@2L}O&5`Zwx zO-)VB&A~}G4GnB`sZrC`etum_G$~RP&h2{tV*pMlXw|Gk6tAhPD_b}NpsI6obID0b z?kJgp7&m8~Y^R<(Gh)VnRJ{#+$xgRnMS%g5mKL`8z3dY>SJ$hd8W>e^adCl(aC!MZ zs1{HwD~Z(3SVFiL1CIddNW8g711!9`?@s4ag$cl0WuT>9_Qy13Yj0`-$YmpY*K2Ef zrqmsTk$~?JD^AQAF%w@^pQKa4lZMbw-~Y&bBbs?{lE=Ni0I*%KCn!V{awkp-Fz?d1 zzkI0?VhT>5;YMoEd~Z5hJLx_PQeIraqIgzt@TLi>TYtfSTYH=j3jPckIV2819IG|< z-?eE>I?8=XO_OC`+$o~Q9b1ThwX}pmdj_$h@w)p2OhZ9GSj@TA^oZ={pWSf;@KT3B zl-&7_0jHjilW$q28I31TeM<}0B`b27(~P>1+tyFWo~e_wz}6#4GUb2y@3-a&h#se5 zjU=qJ`76HoAI<(_8FuOMY+FwT0x0}DVa)J7ekbRA7xozYFwdO>{T3*Z@0%aM?(Ey* zS1v4NK$!P;WWk-S^)uQ5)CNxhvKn|a&Q)G9t%FZ?A+`8ygc~WPjmq*|I?E>t5P!@) z9Q;`kCXRxa-L=VmANRHwYwE?PwpT#m6xrq%1@k*lv?ekD2iObvQLy1>B!hJ%S~F;= zW8ef|N)K6kHjBhgR@t>=j8Aosa0D3U+<@1iR$b1mIhk6x-#dQ3xqW-;=;kL3nZ(9< zxsiW^nwV%}7d?s+<{#UiWP@sCIA>kN;9eNOMemGgjBxqlOgTdj(aW)TVF7&_YZleCj4ubOdh<$j-u zYtcB1UPoR}ld>vunQIlnwz5|59@tYsfJOBKA@tsLRgQ8eZ$A=ltH57%295%rQ*kC? zm}WK{;{5lzxD&iGq*y@;(Up>(N>ncmPl7RfLVt+7W|l?9`5rIAh*0V0NG^s&&YC~I zr6D!Tbm-l|ULCVBokKqx{@BVd4t7@8cR;*3N`N7j(qLdTI1(c^9g#1y)lVF;3K{H z0&v4E)^tHxz@&7FC&O)2I?gtQ5#LN!^6#uN7se#Aos#ku$``l;n81+h=dw-%HJ(j= zIozzo2LRd(3@P^SGb1VLmwkgsh@&$1p&lG|5{ z2FPl~zn4T>xxMb>x$R}9^7e8K%5}BN4RwIQ?9)Oi*C+$uXJ7Pj;ed){BKC-Q>tadQ zS#n`f%x!3^33ba$7c$EL;{N^Nv zmiP08kMKv{I=btZ55umz>+Ede-@tO-?`7R5`vcM4k_ZYhS0@MK3vM_!L9 zK+JV|x+b7C*VEHeRu(B%`66GHpH1AGE8`2~V0w3LL@542z~H1ni)_iUGMsp^0BNL8W&x0<13c{jJ*c)PQG0GQpN)Wk z&?~}zK!+J{vmv~(^!2k9DH{Y_#Aj5kSLwb>EPm*5Wn}L^ETd#AO;C|}*kVWHtZQ)W zkL0MSmoVf~kT9(l-=Y2833afQ?Ipn%yT9FE>OaHbe*ak}w8{(#r3U>#-PRgp7J?mY zmS>4BGZQkP$#u2X8)W%;d)*?xgsBQyd0O3p`}Zay+MVIu64x@Jt(B9VogF;d`dwjX zs~RHOyu%xP^G!eBYW~Z8n7h_ZCJ4NMXXz+ZgYpvTD5K7C z76_>8jy|$8VN|-}B_ymMZ`U%O?_3qc(5lL&TovJOeV!PMI1;16tZ>D*YJXDltAuCd zzNSLp@>9^vqOyEv zdvdc;9^?3uUEL)7sf##LwBXH^a$GgF1y^I&*lu^kS}AOjWuh%`o@201PBW`CbMaf8 zOZ`x@8h%;H@c!Qxs5qbYj+YA4XU4I=HqY(97N1<6$LNk^vDWD|1^|FBZtk^W;xY{w z4(DDwXYSL6f$KYPb%{U2j=le7FkI_b^Gk3^m*_=5|KxyZb&P7FqR@U(d)WeAeQc=W zpNX*eRlgTX_>NRc5WF~j=oU>>C&;R^8_vK1sy2P{!hx^^X^IBWY&hb2(tJ1*6Fa9l z5=AA@D2QLJJc-N{8=S+n!kFCBLPmQ}X5WpIr1g@?08GG#dgwG`boN2$8|H{p)>*ulbY4+3#(Bl?{rb_$p6m;xW>zJ zOf91y+ekRMR$29?trqxp9>$PPK42y9q1Ct^mjf+XGIuTsmQYRlJmz3Yf9E!HdKNp> za>7kvG3l(BTf^tq;qF!L9r7O|S)GFAQ))0bjc4R&uPg>x5{2aFBsy|A6@GPCR29mi zaePkGWFTHHy8h6Fp~DhBLaeZwE(umBTUwd}u94ygEN@c8b11mY7()%*D@JLdQ}mr; zg#tR#vJyfKEO_Kx__Y-LqgXF*7Foh

9=tbrs(ZS?@Ma;I} zz5(L_V4u&-tf;8C$&Q2fzl2_(RfmIX!6^dDBn35fA%s`GR!oAWiVB)H8L-H~2?J~| z7&Wi79Ed|f&${$5rORvpLf%-?X`A>6ScC;>T zQ2}8RlorkHwVs~-M=p$c2jxg;>_3HytH}Pl@{eTOV=xWw!r-2B2uABa?BU7qE$+-h zccB(sppy4@&{FR5wK9>ED#ESB7}6nQe>BDZ01}MH!}ReCqUU3FWv~P)B{?PAX=ym} z+vPN{p%V<36tV-3cw>A^S8gc`{X35V28Wt2i@n=@@Y#unCj2ribc1i9N=oWXx@WjL zel9n)*L{d*b+15WZLT?_pMn5nK?iz zLJHcX86TkJ!CBubII-!q#faLwy7gkg(MPrv#ZwuhKvV6c43%~sDp*axGmZ(c5z<@FM6eM7nfxan8UfJSoFu-0wpbQ5O*dL$0 zbNRd9Ky25KBPI?wY`njEd&14GO{2`Hq2DRfJin@e6Dl}p#(K2 ztmGO?Na|G13-AhA%2Td!3qup*w+P!Zp^VC^!Q!Cbs zFF+ZH8%wr#E7m4hjvH#&uK^FW$c2-SnN3+an)BKnxibs|ncIX7z(w9@Xm(e2HI@JR zJ-@{X(8cLy=IGtV#umt3y99@fV_HeSD9IOTOGADrjW|W5hRZymL(^n_ly3+T&ysQ>Q3YE3IH?HGV( z**{5`(aSfaVm(>IGoju|r{NE_fz;~$?LE*$Z~FKcQg(0~o(twz|6kDrJ`qZ2zGUBD z^d4*>0r$F|_*W&tio!yz#BBD|E<8B^0N&+go!_DXAk`4f3znY;SU3f(IPeN*BGUGp zy@dO<4GpJ^>nkcMrtttWuSz)r^cNLEF#khu<)HD*$sL}rO639|He--%?VhDH5F_#_GZg8WbE*Cq3B2ws-1(W#|Gviqee zRDiw}@KrW9-`||Z;b@Cw90Q6apnC(*dB8Q9p58{*QT4k;5v)30Dp?{88ynlVZ`u@S zxCmiDeFR{L=s^{A^*bl~Ya}TS;QPPp1GP3WFRw<8u35)UT3VWg`5iF5g0Z=1*$WFH z;IZw5^d8dGD`F<(32BPeyc2?(&+CD(KSimI3z*+HVT5Xs{tD|if4eKiE#r+K0WN#a z6DFakBq5~n{E_i8;Upo&{A4PHv7Cn{`ZfM|W2rld^Y&LWfU1XCw%-5ORqjoAvew}p zuPKvRsxy~4^aUD#h6GYXd!BaxR6)R{4jDUXrM7heI7Y`?g-0-GM*V|iE#QFLyV1+a zC7*a#Su}6K$785!{FWT%OPH!+D3KfhNCgm(&j3`rDH61|kN46Qks5b2o1EX)k|0bZ z37cGH2x1xm@rlTWdo^ufZ_KE^kymguvT%oq2P1Q4f-#JLF*YO6_|`Ky>;VM2v|)bxUV|lH8{C-D#LXRur^OA)xPziF7|S>yed{%fLny7 zRtbQXM|njV|28Uf0*`ZOn`aeeP&>uX03d{A`R88CME5!+0j07&@xt#cym}RcbQ17k zi7Ft`ZA@74KF_8#Hduq=cd}pcG+fCsc@vBf&_puk*T`qp)UE0O3H2MED-hd7wbTS5Pg=?CBkJr3)w0;O$QC@f6w0{lj!+dyrFt_6$cdV`|pqH4g3 z{x44vn{F_gp2l@eh1XKkk5!F{Dchk{u3cHG30Y_WYPhS+*tS5ram(E?i{1|t@tQ01 zo}t#W{O*Jq2>LdQ+F}}lxGWv=KOrM9h*;{jF+7&7ZNifvEQ@1a&%DCu?1lLaQn%%k0 z@ve^Q>NFA}9%Zl-x&Xpund}ZYeBDO9NrrTR0i&@x-MOZ6@7@kraEk ze>~an_^S;ZT$Lq9cm_N@4JthlQcdO|B}?Mju}&KQAS>eQEy*Sl$OF`v`H+;aqgV=0 z%RaNE$MsgehKPu>l}l40E*FtysZqS9eytsKB-cvJ3)Eb8>LO7k%c(+0P?~|nPow_! zeB@o0;;<|XF3tX3>X)Pnc>Ux%E=MPnSuRI+f&d0psokd!?c*syG{l7I-hM!S%U`w{ z&>8?E=V&16DfE6nN^m~%v89?*}@Ku4I1xT$xzzE1!)OadGQVtlK{|#sUFbn%k z^~kLg!E-;iR=9af^j324Ki&!ddaWWs#-gI4_V)G?5)y%*pj+MruoAF1fpH(uFc=Nz zGV_1?hTGm&Qd$ZhD%!ZLr>{>)Oq`#R0tnPjPELqJRXygs)QWoi6ft~>@!<_BfikMC zt^G&01@Od?bpf76qR>f<5)akshukDHt=C$=*B@J3nNMq0Z+pSbt*dNed46dffqWtF zR?YYA3DYX^0RsPzrmu=>v*DU;p}14r-Cc`Yuu$BJQ;G*E?oix{TX6{P?pD0GyA`+M z?&o>Gv;Lce6;?>N*fx9i%rA{~8MD6(R-x4f`YkW&0tCQX`J@DVEhN@JaW{I>p=(r^ z0CtYFc6o_a^m}2NDwQn-wKRjTV@8rDLNT*m)qZ)`-M!=??`NX|XL<*+hBtUL5utP^ zN2>5f4}PzE^WHHnjUTv_kUqd*o|6`obPxLS#T~r8WP2)`Mx_J2Smj+T#2}xExMiJ` z)mjNtfu(!ZIV3|*ohphknZc|~;6466y}Zp_Gjx?l)jUMb^9x5*3ZYEo&6^k?IJYY2ne{ZS4XHRwin)_Z zF4*3#ZS-cX$R~yW@qwT_1C}5b7U{C7)0Ou$7lwv&q&kBzFvqet(+7k-2rfQr<~j;Fo}FXgV(a zt8TOVp_-wQ3opjyzHm8L@pcRpBFX&X6gOTn6g^~Iwt>L<*B!b@zy&MCPPJ=hW2OjJ{MoBYoRd&v=U_2QB!nN-*! zchZ{rEYZJ1Z9YWEU0<|Afk$n)oc-Gk)amT+WS+37zt(3dC37cem1(|4B!H-}UYS0I8-(QKJKKx&<`g-HUFD5|isGMeRB=NEn{=4zKzt_mQHGeJ2HLsn5$ zWp8aw!keJYQLNAN( z_OFV*%=b8sa37^cdf`;(`|D2f&{K;7>(p6Aeb<%m>Ellt!*(YU-`9y1pDwhi+r^ak zR0)A9f1H^zj+e6l3rN(LWTu1X&~YmuuQE!S`0@P_77hK z#Gc&cZ+C5Hrb7@{HjO>PG+-1N5T#Y$i3H?>vZ8in)=oqqaGV+HE?+>qNW`YEBeS^Rs@yRF5QHd-{ z>K^;A()$`_abpeCB&jRO@55(^7q;&k$L{Q|IF0kf<-*%BAK%Gz12@Lb$~;!5pcSTV`cP$G>iNJzn}5YlhQA7->AyNDQ zwVP{0nxm>+jBISF_JVC~;c>uhl}})h@o4;Bnqs1DKcp+$imI0AD=BC^i?3~K zB_mcQAz#H}pqd)I zQUX}%^&NGK>&t8cp+Xxj4%F|2d9o+OvdE8pyl~UU=voG8lE45t{P26%#HuAv8o6=p zk`0`@=Uep1?xpa#M)7ygH*^V1w_$@9-#1vJ!DCm&W`hJR=7X;&3B8*Xh=3UyyOEIh>Cnv{`><>WrWy+PhazaPGaeM=&iI1BZ+P@MY zK^M*TYlV3wAtLg8CxhA+Tks9=sTlV+cC0BX3LP>{+uHR%Mxrg+VB})c8mwpE-!JyV#s<4?ZO|CyVUllLr)S^KF7_*2 zP6*$iQ&JMDzh;Ydi?sK0zQk;J-%PyT@`VeBg5+tpby~rOD1=uV67%bk4q2Zw-u}pD z-53gm8rnZ!B5d3*XK#!f3%6uXtQL0cym;H!y}5zc9mL#T>M1U^=tW(!BwzpGG7LS| z6m@6$Z4ZPCbSynbJH9tw+4ru^|3Eo4^S*6CeS>eDe0?19STy!pqyT;m6TLEUb`pDA z2McXg?`J()`1vRK{7bdSCZ+Z(capn)?>F4!_d0LX<@<7}-RWaTl5;M(uTD#=jH3PL zN2SxsS?9e!2zuE9?iW_XErmBEEG*kE^ABa?LRCOZp2O3Fj%C?2(J$MEyUNzCB$&0T z!>*4~bn=19F&_9rGl!HEn+-Yj0X@!dLiT7yD&N zbv(N)ik#}ff|_6&70rp6Im+s3=KWHhP3sfM1~%P1gPdc02x=tnBV6m(nt@tfd&3fb zcK$EgX|`n*w_njPLGp5PD5XR)8aZBp8Jjj$#8Zv1Ntd4 zOjs!VT`+?W862mrQ=Asg9)Wf7G(+~{UR)eFEEMMP`V2W-nA}QIf*~SpG6g?pmhOEG zb)V~f!XTG-Xw1p^g)sR9ic-(+74+jl3-xbDZ^E|;>NFvGi?DjejXXLgn;E%EWByvQoR$2GpLTCdwYOCcLmo_JAoF<~4MJrQ zQYDYV%a}{ouN`Paww0uT6itPvgfYmERwR6_sYZottZ@UDyy2qCry!NCe9+b!Fhb>6 zpoR)t$n)1i_XozxHDAu-?cC+X>Wj(sXE8txQVQ^@%ia2uNHdi+E)#!hmH1$pR2OD7 z2m5ews+{xBZ5{JCwP?mObTlgMkDFZYBQLUs9?&;5EZ)U3IN6nWnKTBUH(+*}Bc|N( zZ~p)Z1sFr^QF^E(q1?8w;dXcV6IhSSe%!u?(qj$B!(|J&DeMXh9+)I&Iao?Wo5e8H z?PWx@@irP^S^Q!cOsd=XYa#5-KaHG;yAHSvzr$ci6U=Ib=Y{AnPO{+AW2-u)F6i&g zIj1>$Od(;f#bv2Xk(O9!d$3xIBPp1RL%(j%Rbv@5NJ6zGLzv&mpruHLK*85OPgrjf zEj3iwtg(}lMPZ<`*RPuTdL;fBBZxS02iqP}q$DJxxJ4}j;UGsIy~j$_>woCP{?_53 z+Pbe|giJ}u!PfeFi4ptxTLQtWpCj}EIm01S0Gix^8dmX(obP=9q>sVZ zvUb{LvRY@H^0R=7y7W{G;{(i&zi(F;rorxwXJGf=7GBd2^MPx5k=`VsybGyovpk6&UBYP7|7Pum=aKqA$BO#}{@ZQDu16S#wMzT<c+#O5av$D-@lm`U>ZWzn0}`dM>!&wL#zHv6m05O;64 zJ)X?|39)^A`4vj00|k`dF1F>?Z?##R4eBEHV%_|*^meth;dMl+s(R;nWc0dqyz?WW zUw+8zQz+=a4-a`KxhbY6cC}yh^9J}cc0YSmo*j;d<|Y7m^_fwg@N7_Yso}O_<@4=8 z6mi%6RPMP>erU&S^vw?GI^-3|tl)QXJTA?;xX`lSO-lT%{EOI%ji5T(dCMsNm4p)t z97X45ZlA?R%udeF<03kR^ebmzH^LO6L?_nKOq=+^j55`Ug&_;e(g)o+eO9oc zqz#W+Rn+XT^3N-c2cGz_@hO}-&4|?D3#$l|LN$R%4JcNtb*CC}?lIoMGNR(gN=c3S z<$8UHVM$#%&#&Yon;JZ?_Bkwo+8>2%I7?hr>f*J1nW52I7Hf+lv(WLc+=64K~?!T%8DMua6=*W7|S z+rt*&3+TaLVaOtA3cLXqDEmNa-y^vY*F9K*wY`skRwxOWf+HgHG<-jJvGLso-u)$& zO*)3pP7eJp^q#Hx@WLh7e(nID{KG&rY+g#hx51h16xgl6-v|E6&B};(`?BAR=102n zQ@V0U#S)`WB0wIw=U@14Yo%Q@SvyLTefw$NS{K}X)EfC|CqFIF7NQ}^ffnQ)fII<_ z)DY9iA48mF^k*8{}nw7oDDcMx_mQi0_=Q9)M-_p;99lq6RPV$?f zS{26rLIQHT8D&_Gbk%@RxcuDBcK2ZuvE!Dv7lpmF(m*{&7dnl)V#RhB`|8GwDAv&k zt_qB9gFL%3ePx5CDSZo=xo%(4jTT@+!XLATO=8$9?qS6x`;nW2ADi1wovpoI{Wy)u-6GI41|ZOO0*Ny@1NU1*BZ&#Mg&F~1SK zvlAat7-#SF#0$u} zaucBPr7LQk)7*JrTI=TwV}!-XHv>Xh!k<1BYn1`oDQ8T*?F+-}>+72{;bZ0rz8(P- zi#E51M+stpF5$`v9&#`>H8pVe@mQv8-2jNcW;4cqZ##At4D8NXI0jxQEMeTfuHXF3 zt*o4lWBRF}-QT!+5*5BzigJqht$r}zJi7>-4q%n z_gvd?BnFG?6U}*)7S+EMC(m7UG^3(h>*$_2%ZewwZE+dt>p7(V$b)UHb;BIR7n&jU zG&-1NKb>J9scW-Hzh#u z*3U!9<%BQ&`H;5PBAboz;g4*#ExtgZMG@x;!}e0l>(@H9FRxQ?C)C-Vv3(B{H{VNr z?+BN3zM9iEwsMKAKcp5ZIL4F;(Kq@uw5YmD@P&+v6FFM9lT8B#!wUcG_?lTKAFG2{G~&!v)`Tu)1memlGZ2mza2RUd!^edCuu|< z6pNs2|F7dj1Dp3T4@HtS-W?m8foQx5ac@2<*{E^p?s=+xVkUx zU$`rze2fU^u#-{-}h$YmXoB*tJQrZUiF<*MmjX8M6yZ&8=$XOT7!hA4|0+W_Yf6UL+et zbt{Z=h*PXxuqGqYl8;9LQK&iiE5|^Q_0zB>kKPmFZ>tc`ZOw{J@ruzQ**o6a4Dse@ zYV0G@;ZLbL{7!4V`c4=&?jenoo>?8?F*e3hpWmLtl#72PA|tZ zc(M0MZe)ns^~0+H77hDuHwdHrBL!V*7mc{8LUovZ;Q2=l=*n|AEMxL^W@Qk%$}B16 zzwZH{O`7kor0*N4ukBE(Nhc$ypiF(S;bavO$4=hDCD%yokA0!9Q`B7tP$Optu&alf z=McLnVl-(mO$o$$PBZB!0_;E$cN!Ia5)*Y2-aoh<4?DEz@BFXS>p57ue`<8G`})^% z7Abe7khxaZQ(%_r3lR+q;lkigVv`plt5k%AcENsi76PISxMgooKW zf7$xs${gl<)I#lRd&Sncc{lj$I5-fj6vjSH{fuRp4%%WB&4DU@n3udKAp5yVyZoHM z8q_t&edrX_b=!K;zapoRyxHt*^!-c8ua1c7L@$2w7WqZ81gI*tV{Fs3MvM~%2t1|#{iW+J6EB0gEWBwEe zu!9Z17^e@uv^1?`#c^^p(qy{#{$%vnFD}#zvOcfFDA~BlzAO*V?XIo8&~k&( zc^}>9!IUIfprxUucHk_d{?QUtROo4L&Qw^$82*7awfu`tNtn#Y{@(EFsakGzMt6=1 zgDG~0WbP-ug!;C&r_I=d3BT%Tgx?iAPMH^VrOMxP5{~thKg3uVHHbaTXxi@YtHeGI zH68gq`aBk&-9K3zED9ts^i{n*kBz){ovZsX4RoZhv-pCfHDV8gl3ULui|2;l&y|u6 zR`}OfH4-z|2W%1U*nQ83+v_j5$%R^)00r5Y=kYp&Zzxq8d%5R4UC;eZ{9~lSYrfkh z7S^)nosSqBS&+xE4F->adN;9)?eHzNx8;qFPjhd==UR@B*W}zqRjbLF>&+K{-wA`9 z;ZIlh$EDJmf7!5k&vkM_?`GrU-y%kz?mVs46jojl=;hDyX>OHhkXi1}syqbDOpmZK z?n;WfCT&(_7O4E%oS0M{cLSdj&wCYdeLr1FDEL0z4YwpeH;v0VOuVACXlH|}0G8*=_PgF2NmRBdKSXT^H0I+Z+h?PI*7`Z(Qf#{}N>9l3@T zY}+R#-^@jJdr87kKyyYDAk?*7=2#HGP*=DV&c$eiW z_+VV5=W+#o5_6HHqJb1`?M*}j-B#B?(_pV4%B}=KiZ88>?s+sh^$ODRtR$V+B%}B~ zFG!a*+8g}P0cf22xX0y*V7yCDq4OKXXPr|xc3TqV-k5e^j3e|Q=$zOPVY5!sz3|a zar%bXAaS>szA*rw5jl%4ma$66we*C%W=Ea~= z|C^ozy9Td#Aa93V40`xOjq#|Gj|x}xjI;_u#Ub2>>yC{72zkcCAGv7P6Al8yE%N_kAuOS%?$t&m8*dD43)CgsKN&xAM48XTbvxaw zm``t7o@(FStJq6#BC=mMS#6(lr${iWi#BNZ>FeZouvamh-c-zQuWGm6`uz&;Wv^o2 ze%LITPDbeac12M4g=9Ftfpc^RG5f z7IljVJFmUGVtU@AOB^5dywpdlZfCL5k%)T2+jcL@_0fzOjG(#EutKqNGDHY`UTb$T zyviXoy1|4?EX*B}%mH$q9VS7frOh##a2*CBgwmsW6VTisyR*@x%@{ z>|pA0mTw(!(P3%__D5=`4T)YAIDZn|rjZcis(x4C#x@4c=BWtaWL#>js`-D&-Tf66 z5U7GP|3hU~*FR9Do`l=rymTe%v3;?cns?6(F$5e12(g!v|3kY83!;y=r72yQ-!> z|0~CHj6jw)vP*WWM&7dxq}j^*DrkV~<`p%*C>iUERED9z zJ#dIM4A7bYnTGD}?#<23y}do5-Y~Lf8{piyu5QMz>B(EP*7_(@E^%Ui`_uZ`+6!~$ z?Z0t=Kg5fMhU@I<@$H+Awl-m?I$Kg>*&JWd3@>MQT4n`u=m;GhSR_j=vodjz`S_%w zxS~L%Bsf7>mj<9&%=(y{W-OwGFiA*f1 z5V!PSkgFEFD)T`c1l}?Bak4)^NtA*^3`tHr#oI_6iC@2%5~L6oCeg{3_NJcJ59k7D zsCFU31_2G9tT5#Bovv7oK#(m(k|lJmdAV4xbV2&K0R?TKKxSJlk4`@ieXf`i(kX$` z4MzMGQo75~EiY;iY|Nm^Crz4NsWGa>WUi!AVp0g^MW9vOG|y?YDq#D(z&?3{G8e*- zh{ww|r>jNu@520wtC!5apXx+_@h)xsyL6e*)5-FaMYW@tH)5 z49r6N1HQCD@119vY2e$@C#D$*$)aJ&&7h5sYF+rsfA<)RFArKfre0^|`|>w8gJC6Q z|M8OKjSXX>CY)rji}}|F8m13t&!Xf%4#_r}V4q@JRX5lYNoX;n`xt{iew`}#a+AM{>wVOAVm;9=QksM7L-r=-~feZ+bW{xg+IbVf*dsINy zoMe;{@)lI$H_gRib%IjzBvqQ_VK$Kg^)j5oSBrLsu|BJ`cy0CBiWhNT;&fQr5>ivP zK}p{7naLgh?L4ugztH!2q0d>{xUiRhj-T{2I|@Bm+p}n20x#k{hHZ~H+wi$@lwms( z^)l>7p!kIL{fF{B2igUlZB<8m4%?N zNW_p`ufk4?fq|NO_vBtgrtywkKPF?PF7=A$RzYa4g$$yx~a?8#Md0 z!LoxT(zxPLg)ayIfyakgzqSEaLdlQ7g=@zOaF4XUef(FIVv0jiKv`Y3R6e|zPQN0C z?;y{m5I2Mt{sJ7W5egS;87edrS%G0f+?y5kenFSKhBwHTD>K#3seP$=+474WM-?9g z$_u>1w}wmuijspp7Zj($qhFO)r5S2XF-vw}QLsg05e^S2Ecu%$8}->xZH$_U2zuNz z*ZMt*4Q8wv@$hP(U-!zf!=q%XcG^bA>M~@daiB$;<>*_Ui4pY>bAMau6fYmW-I
6;dj=lo2jv#!cEIUNCx5W zJhmLDxER(uQfD&+gD`)=It#5zG(oP<+OCMa6#1tOU$tHTL}4fYiKUhMqDy`e08R|F zbvU<;_Deb5*nPMZ-atPPhxO|D-5LAmD%L1#e`7n&=MB(oVyECf80yJc#KV}lc=13~ zmy`$pkWdB(@7;ewmSy5lnZ{AJmVTeUC*2J@RMM5@yp)ZfkkvP4pH0K!&&6YUHL6z= zi-xjP!@(n&ei4q|gx~uV{-=MZ$56O7`wPWN%xgHX+0JLF|1Cur78-x0+b4Bs;ch9x zpc}0LHM4&yA8X>^FCB?KQjRNTW0p}>FcDEv?G&V)%nw?wS4qbvy%v(h68iOuQ1vmS^evAqbB(1vA*0nKhqxe;d9MAV&ZJH?qd5txqpCmLP-s;46Pw_mkPU?h_>J{m&q8y1`wu&_J4bzGf=lZk3l zN7`u~KRoKZN5!GZ4zt&lKmdOk{^6p_*xWI_pYsq~n#e&NWZn6$Uq*gGI0NBA#Wds2 zQb-YA9BPUSaLVK5X4`<{JL7lT-hDrj!-=Yb-UU+8l!|4|kWU=G3m-43vm1};G6F%* zE{x9TAJ2hJ2h|k)-bnR*PCwQs!vEqMYUCC3vPu2{i0=kzGS3C0!Z6T8++ajR>GXcH zS$5X9MAilljj^!`9-@;~(U|WwwYBj|Mg08yKrZ0p<<->I7WkT|86A7roOdh-?`@k|5)>TnmEhc*o%{ZzPkfp6SID^v58>x zzz}QsK`lw+t6)7Q=^S>&f^6KPQ|kK*aETTKI+teYROr zu;-p9FmL&j^Yewwi*<)@iBgkBS@e&;v(>Yf`gZfId`Eahm{ztbp{2M^;?ld^nh`p3 zsoJAcJ9QL9w2+_C%9`=%iFG`*qkCECQ>38fezwQ%O?&e-6xoRnH*r184T)D&4{2@0k)Zk|7|l{@Fg5B76f6=B0w`?p>{Sl&${;8 zu%4GdN~jh<4pviDm1jII@)1=rBC@iMT^+)lIDIC2au)0WbpP7gyo`-=a&tGa0<_@+ zIYmXIx0^rHl~q<&R#gEe@@~>lKx|MnJ7#cuZ6w!7RYzysIMK~5rDmzX(W7KcOH{;w zEc_j86lj>9jzE-LF^`dyu;k$1zb!{a^w2qTViFSIZWwTJ8yg$5kk~hnEzixBs9GS7 z8URM29`rN6{}z@}U7v5?*40&{uj_b6IWr~L_c>IkCV|Zz?%RM=>mE7!XvbY1Fl22G z#Dbu~T}@}pR`&LOG4>I_AW%@3bVA9^=CsjMsm#@hO zfz%tx#G&KC6pyJ>i_vYH}5YWJMNDP z6YLL7dWb`HmNdS!uqTZx`Ri*W;q(mG%cWo+s!7^n3qIm7k$Ez~!A&u^?@Q2H4@;`5 z*4K$AVCKPYGR%G`4HD19w2t>S%P0!FNaV~XRz&1+a5{g7V$^hxZtMSz+I1?(h-7d9 z!MvwK{VKD&1Ss5N_?B02DuWw)7_kqR6+z@QP(#4RPS?k`KHie@M?@nw2qju7`% zy@>fQ=eW7z>y5U+39xoAw*qVut;_**pKCxouRcUmcjD#Q`W{mU?o1-FM&bDdy`~ z17smGiVqAO72)qgH};a}qUonl{0%lAWT?(8cD!kOT%A z_FcyoDJdyMMMWSm&)B9}R(IQ62v9>LbI(0Hh@wLJ;_f7%z-bRzj4V~$>fsE#J%kxI zQXy)9E1(!Ll=0#dZQMI-K_NYBj>HI%87wT&v9lT&@ZQ|uFg4WGC7`CC9Uf9n+~&&u zZ&lO=QHRb?ysTTDPrY4uO}IpuSNc9>8a{>w+Q!@!|5wZ}Ud5?Ymuw20BdD@-nfAns z!ecEfT>VEgtN1H;;yT^009&J_-Eq|Bx|d|rB9XZh@Qr6}$E|5P?~XQVt zY<|4Cf!gXUI#p;p`Lww}$n02A$15TEG{1u0>O_9!31g4uu)@I!I+%PKntW783uK-5 zUZopZr}T_P)ZFhRRmGtc6b(fPHq|b_v&h~NAP3d|mO;os3>V}M{G$&zRds|g#a06J zrbf5GsCp=ih8)gTk~mu0K7wmEDaL_Q`t}+OA!Fm109MqV$EWhp0}m5~Avyay%)9X8zzb$_AnU1KMQTKJ$qK`hD6MA0NBj_YUnquk>O`Nf}4{VC9?3Y zm+kelxAv!>J9WQB^w#Ai<%_%}@I2?)C&WX!F|k>TL5D@c^(xwl0np@ORf8!2YivDl z68p!CKxJYp6O^WsPIxo%bH9Iix45TeP?PSSiGg0wPUqusJd9#MUuLll;8~E%hjb&= zz*vKRC=;c_`FE;b4r50nM-kCQzEf~qyZ^({CnKzViO8A)W|l)Py~a_^@^cN&PC;{Y zGVD0~iq~&tZs@8da!+=f-^`g356oO}Xiywtd5_0)&))DMSgWon;+?``#sc%*KLezYCaBuwK!iie$}^PLwu% zSN(5o&fVJlD)GNk9z>xm_Htbmq3-bEzpDyFKJqOv8}%C=t=oTL5AN%$Uex=y8zc2_88t zS_V0Ro5P9<#k{G%p8%B$l*`d4im9|TqP8`*lo5M~2GF=49jS?SdHZ%!;RQC$`1CRJ23>%;iR|7~T8iA0V!dugLrg^EESNcS zXk%%~AiRViN$Uv@eYrN;@I0;%f{7ddckX-E`I6AI?s?@ZH~aMBy1{>U*A0R?CDjr# zg%?I+{~s6NvM!rK)u3Jrzk-)#E?p}}xEL-8xq)u^UkRIX<3`84y`rn&jL*1pl|{uu znk8=~&q2x&@06foy;6rtMff~W!g)}5OI3KMLnVDXTyvF3D`(hdOM2$Exs$eMRFpJC z4QSJ$V0y;wnWSRaM-|4us!W!0MP)eLJdXUo^VE|f4#9IIioCM01Vp7%quLNDm*~U2 z)lYY|(jJxs8=6sjxLc&bpZGYcZR{dfgg)L@{wnx3H%r#!>aRb$oWS8m&thDlyz+!D z6+gSze25dStL`(8^GCW{0;BIE5!dY9^2|$E0t|*oTyOxF^PePAx^!YeIdbIM$**_I zh`M51I^QHHr^c{s5;Vo3eSGOZwJ*;upT(smkb#31{FZHjPr4voRZ)L}VhneNji%nK zeYjWBPO*v52XwJmd~tGKkTl#Us{Am27=?Z}l^*Or3KAqoV-6zelX5iR+qHCk8@<1P z#^5EDiR{4&>CIV`&vC^%`E%`6sJ$EI#FMl4bKF^&gm&ak(FF&;Ovz|E^*EZgWBUD_rW%lqU5khW5#1=ymu0otW?ff5Rjx zD%vOrVL#>30RuQi~Kw6jEp-|+05rj42C3>tQ_lcoe$+yMY;1l zVCRzdVk-CG-rd>Hh=cIJVYEEwJ{Dx`U0tV*IfqrV{ zp4{NLtkhFF0Jq{X{GK+vwx;;S2xWZ(eBJQZhZSVcy*~5vu5oK^?28*WUtb;ZC16lP z2HqQ2Xm2ZJ#(GH#+XOGVZ>5FmLPNF%)~3pD@AD6%EgDujYy2L%H^h3BC$>tm>i@^% z?v;qpX8feIysU6LU!iv=36+O-{*l_aIqUrx4Jy%K%2cW#ijlEvrU=J(CnpHV@&MAMR+j+t#e#GzX6O0;Ynyg-tXcAy5CHlUz&MX=!A3D9 zbZF}0(y(R+wD~{`1MAw^*~FWhq_nXdc(hOj#X>dzoc4wWXl?EHMkmtgC;O%qz$4Dc z$jCobjRA)!YJO_U;Z|v!RDli9^a+;SbZim*BX{i+co4yV=`Q;hHUd-uI5C} zAL8Xk6bnkK%R=T*8cJ0fTyw{(|4ar!D16BFT!uYby(__@dIF-bs6Z0FOl3Nxk&fm{ zF;&mOfa4H+@1BSgF-*s3oSj{&F{V|vf561Rq??yn#Rnp6{odgcP{TRUYNJJRH0U<> z%_G=SkL@Qnf)?vic+CpZ5H6FrjJMTS&GWgDj#A>j=^o;NRt>gGNM0M zfgZl^(tgZ=nu+q@F&uMk~|<=cn32h z@Cgbx{vnA(hw||>=Ja1yE-~W)g?I%flx_>kjTzDJWpc6prJX(5R7SnMpxl{Lh)gM} zMa%gmAu_YiTZnT-i16z;D<=^4g}rMZuQL6Y=&HKLPb=!$i1pXu@wM#T_&=?lB>zwl zdg+Or-lo3T%sn_4cfNpfRL@#hoG+IA%0uSAVT)$Ef;q%9svW{M4|PAJ^bKLv-H)Fd4QrAW~@C5!jUpY-i=Z(>uw?GcApp+-X#9yQ zN^lSGyE-=oD%GlmmBmGOR}qgKBt>3S8DO1Q0@fr$*9PSkpvw}b8(i4IOaT2uuF8S4 z;Ekt`pWmCnok$6`h#U95-4B`~X_`lO0mBRH7@H5Gv2xDdct`HT7R;JhttOpnqIxCh z+K`^Pv|!y6lMaW1A#4b51&XqTQ1Qnbdxh$P(w|17L)IB+i zbZ(#}St~1yZf*fU_UKf>Z-wJQE!<`&@fE zwHt9n)kUed*Eu3+bCRTol=vV8G_U#4_T%2ue>q;ZfF9^i+nQ=LM~7Gzfumt`%JLz& zwnsdSjjgZgBomKe7CwC)d|U4&hc9jG!b#E>_b`R@C-xANzez2rU^>>;u%g$X*#UPq z_EZxXr{@7e?Z5dpvbW=ERW|tWyH!MUrb#XPtfEw5B7y>V$yWAq;`3-QcHNskeTnv? zLX@VNt?Tb~3wkxEvDg0RPe4ogo)?il0(3%qRRCnD+8b8+UWW2Erw~@JZSmnuV2`vI(ai69iJ+f z>)7i~idSW$Qx}}Gm?afMihiPKAms`Uh4$pgf6)lc&9VVPJxBR+mNUyFsVdqDXT;l9 zKj;0nuriW{M!o{_tV1qccQR{@X=HCLZL+f!s5NKsvNDw!ZzJy8R&DAh9us`q&ZPrM zS?3z&*4Y~DV?)L3Dw@G{&cFva}y4sm;Jbr*fzQOLd}uxYki&&EPl_w818!v%gL_?!TyyK?}xV*C6rV zLIjdQ7%2NU|4F7CkKs-(#`E3ZArO>@r~(+s0i7kF7ngxFpUW;!Z|HQK4=qizqiSks ztc9PDnV__zhEYwcE+41rz@`Qd|As6fI4i%gQHur7OPDOOe;U9WqC?|*<^~1^ zLPA37rl*|v#n%Hhm_#fx&W?_-k%MDU^>LMfuWvMg==}~jmVa~`0=1Yz^#v6PvkOWk zdARW8iA(0#xll(?XB-p0rsf)%|I$jY_}|e|+`q}ss@F7V{7bIvb(Euxa!fYs0VcD!xL-CyW?6ggTd8d|;kp&vhj%m9B-L5n##guKZ zB}Bh^b)!jmGQIw`&=!_Zi2In}^U9<8{A+%J(6=){Yf}foX-vS`Lp5$WUN7OZg*oC@ z{Pbro%%LPgXQ*KA_-Ic0XL()XfNAKG?}Xq?9l9{iiNJv&F-<(RyZ2(7;6KCQRw#<- zgFiti-6d&67%XKYYl8>h;wf)3v(P_7DIAx`VB4B7Tl8X~D`Al2l6!QZy+arY!iMR# zo{e|p_K1UzKqUZDO}@vnj6R+~IVTDIb3x(e8wtyJt4B|Pi|3^OL7Xyps7;!$(JgY@ z-;|z9Cj4v#_rX`&Tw(;*0cFUmm|arTelXN5b@FVR?pJ)OyoB7K z0-815g0nyD;3$OX&a9J3+MMbl2`N4*{y|QKRpTSRCAK#W7Ov$s4C}c{E*{~2Lu?&S zi1p9tcv1r}s=T7SKN~unJg-CK+izZ{IkI+}J~mzNA0X21horg6FYR8m>n+&FpYtEL zk<6*a!1jnU$I$CXOHUu37P`--K_v}SqlGjLbm#>*0hSrOUB5H3PLMvdy>zmPO%Y}s zrlVs#K*?VI&6ULmN?mmOhuOULYw5w+mHlRAkT6^)wEKU2y#-L5ZO|=9a0!s$B)B^S z3GOz*-7UDgyTd?mcbVW8+}+(>gS)$B-|xSBt9I{JE$7Yro#Pq1mR2Zdhjx8|Wzgx2vpzXA!+u zAzf=xF~4$RHm%g=$9lW;6@Jb4EaLY)7(WdhH()RQ>A&iq4Dx@M{+CPtVFQz$!P)+M zPJme%Cx{|mhUx~E@0r}aj~W#mzdiN-{=UC&sv=Z--E;6*K&;<(IW`kA=|D$EB>YOm%-;@JCtW>4(u}Fg#t=T+1c5x0wllzBQdMnh+|t@S}H|>@t133 z&bd`j_%rz36H)J~JjNYXz#nwG-#Jlt2&`xLOy@Y!VaYMpC#RO&?<9n zD~8f_tuy?U)-n9ECeii0%KZ1nVU!!?`XvAbWhq-{OMq52EoKF*f$tH>5|*k>%qHE$ zvI0BZ=42eDPnH1gZX8b*LYJ>{MB%T*ia!pN@Pyy5A+CFPH`{}toKb; zeSEIi)bjRcsB8959Y9*QZkc+e!K8;g$WR}};f5CxTv#6TV^wHnLIwt%Fwm5EY$XjJ zf$aB09>?NTa*B(|kE{_|A^dccmIe4VD;e{&4`c#cQ4hSzFcY`_^t@1OPG66`S{75y z9fs0OcxGVU@t8mD9rW$$r;oMmQRyXZ{ZNIxmWx4n zUmo*`o9U3piGUA52vhVnA#(@O0cZb_3Sn~_LrCPO88a3X+!J-&&R^}d*;h}jLD-@| zbE*p)jFCHA$6Ol+Fe6diPRLDuGvVh3#xA$un-q7yo5_meLh50D6oT3*Zh90O0h4qy zn8fspAvGTAFZ^DmYGUdrAfPW=$ow{)b2p7UlMG^!YW9eHCT<*&TwIo50uK8`L|q=x$(uosH~JbS;Jc@HxW^*&}= zheoLv_eL|;iO!GP@&PXl3sb=GxhM=H?XOs9(ojvjrX1O*d?iwX)wZ!(=1_!@rXmA< zgc;l@tu6ZmMp#i(EvC0V$rf3qP7*-G#Y9V>qlvw|^bBiID+=yZqG+u!4&dx?p`7e< zWjx=G!#uB0x!EK%!vCF4myq|`l-UG1Yb^FU=^88xPS*IunfxPLRQgwN6TrsK~#GRlJ!XY#yooga@NN1k;@;ADqZY9My)1gp5GTMMeX1k z*kyFBC9@HA8gEZ<;ZNXbpXK0Jz6A_@F52$YW401%-6N=7{u7|6&Wqg+`5yugNceGw zn2$C5kzz)8ms8F>Z?Mt5z5Le+L1I7f02fMD78d(2*K&++hMPAz=}nhcmm!le3N&-j zMP7$;0F)1`*#KG-LEV51Z<`>h_hDHqf|{Bduu;uLfcCMMi(sN%r5FGY_H1lS=&(8Q zoS)y$sFXGR{NT>k!7M;L+u1Fi+~I`+c4FwLsOv>q<^VAuEj`+9`^y^{1N`jW0W=jo z{=j=AmvHN!ee;yqf&q&aCa|Y=Llxd?T%;qb@XGg85fD2J9u~-a;oG16Q~ihA zs%B5N=nW3De}!g;BQ&5Pya>`j|X>UI2k$6M5gcXaC2W2#IiZ62$Al-ieo z-YN?wF6suqq`fQ0a((=%j+`^oAa8O)mUJ26DENHOeNn2$>}P=w?M9T=q@yEAGX4+a zW-xueRYT=HFD7{dNA}OGD*c_(1P0yY3hf<`GQ)%+ zuHXWr+`aUSXw66I=I%w?D9c8PD37$Cl4O&PeGY~81^+I5U)RH4Mi_`x2?DemZL#Cb zOokN^?NwMgALQ{j138P3J}X z<(2u7(;DMlvjagdDJcmc13-#@Bi-uN-Ck3qKzGTvFgD(GHGXY=qe;90B}!Ek zS21IQN6buVt{x3&cCXxl%Ke<{oQWR!)56IeGHf95GReuwycN$OnyJ}$)E{KIOE?Y>~ z;j5=RN8TNSqIi@b5pzO+lzsyXwK0<_BfwIuLOq=dV@?6>fhDj$Fz}Ih7wlNs#vlMM2dsKY~;vj=uD(RCq?`p>UjtG7f+;9P-xd zrhe+3)-XM2sDHx9y4Z}1jFVDHR*$lw@5^8no|z$Tbf&Ior`0BwQaY9vEme|Vna*-> zH6!51*S=`6x}1r(BxlslJRXOCsp;;x19#MeJBBdW*!WrSL#8~;(vS3lV4u3Ohf;8P z*@DnitmooPS1{fjf?QJ$*1lBlE+zBf2IqS)S@LOTUo4rfx^XYS#G%9%FP!QUUzMY_ z){36r{bcU@_5ttC77CkEXa^}4D=<}oKsg}FFymDDdHCK|C}%D<{^T>fi3dq5_)N>F znR6){Rn8z1ckIf{H8_sn!5CM|UHx{3Gp)+k>axD`%lpN@AwHup!O?G%*hq|BvNf}g zTHh0~!Wy!fvJ3J<_)!d%9IZb5il>_v5uX-OoQ5W%bb%PBO#|{Z9Uf)R`;6hb&o4Qg zzijLWzc)|dpZ_g;-E4ts zUOOiL(e<&6$69+B1^tYu5qE0&%Bg@*sz8Gk-E#5Lae?WQ!*wj6*c8AMAcCy`^_;mk zgSF=ZYcfg|RA?ckH;q+-y;wKIVlk_x(K?!pZ#g(>O<^@%yOfo+@iT^sP0zS(%=>9$ z^x{@V-FyG#=L9*nWS^Xi!3SsmPGJidxWMb!G=I3%?P_LuUw2*Sm zq4d+NT0_6|v}yruu@qtKTA-+DbYedBiKn%0l75amgr}%&u#6aG^ zfR2gTWZ9??(q=jq7qu*Ilx#eNfr{T|`_&4x^GmbsTO^yQedtHER&ILqY7^2HR_+QZ znKBIJk-kK-?@Te#!;qbt%T$JIF(R-0ALB!0JEg!k1WHzWxamjluWRa?j7ONv8>^4U zHFdv0#tjNQp#7Y*VzaRhSVoY4sFHt0TOdHq-b=MQ2XPGYt(SDIB=LHdZoVY=-COwS z=kF-OeS%Ypa;lB$DOy>9E?ZLx>u^#nl-tumGdOGExcXKr5-78d#nwq)@ z@Np?BI@sUG!NCE_geILzwX!6s0(U;&U==w553%>dvOGz_`j_cR&B4KMi2W}rgiVQj z0YVyDTKNhzfT4_A+nuuPO$h=ZAziy{-MLBp5uSKI4-*1%wy^Lv-T#*Gv~&Q&u_s+H zs75bYh6)SKM|2TpYiMg5J-7p)lJ;B-7~n0Ex3D-Gv@mTA4R?)%qa%wFl`k=afTTR$1`a|+F)P;wOCH6pyGeERM-E~5*y4+kr%-3Om&-yv~~bZ+yx=K zXzt?tgrIlWXqyObSjV-w5{93_yeIsK9h~7G08NCK zl4L8S>b{d4BF#>QO|oE!bJ4Qm(bfmA3A0A@^dJ6(zJ;hb*Tsail|iBvQ^R_G-py{l z&U(0Lms=un5N=^70fg2LZ6`t<%jBi6B8GI*4@GuXNqctenb1m zhyh2Xu!K(+%2hJ;hn)QsRPh2WDr>mB^R<*uS3I}MVU7~gdA8o1DwW7hsNy;%g;5ysiFT&kSKGaGLt31@+HOxb@o!4dahqqk)fd zIo;fJSlS-LT4bvu(hV5PslD{^JJ*j!9q0_^72&z}0n72o)jL8SFP-I)A)=2t6X| z*XDQo&zEExh$#k~)<1uQ@)Up&2f78zdfP@`U@QOwDY9RLZ9_# zm$b)p9Q$2|zZwOP$;-_e2uJqJ#+$ryjawIcAmu+12aDzGyl63%C_?OvnVy8dEWE;Vj3+sovn#khICf3Dxg)>f?w^^&a|_x{Y|ARt?p`MIb;nbu*TPEs zcE^*a*5+zDiUD`ish1;-C6UPT#Gypb#B17x8nAKBp2W4IjVGCTB6sbReSfOyFW>pp ze$f!)m?_j!ajRI+k>)_~*sS&ZVwgqQx1QScd7I$5_$51ueDnB-r~R{mU|E_S8fpc5 zW7fVa>)HZNS=L`YtiCYu0Joet6uOt0F7W(vd`lHpHJYE#peaus*97c)HrHHA@T7Qv zw8ySiQkzoWq<9C@rVlN;{zxw_#y=r|BJ9E4Ceis>VsZt&h9oub^mod=i=UJTc~Lo{ zL5RSo4zSd2AX&i>7b1q8kkrZzsJXKd#`=we9hMQ;`16`kxQ1~g^G7W|cX)KC0@j2{ ze|DQa6SFRj{(EE3=9B2kzqfQ}1X0N!hcxIRSClf`DSDlnp{!v&1qno4F&!aL3crI? z^t1v^zj8#7Sz`@A?AiGpB@mCye|R>ryq$9X`&A4KRuBq_&ok!T%am$uDhG~$sOh{! zEuoP_g(nnXibQ+n3Z;yOF;wAI3BTJ}?uQ4$!WY1yRaZ=rObr8@c z+ok($Z9=N83re}t7MCex%^4ZDPT6l5bxJ!n?2s5&J<6RwOhaZ=H^OmihKfJ0S>Zn# zS00~FGUQUxLB$S|)_jgVU-{{I&s9m73>m3Y$BRZ@SIk?bceVnX($8803$A}G87noA zrT3wil}IvfC`3*58lz^599Am0&+aqPEJHs|sF9U$nvR8dSjFuYD~yG}IsNR`%UhB% zR?g0yG*BI;?GiPL*{dFmcr+4!1+zYhwSTLWil$AF$GRH4UXqM>BsaMRn>vZ)WWVdO zryRyS(0}zoQGycB&-schj4OgI^xqYCm~wfc$KgysMC6Oq`Bv+9jf)GGlb1JQNu8fp zg%2XdiLBSE==}>!_)VL$6UEpGNwTH^E));HB6fCaiQmdEuKb!F4$I=Gi7R}yh>&q{ zftEy5TN|QOf`Wn~h$Th#`-07tikccMmaoHv9wLGkX5``VB&q4?>Z%5r4#q@+)=?IS zb0u6#g-fEA82PF$T)@Swzf;jxVA`b6Iqk>%eyXXJPEOW>S&__>X47(+yA_-n<4*aW zhndZEW8?9LW`jCtB1_y~%nkPpJFp-eMmz!PA@kcV%gQbLFJTVtgy-9G+8DNjt7PbI zH7#eglnU|q3Q!G>P*8JGg%EUNEhyBTW;&5H)nD9s<4+W4;lcPaT$3g%N(U5onI8S2 zIVFF)ajx0?s5s$U7uB&gyZZOD5Y6@ZQQj{WqLd8ULnbeV^THcW6$EWjxn`O08g}jZ z+4Zv|t%N&*f;D<)mKhnD5)mGmxmmbk>bwzpifb~Uuix#I_s%XCTfO~KIyW%GCW7D5 zCJ}U>S9La@%2fo@9P07XrARULqH1T~4HW#30d>nyDxrk1{!ztZs8{ ztWbJ}`mOw%K#eeT)ntUbJ#v!hY+Q>V8g~U6Bs`I)F4Prx0R@^!8evw8; zy@f*0%LZEYZHngGJ9yw__sk!}Io^P53a0-%4e~Z*!-X`s>S@M=e)2`Y&XH$Lr+TJ_ zL5n>9d!@WTx|m|uEh%MG`wll!sNiO;Ixj2rQZnLD>iQk)9+3JIGF-zwc?e$7U1F!3 z3mVHK+o=SOfn&GeXTp*v|DqC5`HSIAWm?Wy{E@mMVublZh5-tQCKH`Od^M?VuK#{gm>!iDe-F;$ z+b@cS?Iuj7>@=nSKy+NpdYaU#X1XNB?v-X+HFb*J(k@e*VzDrjUeIJnU#WpIIzTWS zODW`z1zCp=R%zvjOd8zcmwyZ6#6>LR>(12wgN0jO04EAx79K;tBmc|d7umho=dbF0 zImH;5BYml4_Zn$<%2e6@FaF7a_v3y6YMK8|1)DqD*m6NwChWz~|6Ms5KsE4&@$OQl zR)&s-))7qnt|#z>5+?TdS^znu2kd}til62|TB7=oS(L|!e(w|ttH^Htg&c(%=s{vwa`g&%sF1(GA!sZ&M z;qkXDkwXxm2J+eYNYe*!FzN>uuqc6tzEvY4Gipd;5YFVY}xg~e2)_G;J*Kcfs;m0tHjcOft227&xX4#~=g1CqA z^Z;?MpDH;=*n|~zc{pm;iKRv*rusbg%JQ$}qRgm$BX~`E9 zjp6%{d8Fi0&hZXsPB_b|HmA<_0~&*2FEB|jj?MQd`J4~dF=RH?Q{RdGyu`hz)EoOP zQzO1VK0B3oZk9W;t8_7WGBgqmkA*4C27u5>6$!g?$&3iM^IQUK!-`4}QC&J3=-B7- zUN|}`d*+k5(pj~2_m4+(birkeSL~|5380jOHIlP^EoPbNFK1-a8LMj6STN=*zQl7@+)cpu#EBL8s-X5gcO zGczDj?E|`fJzqyZ59(oKR>3Hu|8)!i2SMcjeGt4*`(0D(_f+}n=e&l9<^!g70y!7D z&tL9Q&xaS*{2q0WZ!uli@nKkiZ0y=rBn zdl7>>z^i^t3c!GB8hphA8I5xdo7pi|hvqf_1OY&6!zQlnKM= zqa57aKZ<5W^J29sB=p2!4g|6G!_Iev;W}bLDz)E=mNVyVCl6<~tcMK7xHIcn?3ghK zP2$U1c1xAE1L_G$t<*=j6K~LWUv-h(o$f4AmZQk#jo84U)O%kaHR+ z$-mZUh{9V9e?Bb`mrS#!XIzOeR<`Yq&0e(I`MBz?9BMGmtWgtOXI?#`znW5gZ~TiN z-$;FA37ZZ5_nIiaoqFFgwqwlio=_!+(%39I6WRLw0=2sOkxIRFrBPn3{xrRLPAjI0 z78FQJSwbU6e5h2@LE%|z2?Eh^K&0oXNp?Two9v!}v`=*j7n1!1MosPSwyf9=K9_sC zQq%O!DjH9dz1-4{FdwkpG4T`WmZa*)<=4JSkTyhyLIP}ce5E~JQjD>prVf^wRB;*z20c+lx4dQB1o zsjU@kO1eYd@)V29y-#I63E~b+gjBOBmc>+0a4hEP(2c;s zz^Cxm{jd79oiq5NUDMwH$n&4Kk=zXWz<7M0w||5dQ@%0j5&g|$S^h2LjY;&2FYp76 zH#k?x`1N{S1#5_`1-@D(HJ{8Lr=&9&cCPp88uZAQ`Gkd(FDU~_?Q{=%TH!2dVM{9{ zpLeDxEfiYbvRE-(&(r-WsMso}I)Pd6CT7bEucx?^Eu;-Ip&+VjT#Rzd5l}g>DDv&P zg-%}^`_M{6R6LjYrjD|qrfVLGXk<~{eT7w0)38ih$0iLzTf#5vbvu&PbWaf)Jp>ml z*7&`)$vGgF_S5XslMMJzT!yrX+4q}NV^>dd&f2t$<)LvKYzJ*hnHJWZ%2+8cD=*Xy zVd?m)8dgfrjsa+wWXmy~D7`h4Y*z|((YrmU%c(N@eghJDViq!0&tef2b@OgkMup#= zj)_YGW;bGqCqryD7RMm-k*cK;6@>5-Gah=GVi*|+8q|*fi#fgg6={;b4aGvuYx;)m z(tq)%X*#*7@O)9PkG3@~J;VllZ1trbG ztp+x+`at#&B&OpDq4TQ4*De1h7y19Zyh)I~0ac~l-QATHEeee0K_N+I<&wm4Q}Tpi z$otgQRhndHm)~t;?SIF@E^ZnoCT2oH0vAEF4AtzBGfpHWP9%U64jW%Tc?SrQq{(b# zuzf=OvwRx%ff)L3!^q6iGD3{(=wgNp zJk7m2%)Hb%^(Yw$E33w@GOyZkx9?DfpM_d{3vTskUl&KV>Ur2z;6q2c>girpGFs-X z*DSwRCRKMVEn>Dz!cH)4!XZqf8+U8V9+$Y*o_q|=2(%9(w!9RPwJq*OZFGM(GQCX1 zw6%xW2!D(SkI9L|%O1Tko6%8^KaoN{h!6U@ zeC0H6_b%|l#6!en9IV0hQ~R*k&uMNB+}Gb5cMVy>3e7;g5;OI`AmK~=m?ytWI}=bF z*OOx9W+Z_!+lzItp5H9;v^B2Gn{%Lb)Ir9U z?br@3vP5!jWhyvP*s-)+ldUhybLH4=AO~CM7sKo;a2aP8m0Yr8cQjB35>m12uVQ1wmx~he>J@#sc(X6NzpGXT! z-h=`DLx@OqM+Xt$22{O71J%ALU!X)36V`3u{Vx+@d_g^*la`h@ZT?4AwP-dD^jmS_ z<-BwUZ_J1ZcP_DNaWJBP(DVi?C~x6}JZ^}ZY&tCsKdAc?T9^g<7rw8V)hdu_F^FQy zs5oSr=l|z(W z?v5+Op{(zx6mKyv^$mHE9dj9R4*kkI}}A_F+HWYs5P$BKKC2%?#F?g&IE)Iu=9UUXI;ps0G^V+UN zD~XK20(SqT$(55uIem0P|1g_HGc|M8XoMYq-nO^;iaYJ0x9rrL$rbZk%O%q#0aYGI zhcA#yGAiw1EN{1!#=VaRxijQZ=ra-WjqDO~1ee5xZclAgN92;qXY`|DL98Ei5m*q( zwtR@gEeMuhCzR-01X-r@`CUfIq8-&v6<4=*GPJw6cuR{sc4={Y7~LXx#sOAUk0&|x z9W$+Ul-e4$j2kjLed&GrsV zL%2egf))$9?IAknCC||2es%Q~&?VWY-!)9C$)dJ3b^xC(M}7QW&0ibWZ;cy%v@KF7 zGm(hvSl_SXLfI+Gcshl`TW%eaR#9`G9zPJ`*-2VLj1--okAetB3mYk;-!mXt708t= ztpkO8E~&{K_%(+Y_k~>NXK>k=eH4CWO^>SSADNq!;wyf=7SiFyy;bV%aq_$}8T~3J z7%xC+WmVIJ%j%<9)KNLBu4*XcV{9?Z_gE1hZHsv=jeyI;8jenDdM4fx`dm66hv9VU zG*C+8ty7@`jIu8#*gO%kZwLpTnWDV^xv}8= z0#Rt`>jUr}pkW@?yZ%x+O*vRpI6#vK@Oj0w`epn`@HzHeJ8W#VPEKEDk$ZN+o#;LzeXuV`GNZTnspXsjUJ4a7G?YJqQT?SO3>_X-%-DM4rwg$8?Yzi=rt& z(WCG77!~ZQkn^gJrhgGvE;Bz#(uK4bDY&4Huq8Z?6(8eaF=hcBc@7O6YJG9ZXO6j^ z2D!CqX}}{~o7wIpukqt?rLdFfRMuA)f5+o_!ggf#tWpTfZEc0B%UwEKJ5DC*3L69` zG!HfD6~rVEkK!s`&T3{8CSQeu#|u4B8SX-{$H7rU-n^wSa-q!*6S+T@3%j?Uv|Xq) zqcqH;)!!`VQ8|O2_!lJ>iru3`1~svSt)d8jivuPw^3OdG#apg9k?s88D&`wqx>xls z*e`7hu$A@QR|H$GQozP54N$!O@@eKU>WkR;X0fuU>Z=rfhf1)} zw1+0*b@DT_NnReSLxog!hG=tsi^c+uRC;4Y`FKiQuA0(UW3(vYysPR;3STDa+uf^5 zb_c3;Ta;QG#Y*ytoFBaUm}~ExuY&(jmSn-kyTMmvGJ-$pkT-?9Xx4-S4?o{}*g-iG zgZ+r%av^Vu=tt&4Z-*Z*9f!0b_e#dSkk*i$L&B|`Km3f%JZm7xIY_lKDNbddFgw3rM1HIF0v%YB4eNDE7 zO(XiOEq;*meNi$}3NdFcC2r=V3O_U2u0i`4jZA*$m~e|d=xt0ChM67S{kG!DZrVat;?t%Kh* z6Spk4Px?%wnDEk8p{&?Ky3B(kf$k2l0d_g99g{bJw>Rs$=Fg_mTyA=2v!wI#DFW=$ zc385LfUr8mMpbQxWi5@G-JyGcJ1$(3&ego8PHY7k%S&-9GEl6jsL0IB?8^Q1^_4FUq@$F-&`U&!WqWrQuzAtd*9ZP^56{EKGk@)06*H zE+dRkP-0AKsKI@Y6B7wy+to_k67DYr_We)h>=BPblAPQe9Q}KaFQ!5ivxfHPUN)tZ9T{F%9o_ky?oH^4UE^Jlwc*aJ|D%iUFXX>OxmRo6HhD{ zZEqVh=~ji&&U}|KtENER^&{QXZE2 zSZKDUpDCjNRJ_A_Dy})$uwy8w+|sTj$2ToZZ_DrvbBL&mc`-7o>R)VBX*CLVhAIeJdw<5QuuQz^+K+emq?+6|xwo|&jaDHxtrA*H0nro1pJBpvAF zBeQ-Onaw<=vCrU0uH;8$KkjVi`n@e4b-sQr*ME{d|95|YHG~sk{8tQm_j40?O*2>~ z_rW?Nob7h~>SBfOuUlM?6vQ6$n{N*x7Zh=Hq~v}8^WVh_8zbig5b;%14`ClYk5+~+ zRw$V}R$+b@{d3j(xb=C8MFeJc3*}sv^n8Epic`KrBYSq?08HQ^_ICqZ?5}Pi&x9Qf zKu(8)3SD?ir<=g6nlc8B7N=YEaWX$!1UxE(q@$A7Xy*^f#Yxo-=m`EB@ z-PFls99Hpd*Pp&@VX}p00fOv;IZPO}CQ22SMn@qzj<)yvE z`=&72D-ZqYi&1!=6XPwu~ z;~rHp^B7mus!vfP+*6gb=vVu#;V7N_8ej2<6Z5{&==ak8dMHLM{J&Vb|HtP?d#uOU zxWlzI0-~6rHNxH2Adx%<1_t})H6arJPh%={CXK6`cVW>nKZ)PW&=d^c&3ugH!|jLo z0`Kj)2y|)@)6D7;WT+T%Mgh-Z7>CUvm5WAEsszAbnEi`O>pCzWh_2#7oRj4OWkSZ9Ynq9iSHkb8)1+%7+1Rb{fj0#o)NNQT zMkbW$%%e;4NvVV#!2FDBfT7}q;rvKb8otZ&MZoJTfWYcM8^>_gM6~8Pw5clX@MI zI9vB-Y>!rDaB=*3UvOr-OgrkdD+w0p!|qm05abyPEA=@4q*oCvNSpI{`+8ZxunFxj z8mzQ_*m4PbTX||&=OS!m8bmd}w<_8jDebH~^pY3{kUX~HR-U~m-xIYIe9Ia2<1@fw zml9UAieq&#y&{i}L!l30L_?qGSeiWLdMSy_w?b~s+;H*uziPOYtg)q!P4rkIgMiK` zC1MDm=;{805exV{3&K&89PIVcVh=CROblsa^yqsROE2r`SXH1+c~k$-)QAb83dAI*P=aj!fHg&z;;N>7l z3BpTaNJe6?R`0nJG~omlzk?M(eVjbUhrsZ|A%3>mEgD=Yi6D<)4FUk=i!?^Mi6=`a zGSql91;M`bQea(0k+~{11?}PyGIj(9&l{0I4(CodG5sE^4k9{5l(V7fO3$R~lK!kL zt2BSHbQ3+}QRVViR59iM^!3D$oJJHK`uGDz1!5ic5E=4VUKd#@-IR&uC*CSLVTW7s zw6md4T#XXX_n=Lpb8Tp|=&1oU9CUlLY^V=YPf-M>No&(@&8)QARD1N1A#{}b zg;-W)1%#F!DXJ?bDQ?`9Q%n6kt%wFRMNJ43VY1W9A?1rHXz(@NLJPdOFP0}0o+FB= z1z%@mq_b^@wp-imL$Fu>_8n&)qJ7OgIUPddMF!EZshI_!^+`ZnaORe(d3d!DUfEUh z#L?Za$bDZyc*_UC-D#L9c>*M(FmLrFQ~Jv0(vNOQXnz$;Yh_##7YX(_fJle4{$1uD zi=%GSkIhT+d$jW*?BC7*PZAdu&F3OOOiu<;@Datx6)DqTrN)hqjji$lOq=S`@UNC+OWF&KTdRU+J5kPB6a(w)-D%Z`(+eAtEmzM)Ho^R*onJYQ3E5!?SF@@!6w zbs_miu?^1gmBJfrWz1thlCHFyN4E|QSm*ka#&qUyfR@$pHDzbTBrJVr0ClB)6)k;K zzMtyup@Kg-3+~q2@7(j$5TD zbY!=H&$j@iLyM7e-6uqJA#LPi;SBZ368e`SWp44)ZW60+fy_s2g(DAa!~|lxos{cC zA)Mw>KmbS zil}E^C!%%~l7ByiOY-PkS)Y5-_VklJu(D{EO}Y{L$s3=JZoCf@P)Qa1g(bqW%o+|v zI-;^`QNtjuX;3Dm@X6lEqZ#7oV@1-COVTz ziu$#lJlX2nUyA6*jIdCt1&!f~3(px;iz69bbNYtpzC2{|hS8|`=B+lADQYo6QYbC6 zejy`CVCdeISXL{hgrzE zh&QC`+jGM*=}B>W-Lu!GMBJg*(|nX%;Q!fNf1tf=CROAL+x=hu*<(Qbt`XqyAj0;H zi~weCfDZy|nzf4ycFf?vaIAQdJlLRaV^*XCbaDSLV?0HLEb{Li=fj(&F>loKX-9DG z;(X2uG>HWTlz5Th4sz@Jwo1Xp3|Q!%%E-zuoz@IRfbBOZ2FZi0HmX# zmCwMaSgf*jf)z;#fND9+yEh>QEWk1VHv!XHvC7Kz^+-<-G*QgpU;Bqx_BKi`dp!ya z@@0{@3PT`R^kNW4_Z;IS0WtsrN(52x5Jaocg?t2Njm)~756g0Lp!LNlp4*)u#~+bF zolqa=*n_7IrYyel*tp%!`raffwq$!k)wkVo<#_5&dY_vKJX9>YoP=@}4nEE8K-)DF za_S-Qo!&>=3EZ`iKpi*Tac$v#n7VDr_UNVne*WNOYWcvU zpC3)s$oIkBOn&VEN-vf9w~%EeiNZ6&SpQAXCxb`Ho$#9?89V0R3uNz)*Q#cHWopO(x~b}p>Wy=V^@3?5#XuglhB zj(oG^Ra%KL+4liEs28t(Hn*~dOB7Mj&6lcm_Q<9ipV@6z{h?*e%>u_f7T_dZY=)Md z@v5uM(u_Jn|M~ljQ<3cX!gng&z5>?Sk}(xSD@Qg?_40U2uhDt_~Iu4>3^2>>fhsgfz=?{pd zFT*ZdyLn`BG@lS*gM`6ifkFcS4BmA3iGut?XA{@t-Zr0}ce{Xo$tSYU@hUBKZ8CWZ zK=%GCQN+eYaK7@z#lweV z;SRd}_p*ZtlRh;oRf=p#!vHLvi!h)y9SHI)h)6Z;piJ zE{lB33+>Er9Vx!{zJFn0vb_jJ!>&e554D|fsm7ay=h-ZCzObs7o&`AGz`Kjr`gmN6 z5E0YF`)IxMvreKeAB3K=*-!9u?&{%P%ik>*g`PSY-G|UVtfl%C zPV%uC=N!+-*RKM%#`N*8;{)|{E~uG#R~_tYDZ$KQ-Pv61vEqM6JJ=m5W7bQR7fa_9 z(wY(nC&WKY1;4X(ptE;-h8@_{=%SYJu3-c%B==41cHV`}E!s%{qp;6nv1EY^Ki9yS ze?NpHVIj$NBH()|q6^EjKCCk*pstzZ+#7e_i=DQ}V`N?{F z#&RCK7$`l{DJ=qy{fzwqVvkM5pkiZj4|i+>*W{${dfS$x}L2+l?+=ZZ{f696nwa?}(WQs;!_=4zwt!@03aN$%Yir_)|^RCc-7xkTeqF!yF`U zHIwuF31Myn_dW-Z)bqEdbrTRWqI;H494YyvU~Q&@3XAf;?qn>dd7E@-XwzIUof9yr zKO{fMbKQx$-uWx9BN)`x43~Ki1y4QEl zHO<4;Fd8v09PR^~DzR*DI%6J%SyB_=RX2cm@rSH66O=_*J`<$sxvPO^6VBN(G6d#w zC$UdHyeFI2gtxxUfdE2Nulo`Q|1aJ0CnBt^scC6ydIW=7s<`Q15mLcYoG{^_hIjKJcAnLo|VQLK9^d}Vq5Wh8 z+)h^SN0b7!u7J3&F1Vb@^!f>X*8I6J|LEX(jBOofEAJTflN2*d_eDw#&|AAgU2sF=OCuffBy4mQqgdL5e5B1F(Xm)Qg9nJUaofN(g%)^^+qk9*x zt*XV0J_nm||F*|zc!G~ee=$g+W*~YKgygaOBoL3iBW#l zOdfE#yJ)u+H>xmC^(X+X6sH*q$7s!+I@EWrVZD%^SX{UIZCU#<-|&^F~zNtbvsmk|AJe+#^^5s z=JFLvD5sVMvFj%L4)}-n3ZU!g3wAC=)CsRK{x7oL0w}9D3ip-nPU-G$kOt`n0qK&G z?vw^;ke2RF>Fy4ZkVd+@`@a7ZbI(0jzZsZe+qezKRceN%r*OU!5b+uQ-n3 zn-?A)nE2raKAl6nofpyB@I2n@3E#E|*YABo#I(F+Akq}v&XixFQo!(!^HusuhBBz3dU^F#96|yrc3k;v+-ztK;yScF)<;i2dm!Fobgg(c^bMz!^dho6<#+`2g8*>ihE;)Wz536hi4wOM?(fApSzR$kTu zPX-tDIFfA)K>`HUh3&$z;`2@A_ z5#@uiZbkK71IlX={X$*vl9!>xp6$LbN(WxEv};!Ayer~Ok7DMT#-7l0VBHPv<4p|p z?5_~-#@{X69=pmUTm%``wpPWRde!O#DDxK>mD46!T=>$(*ZHtp|IAMI&2H*tg#`3h zMRXQF7?hsGm%BQ-x|e>dae^PLK~-94fYLmPLn?f~GaKtsS#_Vs+O|LT`1^DGV#3}O zll0W;M0L4*N}z^roHas|4&*TV=(^1X?@!2*3toc22_C;+6EWGrpi)*{{F`s$tg%qq z3D-ApQchjLqq@ya%zskR7Rt$c7e07+tdh3Ns>T}w9TM~WZ(dD6-JUoypF1vst8pxR zo*x5U4^6AdLdrTyCFFFhx(e^_>pR!*Z-a05dDZ#<7o6tff#^elnVFfXul=q{f(R9k zlW8H9UqnP1Jld?!D%k(SO{HiOHvZkUw6ugxq>6mU?k2wl7`f!W|3nrLp^#xsL38Zs znFg&FC&`2x*<9Xyr5|A^3ti;VdVhK}iI1pK^R2r+`~LfYi7FjH-5B$g zf&bQ1aE%Uabz$NB=_P*~;Bc(Ws=!j?2=sh%buUYkH#YA1+(^{&xIeuOCw! zr+#BQs#?QKyOQN8>RD)Eu&3ViGHBJ}_Or?+6zSKkLbdhRZT-wk&FpV>qg`w`2B}EO zC~2L7fE>+`&)eJF=k&b|DSfw3`#on$gm>2ff1N-awBS=N@984vKM&6GPP{d_CZfM?C9Xq2osUb63<9w{kM(xE_WCFf*<|ngVYEN z4k`gmpv6f0=?821>d1tVmTxWL}%!nLe_opx+vr+i!}IZ zh{KPh)%<$9u{)_GRB&$7db8B=vnUd}XDA4zn99#5jr$R<6boW=4EO>`9=NuhrQpak zu&Y|Q2t6l(IF^LcS=Ymbt_s8GreuUWEB$osyRK+sV6)Lr1&JaXpLLDyEPyzj)tvl6v<(S%#KLMp-0qu$F$ zTu7jZgrxH1MEw>mMVa6_D8B)`^3|7QgWO!?gsj+t5~?{`aQV%@fXP&9H21c%Ga_guo*hLgpSR zB+!3;DCwR zEicitytEzItz~QNTUx-QcJr(ywrfT#z&$o?*{sJxl&wUD4x(jFqGe z0P=3u2$35JNis&hqnuplIEtRfm9D0v_XOi zfElM2B8Y~3nORG&A~kyG@LoyoG=xm z6Z`)H_aDHq-9!Gr%RCKkfI<1OmfwxmI%lts-^|Me>D$HWX_W#^ezP9d(^ITMk>mcG zcK6$;PqH5=#_FkSqTCmbwBU(>I}+crvAMZ9GY-!)G$^M77Xd(7#=cg)Uaa#y?lZ<; zIF1+pBq9MDLI20hUNU1^WRME23v&4nDan;Y_BV8y>m>xOIJmtJREX-Tch2j}R9Wcz z*X`7~J+4O2&>Gh)0>b~i!AT#vstfU9U1|uqOzsLjY+Ev?_wm#P;{wkiKRmce_mX*PTTW_%h0(R~h?)#i2Jb{0p36Uh_s%n8%)5-j%r3 zi)Kw9GL%x54{OqGHSeO}n%u%x4+5VuS&COT>X(nr6Q&R9(rwu)7ELm__J=^5faR4x zV$JpWgr#d0hlJ?Y2aC;D(KXUxR+a(_p>P3rAc;erwk*!hR_RSte^Bb&6@2kJ-z1C~ zWKDC+roZx)eN<>(#I|n=PFLKZu_3TU;0Z|3fVU}NrbDpmYe`UOkXXEuEG?gG*gn9r zdX#K+qzjDTaK!Q!jB~0-#f+75Ur;UKQm;`!)50eVdlr{gJvzFy{a97FB=EzIR351J zrM^8)ulw2Gib&J<$Nt}*{(pZ)ng!XQ!Q?4UG_l}Pv zXJ}z(ZG=IFgu#iv{{FYs<#-PsjZs1nuHM26rhs3Up#mG?wV8JBp1|UHKlIVGv~<(= zQKrkwTXTn|;oHW}beA2#P@_PDH2IE=pPxQqm zDY!VeU_V~Kw~EUDN2M+s6MKWy+I1JXY3R{^KQNRi9Xk?hk!;b-v4;Q6CX{RInhz@+ zI&$J?>d(~F=W-q)p@|)*z72=N(}jhFVe?<<>FMXB=IIlm118eEg6!-)J5E50d@@Zv zb1qtcJy}PE4dO_PYOlXe9U^2+p>=a7)ves(BZ_aXX>Y$Ir&J|E#fuz>d&^om0wVPO^M z39$)xkd2JwF31YmnIg7c9{2WX;f-M%F8-MOos?ln4s6fw*ggpS@c#vmD3nl^te;2 z)LXX_jqPhQnH$RoAS-)Zcv7oq#$Lw1K1&Z>8h%iHU8>#f`nv!2l>E?S7wwLWP41tM zssimoA%j5@$|r!X=7i+^*1qP(3nlB?7#AX^x+I(j8>HHX=Rd1>c(41bjj4bpUPP&Q;dTli{)q4m zNeG8~LEJJik(Z%$^29fC<(cFXvg(po1sf7NCa6O8uEHsr=w;8Z&88^sOg&ZH3k|`o z-2#X91TTtxUQlGJXY}w*hG#z^_jbuFv+nJF4cIm=OyE9kCpvm4fR2Tj=r<~wm9+Hr z7S`YhLjJTF57~@mTc2IiXJ+_N9^Hx=nymteC95D$CpmjA{0W}6xeX%Tg-quQ{*oH1 z4_$E?`ZBX2P_J)OYu^4%j{2VKTLWsVTJbMRm z8;FWqqvgM!M9h>|q9j{DRs11b*Jdo7H|8r-inh`w1!LpDSz60BJ_YsXiSTS+_9@>` zJa@ZvPKngV2fs=7=23+;wfwN9-93~^nG^4FK{$<030Ko0*A3}(U`}o8HOnj?--eK> zUpc1defn3YBtt$;Cn=LFKHv5!C>kYSr*g>he7+|!Vea5dBmaSb475%eY0%#>C1RE2=%U3hiYMBFMaSyN3W|EJ%X3293>t6f`hc zJVySFh4M`C$@_SEX?HQg{vJcx5SRhz)kb+9`}dt-GS7#V#&1_s^|b|(^Ec1ue8iGObI@gG zF3SXIMTY_Ue4@k#@gRI6AO7I4sA^zxCCpSG0=xMXm7&8 zy2(@V4?r_j?T_8>w0>p)eW_W9xZ}v37|1A)ZE~~gJG)n!x^1g(YsBmJc>2St@8k1K zBj#>mLh=3iys%6Xw15~-hF%t0(~n7_d7Oy!*fJUrg<3!1Vy?PHI;3E@(!H(cj>5N$ z=MiWX1Hoo$Gi5q3(^V(g{v7zB0uDLk4|OGN=DMyH%820H;rl`#Wfbgh*k%raYW!j! z-)oLqBt#`w|SwnD4FTgD%-J% z*Lg#Os>BQJl9L)umjRCk!=dm_G@cVuDt?q^5U!irC_erl=12#LC&DZSa)ibo92c862XxFqn* z1nG&O;KcWGH>ZN0EQo{kfjZhiHeYLHA7{4po}0v=A;l0%RaMnjW(8f%DpbgzZdt;m z1pytoVe9xdPt`kqE|j>|L|Qsh>ck`L7rse8N#L^l`GaiE{fk+3HgxWvcZ;NC56=Ug z@22s{JbkFb(*L0(!im@a<`d#lLW-J3o_`z+C@Le-Pn%Y^K3BPBiCFvi6-mP-n6G0d zu!n!+x6hY7u1aR@X%eQeq}(`CA<2(o0VVse@Cm5xz}uD=L^F0RBb*o1)D-uaK=>y(AiM21Xjh&Z_i%DQD+jqGa7BweXlQEtA#$ z@R*pGPR`D}{H%t#Z+Hev9gNOTv4`&8ydCx^@oHOGiSDP4(Md@SRaCmoe}O$e1cZc( zHareE$}%$V%9bOMf5g=w1%=O9vQf@A|NOa{BA%AA>;vu?P|xzGLGb}=1a7>7dVrF` z@>9fw4eTLgNHVES6{iO`9fnqCPDGCpxFqlt(oo6KB=B}n{mWM>F0ZIi5Gy>MT*y@W zp+`2pPUB&j{s_^UWzF{f^2zD+;Ni66#C`B{_gHw)Ulyb_;c-VJj;e_`>giYDu;s9H)7Uf+97U%rP;>mMGVmi zOi&JSXwC}i3i>tmYw~4ocv}1p9MbXQ0SWw$9C*kQ`U8mYQJXuc8DO8+`uIvHyIs`LmE*jLdpuJr z$j&kJCIb6@1a6C$pv;F4i(_EW^$KzFLg$uTef_?ViQ!7otK45rS`m0HDN5DrK*{)U zZr)ABUn2udeEA6B`2I4I7!n_?KZ+6aOFy1bdW(uOIN`8k|G|8Z{%$%AQYypk8#4|I zy?WPxgpMj}qC@x*BbGATj&as7GnPxeJThh7u7AlIWq?VP7jy$lbF-&4t@O@z$% zN^xj+N%Q0kH<@eecT_xRp;f!Uv5)5-@GM%jeV?|SuvTh5w1dI}EL867+XQG3Ds_Ji ziQs?a#^uK`CGMl4KSKomH9QWBFIkm!@RauzW03qfwEs#ral(27J$fwMI#M)`RxX)Y ziQSPuyU)VyB^QlO&dlk_uoM&(gWkccg6cWy&AXj<1R*u1D>SRg+JLh!mCH%wJ*#Ve z+lzXGPQuLY*&@{Or-$Xip=n@jAH@lF@cxC|F05SqgXA>oj|K^|3H0}v(WnvulH3kf zBxKL*1oGGAcX&Q7(*OVR!fOcu0>lc{uCA`YX$HgMFfkFEC*7A@roOZ^d}?p&;(mNw zfl6w7t|k>UBH$c{jcCQCwZe?ZVUsF&}aPA=(A`ZBP3lG5>GaK_=r6dMpGwA#o+TERjfg!_}Z$Ezg zSg@&*D+D}Z8K`oVm2*coI5;>d>Ez7JiVR8fv$KG*QdAXV<)va_Vd3X*$;%Tjp82Hp z7aI?Yf|MexZ!w}6yaH#C)0EU)_#A!j z6>jHlW&Jt-iR;ZZ`?bnjpc8FGUfRBE$ZO~{9xf6V$ux{q_AttphdW(?#xe39~3^J=n+w*7b5?&*p*E3=B!&h}$mcqN&6Z zA*!IRwTFy`=i<`8;h^QA_SgNuoP4^unNN_Udgg$q15+Tg3bc2Z-ll(V1ButaE;|-` z-o=bLJw!zzhloRn`v960H!@_vBu$}6D*vJGQ{J0=+Y&kj zJr2s0afTfS?I{MCUW9!!*SU6`7VYvZb$Yz7GFqD9O8SyCEyp3wYP)zHLQsy07=ynng?hsiPFct|zl7AdcsyFj#}1 zgtAtI-i8REQn8ep#~4MB*{4yY`=0fF5pFg>68l_55}jZXWjfn#3I85GhuH~%On+PN z9i=LC`sQRc1XYCPM+|`|zS$szc=C5O6h)#7bTR^HziIh`Qj6o6Wr&fbwV62xWg4Ih z>HuYNbEmpGG|C4dkYO9%dyynVlQ#N3d{&*=VK}&QbyF(4fSt_l9Km`ukN~ZCv_~__ zNkge>bmCJB|0gA-BzYBE;s(4$sYs$K6TE(jNa9Z)@@4VOD_Z!cvaHr zE%NSniQ8yDI=(?-%VWpT9bRGi3R6&F-(WyO$T%E2pcApwE$ePxBtJgykl3e<$=^PX z*xA<(NxMAB^w|{+uwc5}Ca14_k>Vv{b|DT5Y`;2Rgv$Hg`>3Lvwur(g)gj7@xS{$h z1+ln{mEBWL5nTrqBzhX<@DT}~W(H=Vl`IGYcfSc0^`Ri7stQbQ zd}OdRk&A$tk&%&~|3M&89aI)TTv~D+-hfR>=A{~PK#}?L2b7U2)5e9>_sef>xTumc z9f4yfHvzeXq&TFc*-1&%=zv@kSvon@0j0^(67*qa z91jeC<>ckJt{%wbtUUQ~jCC(AF5*k0-@$XHB76NZu%G{`K%n7wC=|5rS@4ua#B5D# z>&;}xE8oq5kCJpOhmM&jmk$|e&PAZBqhtN`D?gDE=y*Xv^zssjmkD$d9T=jfqQOUo zZP3ZgOdw7{$4kd2Oh*o*Pz?HaP&KaKR_A^)y4aBKp-aKssqr~EPl>`h(v{}>#9aLx z74k{*vfC3lwh87mKN-(MwW+&X?3r=mM;ShE;_w6T~N=;oLpcxos0a67-ywKq8p`Z=*<(ivfRWT#(C6Qh$O6I}9z%Vm2r^i{Ut7E}B zt7=v)ENl~_)wr)rcfAZ9HZM%{81&eQ=`ge5+$Vv5wrT4Iua2x9qk^I$sk{fq^?%&@ zV0rD!y1(R`OPnz55aA=;XfcWAsaozXGWZ(~%pk(=Dvk9U zhnPvRWF?-{Qa@XzIVk07t7uML2n_D)pcPKWRM#1Qp$yp+tIrWhSr6J=sC5!4?2)j; zPnn;%8NmzH@D44*gDu~K)wptd2#DK1UT0T%AiO^6-=c8gpf0rpEA>E= z*C*K>En57;o;AF1cF727>Z9zxb?LkUQ8lA`a9%@1GFTF6?5@SPdaO#@cSP;kAsHL{ zF9b1>9bvLS5;1t#Km=OgB@RAu`$}xpX!G+iTHLBZ;1JTobX%@y-hdL`+5y9*2Lkwb zLhr_R!SiAAl&O&)p6A1~HRXbhb{N#r#iqVWlSy^rK8^-;F#sBv_`nyAYe(>UE=l~`(vJAOV@fnVZ{HX^yJ|-8zb3F z>=WbR!8z^Pd~!_#MXESBM{~hLPunaOR@O}XpM4O3+c(TYh$;0Ju%nGsl z&!#s~KN!cwxwDhqTQIl=7EFdDx$3`+*b(vsL}b&7^K5AfuC}&%A%T4xxHvfE-4{;F zk+HGTxhgh1ZH0v&tN$Lkc;QCE2n0o4X^G~6sss`qz>TBLlq^o)vVxhu1g7Za<>ec; z>HI`?CTb>nK6*B4Haf;X7wD2dQ$4d()8EpR=euhbR}~3^{t0zu#Zas$k?mUC7w{~M0^hZ113o+ zDNx0i@|Tjp_xkr}&bmRAqOi%`>~p1~e*_J+ZR_39t4#6Cjn_-GMF!mOuCg-gnVG~9 zGu?dW)3uPL*S^rqH~zXUu}5lmkYB;8STb_}Al}G<-mMEdYzB~n%g`mt((=1#5QO6Z zJcuykoN^cV-%!lJW8&RVsphb}cw{j-f0>yS zIVvNyy3Vp&K61?4(!e?a7i@FViev_%W4Z>X?4L_mO! z-dBGb?B;KjUQ@#hncqb|{PWGB{XqaPmYvRkJ{yG8oipO_n1g+fd~V5cOpdBIAg0_c z5&uElgRbP=B_=B4l_yj~^O_zeB`xVHpn@nZ~nW$NiS+ zgRDcCgolcTF5<7Tj=h;)3T@yYJ$K6(@+4+Q=G@xqR&~9Sd?@Y5OapVSwqXLh8_{j+s$e3QZlt?%7#BMa8$#` z!gA^)gZnX-VqS^e4@}$*#ff}js3H_9XAVFE2FhQE_{iv}oT6gK z_EBx^=G-f|mT2J5xVShEeK^>lmYz4*{*{0C%9EMtiQ&DU)V>GzvRtuY;wUpxIa|X- zaqk$@U0_hbha~2z#8C1lzUfy&>r7gOP*o&Omf`%Gi?e_7K`9`FQ96wSLE&hOg`6B4 zQBfkr*yFZaLmoy94~9({FGt!Wv3vVeNC60e>m&? z?j*7!%@d=9{UnnlvCZlL}6kNM?{k5Azlsc z@hG+OP2Ml-p4<%LBxRJyqA*Eyi9G%`lj<(F5yQ5jd>sdRJiSj{BKogA#h!j5v9C`L zKF!!AFz;Hf?eOC54S zR7fV~rePpoU)7|N@tODY<4khIQfWfwspdd^tj~*QP<23XEQHe)e?Gz(hF_p2%Z0y% zY3ERzO!NL$x&N%gu7|$vNtEG)D5^%aj0uYyYXCxh*v0L@D&r%WdK5ueUPyMWp~ zNF9m_#VvA8n>aU*Os`u&Jz1fa(RU{)3o|*g|Ki8fUfNSKpL}FRM`TjuRn&v$d=|`Y zug^}eptmEMg;ji;JFB}@cvF2!Q~j{6&L;Dz@zeynMPJn7=fM>sQ}drZLZ5gDi4BFSVh>+1C5{QvhAwjv5K@OGKQZMA3AM`D2 zd71ORD^0;Ie8Q!M!~F<{8~n8E5otX6jBH^SDkL(3sLW0+kR~^eVOcw>mWe`2{PXDOTN=RcLS&PfAby7F?isM?iby9xLqm;RGHy~Nd z@a+ZV+k<47G|-^CU3LHcYQPIivqF&FKTW#fe{IxD$-<7^Q0j7BO^||nWv%O`wO6{F z*-}?0h@g1<xKV-wB%anY3i<&Nv(e_JTwJt5DYPh$I~qT@@uhV zjA(IjQGrIid=6;F!iFAc26)^O!n+Egn&mL5YK!GEgfc7K=l`m5;oNV8u)i*4<-`EE zq7bh*A5mqXU^B2cFmfLt-EiHwOmx_KG8;3ZLI^ZkmWYvIi(ttCW8QtG$<(mfBidy}i8J+Pnb~Jz&C~ zBuAY<-_Jpj6*Of#Ds|+9k35(w5oU*NYw&cBXW#+8Q8s*JGAGILj{u0uWVMK!oMidc zGH1zQrC8(@B&Pl8BR%WX$izqU=1xSF@Z^*fdx9*`NrLm8-vCs!6lMPC*jR(kNzp<- zS(BQlCqH=WXYc-qa6%>2m9y;RuGK?BASMOX2gw;5Z)mo9$&P^&X{M5vq2ZMIFQ6py zPB>SR0@K2GNeY=DaCNvYo9t{he1)}7L}1}5@4ezT;PxQhn^a6YJh$96Wg5($zblaQ^1BsC0c`E42bVemMxDmVbVZV!Y`19iwMuKOYN`jOA z)Tjwk;wgUT`-Lc`-IM(ZvDZmVdk|^N^Xe1&V+N>{pB(#~l(c(v!*b`I53ElmX`S0s z*cYd=_P;2i)X+XMN(hY`X??6A6wl5jaVrVKI;=u=sU3XsOb80RFsSNEz&YLx_G<2& zl(UEX>fXa}y9FMvgG(pknux7}C0#Rl zf^n>9D-2}}u72!^Yf89JsI`m3Y!6y`F;^8;!x2GGcxRNgzxvzoozTvFw)UUuQ|^jW z+s|1uq?rqEfv`%Sp!sMd+1B}kyziJ-7Mq4G*3CQbP`5hV_bt||JkCxcV*kqQ{XMVI z=J*QrnIe_rZi4r~zVq|NZn{FVMmK3G>9-$EFfJ52(-n7Xi~>)1D~nzK)?biLSKTAT z9?pFrDng(GRYWy<_~CYAMWe`NY21x0tE3l&*9(ZIwq^2=F`hi%EldykQOkHu|lQ-Sf!4BV*Fr}hH>6s}$J5T9*FQcpn@ zj`s}N@AD@WG{%)`cP;oMubzF8o_&9RZuV1kabVR;?hi}uhr5$SJx(B5p%rR2baUuB z{{3yShkB&vQ{EL*5kzJUBLk zfk0v!AhFWN%s7C?1@;;4jK`;>NEgp=6QHC|;D%GB9EH~JVeex9M%=z}s$u-KSaI}Q zwM>>yQ;LQg>Z8=o_6}JlIOax1MuPA{GkH5Z7J}%a>3t6$c7kYgjx^XH)k;kX6|ArX z87gz%EHi#hqEC|Ri{@~QdtQwaP#|jl1W2bJ9~SSgk$u>BMg%arird@ZU!IzwC7@o zJS|RbJ9&aDXi6j{ChBoSz?gugw;;C#Fb1DYDf>+5t!*a?r=2b@<8<3%5QBPt9|0ND z_DCDqoLB(ry8R|<;M?n%3>iAl#qVJ){X#V`^sv>Tpe<&jR7$x$hiAxaIlx2>D+d#q zjEx_z=Y;@*0|obg*jUqdTVi7W`Hky28M(RL&aWR;GJ6QV!gh_=Lt+wRAq`3T@OhLt zC?I?OR+bA<=a??gAgcN?!SIFC$x)jek@2H5!$pOfU^%wp7<5fon?s`0&Z!wQZ$Z^HeJVMQcY7!y7aQ>) zW?1d)vKZ1eTafRusB&R-!oi7|2NSXu;p(CsF}EtQd24m#$*Ixe1Wp#}yhpZ?wG0;gq{`ltpu2 zu4*MhcYK$ikfOaUtc!eq#AOoJIS&%8AmI6pQj(x>dlk9H_`VFPKSjl!@@6gB3p5yZ zwQ4!L7#}Z+?NtllWtFZvD8b2%S2P)tpL{L-Fkj^7(tW;d^OE3vqddti$gg|1UGW&? zTo9WpcqV&}{%yoS5&Pi`<3`{PUBc_a2^RnL5N?#Dmxa#}2AgOG)(j4vJMO^B(7kXE$f z431EJzFd?g9i1;{x5&0Q0Z>_CpTm zU-``k896jZGL^Y~_xKr$H&Sb2|c9P7#$ z&~&|`;cVK7DI8)s!8`p=&%h;V#io54#_*-b$dgQE_bw$gaL2UgQYA-lpY^6SoZQc9 z*iZnLHwI>mX0QaybO+0{{(^mJ8`{??kmU9|p48X9iiUtoRl-5LftVPh6HR0~CB{L1 zwSD}ag)k)PFvR&WvZeWK(~~ihgO4Z@d&lveL`P&x!ii@!CM&4zQ;P6`n@qPKBB5Bs zK@>+b0t7GnK6&iRLmDUV{SFQ>$$yx}U)z96nd@I&8LtoFbB02WyIV(DTmt8?Oy{#~ zU?%tx?(OrBan_ZC5N8XLw}Zox?5uA`39QH7Lc}Z;nF#D>N(?vBB|oM*?$Zr3?hjaB z&)04g@QJbhCjsK)$|OpYz)GJ7tgS#|14sFTgM*agIMB}m#K5Hk4l$&aYWTYiSOygx z9StBcpvwUt_O-PZe9;kn>uFUx-fmN87msk4Ln$i`FL^L%UZ#)ME zsE<8zoc4Ham;Dyd3B6Uhq8L9+er?b>CsYMqe-)K?om_Sie|^9&F|i&LDXROwLzpi^ zEzacRyu%i7565wFLNq4I5&Y_ElZlBR=yw#ynrHsF{^l>76)CL*oBCh?BT{{Ca+!CR!&pvEdO~c3&rE+kcdUJ6UFbLP7?22;px)2`fJuyuw}{vks^0c`i@ZPbcRIt zT!fqJDZ}_O9GB0G_FPEWdr#ptvWwaKL3Wo>`SKfwkxoOZmViPm4B=FDQih>cC~j|B zq8dxGk9p@S!QSGKi?h&Jz@Q=Q&-pQ%yG!L;0fWbUOx$cp%!u>fv%k(v3_U|1jt(B@ zAWY33N}C?iwl+Cg<9U)rVT&>i$GpyL4nTYjqr~8x@zyB1hGtlFY^w{a&_ob*VGiea zQAFEI`|KU&msoM{I(hFhB!TSX*^K?!3Y~gdCLxi^SpQ$)Y1Fo zFu7y&#TYNuD!|29v6{qe;^!|Q5{3$7C=-qpqvjq^hSbN4FF8QCHoq$qEi~!?n{L9c zN-1GnbjkZ-%4>|@|8^kiL(P_sOpT!kh0+oTCYg)SCrFd0bha+As~j&(^1McDQreiN ze}+wxroB7dnZym(V!S&vGw4{cP`O7z%r@BIW$^Lh*WjfS68Nk#EAZJao2~&)Cch6x zf)alj-fb2Uk8s{@m5wr1m2pxy>OJw`QW(3+mlAY_KKu{CavP5-xwi18L6a&lRz$=s z^=NqFtD#6aqhFOfUgsXhxLXrSU|tP>b!$>RzWs#hRJ-#wKIu?dWNz}yx0%v{4ga=y z`*6J#)ZS)7G8|L(qsvBKdN1}rZNe`Ah6PWa3&@5=4#8vbsf zYU&+CD>b*X(FMn+-~W-M?zt>Y^CFeRATIO4Ct6C~&`_Boz7h7NeMPA%N)nvX`%Mte zpA}_gA?$WRK%P#eCKE0mF0KK`n46Ros5bQ47fA7zdU|@m=j`g*AXmu1$fzva0x$m2 z?g`^i;!eBMz3Jq3JQus;{iQAN7=cyZXQ!t?y9Jg5D$HIQ;S}eT4`Nf9mQQsX;yObAbXhud-umukx@RcS0uXS+0bIG8Af3mLpQ>!;0N69YV??bK=pJA+g{~VFyPlcZ zQQj#$X}3PN)cOQlvJdb%Sy@?*G~}L~_#}WzAAfOc_STxeJ!?8`_I22k*olX2A^LCB z4TOp1TrTj2Ej%3}8 zo?lsGshTZGh`iEIJ4I<4gH#-@i`)YSH8c>;Vz2)D5~fm4_al^>@w z-1@Ic$BWFbr{;NAg)M>kO~ImC63hLxPq%PXx8JJrGa<;Q-I9xgcI+%dLm$*p4>FV+ z+{;e?<(b1^2LIGTlh`wbLwVXI#4Y}69yCfH+i(8`&IW80J8DE?GTl8bjp+#yKI$|c z8?88)g_y~Q18wZt<6`e9V;3AF|Y|wTIP2Y)3 zl^NqlypyvW4ttaF_G);(6WJ21ErzAY4MGPAaJ&`Qgi6{sZ&#`3H+XW!j&$PUV$>%u zu@MIMN&Df2kD!De)*uK=2wwM>ye3(E#=8Q^Za1V=Us#{TN`>YMgODUYD!W=K>2T2s zxR&o?v8wYJeWB2k73@lO_{Mw@gybIg%tUQcUjSEgsTsu{u-7Eh@+FbcmQA#RBO>v0+E@&_AP-Id(ud5>5sGW(c(# zD_;DKlOF9u;-*lHHM7@$;|UKX7Qrpk=!u|7 zIM1VJ35ul-d!s8u#II$CTUVZlU$I8gVYT___#sHa!sH~@%c6Pt5~qSmKftTllJwt)33!E?ES}pz37O&UEdvDkCNjy&vsI2XNyVnWIf;Z1; zT?X}BE@R5Vo{u~3lfG-N@+Ze%!5`knni6?~Sq>f2pAXIc)=Kf@IPOX|jb<1`Ix27I zkWHG!{{sHD$D@He$Bl%$HILVD+HY6=XNF#9I)y!2o`3NsJMN12$O-LyNhd`r!(T-H z`b&xkKrKEn7*@uv1(1%u=}ky1UP|Vp{4dT3MfV?~%r(JluHT71WqirBAX!h~Rv|_tY6YGndlarH`RjFnr#p8hvaId5~(KVUCs({#{Tg^wjufP^|c4Q*48?~ zDhwPhPwv#=uV26Z{1GLnGEZE_mZ~;p!$XAr zQ1e}ZnvR}c%n=EEQ29`H@3hFvKm2;M0 z3{-t|$KY5gGf(EH3;^&Tk9ECee_3Ya{tFka_n!RmLZT|f(T|X}ME{9B>U#+4G>b6L ze40PM!8VlF(wC2Jj$qV_{^7Y+z&5vyWwICd7(41F5&}BAIdbpVFxb<>=%q)YlVo;+ z`1l|e`6DH?n9+xx&F>^!BpOOW7luWLi?zsj#>yjH6W zuwKbtRL4mFEClN0n;jS19e=v)Ngjt6REFMJq?qFOknT0;ah#$-OL)A;=hWZ3x6W(| zuZn5uK7Bb&DS&UC>*!ZTfet3zMLv|LV<*h^y<`;T@qmm?B4H{ACV~ey%ooTBANDt=bQFXsmI-y35cLCKNe(ik5apf z^g7PJ@*{|lT~YcsTpszo#o7NX$2HCEPkwd5X`QxHCuI8l3bXvcJ{w}@Lyji+5fD$r!E%cX*u3eljL3C6Yoq^?|tFJ2*?x3saO29_tJ^o{fyByIk9v& zVAYo67iz{^8VL7Qtg@WvV|ezYYs}pR&KJ2QoMt+5}tqh0BjT2rlcyed=r;;TC5tHi7hvg615;>Y>P2;mD- zpv+bR%3Zo`GMw;wkzSHiIk~4<1Qz+2XIZ!_(g`exh%NE(E0C|}9=$9(IxOAX+>VW7 zeGOwy5LwrhF{`9nSyedja@Bo)Zjl(6N3rl}m}V8lj897RViq_dlms0$N&P*?nB&pq z!J#=qPJn*?`JULKOM>7WvxulsmFD+QzuK`y6cF|VUb>d&D+j|+P`MQ*W>XriHR%? z4y?7Sv70`-PS%dk&(mOCw$k~x;7qe~uX^qB#Q3tSnh~kg!{B68-a23vrZd|5DP^S@ zllG-E^3XMzLp#Bj(X`iAVJ~F`r)eZaQy1-3VwAo)`MTqJ+|K5DcY=5rnW*3GU!W@z z5;cPv-}OC@pO0w^_sy-A;p@qDW~!$hQEc=pqc zD533+#-BfbyiZc>>_#vj8GJvamiu|H&^J$o>OOAX1k$H@bk=ZL7p!%cHyzHz$ToY`adN@ za52y$0M$P2bnB&nA%JrNqpzXa{5b%>59`~Gh=4=!#mEH^Fg}`O(1KK{(D?TOe{fS% zN){V$Z@vUFT4rWu&~kttfR?sAKj3{0<)B^fo@0F-$-&L)Dj%CS29}`^81ERf6z1jC z*4HcNDJW4>ki1g*3(--cPMSQVyWmQ_)V4_w#aOMOjw~lfj#ZYI$Nq`Lk||!Y1|XCU zg2W!fTIyLb>2*Mle0~mS=L>@dhDM+x`}Pf{LZVO!jNZY}UrXzUT(Omn4G?r7i3`xI ztST+Fv9*ntE(GiZunMWH96Pwupu;Lu0-CKO!@~|-+F+F+jIgu4t)!$BBy1oNO5r&1 zZWI3AR-Y>h@XLsXs*bWjR$(p>E z?Qwmkh=>RlR#r}2pjPKz{^Vz^xh$6l_!@QPjV{=Ms6QOS|D6odIuHHFCjt;*3JMAm zR5fxO@PMzM!f-oZh>l`bLS0vBW7e|ZIMU?u7P8?c&&(gTP3zN4_veCLIrd8OHd~~ueA2WC-$3~E5#a$=wcKzMK zr3LX*-biJ+#4^(96y4Xkub$*aa*BhW&zFAr;&U<$-^58jxH_n$WURSEowqAw2@rFcL$Ey{6SvP8Uta+FXg|G8yd;7oT zq;}kB!t%j=RE!TMnZ@@k689=|N)*MgSI-ZSQWFHx=DNA@3#a;)eKAFZ|j}rupIQrc$ZjN4Vj&9{G z1@>OSgdQLxjGqx_Zg6sSvT-$o!_M4yWAgdcf63(gT~^0hqSDLnCUjt*`bKL?5c z2a{I?@uPc%-L1Oay}I7Lx!=7xI5Vom+>8<&X9?`jJZ@(H9~Quw*s%qPCo@!>5XPne zrlQHGciyL$%nJq@OMKZhChWtA(#DrOC*pyoW=CVeg{B-cUUEk|uU*>rbCxx?zdH9z zs!f-^x&6^{`=jhOsNB3zhJ-w5_J}$2qPmmiNZd9P-Q03s;94=K#Va0q8s@2vx zm_d0uz5b0FNBiG4z}8>p)70R#G(f^EWL-p8`@QHoR5RSH2uhZhG+*D|HPL=%%52?f zs|d97`~7!@VK}S#&+|&9;Nad7G@rnkJ`8fd(%aqJh}-k2G~ZtUzsV}xhz$>K+3{`o zRa@X!(^*}ao$Y&2$;{lmq1r^XEwfFN>h2}>dfqwk=g(>r{kM{{lQVWWC*t;-(6(|- zE;sOP4D%ewAFsQNME^QP+N&G+Z=UW7C_-L;%MmgjkAv>y?Wyv4ip-~FL#K03&1I^0 zBcR5tXdBXz3VVJ$h&y%_5B)0o?2i-P;|WntqYP}#n$N|fo*lJu^>m25{Ol07h1)vX z)lKzABr0vPW1)`;tAn_;kLbf1xb?j>#VNxf5&p_NJr+8;(@5ot=C}E~`z1WlhR)X; zujH%<3EP&FP~_r*tMgua$~$@8?4KL(Yg0P4h0$3B0u$!dDe<1zvvu%BZ@nRMu2!Cf z+_qGk8h&J$~x*pRvlR?BH6c+BG=!uXxcjPth(d`^)u8 z6D7)7{Eg?XCFf{B8nfpA!I@OxpUeLveXsyRZoDK|%79L30X2`2gTrCKr#)+< z;q=$HOUC%HqQXKHo!*h@HoG?SY8O|AYp}6Ni*a8$j=9%^^dcKy$C~KYKDjs8jjd-%klJ@yY)w9EleI1txxe zevonN>Jqw*r*!mdCT#t; zH$V@;RYL!|GOM|1m5v+_8yh_P;`B6{g=^xFimGbx=4NGiV9FZrB=7Hq-#c8Ii-4sFQ#Y!N^`nf^=c3*QeCBEI)oU{jzrH~aur5M+NrZ&#i}ZZ-Z{e@TP!ydiS{S++)(Uro7?2IxXfXB zkWUYcZF-Q;c*3#@p;W!q{ax_mtm&M?bmuD9P=3hV;^@iEbV+BEH^g;6lWrxz8w$;jIl7&gPy<_LmR3H-q zzq$AI_v4|-96_|_hk{E%KT+?K-fd(CV{te>J>Fo$c>M7UD}fU$HqJE)IxNv)bYa zyG7n(%JO%nJhk;+>IG$}!E6yoZz6=E_*^(Vc%8)ygou+uOblXtZIS<1`P!!rznO+;-?EnknOBd9Ihv z>A<)G`+rj|G;mK-S^$}9`XRhu>`(+OHL3N;Euc?6E#M+{I+!!RS*C z`_mYol|qr}ADHDi#+2#GWKd6>Ms^=)1BZ81;lrv;m*!SCkm zu)ZR!^Sq6{$EtkgS9^P|u{-@!VaZOXp_@wxm->&8>K`H&F-`$N_D{wM6@ga0$C16V z93n*lPj%nFan3HC_xA~hi`H|OL4Oq#T6Po9ZiWxCrg6*74HZyS(!52VAm=(a&2_Wq ziPNVTLvLuW9uvKyVi_{z7;uncIsZ9)Hm%sMktJw~Fscfys08lkDM$?xl`GlUs}vAZ?4~ z|2MasUx#< zf?XHG=g+YIc&TI`znO1z(3(AE{YR#0ze3%{Y+bvS0c#tO&fNKQsWCX%*)1A1lcfQK zl$C|0>cMq;$4!a4mW-@zW!Z3O_x>ljaWl9a z7Sy-B84!GhYViJWbZl&7d|W)QZW^%6r>6nnRgx2O5Gi&*Mp7~?R{qz|6+0y*w9sAv z;X*+h8;h2WTJv9V^}C5ZBWm9{&Eq91c{?M#x2YYf)em*%@j<78fZYNp27hEOM>0tY zX6AU|Jkbnl0RaI{PUJv;rFW!~7{S6IA%cdMBXnkM#;8^uV9`WBp@xe>_>S(L!-tpl#=3(7XSSD{R9PQV+#xW438iKW+XYx z*zjN>A?oCR0xPTs@7FohajV0detbIwWMr^y1H7*aC>qeunL7)Fk=GneCktX>U_jKK z%-hyVN%4M8(y6Qj?;vk^Sygz%x+r-o`#b9AB8T7Sex!f;DNo$LckJ-;ubjo7tot0H zH0znZrN{zCd(C23SY3@*{^mkyawX35~ z>K(n+vdw~6cfO6vEi`8@n+dcS2TW5C2EqMA;9q=9?4=*^`Z`i@=9l3@B;Jmuina5FVg`mjec~pI8ltGIfEJ6326ac5xc2S2%-!uZ_Uc5wuA*UD2zj1yz46o^o$-_>$K}4DV19`R?Bh(XEyYVLkV|Z z(@6b=Bzr8sD|mhgj)P8Elnc1=8|R+J_vn|xEu4GGl;A!qzsh!6&)Gegx*EE>dt!L+ zb9e%Ml3XG)XQv$z%6H8H9h`)ol`-F$CZSU{eXiU{hQ65>sY)Tko@%FQL!S3BB>&q4 z;=?6M$T;TZKAgu$;i{^FFvf*KR7Ba;VQ1@6biBgk6v}i_A6mDygRzjEv%a0Sy`N*y zxjq3km1Ytp?U-6!$M6sKC;hOKf|V`}fhlyeF~_huH#K@_>{-*T9RRMOa~$v2Q> zh>L;!$>Ogvjv0L=n#gxS=V$H@6L;7y#50gO3b6_+|9}z;7lQrHjxc*q#uV~g=eILb z6r>ydc?cG%Sk_+n!LNMoTtPw=`@S7S5i&%PUWlU_A)cPpsPipaE$S@13H21QuaP1H zUcLREz5P!;yFT4J9}H%CYh{L$4oq26sFe3f$+Hrv#$&0*hLlVt{yU1r6DdOyO$S)_ zlQrriGPzCG+gaRP`OL&q_^C$Xktw6E6+_x~`X9Fkf|DFb#YiLGo)eopJM{8f(_K&} z#q{q!{v!;>dxU3hFHtIuLyc?NzBIwhRSbExoDHt@y1IJbL*^;?%B*XT*Vfch&p~|m z1LoS-Ouf1dqW$5{H%OEj zBFy$3_die1*pm^#yv7`S?5+mE&J8n^9%aNs$faZa6vfi2uYm&||K9e<+{Fl;P}jYeaRp3=vaidH^{WI&2@7F4GE!k0vKeo-QA>ITwJWI=!HWA15~2o;@n(Z%ZrQZT3P^Ltf{Vk zYFt_MlD4%KFX?-HhHSmGv$NBD$%U z!5jn|#M%qsI{_dL%hqAt`XuDwZg?mtH8yO3yUWMV-+1*BUz`XY6DhR5v623JXlJJ& zaCU%(7JmmkmsM3UL54y{4?Lvu1P#+D*sUp0FIwp65CXcHtZZ~lOiWnVIR#4lGpw(_ zzd?L_yy6rR5>j?{Hl5l-lO)CvW^HjV&+Y9k(1!K&d}MGx$O_5kae>na<>vN>EBk>I zB--p_H8Ut%43c_Pm5_DYiGN9nqFAtlQNfq52(}Y0VyI|9>|mM1YlY&}eG1H8fsD!% zudITY1yY};g$=O;~3AxlvsPirM5I9GL~uq-AqFKaN-nlX$fi9l=S zoxY}S)qQBMu+Hn$Z-1G-krfm67ruIwJ+>;(UYHMvnNwp_OJ!6^{xCy6OXL6JSKu1o?z3+77xGGc$yA?jh4g2@Bj(dCYe>!FGv3E1EF_)C{D!%r7DP*x1 z3gxQFy%Gn5Bof&JLN@UO+M6uc9#LWfFJq;F_BvXK^MB~l-pS}ZEN@j7gu{F1LhD%T z=NDl`5Yh1Z(V$YEX<0`2e?p7ctlpb**_cf8CR0M=oZ4qyPe(?D47Ed6GV)&GUF4~-Bu2P+ z^t?()IgR&7t)UH0StSlV_MSwjbAOyCb>7S8_a#whmg!{Ud6s789hcq?lByn zL{i>f0>KeH!4Z{AgP0tHsE(mSzuGc2Hbs6WojE~`B~C?Nre3Uxg1~95!2G2kY zRS5A=;Xqg_2nmOpdGyu?t+EGYsr|-)eI1PUa8X9sL zc+z=%N%uuCmsC!n{Gz22(3JaCL*e_vUg`D0L7lGVFz*B3P4vz+r*2W_tI`tfKtxJ$ z9cAHXqnC?>n3CTjdDw4``&v(=Wk1xh-|Il0qWJTZDJtYR%xEje;qwqcx^OcqVfA;? zql)cxs%0Ity_++(=A|@SWlMy^tY|-b-FU=~{#_p^Ho2bq>l6G6`GLyW?tHmeh|p^b zZ20TFfI^Sble)M&r@qP$?Dc0a!7Z~mj^D`r0W*3KyUjn56C^6z{0df6up(Db>~0jg2==_h;j@+ZWC6wIB3gM8z)$|Mo_v{)XE0T1^ubT~TvlKo}$n01?e_cD2lR^R*2P zQBhGpr_6u+K0$ycV`sl1+JAnHKa6fn7O5!d-D4(nfz9uQk>I^F6*Y0Pe3Z(;N|r^M zri7NEf-&D&6PqSm3Pe1rWKU{ZzDJs*CUi-1l@o>+4BtrYPTnI-FTCOVHsz88B^^Ly z;>yV4Wrn*pV*-vbBdFEx(dF@<;%d8F5r_L_X=JL*mFy0LjTc$}{;Y>2O;rU*NgZul zQ~b$&7Xm`~gdCG8#`R~9(yyAc3)$=QqTHk5=6e#2?BdNIKdodK@*oW?5D&?qx$b?Y zxTb(Yk5>p2O&_4dle=bbU+(p5sWh#<*o!4IK;lx;C{tdmuH^B#NT1l72#|w~#I~Zr zvK+=Pqs1!gIyQ89V1ECycbk8JY&KDs_`9_TQHfcjWamIHPT++tuln9tehYR`dS3?8N>UJvdwOK(!FeXk(M-Y=Z8v8OJ3D~dR=M_3)EBie_i&;=B%@dN$!VdCNT|} z?ZH#)tO?SnIXh;moY4*7&^RO#>F?SvEQs0y9 zT0OjIqW!Q(S`$~K*hL&|5tk)$kxYktNO!pu_Kw5rpbvVU16 zr#ThqWA@}uH$CaC-ABv*QgNb;P>zb=oUx5KcJZ^GkF{$#H z)#+wV`0SZ)9i>W75ESS5w*0%nwy5UUyWHEm+UU1aSj%kvc=)L%^}lMK(#_5fWL;6FpX(^s(d19Hj=s zV(*gU&fBj_*0mtfyVqH49zMVP;yW*GOtln@$e*qUF_PEwl@AysXg*Bn0`a#UG;8o5{T}-&XhKh3biMo~jFOYwM^i7k*uscWi@)plSg38X(3By!7 zpcUt(BqSuHriPU){h$064GkPTe0_6sCyY>OM@f8QVn!$>#TKZFWo1uJPC$JPf)J`B z80z=^DFziZB*X=g8hL!cDMWb2rg!*niiU*eWr$NAp8mf-=uQ+X? z#*&%olWT3*9q8w#Y+P!y+JjC*e!lKU<&E=s_+4zP^sPE`TVBoVIVo3shSK2{SB^=M ze5`xqoz8erqz_1&4@txNq7q3`mdBmEk}_a3!TX8s7^ggsI9Tdp1pRssw*M0H>QMB! zbo_K??8Cu*IZZ66iOYrwr0Gz@M75_c9%UEgH;_HNNR4V+9c!WAP4;Pi7sa+3j;+%u zCVwdYqd}Y%6QqJVBwV}FeN;H|=WavxWwRr|VEn7w)J0YPH#WZOU9cqY`NN!U!-`09}m{fdY+ya>ENimh!SmK6iZPRtkDFr2pzSgvoR5Rh_puZ@+?Fj%LIq=< zPpny=d=_OMlU-dI*XQ^4PehR)STb`*SCeL?n$oecb}>l*!r@P45Qs;kl6NT(u?t6} z>oGCET8y|?9tJ;7aT+KpmS92&Pu1r(98OAgqwX1>Y<_ilQ&HVeQGGMMdG|Aao0~&2 zKc^BuvjSbNjv}|qyu&Y^@T zF58u&az}&GtJsvGbf1>0a*m+Q+LkId_^~Zb`Nhl}n$10)Hho*l)IC8X+c|8iGuUoJ@+W zxfQqyYB#jBp1USC1sy&fggQ%O^tjQopS5*Ag(gyO7IF{^Cd1tS9~NLZp+O?rSxiGi$lJ&29`3>QsZhQ)Liz=2a>BSI8)?+*tMq{EvG zsRFoHb-Y(O|8`Nzf1in*7!x@_&SHuc8{!$EWD%L3J~WE4E*nPEG>ar7(D}nfcv?= zips29jUD5Rp-~h80YY7!eROnxaBxa?HW3jKs8y-a1wk;Sq%=ieYB3|1CP9h!c{rs} zG*UJaf$1$K%XZXX#$b(vPYbRJXAn;jUkqvFb>~}OSl|S!15#2_8X8c^(t*V-I5Qw& zJYECg#q;yUA%h`M)D8_vt*o!j&&LRnWc>I6hAcoq5RZeGfqUtP5P3qtr%z~Gx6H(+ZrXbw49le!F zzfEZdnt5})%z@|spKAxU-D59+&`R(CYNCdQ2F{QeAx&~?WzHNS_9Lj7EAh)&4O{bL zdFEBQR^vHmGgv3n*2iQlD#Psz{d;mN8`twmHGgTGLqT;1-suH4j^Ms>p{= zf`qDkGWU4HDA3bgW>#5bpvN&EKHM*4`_@lX6=qu+BUULBx9Z2GI-BwNWSEGUAsdfT zB>2mLzRhItQN+XN6vqZpO8O+E-D|g^X2J-&ZE*sNFiUXQL~*a8e4A2IpOG@Uo0gGS zzN8AR`FCGuVuD+N?s+)3p69kmcBbOjg!ik=QCHOfLh8>adQuAKhkNV8;Dw#HXC+FK zJa$a@kDx>Po{^_o!J3GBMko`+HH}p!%~{yGqSGSH!mVm#p1JFo1W-*zr4 zKNX($xMXA`!H_8*$b?~3S`w&xBKX9$Sx|p55HpGWP(d-7CgWX#7OXj?T=%cM{5QTo zWr(Qal5+8#e4o{yJZcRhOk@*=k7;HH$gdB{=92og0}H2Vey+U|&uXVOL}dmUhj4f9 zM@KULnkmwfpDgp^!!kPWOi!+ta)@cBF=#L4S$7fUm@mf_iI7?b z^9~0@Skp+;rTit&DTLhoE(zZZ+VoOvxp~;+n|xRXp%f>+A+~RPq;cQ>=0|@I6(;9l znP=jg=b{TN?g}eKb!Q&J3o-US`uOeBUPK{5d=Pz-{T~tS3nmG^(cow@BGbqa?rqc< z_au5eBY26W9>o}Q1P)vYx`Qwif+?JD~&uy5Y_q@UtW0k_f6m zMt50Yepzp6TFlC}n4K{1@<)m6*!6HqRlDjn>8midh=P@-~I=^$%zr7f9#N-DR$) zm-@U8L$c}*L~(~|w=itU3KS7+$-MMFXEam%f{mIKtyw6lylNnF;%7@ft!Js^YxU-f z09)fC-Wf3=Z2vQA2tiSDxVn8}+NC$Elr7&>UY4*nJkT)*NSdptr~sudAeagWc3;0D z_zQs{fRGFKnPpF9AV9$)PS0E*BB~*T*a14Op&_^q^!*^X+A~cu*{betUEFsGO*bta zY8@>6-ab0o`-dRByR#Fx`nPdI%!drWz$`H5RpkA7(m?Gs{4iWZWa;bcs~44;uP@2f z+W7c-Z?Dtwe&aX5tpL&x^QQ4Yylj14;A42o)RAhVi-Xi>NF^qJ928tkRhZalE{sgj z|0`2p7}w#2LqkFWWouwMh!>58h8EC|{t?p8&kyZ0H3{`%D$XXTs83IUyBaVYv**f8 zOq?M);s6|Kz=>nMUp4r1u`|GmWEvD4%FShS8@~{PFyGwVe0O=d&L6d?Ur{eX9?`pn z(9;vuqTSmgOeP`m?>38PgAT2+xf!e$MOC?8Ui{haZING!2cZS+mfza6jmWwhYkL8V z2dM073FmWgaDWlU^5-{dE25+7TK<2vS1)8!_*S(1&kb^}jxw^|PA30Iljd}Boqng~Uwy7q#nb-YtX;M+fOqzpbHlKj7(hpjur!hYsIpTJ#NzGZ;ME5H}(D^4lq3&=}LOjv`dmT33lBitR_U?3{n z&x=Hia?_L3Q}*aup=Y}hK}A+A7w!DDMe0e5JUyYg>_~q??LDWUIPTDYBx6iZWC?MT zjZdE6dq%Vx68c}cx!#TeyC9aKAS%Yp5fS)s*3CPQM!!q1z)kz^hh?wAhmT5#3TQ8( zsU7c-b@FWz!anh7E{#P}$$SdaVg8vNRP%mUKrfC(cq}P(kGjlCRL9AMjKn9K*)`?! z2Qe{HOenc)grlJ%GIVqo;atpMN$0XMyL?mqI$gFAtcf}?)*Dce8h6;&5m|~^y;mYI zlcD^=(q^0jznd@Zk1-{WI~~D+RDiVmlPoM{7(Zm-UZg;Ki0Kj~j<}!qMF*TvI#`3@V zk^*7_1Fa7(#P$Ynxo%&Vv0|g0TE-XeN`B)B?OVtf`YG9cNukOX5qd>BY@(GVU6uTj zvi%Qt{8~>Ct{b;mS-*A#V?=M7GcenfsRf(Ko?^V98hTM|epFsfM(C$VP8dn0k{kFEJQ@1?Fe6Yq+=VK(4)@;sD1=@?~H5tjR=j%j$b;*5ev%t*m~; z$A2kQ>O@SYCW=KyMrNd^?+eN|F)=|!MZG)M!{8z~eUiwxDyJpDYw<^28jRvoL7nT9 zgOs{>;Xavu-nY=aLZ~!C#rg9A2Tp5Z%5e)tm73=7;jpFM*uU+Y0!Xjde5Tp{R`E5XrBkDWf(sx@3(>ygG@J&>q_*U8L6xheK6*Vf#G8z2j_*m0#_y2TbuSmat2URFMXH#2dm>0nPg;s!D z^x;wlnf{4v^y#DQ-t}L@u}g)OOM5$c=D6Tn3}?H#90N}zju-Q@;LB{!VNTTIL33Lv;>qQ682K@ z(qs_nPX0VxQ7NxP|7K|jUx%+WO1@4+*|M;Rf>VAcnBc50lur91sIexfF;@&(C>G4xWe;mSDc@~;70xpy z+Tjigu@XXpYIK^VZ3}%09KElUpLD!$NI#YJ6-NuPE> zeq-y4AGHq^+L0=5Nsy{C4j@afAjC0il7t#P?e(zfMTKBaXQaFmFMt}p7eR*&ElNb5 zDCT4|CDItT<<9WhRkt0v?B4H->V>z6meB}Jamq+VCd&S7p3KDib1zF|FAGi0i?Ok# zKDV~~P{D2}-d8g+ZH`%UhE;8aS91m&f@-vQm8jCR&?`%yOrMy_of_I@)RtIvfnoI& zukL!ezRL)17K``*PKSv2SyE@UNd6l_=aP%py<2n_XRxR$4Q5Z67NVa@S@IQ??$des zny~lDb_+HowwzzB$LKPAm*7in@$C4Smo~&)oAEz zZkl`?i!9dlemlc!_KaHf*$Kbu()1}1oL+|C#Pxec&-rpF+Bq{l=Xvr`Svi8wyXdge_YNDV;bkgivRXacQS^#P9Y1U0d6KEIKIusO zx5xXv@$q>xuB0{|b1=u}=lEv&ciD$}9G)dFnAiaTfac}q?(6R-;&ZPlDf##?_;i22 z2oMWDei)tGo;lg_qJfJ5Ar}V5D=C#qRSkvaaeLe&FlBcJqdpkS(M@L&nu(Ys?TNmzbZg>3KtUzRq zC4F^rvIhTY^|Yg@i36D29vwVfcT*ADc^*pj8$qu>T@<Zm8JZdz zV6o=q?hgJ^wu+gRg$3Z|CP+;U5E?7#B*SltP#8U8$rLImV7 zuw;8qiKCvzz{bQhkZkz%D@};xpWIt*ht1z-bdo82TFfyFSGT_g4z8gUB{Fg+YDv!H zGrXzkgfgS!6qLJp6}n=jC7rp=JNg6h4Gg+U*i^NZl(&*DU!5>(q68tXj$!a-M8{w- zMJRx{ROvMHG$GWV+R*P$naoZs^I$6o8HZ>R4H3=_ad{1e@u=#*9Y_;E@qwMkgFt=M!X%dMzS|~oR zM21d29=M%XGt2ESMc4L>2qH0>DLmt9l{cj&7(EY* z_X@^rv1kX1I*Kbx@I%W87^C%yW{;G)t&&=0^hm1TFmyB)^pw9OQx9iJ6kRce`&Pxl z42LVVpwJr8D3T+IRSz1&`kmT+!9i0!7-vlRJ`PdoP%FwLF=lY_DV)hi;FlnUAyech zkeFxs%_|(#s_)O~WS%vL27i2y7@nxvwInYa&rQuT2-DrF6=PNPNmTt17a`nRsJZ1# zh!QbA3qivJ@Cu5I8Jm*Df5jpIMqw1^{1#%!qZ%PuS57{+u|Av@0)aV?4hQi!P(6X85S0dKIuRoOh-35F#!zo&Tnpj z_*gqx!Rk{h7@dNtAqcnti1l5%kU1Tuz78l6w0CsS)6w1jii?e{?s&;&scz(KqDN!r z;PmAWdHNOm`uRd?^K*5rVnl3g@eD4Q-g;qolaj-26)g~cDFd>+pxotX z2@Vb}E=~nSHh?QAN=XrhCT667kbShbhlz#;oaU;cMdQJkbP)!BLpLn)NJuccczk$34}Y(y z$ZTtSDknD%ivOl_CZLn{4?|x?Sy@u08@{Xj97qK*GdnC3zcBb1v9f-E>r*FTl9XC9 z!9farGL0_@4~LDH1c?z0nmahN!+N)b2)C%v{3X5hB5LCw1!2LqE&ly75%b-te8-Ir zACcer<`;x;U^fp?+ou^_iZ%HY<~SYb(&`C0NW!^##dUg4ZaP}TP}a8%}74}%_s_T#jPtVwej#H^#L$!`eBl8208M@)U$SjJ8y zOP;w6`~1$=Lej@6ss1S`9&-g0xUyh5w$9~?t>j5~y+_^q>8C(i-ERw(qywU*d*4HQ zEV3r#OxkC~p)w{d<4`*l5Sgg|KdQbus_OO2n+E9yX#weymTr!8cXxwyhk%r%bVzqe zHwZ|H#34jlK)So(ef-VLdS~uBe;m1b*TK8k-@QL6Q4qtEBG03l8$fnBU>!DU+-hTy zpH8ekMy;*M8}!I8uJd+U_k?pYj8GC+&%L1IM#}m0or|9P`VM4nRV3!=!daY1^o5SD zteQ$wjIdNjuvIrhoPR#oc5(N*G_1XUrJpd>25_VR5P`b`in3q5=JdTER zsTP>%@vBjRZ9O+OXaO%^CKoXTg`e#XF7+`JA`0;R6v(1AahjZcn-JDVN%quucBqo0 z1Z3?;b1NS#Qu0zbTmmsfqOpWC~y^rt;XQ(~K8;*YoL42(Z-u z)VUVO2v$hp5U~DXgQ4APe*Hf1Inz#5F4tJ|Ww#Hs!8D{@m>}GwQAtK#&OVyja|q$; zd&Fh2%!`JNh_lbKW#~S-``$jsF6aL9lcera(sdU;D%u(w;_LxUajah|_p-|1B%qAJ zviI~bxCG)YuVG|L?U91Dl4&y5Atk?6-slNaS;JcwA$|cQmIiejLlvdKFK%>)w9Jp2 z7?OF}Ht=CZ7;3?Cq#rHdObBcLpb-c`5scAI%iNVXxY>#I{=6f)NxI$Y&XDYyj$KyA zF#LQ#a|W%#d|9lEJNujH$1(a}cVt(;cMmI6;>M9;WIi?tOB}=tlSEUKq*K31r}(jb zA;eR(=<8TWt{t7szK={ua1}_Q6-A~^g^35yG65flLj~09+lQ@w!=!%UB+0IVkAb#b zF0Gy>MeWu_1@?`dexK%flAelCvrQv$@-C&rmu%}&V?doHGFBJ3EDU;frptCzG-yy7U$VkS8tsahz@}TQfBqeTpx(?aj&u7TxXtD3P68BV&<<3&Z{8U#${{LFWL!d ztFCf_ati@rQn{ySEf2>L)gR7U9jO)=SMCFWpkX6-&EBZ(e2Pz$0`qZ0`I}w|j%89|6bus%ft z#Gxl%KE_Cy(pkd&w4{aN2#P5leV_Lg38sKlojD_+n?U62v(91B0x_S0put)1xB_ z@Tw81X}0CH@~7GOXkE=fc%^j3%i9ceeT0OBC|+iD;8A*Zb@hgar@!W)4v$1`u)udn z|C50My1abstv}87qTXn=S3m;GimZObe-Z7tF6&*I%`J7f14 zxOI4rdLoJ`!-#2XmYmFj2SFR0N!d^))5-9D0Kr78mIymM3_i)wbO;@O(cp9%y&Mt# z$a?qE+QKMbFcrQNlANW z>y7EsnJLnb#9ZX{$;BU&14x7O;o19q58AMwn`ZE_n!*GW6{zjnD(ZzVm=t5hgj&Dk5M`iLef#eEfs&W%7X?h?HZ2Tp}lpM8*Op33HT0)fT#lC=-H%r}7Cit^t|8 zbzS#pQb?b3=rfy31YxUW%u+sLockAM!#{G{hy`y$Y~t9nH&LzUL#Gd($`>dsJ+{4p z6e07Ccc;P)s^X2A>a&{XwSsR1b+O`?8ESd{0*Gza$X@2?o*FF$NzB$KnX`}m^JcEI zCN@6C*Z~an5{VjIX=9pN+zrxZaTbxxFV~|Ze)lD|ha@gMLEFWB$S=xk4?d?{$8ib{ ztvvUTrlImPt=a1TilDD zPljgRgGmX-;{-*dvuLxpTl@CwKT1Dm1wqEl366B(aaGlD_uC<#3o5|=jn5>oK3`vT z2Z7)3J@N1~=d}OwIu4*dvx35=_b|d7O`r}f8?A>RUmBi8 zD4X|b5lqIGtWm%{kWd}`zH&@txUuVk=Ejhk- zeWm(G;1QDZR5<(b-tc;uQ{@XMEnn?7hCvY@8K!`s-~v$M7JnW*PEbOZqg z=@}VdMgsfA;NTztx|4wwg^0*nr99um!_&iquCC78&FxVC>i6}siFUg zf-y8OAj8MU$HopuNQa35V7{LZtYS$#RtDM8)|L}^D1kEpys@a ztKHq*K+Mg;azJ{!FZOZ=+#Ozjw-#XM7x;L2=YlxL|KQX-;k_Fi6tf1}K|>v#^pun) z+0m+Mx0TcArY4?P8PM+ppmku7xjuo-f88BK+uj{`cs$42ZO{a!_1Rtf?5w_(b`P&H zK&{IZv^1?4a>)~AQI1)(HIl1p$>^yguBs%?Y4mD4`xqK~ zb^4Byxd}}DZPu5_v-L3aFp(zU@XBvKyRD1fmN6x*^j6Zk&8}Mi&0uq~o*^GKH<$BA z2xa0GBLm1l)75QhZQcsnH9Nrl8IG)`0wY$(eH$IVaQ2$*{NSQjGez)w{lW(o+C2n^ zi@R!g?Ku>4I7{a@2_LSg7;R3YD42G<`lpWyHmJ9tJSk~(8RUxLYw}VYhvT`_3_s8a zeH1`ll$weH87gGQmF8TB>v5{Iw=$T*tWWK5US)OtN6NQN8IPt(L@9~cjI*BuGFxhR z8y6bmnLkJa*syI1EwMZ~a`dx%fvu|AfUAX#AGK=1N7n3EARLddp@~ zcy92*hU_M~=H%P(TZ($Wq@S+e8%%=ne|}44`&#T~Flp5`rQ2*#qr`6rRBY@TuHQEt zPIbDxTeTQqo0XDG<1Esdks!%56dz68)9GJYp+(r=N7&!V*dq_xBhfM44~n*yHE7=j z2G#6q%}M{sivM;QbKK*(K9HuAeSgBG_~T-QP}jK4|7mQ_$ZvN*y>#W-eeSH#&(O?r z^UU&+0$>+@5UibDVPci@-j(KtYgOj76~UG?$79RE%UZVX=U;7DY(^`VUrC}U{9nZ0 zu7|qS=6D|-UbC%Q#da)po>pI`#B3{fU9HOlG@_Tc#aT1TZnp5!c^OT;M8<7y>jc@ki<9^*O?{eF}LApbI5+L;lIZVoQ+@Zc#IqUjZzKf<$ zOj-g=m8GR6Q1=rKLNv;`NveVT7I2SDOg~mvDdF9`vK_Bshpz{Lo@-(Pcsj@|*J(oO zP{Y^d>9U9j*XJD)svUghF2$fz06!RJu)WT4@SU5P;bve!h)3pZ2gG4(X1XX!ApG}y zwtK$V?@HBGRXgs!N=ip77%mCi&hZfZw?Fd^JjgJu?d$-Y9YSR*Apr*_t(@Fhh%9hs zNECqSu>eVyq6VUipi3)@v zgNy>Ghp7?UIy(LV=25T|6jYLws_N7@DjEzd9z$opfF2n{Tmn`RY~aHdXS~=NZo3T= zBKCH6pjZ!pMSzF}De(VMK)=TmoWAzCdbeeMPeS3twErHS9=^&5mhjn6rT`W;#M9IB zw~*HX@%#dbT6t>;U1&P-202F;fPPZs9+47vLg0~sXyvH2MG%vNvvC!uG=NAD{Rp?(^Gig+2M#gJ;df-6^chB*0&=C0%_aDGPGR-zI^PzWl+Mdj^ZrJY+&S|#V@81xl zj6|dM6!eMrg}cxuiBS{0N?mt^cU_sQ)|#u<{#7mRI9bbT;-j*!nFoWIaiFpnc^6#O z8}qA@DJ#VzBE@4n#iJ#qcDZ)tqSdz_MA)^k&n@-nT|T&ufnUtk!W1;=z-C-B&`{v9 zQb(0-UV6-FY7UQ957aiMbuQ`ocjiPlr7f1THxYHsXt}FpH`O0?w#PZ@=nqG^6fOT~ zzaNo4iZpQz6Mg$5mxMqeMEmIi#XE;&O*!_2E@E$}{l^`2LkuB`P6}7GNyS}r^W;-g8 zyjd$>{|um@R;^|#Abus?4mEGmtYi|5rJGTieiQsr9trys3Ah6YSLJQ=nEJ_5ok%C` zsTi%9L`B|ViywT#+$jmWER}hIHTdozEue4yKmj^L+elx4Au`Dm*2 zXmc3+&_^#odl&EknX4`bXof3-7F*Zl!o$rl^Rct{uzuw^W6;cf;!6K*y&qKsY02G+ zGVd#>v$H54+l>B`#&P~VL}&e>r6twL>c1Vx#w>86RJ3-jtD4VHfk#<;^vmPCv_@b_ zJ39le1`tRwJTf9)EP;oI*WcF%DmA)$5q!9~xU8+Mfv93B*pZGQ)?1>)b>_!c2%CcYOm71Q%9R+9Q1U`1fyeD}RC(R(v|3 z@4ilQaK6n}z>JS6yt&5%hy(bhRGzv$GsbfY%p4ubi6LNG6&4nfAhfToa#@2Sie##W zdtkl*9%^v?gKvV8a#ayngNJtgMDHzjpAYba&NQx$F|zs8Rl#3VP|%0AwgIKA`Q7%G zmiU;MQKe%izvaoHq4Wtpi#qh><@er-Ji68S&yC=}F@3}Gm>I>@{DcW;&v-0UR3QD3 z43}#9;O?~?gh|_eb)emXUQy@)ij_Pm%d;uLb3^qeqar-1p$q$k zZMCr>o_5^V56tiEnUodhRUDBjFmxP$Y1B-35lo<^Ltdh0C!2)U$gy19ZE0*}{y+>w z*pU?9Q)2O2d6>!^BMmyo=}ti`w=~?X&kU0=J#VeQ2=?+ivc+;Nd z*)H5zA$ut~%kxe?)!wyq2aOWDDS?6MRr`p=h=pRYRuo*Ck0R2e1Wr)CPH@7Go5yS= z6TRYkCoitF(2R*9BJPRuBTwr_IJJtZ`@2Gd@GH4=r^fdoT5pmF#bG3%#A?cLZKAAl z$>i)~@)V3#qc*aCKV7}oN>ig!k2cEP^07&~9p5+z?vP z{jP|hnrIwuqBvwE6V`G$?*m4nO&3I$UPA+G*bd2(>=eP6vmZ~X0XfA03R$%ATeQ*N zhv@IS$Pd}*-@Dikfv-UH!Ry|}{@wHtbkE_lXA{O{WBi5Zr%R7d zm;JnxBD|9Vyu*ZJFpOp1am*PTk*{D<#v5Me!MXdpWUt(Rj2O5*SgFfzAE zy20wOjX4#^*Uv(HVBqF=q1tN*P~K)=-^j}RyZ(RhwG1&Yh5prjA|84jbbfO!h=Uy_oNAZ`cL zF35wj9C>;0K2oXxhz??7$M|-roWZpUq)d2tpFe+A*USJ91~o2AEiZ z0M^0WJRuQw>hrFCvHa~K%i;{d zrMHfvZ{M~R6@4EawU0;Q97Y@lLjUDub9M=7d3kwU#(#x9D=WS8^RL0`#L3A-%TG%~ zQ`p`8MWzr0mV;79YwPWQ5ppGxK={Cz?2YFf#Yuq;4s5Q?Z0=avpJE-Zp4sO9 zh+@5bN|d0*1yOb_nf&qnYhYZKY1pZ$OH4iB}QRi(Q4S6shds`Dt>_Ke`kX>^SxIHqj@t>#+xIxgr`Z;6mo;xQE$tHj$OEq zf4px@4r{}OxJEhW=a!uoo~~;tweTz`mfK2 z7rCKDSrg$-u+in{LquBA5v*6fmGDr0Ztwdx0)j3`SsBtz34rP8XDZQnD$$rG{)Dy~ z5mR}L=FGreQnB5FtKv4PPny$0zu#DX0UmIyc)(5bq-+k&(Kyi$7vdItg=4fRY$_h5 z@)FV474TZY0?Lh@>LSmKxf_;z4d3ZS2>zK$G7nZl+1ABv`vOnOLdU52tqI*lC%vDD-!OnvP)=A#>ld$* zb6P_?zT(El`sWXITr9WqXQvHR0Y*MGWTz@OKga~2Q*Y?a~&%61)X3 z;g=%C=(!qF3QT<|=C3}VeSIf=6DH&!haj&q z#V*4G!$52_K8|@F2WWvpsLk!|EjX+Ija-(#v8)nvI0SMO!Boo2ECNDEz!X@XFtD+W z|NMDzeZ8uYfS+uy@UEAK=jH4i>65t-h#CTZ7MztunxXInj7v@BHbFt6846dSvhUx&x3I7P z?ji$&Y{2V-j<(X$xvST@r~HzB{iU1~tMuM~qs~@$?u9FJ#FeSAubq;^0&c)}C}jrY z**+9k*VObX)=ER&eCN1_U_OWxGUKBySt{&AioxamOY*tL4&y0C{$wl{)Ml#qLw($HjvI=^0UOZA)!hKEC})|q<)Kj{5>TYC>K;&K26CR~(OLL< zxBU8+zQ4|io6etyR$pj$lIHufo2^eI;%(E=Psl0;U~@g19?)0T*mTM)M8mmb=rcnJLMw6En%k}H-MzKC2+gF(tYy$yO>7y3P$>a`k`xq&Z@tnw7(bI z{&L%r*Y=qyv%go($#NUDB6HyL?E{Y{OqGCLS@~-_1VNOf0`2};5A%VnD3mAwT$Lr3 zm1LLcF}I6tC~afK(+0SX=zU|3#X6LaB1YIfpY4}cq(t^V0t9Ivk_kmCP@)H-VR*I{~6vqLV$1qVwFEK-T zb+Mjm-}QZKqx3Hi@r!RdQu^-+WJGfUFJ9msDjE(`c>A26^@ki_E#&0nU0q#3C~j_U zehxxKx?iGnitB(Puq?%>t@Z4*uWi zLtHFuybES?Ph-^3j@QtRpcZJyow79XV|~WoQ7aB&z&l)Hw{%r~7z7RQz|G$E`NGlq zsZ^}M*iNJ1YeLx@sRA)-)amUpElreITN>4-GQ2&>L^QmxhdvPRTdwhcb6Gpk0 zHX)kYkr6JhOoM?KM!ez$Le4^;ntG(}tdIu0CbVXz05W_zS@Si(PF>X<$2^%hPwE7! zC65t}qvpV|XOg6LAdqS7XQdz!6Dv;c@b&=T5PDTUHT7|cK@V(rRc%d z65mzctf%(HGNf6Y`G;Dz=?i0rtw^iN;91<0yyxeGE@XH8p^WQTL*}{$#`=vT+Efco z&)^-Hcfl|(f-w&8{f=oPS71LNvQRTdbwzbu8_gK-%_k`?X0tn9D=r4`Z7w@>uINzP z5(HWw!4xuo{h=1!mF|Wm1Y8zvZj_MZhv{dZr{Ay+X?C);zu+p1FEbN)_9yE-OnLQ(+9d4Sx-42YHVpoVVN!T_xWL>qYv%!K zK%_uv)Y1At4A|>{o^euUx3dc%?VDR$14Bdb8?=7%pl&27ZSb8;KTm0WF zpIry9!>a3>S}{~YVkN^q5yv|g%QKj&6!pYE$(5k(IEvF>+kJGF zg(~dGKwx7A;gF_VSM;vZyhevzjeN^YrQw0PI`90e9GgVtmQiZ~xxviM zX~!RJPPZD?Bg9li(&l4(;mj5D%=IIf^A-_iCGriE_tVc0vqwQO?r{P%e?A5O*WCHf zo99t#mu)_pmkPK!CGDr8@h4l9OUYb}MZrZY#v*-+_sYvRPpz-GIMcT$V%SLTH?OWb znhcy#xe8BZPnrdLvPMjjY#P^7lmk7s9^p^@m#S)_45%+~_wAxM z`&Cp_1hUR{qJdQd(?69c9L}JVlyq5M?&|DJ1YP)jIv!;%1pM(DfeeKbwQ?2T5vzuP zfPnny=~YT9C6Jkk{o*#t|Cgnmjk=0=9X~bOlnIAjlODqwI@qC5Q3+9kn*?$vhWN|b zKaZGkinnQs6Y5{k(!z(H)}Q*PJeP7Z0mvWDZ()U2LhF$_ls<;i;xh8` z6871PiefIwXjoW)-c^~xcM1xhVq-z`97ooeqN1XY&pZglj*0@YJ>x?I1K+>Hl-mF# zT}z8sBZ_+02JC8D`Mh#Zhk3t_Uu5;XoH`qeyoho+4#GT92g?&!%?1Vrq-A7GEtM%1 zUo#O#H0ZFfrDY`~d~I(>4LYpTVY!F{PI2r^Pzzm#`#KQ<=)TB|f{ZwF&QpWF-3=lm zek1F`0*U+`a|jNI$TKsm-&l{}zdpP2jE_92s=4AI78}qv2!(JnGw;87OJx8`34obL z#K&%zO)0XvQHLc6juzySiUp>VY!rBu9f3L2Wez;^-<(#^2yvIcD{Q~1qo4GXNTXe% zC$2MB44yifQbLeX33&C1pj7EvKvz1B`dBvVN#XYgJxb=w~ZObW-fOX%H@mRll$GDnIr;?=Ij$E&nq&u2?&IFlB zvhw4vy8cu_XL5r&%o+_$7E=fJVqf=aUyE6RuQud*498i_$GO$yh83j7j_I9RZ@Kk_ zIgNQZt;sWMh|`-f$JuJ|cdhj4W&4MaB$3+@a}=`&kyiJZn(LCS*vvD35X+!-HGVME z>*Y<~_2p7@E+LjH|EN|m_{Xt+ap`Yax98c}F$CcB!binB>8X>L5oerDwC@BECTA%gg%%e7sz75`;Da|DxA9R*L%6`=MX(flA<` z?hy(c92_+bHMqUp1q_jF7!eU|H8m~A#?pRTMip;TSBn=xWAOL#%xqnhoOHxZ9iq5} zX}CCFsb(iI#KoY2Z3P@|5V!=X~pLlGwTe*+6V5KF*4vP?Jpn>=MRssaCBq!m>=Qw?#6ZM)n1CbQ)Sugmh41Or7!b%Jvy^8856%&Vx zZ2XK8Uy$quA;7^MP?z6{4`a)}mZq_JpEZP!=04m!udofrHW$`&iw8DFdw-_0p$M0 zTSgXw=pFjxa0$}ad{y2InI@H#(W**+zg}=44d9m$qkA-f)nvZak5ICJP5&Aece&Hc z)8;Gf>w3}i2bI9HbXrFPBkpQj-^l3H>+0lda}9TwWr5bX5NM?qdb}29jc&xBIw!Dh zkQp>#)@Wf=>qTf)N#?=F?os5raN3bblKdsLvJ#=`9ye083-cQS{+T@Qb&UG7L+ z4tILkl(?E$IhCsj&ea(2aIkolS!WfSdklm&-3IXJ8fx;y_Ig|f5~R4hF%Fnek;ZCt zMHTR=H__D(?o_iEldya`W9mVzG`1v|GqECORWQ$}&7YaDu^KY07(cXUBeqLX^c*P> zTO|h|Z zyQXZrw#=&Ibs=kbKT(Vf8vzE-)-@kK79SxNA3;3#^IyK_qnn2BK1cs&-55uCV2}K^ zjHP`htn~fY@1nHD#l>sBz{kU$fb+wi$2I3;p}u=jU0UCu`^UJG31BAm-6LBV40_D% zx$kIsI?4@dhHYuWi&|NIx)fV~BbPiKd)P~KZ7o%RkBX?Z_X%)9@7|4!kEcRt8EA|u zXMqfyj+QpEKk0E->!TlIEEB&8O=oBwWd%BNeu`>Qv5B zOuay+R;5lH-Z%}DfQr-x_kfEH{yiw+#YG7Nx0+cUXeOF5gJ#LASFlU*aDU`6(BR{n z^Sb(eg;D2=^xLrOB98eY6;scg`O-D!c%Wo*Pk_?x?Xrf<+{+A99(ihWqS2ec5$)Ug z=fRODLfHih{4^q5o2~mHL?k3sgbx4_0t6pw_>VOgl{e}SHCKC*v~sk#uRK@YVo<9# z%zsK?AjDQlHrf80Lt|uNA{iv-dvG(b-Nh`7XdBT!YMOJty&=l$a&d8uOxDxA0>6#& z4Ca$HRg>?ZkzZE&Bf5T)Q7hRQ#}g zDiO+!_)9C}l{dn9L%o<1#b4oRVEE$A!hgvg5GxCbA8M0bOQm5Kebm6mlEi_R&cvX3*1W#Bgdit@`&Tl{*l}KgDO^V;%3w2YSPx}obPHkYo7l4%Q3*K@9s!rKC7^#N#xNr-m^}&!$rDd zk|xJ)8eMlm@B>K}+&-JD{ayfT%Fk#!CEM`YamZZ8t{siEb&0(qxB1J$#;KOhXm!)e z%F1m`-XW{YnQaUMHWFKnaZkH6-^HrzZvI#H0NIKOT@s9Ctmu&dW zoOLwGa=~EL9xa!{)Dj`zdcVE66i49e zqv~ZzEr<+)$vuFG-brzvqZO+&uQkcl;M8deZ;A3QD=z{xz zia%Kky0}Q%r$`YGN(ek5OcC>~ve;2lNTC!IIO!>)YGscQFU+=32~C5<$E2Q^LZkHk&*NDyvmQVo}cy(mv#=q_a|$6pZSl8p4oqv&3<3E zaT|CmUt9`Z&q*AMjJ`s9@ggclP`Oxy6Ib|aH@#E=Va%o}?GM3D2QVgmIfa$q#pT!s z8BPv+VF+HA^*{;=3$M$aJD%;R0z}@aK|tCV;~;O~)Egg8 z5#bFEd^ov#vAPFtT?demZH&*4b(ChY?{jY4yW+~Cs>>9I<5dhY zcECP%w)w#p7BFuHFsH!pr-bhR%CF>zS`k1vVUU4{D+yB-!GoOTzXiNPs7X5@(WfFm zB@=qN@J7c3TnOF+0z%H@nLQlcdZJB6qHS7y-D<+zJ*{e0S@!Bb-EGnYnODfzdfuwt zUg=!=sc-Vh{%}IyP3yQEU0x{0?6+%qUo6}4yE^kQL9yxGpgw8@={XYn7M9_UUFYGK zHp6?B6Qtb+91Gck?r%DJ*a|xY8cKOPp3Rh=2OjcAlcKCHB}#p}<=@T~8y>K~bXFgC zXL`d_k#0Bl(-_KnIbyZYgeII+w^fi|l61;D0ASiHxl@RIuZg+QbMc2>dBn%Gvpcq} zOXHu1)f2nrqenH5(4dF)6H&`-uAKjW6#TmmLPRYQoF4D7dd`=RA8xjfkIyIXNspf| zWLIyGyn=2vf>xbLn)|@Bejlsny3kni*UhNb(R5fp4K&vH@gZXM@dzvE)ILiC&(T(t z*4KJN`#HL+uh*}k8aaXC(iUzlBgysxVQ5^5w*7L#w|3$nR*KS;6f1oAv^TfxoIXzK z9W8E^*SmZbVss>Yc+~JdfGs2?;et+I-mHAv4w=Hl(M{002!egU+N`n1_I-LZX8o>W zfZRj=HlSBE8T^`=*-x$n7K@)m#o$bmQKGG+M)2VFR2e`xQq*-cs#_cE zt#hb4?|&;xv#NHq;GXv18?_w4JHG~PH7{Pl`P^V~#tqq{Qzr1E2TP#KHEfSBa_l%J z#AES%F%hYHdB<^z@Cl2i2s1{s6%9Vwn|h=%{x?dFVP3QiRrb%XJvd2@1( zSd?(2W705)e~BzyOGuD_Y2T+;NR>spK#7vj_qmBePb2%rAeSoZArXRxN0lEO>-!ra zf3Zf4ESj7cWB8;YN-mkQFnyM{xSKH_Cxc|&*CzJzH zH_HU^RpjXC4^=+sp8zwI=R8_MX;4X~Q@&%2Wa4fzU^iN5+%Hu)ny%u$+4p;P;myxa zffm(v7UixkD+1iwg3She-M*#{#dhANwweXG$0`b5HmU6j+J0l&_lo=4a*k(l=`74xzdBRZA(`_K)zTFYVyfxzbMg{DYD1 zM(Xi!rA_yL;R_vG6^9+ymSw^UwT=_&pFU8NzgSszwio^~xOzE1k;LY|*nDT& zTxTC?MLA$%*P?xU9xseTiy9NcnW128Y%G$?P8b6U-oYLMSZGiqgkw(EmY01fezz*%r zo7*>K^9MkQk&%&{+>hJy?E$ko6$Zc>`;cig5>d~4ED1A@f@i!iO@D8v-`q$%Hv>NE z<0GYO&->Qpm;(>q$G@jB6FsKBW30as;fJLtDUBK0g#Fh$TUvnoSm9s2h1t51|MVL4 zo<*t6w}yJ}e}aiakYqNYE+^*-DgfQx zxvQ`el9J3gh)*E+?GVuFs^Z7Z337!cbfTAvTMcSd7&LaP6B!9a9=-;P9Ve*hIgruQ z=Q=eeFjtItr1gDDRew3(xI?_McAMWL>Kru2A_3Zvz%2vBji3(%f`0*lBtvM`T9dy< zPi|m<@55(S^8rOeg9X!?lagQLt-ox<+e_@2F2K=f$%~6i;qH!5s|w^$5D<8zI|@ya z5yreu8)YSwxB3{SbnR2*N9n;C(eE?kJiUe!gmWcFjO)=8u)5#xN1?MWG-4!;|A7nH zCK8(hHxMq!Cp{?EJjVqAhM(d2`(B^~4C-j`f(Zjf`U3r;%NIi()Wq!AT(e-T5K;X= z;pAiqb6*E~?1we=VQ4eul08x2x+w#7K7=s3M&f&v3XK8wm%fgZWV|3EbgDr3uUMM7 zk=fKp(MQW|R7*ktEnGK74I)Ba4y}bpqw+yeOHFr7oK?*8J3=&8}U_xmz< z+yOu4SGdtbg$dCMm5~cYc{Rk3?yK#`-BD-j#~qIITs!$x?)wz@VP?b^<885m+q}K+ zJvYW}^Kk!VgTuoQ*w(@8o=PIVEPS2%ZeW1%Q}p;tSc04u16Ya+u>BA`RuVK{_)rlw zVHys&7v`mwdAN*$l3uX=eB0qX(S>_=@%0-6cC-<3kCvcklhcFm;jk~Oi;-R<=_I>$ zJPT`$+y$Cr^e*OrL&y6^x%n~EPtjLdzwT$za#Ht0XO9()Z|)41`L^tPMC=2s>({I6 zqWNT5=RilO@Ln6{yhe;aE?IpP-MmJFMOB^6j@jCz^saYh48H8DA!+Xx$~O0WLxd6}?XBhT$d>7~&9~e)f%D}) ztLRMbj!X87@HPQ9@tnuu*E03Zqe@i`wgQ9n2vYrhdhKUO~TbJhH{8 z$R1I-q@5bINYU0KW#h5G_})pag~di6Nfmend8tRAE@>|p%*<8`FIRhHO4SneIz771 zoqQ+k;y>_jFjmz`fCLdtY8RB1mE}QKP1ScyIY?Pm@riX$O9h zJ|q1S{LAZ!0gZiLh9pbm-`w852=5yn9{#V~fr5g6cCA^vSee3k2T*nl#C$*`12k%2 zuQFgu8?yqr-tcvBV4Z>50P@#gNgU?f%pzTYk&%^;uLVGr`6^|zc3^Z(@8%5yZh{&7 zIUxGwC)Po~y}JV%6OvfZKk8&Q0~@)%clUmV?SKCtRbK%V1=zJqN;gPKmvn=4EZyB9 zEv+DFr4*l{Gvpiqi|& zb~X-9PC#oxAaFTKpwIz;Pwpx7xnAdYk3jNQfJv^(g)SgSs$4N6SKOfnMs!^NCVUWW zv;bLp?!XjbuO`01KFhE4LF;#SbP~NgI(8V?<76ju-ab!(K{pk_9VTqGb#=@-;P8wK z0{g3)>F4u>Wc9TrCa)Pq^P;7PBaCJc?7P2tftah>%p^nGyt4!QH7{vXvIJmggQhj& zxh~vD09&%Go3Ux=HI)tLPKXdMrCHsY$?X{rcnNl1lXzB(-#xOATe=YfxQy=*Ef#!( z*pVF;#u_F?*=MYm=_K%m{KSJv0ilpGjHj<8v8f`n;Y?_pdj(%I53N}^Zv0FNRRk45nL-~b#{SAiIU`JPT1m2>4tcT= zp>`Bw+bULW8t2nf@*r1HD_4bMR>K?~yaq08ku8XBtuif^oMVKhHVl#O?a(8DtNO1N zKn^|>!g!z7$qt3Cz-7b8rpMi)CE)qZ;m~vW_NwWOxS{A^hDv_60RCXyd**cGTr=Y% z(wfYbciP8qRga4Ctj3=9jm@<1>OUR3 z%n0CY@rDgKL?;`)8E18~-4>X>_*TBav*(^}cYThC#Jj0Ub(2pGbdGB?zM%_{79k>Xq?)Ixc+UH;1%PfpUOdgo^Rdh>5C)vFA z!kaoGxALnjHp!>hkyGRmEmTS=?S6^oQ~qC<+S=G_=x_*tdcjX1yt$r<*S*+EiE0;oIt~@Wo(8GIF9gxd;x!*>U3^ zeW{gpNfvd#b2&rHZhW{Q`X!ANoYtoINP3<8M#jaA;)EbTly9i{_DMuA9Hfr@q4dN% z>~X?_UP91Tb)4(DgMG8(CxCs%)k*R3xq4}y4q~mH*E71V`48j4MGjFaasKrO$Xs@3 zSQ2EwX=YRv#;;hcrmLX=de&)QM@fi_gBZcWB(E~D0xUr=l_sn~VHH@DKoJ2A4Gk-6 z6~JK2=rt<_uRL)S0@CD)fw&l`)&QDAnGoK;2{_j9F%Y+PnWx{}YBt$H{aMIc+f!)gW>l_hLyTQ__Me%jThYZJH=^Q*n!zVsc zjq|@bI=yPRPKeN<_qf9U(3r2sp6Bq|HJzoif5N9E>&3=O`e_dSJ#_D9=4q z>E<%@;}TjNxHXUCAY~dh;2XhWThz>hBFvSQzX+@S>z-w0d%0Z7`FE|Cj~{y3DRaVg ztrAp=z?R040v5}f?VWz$9G#e8H~9Xto?E@cq-<=wR;Qu6hxNJ-19ke~3Y1GFc_7@q${~~v8W1QT4rWT@Vu&dOv)V7J2~5;^3`%?}eUlqV$3L$5KvNxS zNQR7doWL|KWpc!?5)OmK0wKrll)E*$RZlLC-AOFPNT3w#-ITnnwWh6*;28Wfqr@%*<{bu;3A9UiQ6?Dl3|t)HR$n)c4&I_i!|n^b2Ze z?_AV2e& zAMpdFp=i!V>bn+3l{Q9|E#U>E3Fo&PTl{9cDdxcio`qzzh}39q*?zG?pNUhN0c)!GuYr+;Z|;jpkIwOyO&dK6 zhN>5m{{v&Z@U8g_5jpv0y8n|sS1U3;en9Ky5z zN2ULvoB!`8&$n1V8GN8+IPzk0dntZ{#0QL(1Tqov+bpU_;iXjrp6B*PE9oZvwDt>3 zqn3+xr`t3{>F34bYchMU){E8dt}*Bd8s)Pa3`HS0?AFGoDLvygm*nwtaz)ZoR$j+_ zxR#Fb!U?j#5rBnefafY-yVo+5HvXF`d-sCa0v(5q*g;ctba}^5( zWcUshh7=+KdXu^Zpy3171FZ^fIy&%93+7JJ04}Jfb*E43zrw$FdJMRBCZi?-qGmP% zpnhTd@Qs{_Nr4_W)b!}_&RsZf%ygog$~#eQEScV@s?4vT;B097JZ&>ciT!C=IaEa% zK2eC2Wg{X(4EnHHdkHUsgFvA&bvIWA_n9;3X%#kIfp!W=m_bOQfIwLPj&tEJRK}3m zzrBj*AP7sm0NleMA{Lk_sF@U)UWY~XZsg~iB+$!{W1inZudibXu9#_8(HpnE#3K&A~iNrNEpZABIEDoSWwz1Q)t$0E2O;R<#9xKWa#MkMT{pa2475M zveoI_I9l$qt>0dsLiGeq^k2kteRRKs5b<+&KD9-+5gx9ZssMHf8!nbw`V#tSwof2h z#G=o>7^#pY(tw?t=@j^ruO3!eAs&j7f zH}3d}f#SD_A`?fqIYn*Vnh<7Hgb_&i>lktgx}WUzLVVEQ{Nw4HutcDjL+HBb)k&+K zAU+7arLe@yR}8&IsU^0)ZRvwR)Odju7)=bV+InGq(j3J9Powq}J6~A?>hIK1`8!?aRF%R{S zF|!xxtFmpO z>v$k=6h7r{F<*$)_cws8F7H+Dvbs|oW3*a1jqYZxxAcqf9Ah=wxV3zp;n=1sf-HDL zndhVj9b>^?(0w}A7!gnhQ){k;SMzM!`fj9VvLYxSR4F#vwBaBM(&;zI=WAGZt`!%q z4@q{XStQwuUcFnS&$EFYI9E^ibZIhtH&>Q|D(7&{SX5MDcpg>_#gtRG$;-p4@!*KSN@#L zoUF8Fyb!6F7Ji7o2_UZGUvbZuyBzfsfYIuwsdh%7ZgS<`+@cCjGkVo4`(|-=Brq)w z(@5z1eaV}&@nO0U2u6F1k9hFsE7`+CNTE3gA>%Yb25?(vWiciVa1o)M+h|wJ07)6Z zwoPmJ*f7n_)#;O;jurtT4qgx!cOZ`wEIlA@2jJgoWg0~j1Tj+e94`8D%F1z(k;q6$ zXFF1f$|)Ws_E+bZ4|PK#7~R5uHaA*`h=puzTF?`+ebeFJY~SABOF<6vKT+pn2&vwk zAG|RZ%=$PPb&u)XlbluAA=+6)sX8oTXv0N>F;Gp8U93V6dhxu4IjJ6EGVk$;mSSyU zszQQ)@x`lL8i7d&lsy0&hJzDtFarTbuCA^?I|w2-;`)b1M!2&^z^R29@#*QEFqVOCz-!rv?i9eB5*@s*0T8vIbMfQQ{DRMEG0-#GxEip(gS*i%A z@$PPKO)Q+=JwFR#NpS-oS$9{Ds_F!=qk>^#`q3Q%G1p1w*sOJe+BZ-0zy{dADFO}1c2D+7Oa~0Jq`se6H@Zyjye%g#;a`PccR7_dsbI?mZpku}4}rAaTohGB?vOF{o$s@@arjKPef z?A`6-F{vdWmAp(sO*&)OLSYpPp&~?3SSQ7-`co0)PAOhk4VxwJV|6We_g!dN7~ zyX@ARCIDX$K0wJ3nFpH&Xt(DGYo|Fh@*}!?-?P2b+X~E&;@OeuZ;fz}_ZajLJVrLl z=-U7?o)Pv2QS{7bY~+DdA1a!XIuc1-41|xzW5p5BZ0ps({+ zWkW{g)vv>bh2e&b%Z7~TnT*RT@X12-%wB!NO!QU5uhbBm@u^4gd(xVu%_;z=;`=ZzZvfH ze80+=eWkEgw^~10p}$}Ihk*S%fZXrVY<;9a6U@(9Tb+Zcs>||i{uIt58XU#*z1Ld` z%>coAH^%}_z-U7j0=sx6u8M7eFE}GKX3XFrS@bQWTam^Lz*K2b()y92?Zxh2R5>O! zI3^xh+n;WfH&#F9czyn_KJPzNoU#QRcm-OuZJmDhcg=-r;JfG}qh}I%>>c?&SQyMk z8nOFnV>$w--`Ha-#VYSzEef{JHs>(9!bF7ewJ7!d1O`KkaG0#RUr75{&51w6Z-L4) zQ1Z3sojdtCo1`8=>Pw6naZFU0v-AKL6W(hI2xxGYyndaU zmb17lssMO|$UdqBX=Rau#d^fPM!T0;CXBx&goT zU4gYN(!s>a=(v#kac8~|cKA2iV0&D-$+OT&aU0M8+mV4yYU#Jatx6&)N%#=(+5 zo8NfWE*vAn|IQTgdyczQp-uXQ6Vde0-2UGENM~q5J<+Vxm);ka>9qhoqRxy+qFi#X zsaVK1#gh~G*<`6Hqa>A-kN}qLTyytpF%R~0#GWz)b$3NrJ% zy2NXAhIhb11%$vpDr{V#xGT?rGOnRR7g4dXNa!o@5%;g|5g>5*sUZ3d->g=yGLarq zsQSK(k3xhCic&Rru}p)Kw}V^v!c=ag?$|K|YZZ-knr!Dxhyaz9Aq7I~1z zl_D3Sl86q#eiMMibwZw7S|0cJGZz<8fPWq^lo1i&=qd{d>1AiHA-G2k`#Cihx4F~* zzRu@A7PsPgVui?l?7yvmcCgnp9_UG0tRl4)@T7e}LwI6+)(`a&&TF^&5Ry}OLwfd4 zI~;vkS%&nziZ?k0=#vXXk9?*&wbwA>gLZ^AqJdaDOHRY!BaNWkv`eV&HViJ<7w_g*i9=N12V}Ddl=0Z7RVpWxCKVvnbFX4$!nWp4g41u^#Gr6LW46J)Y4*S+6(~fq#uEGq3A+8@bp=XO8zl$;lEh#a z`M2qIxzO;4Bsh(HE4V67&W{pRZW%_0&{WX{FIW68+V5H)7!t8voYAm@qJi)LHQq*w z;~pF}%4@z->|R^R0t4JKu_L5&9vS_`ebHj`13;Ve>? zbTZ~lvLq%2nKW9wA@%c=4_kwkpX`{^9oCuGDw zlW7itdG2B8J4T8j8C>SLn~mVU>YS{A?Yn~R)@%QK7WsKE z(&3l1&}vz>gStY))oh7vNtQhA(#8G3->D;bs8^4g=cq51d5_<^1-`G2hMJs~mXwyI()a@FaUevj?`dq@^v7s`jLX5&J&+t3 zyEB+yt~2?Dg^Ko^|ruS1;&tEF&JmGNx+-%js(5_8ieJ7w8ex3QMJs>OyqJu zhLqpWh%78g10bKm`O_yr{ef2^&?UYj8GV*yXcZ*~^mUVq=2=3NU!u zq_?1~osEx)g+-j)=xqv6da+wSHj4iQn`=GoIDANX=GF+f2w z2wel&806#~&=H?tbzv3`*jtTJ8GUkaIzX3l=oT&}+t#OFZ3ZHZlnJ)>8kHRCR^y$< zj@7B9eBw;Mce3q$CW>}Rl16%v(>W;S!1G}wxPj8w?pu6TrDTBN=0m47<^H2!LbCX3 zbkG7K^)VqBlrJc#iS6(=&s9-54eund(Y+g~vIhD6gSaU@ioIFFnJiXFjoG$|Og_wDqFn|() z19tsw-WbN8A~Aao%l)m}g!J^=bU#r+XzF_rHv`9Ix0h2ENFh|{$}3uV6${zr#l9*2 zc#&8N@eV>>_Qjt8gzO6u)Fzp?ZBL&C6M{?8C#8b#POUK}M8hh6H@(@Agu*#$!HytI z@Wxir`)zbI!wEhUin3?riTn}l$CVjZyPa^1Z6uD1okM9woqUJh7%5jNcvq^dr%YAFFwFsZQH zXos5eTsnx7AXk?SZ7(|$U-ZRx7j%28pIp~~DnMmWPEXsIbbHP}lygUy#56@ycEb;4|Td#|><%4~Fd z?|n4419k81Jn#K&_2-J&FLs@~QR};`B2C9Q{Z-Pc4z=we$Jpd$5|&nBYaLihl@amA z&t=lhE|UMW4Az&_EV*- z(3Isb9yMR*mUH`f7h_-N`i&#@ZX3}2t_|dsLQ6DxcIqRa3A7(j8C&m*ffeiXfKHKJ zx$L_spsPw%Y{ZQ*xIe2pWPy*n;~e&A{$KndAJyqRR&^P~`9>o`jxA+3XEi#w9dURo zsKN2+by{$n_QvD)mJ_goiPAJV?ztjRBX4C?HEa8jHP&<^Y|BzibUSWNMM4y5)up7Q zz!(DE=^!{mMI~N^KA6cLuupJsqODe-&=NpW073?{3P_FsHzz9#Y6e5km0OLfCam*I zJOBpd>FEig0f8wCM5l_9ubsII3yb2o5&V4hA^hQ&QzKZPjc1-zr%bRsJceWOGY)eT z)^)XS`jf)3BOri5Cn5^H&7@ntucL$zEDs=U-l*7#M|xSHMs~mZWfYcF&ogpP!smi|Q@ZV1S2##>J45 zl=O?$Yy*QCyM@`8xMU=MRi^niRzg&q=AC{Yg@-%o=wH5fusY;yzfpme{mHy#Yr`9nln z4$jww(lAauyxqqRu6g!mebR-M>$66w48om=jUqk-*|O!mdGPjM=YduViN~6h5PkJt zQzcrGlGC&2`E(dd7~k9U?M1w+_zy(4Kq>z-p*|t#ppW$`i#q4`;fzU%y||Hidb#^PqZqsI4~_X*=55Lw^M5*@ z<~(^0s>li0xcc&!`II?7`dd&wZ392wee93>QuSfXZj4q z7I~(EC{dCk&qvxMSY(i?$=You)xh;lCta0=n`xBCAgB5C>JDX9=jUn6UFMBt`D)G& zfUbXb?)hXkUO#KwwrK2W_VZDZ$%3@*OO?Cr@K51<{o@H{=#)~=0)1`-+>gKm9X_^j{&3E$u z*Q|QfrG!c-&2m4aaCBFZccFch7k$<}W0{|Gr1S5*A1%!85PTW{9$;qG%kfs24S&e{ z&T;(Qv9_9;IUw8@c}orUC~v(4Ymj4VZvGcYlYmD{T}=&Ka=@Vq`VnVjh0lU4rnm4os*nPGP1)`Yi8s@cD!3?l7HG`e$ zGyikkK3OXcl1~d3D|){~$pt;@&EMym#LsWyOYs*_<`Z}YUqbIR-Cl$|=o4gsHas98 z09Z3hOLtFY{sBJH{nlKW8ylv7$=f;kxH7fv9tm6TW}4)u&&$&`u}6Dy@b4a+Kac*g z4OXDNaBo>#GZD@^+1yM@P1Q0qWKNI)C7A#uidW+%Cl>{_5=kc%?Yx0IB#MF;4Gjg* zD(w0Bvl5Vdd3#d^n|%DZLse8HgpVxv%+B-M#i#^9g@Kuw8KiQ9P+5K!{+_ji=hiXz znY`D?l7K?|Cr`H;x6U_(9Z0*JkW)6}2yhW-A zL~fgUK&U1wi$pXpk`0zLf%Y(P>OVc32=p}21ww%R-R-5@un~-{$MszNPzV6pkv5|d z)fX{|X<>X!6dd~#{N+s@uAna7J3|frfh$)F=k7crz_2hOybKSc#BfPwiX(*+B~?O* zLpq>bqBV*plY?YIS~-Z-LWY&g^!uW>cBfP{=+lysO3Qal?IrJ~2w1 z@U3ZnH7s-~EJMT2C{>!rusW%;CXC>}=`|j(;tWmoL(nsxBktYXUx9jsK>UZtAXOlI zc|DsE!>qsYcr-Ev73Ax3eJyQrdcB>YPfX|cEODZ0rsMYBF7NMSxZp?e9Ki}@eKw1c zJ+7(!#r3YcnvIZ%#9rCG$uBM+^pNTcp`uMSa1&LCG2me)@!ZL&`M((i_9vTulxm2+ z!Vl2WKoTyncG0VI_xSwvrC!-oILaHJ{M!f8%IdDvqEi1;J zt{p8aj!pd5ZNlbFi;f0IGgX(Fvkx_Y{%J{-9Tf*l*}bRfNjZYA%O!>6#NyPTI!YfkYCZaf#Ie0ZAqhWb4i<1 zX^nX$5J;3~9B7TWSZ_DEL;y6T1^bEROA0+* zrWt=O>uAX(iKnmk^xH23N)EDQp^(Pahh>bHvxgIb*o`#bPYwSddSyoJZ{NSq?zy}Q zg5H2Fnm`=#*>~YbL;(Qx`T02@2mv_{ax(xO4lt}FB#zj(xX6EVRWNVZ$nS5hNFAQP zv!*q**& z>&dV#C{YnN+N3+6g_J9f>|MviIkJh6pvC$1eB4_*cfjiR3y^MV@S5Z<#cHzR1@U7$ zNdtcklX8HiEd&NPmA)vW(*zMNaDM(L7y>{+9s!vgcTz2x0=2pLxVU9A`=EFxM(STV zWo~Y6Le`h&XS^*|#DS+0Dl}L{5$ai}24vf?Tl*jSWv05Ilk3WM~WIxiO^3wH1Nq64-DS ziwIFeC)H3|O0_B)_`iMCC}PpJRcNLX*Lj??WBFEE8r&Z8p27qnr|@IrE5G)Gqmfvg zPCtruZapUcI^B|fsJiY*0i^~#=1Sbd)3T{O1zMaYJp%)8OfC4ismV!f44e2cJ*L#l z%Ri#+wW4{0@$tVA+DQY0o~|7LO$uCs4Q^%}8Tm$)t!HR5`s)52_MBxpA zAFb~PRb)7QoO}d1LpZVST{?13r{8n;2u=Kil?mB&64}*l9_<|KX~z=JLww%&$d;Se z^${Y8g#n+l>MQDfRy=kY*H%+xN8go`?|jkfypqg1pFppNEP`PC0hd8abxTDMyEkh> zLf=FG-Gm}g@W=Z(1exEBcpazn;X12zC2rYk;8v?Hkq@UeQmGCbkbW6hn$B-*95q3p zr-*9d$n0wg0^GIcaV5*;+&2q}x*(O53wa27F3HZgN%mNX>ZRxUGpGZ;wNl*V%!|9s+dmzb+6XHuy12N|_^!8n`OD;J%a>dyL5WU6?M- zdoSxdgGn`Po4Ug-Z?=UJ6SSFjFLmG*I?O4wSbV&H{G1v4JeZnWn``vM!RI0`lo^tH zT>clU$bA}DxD?}P3hwGdpyy1NucAto+_X`bE#tK#cnn_HzWvLE@05A|3vHndJX|vl z_cgw9M`&fp)X`39WVC3wO4U-*D5j*A4g6;Ri<^FNq39uL0Uv2o_FOpVuB*OS__Xly zwAby2;g5r@WdNfx1^fqV@A&WjW8a2YgFGDh}_P z&fVCRe)R}nD2uuhQuhTiU*d;g>;7Y5Sy+J3fcOfar2qaeXpkm!uY-g}at=fRkiRAh%I3uD`F#tv<4Ku!u)D)3Q6M1+-mXWe63BN|f>6ggp9lRjdp zlL7eL)HH3d#(_~JPzr*aa9_U`SD{ZE;wCzh0Lk3s+DTdVBf}Hh=3C|g*2mW1zXIsP z1Ox=Y&c@BneeJ|7DCk{<_{r_JbcafjiMj1Lo$4YLk$Fy8?kB2FeZG-{-JmKvL# zOx^w|N78wIG}-!u+}*UAxRB_W$A^ zV2VJC+Z#`B*$})nu|%?Sk_{^J}_Da%7}wf3h86@@oLF z)yb*oxo9Ds@76>X0*(IpF39Ws7EiBG*chPNyTNswuEylAUO7xZSlK?wvpORnQlgtX z_nm213%|a?d4EfHrYj{Xi8;rNYVs_gWqqZx^LpcXQ68W5a~W~d^wrUR=lKP=60y{8 z!{2&~5)0;|g$mZ|v)D17JNCx*8LWbb{5xUH&{?ayX^UFM#8N!j`axVzNsez^34w3^ zMw*v%XK3ZhFv@>Pp;eLFd~1O;JqXcrMK0nGIg29mK1jNB)88@r-*Qs*H$YB07D6*= z?4F8M)H1*9T-;0{a(g=k*Jbq*s&S!6+}iT6j%+Ead`raK+|;@wSErdOOVm%%vP6By$E9l}YR{8n45D8DKHqB(waOmr zZ#=Jiu;NH59GGGqs?_dj*O-$A#E>-AJWfU%}%FcL+ zV5unAior=0?xPRjwR16MZtj_a-|u~W+W`K=@OF@`xMc2&WpXi|3<@;@cZPxk8v%Hc zGkNA~Rk(dc>~0GCoI#EWyMJ{LcE-p^Fit)t4Sbm+9=3G$@X)m=?zLgAC@(LCORs6E zM9tDv{m`JL3FNS8+8Ww(8k#f7DJl9)P!^dAv_)8?qCU|`*l3;#j)<~_K#^9aVd-4f ztENSnLKOWK1>fJSS*fI=BeT~Oq%oZ`N6DY76ANw38Yw1A%TNPPa|DZ6WnK{Xcez8( zBO*W@|L()@T3S}CELgb9Sa_G=ao)1lCOXlMGdhNe%`S2aFfwbesK|&7`T4_kD)&{( z?0esBd8%V$_3RC)v!LqNBqZ4x87jKWrR@q+S@Sg?1J~BbZ{rY3`M&BffuHSllw{FF zPfyS3oi}M*T6{dg>sQFRq_^_GidbOW>Mi^N)MPHm0xO+goKtaj29?|q-B?pZOQs|X z$r-LDn4&*FlR~IKZX8i-t}T}*H}^06*VuaxGiai2M~i1yS25Aif7)4&zVjZ7fG7rV zTLYb5h5{BA`**t9KO(E4cz@C?l+4{`%jl2fx7@44%hgfkBu+6weUAqH79HJevqa z{K#J!q;&SCp6rt4l)-n*of^4{Kb>j4Y*(TxT0LTeoj$iX5MkMS3?BR;fj$$&6oi)o z114L_N@pOFnyR;@kVeGDx1FOExpXbuwFxhW^c`%re1uCJ-$nAbKO;X#vM14~XyE#* z?lNHz(&Gj%Y7}ObINE2oJxvf2Gc5CYcwJo1IEcCV+T~HdS4rh7P|BDz$B-wwueEyR zY!!B~V{-ra)8#$3vp$TTsscTKm%a-Ypiz+qfnM&7j1H|jTtfTm4hblKUTyP885?rt5{=~psqMVuV&Fm!FB)x^sX?E0Z)gky!4u#q-JKWA8%4zx@O z<{Bk*FhyA4P#ss+&819 zxrwrienp#E=nK2Foi-9JXe|_DjIZ?>HZ?1Q9KKaDTx@KZ#RIG4t{%@H0z^&Tvb8u6 zZ*fHU?rt3%5W8P7l9P`sXH#!D;3COAJyF8K!UCa2q2F#we7sYPiNiAzuwWx$RG}-f zzX3sxqw0@_Ug5p66#hCYI_buGnZ~LK#%h7@qS${}?>oo*BIp!5tOH26-ir&6cNJd| z{Hnf?M|L^5S}0!7i$CXhDgNR99wS_>8YC_OUIVOWS{0fVbzJ}QdF>s(qqm~HO0rb1 z;@!QvKeSWS()ux>6Q5`N)4@>l{rd#9GPN=el&B;d;zHugqH-Q7OL_p{0icW;5TL+$ z$&wZp92^=P+}GO+BBnw@L*YY05ubWVDWOn>Ai3gX7_6d*Ri2>N@6#^>;1I{cdYcej zr(-7zG5_$POsfJ76%_=}sWPMhVFqY%q8Azf@i$Y_yM(`Qa6vj`A&9d5^2PkH1T`ZQ zgb@op-ike;)cf@n3;X#Uz6d9b)4xXWjNJSk@X>o+O6#|X6Cvw{yI`&k6L?Q5-3}@{ z4@yJv!tH;)hi*n%KW|?Up7@!lKttsY;`D%CW)nx322Xi*S}3>d2Nq()1y?8V3xMXC zmKH&<2=no!OBJco;~E=_C@WVj(Kw;L;^gPIT%lJH<(cUGy3URegO>4LFWrLdH43@v z>x2Fv`Jn|67!0smF|hz`4cyWseN9PJB#Q2^%(){i^gHio)&NLQP|(oeAb6t!)HY3` zQ=l33`h?Wud7!@TWZdqBmsnw1I2|jdk`Z}lFwMp=2|Ti-*gMrPXpkP928t~R8}57c zBx6$Dx%cl>p@a%faw9bgG2J-U2x-5RLX}VswJh*Ca{SKfq!-PubFS3IQI!<-2^PjW z>!z_jS3mE8UuewxZV!RX`+mmlf^1vcsLxgFI*$+VWB`Ry zz2(4OSboH@7_oJ@2fB?^zAs^Na-6rP`MF!t|Ls4qT}LeOE?vh26GeKz}<& zG8U!K*`>D4ZO*aaUF~`G5%3n3a(KT!nz^W|8klal+L9Xanpzm`MuHgG+k!M1>hsqg z2v))FGe{mpvGZi%nop09@u66O7Akvq0~!h6+1W60HNdQpm5J}`=>bLofRRC@`+>yv z?g62rvAwD)uZp!+G3ZBQ^hxVh$rS{VD zRWE2u=E+lI!=(dJyw0IS(Zn2L2BUh&TWe#IT-(uWt&IjXRY$2G9^iJh7V8#^$*w4@}hs)~$fjF|^C z^_iPbH!PgNDF+&Me#*Mqbm%5~ASuZpT-s$KI+N~1=)I(sD1 zw@|vSMZm_)8%F@5UXW!}kg=^;4aq<>4NSkSQXa=={Y5s5-K+9;qdk?Ajaj2`ZZwEO zRsK~Z$F3qC-tcEHYII2sHS^-ezP(h&bW@XzvnRtT#ngi{ZL46QA_X4=H*odGrxmS_kKF@Gtmdh03TA72_GoW zOxWE5Q`~$t)KF72jSskp@&P}l4ZNnS-4q(FNFY1`=S8RXHqm<}(go2j8jZxVa-FE5 zd+hlP@EKP{P0Ki;djlI$0es z465U=_EqOCD^ob;gph&vku__mm>##jPfE^{Kd09eC@eWS$QiQs3qIn{c)1SIY7etC(FyeuRr2oxVrk1(H{1607m_Im^kVpg*js45v~J3*Yt z3xxLN8s%V32=FgfSEqk&>nCd~g|pRC zrsTpDkW*8elVTT-4@~O_Sl&_6^_Fk>>0Uz~)Z_zSHEKhO)!e;JZ&nig24^lkrvNiDW5NDAp4@ss0w&4 zL71R9_MGbntn~@n!irrf3E#oHRU~X7p9m)ya@DS~sNjqtNcuO3n69jh!8;6c$~wV8 zV-BE&A<2O!lqTQ)efSmhhO5qFrAj-J#@^@O7o_HT4nyMnY3T|0ZRO0x&n3p+e@0)^ zt1HLtP!E~bgNpll>fF*8w3?pGdArm`OL6}w=CMzmI!m=}bTD5pEIUH$$gw5Qn%j!nwlEhL zY#u|zW#+N?(QNdmn85pC(xD(niR)5fTSyvr;TX}VCWcK)(7Qp3)6v7Re~(>Fkt?H) zVfYpy78=j+u2he$njkTy;eN7nGkdG-W|B#GmXdR<~E3M z+ln~P7BrIAb90tUyjjk|;mwaC8&S?=lG__|I8-7#&{n#vpuL|-l3?@q)esO$MFDPc z#wL6jNI}F3s)S-VPJuG@1%&5rKrkOW#L+s87p5?hpIoTS0!!_0E!iBb)l;d%9Af=a z985635VS4>lYEmcmz&Kn+w;bcLTv%Au*Eu~y4I;v`8mTUz5=!w{Zn2clx`*uzrL? z8Y3fHTEz$zGZX+}_jUH?%rvvc&OGAsPIK=>orz3x_c|r@J|;bRi}ryE$&NS`%lA)u zciNc}e_h?_iH?ttv4E`9gbiY9{N)Wg8rs$6rAC=XLqh{RJbWovMTSS_Gcjm#%c{tt z`z0CnL4Z%QUklgwZ}Oev(r;zbq~s*7X0qe^q3#CI+;tnj7LUowdU8Mx{FUN#>hsk7 ztqKw9=_V6@HiOZ;+)8YB|;cdB5fi-ijJ8Ks7U}R*Se$5 zjQ0OgseN89rNquM*RCJ_YSBql%)Fogbc*dHz@Jpsvt}|Giqii4DsQ#1mFMfR1Hdt#Ea zBQ)+Z*9C=PQ1sZH{sr!aqgxTxEi?V?VJP`q6qZ+b4DjPP=wh&n*|>WWVC440^`VIaiH>DFTei2 zDEnk&_1hn>P$wppjZJf#MBjbP6?|@2l{LIO@BB2QlVW4n>ggTiY1e8~FUQ`(^R0@y zxLI^oKmAWi+G0xHWCor6NX%*iPCKXe;#c`YwjPI}SQ{-#E=HWiPsR4Xkn9)Jk90o@ zaGwcqgU^F`>`lX1Y9#3F$6_2u$`;68o+=OAtPGxg2KVw-7oHA+yTNXpfr+RuCRYFqA*GQPLw`U;ZptXp&-S#iZJC^!Y7{N-|i7V{>PB& zm-=a|tp)=6I-QIS%#p$AyTTlzNd@!|QW$n4-tV){O>Acwk1{2`Wd;doupa+*FVp;3 zD)H3Cb62OIc*84~S01%$h$EziwU~Kem^P}L*Fzski3{0?Djcx*c)3B~38n={f*}|W z(N>zY)nYAbf)yOONXXH&Y~LCnFY?ctCO!)P-?Zp(G)1VCx#T_LexiN7x8t_--Dt>f z{UzF-BSX^N3BmV0+QiI_RrYmSRwO2=(n1qnl}bEewDB>^{BZ2x%rvdG5kr{W``Nzl zE2Uz^|A(os0E(lFy2RZz0fG(=A$V{b+$|6+1b26L7+iw|8(b3Ho#0MzcMtBq{q62w zyVNVXn5rIQrtiDw9#KosxOGclaPfHp2#r9n*ep+t9CHp1MBm z1FYeLD^tEhY4I3A^!{y0Ar7;V%`T+xEmL|!!Q6zHGII6y7GG8LTN$XAa2d^A`Bw!~ z7{dQN;QmME0veW8euCtx z<%M;1@d$7gK%)UzE_iq}H8$R{-ge&Dk;D|`=8AqyJ-+b*IwJt^cbB0QZ0mFNBo7sD zzwxxIrq5E^zwl^WcxYKYMFDwT!o9XSf21GZR@O%lS3Srm9vxR5Rlw})%~$a3lE@Pv z7oFftEoJzQN`xn=k?i=0hpU(I$E9fS2o^ivYWjDu({?Ct?91 z0<&19(1D>;4vUOo_sIrr1LN@_2O+nLkb2#xh3-1D-tT!?6qNd(^JK@Y%pwBHGjd3_ zy?$VVTzfxLA`u;$jnN%N-%}Qy_Abzd(W$}@@!=}QE1<$u3)yba|~<(IFpTumsfv^tkkd`t9Qs}wy;^l!G@9-LVjm3igv zX6gU^ipeR9J!QjO%0AXC-uObxE@#Zx$6j}d5MQi8CIL?+UmXoVC+}4tI{5qk_?@%5 z#Fqa*c3imt%Z&F@d7t5*65b{e&ycP#uxx_+S~cdHk^z2X=cqe|i}-d5O7Es5B8Wde zMrCIg8JF|XwWe{Dy`>#tzsHa= zG^9)#a={?LTU)lN<*@yeEz*3|Z&VKc{ostDMUWE-pj$%(+$0S^L%7yc(B z$;*SqRSOYjZ7v3qi!A=Lw`5UJ4Q$Mk4XzI|2LSAcVX9K?5pDqhwPLDrr)O4 zUh!lA&9g(ZUH~{gwfnCWt z#U>8M+piukGX0sJKc-id-2o0AC3yERH9S_R)D6e7z)ab&CjgzK#~|hy50w9*CS8!x zYm)u$x;HGBGtGAm?+cXYmJi#)XcA|34q+CFWv6g~!N%_&M#H=4be**inF!Xok5xYk z@IEP`Z$G!mTjUPiVrfFLGc}QnjJZwP7YWT=*4J04O#ouO~oANGo7)DQDucu)ZTtUp$7#Q+owob-0m zJaD;xd2B~{Ts5LN$|MO}g>;vSVpg*Wn`t?rUvbxxacdPnG)myNYZA^;##yL=xfr23 z8n|OHX;NI~QjI0Xjpp;hnJ{Q625_O$*l$s{eT^RRom{PEMoDiwbZ-#M?hjwt+n4TP zeZ}KijAqhm%R#Qn={7Rc!UZSqXB054-D7r6$)~%2(gv4884^8pR8$S)*EP?te?OZS zUEZBBiFRFEhDaA*2AYy%Es9w76g`Pn_;h!a`b?8D%8q?i@b1U-?!Ru8u1lg>8v1^+ zqcYyBGLFEHPy#dw3UR>9nT9Xv4)&Gy+a-^}QVIpU5GjtZ^@D0LugTJYkFMiCnjP4q&6#$uMQc&rN4g21y!YElT z!CMRMKkNZDK5TD8tSnlODL)zLlE?_QY#6jVzE48|0FlgA4p9FBX+oySDmFHPJVXDx zkQ*9KDjtwRq-&V<%yer9`IZuFKAy4D#xU^|o< z@3Kzf6tE(GmCf-x^E-FY7#rzpY0t!bI=;G{wRYDmmzp2;x|~Li{EHmPffO~3Oo?~G zDs#vIaz8Q^>Yq6kw9Ndn^dl2t^z1R&&RD#hh-zx#VVT-CrXXx#~DbzmwFQ zzL@AdyLlXVHeb70dGkMA&oERLZVmnUPB$!1bo)lB5j&la{@St!mR z8_ghTaF_%JktKldfWP$Cq`nHjRl`tzycdfvdB{j6O^V7pA(l^Qwm0hizQ9WIR8c@n zOubbQ1w~HMf10v}z2hQ13jF1#&^V&uO29FVdjb+KoKzQ?sw6*AkGWZd9*%QjquN8yH;re>%qx-PhNnK?L-4+KhlS7uM7l=tufm2Mh#DF(`vs&g2DS?_zfL z%-S^M^48+7U-Z!F9A(}5Mr=rlTZX<;SEos}wsYCKySv-lpUunwbW@-Pq(3nVD+lk{VJWke?(VPwj~^3~lu@(zcXcVWJR>4qzeXF{r-VSKTxo3b$QHN+XXPat=Bmr1j*&$ z0J(g-EA`g)cjnnj#nMtzUe7DE?m|LBfFbX-m#=~XMi>~7q8>ZZyjJTxXB_0bVB_;- zo@{SBub#B@CAnkZ37z>I!M)B%w$b8+swr+{G|H%n+u))|nu{I?;(2GpGpK!|R+XNX0GnMuVoOJLfX4J0vo7P&XwNDJ1xnDsYG!j zZTytOx{%Cw;*#->u1Ma!>l>f$6c&4$HohbJ@loVFawJge zC+ph5Bx1I^5yc58neHcw63*mHvd?I zCgm{Lv=jzHWR5|=945E(5-OYZI74nM=Wd`D{;^&_dCpehXp+9+7zXcTve1PTf7!Xv zb_v14FI;>|&$67ytDMQr`^&#u8$d`E#${H{5B*AIsSvmLgAnKu+Ej7Xa){;v;!8N% z7}bHxfnF-n5~XzHR8`n@JpbhPZ5OakE0>eJ+0KvA@!;1yOv_Eh%j>b4%X-FTbi8me z)v28!Xn{WMVenFacJzhtZf~xa6@xdgOwPnA=Z{u*4PINc)NqKb86v}^H`EDwfZsQ4 zT;$ zeT4BqTMJ&?emRx+Z*6zBP!J3ZF@t0pKYKeq+f5@QfAgtw%2#^ zmF;BI$1)u5KsGOpAn)&4tp7dfGvR#8j({n$a6?Chz&XC#2L8XBL;9SadGj3K$G%kQ z&d0|EkxstbN`H#C+g9WC96>jyy@Pc0oSe+3`<0aeb2eW$tJ^_{`ap+}UEHj_A| zI|cqbJ0022^68ZWI{d|;}5&QGX@@E;{REmK)b1;T#q#a-9DcW>(F9In zVG)tLi+_C+N;yJKz{_u3*R`9O+CKOE?@`|gpQ&Cgbp%*TEMv{P{hJw`;@rpjQ@XLF z^Z{Nyu>Ql_aN9nS?j7GkOTKjM2a(JF-qgB#B9?~Jq}o*BOg`^-HmgI%>rng6oO4;l z^&Z@N)_{R$j5c9JiX49=_rF`^4|qN!Z_o74s1M}NAzikBY-2^bmRLlB;^Sw3_sa=&47S+w|L>`W1MUueX%-q@@A2oH)e9T7V<@moG%`-}A+JhXI3~ zF!|(Rg?c7ND&bGm&t*E$evG@+WwJ)QqGAwocxWgvKuQF*4y@S}WO`l}CbQ@7eiy(J z6G@n(>kAnX6<7QzB-)m7LDuQ%>C*ok=S3!KAu=J*x#awiG}~m#w!n5~gm0)cYqau-4gU?UWg~ynqu)lP3dJR4~Le3W1!DvKLjP->g^-Fx+-z$+; zx@>5(n-tO1I@e3ONS8V}CFxV~^ztutYU1$CC7_<7_VlMxgV4DinYKSLu6hoAc$_(H zt6O{C`Q28aB;-Sy*m@Zd+#!*=kexZ1ku;eRyu`jd1MKZkApK{9kmWqc>JP$MXfjuk zG?#h*=_I(JB-qL{@8+_qKRUw9bce`PMqkGPSnVvp+}Be(Sg=5eNShx0w<3CJk~9}H zj!2Bf7ciG8xZb4qWN`F%DzUxNF|$GjgF-sf4@IIqm*TiPCc4LzBzUWx+;z^f%rLQY zZz@7WS4qWKk4YE~UK$- z-Q7Es|45LQlHpw2G=p-L>F@pm7>+WANgSqS|94WTvbMg_72SP))qU0VPTzgq`L6wL)%y+pPUL(89{c4YFPy^DqdSM( z*Jsl>FfV!mtdx80tyH}&Ohut1MEvV@ zvLP~gA2M{<7NO1it;vc>a#o_@E`q$?|qKFAnV zlecaflp}`_0jjzrxP_#a5x7WiDgBUfzOJ=jT(s~m52yl5o>}HI3pq&d_pyE91$^IwgYCIQLd8*0P(-y@6BrW2dTY-SK2FgN&W?|qqCWH# zLgdL-=Hg4Vs3hrvOBB7Eyz%Y+!Ps4L>m6HkwUptNY8;)Ok^{vH_)%4LwC$c8Jg-tH z9W1$C*7(E5oZmkX)$@n;ZwZWK8v_S53$Nm{RO_}0vSuj?3Oc4NKz^)XIkCfjIiE~A zJJr89L~d#@cYyH4N$;)U>jzKAZ1D(%=1)clE?zdh^*y+5m-Lhe6-03L9OcsgD{^H1 zrrS}GxhvOu_ZNx{3F3JG1j&;*w&@TQ6a?tP+uJ3Dg*(o7 ziSh6Nb`#nJGB6HBL_&N7J)rP7d2q9wA=p%5_(H&Dra*8~DhGp2BAe%}Ujz-Zb)*Wnf$kv8nJerh+_b$Yb&3q)+ZTXg}o2s{?wEb7e`u%qm z)gH^=R(U=MzXVNdt>-gAwOLgG+E6R*<;?W>xa#Yfe8P7MhhgFm7DHKU6(sufXKX|7 zShQj_n8Jol+Pglpow0#$A9g+lSMXBAt62O@y(2EV-6?k26=Qz6iMJ>gZdS*>+|_js z2&m)cEtO!i9RaY)4{H_iTm|9Wg8*)k-)JhE!4Z6H@;&A-kD;BdT%E7IKSoQ4Oh+2IuG3Q1d?J1uS*Zl53|vp6gi+)1mr2}+ zy65FSOs%Za_Mpdrs7wn+@8=vRiiQS7^N zDVS4@m|JFPuLNHM?xkX~L-m;3QYmjvX>X3O*4<#C$UK8Shf1RYUgH93_L(f<$yC0T z@^_~rNAJh2$$`be<@+)b&R?s5f{k1blE3>4y5jh66axI|0Y&XCkkSXO5K=-HM%-%kAMcmI93> zXbz)0E&(W#elEWQz=eFRO-q>;G~tHX!_na5hh?O%hGp2~Pa7DgH~CHN_KPlOc{BBn za^;FH+$@Q#mxU5bC`ICW6XSjiBl8`)Zeap;W|T9b*61-=^XbZKfPtEL9O=<=ZZJIBeIB>;a0Bt)93aw2y)Rd zVLz>NFfGh{%LNLkCO@e*D?f=94E>D)k&@@*ApGWyXtn+A-mn`u(f@%Y;P6x^`O!`3 zYrUv#z_)K8-G37sXc6!5^sAi?fl|SycYO~WSifC>KqKWt1kyi9VY;a{EA9#G!lVo< zaAs__PswQc@Fij2<5~wuT(WVzBbRP7`kR_gk^#SPBAPWcJ zW)szyW_3n%1{iAh8s+GMp88_7u3~oC5@0YThHxZ6(^rs_YZ*GJ@}MP&p(A=a ze|Y958$k4IGL?-&Wr4xbUp-fjU2DCz{K@%N7ViSYz~$m=LgHLBHe13S*q-6%g^ASa zJGcN%*7P(d4-epe)&S(0@bI{0%W*L-bxO*6mh~UTG}=D3mata`PHlE)co;Yn@d@da z$lmxDkL<>*_S(3{18H%Qk!2MOw)SyrZ!^QIH02_%F!MYyNxPeWF+ZEajxPi*Uy#I# z)1#@q5(q_HacnXCEZ2aVFfDTTAicdGKV_aL^d-CG-jrV$_we%ikqXGS2uzu11<489 zL5U7PmNRGPf=vUEZx488CJatYe4|EZphSum^C2J}-R0(gK{iiMF80?1|K;@B7%x`07rZ$F#P*`o?Ke!MliLnf_RLCW(21unxmUgbe40BpX`Q2a4*YytPD zn5$$S_6LN4OzUVkG)utmo8$naY9iCLK(r5)if%ZnGcv@0l@f7FMZDu&56+Em(TR*6xqWg)15os&eAA-GiGE&0^Pav~EAfuS`@ zh(MyYi5%C%wHeP)IRw}*n9>FwHshXurbgdk^nr^GFp3BzF)`!}Mi|)1BUuT#_ZX%2 zUH^pSpcFtYtA|R7F0QqeuPJjU7WtOE*JUnqEV+bNweR(6-6o1gHzVshwyp#J{?wms zIaJIjy%|optm}Xa0jqmQU%rZKNOJw+{kEo+_SaS+%<*a{3+b!7pIj;|qXdA3se4~0 z@nbTs_7^Bg7=;U0|Dm*<2PQ?34`IDn5sGIq@78Ev|%ZwVw>?z(Wz@MIRL0UH-=h}E<&6dV zXDTto1z48MEq@2R2)BL9AbCH9UcRd5)-gop0f1Q9axll%0Oqs`b&EZ<{kjP`iaH4| z49H3;ex0)jdFgM$$|_FqsniPoEYgSBK#5+7aOZ%N)t%V+Q<8Dm>dSl;+Q^cFcr&ux ziHa#dZZPy~zVGm6_9#`a(31vEKv|eKL2!Hep8$I^tnNF9N~b1X=O%jNDqsm1S4qsR zrwC61D~lb48J^!1EX4T-lJP>$!u`zJh>5W&yi0$iiHVCVQ zkEc&Bqkff;@%K+=WI-%Dgv|6e&H-|!hwjr?V>Uh--z@;S=e%KxPn~OYmg9i|WiW)7 z$qusT%{X$4huCo9Da!1cSs_Y&Cfu-N<7-FIOsf2VT|BOkGkSMj&$fQ2#b6mNl8JtyZPBZR6iXL>Ylq4}=6ZArM@bnCb6alVC%A z8gZywrBB$?0o>_iv3pGWL7Op3msl@5(C`>mtZDFmOptSSa?v^2vQjSObG`@LM}W5z zyEPuH5lI`)Tin&}I!v$nRRi+Ay$(p=htJi;{+;K&z%Ug}Cw+gmM=|Pf2d!E`0p%Lj zOK_zRA;IZ(QWl|FrJ~Hup*LW|e0upC9_QnOdpDQb`L9t= zzT!Mbgun?#x)cpqI?37^)rvcP=otX`@;?v%vmq60_#7&>>C{Y}Z~%~-QoZH>n}0Ml z!}?lGHz4-y%KQ50_w@99CUY174$;vV>Z9W~*^79PNU%{XvUz>$>Qq`uYGV zLQii+5C}wg-|}bBvv~aCSEJ3Hl1d_euo1Pm_3R39x!w-DK}~P2P0{#z`{bs!UD9iSGPnL4?Z7#fOs7FWJVkm zfaiF_^Hk;x7M>b!S}A&EZ_7akLr=4_4Yc1+m$$6#iCI`!0FHuIR%N@NYr>H~jS~~Z z8)CHY7G~Bp>)9C@QODgmOLa|K)TO1R0hz22FdhYkJr@b!L^VY+Xu|L3%I~*{1eK=@ zy>$NZ_##9()!dw(w6CwM5BmA}%wFf(7HXd&=qJ zBi}LfB%ANU(1HV8-D26{wdrw^s6pX-T;X(7YiM>c;7Z_5i$!Ql1Lk{Sf3 z2%ngf&8f*Cr7Y|kkxihm&k10H1Zgk^u3=v;eMTVq6ekidYaacVAp-a!3nzX(q`#3m zSiSKKbE34uto7yZ%KJF77S5S@QqTizXOQJ(#SicWhC=w&uOXW7Y4oO&B0T@FJ25Bx ziM037v2CW#%GG0j$saQ(-Vv5cGZ6-xGOj*c214rs;Y@xiAMy-8Mg0}+!BYtv_Co*r zD7vTSluA`Ez}7q+zhtX$$^mMCKl8D2?`Z4%?3)YvRmtF6#bsQju=Xu+PV492tel1K zGAE1?>!mRk;}~l!QOmy}R;uCLW+7aI5}7-BF^36b!-IRH5qqQYUVJKHK^*y!@sBQV zV~l~WrQMj90g6BYI`rcn+Oo0~wM84Qj9V;=TrC1BP`vHLJ2n}TDN=!HDZodHeX2O) zU$~{bM8;~G9)XplDy9mKl!)buh@A(T=f0wosz(IIO}rl*lhs_L5+*zhKR3crpc1Af zohqPECU^OaEbx?jcI#R5UG~#y=h-XrssA}PHn8V5 zFbV)~t1CG5mC+f@e>^&!KQVYAtKtg*v+t#7eT*-CkWoBjghH#Q)Rc<8#D7C=TDuk7 zyUuK=r09FuCOb`0KFjc$&2vutvOGM-jBg@3;0tsD>I%lrsA&mgC3MYTuvR{m{#Ye~ zi|alLJk^xDa!{#T``#qGtnNGtPM#Wlybh(R38=C5Tl28l1BtXQ+*Dw{!)9wz?<_Rmiv-%7`)iE%9q6?AO_$@IC9g0w)TEdZ&Cde^Ce+6rFL*aHz9iBGjE67%o+Xr{?+9vnMg8>+^bhcu@So0I?&RUz6cKNpq7UfM)sK;=g(V z0SXdb28Pf*j@4DbI5G9qhd-m$sR77u+vs$^>?RBXz)@ugR`3kp0{%VQ2~wwT?d;f? z^EA+aT09;i3*By+v-JO!h}xhZ{G!EMZAw|L&urL_nXQ!YdfEy{cWXBTR9V$hY|6NXGJ=o@H3GeBL?Zq`ux!-9sHhgP4J1s1Xy0A0c zMIhQ7%6t0J5$(JqFt&_Lm!(nm)#ILarQCkg?bNfWiKzzK)iTL}eA+F6mV7{GNF5%KB% z9!RZSrcUwc5M_D&jxLxkS=BH?+0)abrEuQ`we7cv{6Jm-cP32`DQ8H%&MHZZ?@&}rh5ONDidJIZO z;BW(z7JKBDuLC6#beSh4FGCartS#QfB7{IceYE`KZ6w3V7mxUkfq}5>JuU-Xv2h}>$b@mLo9_uu33+%Gv;C%THMJQpSMi&OMYKOX201(PmVirH z2@04VHmmJmsW5W!2-PKezRE0pZBkNcPg&*{&jHREGtM2}DbLxa!}?`OTBv2eeJGE3 zxER!A0<$eBsSyFr%KCZoQ~#ezx19aAuGL&CwTJ^NU;{ou>Q-X7+Z}h7^SP$kZ;Nu2QUjl*djriPB~KwD)KX=pHD?$Iz|{1%I(<;yd!GA zVm&>vcX)bjskvixGA`ByP^Cg*y22~y)+*S~B|9E$-qN&na`I2>SIt*5^Uh(yvw+AX zucyBfRCt;eh=sF3Ej)Jfc1P;|Umx}yK_@;Q0NmFAJNIbTWvia@T!Ikm|4Cv)?0a+G zR)O1Zk0iMndVm=RPf$UUUsb20vOa$Jv*3hN*>$5`Qet9L_fh+p`WlRRRV|kRu-2g}}6Ft|>kRf2HgvC-5ztT7;EcbTZ+_BORz_Bv)@5qP4h(4+~ z_Ou}5D5!t`swQntEFj>ma_oGOC>h7*V>5&w_2swDX;puJA7KeNFn2bU9M7&yM5WDO zatf_I0*qiu;ik1E$oCH*}jd|HwO!p1hzBoxc1dZ|ck zJQk)&mvvKs$5RcrA?5fmv+m;Tj34Ez&2sDdw0;1}9J{@_0qmjK7#X`G{lQv! zA9!taG&)Wpxj5!X@GC%QQrZOatiC1_VPs`>GP};WAp|TW)DBQUPdsDg*ZW!ReUiIE zfi}ql`tn*>xj}}2^#fk)MuF)odFR&K?MDByV>j;Tb@a^NtsbIatzxfGmf`ZEqN17_ z4k{|x;5-0!3=1bHa>SnF@0{w~OGhQv3>!@A&(eu{GmKI<<)>$2>M6lKwQ=+Rl|H4l zGo#%MFa(K+&0V7rgsuW5jE8(Hj~$TjwzGX<=WmegR+*bHjX&3u6DPM6?XdpzS;lh= zp!Y(<##YXo%-WW|*JDA7Ng{b`Qfl3qaqPV@>x)DoqQ@GLk2& zwIfin1mzJODIpLgRN$3UL_(z4i6B#IF8!c|x&>SL4#+LVF$B%UXa+BnOfe{ZvD%wT z)UpK;ZmepCaVw3BbD__I4hZFy`mSY(V+S?OSLPy{Q3@4+d{-F>l%b9!8hy?2mr4=( zmh`4zym>X|sXSjkP);C``@^DN<*UxOJfjif$i^(yB#%jEZJWon_NakG}%+pDRUl~^{V`E|Ih4+BxUEiZaZ zHalx`^8%SqphV||JE;bUb(5-2wfU;Bqm@Nalk?l9^+#WoeE$)3DlSN1DT&J@=>d=j z;CB0ht@1J)&(pbi;xR?OC;N1I)qUfJTe&c^_HjpY7=wRT_6|_7!YDml2WDUAVJ(X4 zI(?J2^7nT7R%`>qtMgpTAS=|c;1IG-N;-~afKc8)M-bX;7>JfB_I)%B900~N4I1|HlV^*L zc{~X0%t4fKxjS|{!LM8TqVgS|Qk72`4>K~!2@%W>F9Gd>V1K6j&?QzaB1HWo>u2}G zFnrB)7?#pLf$bw}W~UEk{DC}$Fwo}gq+!D8LntM?2b6GgdCt*9<2zVzO4NDl)dp2AQf za=!DI7M)ng4gx-FeG_KU9U`c7k$zPkC#k%4e%Uq6+V3<$K7|3v(Y7FL5!<=wr+e$) zIwEHksG*jYQff2uJ!m-`TySpcchxK76 z*E`EiyShX;9x#wZMw2I#r`g9@1SH2bxDpMgw%*%9JH2{G*tii@=0v6uw1)Q~t(O$M z1a-j$mP6+Yfn4-_-a;(RkOmTu#QLMT!rQ}MyHq+$zH!f zCnx0#%iWn;&C={R4W|4Y>505k)30AM`@#+ky54skPAh9KO{>#Q2_oAKezD89WOl1k zdMbaZHHkm!y@7%y*-7`i{Tbo3awI-az<*vRz&^!(-w&8#jf{-MAWj`y|FB)C8)WP1 zo1UJYnDAdyf7_rcgYjmTA&7AB)wi`K{=L?g_I?B>%Gb_uMscod*9nOJ0kjhJcJAUD z1Txx*azk~xgoc35*dXeQz0;j;GYAI-&}17_0>NbSfNohv+Y7qlYWgv~w>f3eu6p7O z_CLF>|G=y*!Oa~+bwbrz&!4dE`y~vZ4^*lVSd0j*=mLh5W#!wbQ+j^GkyA8SF^nbctFt^0JaT8eC;4@`jRVt1Az}vO5g%3xre27xaS3a2%x?ot^cf zuuzPQ&Iz`owakK(j5*YzEuo8_njjyb0p8JpM&zCfAFX8N*-4@>2e`5$cBqFTc9F1O zMudOVeoxA^+}~ySil;fbd9%&VYM-ppR@J<*NcZQ}Yivepc7eaoK@zyy8usZ*KD%vpk$ix`H%V~uY(6y;N;#2O1`QZ-gHH*his*u=tln#{KI0Ef8nr1|34 zQd1V6s%|Z`!K^Q6<$){&{0H_?L&{E7(tZTZdK^fzdaRq2lC;RD_K9LDpb{!zrvZA6 zTqPn6Hf&3cdwV%Tdj$gf_a{Sg)KR61YCJdgdaez_pvqEc z$w7%7Z*ESr3K!bRl>{GMA47a>4=+MKke>s4U?DOpcccY-CTI~{Lc5WLyrrVeL_j$e z-E9Y06VPuK{;q??M^!w8_uwk5=GBtXZO4zz; z^NgCaN@g59q3facKNFjcx7Bkz=XIf4ML{w%DKbD-R!x01cj2FW8TSqWzE3kD;QG)m zNT)5#4tM+I`%{YjZfBvF@tRmvof9RyA*nzP;t;HE8F#}Ydi5+ly#zVn1YoL?9S^$A zm+o&ZG=T%@=wK2p3MsBV{TN&C7+YQ@CmF)<`;L=nItSZBuG5p|#_15zg*C`VG)OqGO(b?Kd5TQXc`3`aDuxsXw zba3Mw_IIfIqS4@Lw(|dQ0o?qmMfCA784qK=i@xJSrMtoZ%g!`mAj9xcX=xrb zB-Rjcd%M^pUxK2}7j&XNxMU0*<{5v z7{fX-(h@|z$`9MWGE;eG!e%wJtho5n)8zoy_Aln9=GHSuEbTfxYFig(DaYRR<1ra; z=4XN%`3zS;@Xq0)O2IsV_|ff}yE9d|I=NS9QHR5Nirwm2PjZxXJ;K9r!HjYZb*ww_A`%e zVhs$|8ikJ^-ML9(GBaDj)Xjj{jtm#ALY;NAL1{0wM$hMlmu8;#^95b_zmpRn6a{c7 z`2E)Jsl!?VMn|)Idt=@>I|I^2oRj2Vdj9}j2!OMtr>6t|GN0^7Q#BYzsLeo*M<8j| zt$-Mmexg=6YyT(z1fMT%WQvR-1Ao40TC;3+pM~LooI6(MnGU z;m}-XMz#sWhb{_ooHPC)2vzPfM|BPU9Ni7B&>%T1_H^ zEAOkt80kL_I(H`fp@=Q|MgC*Vi|Rrrh^uZw9z&qt5VtxvsOjc=sFa(l58&unu96{F zkb$w-TRKS@hkWrKl`-jch|Fa4Y*2J}|D!PqBb=gCnq`}~nGQnzXqt6FmIqp}Sj@U< zJOd4uE-DuI?B^Tdn zg6>$9{xM0@_^^mUWmk8rZTkwON{jlHuvCrN(qYhrYPKsR`vziXz1?<{1jkc^+mf+a zPe*0q>^1sV@?le`Pu17-B6t@P9F-Kdq%Iv8Srm6`c2XoE`TohL`!z4#*N*B& zK|HM-x@1BmR+2C+5`-GNFOjxiZaoM6hbJh{;wQb%)Ktg6gtdyz-x!l2x1#QXb@XD6 zg5Ps{DY3uj;^1Z2h(awVS=O<>JO(xt2;+p~ftC^{r^(haA14=n7ahcYVE?d8z1$Gi zXoG3LN;KQST2s$n^NYRg5>MiM?V%Fu7m#rA$%ouW5a2o+GRgpps-w&gVQM@IYqB0%K z=A5i2gt$(=r*Z5K*cv}pJn%85H8sTACN_{irQ11#c7Y`96_n6W4 zlIOy}M~cTYZ==qQ9VH#RAb2+~(%~QGMJN}p5K&4Y7p~?cx_p37>FkEjIHNbpr*8=B ztN7!KnN4h=0xYZ4Z}P3KPxo!jg)RS!rmujBtLwThZp8*D#oevA`%qwTcPUc5xI45I zcXtMNhoXhz?ykjMiu-?`H~*LHKp?rp1j5;8uf60*;53<4X9MSiZX^BS7Uk%MtyI!} z;>16`BToV5VoE&4)*FNmGyo%^1US*f&1hhG28N42O5qKKW$njr$>8T&QAC_ixo3C0>S<(zx`-6 zMIDj8ZDXv$$f)<$Vti35wa{BHn|b~mu=U$po_?pGI9P;L@agu;q>>?}QGc^y{ihX< zCE9+F!4+)aX7PVrLO#~=5nThSI9~CujQ^NNG(Pj1-ST0R;FQNlY|D6t$^EL|9TXro#A%9NniN)@81V=yHu470-H^p zD)cNvjr3FRWLmC`j_qDshg&J6NO#UNNVgxaz0OQEn)Lo?M}4Vi{97@W=9cv%Xq<08 zdw9uPQ*<>$#J6Fxfp?;6_4V&(_p-{sWo1d>d6}qAu&`^q*A3t_`nP+RsHAU%q4GuJ z%&#+~aK+*)+>(SLJ$G**khF+CGvKO^If~GLAT14y*)h zC(2$f+U#Ewkzil?t7#9?uLYNnX)uwjcrnK0rH;s@wR^bfrP+^qC)s!P5ttQBA~hoZ z=gX^W<($&V#h7!ncbWyjnSZU>-i3wx;@V0RyD+N0LGgm)}ZWPQ^^k z&qvS7Med84n)v-~`(ROfC~a&+{JxJEbfqrNFNAyVyX_dpdOThYdlvcBXzo}VOa_O~ zLNH|3)Gi2Va)O%d-?XP^qO?H}eq6NIER6?HywphFh6B`iio7eMFtu}t4eIIXezlRe zH&eI%=K9b8MVIY4j{nI^i|JYveQS2|$8rir^%s|ZjsGYA4Vk|%!C|Da2lOns!U2U> zI}f@^^acV(zbr~(uSX;oo)wWXe-IYNWmkNmE@&{}a&I6y+C%cL3y~=YDNmifhk_J> z`>9u#6P{%JEbVP5ZS7=%?htv^!Q!~a(krq-ys?%pX4vn>J>bUkx!E4Yeu;R#og12D z%d$eL`*t%<*L+F0+Z!7u=&&vLDG+?FzIv~xyj zmb^}rzv-NBXAW#+zKk;r!uh_)m3T?_ne0OBKIgI0%94C6a&QYKr0n=f%_k8T3*(tG zXVa+XZ59fS@m1(}Kv!=C&ZBRZnwpiL?|8+(gGEEjWGf_~2&tr7vGiERum%R@;;mj6 z2dj7eC8kC_>IO(2??F;$A$z`G8P)0mpJa+m^*%@HMwO{Bm zXVXMG??a`1X^Lnbsqa|9@jFbuJxD+>`;hg97=h!~6*9=c(zGpLq+UY*_%Br$M7eO! z`f9j)HU?Ew3|f330Zc}JxT8L4C^FzuQiNz)|B{HSB(b5WLUrwo%n~gIYpE5lO;#NU zbooDzE!q1b$y}%1(cOt)P;L|+i}exYl%b#^Q9~^2NMh{G&F#KfBMv$}Mq15S$Y*f6 zC#O9KRn(_2EE0Nm7FXjQ+Nl(}_0irmi7a)gRrHX_d+l@ijKp+`{Pu0e`n@|U!SZmK z8%ICCq{qyaWiLSmbY;=&%>txz|IJq$bto>P;A-3(y28hO`{#1Yt%F{YUqdAKb8+-J zY$iG(^>o$Si?5b6Yur1#qL1w?}!5*n3Qdh@+`KPFzwX zL2kSjYw$zsR!JoA}~*#S%K?y7cq5ZT{(17_cr{xgT#(|PJI^10GJ-}l9$Ecq6y zgoEZt#;ha%o(!6t8d5Lf4;;B<{jT1MD@HBqXz*Fz?o0OWDek~k5Z0Bhlz;1qL$vmQ zyV>!cwUI7uwVU0pR?QHkuN2Nw7u!(F6QkcpF&6@&-7PFq^wul`$$5A_#Fc<4Z_#TE znjhl0(f8t1{Qh_QPl6=<{5cR)MqL-y(6D4;l2e$#V78#-@gxnVj02dzK%}&b%k@o= zTBr8t&`@9qd(4Ug+{NA9?>(gRTYTr9IDi2RL?EI#hek(twi?R5E48vzd7 zbVGmTZBM=wPm?ctWA9My-{0!2ufI}wrRiMjnLWj5AL1*~qLjIwMOZ(K@Y(uYJQo*o zAe#$C=4k z$v-TO1VGRy6GTWz?zX9?rj4tRK6&lc*%JSeq@gGIfve)Bp=}p~T{tMI;^y@uIXg zPEOObfn|3vbkVZ+0>V|#*&#dXSj3inxv-5=DOIk?frGXGq$Sz;tX1{KIi!2dKrw45=;a_6j1#v zpe8MY^m6u^xh5ucb&IicN-e6=hC0OU_C5(UJwdd<$ zz0-Mj{iPP7?PNGSTDGbw^J0g}mXXslTBvhM5R9KT=60rvu_Y*uZ9N@-CWwejWk!CW zq*Nhw>;SzbH$_OH<9dSW#6yMUwD%4@o*$>9K-t!2psp+0<45}O0crgYfD_hAOv@g)IgB4b!Tc z#OoWS=Ua08H#HKr>BNk^5AH|Lq+5=45A^Uep#6_jS@~U9a*%R9bQzZ-pqVh)IPcN* z&S(*mmP3Z8aWyTq?ARrs#U&|kQY0R81?J#(H$i4@7Nv-|imGf7)(XhWrgqY0{dtMg zLLrC8_Xr-;G3LKd7oxBlxN%1E3of=K)s6tpi?wZqhIt`4}(z!?Ck8E?C+D2lIAV60g10gg@tqT^FSJd zx2Gpi0LSRz{vH@3T3cINT3Z48pOqCsz;dWX|7>&f;Oy)hu?0h%6BCb`;0E->7ayKi zr8Gtr^(`%y&H5UM3heHtaAK%t9oV~!+PdX?AYylZop$zDs{iV0ck>VYJI?a#FZsN4 zi`&F$4VPe?<1K#hB^s7t86=`RFJc_c^cg@@_%lqYgY}EC)g*B}+r?<>a{B`m! zpZd?V1BUd*Fi(cE=X0!=lT7B$x$VHRjVo$I*R$nJC3hjEff&};DrM*IZm!v_^?1$C zElnF5nA(6L$*bcyX@Pech>0w#s)~+^N|K>QrD0>5uzmTEkm;k9cH;J%BQt5I|ET(| za^oQVnmsz(yuKT(SCCxl_W=ZmW&q|b5XdGXBC>#QeJMq$XhP|+j|2Kv`*Dv25K96G z(*9k3-Y3qUoBzVofGm%doB~ybzc>9+z!WEj>_|MLS!CQzU^$O7L}#X{hGz&G?!BvwiE ziR4pRGKe-pjO+w`H1ELRC^MuqhULFWh>rA85S3i(u4;rzsWknN^lrMj%w@LSq6$?>?i3bACLQ zC!h{TnhK7YC^<8uhHg2hAQW(+5bdW~dzht9bKZ5{rS(GRnHj<=ob9xbRUyM8Tf5!AvzD`#8XP_C(_aGzKn zjl&!2NV?22XSbuNwJQuW2mqVvMo@@0kZggsm*r4Cv4mT*hJIuC4k@(bXSeH9VF?iL zY1#)N`NB|6P1@=FRqzzos~b!v=oDr%)58dtgp2)IrG&PccnH8oz`uD1Yqy_^Yj%z8Y4Nk`q2v*CCw%<45fiHjClarg|U)9%608Z*LBVs_zqd&nHZ=QCT z5~(}=@v`L`Dn2EslrZ^hutQT25r6cM1!fQLgM{oe2NX=!CvvYQa7Ru-;bSmv%rM*w z(SyKTh0Vf^%}l|YQ?r4Jb%B~(af1@I`XWu`G#Fi$YV!Nh+I4*{@ysf*5q}UFr+{{0 zf2Z_f9T+l7Jy>_jK)@ zAlfNIHT6=RehR>IJ_NUfr2v}4y*?!c{*_J1uBKL_t*2JKG|fWf)qi{OgxMkZ`Q_oQ zWNkw4RtQn1A*h6QTa~h(`+@fTYO__AxafCQ7g*^jt;T563sTJ`c~6w z(06W$&e$vw1N5Ik* zJB%{bZy)#OXn)q!e)QNYQEQ_>qVgLvdsBYbhsJUM-MUiP%Z0e~j~-s_P0;3e!5A5{ zXgLuZd|!W^E`i7M8Nm}v&Oq+){d+!ZG_Er77PWjAu5*PY4rOZ8ky;M@#blya(2T}n zMJ?dEocNOzG3mhfZew6}?Co!ie{NgSSu53BMqUX@(n0l`jlBuN?@~bVN3IeW|;|c&u?g4B`PN=Bxdd*I-u&;tzjoKUoP%jMW3DCzlu3GJ_lM|?>%}2HxVCNi< z6wceITPZ9=oSBscAW3Gzb1E8{uBu*l--y)(d81vCnzq!f5pyJf<_6-4rsRMnLw){{+~6u9Kn; z`2E|C7K75g3k!08oke)Pr=hUIk@zk2)zV~5=p?w3^dE1aY5X!}VkpNo)?@U0g-aK8 z`ajZez2JA&k%DpGrvsAM6FZlek@0v6q3dlf4(CQ5+t210EC0FwOM|10lNXKG! zICDyA0_ZUD7dPb(WdiOxzGoa|3hdt#u}wJ`72(r8GHXYBqPv$T%wjlTRb4i=9U0=B z37zF}b0}xPGz`zSSkI_IfTzSgpy9wu9s)_3(^r8d`mw~%XkHH^;!F1atJGvE$J1Te zH4Up5x%v<-^K*R!W0$+-%rzShY0U!k*`nJyU?~x1%^GgUMA30YP9Am6OyvlrVXu_J zR`84yL^WA~Ky|}=GX8A~KunFz99`s8cA|qWPL(Ce8fZApY}_XIMr-<4f!eI(_amBy zarrj>&me`cfriQ0xd@Xw9Q3J`C!0FF=&4HSY9kf9fuG4tPH}S2R`idg@G)p@f!br9 z4uOSD=E7Rx`kU;H{lxpTQS{?+%yUEHxi;ai#?q@|a$CkW)5?1P94wA3@dJRZLS~ll zQrn}m>?sI43S;*?xYB{F46H&Xpj~4@?tf?8ogD|-EC`-#`Yye>DfW8y+HT+i3R8g$69J<9WyclJ)W3=U`pQwv zlb~HK&{r@J=-i*{NWDC!BhzN~N3*0%MMU1Q0dvSt%5#_G0p;~ILRCs)B|{~Q_WU9piRb*@;Lp3?yow|* zyy~sZr=WS>(%}><&WJA6Q!+})D!TZ^rDdI5K|M-S{#Imc?4n)qQULZUs#Oy3`3RqS z9tGpRaup=CqNrk!V10>dr^#LdMlryXglk)zpCA8Yl2=+vu;W*^h=xE(R3h;&7XG`0 zo%$K&Apeh}Vz~BT>HUsZgqyREt_Sxn6@F!Q@4}cu5?VcFPqK1dLVFMdTYx+M6#^~2 zpcLN$&O5K6MB*`M;c`-j#>!Knw-Im-k;Q(x*b-#`LvIAt3+K27uF(_u`OtP5qp@O3 zepF^5IDNK|(8>p?r%AQ`Ghf!wQ;+hU7G~3Jzi>}IYKeK}^6Ir7i1oP9bahPPp~07b zS$|cP7FHKU`3{Js(JJglr-JRz;bm~Q(f*Aza=UWP`t5ZL+2`aM-V3^JYSd>36GzgF zF--N*mcImbEn*m_m+-M4JI|jG%oHhQiI^_8KR92|!S^;XVl{X@Lh?Zx1PII1gvwz& zm=W$G7Op$_qA$C|*bSYQQv!^-jZ)|ja0ts6+J#C1vqLrN&(?e68Qi9O*9>Z8o(F$_ zl6qVOdY`ws12d`BZynlsPDdoaQo)N6Xn2ko>b(z2!7B`C?hObP7c6%0^|`;fX-_9y z$Ha?%qdflNxsq;|X{%%WN5f!lf)y0DwzdXjvv+j(1_et72TQ`i1^f8E03{^cp> zoJ_CBJ_2l@Zl$C9T^E(2q9QQ0OifMkGCu=7?aRqCq;R^Yr)SZDWjX^~Rj7HAPb{%7 zg{dM{trm^FK&g_a{1FG|_}D}@{?Af7M=k%@abv9KfR<=``>eB->}Zj^r#);NOXLlh z<5(tV?$UxK+or*We!e%v<7BweTWF(-Gb{@Ss_@T!nQ+{nIndRo^i*%xjjXEa#f0gt zUh3p7XzbQwRR2^spMP|x6#ke_$l~{z9EoG`=Z?~DpQ9xbb@|EFbnZJ}pCEx(f}1TS zb@L_awCgg#7^8B)cd;8vt)w(@baVtH6x()#!r=3;+Z9$4J*ChZTbT%uMem&@gqEwq zSH_QVk>Q2-W0LF(^{J9PpP8u{6Na|7x38|Q>_gr>qNCf*M}9@%U%9lBJ(IJtvYzc+ z22N7$KBN+ETkh1>?xpDX|7nNiqV~ zd`xabI8-^50rf}&5TU95wu`#0zW@^1&%NRu2`8tB*wg9J6k?=E?+?s7CD-5kaB{;6 zuNGr^FBE2Twq(A3q*N*TjIyDD^@))xHZIPS(%I~u>W}hgG3#elagm~0lJ&*kF<0c7 zQV(=EAH!?#zR-6mn3Py3m)6qb4Sf3S7g|IUq@PI~dX%yq&epGP6kYyXD1Y6Jnzprt zx~P%4sZyx6p2O5wXZ|8QGppR$y%I*K)kdNJB7F8WJ@NJEejEV8`YuV#rz(MN)HhX` zi-*3FO*Eqln$ZQ#sp775BCp#qpxBH?SPn;6v%X(SCYnyg`NcouujX|z&upBpSLZul z>@`RCQ~~$?=r==;y=kkvWcWm@`UbkyCtEqqi}}ph$`%Se=b$Dtq<|KYwR({ybMp#6 zg?2x?poLcIH&=!{^N0jrT{WMT>F1RhSlxO_0aPmQCaD{{n8Ow9g^kQllj&Tu*&Nf^ zLXqkXyxtc6<7b^G2AlbGF!`ZiB(yGNQGNLJhwdO@$sfS-H_!5Kws?><651^ms5L?y z>f4h4;wk7|$1dZN$eJa6?lbRT|G_LWs8R&Ut(7y^y_3ll>-nFR@~`ha4}16DOw!KJ zB%QUr+AeWW>b4nZ zs3RmF4SFQ`BbU)y-8Dy5BJB7v@+*2_lTXo`J2e$~pnM$4KI!Hj^;`th}K&b~@O0&`JinH#AHN~d!j=n)u8CgZbR%=i6X6YM8? zrzs{CNjL3nQx;~eoaL;jkB(4Yq&_NITbX~g=9$P%`7R~Uiu@83iX#d*A?dd@sWh6( zw4a+_rMyZ3WZ}*2i!T}de#Qe*8p}Jjx@;(lK7ZIxwLiEqqvZ{1=Iyoqig*d$O?B37 zl5evvFS8Q!0(yp)2#om|C*Tjs*SkE=q^GD3W#C^P-mk??I>;hnCl>=|mdBtB&61-J-%q5kyyhD6H zn;Yf&BbkwOW4Yh08x}2r-?>@>io-bdHfCgqlk@1mgRzP&Gs~4BY|4=0n>09*`tAAX zDRWkxUK17ViLK&0+g?U>CQQ`>{fJFLB4wORwL6W}g+Le>!ZWxFy>igY_pxR2kSOa1Rv-%txh z%JQRc)h_dBHn-s-v_B`?wDIa#{}_e} z4_m3J-yyHjyv|I%*e@e!HVWgC#>Wks1y!WHdeXUp2xPJH^71k< z9TN_E?51-NG`ACPfjj*9-n6P0+FDv(j9KQAhU`t13RQs!*4>?*5_Lwzu(G+MawWVv z`~oM^^5x>`B+|PR>y?K%8>^Iyg`K7DW(?-pU|s$+S7%HKrr3=Pc2*8)7$sY0roZ)Ec72 zLnRVHsgh*)z%uymk@{sBewA3O|5sJiT}i~9l??K7B5^`9SI=)M!4f96c3x4ag}1H0 z>H9qBWhmGR$=71pQi+y*YX9tLA~-@rp`Y+6!DZYsSmFYovMqr2Hi!2!z zg|QQ?+#qUCw+7B>E@!it1-3rP57`xY*%cJbMn~hsf6!IIYGRVhap7wa-_xOYl7gy; zz=A%c@OH<~QUh}GBZNj(08?V>*BL;q0$wVgz17rPejqt?-Y%{(r(N(%<{R0=Z?sn` zGH2js8rFL`Za8D$zIHR&gQ<}AI5?^^vp)`}$2ExeV^Vx)i}e;Q9yp+9{#jBlFVd|& zO$Xt>Df;@vRe6zl&KFsU>8|9mR7}#ETLpC+vo^Vd_ztCBDe4ZWT}_I(X%((5gn8YUA>Ob&4YQD?C7uI_0 z$Ea3A5NPKWSoOZ4{K&4O&cMIv`O4^=a^nw~yRiL|0IG3oD%R;iZ#jIi$FXu>n2gIh zzy|?OTIWwYWl{KxeaI>pW}Ql6Tc}zuJ6fIazvfQR5-D6KD#rMY`2YuuNy}cyhVQ5e z<@V^vQ%CCmJOERtXB6Z*TXfC&PS`!)#_taw@Q2r6XFu#ExlcOls*VANrABbqCy%`9 zM9=1o^MBixS2QGr5A*U|>tD>_1=H7{*Ym7!c#5AgSMBMlGJwJWbgEHz?FJ>Lxw9-G z!P(k6-Eq5JVyFlD5U@$K{}r0Hwy=O%O_MTWYGML`Kr%CPgJ08svV)R_%zy-@eiPNW zX&$Rk$UzY`W7F`=^lt}i2n(K(Q_N>85H$6eExmf54HwM=SQrR~m)yn=jd1FhZ(rX~ zIBWe-D2F7o$vPY|sfe_ux)!YO{Vm4aUkv25CJs|*AbtaX-~35mZCHJGd)vui(6P7Ne5YDG zV{Tz#@%1afX3n5eff=9;6>bUSwwPkWqkHrg``;oYsMT{m>S_Opf$!0ZeSO6T_#FOHkV7E#Ld!I(HL!FZLzpV=pQ-ZHpSUmkA{7x9Ao>EKdJt`Y| ziTdX~7`oTX32p*kt2E!kw2s3x;X@tYv=%u2A5;%gf@t`s3@nQ}+0#Z@%SKr|$_c1? zuES!kP8;zB+2Ors;or}O@2mP8v&crcVs9F<(5ilZQ<{COx_X>oY$M}lFXL7zhrILwuU44RR_tDtsVAcSq1wp^%xw&Wih+}wb%r1zk0Eg^<_a3 zM*h44deX)DyBqzhY7anlu@}}p&NT@)IqRvfG=c>(IF&)OWl}~GE)C)bcRaOYWVlc^b1E4Jf9Qnp4&k-$As?Yyo&Pjci-Snz$ z`#!s>?BY?QX1mZd^sFqhe&Wor_$sooj0g!Va1w(W)5TDuWb7`R6Nw4(JB0cIyYK-e zRq5Z*Y!4f^eUa`~O?r}HM%toRev|-l$EXo_Q}ln^W=$|C`DQ!GudSoGD?{k?_9og)_fZgl%_4q!w7wrU`$5lh5k#NA?+6 z>J!MFiz>Sn{sRDdov#RHVInVQv)#qoKo>D5iq*8~F-^SRrbwER*a3U{Tz@olHBEBbmWFHPi>6ZPlRFq+h~FNEdbhebgkfz&~g57^-Jr) z&^{*WIpwqC$gmjB-PLfBy+x%Ejs2G?pZe1TTdImGGB#Y)tgNilQxZRB(A=R50YTb( z5MCI(c;37XVbL6OPO0)L?zAj5;KyVnj{t0*ySuxAU2orUWY5I z9MzDwBtS@WsR{LfAwy+R(>A}=5Go-=wshw1UX9kM=~&&i%1l3LueAo}Z}{}{7I|f^ zJKj~?`8c?E4k@D&8IQO`qqAfDY&VKWI>L_3d7ll{dDUQ?D9YkDq4fgU1iz}aH~oa0 zL4iYM^L?7bZJgQs(}UXpr}o4^Z8Y^2*;S)qWtu^`uUVSc^oNDg80oYoc};{(m##`egv|9wI_pN@D%-yi$}>9ae-rlZrZJp0nv?8xIEMr_NQ4CkdE| zh{aUx$SQsq^y@09UN{a83X1e6 z{pK=8<~}+%*H}v^o_7HgRV2^`>CfDC;d30T{-ymLkD?O{>a{uX-^eXeUvcEIa8)=PY9{62(Lu zIed;e5zIo_%*I^I##~Ov)y($3`6N5G;%pQ6IC{3}E>in?z2Zsc`z?L(!--1Hra=x? zdJA>8jdYp4%~xe_H_QFK&@+}e;VAZ(RQl!QNXDtGHG;O*Y3a5Zn6TU36IvOU=30H+ zMS9~&;b4R=F(fMx>L*-S$t(A}ARRwk8fY)R=yHbea*Es*SoT!a|4eZa`6EpqgsNld zQxTnW1D#C+opS+|c`j2F*Hkg4WS8agJ4%&laZFv6Ws#iOh3wf4pwcH-h&N_n_3om7 zot;jRj5)52IT|QTk*wq|H!F}&y^ZJW{N5;+2YN_S=4#$?E1)C$53}k?Aj=l88?IR5 z3`Ly$-e*XU8yrl;70~_9Qdz{B-J#w$#*(bt$Dd!?*C*ZUDC(gj<{yviVBS$y34d)@N$Mg!g=nK51^g<#j;Exw}fP_Eq$CNN!RO-u4rA810o;uxywf!CXB%cx|dR z=rUo$l{-<_&92Wtb`njPOZ%}Lo)iGqla^{Tsu6m$kEIlO>MjVBgvYK5o}30A{+Jdn z{(YV&_Q?w9B*V*@m>M#+qcTyES^!fwqFhX{rNcptv_>4ZU=_0+Ew0Isb@F)x0I zXhb8 zN3U)Msv2{3X#Lk0BJ+PVC>Z)Saq znxS6x7{eS)2fEg;UlDTxq<+@8E0mzD=fNI86gF#sYwLbw3LEz7=bxqMQ};IbKk{$N z?r6HsNP2VVz)PR5vLCV0L*A56X`-G=w_a_KJ5}HgX4cF0x`klw~h`QY$SM_)fPIoa(+ z`Voe@Y-{Jeig~pf#DXX+o+V{T^IL96v`XBUn3KrIo~PQ`eDT>~c}5O-p7yWPNGl~; zIQxx1{w+LAd>n1}uW{*Lw!9i(Z1L9_@hTpAJRh+&a@@C7LDA)EcO!9c#`mTVx$!7k zd-a%q{B$`jw#%uK8T_|m?X`mLS;t#=NznJcQn3lW?tzHJf=6It-BPrTz1P| zL6C~<`BSD1O*I14I4ipCvRlC2M4=H0bVfh0_56 zT^T_VPDWMIP?OrlISsN86qN?-&Zn)V>zz#t8(qgS`oZ9})m31;xb~WiGC4ZFDHh8t zp;A)I$Ey75d|I9Kal_&H1_>a%Rae{V=%fM4dPnJbZmJe9Vf!&cMMw5?-L^+=ID}BJ z|B2E`W4->%^2mtIIMdwUjP! zj9wID55le{D_tHbYZO7$s9uulA)t7KRuvE_>NzM3IBWnAYq}2}Nkz}PW=QV6fO4z` zWiEW}zEo|uD+aoZSr3UrE)J?JonrhRWkZkLMC_)bX<#us9ygXOVI(0REv)9Jb{u;V z7Ah%2*?DrJHe{}u0DbI{Eoz6ed-Ewi>TpUcDcxa9QOBQvHU#ENO}C{ICV3aOc|pSr zSxjyhj=~*S09A`u)%VZtpd4a>$t}H!ntB1$hV(Dhwvt5y)Wuv#M|95v`V}Yr03E}< zA2tU5!yyYsk45Hu>Kw=4JbG*?TU1=4MkrVqH5aD})*W+l{~iG&FNfS zX5I6TSoeRENvseYV;{Ovw9!_!fW4q!9H(0#P`p6-#d+_=2iQJy;y-Kym2zLq<}j|m z6=SrMEi%FXApF#;a~tMdVLz_zFZ}gpjUeNEe9^~u`QI`72=Ki(@6oLd(+?YwdcMM) z7aPSaokHffeGHsVlmAB4&^r07Ui)NcCX`ZrJgvL;H`06_Pgf^8GoB8cokd^V){8gB zUv@H<>|bWAFGDRLdb$4AQVo83?b0}^Q@eQvOg*id(k|68M^@p-HnPOFbm|R)zFHQ` zGFp!^_JB);Ur$I2v>`Yfmo<MO{lFc4CvLBB zHLIfqivqF(eJ80xyqv&3ox}r=0AX`qHeu_7it{BG*!AI{S3a~p*NJD_9_ z?845iqRy=p4y>Y2VW%wh-PK%>c$gK;!d|6c5#MssTmS^CbZ19Ve?jw9~Bp< zuR!L*fGTyZhP5Z_*;X#HlzuvGhq6{9p+IQO<8u^Ssk@SjKfk!JudUm;-)jhulwAi; z8yG*O429A|(R4z3&P+dCpj;bidi*q(41VTCwDhh&z!Zb5X$i7Z2y6}#i4`mp|IBD@ zZ8GD^o$~3|sISz1fD|w{Mk8fkWAQ6$)Jn9~O0K^ECvmOkKxbZbPC)5n_NMJo;sTEt znXg0$ZLcLGu5o&r=~*#CjD4lDBwwjg02d<+EKGP=gWQ6R`};8Im__1;10}Nf)rk%^ zord#3fIH?Vp(ZNZwS$$=)(4A*!|8lr0~^gy3%68SO#Mk8rtet!U7^87(MO-1;du`PL;sFTCwyI9h1w5)1u~(rjCUFQJf3G)Vdv-5vcRU(MtZu zf}d_g{cOJh>POeHT;nkVcmq|Kya1ayfow4|(*fPV629*7bHrvqW|O6Yocmuxb^dL9 zhn8IJFYfDr5qmJnNsa0z%*EYTTq;S~9bD}UJ}ql(9D`MN98cx<1#~6Od*dA38O@W^ zi9L-Vxl^uNAtj@ddZoeK;}hNnhE|M=950KdGD^^dL=MHU@GP zh6sQyt&MD=ck<24<6jS^q8HY2(%Hj|uz&kgjJw~O5cd?{o9I=W>sIiqs{1B}7?kyd zKu(AD!6$o*E-3u%!pg_n`AZiR{P}euIMwVq;)63ar zUeyV@Q5%%4sNON5)~)sZV}Qr<>CG~4Z9q=vym7^M+SqwChqGc+q--bhfNvtChE&c( zILp+XYo&@owT?^d#Ts{i$auc?)BG3STUPH|QaZz&^{SPziYYtBbHlO!;{vRES=1+C z(3S_=YPRXzA}F3KGz;iM<_6@ahfltF%)ASuo$z;I(^wIsQV9cZ9UuSH_{S@RpmzwY zcBZGNKTZHiUv7?5f`T?%3Cx5%!tq8zZy$#Bzv=?Ni<6UzDN8I`Af8K0T^$z>&)m%H z`_G?GPfsf=E2i{_yG$VP-!0pl0AaeA<3}byeQ^r~n4_itVGd(D_-16o^C+Y;tw@aBRF~0Rj2P^=AFZgpAp`Q!I zZ{hPJ{`&5t*CXZKEW-F9T4rrTrW*d@e+qq{iO1WDv7xII;OpYe!qevc3dg6j%r#z9 zO`|Nsi*v__>H(OTKRlfmOlvUa4t7fi7;IO6ka=X(v8nSnthj$<-?aV32)R5A?A z1><2Ur_T!*yuyd^NV#+Mx%dIr*1u;rvT&}RG1mi8sJ-Z*1AVik2w`874j99N+m7E+OLaPjKkj=TEz->$G~V#`YvX0h}S?Iuye2Q;VJXaF%-Ou9Wh zScZ!_Jg+>RHon^nz{uW%PWcD*7RoBLQ8KY{E5tc0c;g^w%@}d?LAqF(tr3!x!23^+ zl#t<*qW*8Eo^K?Mdy?l~bSFBrJ`2M*P8kFarb;3eA^(>&s0}Zlk&!-@#qEt43?3WZ z*U^#865hk~c#`dTF9S?D!N3}7J^kgCZ*m1duNosm3Dc7rU6-Go>}od}CapK^r|Ta?Jdut57wwghTCxgMFy*Eeu#_$bA12H(!2SJV3+R z?ut|fH!s~TNCXihy;9c?$ zqs)YWyC!+LBkHKS=rdaBetqc_xphHm*-&}{8QURSx*Pd?D-~oa(ahWSbQE)?sJ-LQ z&LYRkzE+Jc6W)1s{ZbC2Wi$To+^^>S5$=V(jq zBIlG$0|3G$)cM-i|ufWvdzOj;dPa1hu;7D2z22NztU#Z{- zsIoej8$t}~rx%=9`awBa4Pmp$e*@xJ;orP;D`k6A`B;cyJQ*%D2{kzc2R{&OS#73r zNXF7D@SsmC?i71qQBc82P7x|`jyY~6N|$%S{0RypmC6GDU=)N~Og!{8iG2IS|4ErL zyKpYQ#*ZR-Awe)0KPlQE=t5zdO)1!biiUZ+7s(I8gZKoyL2Z%8fsgnxl<{+@2^CJL z5HGsvCTf$okOI}rAniD=`TaMDr{@i=WiEIlrIQZ`+(Ja5lETKCSTsQ^t~y_dH=i z{x)#(!@hsywgo;n-J|Y6(K>}1H~%~SmAYT|yCfBU^TC8qO(>=N{Xd?*GN`RK+!iUt z-QC>^rMMH^-QC^Yo!|~FZpE#*Q{0PNad)RUoc*0U=g#B@5=b^--j!!POCYnJfPvyA zR!UOn$--lIu~jLOdFFYDJK>zZn;HKdurCs+npp+$2JySGr?H4kA@ z5iH3UiWfLpOWG~PFW10RJ%9aJeJ2(2|Iau0cpa}h4{XBS|Kwe?J#_p2cX&vn%KvyB z*#ijhsobxa!MHJ|@V(=~mpkMraGC?9wk|lw3`;g#_ao1FW~97=Z$Ju1PaZVY^FSrd zIpt1-g!;aVy@X)n&u-SOpUtRS{^gt0D{BJkl7y$j{;@Z>|;CcY& zs!}7ggjWzbcFza3UIsA=Er~A6ls>86siOCbw+fCFdL{61?!wr!n2wWz{~Y_)jTkoC zag^i_m}jXiY@qt~YJ@ePq%@hUC*&s&w3#@XOhv-GL??fD{~YmB*Qm#N`N8||`k~A2 zeMhJ)fi*v5!NXUG$_Pi(TGe&i)%!6hM7=;F?Fj0>#F9ZA%JS^kwEa+4+2W!dKOOcb5bTx4{Z8xdiC>Di&IeQg&6oT z^dOn>QpW1$`!R{!CZ5;d#h$}uhaVE>-oFd&OUoQO5U{K2M}t86Yg>!pfob%Fd>q~4 zJCgj{IK{cWR4Dn+sP7_ITRl(6?suE>1-o;wDD`My9HvDY3%&Z=uSTo$b{qethREkd zGbsP(vbV>%dR%m&mOP|$dPt8Lq{D33(lw|@zk!X&trvKG-vey@OFamF9q zP(E43|4@^XULi>iP_=Zvhl_m}_UwrP5=@tT4r_=jxPCQ2^EIb`<1!ocX8-nF4nvqwR>XyrhS zqd|uSR5-P@wf+0&rk|-q=SGDZES&FYZol!aGXUc#IXj7~J zmgB3dt7(jyH9Ac`_b1<4tMzqzJnY}1u`6wC0F_?FuLf623W`t_QI6An4eFml$Y3Cj zeQazjJDce9@y27R4&C0skZ8Y(+C1}nhf=v(O-&7u^4LR$kv6^$G{tL@9m)R#C@mFr z^(HT8bLW}av#RLcUNS()6`3V;=hOAUOj=M-0EF*aTU)o_VWXh|)x@|21U?OHfJ9no z+t7Mfm2MYT$oONnq~39gh2MMQ-<|jcUTcDNr#P@YXN#6{J4=QLK7ORGo4|yEtD4Ry zhrxUUHYMnB(E#h!hr_y!q^VZ;$p?y>idxD|*zEYI(qSq z=qoH`dQf;WvT-F|5d_>@vGM8mm_%3^2dK;)WU18oNkSL#;o#!iVOHnhYD1$0{XH}c z1e`}zT<(dEQr0@f{ti7IOrKo;e)bWo_sCK}_&G;P7hhW@>cW;ql0_*EeG0)ZX9L^PsaZ#SX<;@c? z<%!A*y`kvceu@CV=`8SOa;;i-C&W#+Kf8IT)jr{2IrnTm`(iVfcs`AARh?j?iKV@T zz9vwTA5Q#lN+eJe(lJ}_6VS+IOS^pN`hXOqO5$~7^m}8w&%Yl8Sl!_yBVzsqv!{|N z&$0t6k5DTtGWruS-(S}J(eg5Kqbi=yPM!x!sBVntZB{g8AnAo!vf`+p51v0!gRD4U z#*R8>BkFueysTV=IG75|1?y4YZj8ReUhVxMtuQgXWkX-#Q^;sai(ygCy{?A zG_D)&{cy*JRV;|~JNtKt+RDVTDfl2wB`WwPrX`m0Ift`!cOZ00Dm6Dxuh`&)@P0W4 zhZ%ZSop53QTM(!S69UZJ0d|jvD*T~FV__4`&?LK5$>km*gT=f6FgXIxKcoS@?K9`# z&i?8Ig}xp83@XM$ixz^4d4HgU@^PQ6Wxoo=?aO6RlHR8Z>6q~JpH>eMv1&=xD*fTzKaITI3JF|={$Bal}mA0IZmOpuQ`EnmQT(Q>mTY*Kjjz_QEfh38}5W-&`X;^Mzo~dG?X0`Btz3Os_ zM|fm2>&44mHPY&BGFi&`fb9g7Sf*qrt5z6fyD#(Q-uDICQf_K7l^F)+wAo-~>VLhD z7Z1bbLLa0}fUY(j-B}+q4rH1dw?~uD;k`v5u<|^GlZ$Zk`0CY*RdKa&HBW&W|6Nz#lK^sPm}-9qiJo;X(~7@`a_T z4ue8FD{`z&3=B``yVRrR*})nowI7o9d@|KXg$5S|-9A5jEJ@v8 zrETWO)OYxfS&`?riPemZf*KlJMHCbk3U?xIGP`9C&wXOVlo1oE8jrOOUiD}{j#)Nl zp^W`m4z0eg4|kuj@~@B{BIq;-d^UYt53ZtJU-^)-^#9T8GaD+fH!65E?6a2EqTBD= zH(4>b;1(IP;vf{GDRXX6)fC`*{2Kby@a~9wuZ_~wzfazjXy2&=*;@6alB6$lG(X6L z%FDN!kEFtc)6wB;)zohLx!5ZwBZqghxU`0hR-4_* zuaZ4wRn`92-Yo^7hRb@eF!P!238Q{OnI=t!T2si3{rhV=YL0@Yx_a7=A17N|P7T2b zH)yc1F{dX3+S=@CC(lWM_XODK=kB3nVurHj)CK_UjL!hsw*Ct6V(7%g{*y0&LSpEn zM9&pA){sT}S1~Yx6&EwmcF=He482E^w8VqZ;6C+WrX7JV?G+5__}r6RPbe(UFdmSs z31Pbq%}GLLoM*oUK2t28NVi~&QT_fBAC(vu7d^y+Fw7!a{fY;_Lv=a(J&XH{iH>C^ z1*K1}a5F4lF;q%5ezYKhlHIKp)0iG}5gre{7STpNgdG`5Q7u>I_pTzPa(?A!f4ce> z%xCK`lY%7@v(gNzQWiMrCIJIr^<1bjK}&7noth-Ni^&2Zh$U=1P^BXJmgq8Dg`-?f z{zq->%Dj(A84aP^U2KR>e>hB3`DZ@3Gc`L{H`*_St*yuildl}_0{jUR=wh=}R*BwG zn)f9jqZtv8s|iuRDI+f-eiIJ+{WL|5Xt7tqkw<+v%i;_D&%99FI4MeInAJ%k&oZ>@ zjooWw_&1*-#|T;jguJ{ZDodq1z0D{C2I6oj0A%{hXR%j#ZnBKV@n<02P?n} z$iwIALB6*6hIl(y-u+~xcihg^B= zo@5L;l>z~x@$Z2S*S-zcxee~UP3if9gD#Q)Yg3l~>94j$bJvnNgk!PEM8WwJnaKMz zl(96AQ$}K(jMd4y(Dy#%IYS4$oDLhWi;8XWy&R!H`?V)q3B!PK!Pj6DQ5E;r-5a>! z61JN0lupgk=bA~Rs&QoNO#GQnewVlCBjm~*&Z_v$pw+{_`IhwdvZ|{VaM+V8-Q=)p zg;I0~YK`uFgjqM6%c-dRZmREut03i6iq+&uiGR;WJ6-%k)&_e|B%_Em8;k}!9Pj1`iFA0r>gSB4$*0vP@%@O!r&(yX12eKF96eotu` zhQxO#TT7o&@p(T{&NxSyqFu3D{;~@*Y43_SykJI%O)S|^w~Z(@|mK`y2Z(UuoY9k;_AS%n(F zbrqvK0FDU)oqD<))+VLNiKtT3b-oVTAS+e`m6vhI5@~^DgT0_Cvdubt5S;k@EXcJ5 z5Y^i+_s-sI_HbKzxqD7ciz2vIrcs1Q*%q;=WqPra{}HXF#LEQ7x&d1W=(MtoJZ=u1 z+{|*OoC@*6>PuBr;0b4(56t9&Ct>Y0nh|W$>BoL1!+#$u1HnPKyGamX!UU;UYv_@P zQv`;AFxer%Q(A>(>vT}6AKI zDaW_qtX0z4dy=!+4eJ}FJFQ9GH;>6ndBH`NVB%q>ljhrl`7vQ9-r!h;Pv;CjN0&nr z63e!a*gjKApm5;{jE#6zh3|V+#icQ5Wo|?ak2!}f7PpP1RYO(9y}kZy7O}mjfpjRB z$%8P_Wfc-GWT%elFWGv9q%^h9=|TaY#NB>0ZQ?$2&DQn?2Ex2cP@Mo0T@@AJ&3%rL zv5ARjb8T&2M@NTBd8!mu0(uKA{Cwao+*i6N0ZWvxjHg1+KRu>Acm{d=gB9G}-2pG8 zgM)*gUuRxk9sq%&1$6*$c|M>akgm*rY^hVzma1uLN`gM^<7CR`@T~q#=sSGCrHW?D zlh~bKqHzSGw^CA4a&oF0Mt41N;XbMOwxu!lFDC8do7BHhDQk<}b$tmA(&o#1yg;fy zqf>4U@$#g;UPsy4!`bPN8%UN1S!|6Yj75pbM&%2mO7f{2mu=3IwcOn8ji%5nz94qX zeiP!K^bjKoRK?kSTWEeEEVFlg+GH)xMlA_E{>_~}WSDdGXn=I-Pda44HB?G}ce!)y zn~f**iCqx&C#j1GNs}q5l1|UQ`Ll7*%DdEfm-(H5cVo4xc?@DsPo_ln9~y#rXtBp3 z3KrG1LrL=8!S?QEj<^wI0#O-lm2x$j6nZQKR#rz(Pt zbQIq3uz>`~?PO$Nz`(==6oq-;hDJxFi)NO6eHj@UQn9gZJRfK!D;8{kATnT$tf%Ma z@4xTTb_OObS9`{NFJ?>|TU%QjzId(&f-*~h*BuN70~$OVbDB*v$QX>Z2gIkPe;?#h zcb`QI(b~N7!i(cO9fAsa#X1U{6lW3*iz9A@P)MAkrw-!0tcGyx~v9 zL^QzeMFOZWRt&vSL6QZ7aI1&)d0k6nsQl=*Jnnnw_2SBZ#PDq#m!4N#GegG)G|ILLG`YX>juTxUtV=VJx*QtK^V57P{G*u z44-}0rrSNRU#;$l)y;=D-xPi!e)!JiIERL3E;bU%iHBu%%&ZhTTl1i0*z+cZAFY3@ z+0jcMc#A@OEOxBPSDx|Lo(1}}v2)ctl=&7eVO8(AF$_ytttu?B?0z4`)@iZ`q&y%d zKc)YTKM=V+P3aHDS$1R}wUxp11+9(D@}1HPwer+BMt)F$xliwERepQtbVT3PP~p{2 z^O;l4L3_Q>vs?F3dt~}7NU(*&puOz0NM0LEnblOhhT5-rS~V;v33R0O2!>-%yAjCU z&gL`{m{^lt{wV1NrCq;&I9A^kH`fx|%jv7_1@5NAdg-{2<~SEB2Dt z279kmd`UcThsc1SLRYGD4(*O`A2p;v{HN-oQ_7Yh`6e zzzICh@p0TRgq2QEc@{9-`ld$3fCh(l$>{Ftddi3d$dNtB6--NKhU9-%npSOci%!%~ z1F2m^Ee)y+;_TGb7ALJK!{8A7B4`tP*PV$BHN2|tqGu~oRcjJ^L-?06c&!v0WXw}b zOVT|3<25s?dTAJ3-Z#Yy~mS4oM3JnitA z_oJeW{)UGW{K%5EysJ>vFQP|_x?n49K1@g8)fuRS9i6w zl?dD(AHxO)iUB$>@B;$40XlS4R8&@0)-XYVwRHi0e*U?+uM7+fP|%@YRvH@`fEIgU zCsn{0ySA3LplY?hz+s8oTZPv=w(r8!H7_t`#%^he3nb9Jsu&p=iHi@KZblF1YG`O! zSXu&2k`eMq*pr7>A>2LcQGE@Y3%IbKKc}arKEAwsTu4P>PEMLH&DZ%-Lgl`S0=dhy zw6s7QWndA6UWp1eF0PQrB@pqiuC5LM7!MB*aAoiB?|^=s{d?^2?pOQJOfj4p`G&mC zP9fht(h!j2M$>UCDmDk%Tt9+fP$nG-7QIB%h1VxoKGH22>Ivz#L?Q$&OcFj)VFfx~ zbhF~9yJI@?UuFGvuLjDrDw!0z{Sc`vg;=|kW z=ym=SZd|NU8=bgMiB6Y10M&8!sh$C6)&*TFtWLSOY%mpV?XHVKVMJ%48t>Pwm@s5W zv#4ANy78W80h2=15-3N!rD-HBh9UOLuYqV~G|#;4YA^mv|O9534cGpV{m?zhYLmkV>fp0dVz|euk?m`V?m>^o zs=;wx_q;j36_gE>qcX%-}ugsd<-HNnXFnVMwiq2;~6$|6^4MP``MqKc)>vT zv+&BIe*MD;KBhPi9g@>_{y|T7o!%c4y-nUgCTPLEY|&zE>`E(x!|rNWx;wb~zRaea z&0kh^D1GQ|QXXFy!p#C2!+vxHGU7SgUW*i=NmhzCI$1(QqN37Nl;v@9StCI<-RVii zb@2e1=kKDWgT0KS?bvb{sR-APwsN+vYI1YTnu1zMyhfDZnfBtiQw**euwg>#nhc2&OLdPdb`j zij2qO@te?srZlY+S1n7|p{m$!dx;96Fn2y4D;(XMr;es31Tn+fZ@m25Pv8ZU`bNDO z;x(QdS6N{wewRH+FWXT~D^O^eslm7l5zkZQv znyx^e(jamIMAZNe3)ly)Gz;k>XwUu%={yK$FD9~?J{y+&xYgOe{tkVy0c9r?~Q=zuQFZlBvd8$+W*VuP63CL6^V?ZhA0=cEbX!{jVewS$9d{V2*xVym=r=gprg&@lA z679D58hC2lIx;5!#JUnU8`O(%_}3SDVMy_b6#}tt)!Q*8NJy~T0Z*&te$dp);OINQ zqo}+t(HM}TUf7Gk)%kcUWx$x9_zZ|$@Qq8=xwRRq0w&D@K3`)<&Gs?3JBX=%%k4l# z+&;$XFZ!vN5QP5QmLDsIJ|we>*Kwza5#k6&AVRtZAU&`5pIDw5+C^5Ts??Z{)~VQ1 zU7Y#*E$hiK=L^sCSB%C0F0>nb=EHl-@pR_Ei%Y9Ft2cyK$J*Z8P>_3U(f`T@_<=(fIL5fS zmj?&MX;R?B`vNJ|pLXfOh7TKdc3N)_>iheByJmWxSo8kizK#p|u^D2QPm~AfQCH|< zt}6gp(DUVUH#avxLIL1&aiVWis0Ua(Vxs)y_tCt@#yc=3t-_C!Z?+_?jG6#@^SFlx z1nAi9H@CD5bFp+%-A_{>UJ##6ZkqqGuchcN)h>n zeltjza#BxGab@zdjs#@XI$22c0Ylv(HE&mn&4wDtHpaLqVwTH%)&pyL2|H%ffcnwv z`}u|5P{LrWJPe6FzK0?8bjv3;PqVqz399hj2JL~h1c@bSVNvPYUkT7Kl3AGs+Es>F>k&%-28`Ij0|8(>+0&F znVj)SDzFcsK70u4P3U4x7?zcn&-r2;QdG2S$|~@bN{PjulEM>%Q}5^h(#?=D4*U!- z5{grxODESH9d15GE&&Y%RaJ5=P-$stco9Rx!@fQ~I}hiKg61^ zIHiB^(Ei2bgC;6r4v@|!&*iR*reV>;WIyOZ49Z04y^Ql)~VJa_)XC5#teZ zf46an_)BA#G4Why!H@#c0WohYPC4RZrX?}X5WqIJ}#eCY5rOLw8I=1o&50ZFw+XbeJbqeRKY zM+G?Sh0hTo8<=u;z;o&9Z}rZoIG2Gkr)%9szX;2ouGHt`7RMqkCGY8EJ`(G&3yS=w zRO7MIw-`5ZgNA4G#MsE7{jq9&```ME)lbNc8VM7atr6{An>p}X@J5DN*_1SF5LglNaQbz~5P|r`7elCc` zQH2`RdgW?)YrlAFq&0sv@}j)n;DKwR?V-}F?B>RfB38?u(`FzfG>-@mKUzLY`+5Q% z{+rv9Qx139KX-l+jsyYx1#My(3}Lv=s;$?CR83~KERH-)DRUC*3YpD@?D_}hwKMJY zIkU;8<*tqgTgHMcFsR+4VIU)9w6%u*){BE;quj-&=jmk=Ia#Jzc7eMClevQ`M)yy} z=Wrk? zycGKGTw1$_SAFX5Z7BUgb*V*8G&r(!_A@038z-v0Y|;BU{{3GT*FyqIZ($|%b5c$&j)_S*Tp*7^^_R1us$4Qfk+8a8Ty}@d;vE~PB+aM@Y?_?uai9}Gvp-sdY>5g#uzX^Ce$I2JRPyE}p-dS)%g)Bq){bs- zO}oBM@JrlK8X6i} z@eoNRU7$plB;_X4-^~ZqS^fufJj3?09E@C^BAXd*FDCVPrwD^4Y=Xd?cd)$;ez>k= zNUP}V1PYh+8PZNbQS9I4&UZNi@c(#`MiTVi{7V519%mBx_6=zMML{ha`8m3Q}DNx9edYa1aU)?lU<}gXfVKqMMbi*vH<#Ae<4YToD*fk*uQS2KR$59 ziA9QO4De9r%dSvaId(B66)OZFi<+7m(4GU4cpDoV9v&VPNpL+mAPQ%&N4@@+jbA{m zuf>CFxng&*8pCxXLU^<4=_p%5{FPT#5X4kA&&0rhBy5{rlTHpm9|I)vj~@is*f33( z7Z)EaRAal>fH?~o9xEy;5D*c8el?&&2lzl$MP<+BNp&;4Kb;+k5&!etGLroN$FJLX zdpD7Fw-z$SfILOb^1CE-uY3ZuI{Ip8%)o|6sun`GuUmqa z6rwUT+}X~f8WUx>l#-p@aIOy(3O1P&lI%>lmND*0?XVZtoT9#;$b%UA=NMj<@~moA z*+z7`@OBTBkP18-SCJs^1b@OrE~Qn4t%`)kl6BPlaX89(1ITg~ek@$xW1CcnGm}HX zeAh2ayU$){!RS} zEm*z?(4b&+1*0@?hOYfRB_k-&hsCq;g}!GZr$UfXp@M5_T{VBPE&Z1NN8z**sK89p z`3%sFhV8S){!i(Hz;uS|_(N>`mHC$OJUzqVhhe92z;XJ*zDJDgc{*IO==y8;sRVGB zcbE0YjMJgRTKqSc$)iIW1KCfPC+QiUSVdmgF#*wc8r+s-;`#NLlqJQ-0&b}V)8*1CAyqHpH2m` zqt0&I@q^M2>};o&L%vuMrZSZ{*vLUH`KjvY`pY1GnJ$h)F3&ni=31owt&xWWyF_Ex z8#3(SnJmmmYLJUjUSN4e+Bd1xa-ht5ZMR~km2&0tuw@TL>>bbMB)*M z{aXT3d}^C-%sfG^Qq{f>FstBNQI5}iza*sqe_n+l1_b7{nOj+r<<_3S&k(f0uvE9chTxLs|#k9XH1bK@MDSi92&vp z1!+z6Ddusk3#0N|qzF&Y_%IB@g_Xe@7q8Q24TKOO5B>sG$Mz$nnf#<`h4tmaj_aLU zDr{Z|5va<5`Z%1+QUisGLXee-K0!5JZ_4N#C2vYlw zfl|o>Wmp|;c|`eyHA-|>cz~1wK(pbOi&qQICY{6#+H5|}y~|p$$adl!q$|U zE$x2;mIQ~_A*t!<78VuZ#02p9*88gBMTHEJ0|h0m*zE`zAkMawg7uLCn)%!V5O**diT~ zJ|+dcJ{J`#KM9U5}9q`r^o|FyHSI`j21qwB+m0=Cton z^{g)8%4rAFPy3k(XPLP)by&xWs%!H}%E+fU(0vbLHzBF@lWkoV^=&*5k-Z^()iwowT*Yh zoSS7MfU36qFn^6Sc;e!iGQ6zs_Rd(v1@BxpCmdRg;W zmi#5D^l?q%J&|PgOEVch5oHwHo%wcIfd!PW8kT*z{2E_RACcB&TtwEJ%CGSf-&T?C zwS%M@3#h*x%=&6g!d4Mk>OY7@bo~(Nps<@J`iaT;8BSVDBNQqZ*A8SLo9MPOpx6}c zcx)UR`O~H9t()$eK{sY{r$VSzdO=XRi*nG)T!n=OiF8aKZ}|oG9=8u)K!$+TdZ(|Z z#Nms-B%s*7b6R8Z7CBMTL6!GvT}y(u=xa{}TTTT{YRhCuO2R3I;)0prB7bk8W<-)X zzUY@FU$zeSW~@5rd7rYVQ3X4{lXx9M`r91SA}cF@MrxJq@y`1E)5|KQbh90?5exs& zdb(iV+_wnUqsEg`bXBaM(>n^*zNK?UtYgi=xhtzs9qh3h#QL5-xbHD;$Y&pTUe`VA z;EkVJaA1_}7^%wAqH8F@2f$f>5X#ZdNL6708=toIvmN9V!??To_GPzg{#9# z(?9xzFXQ)Yo4HLW%B*qIObO1_ajv!U*V-xDJuHlMEPTZ*TvY|!RmR?Gw_};el}fPw z`WOJ>sPxXF6i&%O6cM_%Y+HC+>5ln}Ep>)9fSmW}+!)P639!i3I0Ol4Q$&&9hSuzP z<>^!+pil<^aI+OVp}AYuiBth4g}x`5xXHghH^HAS4RBS*+v*S_sx@*}IH=3@kCi>E zOHoIM6(TcIoJ{$b|G{_@3zR&C6>x{Sle&8Ie;Yk$3X^NRQ!&vLJDcx2b&iaUn3EH9^ z?0{elT20|X0^DFlh}ND41a<7MBRq`z@*SBSLTtP~IN8USc?2`<8SQ?dRy#!OEvd1x z0MB?-o-vXsm)^uY7$O0y*q&{+TW+F!VL6C2unyE!-(Zr>JSZaDuE^@E(SGO7Vk(0| z4NwY0s-$tgp!KlS)%u}SmTnhcT|+BCr;`3d7Dqj04o5_hmj$M8Ra%cXOg4D-rWbs< zPwV0qaYCDuvo=4mJhYfS`U@w@s#sunQ0xeo2`sI#W%BT3YX+#pUD6&OHBBB$cYk<( z#pSZ%q3JfHpwH( zGZUi1g)t}8@*T^Ue!LgASxS~Y50y#CjxIQh(lk?$-yGzALA9ujO5+%ob*T|!5OcoX zFGY0zlq^(y)71}D>Vf(w#)d;d8H(Q;Mo>wWDG?^?OnQTY&KiE{4tsb( z>3#7ZZf$S>mjH4$b^|oyDk{kUaV1)S1_mi&hX@Q2zsD)AAi%ixeVXd@X3|^=+-*#d zAH-=G#1Dxb#ZRa=>V(p2#U&(+k^c<|85~G%zOc09I9oibp2CkkHoVcqUstO zLVuF&QFt0?a-7T~>=;qj`)vdb*eST_34=g;eW}}$he(Fn7%EvAdaBu6_9v-;q|kfr z$(EhzVMs+#vA9bp+^2K&dD$n+RQm36%-WHqK|fW@*Y)%L2-6rC<9Pz__*rRtN%^iN z<@j&NcjV)V-SEZ(2%VDXw%PCP)I%p;O~-uSEN*`>F9M0>c5Kcbn9g3uSNHg_e<&g= zR&bzDs288^XM-{*^bK{@geN8`UB1GmDp2@^L?DLgFaU1>0&u|+;^IInsjrV9MX5{M z8lc#q-E(s?Tbv+P2Wmjo?jxC$(MlVX;BFMTxLUHavlA21fcU{c#w01Ko2z@X168>U z)DmCimlwCd7lMT0nAq5=s;ax2o9A=JKYl~aEtY8+t{F_*aG%;mY?^cc4rbHR?uwO# zB|atw0J4|yz-SmK5x_(sA`%=EgBTzgE~>1gbj2q%PZ9j|EE-|XpD{kCe`vUj9`m2K zEpQvOPX7lQrwBi$*P|s zL=nYV)6!JX$?i23Hz(FT@iu(Z2sY0}J*gq0?#$qpC~dV9Hf`_@nKD|<2Cmhun6n&% zjFSBlO>}gk2R7dw+oE4FZTR2FwBL+D$Fu{XqI0RhLXDhW;(L&u^Jc07%c`$^B3HB+ zl2RqMlEN}sM^M}f#Te&c9#+dOdGZBRwMAhP*~h@SR*;Ch+8rb+kU~x-ZibmjuOJ2C z|5^0gDId5yEg!zmXxwxM|wf z-I@Q6a`mCPB*WZrnf5K;aIB&U+jW41{la_UYJ`-iG&ITQ7A9{DtCMyi1}Pu~GKSdY z6;|PnC!_xqvC%5u+K=|F^4q^dB9)rc~nDL|i=~#?E?99|0w0D_tAyjK*>nYgK<2U9lfH z;E*d!6JahcO9$)GPzB)^HWf*HuC;-R(Ir$wmULh%cQ=q?EvSegkP=e>Wt`OZ+z^pFY)=4oE}N@4vibeB?7_(i1uX#>&( zu8B!0O%8^t{h$2Qfhi8`6o%nHG}1S@GeL*u8u>4tP)3mnnrgV%4rhFVrS1UUtr!H;_c^@lNR`9G>)seWjF zmbmHtLZ6F3DQZjTWNDj3x1_-Y^rNy0N%hM8(G;PdR(ZNXE}MO$RjMO-{I~y~MzIOO zf<=8#GjVh!2m}Bh3(T()txVlmu5VwPOSI~iIib+y3rzaoB4kXHvAm;9St?REE-fwq zfn@0t1mxxOav89NE98|{NB*u|mgWHjg!|klJN3w=$0>nYT({c2;X^5unAO8k!0a0@ zvs-hv)71Bi@F~wZ*)X;x`*WjrKnyEnfr`CkXOu*VwoOwd06y_7ew)INSVqSdiMLBq zKRnqy18ux+*n?IddPpKnrP(s$6*ZqDrE=EE5t=mz;icTNxA8(}ih!AogM+}!UU1o=_-n%%_=x|g)!g#_I%Vnxh#ix&vSJX5LchQ-u!Voz zpy-yH9UKC#bz{a4B$?L~&C&F_Hq6ZHITJR~imECmdivkN0QeMShMoMpyM^wmxHu+V zyT0|zWjA*bH3?E$CdKYcRmDvNJir11U2e+IQY4JGS66h*%)np*Sb`~M5_HbDc6W<3 zDwV^6QUD>ni%T@npj}#;0Tdni6r4wNfn1vB|NPlpC+3afASfMWtIf$)1U+dF9CR6U zW;&tZ^&ie20A=VJ+;$e)cJAKqce5iEJ9pM|W45Q}q)S=;dG@a4aRKZh-GLbQm0VSd zn#w&R`RCu|S9&skHAKwvgI9Tjn`xr8FZ;O(L^lmVe}9PZafEx=p!kamo=opj05_djz7HFy&|%@@;{#A{)AU@Qk$ay?iNQ8E z+bWy!tFz19G&dULZg`fOn%ezrvaTKI6iGD-JSy-irOAXVD$`*BqwO1|GR}H9o1LKl z>nF}r)K5_SFDmcwLr<`%5a5kgQ~y&IY{Ek}jX41iLE*Jq5<-S!NO3m4px{C{Wv3+9 z#E+Z=r28!*NjXeaWuk#6I$>2r(t12hWl^f3d4dz)oEx2h=&+Q`=nyYeMmX_otWuAi zXm7orVb4)co64*ZFer>5fBC4ALM|9|#(CgKl&l}sx6Hou>2>TGzi9mf1L2bpQ%6Y! z;kJRB-%QQ?Hc*9Q2>tK9h;f)*CAAzu4a@r^=^rMdTK!-*^hs$W#hgJ7eeR7- zRr%8JKqk5>D=Tuga;vm)FTCij2*@E9-;{t)!6fSIsOkc!=RPFM5BzRN-bd4K!gIIN zA(x*j?U{&ZjIz z&|l~n@_WR9OYK^)&F=Az3=Rd68{MJY9uNx`F8NxGFgdy+(@WHPtb_<+iARZ!^P5HJ z7#`RC_QMp=(Lb&m;GLFjsbX3G)$TO++81Yl`9?X;?{(57Aj>6J5cJ+Y(^eU=EEssP z${hw8rl>w@y_}jon36(PW`+0EBiPl+I%;EB@U-_a(w9)ux7cd`H65{^G$|}@%2gH7 zT%rLI|0_)QV{tLoi0&lD(ROMzc23ln@qnBMYY^<Y|dFbh5>0|NZFRMWUC{K~>>A`TpG3iK_wdZcEvKEPe-)dx;?Mq!h}HYho)>TP}_*c8#tC%S|%G%;+P18F?FjAb4`ti)j6)!ZNOpM z#@~}HH%8HKvbU;|FA1NyD=!!K1p_-;Wc7HPvX5Ef2|yuhG_FgNix;0|%O!9^P4C;{ z<=%uLV|6wp(N`L2bTkHcH}nzdbckbWch&N5KnjwwQ7eZaak|5e-(a%DHO@Tx$K<)B zl-s+G^)VK^eFy`C@-`uzv)lG~>KE)Z3u}8*8B1X%dYtTM%HQ;#n_^C>Pd6c}FC;TW zoZ1mTm7W3EwE(9*RPuYatyKskTjy_3J+UVvek_T(8Isg|Iux@y1-w|vXL~!TR3^5R zY$XMaKNK09V6F?}v!~gu20|svkAIRw@{SFb%o!Q-&}c+i6`!b15J-^?Ay&0)3BT@M z?_Ry)fxCH+7Bmg~_vzhleRf|r-z&ufA)m1yxvG0Nqd?yXoQF7Oog;o5b$kQJJ%c$3H+LQc0}Fz?Ujv zl$V%Dl`^WtQaUmkm#f4ncWya#4ilrt!Zl-ix4i<&jI@?niAwW@OECIMlGV(6H^}8W zEJq*3@+VG9f8s~_DYv=I;12cn3+@f7<&2<$Np7r#Uwz-d)3+hJXa!T}36PgJO%!KbiJhgu>gmc~2!tGUkBW+@$_rm1Vr|4h*1eG!E+Z z`wbUEZ_3m6-udLOxBwVbVPL+0|L%|aJ_T@nv2pt>1`}tl=|x4Rn?g&x1y=6v_hImu zKv9T$@uMeA;OcmMd^|Ug8f?@D9EN#=S}b}4o+<6GqYstrBOxfT;8~~h@X3Kbp<3+# zC~dPU9#*c-NC;xvnD!H2h>RNJnwW%zAJO!Jzrt{r0l!beUqId-j3J7S8P-Q#d>s~~ zye9@r0frWEr%?I=E>cA+?MIL~r*!!Ry#jKV)AB5@{&I4kiHP$0k-R+xw&OMiv#h(x|nasTU2;Cn-R2ZLua4cRH zXz4y%1S8BvQq0t*GqoyrgV!Z9kH@(O0I)ZDHKn`_tbW+nNIWn1niZSS%-RIcKqTaz zhoL>}^Rn5`?hA{G?C)NiA>;v+odB5mncLnvfUZ+e(a$$oz!l%)!UI86^p!fO$ti&9 z!ej3Q)p{HQyvz*zmRgSEwl)!Wy}NY^40v76LEIAT5?6is8uW0v)m@ijBI>(4n-fUt zcNyAKkYU00$I9z+AT^SIz^I+`?9VM{mm#_9=2NPxj%-#J-_f6FXB{CW;MmQi{Sh_3 z=hb?l)KBE|J=(3-+Zkz*(4bU$+vw)4!_Y*mT&_0Gx2lzCcsk{1&|^(8GpOI_Fr>?( z;ffl!!au3O$ycxgDGq7Q3oFRD-4-QpG6Ptg{fUp{S7x)3FZS4f;myyfiV=9q=4$tZtKtU)GwyyVH}-{rdqAfb+QT9o)Z0$qoXW5MQNZ zKw|hg`!F1X;tH#`O=&)4{T^cZq&*YoI;U{#$?X{+basHZ73skWs#qT=(<^64lPla! zz~*#epUJD#sxcCk`36qxc@_00gP5(XY4BZ8ZcEvQLB{b%Rh9N(N>62@@U;uU5x z$E&wcOMZ*$2x~`hb-@(sH>=cc8V&sSl4f|f+X@^ybf@4iwe~=Vr}~ke2}X+cgHBMU z<#kAxZJ0Gj1v~?m#5UExrQvIGTGP(gn#tkOZ(x9t_LW+rS|trLLG?gh_VnVns4PRF zYjfj}iWu23?IMXm%}>cC*Y+3iui^#KDw3N702@KPW<~;ZYSZBsXCjV`wb~qk(dDfO zaW-01aNoWd_CO|ZBm@}U-S$!%gf2Ju(IA>UQX^(4((ob9^>HP6!|h$H@W11ZLSb6X<~)uNOxv3ze@WG z($*Z@w)XxAjAD!()H}GJdJC?Zj!Y;;!D&=2s3>+xVe;rM9s{^UJaLz(q#zM21rMx_(t&C3G<^*v%9QSfA4emLhWC#X>UzkMz6-eNnlarGEW6YP|2f{&I1gKi&F)U`3=w^>i zF2~<-;tqPlvOLNC!W(fs$+Mg9FLpY@s=wb)Qu{n@^sROhfAGHFlwTmr1Y7sKb%c>` zzKY4ZAzmty-^TO^cM+}op4ELk8lN3|Tu@mT%xQh!k@Q2Q|7UcQWx~&GsB~WTpyHm` zjnQhiYI>@1vxX#AN&LQW=+*CrNS*^Xfi_zCYUq|2_(MEj7*nj>|NVP*+hFTC$?K`d z@8@xBH@I^f@-|2EvsVA&x@S|_`=Gl@*e0R-^`n)rrVP?&pQd{!kC$DC^|3YN<+i&f zPtt<}v4us~>biZk`BUkGgeT((_0{;wW!Z~4|9zW@Rg0$cz}(kb(H~B$S};Pt4+6L;tVZ9#^ITa07fh$G7k3@oq7Rp6h)w7I-*Udh zt~}@NpCO8R#`bQD)~~+iKA&;wKCTU(2?NL89S?kjO5^97>)61zt3=l#G2y_Yx@(ib zx6%2WcbBI~lg`JhKScGf53~K(MW)ZY$BG18u$p_-Efmko}=c@nP;qaT_ZT*5P)%nxUE0lC#Cv8kDW=@D; zEI^(Zbj6A1K|!!`V4JY2QfM{ZuEe(IX=ieyAccEaYlMoxu$pE` zE?c&R4riFcwk9lK+CUsvT$08a`W@f|vsf$$UaWNd_%*5Du@hAgv4n31gz=tplb2T1 z-&sz9mhC=?xd?}}({ypzmo9LKj~ehl5~mK52_ajVnofZnxAdRm`xA%KY)a=kW~A3K zANDX-&Ks%c8d!tV6nFa*hkvttwru~yFL$!hmom~I2w+4?6vo`|@nKR`w9PGBnkA>6 z#BRIOBu)O4E3wsSL7kUpDoiALEIj~+IQ;{9p=ig?pB=1#BryK!;*mFvK}OgF=PcbA2Hv$P<~;hufI z&4=%`#vS;HXIZbMG4~TP5`jvWyvMGnJsYO!@wbRXPf1wtdrMhngEMD-V;Y|;o2w$V z|GfDCF>#5oH3tTLje?&REp{y?y=LrxySDk4p%3}RrV8poleJXaA@JM!^dCAomoK_& z=X+n98Rgl|8$rt-!td88Jx&M>_4J5{u#=DM?u>akDQ)b%uZHyCdlRQ*oxD?!VmT*E zz@NF&%E~e@9FOq9O~6F%^72wBs0hI6xwxF6@{6|H0Quqf?~MEDY8qUW)s;5|+IZm4 zM~pvbS(|r$h2#DE(bM7e1S#at!otGUmCJ4pTDWPMR_?ECv8>f&OCY}krYn9R2!Jks zKfYA}q|X6Zp#QYWJ0WOyx+0ITcaOWAT7bk%{P^Fy;yW7P`uM_I*hTw_a-bv81@naG zm8~NY3x3Wgc(1Dxg@s@QIB@WdTWo|}bEdHj4Qegbtor}xiLVvV8WnS{bU72UU0ps| zE&Ax^MH+RD*!7`hSJcO$&g%)L|Az(_r!)~htLN=Ee0P#?A~I&xak^_}$)o1q*cx>A z*&jSgahO(taR`jYV3La^4Pps(sWO2ao)Q_kR$|9WwC#TP?HvK4tdy{yB%T%}s|ov; zRYg%Bz}Q+$4txEf8;yE$gh-8_92>Dz9?@DXJ7T>04J%`3Jc9#+@V>`A7yc=EH+{MoV-$-zwt@f zWT>poJ81S&ACq> z6yqC`rH>#_iT7IUG74Hs7Bo@^j8bMui%X=;06<@RF`GKS4x0hcLAdHLCGaeEo}Cv>$z4+V1nI^}b5h{mkQ zJbg)LYCkA9^Pl`c0df+;f8&uDOS}+(>@?r!z~*IQa*K2FaoJzK(|Qd27Dl20(Q!PE19 zW(R;8^)^_gVJV14ex)rMJ|mV>nWYdlwze{jIhEJ$i=W?1qF-H(FbE|C2p6i^!NLw) zTwK*5CNv;HA)&i0dJYb`!LA38m8EEWV-6N$gWS)L`EfO{Tk}}8JHJZn)dQTcqqc%r zu(|uq{&tp2ey%x6Aly%u>gDzR2yw=yee~8_8!;EI8;~C$pZ{Odh`P2vx_a^}tf4Jn_BNa5XG5g6z}c-mad5BllW;U%f-= zX9psGmsa=iCU>_epRuF)xpHcKeaIYN9$-TwEWE6pe^FheAY(5UOTFQGLTdX*e zV!DWG5}?=y)})4y?xMg217QI`Mj17MQbu2?<#69he|dA5m`Ly|?^nM+y*K@m%?o@a zh<*eA|9AYux)HP}=ryN5yUTUEW8krqX>u^GIIYFGN+hwe9x)dm#2TxpvzMHhxX-jd zuXyCiy)G!aljyj0<8FRFI6%B+&R&+Hlu^_thl{o+MpZyMxQ5L#8-Ixs1upuFIJ>h4 z`?FUZW>Dk`M^1R&aZ|eB8JEi+=Bp^Xc>H&66PC}_f{nPqMlLs+ixt%G){qO*N(AmP zj#*5OS;YPD(?OOm20xlf#drx^#5-QV9x;ZbpoV%bUSOrx$O&|ZGN4uv3^W;~x)IEt zuL)u1+2p6zs`atVw$dhC24u_B<}M^gA!yw6^vzB>RE$_E?P`*&Usa4;#_{p0_<1PL z?#o`wvHE0h*aCY&+~4`mi^}b>m9k}3ilLf()qeb4CElqA5#g*>!54!cIg<2y?{DyA z`k+Cq<#hYyKP#38mYrv|63hN!2Oc1rADbQj56OWsf-a$?WvS$Z)LV)(dbqYwjn$rU zPq)8B16Fw;w-G2*;0phfRLNNGyS(lj-`;B=mLZ%0czWtckS~UC8t|w=wu-2VIGMMQ zJS+65C`np{e1ppeElB3!0on~8aO~-_pOonLXGZ4j_ngGPc;B!THnBS{z@qDG5-_2Z zaa17q*qtMJu4agv+S~AW0F*ew|3dl2w02(C_1Ig6$y^!u-7|3Y==_Bpn14os4?o3I ztky>Dy5x|SJg|VSO$5gG>t0?KczOSpm%lTB3Vb!jtfOn?`S(SZKUTCE0Sq*Le$Ulu z@mic5OF>_;szNJ;cUB%%m0Q4&96+w;TnzLE+cpn|c6LVg+CE>WGGmiTLPA1x#&Zo%U5=_GkYMd|?atlY)<%Gb2lQq)i3_>JFAEsd ztkHmcGdClI8V-6dQLY}iWhp2&a9gX>y)5!mQrW)uAWZVJo307LlS8kHRKbi6UjWq?Szz*Zf zgBUa@3XIA$oc=jNI|D8QbAdz{(d~9f6-%)dr~~#iybrawI5mkru-;#N*VTZUHZ=IX zMdD-$7?=ag_kkE<(KWa$L?{SKF&FLVu=WN48ml&Ai{+t~%Nmp3s>d2YauRC+5Y*2q zn0oIRu6lJ|OH?vuyb$90m5yJIodkZ;Ssniiz7CBg#0Hy*qzk@aNl2u_j4x1 zH9K?)05PiNE|*)+_adE*bD2D}QGp$+=oh08S50Ue7mwxL65}U}e;0IPBrbB=5YjRG z?Z@Socf@H9fUyuz+6TUvKlrI=ls;y{2Vz5{bTFli{MX|r_Me}g@CgVI;o*_tU`$Nb zFD@=RdB%X1dXHoo@$RLdBhG*&8AV^^Cla!ZQEOLk!>OLqTU06+F|%y3zYpl*@01}Uxq3g<2k;U;K0a7h_ITyY|6Heu9q^OQ%zWkY4y`ch0`A~TMG+acf9tie?uCs zwKb)wT1O7Q7*eG;U3njiQ+{S(<_o8rfHm-U;VT9=7^<$x@($+%8ZNQ~r&_6%ou!~U8@_LTs{f9BJclDJKD>*BDlIWA6n0BG1aEp|Q zre!--nVhy@BEawa)RoxrjFYcg1r38h^F-$V=rg(V7y-~54AZ$7r1rKb>s_G)hAbBs zG+3~V3XX)fD7zX63)795o%}L7jxDxvQo>cMuzfo@7QU6{lv>9N(w08BN#s>#!~7*8 zQsTI^Xhl)nXSo0<@w5y8kaa$v!HwafGq2n7*`_EE3zXl;+ zHkyRj96;LOXi_uVHQPmjNsZv3eE1Y1WVDcT zu9fuXA>PhsxFQ?92tkcuh=2BG!CK=t`5~QGt($bOf@lR#56GE4&q&f_^z)c=IsVXeo z2G|b_Vu%T{X2?vTE8fc8sJ?pq!<_rSoDL1>4G@0mK2={3fBm&No15RikieS3ERQRW)wdkY_oo}uWj?dwdeh3=fQhx*;gOjT&^c# zi;-sVaiEA9KoL}CQ~kY-o0)_;+Kc}(1wA=?0G9CqI&!<@QRlP$%WDZ@PSEVsED9H6 zWM4~;e?d5YGF|egxNi_wallTez*nCP5K1?KI-0NeUsXXj%$YGKL7TePXmM8}sXUx+ zm9xX=z>_RQUEKMlL7;wM&I_mLV6#8>PyW1!pm;t8e<+iFvxbe$e7EKsJ+NRf0|pF8 z3R8h4g~gd?qTN!o{LF=@_4rveiww{3EaBeeWL=&0c;Jf!Po{eB|oO@;>ndPL=v z)Qw3UVOpBz7t`y)FLjBfG=qq_ajE@EP`S9ADA4D9e}@v?i^nYIBc<{z-=1y!B}fZG zLcF}yu9Fjk7UPLXiKBy&bEAthb`+Bm^H{xFg57xyq(odtB)g2{b2;7* zzaF815N%Z-u*G`W@Sn@W2|f@iTfv9AG?e7o$|Q{7yUl5Aw({FzL8L5OwsFlCKdHRh z*XM#xqy#>3%|bzf^>cuy?pedZq7XI~-30A1l)?547e!k4x_=?W%|Z?*;&I386oXFs z_CiX*9(UfK6Y33lSke*W86vll4_R*<#&8gk~%mzp@p2pjZ`bahkX;!F>||6qsa(`89EtUQoyflyBZxf@`H zbw!+RQxib?LOu3f;A;xaG;DV*^9=|CZf@@_sD7- zUkNPZMt1>Z8~{`Z6`FffZSJBMz7alVq^q#dQVKcYC7cxgBbL>5uX(+knJVc#2gM*pwJ()~Wv-=V-{cYHW`>6s z$9pCRX2*i0+$~%soi!T75eeI1ZRz!w5#kP7U+cG<2G$=iS{_MVc3?+uou=^1;qmW; zXg-YU*eyu?9I^C`8>&?68QJp6)A$DN&3lB{ZvA1ZH^W$}$!@wOtS)GM6jke&q7iaJ z@3JZkC?@PQ><7sg3t0aM)~q2w4_^AglWSBFEQbpV*cw3$eWAK<=C=F#Gn(B`DG*KA z1$HG)nII>?2>oEg239*03$i4vvHVooBWE_hU3!NEw(CH2ZlB(|hrK9D{1| zeXPvkf~`sk&X@z#z(}iXL+Sf;*DGnfp~Hg_mYJ!PC78H%Z{HxC<39caOfaa2BO;9i z+Y;Af+Sk{I{+s@U`Xl4CqWvCgy^}+QF9uBnGM?`*xoR6LTicRPWfj0rd3jV!%)n*} zm z$>+NqXG@QDCZ%DRwH%tk_DHOU9L5@aO>aF;LOjLUxY2z9&-^#G;zN_;W;6V^2PjAEAl>fa}VoosF!fqkh5B`DzCX{`kdy zXGSGukr`w#SAw$4;QIzqV$2-czfMd@h=`1Q#*P3~1X>I+lnX9qiTJ+K=&P#-5uy4gllUbdYuao43A+p`7ds@5xd#aWVA54+3;+eg_Mc_Hc?z!wm zja6r6h8W=IocK_-_Lwq(FDFZpANIxLb-(IEaF09Y$Bjj5j&QJvNAMNZ9%A(rmgSJ0 z^hKXHY|_EPCC=X(h4{JFr_@xSska`WMZSDWEnCm+@E$&US&wU5rzSW@7yLTsKE`IX zOr@o~0@PFj&7d*ybmv^eo@!{R_Rg z4msSaChSz`#g{L}g0$jfhSTWKq0%HAhbrLg>m0zP60hZvb(vlEz|L(Pqs=Yx_4MInc-k=)N->O75fCn#Z&$r$R@%)Yt59#jc^%vgfo7fn>Ln1t5oHZLgQ-J~26hwMErn>(Qz^&UWsj|X zksf<3$Ka@%Qap4#o0eu^B<@#jYBvGSFL87j82iJsxo=R3t07=|J!oOyI%f;Bt(WS} zUNk!hMkzSw6`jMY-xSXH4vFwG#QHN_SA{t2?^=Bx_3)8(zHxF7-V{X@<%024Np(+T zviI-|>;yxSWjZX_XJ%$wul0om>*CG`1%{9UK39UJ@l^H1^z^&(h0%!#RjNy_c42#N zLbL)6JzZU-+iwjG4M2a|oQ*3p`R$v;3sc@oq=yT-?S%a~Xf!-OoMSDUt;zbMu9_em zXnwlDzTJ({i&G^JWcWcGkWaN=Wbao+_KMp$yf8IR|$w46Zp=kY#_B!vn!27#yVqq|qt z(oDB^cge%MDA5Dr92^V)1%``@iH^?WXlAFckEVi;Q%ESZ$5gEkckmPHe#9`Yd`{;b z2?o8GSSJt?C@8wW`aGDx& zlgeskAm#SB_c>)vEa2+Y;N9m(4zWGjM^g?MRY*4l$RB&?@^cscUvWOEJnD}zguFg8 zx^*=;ECZ^wwe=0t)arDS;Tm|IF`}x>T znUv*ggWTv)xoJy*p=H3LP}yjV<0)wE}58hk}eN% zhchNg2V$WL!ddfhwE`VwkUSe4COtzpu6%JoP-eI;MK|0^1!-1SXwxRe?G9<3fjHEX z*MIj?$n1DdXG-T(*9I+zKR1&JWvi#6SnR%&` zR&fme_MiN@qm2QXb^0+o|GI|OdOqs7CGEu=(n2>y zM-k9`hVCjXe9QyVvq3Dj>Kc*jweQX=J9Lv#U96yQNOddT7#sMPN#dUrRbG1N;b{lHXLHXE3&jG`C{PL%68N}w% zq%j*0?1kN24kP(bbjvucT8oRS**3OjVgW0_*PZ_{HrV6(yW9<<_!eSUz%bRt?Yv3g z<8BK3;&0=l!*&T8h5QJ)#3M+uJMI*B5yCwROTc|14_RzxhN6RGAp>sL^TxwB9{e%h z^)=f8aKaLf_+lV67gs5})%>*-xnND{xX+$_SaR~dWZvtJV?INAQc{SuJdpafTII?& zYzf7PK(W$m+&MmOCDngvUzC5OmWX{{h7dL9$;cEm)(J{60l~YJpPHRnTb{k!XYHx>5VTT5Y zf|CoM1_lZNH>MRf$l!Lt@85)Ma3(PJXmAh&K;ASt`IENx<1_5g5U>!ikI^W(xl48y zAYt>k@Dd4UX!38KveEO zhOI(@LWvd-M%dXIBNQG0wYrJ@OE0y8QL8!t??r@$kfiF)mUE&d4k@R((^k=(ZmCLn>sk zy4q+W1RU6@Ccz=OLmOB-g~Gl_ho)l90h0y1;`3l4yLkW>q?7M=hJst)5O)4x6dyQG zSHB)L5uN4x3}WB_Cxp6fX>ir7!>48@UX@Owa6b*-Hf7~K^HTL z0vjx-LDZ}G@g8*ttPGue_PA@)YdE+EcgJPL zPN3Cf?#2sGA;r+$_d6U4V(u;;q$-pl4Fn$-US^i`oVd`I-lkmCxhuZ*f;y?zE4)1u zwsO@KXm}yGGMra)pV zkd08^G}P4yv%-hMA^{D<((1`rB24%8;&|~Z zH`W}XLNK5)kK-hh4mOxicVoNHR@)l%PeV`%jNeK+X}JA@kQ6o1j zG|qdS7*EhQLp6z#ih?(lH;#_+%zOBq`tp*!3a+^M&YWU|<%!P}bTiL`4O|1f8a2rKQEQmiEWetNe>)ds|TE z&<$JlR`E&)%HJt*sUPxadhVu! zjI-&KoDDL)@ia{a28InbgUwFwj@R;*#JhlRCxRhF@}MJ1VF)nplo!!wZIj>v%g3H3c=F?I-IAH+=z1v6Lc4IDvR;Ve^*zfYjHNp z%E~G#F-=YP5_IeHthgvLfG(T9{)b9%sAxxfJ0SE0*cbq3++-ex<_KGYOgQ!+K_cJz z>2U5{$B<3um)cEW{+sN@<>h0v_+$LK*Xy~F*}?6iEjKjzNNW)e4rhF zzjx&*c$>f7?mAy>jakhbv_x}4mUer->tN5BJH-*$d~5R$d`~=1saorNN5?O-R?d8% zc=c^^TyK3n)RcP7nE+nr@_2VzQL51PC!wm|2g)+U~KH?h3{0b9n|WtMo&H%;sy+)F=!+Zv6qRWCbq8m2F=x!nNv-1 z*RwgNi(a70h9IF)O%eo=nB4hdNMfOJq7ywW+0oI_Rbl%2Hy?hbPAbk4Rf9-*7h?6t z+2FE6>mtY>ElsxA1&LfAWO4F$$-LcR2?l!p9nb$=K-|K54Sp<0_>G1}itug6bLcj& z(6n?|p*|qSYw^=~jOGtbPucZXWZhQj*NyVee@5`XAz9#r1mz+z0`gMbx2 zbs&fAD%m{Gfp0#A_wnCTPClJkj_ad@DontJbI>FdUG#^V2mh+>^ETl3l;!HjD|<$c zv$5e3=On#m{{p`>JSHnATV)V%0oC&2w6owoS}_Q@o`+%n-Od%a6N8R4*Kc_oSDf`~ zc_1xQ&~hzf>GbzM97SAqEdD%9(n0C!-;RBw3I7PcE4XVrq2op$%sTI&;@=pSZ5I9V zf?TxUzVoyS_w=T1K%>Qb!EhNmt!SzHkP(*pr+vM3+&gPp9e+hfyB%MTe9aq+{_NsyZ3C$TWzzvToWiLw;O z%@ZMIuY1>>ZCQZHL`q+|GW^AWsoX|t`l`G1`=4fGF|=%`e+HPU*0S^lB#;;)VXK(~ z_2$(VwZvaQK1}i=eWk^RjxYXH=6}EH`3^#T8;kUdm-~4j{b609p6#8rwc-uB&*>#O zBJXD{mx8yTHq~Ra^sTF4lA?QMtw&{DVXnUwKd})R2?^I%nxp;m#TlWR@{x*?5;kh; zZN2znCA#a|(~bq^jIkI9q$i%?Z&p}@B3&X8>8f(`em2p$ddBu4t7WyV8$uR2zu+ql z_@~`=s_3kRys+TMNdZr{;}_&Bt&(fX_+IGbuOWX9QDtY%&l(j*^7Io_6Q_!Jt8E(? zj!{hNB(Xc>5?v&{whA{++&5!lCwE7wQj$W?M7BE4V{B&CFN3D@Sos$e*9x`9rP}k98wo?RQKBC13Q_I z+v{C#lLsK7ta0<2*B2f`wv>TFpzqDprw6_I@@H9d5Sp2pO&6(#l}=?#qhFv2(uZ;S zdf3RzYv1eV#U%j;X~&b>cnBqX++YB>(g9)8&5gi1Y*mZtKZRf$8=J1*36d_6G-+eB zt$ourC&q*1L-KqXfL~nzs_@%1_2l5Xp?>=Aset}HCaWu=-sQ;h`g=9y5J|p@u6sXy zEPE1HC?@fMO^esN8so%YIB$ny?Muql(W6V9{k;Nj;h5v6q9rwMdgZ%PI|R3r%WYTh z>|W(i-*JKaX++{$FOS03HM&BYoV={2Rymd!u+H0SPY5k%J>cpxT8w1nb}NacDf?;Vq<6rUF()T8iNTeJdonhJ zA{kC^v)!}vP;BMi(<3=#ivCasLDnvC`k*i?wyTAQ9TMxwowgxZaM-uckD#S^GmP0Z zr~Tt!dF$Ebk`1$@*X$c+Tl}tx@OjRmTtch60|b&rzYtH>!1ez2$%3OF?W1k@uz-i| z^&vZ1r-33jFK1HH!BI^>8~@T@ILZ*mx2Fu(ig+?F68mCj;;Pq~#m9^9yz&n}Lt|V} zN<=QJ&f=jb7TioQBP(q)1d$3Gx-1q>Qv%u4q9y56(>?YkdjszLou0sO>qt0ooSe~z z|4!#Mb9zn0Y!hQ7-BP~W#Sb@5kBc0^HGl`*L{Gn-sRpz*RSXEstX+wIekm{VljOZFsknN8Uu!?|K~*tdBlFA`i{F8FcQ zeB(H*D?_U;Kiw|UXB(X2RRbi(S2>rT@ZC2*7)!SabZI4|(#1sWKEr>b%3gB`HKF*2 z2^3$tbL|rK=7@Ilwto&WW!D}sx@-N<1*+D1ZH#D`?4X|dnoItC!-|PbV8qg-WPycT z^Y9O?zQ71N%YSRbo6luM1uHhWcx2uPxO?85lE=H|1poSUYT3w&{i)$wpEs$IHYcUg z?SAm$Zx~;tmxMxAc|tnB5b5Q+;F=49DpHsWm6rf#Dw$7fDNZK7_Ho>9j3$}&Ir`&6 zO-!YfrQRZ%ha_fUnh12-M?@YXs!2#P{x*H8fl4}HRJpr@c7(~HOXi2&Z!q4iP#ZCI zJ$d!fZH|i)AvkNjE!OXaQ1G3o_PP8xVT=SRSkv_%VFd*Rcz<;U=f7{+XQwzG2=jQ} z$glm$(D4T=8W14T?`Mgpeg1>GSVj;5PNKQy%TvCTFzrJr8|^y1dm2>9lp8ff&AO`?m%$Pe1oxxDcN&BcyX{ z5%c>r)iW=zne904TTkpb3M+eWXOBkI#auVF{AT@{g(?pJ=U~-NbMP91iFp(_LZuzNg{9ophxi`TE<0%Ds7CiW#A2;X2iUv zy`$stWxwj<)BeXiRkHPreSUn&I5Ql=_($ba*Yqok!)>Js7-E!y)MZTEEz!evy+I-| zw_;5X#pEzZ3A!Z3^<9SNhxQG!_pdCm&~fQ_J?urT{+q#fp%H{~A|)f*Ifv^(gj(unUAWLE;Zf4&Owk{lJH5|#)4cYZpv~Qti?6aKM z*o`3Fa2!vbF1y0lbDHk8U!0UC-`xo+@7i|4xxz^*Y2%%5^!ndB=Hvb|(9HAG9}P}o z#&1fog}x^dnql;IAi(pVdK?xJ=OCJv53WDDOBy9;OzNAe7^tz3vQ@3q@d2JqP*a4H z{A*-c(hr=YC2QVq1?aL^+{e{MKDsY<`>z%Hv6~CoUm}+XSWQ|?KQ^YDhf;)d=O5)k z7rk{^r2W7)Wy_x0DQ&!KOt&mq{z`mQ&s6~%OmT%`^yP5^u`r!7{JW~QQEov#Lt|+{ zM}?5V5dz;hWUbvvx%w7vV#rqc)L~;Ys9D6cButY^78lbNBV&R%5w1wY-i~w)R2tJ^ ztQ^Ns#>W4SGcWr!0jti{)1+*XPKZ+?TPSNt4_bA^rH6Cd&43APrfU&Gx(;?15QkRs#|=Ar(kq<_cP z&Kq-;iR5?TC!@~pbnw{5cDa6!OPpunKPzI_r7g~Y>?O$+7DiHY&@d&aeMYg8K;oy9 zOx0#!bb^z^JwTkm8u#OQ8Su>2-3MxBpv31L$HDvbt3*&DhY;(}Ep(|oN?|&jVeCiG z!J_~!9?47~Zzx6ajq5V#cV;ylM=htthV``Oe5*XO8aHGqwUMd;yO>EJ=@kAjoXFbP z1V*Zu^D>3a&R*TPNM+v`<;En|1C2Auv^cSj(Hr$*#RcIr}QF}BrN4p z(=O0{H|S7l4{GcXZ+Yl(25?X?FGCct>B#=X!ssMrK!7@LMt1q{>F}ZA5?G3)*zfU- z!^`oo5}?QKmc0ssoP@$;{~Tos_0;|rq0~F-{Rii|l?YYarQcBh>;=0(IOP; zoFe2l!ofChA`5Y#yI#~J9f6i>H0p31PRp~5PLRmPm6GXyH%XeUFb?Pag^`!R5%Nqj z-Bp>(uB$u`i1B+sb-7!M6Wuo?aM_v@ z_`ARfWD0F>_}ASzAXBIc#|su1f7f!OSbm3zXISjb0j6&@ITk;}jk9BM)1sFCNsJHw z0;G3V%8Ox2HIKn5AOj}PT!27vcYBwNZm9s|37+78OOEmJ%H>s6j4Ui%eLrD|BpGlK z5W{XxkTr*{udmU|J_1uoz~rJvR|1BJgk)->gHTFUyCQ^PY0+PS#{J&Pd=O+%(4HG?pA}rC2aVI_QN5?Re+5oacE+EXm(MmbXpy5e z3acoXG4-C#NxH6XE?`ZlocyB8MYum|kGYC+L^Tj0m+|RUxMOV39>kRbfNa>8yrNv36rB42gV&GC6JgHtGY!NeB#RR9#f7qrDDQUR81~I zpwZsj-Q5gfrv*U(l!dppHYrCICem5I8APQ>oF8<13m>7SrdU6NFay%Qi2;X5nE@Q! zPi3#sLkSwj?D%(nNi(jz&0|bW;5cQo@>^hgTFkITuBWXD~M}9TE-NZlsSrXGMnN zm^3P+E{!E8A9aQ0sm>Tv+5g_Lc!w11#h`NtABEXO7xfWqI(LALKO3-CK6k8_AH%Lw zH~W`QQfh=CsjWSjp#H{V6n*hOYhcJh>srA$4=pggV90ihBcUvd7&8tgY z5FZR@)4`uX;K;i?#1=BvqD=!DIT!xINlYmt1o>R`76`c!2B&U0BcvK|ph;q7do%^q zWa;vAYbuRF?q43UB=V${lm&lfyce=VE=E@o$U-&822iaGXGF38`-kaJ-5jDWO>dOm zNJX-7V|-fZfq_NR4(QcZ{gg(7vVb_l(r737sN0X{O2qgszdX&E4|L<07lHuCWhFxl z1JvU5)#Qr?gii(+H2!^0M2wIsY7V8Y5GX2I<(kcfkN+P{X8}}Y+jecb zyQRCkL%O>|8U#t{mhKHwA|cI2N?H(*?vQTjmJUIr;lF&||8p2;a2R1b?(;t5SZj@4 zQ*b`v-=5p;%>FB2VYBYP@Mz?qJg73Jhe}2GE2tWjd0L^$DJ&#U-7EIuW^c_9a5lTI zPe4vlV|+DOp|J8ZAScYD31l9LYZ&I{oD>k^MIDa+!fW51BtV%J;rN2&twHRvaVl~2 z_b(G8)e}bY{@P_V4kTRw`e}wi_k+CjrYRMnE;vvx=0z)gRPwOm4l~!;96^KZs4ElM z9;NIbijNAdH?^K??#yEkLH^z2VT08ZJf|KmIOz`=iac*&u)rx^$;J=^qC<_Bpou4) zbOS0g**cWGL-h7B1omJT6$8S#)>q|D1&^Dkk zUJ7mWf}y_~XdT~^ly!N6k!d=@usWFM>}HXJawAhY{(E)QUn5zy0k8Hl*FAuYv|m+? z*p3iR`Y1;~{G00}wy9U!jpoi>6Uyf%^!eZ5v=;W#>Nx_@eA3o^Bw z5P5T@kTBZ~r9Yb*Ha_Kg6?1u#Ax~Vjr+XG#=yFi{CZ&sgtPi@5&m>!j!Kx|4%$S%v z?=eX4Z&Tmqi-yEyZq-hX3ap0>6pDZ2JEl%knLAudT})80taqr>HMJX~$j?+OuL`34 zmlqfy4^?Btze54D14tAs*DduB&MBqU4$N~Y3_IR-g)W?m-Xr6sIsR&dr{qvq5hxX= ztNT*U%1P5vUCk&U4ryke-E~S^)i&&29_naH*{y#m*RPzj1y^XiX+d9fCM&0y{DbB1 zB@yQ0HI>b(yj;#Nn|7+YTk^WqOXEx0oh^NO_UZIt8%O@Ei#U&y72)ZA+{g;0o*v-o z+Oo8?1TMmXDqfXPdk}@_%o%(hgh;R6HNUwbq~KAz%F1%)fkI-3$l zMOr)re(9P*cp+|De}L|`HLQ6(?y}zC@w+5Gz^MGlhu!l7sx=SIF2=x9o>wsM0&;TS zAIyNh($Vxm}4^P7p@BFm29};O+i$H!8DwD%oU4#szZs@^LxIdCxV}1SQ zp6V_FJKrh_1dD7S)3?e=CKOJ$OENrxGB4yU24y0(2Kl2)@Hd_zavuM&`frLNH@$%rad!FLaJh!=525`}sSBePCIv%!Pd z>DhmwNmBmwG1jydaB`j*=uXCyE7r;~am*x__{7R(60D3`>Wr`scJh2njdIN%OqW$7 zf*DW6GuWrX@Zb$nzN1LeZtA%%j^cSWB1< zS!vXB3>nLFqsC3fVr0#3(J;LKwCn;RDDkQ-TBPOk(|`0)0;W8zuIcIug|xNUjBG4i z3n|Hu1Wh7aLX{sxc_#*GvSTRKT8`Bc5fq`(vB_($vdQe~`#?Ibm*Y%DF zuc|jOJRHu|bwh#x2ZuSuZxiV#ldVOnOtQApb9UKe;Cf+lfjwjG?xTU$7R8I+rG})= z099qZ(c`TTuil=#dbOyoKKA0pr;q8>rAd#+iQ2KQMzc8zUsx+me|Wr7T+1O*&z}tw zrcn6Fg!}fV631fjUrw7x25{81ZC~yCh2D243{}a=`QS1^oNUBy0J2cQ`RW*ovNwU- z^e)y%pI;8z-`@{lp6HQLU^BqRhK`EL)8`gI&lrykK zM{Q>RyP4=K;h_l8A95;0Gg%ZLbhjkL(+pX*#c0QN*wHMn~PR;pZLh z&3yY;;i^A*JH3$nSLLWFf-$<9F~y(6@S}+{B(Vd>R~ZFvthnK7I#NAgAgtXePh(qeccnqoD4MW-+p9Oik5{!e;8VG+?q8DXUoDF-I~ zgAuHxO{S7~PZh7DRk!2-003OM!VJE2Uv}Q6@fZ~C;<;qwetm79e8Tx5bnCNC99cJf zncOF5O-qN}3DhJ++1-pH97uIYs?S47|JYeF**a}ZwVHWrzF-JuO$P;mhPv9|%PoO| zah7aVdfk=tNmT7n_J|&TDK}&GatC?48iK>*-JqSnNtOm+3J=>LkWFWqk=h46p2$ry zqlso7f4B8ZwH#l!hA@U#pV%=VcVENlLRI){^mP7_)+N0=bW}!Wcal5fNkesH=_ZLE zMCX4yzOlYSp6;hfY57n|o|m{LDhx+2+HKvo*bEpqm9}?JU*fstppqwYPXO6wOLzFT zRBt!&q%V8%(YsTa{s*-PQ~Qq6$Kx}AngqT~uw_3b6GrfN)cjDhS5K#1uCV<)n*xBB z4Atzct(Wh*n>Vxq070*SM5!@Ip*TD$0s71O)xVde2%i&>AE07Q6lAGLun z7-e66L&F7tKM(E3WoG^?D6ou@0hYS@1#(QxKOh;$fB~)*EuA$P$okMF=@pEee5GpBQ4AyQK5swVC zvia4c7c0lc${HRKfqC^Fbbz2GbZ~G`kkKyGqR(KvqYc79g1=}5Dkjj#Mn)pUN`nJg zO-=rkep#f>y7S_a%O(fiHEAFyeMCg#n{M}ajSH6;NV1%UO2s;8D(=qN8^-pExK~>% z#ahgk-81W3#B!xG4&+!tQ?zehEq)wTBZn9m8kQCpD+gm+@Pa!e9?;)AO_E zoin-lz~+va_kPWLIF-t!z3wwFUr*A+-#=d79v)s_zkcKG{ZR9cc8bztL?aVhV!F>x zzyK59n(=&!+HR5hssla2d#tMfF@>4wprBi1GBO@9V1mPJ<$~(W#W|Dmr~-$3C{M%k zmq98wIyIQ-ZuhCg@aqm!rTP!3QPj$FnhyMYX>Z+}dbG}~;;H#*XZJI*;8|m2-m*)? zncYTN*ufn8lC~D1HEYSo*T6i!71XC6sd&L4OY*f--f3kxlOG&NthuW5N!NG zgdfT{`x`_vHC3dLKmngzwkwC8J!~+}ndy%;BTG#?qF=ee?P3b$u7KgFQMB`kHE`KI z?%Y3r+8bJ@`UiP0zMFpCPc+^}*b^7PUm*pTQZ^ey^B2k*7{)a-t48fzIq)aqXzepa zn~m?4(++D1)yfSKpU%LBGXf%bT$;50-;qFY)1S~!gQgwVlR<%py6MHN;&foaina^=p6Sh%9XOQIsnVP38!$Yr7B)=>(-8_J=2 zYL94YVLm+9Ii6AdqMEA|?c1LRx71hCu`C}yeq@MFKh>c^QuAN}^-*}~r`XTtW>Fy0 zU{3_?mhRnGx-GAxs(dw#haU%ix#mT3|Irj>K`KhgiCgqHMb6bTC1j}6vxL* zvNjGp?%`?QimP(JVL`r%x7!pvNy)KG^1x3nxA^=9WAXpU3v=)+dL-L9N1i9cP9d(` z)*pjW;-|r!G>PIuPdroh3ftEFnq@B$oU_aV-}$tmn<16C zg_c}4Z@a;&U1vm&hj%xdQfK{fb{1n0G)eFgFMv$3omP8D^fnME9q(?2f&zC`il-MA zumj3VOYQD%Z_EENj#YYJ2+%eJ2*}7xOiY%65BMxXh=4Tb($AlnAk70B*hw5&kry{@7zKnvtzAenmfM1(oQ)Zn@77P_gjMp%k;DkXwYQ!;x;V-NX26s zZUuB5tpx?te0=rI&B9Df$ms|F%VjLHDK(XLcKl|a=g@t${E7|O)G!l}CO*&l5aV4z zg~x?_$2)X;t1RZXOi)ppDgW3f|N@WM+ez5rK%%LZa2enrDo9?sAZYMR(_C4JF<20tkVPu>obQkj;z%DrJ@qv{NKI&YKi|uaEeuo5V!;*)Ih|LTL?&E8=O3@S)79l|e#++( zBUlT{W52h}X_^<%_?C-uQ5ITj>!k(hjfik~YUGu#zDREg+D4 z9BnLfSTDr^oz_{5C5kB-1-M5a4;{O=6^NI>aqh084i?KKYx zx~a7S9iltE=;)nbxwNYnecHlPSe&H|9xn0s|EG-Q-v&)t;u7F z2u;;#^8HKx;4fPEDC`k^0Tp-UpI~(78~;f!vawRIExxr}(s|rIC-)jMxxSPeNCEGC zf^Zrc8Wr2GFJtM6|DjWe(+XdJJ_N5Q;d}9iyG3hZ0=JlFQXnfC8aEHYDPsgR!{4?b z&w(U8m*a!hE1=<&^T4nG$8)nx=VXm)Stv`vDHyj!?HH1CPdhjKPGDi8n9ed!UaA|l zL6+Zt!s@2?m2@_9u4Yp6@b&r{6`;)9kNHERoBj#~%pd^EVsc67e8S{5Uk~Yae}pv# za_RnW5$@KU$-&570K^~O#4NC%Gd zUS>L-J;Y>js4{yR`)Iiq1z5A;W?jkqcR~(KuGv5+Gdb5wWdu(9p|ZPa%6L5VU#4rL zm|!@XrI ztehBMG@d1oh5am>Qf3lev>oV~WbaGrSpd0wNy){}kAaOV8)Dgz5=BLhg)G1L9r1Iz z;B~EAO-sw&j~}d(l9&&Kz`});ln8u~kdWix?4MD=z?PAV0m3pPV|GL}4*KEePvK9a zip&IP2ypM6J#GVoLFVn-w;TibM~+U?A{q}vBO}1gK|;c#e3mTVMiP@XUOq*M#ass| zmF4%FEi!Suu60K%XQReqzQSEosh6M890tGHC zfKa%5;Ye+f(%XB0PRv`XxlmFpo%YXh`>bE~z^g@xUPV)ri6`JR_Re)pjN05fuM^Ij$3`fPaeX-uK+^1gENhg!c4BdX3j{Bj zm`{(NrxTm%yVl`q&cE~@*zn8bSkM5K4us{jSq8E5V{*imc+Pvn^=ypCa3y zg>0_fw=UFI<`JPENclx{$zL#?W5dnwS#xDgV|O)wW-p_X17M@G*rq>Nb6uS!vppl- zb*sk=)u*FY7)$-V{z#zhhG1Cz2GU;U#TX`s1R(A?ccEe`F-NponICL3G*e@lFqc3= zbI}QFX4a1E*1q&flzvIxa50bmYkWm^L!b8x*fsgu zt(cOBr2n$>J!;ae6YT4#C;3gDz)^zO!fP%#LT;-m{n3~>xW_Eot($U@EhuS&d!9Xj zT*qf3XQ&d}ZpA%LU5CidM5|UcodAaEtWY06d1Iq($-JP5`jEvFwEE9^YU&@U6c-hxZAfhfCZcmW14w_Zn!4}Xkho<=o_iwr*p4-|V@deJG5a8TtY zgW?sCuaMhpFk?feZ%xjz3;IRb++KD01pvcDQhr)|){inB*gNFQVny~PE0^5*(#q6zY7CJ1UxaY4?3qIbUsylfaZB{~A zDE^!2vWb$=-pwAWHJ~naaF}fr^sr}sOwxn2yb%^2=VQ9NJ{4Iz;{9&wqNmpYAVoFC z)RA4S?~vWnidjbsNy!9-?V70@;K8G)fTTb7<1kyEr|u~sAwfXEn>CHJA1h3%s~4+m zJrYlYNVRl}f3_nkGLm$PnKJ`)F7~l87|Q|z0&Xt6pDGt_uf0EXTLLi2R_Bb}_u3%s zYh#OX#T>9%3};mG+volEU6zDEj*FFgK)yxah}&?{-`1T1n>Oz)qgn|i#HSN8d+hJ^ zwI)bO=ug~v|G9Fd^5G#I^g>kzWZ)MrE=`IO2J!gbC2)QQLoE>Ro?n7=yK+4VLI@)h z)8OFX!u-69V>Hc_6dgS&!Qqskos532_w^^A`<=Z~|HMC@pbQsk;YEmpbrA*<9Y6m+ zD=jv*ky;(cCNk_BcoD($4mTPmE-nVX`jV28uU~b*53jFIac((4VMP;uFjHCzWIhhg zRtq;bH^BF!7n7GVT%#06pT7RPTsCx1>fa)ifdSDVS|D%;)`*LR$7WyrZ259Dp9CV| zA6TCVkFpx-1R-t3kgjlPd&%&mG0n7e4aF1Soq+u&rwOY_cbVdj9E^Yp@?QNBh{aT0e8q(9c6y9WAtr+ZmvbP*9@ocQauNjh)9p1o2f zF!TNoiCAM{kEaX=LKXn{YN@e~ZkNS-3a zB)+3WIS33Su21iK93dsC z!JJBO8%t+>8w~5r^}_71_Z;0uu^(Nh1X5}Uy{ea{y%kgw@CSmr_WPl3RiC5v&))!) z$X~c9Uyu&`C}>foppjQ*}D7IZh7|gr~ ze~!J5#bJwe*gpIPGgnhauwlHPnrDI*m)giRqyIDTS#@Vgh&nfLM0*;Vu#zR%WfZ1D zKz~(FzvjiboT>x@3_ZQTn(EU{!Ty)fV@$?jz>?eS6ct~EzUEvUUG$v40*XNxyhnl? zfvUw3dvJ)TmIo0$KjjJ~4ZMILxz^k+JO)4EloJQ65%sx+B$PjjnCTeD2y)?YtdB2w z51foD_MW{2h-2%zkIDDcIc`I}wb*~U9%X=TR;vx~#4~GkA8Nqxzd+M)KXD8ef%%4` zmf!X^_+F7B)4bK9)GXJ49imQv6!m+@kqFDt%#_0Uq>|~CdX6Q}n#YHzgsN|;^%MjR zGH)wGxS2o^%%bCTm9yi-wbo_m(trJD-u>2RezYGN$GA~NP=)x%pm5-zDn7OT#D=T_ zFpvgEhQ^3|qpF zGgK_|I6e#{e_&LhivFsokdGu}C7sr*5t$A8)cfMO>xanAl>*CWcbI(azo zvrc(N25}rzrZ9GJ+r1Xv54P|lly~{U(TPf=9(dU`H#bnFFI*~|t7-l_zj}CjRsqdRy4<{ol3_^|uTP#?HYw3!Mn&aJyc`9; z^ZN+F@@9<8Iez1IqU@aV6oSD!+263W)65pEYHajbYH&~(2|P`)S^-L9u#y9Gc+DSR z_ybDW2UM#9=enS^%f|*tTpZ}mc()3{PoP_(Hg!~w{D&!Z7?>z2NQUKK(Opy$KLkH| zUnnFJWj=2V*5qDiAY2^^yS|qTc`6_`=vtXub)eWkRtODgzba#h(+cSNQE~E8YgUKL zkX)FwmkF%!l^RNK?qN zf=*o5cF&NtfZIpFs3pti>lxn+-=cR{t=-w-`4rK)Ev!ZCw(`bo{cN+)Ii^$;h;yE* zJdu+uj@;3k`JD_mbR#ovjvZcK9TnXhj<4SHCwJ zwICWZnBM}$oc0`gK4B}$_}+l?9xUu ziW=t~9cG}R2Cr(4ZfcTQ3l`sq#{H!@M062w z60{-e!iy@Lj11vkiUV#H3|@KtTN$@x34$(Z&%h~%FMpSFE%3B88Xt12ztPwsq{CUFDzHQpvnFfycCp;JK)`B{?KZEO8s^8vG`t# zAAXaAgcS5u6bz)NY7=!>Yw~d4CO!!}rR)G@W+A5C#Yoi)OnzKfzwRzM8>#+VY-Lv| z$%cWacb=&C;Y91ey6-P8EJ*laF#VAV>B(Z{>tJ+q|3)VsdX@5;(x+deTTf?4v%&E>pe%rG>`Ffe{Mk_m(y#l^N0VHJTvkDzXC4q+fg z3~nEcL|#P66ecBUf`kRY*Quz)X))W>FHXeBX%nOYt6kD6wZgKh>hZC$e-NZ%rc_x+P1a33w7 zb2J^tfJi=w10=ekfuETfg*4>qPAr>p!u``&@ot>lno;+Pd2s6Apqu;qYhw+5;PTeB z0lW%hkM5NKEHX3%f)pPUB)crA@lGBV<}LXUUWg3X{T9ek7jLT<{5fS!-p~>DL%scQ z2J}XEcz&MP6o-0NFm05N+fqn_!@b_*;naTWnn7DHd7Vj$PSrBPFMkUS^1cky5wMRQ z&ko+OuUu%By=4l|j21HM&iLcB7c?ZQ94yLoryE5bv1-=1Z(&ySvaMF@Wap3{bw1?* zE)e!$nM8H01iSUlN@pG(qG7p-nHlo9oj;zY)5ZGv6;sRn{32lS;30Xv(t%h9zrv9N zhpVb#JMRmm9kHHHmTFY~Y_9D%t#RP9XIcs`2T&HICzhoZvrm>!71zTZ)wFv5ecniQqY%_ z%B;orU9DT#FA<5*BX?*CijHTWEhfwW$NE6Pwpr4d^jo%Zox04jg9*qzp$$C!g zNF47t?`_ye+!BAU6VAhP#egWl>lXB|65J8L6;}Y)%!j+Cu9}05d#Ub!mP){Jfn`7~ z4C?Pe$UHy%3y&wQETTO^gF(d(?}k<@ho3nIeUok{bEMG&t8LHiH~LPmMJVhnP=#o5 zz0yl?S7TpZRaMwSQ{oqug67E)OBqJlaO;tPj!n4ANN4dqki`I<-%G#YQ*jJPUWZt~ zAWKrQi3kV9KWIgS44`_Jxw?7Dz~-S9Uuxgp%eMpN^W{CVC-fT(glGY(e%Z}=EGjE} zITcH`4$IxXSILH9=1(`&ouoP)=0IIr9AW0>(O6$MS1!zCtWo=|-p8lz`rPZy*O!sZ zgf3$rZN%}+FigMvwWcOPF_t9%eqXu#wW@N!ANoO*Uz{o-i?(Z@L)Rh%=DlmATue3= zm0;jcpf+r7p9UTt`sOM%H==in|GG9xXZgbm{RlmR5G->7ykZ?Wo0(#{Y+BMP&FrjF zk9^5S_z3CpvVz%poqV4A`&V|mwL_!j!FY?UniIeC;J+>&1N#H<*q#Kg$P!+JNF2~;F3CKnh0$^mLJ_$kn$palg5&CMilIzSd5sd>NU zWGOuyJt_X#(t;MKv#e>3{7-&CKh4P|spFm8z+E@w8Rmi?`}$SmdnHn=8emx|MGex^ zIayegm6gM&Ks_&8?`>U|H8nn*nI}rgw*dWSN=o6Bz1}J|I0C?X{8Z%wB5!s;zBJK^ zini3&)`DUR>L3k`^z!!5@NhYBaU2^PJKh^&W*@5I$}xX6d#w#l9%g1{bJyU!S5;lj zdFK96;-svmW-#QhgvGWz?G%vteS;Q|6hl7QNjX~C`futL4`!ykcR(+>RPe%W=}2al zO3;3uSo056)GvO1rbSUgXOKdp5$F4~wwx;_uFIFodw`m{_HN>{kPMSj#+tS?f?P6Z zSwR`KPT#3<@L@}9^U>*6^}WT@#CN;q_XiE~Hsihcrz;n0o@-)@@%fJ(XT(FSgMQ^I zE$KC8^|kHvamNzI>7M7aG8=1r!6gpk(Zm{NkAQu&8j|ydPR(%eLn}S|qrIJ4*ys*6 zPS?8SOI@eR-u0>BKzN}aB2V$Rix6~i58Dd-Q_cscCeYNdLg~fp&{Cy^#Hc$OSr~U(dV!x4E4<&mE0wJcOnyGO1r$i8w9l0~fc(zY5R)!5xa# zF085%?)vq7KVg@>^?(B&VNnz@d;TZW<1gtJF{KqWaVGq?1(_a$x$Mj0sEZyWmF53N zUxeG24BEH2_pi`fuE}-%2xOP%J0>QZ{m za;=Mlp)EaG$Z4UxqPuIcm}BO7em?f+TNuHO7)E^qLxZXg?muUnW7$GAn+X1WKebeY zZT0>4rnp@HDnOslBn=H-xwY43ux4cPJyfsF<>clUIW4D!tt%p#D*X{kVt!u0k5uxy z!Pmt3$J#Qzr;>Dl!b9%v$Ec%jrX0F)AX#c{HwfCnVGS*?N2c$q7Q5Gj-h14Ay^mQ) zx$clo?AWf~wjKEJ?ZYq5%Fm?KQ$r-7ay*E-5uWWkUdrY#=6^=Ps$Q?=$nLeT-(uZv z~G&ifbU!vr~of?M2K~h?fx>l}n91zVY z7->TD$)(S~b0g=c5It|4D0!^xKkDGv?Q3*G z`2u8$j?|Ti{Ol3f!sH6S%6o>r-M5fhx_v;kv|7LAH=f!ss+sDE892gtqvRG#h08kH z6(5H`{zE4Ii|yEDZIlzeldrqgp~M5R$JXIau436p6Uq`%7-Q8dd8q&g?n`dORIblG zT3T*sQdQ}%<6taFzX+i0~sv(F< zUe_$shjzDbb64@L9dq8BQ|qYw!AsLF76 z?}sezQb9rhkzrlZDQQ}CX41?HT)CKe*N%-2nJ!lW;|3AWr?w}*N!hiDH+;Xwik43> z+C=YR)uUM~0gS()Jh(60iI_2hi7g~{`R%EiP?dy%kS}|=G{#|3_@!fuZVhEDmUl~- zX{|7MqDt`xm11B3ruB93O+5o1KfBtpU7cr0eSf>xXCS90$5Jev0Sm-$X&JIyHxj^x zv>(l|f{)doCH1i$Bc~s#hrnC*4c#xCVF~%{;ZuHg7|*8)rtn=szqmZW`i*k z`XA%EWcM$K;z8~W10Nq-%QG%Mek!mdy*WzB%S*|~aDDqe?l4Y?RawQ86ubzWM6f>v zG)r-5=^jX4y^;jM1*%Bo@>NxYZ{L2y#01qIphIcx3ZTSu`JwpC&dq_7xW1mAp1wX% zEzVyF9Q%l2#K&vh-@s~?RaJ3-Xrp7hoxQnVwoSXgK6VR!4SE^{PCcrs*>e*^9ulvpRPr~>j2|6Mre`s&Ok?Np z#rw~XyUV@kcu`M%c+zdZXBLOQy_4|zAimb-e_47xpZ;RFIbOVtY3moqcuvsyy~$64 zwMWTy3a5mQprzQlLU&B$&L?-LK7^Is2O?6RtizMBd`?%k`sCH~gYI`-ij998E~n2$ zCX@;8RwP`1#zLHf=H@RWDG3JJes9KKr92$Cy-k!~ZLSl#3Z|V}UgyD?6#f_2&s9jTNEX0M(f z7Cpzb)vlLC$R+02Gkvc;J01zlOsX*+IC(c@piNKLqgO&hp`LV8luBL?&F-m8>N$dh zWpV&epRkEUiPB4pqo5quRKg)7vhooVw3A@YS-)q!9gW$Rd=&H8WZOw=dT2Ve<1k}t zY!BP7;@N(cL7>et?f)u={$ZM4gh5J7JwuH(ro0 z2#$4oz`T~HtE_#+lrZK_t)2fVFHD+`Wmbxli@^A&3BFvph`sx_O4|;v14f!kAIWF< zizn}$IVYE8?3uhZdS{c^w1wB@i)8}RHgOxT(HJ$Q!rYQo(8CL*@@EjV9R-cGSe!m3 zaV%0VJ@8(pUAK)thnluwRpvKRTC=ay+FM{G+be_-sBi%;hA%uKJS;ACm=Qvcb>gUk zWNbv?!Q2Pmw?C#WBT}eJ9rB_}Gv`7|yPVDoeF%vfHQnhD+HOTMzSrWvW&S{!3!JD=5vj76KFQ8dIRJRy0MS zM6k4|nX@D4^3crldQgh~Zb(@U7r|X*{F!qt$G0=Kka{ZLmo8)t((v(xsotMoW7*i4 zkm%^=`4r}uUelJ31_lFCQ?NK|;*?Mpdl*QgW@-7U6vK~AxAzL$S{o%=Lqo&YCX?bK zD?NRflVrOW7HM7BwohnLJ(k>9Zj5qJaMviE0i^@@c%dMKKP59K4a#aaBu(1}W*Af? zBx!P!CZM9C0=BtIU7aH#pgsPnUWAunUf< zz}-SfP!N=`^z9r*_ElOMJ643pZSFap@#r|p@@pZ z<-?<_Bi0JGksJl^T7c~lusQ{uH1BDkLQQnKM=34 zwJ_iwb+|n2URHoF4>{Rh7H7-teZI~($~T9bY5sfU@NhkFbr!rYQr8*ief6+xH{KES zw6qtb7?JY)?s2(-csyT3Y{=pHEM}s*E$FEyYQi!&$4+4XZ;0#0jKsTN;14>U1=1g{ zz6m`&{GPjv$oIMYg?WBXaoOn~lux>2 zD>^pbea-~Q#_HaBLoY9nD?y#;1;51*cnEVFrfj(~R+W1vLOTboT>=w(N5Jcp6x-Q(dA zE4O|FXVg*?oQ}=;XOV| zhLR62M6NcQDHQFc+~Q{RW98Iwu})ZXao;cNz!H|;&$8e^#?OCaVEvBxLzKqTpkS`| zGFG!$@9omW%ZrY|C`nk3^UZilF|3&lUCydhY5Fe$8x=%a_J20I3O?}#wTrixfTDLS z=-$)(dpnQx@*_G#qQtdQF=SCz4w@V%m`3_ma2bNnMEU5w{)k3NgjbwWWM5>c3qPHy zHV#vHLPKeN;a6!pQYJ62=HAILeJvp_m~_%PD_%R2T39Srgm2wS>OcdYG%&MYhHTG&FKdYOKi|ehkGhEuQ8?B1DAP?r|8S6S=vCzLw$H&JfCWh?N zo3CZOj{&^JF2I`@^iL-~?{sx_fs=X1lqndFACI(kb@`W5E$>TZ<><(Wle2SWc{zxAsQB`QlY@g{ z(n(ue!_%Z^1+iqMjbv}7=LFDw@%_M^ZS;+*fgw^$VTE6HG|Chd z6in<8&RoLn6Yz{|idLeJOH6ceanVp$m)G9tlYcKE<}K=b61gnSdcEi&;xtbFd*%C- zL4_VGL*kkvet>3(r!aZ;7?Ss(DQDA!QF(cJ#1fl!TZKa^(Uc65V-olI*;grQW;Qmu zj%0vw*NXLZ8D2@;+0#uuKm9prt!Zz&-o*|mLw>F$Z79Xq;rN5vwqh4wbxS41`qn2bUx7Mj7v>^TP1@e z23{!tZ(6jy_O}9&VPuY)j`8pVQ3X>9N-8eIY7VZEK*)O6SDYQSY;FaP z#kWu11yq4oS<9D9!!O(lzdBQWskv9X7pmAXaFr$h~xc4JJ( zC8+!{kBg%UetLY@1W_zWE6F^|2YgRpeyzwEa4alyVh*GQ4!P_C$O&=y(P1SO7=jsU z#nSX>^K5DGEu`7UD07WUErIct_f|{b-J9_o-F9s!Whg{tiC6f>wov=GOfG~ejZe5u z3ysi7Qo02##n!8BC>mYE#J&3!!imwGFZ6SsF#4|27-zKg1JuCIN|lj$Q`Fl-(1 z;xiU9STxGmDF4@|aZ4m=O50+zL$JTq6?=bel;2=EdnqG+HPy@(qR9DxD)Og#VqO;G z{39_8GDpr@+^lFdLechy7&EooFEtA;>^CRE64$<50u_(CdKlii4vsKfStIgn}X$ftlPd;yl&W!6BE=j`Fwr zB&Jd#cz18M2k1^&@adeFx3!TI*@1y=VIEEu3Yr!$FOr}sk)oq#PtPpt>Vgk39bJ=| z>BE^B^!j?MDPPbMIXJx1(9m$S=zUY)-`8jK4j?H8Mn)fVa;*7DLH`o63N!OtxoFCg zBpM1#+^Rs=R9&42LkCVxz_^A${+$?sa`ALqTN?mN>WtX&AdXH>@o{kg29znBJ;Fp_ z#8=%1vvQufNZwC)p@6_kU{2uGkk-2?b)4|pMUS<=fGk<17z=$SI?BOYwB6iw@(7cW zyQiqA3UZ(Wl?b%oA8$Y_}GX8ZMR-n`PqW}dUy34Uq6DmHr z(kvOZHkwH27_Dlb*SEO033w&Ng$%`C6E&Q#9DmQhedtwG&JT_YeB|1h%^13@LFQN= z&aWq^a_I4htNW~{EY|>2Cbv7v4Zn~T>nSca&r8+y6+Bd9xB|>?U`3u4clPfo#S$l5 z7UHw_tQfw1{S)Y5Q#pw>p}~D*L=6s7va9kM#;lzJ%|m=2Yr;CUPiNAKuZLA>Y(UJ?$J%U!LCYuLuj@bLdA~0*v(0N-4Di4Iecg96$(mFP$&c+AA%kp>>`sN9R675g@&_`6aD=Z6?)#t z@u7N!^QU**pTn4KPIF}74v4;Hg3UuzMJP0i`dszR4KHJD^83RYycu*BHe*02)v7q+n{jFxY+yM} zT`kr4{U_`6NQh3jFKHa*7kYP5Sc1x?-g2w7>U^$Zd8uUZ;j~2xIxwPMzx?@thd#ON zZzLV%Y`_T9O)73b{G&hLLuzC6g+$(rc!@?HuS0k?JOmVyq?OhI0jta~F&WT}%oE2f zJ2$=_bYuHD$d!bPi#tBgMw?RB8TX6wo(Cfp+Y0P#%D1Dywz#GobT+l)`=`;3 zu2#Uzurgw@YbXZ7Op#9GQ0^Ik5*_;|Y2D|B1_I0eySt0Of8z!QejFaI{j6(jOlLM} zTs{G$+3Gbi^D8dK+Q_0ucY!n=~#t_J&W& z9VueYQGhf7+>JqW16Wg)m$Qh7FwoFUIST@@{F>VLLCQ~RNS&4-8jF@zr&!0~n{nBQ zlcVF0;o+$vn*c1P@L{#jGjF|&F(L}>>KU5dwCV9)U<@=jH;WOT4)0!MW|Bn7bib(| zdvn0<38c#%5W}yy6-=sbv>yW)2F@0ztnAWDc$b z5+A8S`RT{(4hx#ZFM5fP@=1O-?Y92CjqiEBNcYy_9un)1j(WoibjaGPjwdF&=aY-T zl^WDf3OdC*h6W$)6yl^OW;cr-&>J7Wh#WlIh*oDe|0_gAAO961r10t!u)5hv)%+VK z=bpwKMLuK|1H}u-jK+5&wEbLEEdRC9=lGLdAJ?%}=iiofLkpUW5NVBILFYY|>FJa3 zzYO-?Wa+w*42yl~%pk?3hd?bCmA`M46%MKtE0-^>Anw!u_(+xF+aZgUd%flpTW9(0 zbFiQk)WLsxh{TE{5k;h{lbJdap?R5u9&O*zI8Qe8yLI-);_HvwhAWbH#2!yECISaX zAx~zy_ZG*z%PgN2UD$8Y_%{lQjB_LA>724VNK$HyG&eaWl9C zZ*AfM@Gp$Rfd!;{rFgog2>Tz(?%kSlLokC=sL;@v+Yy98 zH!%IKoL&LbZ?i}gX)TmcJWUWYO|4F`dT`DW3SRPW*7N^vjtg`I4A_jiue7o;{8jl> zaL$iQP&iS_3iGw`{ST(Z1CXorMntfu6gME;gnz!)^qGL%w_W_9os8rz|Kuy3r%Z4( zrKs;Ej_=mBebt1w(D1v|zkJkE>|Ugxx$an1^QG%t8)H4KT3YJQKKin>@?gega}&!-ql-ef_NI)cXZ?W@hS=jE>h0+1U*ShCJwKIV11x)(|YlyJfAc z=s$1#y6wewOdL&N&gPN|mnfcuT&=^1g8(B4H7BXELCxorP@j302Vx|2!Fys%k!|5!=DL@<6BQ9EhWFv(P-1R0sFcs!@`9W{U>BuletLsT zK)^s4106s(Q4~R^^&BG;p&U;&M>7%=t+Pgw`az8;BP$E8ZRO?V>$!tTQBn>Qqt*d7 z(-fe&*Y>@3&HTK)fQIR*)yX%HiHSj$Ey56z&6<_ym0&FoJp3i)JT4WLBfam%-stmMd!Vm&NSB?m$w^9W5MXqZ=4nGNWOIHwy#wy zq(#eAuddE8F)vFakqIs+D9tTK)~r*DoN_;|2e4D(FCDc#fI!*!lGl(D)21&9~E!w?0Wuur_s&8P_Y2v|Hi!5eB`Kp{O7>*XP{%% z2Jk-|i6`=y(zcl})cE8HJD0*k%dFt&tI)Pl7TSv<-m;%(ri}3FKLHlvg*RBp&x=> zIa|D0z7GxeY5C-4zQYoG?b^xxf-ulBYxr!8=4y6+mQ-9wg+QUg%&?!(Oh30iePMXn zOr0{0Kd?cQc4^Uch(1ncVm-k^PM=;s&L4w!*>^l!OHJ-z#WaHf0{MfM0)ijcd7B`M zyX|&TH4dahy*ci1zdF(eWcrFj_OJ1zz9*^u!qXA(3Tc+v8%T-v^6=2o(ZPK?{5Zq} z9?1_|-;d%Kczt-SYCRr=!*TE$qh41T&b(pDAe#i75|S_W1T2Q)!o-N=P8eds}s`2j4k z@fH!Iny_B*(57|Glo;BLzVW8UceJ$yi2j^yPeFi)$ydzp?+rL^@CXQu_4Q|$mXLn^ z0zvXi%feu~)7v}RXuXJ!R;m>(PhTFr zj~h~voSYnz#GG4Hq;goK;{2BTE-f1qJ73_3b)%++25>ilrClfZ-|-|UedvAf*JV3b zTAq5Z+Fb5iDa^ZS$mVNR5zLy*H+CNu|%be=el?>YQepb>jqbqRJV-|M62;mmuQ_04u&iNU?^ z$S{jn3n##pE~CcCE!(UJg_bmJPg6j?N zLI`ln%+4dUSUH%P7v7iEzBYkU4fe#Xrjf=ADkPevSP>}x60Y~D{-=*$=e`iQ4k~ax z`Ue7RHo=39b#)`O??RPvDTj0`7Qv=_A9QHLLNHHNGqsjQ6@4dpb$;BaA&Y))*sgxB>X4Z@?atuf8j} zQ;_*vPWW{vsVa01{*QkKljst*h&Dd&=cJ~V062)1;M9u5rGQxo@~rGFM~{0|Zb<+4 z!dv8J#_;J;iK_9BA~MuJA20e>S?W-ZT{`(~QBg;ZoebQ#Q-(WCx$dKS%@K+2Zb$Pa zxl-;0md0O#O&2=$k#aD_7IN-HV+WbJ^D8S3%?9_VizmktNz5Nd!Tc2gH%*Qn^etCc zSNw)YFbv}XYYF4~_RT{0GQe&KhLB(e0Hzl@I_ch=DQv})_*D6voFNeuf&g*?yDAmx zK~9Z+ql1op?4&KY1}G^haT7yogxFOEeoez}@e;=x)VyTJ5Xk%G@ePbx7 zT4;uP7$VCw)ao3bQ*c!_bTOW_Do%_kmEXUM(a~9M)GorHKU2_5wgv9Dy!3e6l?JPe zWJKaU@=vo(5Jd7c5et$2Abu9!xcbmiZ&~-&>KMTo-Q=|5`1DJ`QP5h7UsFKFti@I)v&X-BWM*NES`|?wTPI`8X><@uEOV$|& z#U^T&7Zr?T)|TixiZHRlGQN*sJAi58>rPp(4h55rl=WsKjcK$*TeolY+_Dujbuzd@ zG4NU`b%{Bz5US+EvWPzZE~u_!3|Lls;F9pX5Q<#mTM zLdPv1XRz;|X`JzVgkQOh66?)fo(4;S)=?{Dk{3oh-r1mHb5@^7WQmg{NEV`QXlHadE@Yo&WwpT*}bj4ncof@ zV$ambf?NyE-S`?B6BEuwYRtUZg|zCep>s=z@8{)G$M?xF`a`%9)tKoM|8Xu@Sk6vP zEX>TrnKoA@um0l|0Y?Z@1Z=hdX{>u?b8-O{B~{i_QgZNaA^EcRqb=!(Jw2+T;^4s6 z-tGKTD!!qGg&RnZnI#Q-&4r>WC#R&Sm=GP^&q)$F1cF_n6=Z0W)R=Km!u`K*=v=^x zWei8`9vQuyH{%3gN?L~QB~ueVR2pzCz+U1q21YN~RNPtYEG&pBKzhxh8#KOHMV2Wd z$AlDFoKdimdy<%6?n;cw;p27ytmgiPtyWGYK1VnsZ%dEpOyD>`3XnYf{2*QMg~)Pu zl5GX_XioXcq2-#zoLI-mh#U`(=QI_mB?(AUdC!vWHB0| z(r5}NeRF5i>y=L{L2s}OHqFA(+d+|{fF~c89UY|<0cN%&vut9esJc|Imt(2rSvhC} z^BFynR_Ne}8=~v3*v)HJVJJ6~@ABaT1?MiSjyHW`ZrMKkbJ3!r`i7}Tj@wZ&mu{fs z+8vVML*9I(DEWeUV+Go4ik{U?8Ro9$!qhGx+D-K2k)yHy?$bb$E~;F#RZsim8V?Ws zej_^pHoJCLGu+Yk--L}vV)9+Uj(vbJ86B9pagcsQG6sqSLfOPztZ zI<%B2`aV9h*$W-mH0F|7@Y>0F==#%&2L_JB3c~dt(Pj=*tMk_Ip5gWoBI_VW_*Jh zuLIk%CCUXZ;aV_yV|c5R4~x7ow0(Bz+uJ3i+-h{pjsmtz13BUC+g-GXhR#9h*Gd*) zy_;a8dk3Wejy!!bnBRW^f#YBP_Vm!EDR20NQEzTAY{C?1VNpHt)U0 zfW&Z|5{)Z|zhws2U+3f)X=|6x+JTA3Cg(P8*xswW9A0~D%rWc6P02e&%bb-$@5}v@77N`?mnX>2gc@8ESl)IwapI?U6BD3e_%-U5}#2}C5mt9w0 z7Sm#5WWbYW!gE{XgEwYtd*D*HQ-8YGW_#<@lrMX+8tH3Ahu9580;PIfsl$7bo z74A=8UKlp%w7XLIJ%4;6dIBxkp{ne6m+U6DHnYDPT~|{V5{)Xwh&SA;4Iao<^86pz zB_(JCOR8JnW_G||J{o-`n<>eEL~Hee_t{3@S=`3QK6;1W(o3X>rvZzbR=oh16!!V< zcKj6UwEI2~PK{Z&K9+Fe6HhS^5B5JNid?V<%~zL9Qzd*mPbn5Wj3f#n(2ycB`vmod zG!x=qNzq4FOLxG9Sx0KX`M{yE!uKC1aY=rNcyw?WLZUgI-*Mkm9lW1UN}*Ds1=o3a zB(}4wO(Ui5(EeZDG=XLv!JmZ?%D*@?)hWz;`*~;H2CvB ziPL9l!3sx-!c^`pXUHWktzuy~l1*9;=I;cE;IqQSFL&^rv3Uy4xY%COHVbN!)L8vp z(fwgbn_MYHQts({;F`%ArDi!Sz0j)V5eC(G7quy~ErUS=W2yYP^W-uplC?&szSjx= zs8goTE#mKKJ!UZj=QWzhorg#>Xy>xbo?+4Az&@d^{a^ck4iUAA@R(ZT$i$sMKsk6K zqB^Wk55FZI1V|K#pU8e+j85H`0YiIT6Q5o62ga4d94bQGw`#LZ^=!;MFf=B(M?AjST1F;i;~#XJKR{bS|gH4}r~g--^O*DV9p`BzLXS0{M)1 zgoI_Yzg|G0@?2b8vc;7xEmmVWt;WV+t9Nyc4%=nvlwC7voNSHGu$3D|O1FWhSbnXJ z{ps+P!rM;lF9Q!;7(7`@=H>>r^q|K^nk|xi#nQM4K!TZxiHY(-QrbzdPfh@j|D$8Q z9)OJiRSE(xXQpuFc&8MOxT-0sPDr6uKM8)9;=B2yU_=#FfHC**Fj)bULxLgJojPqw zgs#?U`m6H3z8Ajd6uDj7XCPu6um`-Pqg_Op@zPRTww4*14?IZmJgLPKvj5(PmmJ$d z>;El_VAxduZ`kz2c)KH&i60_uJ}Z(M6;H_rN+XETb6wK9CRxja4HVlk3nI*=-%=-F z9xmBrdQ*7IGL=ofxJBx4VbL98eCaOi|Lje0d&lZ#-Zr0in`4tr@6Kw)u-l-&XsZ<} zXTMdet+3uwoUr9QvhZy^i2Zm=WmO5O0*lk z1&KxoEhZ>K;;FbWIEAtUfOT1Fn0!D}%k8kOvD%J-MBf}!NmQiF_lpP7di3#2>`&V& z57!>BN{1)@+AM9uSV$V-Q zIjs+LlZF)huAPi#=Hqy3C2rQ4A!GzhO5+*nOZDlu3sa*#HVNtp#$KH_L_4`BNyRPo z_sMZZ={{Y3%p50QVDY7kZhXy|Wx+?~QoEHnVal!U!H;CD{|$H+stXi4>n_=k*GzZ7 zZ+_XuN(wxY^7x0nx7-Xdz38P=p=Qi_VYO)6(s~g?hsoe&_3q^tm$=M=>aNN|&>(|x z`%-s)2YyYzCQ$}l7cZ+jii-IWbwkdU*kZ4H_P7#EC?F;=u_g>_l8~vCIn2CS=eMTAA%#5eu8|<`T88Wa_M1`%ZI(sZBYD6A*~y z{URW*&iwU>8dNOYG`p>}wA$qO} z{Eh7feKT!mUeXUOkSJ+SAyLqxVk(YF&cjlM>#@INW_ECL8XFn;y{ZaBtKPQyxldl` z2jF?2P$(Byy;{`IU2exiSkS8SnWw@!{rI>^sR@X6tF^Kn4*Z5S^JIU#j-v@K@5@CZ78B*@fiJSOv@}fYCm1M!$^O$tZy6H9 zbU#Ni62ps}eHu#Oo_t)lKP7&dc5w2Pc4ScSkCyo-EJ4OGS`rUd)#BE-`FgQ;pys`K z#QY;9(4MMWP&UnGA4W(_LY{b}q~HYD8?=6)q_`Jh^jr$OdnYt!L~m&K=KUBUxgn9S z&-P{KBkb*OTDQH-b$4`c#b1+i7W(>;?0kfAQ81gK3fAEU@Sx4vHxH~V$8_)zMYU|mAF%Zx7dYJGg;D+aS@F6o3ve;poUZ}D~JZ?oZdB_4y?bg zVh6pFn?chCj`9qY#wnpi$8WxUkG=U6lxM;T8W|4QeA^zg=|EnhC~PUjw=)A44d(s* zBnD#m2`eU$w%q749k`bilc!egcTURe5ae52=SgEr4TDfFPpcO;ju-6qgbm!sAkR_E zGrD~KGV8lZh{SgfB)w)WOdUsMpq2*@gAtmdi?1IL*D{`wY_BG-%N>2PTCKt=-ool= zz~5m(e9;XXa9?Uu=1s4Zs~loMg-D^8e!PJk#&VagvRT)ze@q=E6x=Nx_?NrGko~^T z2bqGP0^GOfl{{4yDTGs!S7Bk{A3Ts!hD-Z?a1yZ>l$MLDePCcrAW0_KX!FLMxO_1R zFZ=JTZ3YlJU1xD*<*crx&nzqu6A>}tqvhJq7LE!zIq%x$vEakaL5rAQ?r0rd-L(Jph6aHoptQDqJ=pwJt_4U{inuK4W)PFpqhLFrmZ8sxUd%Z_=79n0Y&kZHZe> z5+~cXnwOTgyHb!YaMZ4@p`oFr6>gq+p#wvm^UrosKA&Iim-AMaC#@+hbM1KOoR9}ZH@D225`8e;8CV&zk_f_2^w z2`Ri~Bb^99U$oId3~aFfjWwS*?5rYihkLlFymH(+RVJw~PnwR;QhxxUQ!hl&D*M%Y zI~Tqz=P`sdIaUneyM0O+yrqIPj!}Gg$Myx)V9&DD6T(MAf#t%=YUy@cSeOc7_6*mN z!~B;0tDqVb*e{e;?GInZTb&`!qd*A;O7fw}D@I9uyzo1h??#9RtZ|h1pMcBWpq(H;^1SaAF5_ubc(&|k9B=c&6f`7Sf@~13&HL+q{_xJpG%*+Y=!TE7A z(zXi({0}iWCQz){RU)v0^8(^^{tB=l4sx^R@gW%Z%0cl!#{E-iiU`>m{TJiAVLb1zy3NP1(FhLgle$ zIV9~s$+Wh>%oJ&wOFKZoRx3N5jpK7#^Q-=JM;s?{C1J0{$Mf~BDl8zYHzmB-0)ulq zE<=7&idR#lK4!B<8yW=ozX8D#11Yi`hzqbA(WHA5=kK8$50yI7=%ZZbim-NM2l4i{;Tmh=% zT%4??cZ;CNiUTj4Ou0$zhbq-Hg}3$6dhCSEJ3n5`NuY{2Ng;?twHSTYsQj(&39^k+ zQc}psK7vHvyN@>cED^8YHZJN^H`mv@M#+KA-UnAmauZstvufW$Er`qJe>EFWw4*i5 z6jG~GCJ<3LHtVrZ1ho%zZ1ns(Ix0}W&$#>-7XZK)FxfTwyy23GIwXOfpOFs{}Op_!MokWKYz*^s{LK;U_6k&&QMd6xXY-BNBcvTPc@z!5w1!JN;fI3 z4yt1V4tyQPn{cMuxPOFHPkv(9$<4-{g!wl4;8n>S0%%#&%sgxlDJ9R#)xugH)Ut4? zCGA5wDRhv!_BJcEI4JO4<0#i#mC_AHw9(j#RpH@ zuYC$^0lYgtD1Cg5~`Tal66gqN15EZ>(@9ZG+=o(>9Wn6$D zE7_tU#N0hT*xcNWQYSqYnx;sOMg}VD%S=^SfBLWZd#^nObd%?s^{zhK=Z~-mxTCd+ zqdyU%4YY|Xe(bwYpb#s(BCz{13HK?#L9q^em?bK}OE)6sLsbJeybf!-?hd;IA-Y7h zMDt%PeL%0@qA-&rv_dBa3akP;ZBuo<{6A~@&+I)5fZ84lNQ(NtTk7i+FenrA!ldJrfSXj^o zTPt)YKMih}VDEzu#0m@@^+{Ydn0PW&2UZn#YMr;5aKBA3P%W8XgsfJRRXj)N&$fdLo) zt3J{BZI?l=i|&B10~`U3__xqL7`Sk~)-yXnh4PjmWqJC~Mg)KI{l zj>&0(u#b`wUI00ijA*cGYs9Xth;_IhYo%n3SPQ@EI00J(NC>@LjG?`bv}bvnS2u`mgGV=9m9B3qnoy-IhVGzLuut8N{JwTTigq-d5yZ+{vFN6atQ?R@E`8ZgQx$VSf7 zfpc4)Ti?9QJjB@W;y|vdo`Q}0kQ#$RF+6>hS|dfF8%4y<>aV_W%3{#<1|HT9wm!ob zf*K0!W5E$S?^*@s;aB3iH$&7yBw(OILS|dXr{+i|S~(Nx5$SUwV&xY)^5CA?RrG`v zBpYv>_hlQ!agoq`*+LB~o=zPqmXpAe=}(h322%zBt_pBgA^m8jxqHlkMK4;2XTOB) zm5hrFuU{BoOBbE^fA|d)n?DyTK5Pu0fAma9(sN!y>)>QKW)#8Ph{kvqy;9-DWfWL2 zEu44|?HEe5j^g{+XioJU+J4K2(!A$${Gg4Cj5~_Js-Bh(FO@W?=0d7Ot!U)Jinuf@ zvk>hFqfgnn^|Y2x!FK}?cYw6gG$;*stZt_E!t>oobbkk*Ax%S$kYjYlSLEN~5NdTJ z2G%i_Zq|==@lFn-7b~l^$tp&<50jm+9Rar#`J>30?mBWuLUo~N>?|)9Oe$e-tm|Cq zNr`u2=+v)=G#Qm$K63t7^i+ElhD<&W7%IrYU#yQwp`TjTxd;NH=V(BU_B> zwUauu1C9qZ_Nns=qn@E{mln8?e+kOX&Gl7`vW)H?h!k6w;2I}cs8*>3pR-N|ZCG>w zr4+yvrl!vIdPpr_252IBLZpE&3^>YwxEUBI=HYzeT6Xa!>3|;>jCZ+7Tuj`=3a|Mi z%?)aFYUeL*;ebxM>qdYkbFx;@@hV&{wRiKt;~T)7fDvVX2f)c7yN{K%3S=^fi?5q; zLZG(hm9^fsH-;}W?3=$yTqTcPl(5*QjzRvwLF&0M*qE6C`u&}*=Cga#+Oqct%>b)F zF`G?EUwiu#yyLeC3Z<+-(FF9?B`P@aG}M!JRm&EPQvUyQMCWYz-E92b;n{0-*JvY@_ zlv|78!OqTT|64RS>+)xJHlN`(hCdv7@-*poQZ?$5HPLK16EY%d0?trE`cnC+ix7n- zcMzoqE>x!X9zW9Zfm|v1xAU;m9Lr{tw16sHj+Ye^KRHH?^y4<92srOEs91FcCugnS zRP3uJ0x#A|X(#Q;b5y&>*!yY4k>e{1Nf%OzlM4C$Eu&YQw!lbGfD7g)E$wQk{V-{V zXS9ZdPKRPth7A%;w{Q2LY{w^$eVdq_yVQ8J>ShtCF$Q=tLU^X3Tu}=C`B^5wv@W*; zL-;ZFp3il|w^6Y!n{Xn>gRicRDgPG!92hSQP2s`z=iCRuVOZQz_EbswDvWK2<$E_< znA7B~U^Q-nVe&rJI%s2bT{geNUk#5dl_vlepTA` z@k(8hx8N&n>X=m$_zIt4^4H{2nRAdkob!qIm~(=p16Pe$Cy}L*sP^kj9VE{iw}4wK z1Rgo?{j*%_Ep`%f3QdVOuSWSuVT738lH5jY+k)A-che{Ky<~=_8Dzta@g1J9i^qq( zR?VIvsVt_C|A4@->~ZWuZxIu){?^b?O4B~oKvYZB%UjS%lwPxP2L9mXy>yXVD=iC4 zCDdO--?8Yi1FM2{U@EkLfKr?-GT>i%g?F9e471xSKwTK)qjH9s1u6Dw58=?GCaD_2dN z`N`bRAHVIjVIA?Q8nI;zdkQ^L(5P35@p{*PHUErh=Lu{J;6IHDzWz=_7z1Xxq(lRm z!Wjly9w)F+l>f#VgM%t6n!6y_)!!wTI)trWK31lZJz%wx-%kYQ*7ts>-*k3<2LE?T zb87ZaV@yDi^9h~?+A9qX1)tjvXgU%oc={cC5Zdhme_}YR@u{NywV9Iq;s1@)@?-M@ zK3jHv=|qT~JH&?K@*TPn z4BKuFFvd(@glu^H)qv>I;C28ReN~+HehkUMKdI5S2Jpk_rXi(PFrSf^JtSEyAk=k| zXlO`f5F;^8MD9!CyBoFO4n1GjI2y*c=IN}lT266Wb_v@EI7xrc_o_E{jKp5p%rp*Bp z&UbxN7p3(>T?@vA)>7M^xQk%)i;`5Ku`Oq;f~qr*=}3_?8#7=oI$p%d`L zJM}e0m!R^KL+xDXeNk34Z&C-ZZPe@xS3YxN5ytngBFT z%sli@E;0LlLM%=dMX09Q*a_7J4>)$;kRe5y<*ia_%!0hZ-L$9-yv_0U@q|B?e+ZVs zAiNiQ(Nqt#p4)l~6*XIBMRegYS|@buY+NR-On^i*PR3B>?PU9RGu&+D^w zgS!21?XKNrMG{zz=I!P&$Zp*_k~FT6_a$ptEV`mFW>owEVL0u8$3%o$5YI`OqBfTjDoTSKN)U*R z&5>ZXuiUZLwSUoP;R@tR@CtCb=ORXg`@juo0s#6B3i;Kd9OFQxN#pvh(3obx3-t2+ z_lv+r5)U14b7W1cYHFGxS(2o;`?@^3xBSRf*sB3RAX#hgft+_&qj}tdqk@OiZ@jbfAI>nI z%~uTw9BytmW_L0SXmq7hOhsOt(jIm4X5k9D#U+j8g&6!d@_ni&;c-6r|0{OSuK!!? zXfC_7FP!igm9j*JEbp|aoX0mHrmTXAqb+~*&%Bk0$r)%gBnV(%77}6iRYIKtNd_;BCHQbTuGWGyKER z^14gopCtfoa)1nQF)8Ux&1iF{&AylEtDw)a8mk3h+x(agbr=6%CgRU zm&}x!>H$v<=Qmf!dCdNdOGmpA$a@YY!r!R=|w zA)!};G70vt$>&tb{?-wFN{2ib>1RLl+vBTs)`Nros_eRd>Pt~?Uldcp#6dTGgSdpQ zwtj|Lyz%d@#G2> z0u*xp06NCdGjzb?r z-msBUT+W&84W+UdX392MU7i1R$rpONMgKJ<@u2v$4Qc;C11hG*eItPU?2nh6l5}%l zT!cjg)d<^uhnKGQ*qEhcl8>l8{KX+C}YmaX$ls zPQtUBbHhwdOOots?3VG6)%gd3kPub(O6li;XNo`Ha{pI;=%UO2cU$w&`w5@LLWA=^ zfa>+%?0lg<^?wzuTr<@BlUi2hJFSbYk*!PbCPw7iY-hkYWZur%b-wy4c028~GYwC- z?mOnZ&NH%0VQbj@i56>EPQsE_+Lr?>h5J?{S}(eq(GsC@v4ESRt3f*%=!3{(x4HL7 zw>Rs9zw%!!-^)&bn@v10$MC2@85e#)#EJVi(JL{mQJ}w7Y44?A8S!)Az5%y!%7rfM z@!zdq63ziH?50egS7Zz_OLs*?E)mwhk& zjYtNTi=#`FDasHPt$IW@g*oCM^x){mSsH;=KgNT&@iWqg+Qdg23BjOw?xrs};FbgSe^8-A<hYi5(5%EEZQI?M7`zPN?x?w5>l%($g_msCmxhn=;y&xF9Dx3cuPG4K3 z1hU8BSHVo9mmQzuTg_mNYl8}SN?6`K)l9>ab`bY;Q>24>2*|jmUPdkuu4`!c=Ypu3 zr=cfu>qyFI*rHxtt4hbdWhHQ^*$8tfQ^**OA8_TiJ!)D8pqVr>Qi|g8%bD9QhEQW* zy_O2kNK51Mps$)e%GrlO--P=9rF?H*uSc5%7LDOtgUceQM`oND5tP6f+uPH`$*2{) z^v8>C%_Y5}?7eIeXbC}vRB7q$;V$%#@pR-%oVWFQz~sWsZ5On~Y3YnsSv+E1wDwvTkk-b7lo)C7f+-@6OHw^1O(ILA_HcuLj`&KYxS4L>`B-SK5A$LDVT zrs%&M7RE;VSG{0K6Hy}D@~Wx>y?9&d*H7?{pHtJUEZ@o7hN~B-yU<&ZX8hXlg~8d9 zn^{8@*qaL*2|F3{zBdd;Q3ZGY2l?|Viia;UdT;5{jbrukAdMxPcH-)kM6&w|%M zYa}u_POfq^i`9ZcW7U%*!YBTvdYio$0hAD3iO2+!O~mr{87?uJOw8IcD_=a2{{!o? zfKVv)@vsAnCLsqFGm{Feu$kL_#k78*g$8?I;bKgmx|>Tw0|ACzh>xmqkkChciQ!h8h3X@KEwo9Q}G9GuykKCJ${DTryeUQ z|157;g3;;O+-nPeSrHWJI|@hJ4vIN4W$E-lV-Gi4Rn(rw!YE$7gV zLjl`;XTkNbXOxEnHu>6Th10XIFiPTXvMs+jzqo;j)wDQ}&A}s?X;7tBh9ZONdd3x# z!ES`j7xWbB6GQl>kKM4RTuUM<%FN2Tjg{k#v7Y?AXC3^nthjrqlqzdp!22O&knVPQ z$<%n_XYloqQ@Nmbj3>C;hiD*A=hDx40Z$ZW@=W@)+*=oUwx_ks?y4b z|C;I&w?pEo9~B|#$8DA_8Tu1d{&RKM>$HrWM<(@2Dq`qQTi2OH0XsEDe&g|ui>V{K z-Lc$;6{B5-q8~0o?vwT8DNJ7MajPP4WQSk+a@OL$P`%2!NyWxpZBm|}d?7i`Bo_Fi z8efJat{?RQ^2QI!nx>FkqQuzv4-;qqeR6{3Oi#rXbfbwcLlIx#HtqB^$eI2pM{rKT zsD6!3*n&rfFnPt|pT9%4&M%OPXYIB#M(;hnz^>{qU(Tt=Pp;p;fB%6_y;S4y%J=^M z{7m@Wg3-ACnH8m;kIf%JtGgUo> zjAdmb(FT0zS$RkYM1K4Imd2*1qbvUUb$;%5&;TDi-9a~56iQaXb@A9|tPIm6pexB5IbNNsz? zgg@BzbBKvjvU7r&HCc?Tr@9U?JzW`%bq6nJ8-#r;i>oJzyh@%f^A3Z2ieJpy6GgD=co6Yb zm;Bl1-h~OIvepcino^z%ltyEM(6{?Z6;W1Jvgli9mVId+#$?N#k&7)%AS&mX&o)Q= zVmI}TiOO04g5h_P%Mx9F?yOshZWdVt#B$d&MLgULs0JSXPkbeg$&Y5`L?yktUt!kA z`GhM21~#^BQoKKmW(4_87u%%#6~(AsM1`0uquVmQ_g3qGq9bl;6`i4W+9 zb8=N{8st`plgSBx{I)3Zvi5M$J()->?|yP!f=P@?IPIjJh|CDfs=QCTz;(?QvHMq@ zLMp3@oC*|AF86XV6`bJB8V0L(}$YN&7i9oJ`<%(He`-m%$llSB?*ZT_KGN*SA z7Lu6dG&N2}{v*i;GU!En;~&M}Pi|Gbt?x?Krd5=5H5;;PprN5(>Wp9X#}>bAdN_Pv zH2w%*qLnN3`uVhR>d*B???)KlmsKUx0=|m&`0WGs(VTg2iZ1rXceRUf=zU8&VLz|> zUL5v`i57`m?rC?Nv%e2n`J{efuI=@K-5qzJ`xyu28SUP-%Rr z7?qq})n^^*jEQ#tN?r8|e3o6*dSPotqskOPfM*|FrFbIlCLL^;jh`xPM{;EU7D-az zTkLlHm0Z`AEV_s|5(lB16GM5LefY@3w`0w$ zanX^#ZF;xi^}?kv@1B>Yv6PglsVT@kjB1E&nJ5+WY&8O;IcH?ZPQByuPUKJ^$}3-* zP-%X?)zq@SZBE z1|w-7%vGJS&$brVSU3re!6qF%XRqHNtdkQx?3s59U$cvTCt2fB`t;6b*=}LVpLJMq zL77>3P}_wSqjZY2AbSU!W_G0)!?ENmrIxt2!b1;}JMcYt1m$}N;b09*lAJv`c%nd~ z8KC5}O5xf>2X^8S$f1(gWm!OSXpDz*?w@IhlvYo z8mu(2WKltGPAch0-SCH9{G{fZ9QeK5neQJq2TYU&?s>Xxo?j6E>V1WJEfV!<4VIjf zjntMBdKAm4a=tWlb0NoT@>x!HLQAK-sa5N+^=Qiu8>ZQf3?*3TZ_&X>hUQoR{CRes zFWuh>yq}}@QEO=h&ElQ-nJMSpzp!Z)2$;%Hwo4o65tK#qacW=IBKKE@{Q~P0W?FAS z>E*o&tIX4KSX2eeiZl~HheAqrQUyNeilhmN&-d z62jhxUSO8{AKvtPWr+yN5K|F#dVte+i@tZps{XQ+RfSer!`wolm~&D4-Qvb)vTuvs z%9rtU3!9o-He%V&Po{{@4~W4h_jyTW*{ej1)XEAM*{qEli*U3%8Vfl(!qpS>7qDMo2YXRB+eeI;TM8(ajZohXw-Q@T0 zYwiB~Ri0MPW?5_0l-n(?Uf}VkQBNEZ+v8`%WkBh1`0_6k#uhj&RaI5N36hx&!bWIa zrA#ilSpz8f7kOIs;>jPJzoT~5@k=Ld`(y3*wTm!6Oq;b7xLXm+mQTm|_}`4s%a@hg zgrC$e|LN%H0Ejw9@6F>=ULGZ7LLTx*HD8@0NWnW7mqAFdD$#r-2mV9>YaKdu5fUTv#Z++=Z#+19q%-Rv#Q z*!d0ovhTE0)8Q1*@pG%#{$?naY7h_*0KyM3TEX6a_tzXt)6%Js(HKxNfkh-OJzZtW z(i{Z3sR>zT@a_tq%lBWNN4T`d zUMxwwve(S6dGqdfMpX%3XurJaSNr~+jJ@1_^2p5eP% z%GY9Hjhv|to<5(L2|gAqSxMQ(Nk)XEAK{y~OJ^fgYw-C-eLZAn7I&WZG2y!%qe94k zB%_{07Wg=Z9=9X-pyejk$}B@nMD~@JhKo@!k^iOVU+s)r| zS*l9BCD@9!nK#kpc*`)qO7D-8-K(m!qAJ7{*#euSyL%(3e#Dw?nN7l4x>cP9ayQilo;0_554GjqinVRCx zUM7y@%3Am=X1m(oFk3xuZL?3@ZN2qEe$+Z<^|)^FH`p59?+AW#dJmYN;z=vs>`UJO zC#O7}>fTnzqUP?OGalwEkv>pkMe`Rc|H;tg@_8RozaD#XT>1`#az;_3AV&W*Fa&3D zXfcWSuFb}%ho^QPY@Pjeeb4mmjgwgTa+ATIA8{93EeeORxwz&_4D1#?Qgm{c1`lD3 zZgKy=a+dt7oM{MguLq4bMK0gGUiG+02*gj0Qfd41g=D&XJX`Q0ezB2gB>$_o`AowB z0}HBaa;mf(Yl#*&Ph1JfS!mOR{>ADHeDx$xn}(REz{x8tl)#|;jYmJC`~`-^PRWkK zl*4LEGKEYds>3gEbn0*!th?X!{ki_61ce@- z*sMXtE(Mx=sJNO!Do@PNhFMGro$7+eJWw#J7=7q}UYC^bSHx5w5URL*`$HYL&U3E0 zzt{Qb*L9WW7j(91v%7rK{Xx=$5B>F`mWXlM&t%*bNTjOd7B^Q$ipqpr$_r_lUH7Ep z_LKcWrc`hWp1VyE^PkYEC+}5*nM()^S+LQxlx=oGJiMdR=xkZ@Qz*%ZD2T8|l92B1?(UM1mXZc3k#3|zy1VO)-~RW$IxenQE)`^E-uFrMfVr1;bkrl; z?<735YK}Q~VoKl3^61}ZCP*dEyy>P@)QHQI-`PJ{>cSAXmptm0+K~6^R#lUKQf;1t z%PFmR6Omgwn4go!{C;h$%S_l|ix(a>`z2+%x)aZ9JSnmYcBb3am+5NI^aG80_w_n8 z6;=N)2Aw+l$v{-}ZIyD<3sW%0z9Y%|cS}H76{161%=yPDUtNbUeqb7aPD4 zc?kNhZ4SvlM!d}WuVSl1o$`s>VI-x3MbwcfVpYgwCwi%5g-eVQ{~WzTsWXmDnj>37 zKkGdAZRPjxXFmfVxrf3`M_gXkrB$gWBXN+!ac*h0M6ld_Y!RRm)YabdD>XfqSAY67 zg#M7)x5}wf($f5Amy%QoHx$qf;K;7nYA8h*+4tAY9_|vzCt*eYQ91GWtxm_{45t*s75%u(wwJ&Q^$uCA_bZf-zS1Cv2# zAt*gf^T?EY2sCy)mK@ByKDj>R2Kn3|hAGsDCXx)is8lRSQcB6xK40y+H_zo@D2HjZ zl&$5KfAAKLfCO73{5%rfyW*d!#vu&QDm1Cna>jLfwT!!AyXS> z7wf@P^ohUjedpZ1_hzNPzg-W@OA&rNNxXd}*-QyP$IJYM$iI`V{}32t-yd zD!3rOP5G>V2B-fg%TVr}X=&jMQ~{0tTX+Yta!!$D)t}Gx7SQ#sID;t)R}VEJl270u z6AEWJ?>={z(Sdvr|LROpl~<2ePf>d-r?;kBx)M#-?8DsbU;`xWQvARvE zE1@VcPm=e+FzxBn2m1$$HxVa3NZMU#d;0LJ+kuWl+lVEq=MFal=z0Jq8e8VK%@gE8 zkKq`LdmMh|^CArtuXzXaPA_D)fZy$;eM|^0tv#EVFam;qGTnSI+r@DZ%ZZ|0b%Zrz zvp6GTXr)bbY-)B{MBV+1?vWmQNQewh2eO0`(;rhbMkrA&EiEu#Dty;Mj5M?69y`U; zl#9nvY})-g-vx`VR;J386=N5mL6@Rk^#jD{l$7igI*%LIUU(`JMIa*~>2lb?2Iil~ z(;$JAM6Iur(KNJD!i-F5OS>PxS}q#00Cif^640?GWn`qJq<|MRCw1r6(?`E14aX5k z1%kT2P4DA|f{d~P%TNm1#3Hyr)e3k*4KIP*)z#HEO<3627vV`H`H2@rF-tq!TN@P` zz{pwFGNa&{HVlIGRX_-IYARRtENvyGm&ExYHpLZlDr+660~Il3VP^I-Zs#ea!tnuH zo#0&49Ktr6vUF{ffmCTmQYxX_{#mJF5v(V~(Un|o z2`##7?Uvvs=r81~4aKt~3{~?id$y(c_eLPNa!LNW+Vo&Cy&ZijEh5Y2O$410>1h>w zVLV)fBnq#|#vJnWF)xV^|~Q zdT5X#`~Ry2*s6w|_{t2g=qvPmYzJlGNAA97Gqr+3ZhcCo11Tr*fn{vfFce<9Bv_(w zCipHmeXlsG5F3Jm@9;*;q+A?KW0Lm>;0-{nY=?o&4LezEJe0h5m-{|OOcX(fDkE0r zymLeUZL3x8fOTizF-yMIGRekWll9*Al9d|Yj~e(RQs_7}aNDe19etMXU||eMWu`XI z^{-f7{87ub|dc8*RwlqgOfqy*SErBOF`AY#h?J(A{asO!kR_L7pn ze*W}dI?hd>)~e#l8wV{J$w^5ns;V5|RnyeuF~4k6F5A-iV}v`of5nxRoS7H$uW z&(r%2+Bu`oDKr`NWnt9`5v}BUxSBEx17|8FB zTikGgAAIu*0+h=b=;(-iaI6|zK{P5V91;@J*7o*!iWz6!*y`Tc>gO2j}5H+_H3yv7xhJif&ijHu+M_b zG)##yRXW^IECfwLPKJyoZK}DDv5pZ@s0f9#FX$e${~+N1hXu3Jp^6rA!~JSE9!5H! z_%!@f)wJC6QQSfy6{)$W~h^R5=`1tH6n zCOB(UA?g)6;J0wFk_|)(z2Zm*3>1U_wmbg%u6fm@hT_-*PODKcT)ZApCJjaU{fBUt z-`8)@p;t3A?!_$`SEdlBHo$YX6ICXF?sM|o|41CbZ67#YZvJycz<1>HhH4U_p1ia! zHcl4@FLY7wSDw!YO*{ZR%4g59qh52t^;)O+O#S+_Cer@C2J`DS*}?`?$Dm27tW#ji5( z9&2KW7ZM4l`sG&Ju1YO~o1l!_cBbh_+=1re`laMKr!JrAXFn32KHEx_3JB zkk0NE5;2Y(#bSG#=G^ke2164sKOknNi64%)34^p$E0(x<%EiIKVrai@ zwb46R2qP3az8qAk*meM5(YAAYC(GAa<-7Gu3H?peCcd2WR|5Xnb4IonJ%Dk%lcw>D zc%>kE=z4wZ5@tYGtC+ zUe59?IjZUVQ0IvT+geRV?26uvk&zKP1_sxbczDRq&;Nx>=ku<6(4_R0x6IExNJvP~ zCDGE-qW-Z&yG|0VUW~TO7~u*IJ!e^1hD=K0e=w+jV3d95KOE{E$?t2Y2zYmzH8#J; zN-cm5cNng=ODG{4r!pu+#>vYoe3DkShl8T$b@`l{@=eBK$%&I*c3zKjhJ3WVKBuR~ zb>zi7YduQ-QeU4D3Vo8x(}i(KYb4czRg0*{Qj9ZM47zxzZ%{TQ-gFB_ffJr=WobSa zYowKb5Da$ys~4A498_K%#_;PmfX*3bW-11{z=aC-5FA$bcL1e`Q+>AVJc>F(tAvI8|00_51O5?1xAvLl6r^p3vgNH!+OG|BAz*m04ztAwhZ$lTLPG zjfAdj<)DzFbY?#t{CN}6c{V#LWq^6oObiNW4|KuO2)uTraD|qOpE*MPei`EK2ns&G zTuo$xl17SPQ!Qq?4J4fBqEF z&@lM0a*^1R8y&5iG$=mJ5o!b_diGL9?u!nEHidH;ga&)2C{L9%YqdR4ut}ZH#Q}fY z<;Max^%v$%nGUk_8Ks1v|D$xtu$pcEz2$#UYT6g+@r+3E9nrvrKl5o=fEi5>vysGe zvaq>$vZs$Hg9bh!>a(h?8EPKiXe$+~M7` zpNeT`HX6bV5LK40i8vS-0gN6gvd-zEZOad9L6& z8bfg=88sPYwK6ejcp0A7NOw_5f$(B{O+;C@wds6kJ731TvzovpVu^FS^A7~+J3#+2 z?KF!W7P%X(tflNIn@z(hI+%j&?&AsCt!-gAJg$)=-TtGMdiN{3-f&gA34i%O z;864Q2b!YwSjfg5ahC6A^4w&`eeg<<6-YF~7{;O%Q}VW1p6dVj^T}yvmDOo(WS_kx ztU}xm0HuL?muM+_E|(!}-C|%F#3xb84O?~jqleLs#=ZOz+!3SW)vBKgwb*H9=|-2I|IK2giR7-@m%P1{0{7y86!676{u)HA91f zPk|noRVckojQ{NC*R^)ajsKPi;w(1a?Uq@q(KcX-I*RNakBQ0s#*9o%`zI%O_>JdmKf%cZ@b>buZr7R}3+{{+CsHq_gbu?T>v^qmSs%-Y zDO*T|$_HrFzE7Q$JE~piA(^C&~eW^wHEGKU`meSXajbeu|uava`0Z{_^FEot>SR zS6jdF`Qx+$VVIG-9Hz9Kv58hHx1~$l3V887JM=4N>zHsjSw!BwW8L4^Hk7wFGSLEX zy){QBV%sm`T83d}Qht6fL&N;S!a%d`U5hJ8B~0d1FqcutT>NU@Od<33BSBp^vX+#D z5oR1;lX{x5Y9x%G0BI#53_v7qWXT6ef9v1Lny$%^`XkduQfR4^4`p0ek zH&;~AgZo2+KwMw=GESthY1#V{ECXyVL&=s+D_lN{4Tj}Y@7+f7_}vD3LL5GRO)@r- zfIpXw`1I~0hgFD5nAt)&I?77&Xf=bG+n-NT1m|gdD#C{m4^HFque0pea;1BsDDSgP}=!oj-9#AXd; z`vYQi!c&xGTt{NVE1G-1db!|FRgS5Jkl>Z7DSVP_xL@xmDVQ)K|B`Boe_~UwXjoJu zBFbXOQQh-(FSJap=(l3kemx*mVqp9$G5pRWisndnPgDM ztF;c31%_^k2}`==(YlZvZE~9+3zp5-<>Bh0M5`du ze;zwl4cUaEut;Xpru~Y=rd;ro)ARR^aQ@457jjZ`kye?gU5--SY^WZoVr9nytu4Z2>>unVt~Dv|kJm{ac<-0kSiJ&1`4w z2<5dw?<&n*-}l4`6nno^&2x8Qx8G}Y1JHfVPrKnBm1zDq$2CmCw_XDALS+xfNETl$ z8xA{F&w=a(AYF*FeVL4z=VV5OBa6BGx{$TRyM!8PshhB6wCm^f zZm{5rbb?Nn9j=LZ+y5jTYp1*TON>-W8RH~uxY3>+q=JIIhu0w9EY!#{bAtvwBPpr( zl6mz;iPLKObHn}peNIkJ!4k0@Djbxyw)W8Q@bvVwk0GRbBBn&`E_Y_hhufapl}kmL z#3IYZZO4q!ovEq1%dj9}PJDTAC}Ax=48Xu{e50qQUpl;oMl-s*XE?mP=i}%1V71XH zb-lMzGpe1lg613^XU4_H2VD)|Ruiz|z(u-&=Z=Cl6$#O?h}DRh06g6bxX+@aqd~e_ zu6ov}`S3SJn(3S~l%Q@ywhS<5frR1deN)`fxz96dY6tRJAQCZILCVkVD-A;L_tO)C zTRaIRo>+DykUGrC!?WkicYkYk1rH@^xXTS_L6GshC`01>7!(u~Ad=t2J+a(SSXW3* zPY;Bz6CCetJMdpL>@GH?H=i0`Q1*Xc|KIpwd-acoyAEQgIgph+o0vqOT(TI=GVCoy&c-KiT_4Jko{$foaax+ zR*UPx2G#YLx~B){Qu;u0$#jNmPl;M>Gei)jqfDJ#cArI`4qV5`uiO++gzjzSd`J?C+h_}#9P3}fYibf()B25N}f><#+dLWTE{a?XT`^AoIt$K`L zA;D`&hEEYMkAc1W7mTXb#AoQEj1a|;Zn98bXKDRRI(4R6SBdkKA5$6i8=Uv2()+gN zRb|M&3z}`i07WSDEa>E1s*PM|O>;D_mQdYSkojMZQK@eTU5 zS;eR;R+ZW}mRilk^khPUdYi!>3B;YzykQ_6o-RG7o6NFn;SChGYp%%!YM1grZ7_=X z+^%ph!)_KLzI3YFMdoiLI3tu&;tRv*FQE&MZdqmKDu$ywDA&NKj2% zU++{`?<7D}GqA}>b5*rqxb(eWUnMIgD@zA7CFL2!gO9W{17&5P^9G$l!@}SW106^J zjsw8`z^02+R`15Tr9L=+YbZTHH0JgDeEKuT!!yYU&DP7Hmw&5nHPFjcS663e69#po zj^W*d(Sm`IF$W2K`y*&N`7<-qw}wBC=V5Bil?5EY;dlGae0eA$BcFPG|BDR=YyskX zJ1)qg;V8uq)S)m>TTkN+9DdrFpi(oWD3){~AJ`ai*4Ea#j2pWu6m4qJ1$H)dMMZlO zS8R8cSRxDWf(b&6_;NbGZj$-)pu#!3xPXN9e-m3%lTMX-W=V%Wu_)@-bSHZ$=@QS$ z0PS}agGjwJDYEgL#Bjg=RHwA83`NZLe-+*~IiCE?0c1P?n@oD*7joG2CPDpdV>2>7 z?#6$B*Ke*lLv)hLGIz~vWB|y7D}GAH|2Ja%r=wXb`$sXTp?W;a2`x%E4^=fOfVij|2eld_Y<>s85eSI|GnImMcP4+ehDwYA8+ zz0{7ij-zow?&nI2n=C!}IF5>&xdZ~bj8*g>R9RzgDnjhY6oucAQlp9rDOv<1LLz8W zRpfWjC}%~W_}Vj8J(yiz;X!ivOW68~@Ef~PFTcupPZ7a}+_Enw9@PWeID@EIB84)8 zKT9w~L(OY71!DePuR9Ai_(9XCaG7nEOB67#{y`ZkOd%~8x8ybfmP>6CR?pFWu zbrB{#(Ta~8r6H-Fk23ueJg&7gC0Kp{&j+1zSB{FV*AdiuNb|6cScoH><#9sLon?TS z>){2&IEx={YK*LOGL8g-By)z>@s`PReof&C1pS(_WQh6H;-Zb1M>)$mQn{$G;(_V2 zo_tq4Ug~#I1-@*E?)`vEE#+B8xwm2BG3rpgpF*OQrDZ~rlRv_>Ai?uy@1#Mnj82=b zcCG`RU+;by(E0JuF8JW;bn<@wn5iccZ0(YinDqCr@?Ya5lWuYlZAc0}gjkgrC+wJ-}=0f`zO1=IA3P>jgCFoycAo(@Y`ym1HOeG*`cIZ zyedN@xJ(47s=?Y}v3ylCO`$ADl2WO^;Q7ZnZsn$pINk_CZm8On@Ayw+76Wh>)p;cFo z-`UwYKM`#30~-K{nAV?86mB4eRYb4K@OTwhf-#JOiG;ETKj~ zKNFrqo(p8GQT=?z)UPwPO>VBP$S7_o@7!)~xV)xSNxS586#h(2EiNtXp1c1Na2v^C z82-`Z7JTA)mG5iTVGI4W*80iU4+vhtVLx57s$ZD3G9KY&wxpI&vTe$WOG?zL@(<(U zq^$`Kg0i4mKRrGM3uE3^;;#>d0Am4h&#rAb+?4TDyRy4B=mTmBj*EkY0F>fh6pkf3 zjQJliIvLho!N1Mp4@zTuIXyfnU>%2=MlP8Ob%zC{)iQ5UM?O{ z<&z8@B<)f2kkm#Ce%)NZD^8s?-NMTC%;x)vh0f#}nBA9Ziy_z*R%T~uA}g^bjcI^; z{?L`T#E%c>yP~O3&yUw6m64H`i62Z3ZEyWI}t(rYay7I86NB*&U0nM5|>q;K6A|0!!72n}1}%dG)s8X-i58 zs0HjhaD;REmz=BTWjS5yDLJ!^ighHc-?$|WiJw#l$B> zDoGQWMz7*dVdYdNLhTE=!u4iZ;Z`VEz){j2(1Ur;P5y|kaZ7%L`fk*-ZHZ-8EcpA{ z7t!u5~}Bv%=pSN1%4a9OQ;}qoUXq%yZ&kBGO8e=LCnXOt~lf+~zClM^1AeF6}jPzs&U)%@k(%BWo<;&!Y zdlV6rm)%$FY(DN=pncc71>FsAmPf2z0GjfaP9Z`rl}=8nh+;S~kzzf8Mj;%Bk|G=( zLs?=9lQMG%pCn2rCAE~Pvf%JBeO3Ny(d#UT8NuMeX0Fr^+xvpLyUZ<>$Va>Ll4P|$ zvh0fmA{~t)j4x3{q(oT+e8jMED&vk?Vbgf0&rW3qDTU{7Rg<`Cq41T)0HuL2xHQnw zw>|c91-+Q=8CygZ&fEn^!-RZA5-FIIH=%u!?twc)kSNaDF>8Exc$*7EMNUkx;GaaV zva_&EfL9t=GUn$sb#;$i+o;{j5T(wQJ5RZ|4W96NS=Jm5f=MjRON^(fEN!dBIMLj) zkaX~Tq6bYgMJVwBkO>3h&H>6`!Qii%>e41yTx{0Tat~0@_5+ZloFQl4p|7ZfInM17 zq3gccu3jnbGE4OTQUBTp?};OEG%7q2t75j}|%dW)-^B5r~ZS?C9RG zk5zvKf#e1TYpbiaTv<|iAp8}~Ge9^Gl2^{dt^?Wt)AWohnFv>8vMJq4=y%Rczt|2KoLR#P!hF*od(>4Kqh$V z-P*$}Y!z*!DNTvL{-d+AGd4CBEGF4Kgl1tJH)Bf}OR0r4nV_U{dV2HPlN1ghuj&}966%D1;VZS zC6kPo_2y&kCS391OuBEBcQ(@)v8a9x2M^|(>61>A$A>`)G%WvY(Bug69sQyGu!?fYn%3&ihHLg-0+FJ}pwd2oC|=&b!mU0rcTd|590`V2uDlBzBj5|rqMks}M&+bc z5fM|e5(DU<9P%C=YBpc9z$qfHQ_*gc_ zu^K{pW(VS4!du19QP#$0SsC#2$+SGQA24V={#Oeyi|5g#QdknQPh>uKOf^nES(f*# zV-KW(|7801g!(Np7wK(;nf^I=b*vp+B}+rj+8IoU(^e%}qs~zowro?gROQ{`+`j1T4ksj5PK$o6{x zaLyORT>bcPC#Xp0p)-XdqCEZ7J3iFpRG|1KLOrmED(PJ}i!Q0kFh#Rm;K%-S&ERl} z@0w7h2pg(sP()(V)&8^EA)`?xIH>*CZz5n^KUtr4-)6@Xz1r-+zGAlDHLjP{%fJ$c za<51rR~jGiQXGu-T$`uoZ=<5im1*Nc#_wgfxCO`WC6}q#wp^!z4cFxo+7TWxf@HEH zK>T&nWAF9l^wr$VEJlHC<9rTImG2z*z?cK*vxPahx!oZ2wg9AWXUDuo0n!}JnwF^d zvpjqs=wC}m_El|G=&GvKzs+iR-<-#P210r;I{*={gG253?zB~-cOWWKFE%0^6#_Jq z{P&_$GNrTJusk!is7Dx_8chr{j);M5s6dkc1V+8%2*Qp66hkZwrOSkP($JzHyJR0k zbV`HoH8uYD0sN@G-AKI;&-4GjH2 z1kvspo1Q9F2q;V7r2*wEKn~Tuz!Ykt9L3|?-!sqXRK!;Xf~%{lfbfCEaTOUZFn#pr z2d6%pv^|ALtZ zsFAa?vnPpRz}h-6D{cNIg~E@TpPpmzmf$!6^Y47xfwK8j~Mi?dCcmRbt@q)2}pylzXE5~EzsJB z<$kJOk-w>gin(m*FXDfV}9)Bf1p z_)xpddD!t(celq8lU9fAC<>k z<-nesC=MIEx}Pi=$oXtfFZ|rSVkVh-4oETy#Hn49IB`_g$(f;|?pPJA zahR}vKjO&GzGawt2}!_iXaeCXZ(*Hhxnhg@(dB7-i`_us{%LI&GJ!};{WPC1Ed9Xz zmpKi~r)|%=8IcsHAmjI1-^dXg#XBW)s+26WMotp(`GUn!gvo_nY)}4u)sIQ*eXvo; z0tjFD!%@DxDW?BtU(2ivj1E^up>OyuhDgitUF>UeeSF|M&YfWjs}Nmze3Gv?*I1|$ zF3y*z?9D-o&X_BH+E;fP++BB7>-%ePvDs)RUbw5?ICz?)GmUH^W^cR?lyLz{120}KkAS3^7I6? z$cP9CQ`6J$U?4?N$*&C7;-qw6v>an3JFQYG>s7`w==5KLH`qZN3SMWlC zlRjuII)e_@SEftZBvq>3Sj3o;4$TuwGzI)7pc|(5kqn}h%l>nS)^~ISxuv|v#oYs` zey69*0CW)1;+3I55CxFv-xW&_3Sd8N(AK+KOqMMkHP6DGLWA0HjkEC$BPpJwu(eTw zh5-TZkOSUC>}rt25n9T~sasGcm-GSVvP zMpSzMkF0AOFatdMzPb}vv1&vW(ukr0#unT-cz7lviXjjf%+~FHrB%O9g2Fl0G>(iM zaMpwTj3iTu|Buet#|j5`_Yhf4(qM1G-alQ_<-|WG!vtu4ECN#Rp)YqBBelOfpBDzt zr_U5Ywb0-tlvt@E&|}$T)NrvJV~--V?J)5_`(ybnB6Tce-i2)tKf8WDcnnA{ZB4%A zsAy7Ug$%LLgV9+pni{pjcsKn`w^%yFR7|E^F1ZkVC+Xx$*t->&!<}nv&0BfI-Pd`Z z?keCdfCCl$JnO&g%g5!)FW$1Wd%}Xne5QfrzBqX$<{%nX6jrT}wuh&M44RrkyJKoY z%qi-3xo1gLoK{Q3st>N$UD4J*`z^l2;_A52$H%86jyF-R5$!o9Wh{0@1PHmbzbW|V?XU{ziwP# z7KXCuOuzY!XQXuk!+pi#PJ+@p`KUWjisSlQ{>WhycKP6$>8~wLEr!6iV+GHsq}8LM zKcK$+U3EQ?r`Y}8!WQu4UQ(|ijAf4};;)LQsoi~%E6v%jW6e=-U6F0l+UG)CF*Q0E zmCMN}~wfbP6QsRpi zroHgLc=D2i^@8Ewdhzo7Sd+$mS6;OlCQ%3!1;OHArFXmiWMX2Wu8vHMGJ1H&1fMJy zDyuujiVzt8qru-MWB4c8CgV?2w(|uZ@XUfYm8lESPKnY^FHt*HKp*YOGibpE&#vd} z*+?4GdHL|#6Za+7F{x-v{>#UvlT5u&**xZ^$ir4hFq?3$c&&Zz(wGAdOf~LvAsQeoIj8RZeSKU zOr_@EmING1igh}KqNsVyF-GZV*BXYAeI;fN^j}S*<%*TJx3-*t{lSLISB(XUAVxB^ zLzhB!n#1lV9eWnYx1%#wLpKd^a4am)%m z^qqECuu;`x$bmbA>C(*u*t7nBD9u0cjqRSpa6sPp=V^vkrDVl*>B@5YF7+Nr+Zl9O z{PzD!{G&7f8dK6ngma|$7xBsMPa5({)~PCTXK_Muk)R2FCik-m)t`+NQj>c9B67B1 zI5X_ivw3`$^KK?ncAZ1}#H8*^(Z?t}>2T%2neTE;lvr%qq+deya#{4g{o4 zIHQad6$I%wzUIf+2kX7R&+7;6{CL465kyl|x)uu*`~9JMriRd{0H;eN5;p%1vQTf= zOW`&}9R<@7T)id((d()+_TL--I3+#tg7SE240Z!n2#qzk)n_bws%;-(6v2Y!_P9NK z^Mj>~LIgezQm829e)tHP;naRfU|1-Q#K4OGB=69Df~V5-DhW7P_gY#vfXyzzIfxFFU4c% zIT1s&W4YggJsaGNVm%Pp=W7%c$Y^3F!a58CtWRuH0QMgBT)iuLDIG6TFD zr`arTC0|x|J+44bx99^#h$rpLM-w6R>-F%QU*54~Y#jmBh%CdWWKBdLklSgzpN45m zyU+x#KX&`nP}=x@;%q=1F;J4Sz(MUq8tEfdI;jFxvNBhN&`OuPBONAl$Mq%S=|W!~ z8sN}7=GIU(PCUUg1f8(=`kv?^Xn_9SyA!O-V`F1rGw$gTgV9EzMiGlVW$wv*BdME^ zh6zW;NS9cn<5pbvqgSK9u5x_0{$B#&1`l#~{5)f%K@*9udqH$c2r(Z1;WbRfEEf^W zyZ0rkbiD~Q^3yOuM&d|lP_%-UJuyosxcXRTEU}Y9<1C=-5MOcj-+*s3kqe~qDYAqE zfTsWo$98=?o+Driv~5zs1n9uBts7WH^!4?nq@+wt$ZHyrx*E@bMVDwLl-T!;@Q!8W zB-~W-oefQ!V0sHCA8s$pX|QVsO(ehu(4fmK!&e%7#x72Gt8blNyO zH#fxrPW;NrPX_@IPEk=|Ek{2)fiDILB?^j>_jEAY#Lo|LD4ZpR9e5>_K#MEbgh>6= z-~yXJ*A5@phZ)W9J6mz!7c0|_j%(O1!L*Bia8N3s)PL|#YjkyS0U}9x^mlR1(n?B7 zc6K$x+xWExWvWAFmF^B{rZ?s-S7fYOU&nI{$G5>nJ$nG)+~KE1kbyDGV7PVlf6IZj zUI6$n^JKW-%is+b|IjU4pj!MNVY!Pu!A6V)?GES+E3tOn~i~cU? znisLNJL{h%PRC4j7U^YnMi;WuVX(7VhJmS~EG(6n#UTH=|F=AL-|j%vP+5tqxjk0> zvF*jnK!HllfZv%@H}eaX`{6E$&VHjo06dBy@|V?*&Nb_pmAbwOt56lRW$4)OK=A?3 z+Aga~CNHL1MnT>*uLhz4lqlh7@fUyE2!87Xw^0NN_P?MDSU;?JXagj*MEBlnBjILKS1iXL4C<39G*`k=SC|2CGoW!}Jw=pN4hxAJW#(Yixy_ zxjZf*_kMDfyFjZ<_L$W5>z6&vuZ1FQ+Q?9n-+&x& zcE0oO1pPIDql{QeWrmMXS5v!x_7y4@V*Fy7jvh!t+OnNaxgEdfmiV>qGV#Z8?(A$6 zg!YTeR%py@JXY54I&T~#%j_dYy_C7OpY7EN2bMH?`3 zOFQ9?i7D~QrPJW_hj4E?NvnGCuBNpcrzvJ8sw4w%Q>{yd4FeRfad(o(P{?Pq+pDXh z(o)48b^*_^%*;%X9Z>3oB&C5I;remMMwO;BZuET5`rNCN8y$Ehzkj!1X?01vmjJ9n zn%2+X`~T!k|8b9hTK@wD{D&)AqO)w#mw`|CLhllo_-~F$)GU=|0zse(Mp}On71eL$ zM6}xQ&@D+q*ILcajB-boQK8XDo6(&8E3}FS8TKclq%&*NlRVRD;UZ&2T&w}M+GqK# z1B4%fc~xVE7lf@GN#h&#YzKt+<3%jQA@?%*gjeNiOfiyQXZL;f4|*KSJ9FSGO}I|U zkp&9`?kAs6UWUy2{J1cna)^Ja+inMrRqRLWHqJ(TidJS)`>3oG0hJKR+CoT0gEzoh z`(#{KkbYSR%VaKYpJm%8@!N%?H{6;A&z!632t+!4hRWIlh}_hd&85fmYo%B^Od zavromiD*fqTGAIefAK8-`2x<78^Ns)!l`*4c7r%wI8RrKf!w~dcUK01fBfDR#@`4- z*fnPz;hNInV`7KVk;lDvnsVS=8E;MszAHu?!3xC;e|JJ&sFkgoVS#C+IY z+u;HihoeaRiS( z#JNv;b@6DF>c5iJIWv;&YzLh685ik^d`9I?uE`~wIUwEaHlwjBP$2t*4XU*gUu zh;=E4DsVnri6$n~XLLv;W`F(kvmocspErS~>J{Gij+QE3}(o$qBkkX1*fhPX{&KpBCc*czEcis3qw z1GVQDB+PzE=G?X3Ca>F@n^5ZZUY3z<2-fy&@FLG{JA#A@7>Ku>L0;_(AYosfpH?kj zz2X?C8m+9R{)sHX-vQi$Jm20sD5W5{@Vxllj6n)SmLEStLZQM1qszkWlYZe|GIw(| zw=nn0tFp{m<=;1(#t=I#h=7(56%p?bj8qoq`*yX8wqzpF{~~mH?eixC-osd0ECq+i zt=g%dz20do+liXxZuqtHl`52>m*tN!O3o5joyU-743`*LHnk=U^o|d1O?>-uT4t0 zU7z@*BMBN~{V=|C1k0j{tMB=5zgL(#l-#V+q&s@ZB#Ks0--<&e_#Hotj9#X?ZT-@dJl==OH5`Kl}mQ9w7cdVWxai%cI2m$u(g;syf2M8Ab zMMv+Eg|)Zn@~WK*?*xsGyyoEaIK(vGO;CI8=?Gpu$GFPFJ{JV}PK)|YHC(k4J!qjk ze+%m@5It~%*<**iTIf`KI1xCs#B;{yxJ{bd7^wQ7s0ou(7b{?X{V;!UT{~)5!)RYR zYKL-%UpI=~+K=7Pi`}^}wg|OuxwYhaLV%|fl|lH#-qlDxnSuBvzlipNP;cD149{yh znvruOO72dq-ZUaY^E25_dUy*5OO6qRj-5Sl2~6ixA6}WJ#D0^bY20P*9X8nfbBd_z z1;2QOarF@LcKkH6`OK`j_8qe=1$$(8x~ZHU+K}24GQ|+Zm{+VTh;4pWzRSwp6)U`r z70&#`h#>VMA zaVTHHAKMKX2!3F^fU~*yE8R-ReF_mFDIsBmTQd3COWF1>)VEMxyUFkaKD#O=h|U59 z38fiBmKzQr70iwQHfk=V)KEG)MWysFMhifPu|@8`*7cdv*rgll>ZU+?Wz`(;Vukfi z^7eNQH)vNW6f{=}IQ+M6fJ0kfSLe)^(~GudMh9v^5)+N<7d*+vSQv^_)|C>%tz!_f z1ilB)%}m_wzCw$hBgTGojHtxoSx2Kyy1^A1o!yFFji3aCq2EK z)Kpg|QGb0&mzQrA6hjta1X{V%_t)=CxggnS;sJ#nV)NX*t}GCz^f8y0tdb#;D$ zaCHrjh_oIW5Q8)2p!r1495vYaD!M+FQt!Jd0LDkb5kKXE@ugEe% zKg!7RxDBIXw&cDtX!9*dD*Q;Og5Qz->KqwsGm*&2S0{;BS4H1o8WKvQlH{K>bxl)G z7@=zU{!;{-wDa&eE46PRvhTYuLVU=kCBoAu2T8fGAVxlxtZx!MA%+5rEC41T2F?Z( zF@~Zb#vy##>CBOu_X|^t4fM^F&hq;(D%}p`9HaQXAK}z(7)DzZe8eQnUqSrE5n zb8$`T=d;gPL^W|0DPrS?S|l;PXN`}LTV?&uK>Te+-*>pSL&$S{zVEVkpg1vLAiDb+ z?5cNgyO_H^ph2#J0|64w#eS6VY;f%1X>kquQg*K&YowNkcPK2-WaT5WF-WH zgP5%3jZB@+f=A0(%kH&n{~u3Z0aRtQwoA9Pba!`mY#QlCLO?)TI;9lYbW3+C4N6FZ zbc1v^(jh5um*?F7%xsc^jFG44rgNk9qF zNG@l*EHI5{l1p!4=UuGjLXb}U*8oPEl$c2LG>-@ct_09~sZ|bUd2qM*E^w{~HZn#6 zwnALI4HQ<^)^bZqN-{E5TZ*eH02kJ@g8DTCTpdh!v4z&g2HJ=7!sznF)-X$635t+J zD^ON#XxOY(UNl&uldmy>Fd^)7v3+rYmNW=Pf>CP~uw;M;1Q3V&PgK#scaC5@ap10M zw(z0M;X6~`8z`Mp2$h^2XgCnE%D@^Qz(GM!Qc?oyM$GU+HqKXr2bK3*% zuPuRRrq6gVU?6^jqKC+m-t6?e>q9$EmoyhE*`6HBC;uc!GSlbnvO(PJik~#b@k{{{ zFa5;HpM=EsU5Cm}agix>5gl~p+P@H1@|iR5C%qqVtDUbS@_+ASwJ2wlO)o0(#bWm-+P31WFldJ3M?qi3TkYVb ze4AQ8Key4Nt#*EMEY7_PHtV zGz!bgNW2f^Znu8XgNe-MpP9XXFyF$nm^VVLOBhb!llxKg z*vVZMQA~KG^hYP?dEL`Xa&t5CI8`S;f*Wzslo(s=N-MG5sO zJSo$xsA|2-DxaHKJ&I|8c%Ghdye@%NF>%0bv;@2mbNhTW`=M09=v;nS{fV}xTGk() z<@=8aGq{yhcurKBwFp9HpTZE4knYsZ&PjMZuh>COeIMj`Ly_;7#{^E3HeE}BTpG|X zy6y}iKdOHWU-!XEQBEFyDd(+UE3Y0C-BhZx#<9Hpl;bK#<7q_FSQ(QY?-FQp@?Jn9 zuF~p3ofMDD!{MWF^jvva5F`ZD3gskcnlMGQ7RSXr6oKex)! z8kNRzFG-EHYcTPpkD$<;@UXl2aw;Yx<*}4b13~73CJQ*lUvz$B>fi70+d?6m?jplO zL%xR1stg?qOyx_6=m;VE`}+jCW^lQ8c}W%6r`DghSx>J__n zJz_s96rpjc5JauGxw}pn-Q=Tx<}yL` z1-LUnBgSdd-|Eno9PV!@PT$KmYm#xcNDK?D<>mh}T9_cO{kj8PhM=CYaS61Y0ndq2 zBFGEAxovDmhpt+}nDm%{tE2PZ9YW!b0J@gOn73&83wUuo+z!_QJ3E7qO)qK1#N^{h zlt@`$p}aVY!$@bcP#AcV1N(9j^?ges)1=B_bR99nf~#n|#H$AJP!DR4k#9v$xy9aO zN;kQs%(n8Rilv@B84N>MEb%+7=K-@4G73u}OTP7jMhzCM2yb z#&5@V(Q^Hgkd~B?&ifYjuGeVt{`k#lE{V@3<9_F!6o2z?$CK7ly0;!BLJD<}Of$H; zb_IMQefbG5zYHiTizz_&$|Ar=eR`F~rB{gbMfC|;+_|rx;G_y3)Vx2Olh%;>KF186Pm&CIc3nF>HC`=LP^dXvCnK@X?fA1OyLIh_=&Dn*idr?wJf5| z(>+OQstHCuwxD5j9F=+Hn4r4IO>N-ebf771*idgnaGob`JuFx%&&@X>Trph|f4?KY zn#D-Z;GbZ4(M0Tr%LUo?Su}j|nZT(irBAnK3(+54o`dz-Zbfym8W1qA!*3_1>kfBl zL_GR_chndwuGlD>y3xP56f{k+-&%ZXXhiJ$6C=PPq@7QCEhDcw9TU-nS9)!_;mYg& zkP}H`{0h0{QD*NTP?k{OaT(^~UXovCFM7hqZh{#`6*-#+Q&Qe1iwhR3Ea3P=eZyQ= z>V`zkPYTuadxTzkZK<*uu80?+;A^6Z3*MPq)a_;d+M}1!TS?E-1tqo!We}*M0X_}^ z1wPUC;npF)=W9`156a(TLSr|S6KkWRmChaD8FlqGQbtTGkSafr4fiqd`Sdy4mAq8V zalVF{pZ`y6{JvWfESAYPyI-MCH(fpFt>I|U3vYitDa_%*7;;=M{npK3jLpjhZf>xe z(`1h!Ux?jP`2nh%`X`)N_D_w~nU>lP**3qce=$tb(R8(cN%gtZX* zp3-p&$J%h{Pnr5=1<4!J__9GOJr>=zeq~TOSXwG5AOIS&c|;VNU*}KSiqdK#NP|*~ zbk{8LQHB&{Fc_%k^2|AN$(t9Mnwd!wlU3H+j1P{Eg04ga=>aR(aviWHmA=Z9u2@(7l+Jp3Y^7x%!<>ED)D133{;Y#T`PWRo>9l)b!mhI5_bEYbq|w%(%r&UjW)$P$2UaQE~*p7A~zfufP8POXD?; zcMuL(S`?y6m(T5pZRm~Yf6uN}J_kL)Q~Eiaty9ac1ke2?Qdd8HzXcZ%REx{VhXA!I zmxCjXr5mDewyRr&@!rSfZ62drwc0*bL2Jw4*}P1C(?8|kNcd4yp4(Q?Y7d+1LzU}UGekLqx>F{!2{_VAZuAj&5CS?ei z!q*)21vI2Ab>^TTuFg`C?=6E%zM=Bah@Pe$gG70>Lz*gwA&22ZnEBFE(3XCl^V19R zA8_P<(M0~fxLQp(|0?)?G3TY=7>ptxJ7HX;f@r)g0xOeuL3Q=oZ70=Q&6yMjCqkD2 zOJ%2n!lpKT63gKIyX`DSy75*TZ%gO(lVK{!fW1$!)h8GMzT#r`%ubpD@Xs_BeK7)2 zRWril9~&okLAugmY%PI@7{%Cl6QGky`Nvb zpI9RKJD<{H;(1^Chnm+@lji&tqxe-e#eELPyL%{3bQ_vO-hFQVeGWgSxU>&BAL4P% znOSY#cya}vUi+|<(BbL@>&$JnC!Nt*QBkxWl)-u{Rj5`AOQnb`2txZ50uc|xvW(yF z>__?zf`=df^#Zmty^d>f{x^W!zefM7zMGF_yeTGCfVVZ@LojtvHjuZhd*tEL3vN9$% z);c=P>HGA71LR|Y?dvS~d@Ou9dfY53Md1J@e6;w4s!5(%S$SH3sY>{`9U_t?Uf;M(-`%X|%6J`x{)2~mO6M)!ByMM}##_TATfO6qe! zlLlnf&eP~$OO=3YElbUYkZx$F8wb{~0>{lDU%<4VG9{;^sprt^BSely6KJ%wWs(yF ze#Gww_$~ZkaQ*Lq0qzPN8c+b@g+WZ24=YGl02Y*kJtP+BHRZ%}t#sTA;!O$n{TiGe zg;?@q;V%2vdDU2~LJ^cWVQ#eFP{?Ep(pd@&SRG5O+(xE$to>=}=c`f0S;+%OdDi`Z z&#w@_AvHtyu?%M-xfe&e4}MpDiY@*uQto%uK+sYYI(C4RJtec}-V-+($TPOysBjtp z<1!WR7?gBjTDbmsitO^m#;IlkDf3CD^AY;8A7aa`Gl-<<5U)5UZbmhhre%cR2SI1tao*d?tKlls~V5M^+}b0_D8e4 zL;t*5DJdbMSUp-{jI%r;?XL?GITUzG)zoH zRFgqcx!|s#kkny&^VI{+o-Z+tV~~@P)F$yVCsnMC!aANw18Vxa{)69q5+}f0x>W36 zE+C4qm$7K%Gk(3Ydf~Wh>P(dxZH4|yrIg!4_?@-L5`?V=+fmOy|D~BjPtNzvsLFXQ z((hz^SHz+hS>%TA6mpO|b*HT6t=v=6RIH z3Q+JN6AX9y)_EAI7YQ!K>A83}eU}B+knSCWSu&pQ${ER__9E1pdRAP8xPM3_J(Kqo zk)W6qJZbU;@XO2hH^rbgSyAqJkY!R~=i6;#)g>4xF2O(%uMG@;C>T5wtHcvK$qd-fK}iXjN71 z91$1yS&#Djyu2#%l*+{bhP3}?)V7*8M;a|}>F(|>EuAo_NF0+qXeB@tjTD+t zK3uLDJ;gnR{Uua}p8>eP%V zQx>&6^L%B!bAcNXH6Nj3uxE9gtgQA94oBCdk#EwBDw{{A&`dn3lLmoxp0FnfgqW*- z|K;29Vey-hBgnLMayoIG`pbcCsfGwA4dOON6_fFpE#uNCxxX{>Y!WPPJCzXJ zHDM9&Zg5-lmT_CQN>OVDb_~QrW%QbKI{EXuy@|_cjNZhL3Jm7(;n~01e-ODAKDa%F zgmys0F&E(0hBsTkiJuj6<^_DFbd$>Ml`_k1#XN4ua9zy}TrtpUFo1t73;ys+s)N&; z$9}hfjoe)gJpf7QAZWTpx|D7CCW_(Jq#yar3-SD$`}y_yj`D98oqH4MYn^mIKTW^L zUy9y1C0=mW4$)_t{7p2W=>ci-;7+TQnsHFhxMrEv^^T2tR)%KV0ihLFox@-b|Oe_I1&?kI_k(%{}6O-^4sm6aDTvSVu|vh!awSV3*sVQ zR2DFPkMzLqOt2Goh{7qg+GwV?+QM)>(N456 zd+8vy?sdkxf5n-%c+gT=!DvfoWQxUe{w>mqKBuzVZN@t%EUkz-vQxiKQI^1dz=B<~ zgz?Lj)wi4q?!;I4dBrdAVM^HXg%=>-Gob0#7T?p;-ZJbOMcnDNj;f9zHsG6CrLfg1 zr_R^B6*xjAy>ED7@aOC5(o$z*NN+f9?tb^LQq|Bx|uS7*wo>*z!SII8g5e-q}_Zd7N ziSuwB?+Lz$?`z))H17Mn-+j&V#YlN){fkiT3{$Ud3R5O8cUqOqI{$~GeeN8v%D__| zuKi>1o})VXx8S2Xk7*}$D>*38+S##4ad#lNYyi;OFDFZF@e()>ykpKCkB!>;{!Q+C zgBVv5Jw;r9mk=KM-$%k&lvh|5GtOKX0N=nYyk51O%Etw@%Oo)bJ#=krYvp4=}p>lAk2n8t8;bQb? zX=$Y^ESLR6^)&!V*Y((!3i`is>4~S|H#)aa~BbNzSBgFw;Mh7RT* z=%ga*r*6e}MP^G8odlfUvtIPL$jHb5>DPx39~y_7f+0VU7gjJ2nrs`FloF$(V|O_W zI;$$Su~$wTww{)bI=QlPa#m+%@L#_C)qHW_hz{RqZ zY@W+-#Cl%ijD3^jx_0yD=#N~tm&Enm8T$S_zwIIFIN0gc{vx<`u8H#GG?yI)>Y)b+ zd%f%Gs?Kv{6gRffP4AJMk_xoVGmExVJ8hY9o~CvldaglgDG8RClhOY+u@l#hka}{s z_SrUnxTRn1P(1dqP2xL>z^lw$2bAUVn%#k65T)1$$r`^JA3^yrx3n@&rEjvZ~&KFvjo1OVOdHf#)`eO1VTS8nCOAOpqNmp z%A2G;+RMkwy`rjGk6nKtFc-;LvyQHM3s-NIPV5)rmTg zSiW^wMCFVSq@V)=w|xP(GvwrPiS_R7j{faOYV#6zUU1_g6# zFXc`5%cuo8x#gcxz*C9E5s)(;#T9-xPDIY-#%J6IdWgKjA#aFgZTWCfVS8Q| zGPl+unq7Gtyep0~>cK@r#PBI1561o^^M;QE>?I6YA3-MGRJiKDuG{zT&ski8Mm!uJ z@~7>dr`@l>W}^kH>P8HNgoFwT{k=bh0U-jAN0DsIa1f=NNC!&h0kqm;DC-1VrRxTB5-7)eYxM!}DTjZco#DU^ z2l-zsWkn-#y#nDo7oz=nc%C%wf{`0w~e zrmo*!!hjqJ1drW`xrtdkODW=s!_Jt1%i8zh?MR#bqy2r3lH!}USXA8pfQJRg5i=0| zAP?PWzaCFg`Ul6KhxO?Ggwwo!eTH{=r~DHhFRnU}CBoHA!xLYT+PeChz?)3V=zHZ* zHoOmvCupe%Zl9IWcb`Daei)4YSc=gldS#0I#}W(PRpgp0uNbdUvfbz%#!Ab>e$!V; zX~Jj1#RpU_w>Uj<8$HQloYtb?IlF|tZ}Ukc4&|u^6Jo|Mqr}OE$}Bro0!+l~pm0;wyV_(Z~r9 z4KlzR+EbBYNck@+<4iMIFvyLRL>MwyNC0g|KGeXxn-C73X^^KS=b)b8Jkrw~tpi0Y zZ=H}m?X92nwdlG|LtnJ`iDGs6{J_`8`5Q?^cRbN-`GVS*B1haes$Dt) zI0fsj@ey2Oy?GNss84u(v6P3xeQvjBII`iGq&&Tkwf#ukESjL~mWvZ*P8&${osgmJ zT!?2A{PwfUH>Hx1coOc4$*fk0)-_=qMRKNITd330s!u1F3M?@WcAFzqAKo@wyI>|~(ezC&xzXgp;C(4fkBcfD&y%iNsJXk{ zr6(Li<3#+r$d zH9rt!Sola7V{T95EtWHBTLDr*Dk_cy>~lbbsh*KhEzz;quj8v1NTF(_Tfg12gx!Ru zOWmAUB7H@Zmi@6Xdbqi{0VD&e-P-2V+I$>7v#!u+>bcoLu;48YB_dhsbD9Od=r|e1N5I za{JFSjVD<4#a`!daWKt$StuHKH^J;GU0J;0gIcpdl@|>TP8X_p|-pblDw*HRes$hUEUaF9=?}0xJB67d!o=W#99ju*}h?gy3EWKH#!j zzGn;_{(COP`GsdI*NxJPE8bTs9cv#JEf2ofy3L34sXdy)2NZwesPvbuy16$HTyHQr z>nfdt#a;1wIpiYt(lS8nGp=SXVoC?Y2BD+lF;Z52rBL8ssgTV zd;>ktYN$0S;>Iy~>*YtR?^2)0eX31h`o*&^?v8G~os3C;R2)ex-n-c~{htrC8!OjW9Ta?y4>SL%MzF55|5I_E;C@0$L21?eHryLJ8^c& zZ3k>eD^50bb3fP)cC`WX3F7+IY(SKZySpkf?khDlYcz|Jq9TxM2X=!MvDD^Gm)<{L}Poss4WX5KzJI^+bc?^2z*L4^u*fZYB1 z%d=3o_x-X(Ef_0+&pac8B($q@?~1PnnjkUWz(Q_!+7UG8{I0dzYykZ+Etrt62)bbPIp5N&uysdy{HU@V_lbf$5*l6vbt1 z$;^T>f*PW#_I|BB=o1)1cXwxVuQQMhFUb|%v*w5>*Us@||1KopEhPAJsI$CettjF% zkxSk$W>0p=PxtTo=rpZBp@&GJiR8fTVwxZSGHHVUv`$j!a4dPwife!HkV^W)-d%8K z*gi>Fb8}`@NAn(==N*O*O+l=T2_bosq+J)o$l?0BSlVhr6$bR0|M53kPJjB@Gfv!-5)Irz?3 z$e}~Zga))Xg1^SnzSThB1M1fYXGV?$uJp!XoaY>SuMQ(}&ZSo&H{?L^W^bdf$Fc zV0QF=OPg*2>7|F2E0tlF;v)Er9B(U?7nj>{(~BKQAW9@{sD-GmfV!1fTOm`>n&XhI zAn^ouG4(ydu~a_i7FFa-IARd})P+DSihmkOW3pBcU?%ZaM9fK9ipdttT5Ot;3`3oB z-pmAY1(QO!qj_4;fgxMP9Tvn84Vrvuj7C9KTY?@W41s*EPq1ZnsSy?A+d3?<39A$7 zLlZ*fLTX|3Loi~m5>%wZBnHL%LSm%YvtH@Uljpm?< zVNP4-=;niy=)>F#N0LXl2lX9e({3YY8-daVj}KV?*uQ=DEhD=j|g-<}67O57bed0WH6Qn_fyU00{Z`JFbdSU=)n>WG0br1kpbQz>D16 zwUd+F^0abaMfvHJHicG`RzaWzH^-S61*Zsy)%D*5wubn zY4xd80qBF<@0R+JrIxe2T@f>9D?JFetHFft+m^p%0^I30A0Yth0L{(k-XQ-Q@GuAN zVAmn*2g#)%GtgO}+$IOn-rRzPYM{J8?*I(`iG#C34`c%-ZB&ki()w#(jQAI-qp{_MC1*7j`#*;DC7-2%lF=)B1DpR zm6`&>bODRe9d@{mMF`HMcK{J_<$ZGJZ*em2t%`E8u`OwSyoxAXlkE@u=$S*>y0yH{ z+W|Lmck<>m?muEj*KIEVQvS9Hf~<)j1;jUdPdeVbJv&e^lR72;BXUOETLvNazMuTO zzPaHX#N`GUPB4s+6e4$otv(H4(ak+$Se1fRNA!mAYGY5s^WuVZNV{?6^L_R+UWUlm z`%6ix>E2Mr>QLqE%(xiQ3v#;fc3r7Jro7x=u;FXsViK|q^aL&V$R^RD9R1R{ebRfp zJJlk8uZ6_o`uqZphyr>y>en{v1J`O%%^p$7+m>zCN?{g1xXeE8V0EWfN*nFLx2N+% zBUJjL3G!e6B&5MP8i4*sGPVj-V=_H(!pqnQ@QOOlxN?kn!auFv(hC0*v_uvBqoaic zZ+q1z!oh#l|ET`AIiStlg?Tq3`hOwO&U>-I!hXKG;JmaeE2uz6gd06aG_0Y zg@ou=7QwKH&396tSa1yAC%hnBkV3A-%aaSm2$+#>L};c<`G}d)V)^F`#s14Z)iz%=x$Xk%{$2bN!5^L(13B|iHhz4P3I4CazL%~ zb=7+GFGV%doGI15$)~3kOmcqiU4qheP?7*PmKhLGIhHlZH32N80D}OM3J%2vAXTla(<+>F zUl&VEw&PoL^2$z0`Gp6LFLaauv8P6ZNmW_-OLet67+dVTfVa*wY6?)-H5pP?+@H;G ziIreN{r)44pPHG`(bFr@U}|xw+`1A-C{twskyrNb-Z3*X0~i+2wsi(AyTxu_{u4_mbRY|_8^^{icuXG8jJuDHKEfh*AgR{FLr;F7 zp}nVgq!4*zZ2+>&_OBBQl2l6~9hQ*?gv&q*GNuRT9>xi#4weWrPdAdZyA$NGqN|8S&JV z`9jzDvBHVEl%xA|1#U+RuRCK51j`@EQEdJBZ)PjvxH-X3jQAKeHFhR7E@q<_+dAS4 z4pheb(SJzb4U^LFtLd|i>SPr3?Eh(SztAfmUlXOUsBnzyCN`t-WR?^gqKU~;E2X?a z<%#DxrTST$myg+k|Bf$s{(VBsn>>s8f$jCsmSR5km*?Mrn%{rt5aLfx!!?2WkW3`N zL;ouMOG%MX22u%To{8L+Qmt$x!$1v0IJF|)is_7vKIawuv_HRQnO@1_&_L6m)dg-V zIW&hf`8_;zw;h8}BIfM~jb-+6$>m4Qfh5-+gg4R^RL^--r{^Cm`@Cbw4h}ZB3;gI7 z8?j9IZ&CxrC{js*>Z9Xtw(r;DKOZ4;YKUU)z^B=mu}*n&CmR762v}CCIB^GR`+_a! zO_CcoBZN15+b}98(HK={(k~@qCxoEm%7Cil3|UMJ^q0|jiSXxgH;zyHa`t@jW$tYhVAPYE!m4Ci-6 zWeVVesTdfn7aI=1mI3q^ytqH#w>C61l$9y698(-+bFb!Bl{> z9mx_-qK<|_q1N?PRhTnG$F38q!fmwNxl|}^tDQoVUg?tH=pMLxW(vg>fI0(d?DcSf znp|F7fF-4{pkT(%1BlGQ4x_*z#LGyy5w?wl#7Po9msf_gbKdnfkuEAKD)T?;c#+xZ zw=Xc_NO9^Gh9U#&Ki|m#NUKSaPg2yW2A)flAC(Os&8-tSD_4Xf%(H}!` zDn2G@E(5s8I7*h(nwNI%gYsz=$*MVo#cJiea4Z?l1B!Dg)(4T(?sslE@nV;e>nY^< zKREvg1D{5xv#`YO3@0C{`0sBIJb6ieRZ`9Y`(6?91z>?#bSoC;d|IJh?XQw%`~c^w z(wFdVPEJrtr(CZIy zjw0IuN8z5i1>*Wa7gx6(p!@b-yvgl>I1XzJL;RBTYO*7*->d%!FDaZckFlhmc@IqkwHFk?=w>OwfOF>|Yu ziw0_~h*Rn0$a(mr!x$#MDQp#O65&F@W`f%iR8C~85<}zwc_VM29HlB}hcFu%yr`o- ztpzVtEES;~oKZ@H{=NrZ8BK%D5&l!(p;oOYT}u-=bT{jI;GSaW9*sppqQw>Ohl_A3 zPgJz0@~h@17Bw~jG#^)|k4*j+2HsLq`v}f~K;-eviu-m5dVR3e7>5pRF|~}-L1>XH zurGCeE!I%#yd?{T_#DL>r1t+sc^2ci>3UnZhKYS}O%ba`xUe{s&K+8)Lq;>S?{;S6DlrI1+z1!R1sSF~7o#v{i4}RIb z>Yw&IIJ@&N$zxXx8mVeOzxYOLNYcrb>br0+}Z-@C-B9He(!tvUUoX)xiKweKb2)aZ;saaZDT8_ZJOo4bC^!42Tu*xTU zTA=N^iKU@TB?gk5#wVxapR(z%eQxr5!hA7E1^j!@5(?#GD8zk_(rPV%?P$_esvW1o z+yFmTMc7W9EIX)Vcb)rukmL`3rCpBRH^^6i`9g2Cuf8&0jS@9Ao<>+h<~-G{aQA{W zrwnhBB;nikeuTFHOu_rNjV(X~ys-Qzp9mBc8Uf_EK?no+H>Zn}xKlh4NGWwH1;2Jb zo5jn)&|Gn?FtHjEn#;XKy}vaJYCLI%%f3fkZob=Z+LDC3ZaMzQSjhOeezeZs-=CES zyZ=xs&y#$;JvX5r2&d?KL?SDRY;r4Dw%B}Jv^RLz!0~6`7Hk{n)9%%}0igt9@KTxOTg!v0ah z{%(Bj?eC0`eg=NRZFLAS<2g6W7hj%xTPpCAh(K%L68}CL)!42(HJx6CZR&gXg?ptP zRIPb}DqA+8p4sAif_$;OE6*{>c-nyA?_f#XvfFZ6mT!3!wwiwMsme(WkYL<#J$Ox< zRGCC+ef(Fc`A{@AB`E#iJ9FipQ6gq1J?50A0T!GLdKv8>zW7Aq2M~XDxR1p~kUUug zUnA2mmiJ9Mg-TMRpCGE@>3ne`-mrtdaVgIU>Rp5rMfMtx=aagpwXUg_sC>BmgxKC< zk!cWr`nZ@HSq4`yk(Fr{64QxzpT+l6kj`w>^!~-{EXIAT4v>5lbUL!8yQdkIovSu` zUTa!;s3{G{gSr~9XsFFB-8G`M`@#u&`DU}?)+Qx3x$ViPre4?{tYwe6c-_>$J<8iX z&q91-B}N_OJR1AU&I25GQ&Wl<$PP)R{x3BoZxLAvO?!U^* zq=9O^uYL<`|GH6sry{+UFPsE3#8ItVsnN7Pgc{18!KOc6(;Am{t!d>i&D@HT9I%qy zEnfXCcRsYlN5d?IcLY zzolK1QD_hU4%#CAeB7(GhjHh*x}3)fDhP47q3p~yR`=#9mhs9WZ9U!|*pduEb`+Md zK4lE@c9Ptx-I*6EVcJXGvb;7yT)&u^n_!%S+4*~hP68%a{}c6pGOdSFaloiz`Xdc6 zV8469!hRP*ZxVVPi1g+2NgG@keB1-CEU~xmo#_4$e|%}+5pteoz|Glhiu3uR9#D=C zgrEgM3O6+?H6w5mYPf(D3lrnw&-ouTj0;qBtZnpejjYNUl!{43EuYeEykK^tspV& znt) z9LW{=5x&GE=DJ@}0we<>c!oAq_OGmpW2@eLp=Tk=E{_G8FEsZ~EoLlRm2*}41nWkl z9fLX}K%*ueSltO}ktsx4qS8fj$e<0S@%&QMq*iPw{rdU0=6q3XkLn#HSv!L(N!5g7 zaB-mWaiH|vt?b~zlP=>NE^$V_S0F(L)dwDWL2GC$ikpqiWgY#Q(L~LCf8q_m9GxD4 z7@RU8vY@K>4*74a-#o<}BD5+K=_;RtVsW_fU;|Q+msO_!!hS}TV{c4ov5hwFM`o}r z_R)~?$>z^an*(X`*J-2_ghQF6v3fMEOD+Y#&VkaG6*vrdTHn{{tF?E?lTzcpM}(U<=dzf0WIM0cHfBq$s9-}H_n-pg zNGXW#S1aw=*w>3v!2bBt;_*;bJO_B@=MF(Cm9%1=TZ-VW zj|AWfVC?Y4`ldp^I6OS?C*gl)^+20{7BULW?H-=LNVvyK)y|Utr`m+s;*=b*+((g; z?T@AqcLLg~)vZScRg|;K7nmq0FHoTo+aJ$2xbWk2$`F%vlj9kfnUMcF-CO)U=Wjw= zC}00jVNR**ipebZLw8><^q#+usT>}f^GM#*=`4bT$2ej;M=Q6G>U zB?O!RVrcUL{^ZzL-IwAHb9=y9Tp|oM7FhyWkn9Ob8U)SKM-bW4CpD2pDRpG zo3|<+pp>xFR{MMBlrZO36-zgPXzR?Ez2hIkB<^5~_TaC59hOgqCz>S}CyxgY^TrNR zw}Pg4c2$!7Wc0t3o^9=ncZvr^=mx!YjrNG4QHlNxUCkS%=n^a4gR@7Q~tR@#cbqrV`Xw{ z&DAr{e_9V}#mA|S@Z;4NMl4ucv=DQF_+Pdh2mYiN_zUI?hfGGs%B-qi9a?DM4W)73 z%4_sA#EF!8Sf!>Oe7 zpHlg4rx)V}tjbQbY_Ezgkig@{kPiI?)($da*ux!?hY;Hf(p_$=2)`daQ$bHok1O}r zhf9rXw5g(}G6m1s)l*BWx;AtzPDWOCcE5)?JN%alpP_;hML_XjahF;f&b9+d6vs&o zKNQKOB*yD8sR`l@5D8av{J=H5Me|xHE}U&wo-Ta#0-Bvr1_>d>==*_v__LqU6MYUs zlkhM9wq2f7bDFE&vAiGH#rD|AOmz<{XKP*{RjSSg9E_W$zWO0YoJR5){J3)Qm#V6N z5w`-FnN%o!<87bQMS;QyK!wyOoPk>N1^u7UDQ~{GsKv9+BZamDp9bJnLG(T700g=y zad8udBO502buh+DQvoCmj<^B&a7d5!kyy){Ty)W2FYe%)UsHb$MXLem06RO(Bm+IY2V2RocA7;w7Y1vJl=0%Q zBVb3sJA?87PM9=_^0G1wmXx-*w!3CQvyIC;07-yJ2Iv=VBuIG!k%7cDvD4t)Eu3f5 z#x5w$VWm?V+PUCxqe0O!Fqj9qIqqNAA^-{~dCq>gSpVO<;0!D7Uu*@N>Ltb8Br5cY z(f-33)lL2hMUS|=Pb`_>n0@Q#(~qc6?GnycSf7uaRsT%A2Um@kljs3J0`ijP^6_#* z%hdugXWdTJ^VC+{2mJ1a&yLZign8$((Elzd)mH9wq<8snI?m`Be1n<*fsy@3vNCK}}Oh42BA$AlogOE-Teu4S}iD$Q4viEn~f2_x>g~<=)s~4sl zAD+K_)fn!`|2s{wu++^n8(FZ3!XE=Eeus;}8+mJFO4o%(_zJ`N;US!B2ci%|att6u z6DASciJ)Nk<@+BXIR(VwJfG>$(>6Y0(%nzFcgmXi?4&3-p<{V>VKIUw{o?r`%H z2bS1mzem<@NKVu9Exq#~uAVfk{*@p}>tA{}|C}_LNkf+jvT8*#qJ$e)cliRMFwL2j zZO$bJfxgj_;ZR`rn6y0_uo5)xNt_PJFnX5s+k>5*^|^lBA_7f&BV5)*yrcLTwpiGS z6H*qIHQb~Q(OpOM2;Ol*@2#f=oG%3&7h4?{`5ZGg5UstJj>KD!z179)?oHM_a*>B4 ziD0XRV#bP9vM#gs#P)<6dvWg1J5HZNj;jq%y@y-Aq&7PUvqHA}&EuJxMB`UCww#8n zF5~$%M`Qm+3lgv17gsD|3bE25BPANJ6&T2q_RO{V&rC0K-b33MXj$Y88lW8u~>siCmWG^G9m&c z`}^cC&}9HRm2sh0o}a?Q^}$4gk8jJDf%{5n;GSyyIQFSrf)B}i8f1(EAv-}7B3!V1 zq2Uita%Gvlb@aIYt;;(AsoJ`u5}qo|PDe+l!nDnZ4)@@Q*oI$3l3y&Kh zgMarIvp=5^$pg=Wa0abpX~5v1IGvMtl!r%vTj2lk^p#OrbZJigXD`cc*ms zN2hdyN_R+icXxxdba!`m!(E;;?ipkMAcPmTthwiWY9?75viJWrEdLdM)B51djv9fy zyqvbO+{&~3(%LrQ&Bx|X@ zSEE|Zy zPc{O_dhW~A?Bo_rTdUO3+|5-hg(P{>RU&O)X{>kg3VLU%>t<7 zhPK~J7~7KQxp26c;;MZb>n-cZgiTWF%V>yId9Rz2+fR%Uy7vp*B)Zgg|Mtj);2JTXRX#s)u8QrDg2CF&Mr(t${ zxsG289rGJ{F!{ilY9ydxy=f> zc(R-Ipq(5x)aVG^XvZFQ;|_Vj85&W$)CCvfmNjy}(&YtyzNLNtr|?ugdiei}e_u$O zJY#(5po~+a-Yxrm8DbRD9plp@`NT?bmFWTEai2ZtO4fL4MnByMHy_KEHwKV=8$i>f z*=5fDpzKB}DnoAP**b7~$~QVne0z($H>L;Ce)WBCgqefm3+tC8YnEZx-#EdqVKTqp z(M;^Uklp!%P45#OHspA&`&fEOxH!QWp4~6>F85<=nbOs|=T3$S3If*j_EY)3=XRIV zgKM!m*xW%q^d>ED7O$IDYUI#%t0JKc7Giz1D*A3v&+z7Ja&-f>W& z0UE2xQ$r@GUJNOzW?RW$dnL9^x^8LODo4q`4=7?|?>+GYd&KB$V@&hD<$e1FzD8M> zm4}DW2?qfN7+I;Ps6g!h(&c;D?y=h1cPp}OH|y)9P5!tYaq&$ty5B}utJ9tqwc7Kr z!%DF)3=EJidPK>iMMOj-^1e-HD$^Jl8d75T#w?1`#4~99E>xxgDsv!*NF0rck5>VK zTdAp~Q|!&f-->=S>ZM0T`PRqZV}M@;SYtrC53!yF$8@>pSK4MS76x-ko_0z~I$8O# zfxmw>YyKPQ3n$>PUDZ}nN=a*@p`c&|7q^FsGrRBR@v#c6+J6<=O*CMG^3G5^kaU7y z1#qgvA9Vna+b5b08m(Ajj+r#@nL;|N$0@Dqni@cy(9q6&9()+aWY43-J%~t4N=gbB zH=a?_1PKD5S^?M2`z3nU#!Sx#;NAflMuFCtuchVX>6>Y8**0*LT#Cl;P680{$n}GK z$)Fg`U_h#10%Lp75n9q-Vc@&>6C`YY{XDO}ScW{7t7gBW2d!ck@@w`I$C50+&Mo#0 z*+3=^d$=-O-dvsE1PF!aLNNTo63GdgzqVtbNFI}Ve;J#Q=fI+Rg*5$q!|iJ8(|O;q z@)|YojalqZlk1f8@v^6Hk0mP_w7**%><}VsKu9PyxCUk$+8c?x|#e0rph@cxx{Pt0lF@zmgxXYCrUSN}Uhr&F&wwG5#EK9pL9-B053^49+Q zcNb?Tt)M9CU%M3VWAY6Am=XU@Tj_fL%Dgp^NPU}<>n?ZhH%b7ewpE6f$lHfw3zy?R zTlED!2j@|PNw$^gCF&IA6Y+oH=ngrcu>A z4|&(3vDU(*_Nc*j>-El=1OG|)cHdq+U`1KK0ejx*tFu^uPOQNk*8Bm2l|(QKJ@ZLu z{pq`uHJsgX{Qp+69Qm+z$1%#TMk&V$ z&i9TqN$+O4^9XvC#du?su8wCMMa8^Qg{#7J3&Vp`kwRU6dKl;7MbxjZ9e3)25@*s# zHnnD+>$Zwmu$o$^IbU}3qIo2LMSatkgQI-(_r~F?Fejr-PECEj=qKT?`2N~Db|pln zi1aHP)|f7z&hDaFpn=Hhx5U!@HZ5otfTk(5HvLgbLM*`Q$+y3-QOWiW@l5dbFo;Z1h`Xfobw7k?Um}bdmHW6t4*@ohH7+tu5V-`^O(6TE&W?c zqBUEpp`@(*&+R&-y;%@oq*|)($EhqQhl)?}>67VA4;2STLv!;-M#eLPAFpGrtuuKh zCBdpqS3gYi`!eDJn0XR8~;|8y$xNkyERS zrC1OAX<{R!MZe(VRkpUap4%q?*D)}+{BJ1QH&2b4|H5BOSYA&2{h?Z`yB2G6=?8-k zYiq-5!GD2HGnU^0AgJQv;sT?%$XHpG{_Ts$Hy-=7_{mMT$zcc6TOTiK9}{jIgy%v1 zZzbxyitvRDeuYqLl_1bO4}QNde2Mt1BrQtPHJ$uar)O^7BoIqRnk!k5=JxNh+ z(H%QCEpQAvYQ@Jv>>7}Mv#vh)h79D^4+6Eo=08X~QqQBZN>2j|OiTjD-;I|lFGWt`<-S^`B2jZlT2naDX~Q%Q@yill#@g$z_5&0f`!D>okqJ@V(Irqn zga+Q#^ONaUC2){Vh%(59wrRg0rcVp3WxlW0#>Q(2i%%Y*E!>{73HyC^hvUsNKK0+99(V{_8vZz(NBU?s z$2F)0ti&44VIDtj&(Celmq{FdOi%Yw30R3TnCq^RmO3s);wHM76i76;O*Ge=_g9r2 zY%YYQzd+X9OpEy0LI@FEq{ch+2knz5j^w?z=(Cz@r>U#dYyZY{q@DhwU&uoTP2Uqu zpGQ>Wn7i8Gt1R9gQER|~7R_r!?phEFK`Tq3smbym78}Ftt z1pZvFUZXs^MgyY?H>{a%67n)LNe}E3fITdpR!xq?M8;Xub7XSz z<)MYE8QYG96D+=V&ICB!RoU54kaa*b4r&KjMxd%1faC=d)5#Em6Sssf)$84^0_rS> zE$4n8@)lbnvCYt4T{@^%5PNO!ReYwQ`8)FK&e+^s!`s_$wS|?RzoW1a=wlgi^^lN} zfg^8xi3z+1LQpF!3o9$lZVs1cO1|4`YJv&{jK7*HDs4_j^`KJ3#7r(Pe`#v6tgcZr zF)0Jx(9poZz+V`1P+#4_WnrNSB2dB11yWThlqho8MU=}cv_lyIST6nhk2tS3@acdZ za1%%BDk|}Dao2WZoc!1!;vsW`6CGec92=Xv90&C%b*7}JyW24m2@&zbCp1qB+2P;x zB}GMpLqn6O-FsIVJVm@TG{x1`EcE8cP7{{OZ;o(3az>JU4ryxxLqXQERGt|v6B82| znPAR@v8n0R!*ig{$EVNH68YZWi5m(agChuVgmeC{OobAFnT=?ePWR_;@oCH+-DKus z7*P{Uk}AbAPOOXZB(a+RK8z)sSXmkRSMQF{|J~Ej7;UI=veRDQJlsCn!V%DvF@3!7 zmoyBH8k0iUqzrZ~`P2HWa6Vb|`@+)Xc`*#zK4oq5^_KCvCdPcr8EJys@Tv!Cz{*tJ`n+iA z5xesyobx8WbLH6KxCUv{(_`uDx4pa3j1Nc7zT2$U*o+L(^eE7jL≶L7|{@H#c(8 zJNS`eO6tD*-60^M`V+p7!6dJI8(ZyauA|TADKe~M_TdXk()B7V<>OfngHPGj(vo#3 z#6>#l6UC>n0P#xUAOHQEU%BR7ma_W5hi=y;uIEJy>FxH9ssFxI&lDZa7DCSmY6mVc z>95XPFMY=*X#UamCb;}jR(1@b{$(V-BzBF6xT{{RLY9JX2zB-AJxV?KhCIu$yZLK` za^x-3aSHXZx7+2}h0HTLtn)z`hl9#|IOp*OhGYAjLxX}qzlDH?h8x=3%`9zfY%J9MEn4E|Ep@lQYK4K#vefcL zKEJ!wf}D0sv~r7|vaaaJNP%g&ao&HGN>ie=stlnKh%_{sI;yH*rM0H6Zn*+=q72wI z1GX*=4GtRcXg6xR2L<5}OAcutXtl9h4d3=ww4I#yaidnW?KBz;XS3Ax7i*v0o4^!> z{n3Z9NLXLjZzBA=)}#$0WKiOfU<3gYMDB?mN@ZX$WHOAAlVjA~9S7b9L21*|we$0h zz$pa$Lg0;`Kl7NG?Ln|gk@AMdEk>3C^?L*b`iaIyszvhj{aiN9^~S$pK$pLdb%srB zW4rKEjW&7!sP(9+se>-<3~CmDzFuOY$zq0vA>qkx?4JJ?LWJSUA zh=D3Bh;IQ>qUekSvOa>4IrcBCtSLr(@Yoo2TKY%(#%G81>pb$_z<&-Zq z7EM%MoVy6{-#IQ2b%Z%>jNWKcHn;R_48V4l7JfW9cgZ9ZHC8B5Bzi^V+B}lRn=yeT2pZv!L*zkYnSZsio2jKx(?G9Z|{C}8bHas%5=N4Cgf`1Cgu-ESr(F*Za!lFV=dpZb-_A+ zj^J$9nQcB$`-EC(Iq^$4*(Z`->Os6$9sLU&<)X=)59U#G*q8NQNK%oP-{CsW&>U4= zTH~(g*M;>Bt&U#(vUsc$O>J~99K00jV%LF4$BuLKbU*6(aaxE1SIpY{2QzIBpkbXQ z1H3-<6H{mT9t6E>`3$e@t{RaRYh;Qw&-ChvA(B5!WKe(NP(UHo@Sm$Idjy|{|5@zh zne?n+hOcGfnHQa%UA=xq$G1m0&MmZ!(!01;wH?p!pAB4zX#-i}FyBN(d~kBdJnmZ> zo4#^!k2Yl3T3hns;)YnzhP-x~n%9>8Jgt}xt+N4!mdBqgj_e|&VBTt&H83+PEN44L z{3j(*P>5Q$$7P`Xz0vgJKyPHrFYhlUfM$(YlF&Bh<*$@1x#bL*5NK7SbbZpI;(>W7 zKS-0fg&=J-O3LINT&&DTOn-#*-cbfyjb=6O_d+k%ebZ%BQXgZtHh-J#mCk*S8Hsuy zEriZq51l55i}VW<`xDsJ{H;jF1&Cx~0w2o%+J7#x(`*<#-65K-XtjAcOu2Gy{c={< zKp$=JayzG8-$tX`v0%FrP+E61HD~>5 zM@mF)sj)AapE)_zOE6R_bO=;bL_OT^SvWZxb8{*A`7`>rUe-(HTbV;d609z?;-tyD zpWeRG@ereZ9aSot{_{r!EdL}Ssc^!6nn1(@y)WzBd&vJSE$g_r|KMvu*I))j(IZVf zuB*I+Fc9!!@{J7!y?Y^)eahC%$Pq*x z4KMabFnl<5G84f~1@9@1Y1YHwnm=&j6>2PupGLi-WTEvr_T}GXl$k@w0{ND`MB2GL zv*8=`Nhn*VQ4zznKO+^9<*#5(nzft&wyhxh%d1jU`6`osI{`=B+;1eJN1WOukCx-b z3JUCk73$ohhWRCHkLO7O+zGi@bQQ- zroSkb2_-Lcc&rY@jyMUqVg`WKv0ho{3j$a8zOFBLI_!=&yl>F4mg|>?epy~KZF<}O z+hq$8d}?KH(*fZwPY=*BVusciI5SO`I&OB9F;F3mB6C%Xn} z<*>S@F^hfFS#QXavufcRq+92u)1w~)ge@@4JPyP(aL;Xiw~_ySo1@RH^?5CDowLu# zvaQ0}(YvZy+iwe{@0IH}Y`BWc@VrmL;&5sHFlH5}uP0r3W_&Lk;ziqIGgxVvHLvp3 znGCBX40`H2(s3>nfpRMwHOEQ(QhjL8n+$LGL%9B*VRf_d0-74(rA`at)v~ZTQVRZ z%*Q^XIsnUd&ir(+X$WGVNL?59J%K&BYs94y&Q%XO^OTc8`_Ekdq2TU9TRW zso7koqvD2ka?hLaUhdWF#aGSF-zT}rH(^pJF0!vNannHSdVYToS`4bHD(UW?o_{H9 z=mEk$h$MQhJl=M8l@gTMQzVGu=4|*Z{^H%zZ1QkF$Z$f@{d1=d4671*4P}Wd&B+uo z;SJb z zLalk-t;D|6nR7nk{$sp|;5B*HKJwymS^Q=*f+NpD2oU0XF4g$hcW-DIw%0$_U6&QGsKED&voQC6BravcydgZ0{$=0IJkXJYGo5hn9MM z{?%$7@_amtHq-665i(p>_#>zhj_mJzF|O`Sj)zr0!MK45&QEqq2S|)2HpB4mGEyOf z&T(eFVOuVVX78|_Au7Zcy`dR4A~T|O-}F>ZhM&KfJa5z4IPyprLr_X(kx?F25A-6E zDbkDtjvymMEA$xQ4No;81lxE7UY&~9MyBA9@WHPtf$5KL;q2kSfP*RJ5yt{~y5Xy{ zUYFc*55E1}=iH<++wWG~@Ts*`bNFtOM4Yg(2kp?`W_3;?z(C3C0+D`tQh(A6OXup+ zvQ?#ICo!y1+P+kNg0D>GI|TjXzaEPD3s!ZnNP4yi9*iU*{g$k1i!p>h;KsJ%R`4rC z&gq}{KzO7CgnNip?#8ke(BttJ@U32!iy|6<9X+n&dM>kxfpXWf>&w8!}WT7Y?2SoU1) z@nUk%a>KTQ?Nf*>Y7WN4*uQz=u;2bbvK4bI46n?sEUYZ74z4=;(GR7~acH*l-tq-AfKq5}&3e~-a4*Vxz&sXWct9VqfCD;D`z_vGYcYARuEk#h0UhK4o$ZTzGds8+%wL0z zs?@1jy^gUD>Vf*65?wUMo|CXjou{c!^<%7{<{g%DHYLp<|KGW`#jYD{f-{qJO8iz` zHhg*(mTEwD1Gt=pB?d&$tC#-$D?^D6MlM4pyk^$aQ?9_C!M=pT!a~p@0FCW=|e$h3lcrKu|R&UNTNc0`NP5jl73)xv+YUS`j4t<#XaK zF3Y1JHs$2xWRY(%es)&%r1@0J!{bS$#jzz^2gFpG+uGV%T23v^Oir@Y=arRNFKdLK zcs}1>{QmtrA|k@x^h^Dl2*uGzSLK5;x!vAq+FM_TAIjWyD*5^QV6bw0Pa4K&!E`FT zh2h-{jj-v54`g^;OMm`2-u|O5OobgnHca8e_~i_- zcl4)Wflw7$l1akfhw%h@V-Tj2^cWiHh}H@NojTzwT$7lZwmv=J(vkn+@tDx~y37Y`j0^&EG!nFMr2{$!g&u z1pFC_Cv;SU{dg(-oyOyH<5d@{T@q-^KvD3zt1M5MKR_=%dB=%=6XqM_V4AY^^p@TF z$e(&hAH~_hlSc4iIBvikA^7p(hm>Ph&5xFTazNfAVUsC_&?HC4b?K;37OIb}-CB;4 z@KN}9|J@mYg-AdM_IBvRl)XIvTG}+{?g}Gsbym;oh+25D@m<}h;iR)nQ4ZUuSpboQd- z{LI31@yI6)BY&6CZOGZ;^2~0uZb|2GF~R>#QECbkYA`2Vd4#mo&MDXSu7$X@GW65@ z59ldw&<9QCD2hHQ^twrR=@ASKqZu+9P4$>hzxQd*z?~Q#=^t4b`A{UXr!m6Xz%=)9 zG%|VgjnEY=lY)!i|Ndyjn!4LT1;xmTapR)3Vfz}8p|$&6I&4N5FS1Q?^8(@5F9Fd6 z2Crkme1~;)N-zgO-$Sl`ATD3B*5(+w)7_Oc#vC-R79a(4%d}`V*;Jq&9S$uGjr;MR zC}#{m2~@h}%uN03_rZU_T6kvrCO~~_>|sb!zxuv&tc`FE7BP&Lz``KMKoTGEq>KTn zW#b^}734qt{26rb`3m4$z()hz7bGsSu(Fnve34ENn>vWp$kY#!z+wg|^8-5$z!n`Z zg@TBP9{Q<7?*j$~*oVQ6O?g<+>9+4oP(kN%EtPfd(6kJE#+0Jl4ozU&R$-?Z2xAfw z>Yh)~*QAH?gVKgVMa_e*|fs38ne9%SCDzY$ERDS3TSo*O&(Cv-#~3yZS#nYBV|5zw?RihL;Dh^l&1T-hToDAa-_kHa6u7{>iJOFU88m06+RvG@8SaY4AM;0jwT< zZFpX>Y>dbth2q2jYY<~A-l`vVl$sx_$Yw{PNpJ&3L6|@5mo%gQ{^J7!6oA2%rT_STV(ecdiv?5=a;j&25_*1g-O`;MW!%D<|Wqi803!S(>0UYKhd4mB=b1)Cl zR4j0s1q`fIh0cR&6kRmIN2mw2-}S%yJ2J zaz?yUr2XNi;+f8JZhOxwwfAi^vDUayguXbV5ImC}KIDdJkFUmBo1$sfEUo$(g7Yn^ z1jW;-aNtVXEsz1Fc14>HU=6vX2lg4^3dU>98KFeTpmpw=p{4us-;WgHRKG!n1!G0u zc>VtL3LX0Z>JZ7R?BXSRgCR73gGf|jUwDu~P#zm9zpv2E#ns*UIZQmYP_}U~M+z=! z%r^={yw4iT%ijcNKEBd+n7kcGZ{qf+MQTH&&vWX(HhA%65IYOoTjDW^(~SD1s4MXo zTB1vdeLmMo$U^B9k{*ixMXy&`z+aB3Tb;QG`qhG%$~ti{HYBY?)&p75|`H=gv) z)F~w1WL;tvSt>50ru8NV$UL1vcmBfEf!K6AfA^>64RY2SWoQ^Gy$>1n_!LII3@~iJ z*6~J5L0P(~FR^po@&!>Cl?9d?XRi$0&ger#g@jAOWBT1K>H})()Yf{5CJ93&#EhRF zt5fwpZ|s~WNp~7ZO5El=xnuC?v}vbli&+M1j@C>s(vGmC!%AG|CFOvyNcn??>m(E- zfo%S+z0{33{yl`&bqTgkegx%gWDDqLN`A&H>LejD5s~+LZoeAsDbV-K#-PSYl?#-M zISEJ6`U;{X-^FB1_P5P;-KY?Z%`k|dqLWRuw(`W8kl@n*qYpo)#Uu)Tc%NYvjDIFb zSpup+vqCI4q|foiRMMN^NXke{M}~w%goPoYMJiBtV}&pg+J~Uyp&+7fa49eZ_L$Us zwPM$z-Ok+#Eq{9Nio&ZsZ{-ZQZ;<-l9qq~IGgGVrHrinzZgP+v}0S|Y!%1Q?||!zf(9 zt|%&Yp|0StBoSg_=FIuCe|Xn7ui355;G&INGto?A1c!uz;uXfh{5TygK`AKsh;6;^ z*t{B^D3yowtJ~fda%(h1u3*@hg*~N=LxU!sOBFA2uJHF^n&O#2&+b%6=R}UUE4 z{_ZQLI0V^*qWG1#?rx5MZ=gn@5!vcC{n)!t&#Cal1l3j53d$79DIX)_z|f_cm@-yZ zDS(Fj{kwk7_rHI46O)pYl9Q80nKO*O+WzC&pC4|KkJAW=aOt)8>j!$LMppW#rq+gO zecuaYvA#4xeJdnqqVbEb_HSsGQFx+xtGi3`xsSQm0Gt%}eBcu&#&PztVde>bZpPfk zuFyco{`psda0Pylqj-b^(c#aeJf14(OgR2n#DbrarKppL z>s)b$PDLUP()gD4vCH)j5Eh_FC`KWABP)jwcpeP6MNyNpX+$oyqj^J{RcEbLpWu6E z^9}D}it$qD^P&Z>x>TKNMV+j=6T2SSx7L4TX}85=;s;8it*7t4w^4R=StN(4w_yUB zUS1VWOJ54n#@Vcv!R3ML%Ahdkja)b#oUyqkuD$lgVZK!H^)UQ-ruTVU#>SOR7)#3J z3hIAFh-hP?q1vfDxGnb&9t!4s+K`Im1)_b-N~-6xamW_+mkn(_59`RA31xDC^k?>K zTd4vR6@7H9!xY3**oD7Jy!ic&!;a*rg^ zVva}CS+5KGKLEPBQ!TpU;%LgbT-4ndAOkUD>lqd3JSbAHE9`dP0xsBx?x_q{k@#5I z6}m|;g4@|h(Dd#^K{m@MYQ1y4D!b};`n^|(;88Xf(us`wAAjuJg<;Y)V07(3r=s+- zGW9~QcjY2a6%Ca!yLLNfN{A7Pt)ML8{$wpA2zl@s+mz5{*P+S32l6KSRfr5T*W2a@ zxAA#s@_RV4d^cEGE@Blel_yD=1+bg$=peaGCyZZRUESjfMMCH}A3k7XViI6trhxpk z)YN9H1&3CKPs)37gWD`g+LRb%vWVegTXviv*}hBP%+mhQP?qHbM8WHIetme9nWSX! zZ|I>N2TCjxCOoM;j52w(ia@#1y(wS1^T*)GM-=hJ--{8?#(O zgwtlUp>a&uiH3KVi;j+NQ3v*!!+jW;o1Oj7#6)&w%ygM~(6~^gI8dZczqYxVi-UuM zl5)FBkA>ycJyZlF#%2RO!J(>Cq8Z>GG8Wc0I)eN-tQW&vsSS~~ zsuka*_$?MlN-(#+jU^fKg*Qb~WwA2JpamSpqkLgzpUodk8A~!Uu(2_);j=BzyWycd za#K~+PhkV9N9oGMuDcOXQNSlnc*mUE!`ptOU1f_hFof!?wDR&ix3)>Px3l>G-#wjv zWuqXOOi~PSTU>l~OoA4J`W^mVI2xYM^46P4mkOZtcw{ekVQkiI`52q3mB#5-kv>3_uExi_U4wU*YOYQX5tJGKF1#* zKkTmBFg<*DB__e-@D$%YgCFy)y#n>cpZbTlZNtiIEbHSLbT0v{MPuIN#&@PM=mNh& z@NMLCL-n9BPFm2y2ci*~EHki$8sL5R7M)jxOdCW$Tyt*s4z9>15=5Y9h_RUD_QxTgKrt}s0tW5I13g$i0i2qgY)C%b7zL(6;6{k1& zXzDNribunRo=4Z-16Xx)# zG})s}o*zO!*K0)~tnLX_1}M1ELkLI}wRMn1oaS9?pUn!q&b|~7_q4AR?XQC@Js{8wKR<+A4R!PRCfbD^EDBv53g{DkHj)bX`B(*+k2+$874{s!)! z+I{{uMw{(T1}zB14JHO3V3A&%6?FZgQbth}$0?^F7`g%vw@$a(2aKX~YJRMs5$$C; z|0&gAB_W^qz&HZY^MLEYTqxp$o>3YQ>gkS-cZWQ^?Ssd^*9Q42=#6UOlVS~%5tNan z0GfQHUw=>tg0$*kM8x>GX@Irq!P8q`pA;A*HjqyLRmo(5y6r23N$Jk8|V`g6F}w*7+sop0P;j5K&6aC z1O+9ww&vTs6;(uvX1{|odbr%_?d^4FO6}4I0yvO(BAqv-iVRkUC&|=<9fn1;c~K6r z!#mj(8v|CRrJA8KA1NpSRLh0lPRSCqdO*xjF?L0*Bk}(IMpeR5MT>> zjqUdW)L1yUxR!x4Iz?cCmy}fUP$=I-YIK;@!DOCA9TyLe=kmRb!*S#(IUK?>;WW)f z$rwqnR35;fCIObyztw73b&qJfI*&wRZhV?=J~hWI)4FON6bY1#E|#s{Be+57CNb`u!xbL?9a z_~`@@jU|tBsbujEsNK9R1Y7vv6F@OfR6uy295slX|I>~%xk1QRiOYQ7*D6$cFe$-= zN|T6L@W5?Q?nd^#4fDNpv~AE?lO9i6}vcL&fx!s>= z>dT0;j>sFG{&L-3cZPK;S$VvZgX*Jhr%(_3bmZnBzJ&?3KfD_vhUIwrX3#$|u0*F`l~+xD^ND>*2PTIW@$j+}oIG=hvL8?0b|{uxka7EA^ zCFsmiWoC@D%>rQ&warc1EiWeqk@X)%mg3S7XpQ}^=U+0n0YnULt<(~NgR+t1!UReRocwplO5{pTNiq!aLki(?g~Oi_H^i^Z@iE@M zs1D}GY;IyiO8^g6k_^s}ig>xWJf1XI=}EK2yTNIMMiMGA;j-=T?+>V#xWBsJzEvCc zh7`rhI^qBthJXNMs}SShu-~>~)-mC|^Aqr0XH1g=JA0^e^eXs;vVp_~4;O6VqdXIl zZ?L{vDItV*-8vGU@C{m0RaPdo0BQ8Ofw0%3+`Y0z%9@cj?Ckb@Y-|9L zWdo3eiy*n@z|A$kuml_{uG9a$dJ=TzsLo!MT9@L?kLm3nuWvL3y@zv6T<;)B3tRw1EcF)GThCsHg zaK0vGNU{HBx8#ynVe7{Tk?3RxTMjmG?uo|BQ3HkVHxPoeORpySxHAbv6OY$FbQ%Ya zg%1&9V9eKQYND-M69A>%6+n^g2xD=-0Cn7{RN9 zhxn51I{pl*hjJ?zS{%@-y}P6LyIA$Vt+5$vu37S)e*yHA)pssCeC61I*24BNB<8hz zvREMD?RbGS+9Fuqv=GRaR^oI}$rO8a?izmU#13JT?~D^CA^(rGH`MBtBlk{jV&&$Oi2gDCz4jhd zGy;zG$JwofOo2}h#zL;>3KV?!X8(2k8ZJ7jJZlcSS?fIHI_X+@C3x>Q>$2#g`?D`V z?g`8f?=Qt*1ptW3{IgGxb@_S_?~C(l_wDWcDL<^4dZ>t2MRy5Ygw|ap5dAo{t%sF|SZgnXmM zqF>JC)mFgyNHZXrAB89cWYCYbpGev-Tr@o{WyJw6XDC!cAlJCRzqfzb5=rPZW&y!0CEGhM(VASmHJvyTP~J5y~)PPjsQ@k4>pyBs{|ZzsxS z9JRn=pU7|#V2Ju9ly!@RpuM}ZBPt@Yzbd1+_%#2=4L@8}SC{Yh3{5##lL@--`@lPqz?QzHWd`_=b|2G-7j<&0V&?i%N#gtdSxL?wVqkr<7 zb!d973P8w>(+kxB}Y$Bf1@UmmfD0vEhIT z^PIcBejF7AWiR0-AyLFa-clIQaq4th@h0}P?`!%p_<=~z=*ezlBddlK;}35%sqG_^ zjW%l3DU=yRT|D*Cc}xPm8bmDF8#xRYT6!0<{U#M-%UPHzK5WWIo&!)$iO#PC<;2rC zN1?A=cxd%PMWXY*-4Tt`pB_|mdw-DnHhZUec2slR3Tu9ovyD2o2$$*tzN+a;9p3x4 zPf%j~wDk*(xag{EIP@+;I`IqAuIDpG<_y46MNZ#i@VY~mx9u^^x?>|)!JpPl1MG6c z=1tG5bN(E^p)w?+IR>{Tj!F&o(qF*}0)-_S?A1n|>2Dl;B$M0a-7#2?vL zm()`{o~Y_}TbW;3QiL)wb?aKjF*lt(YT<-vZERKMj9MBzupCdVzFXk4!~Mr=walr% z>Wm_i3CJe^pnBNzKR)Un-5x2dJDH|n&I_zS|9u>TPG8_gjIkj&r4RE!#;oUp@e#xF z>Wpgb!?wI9bK?W!>QG#Mj*#)0E`Izr;@J-749P z?F!RCOtO*D6fm4&1JmbCl{B;lG8WL{*D*J2Yesy!79lzYt=co5{^Z*UAyJX?@aS*# z`Gz1F+MQ#ex~l5j3waxu8;k}Jb_ew83y(n%JQh?d6iow7ELi(p09KCv`XTQcVjoTY z2o=FSss_r0WZoo5YXrucssNJMR9+wt1qn#?^{Qp6^2iPoX0@QX)_41xP_L?~J? zl_6??YVG-swi%s?RI$yY%HX>u`h2rfNmW&F@Zj-6jqC(8-Cx=NED;aX<%-26Ch{5Z zM2|43w#E`KCMlhyqphzC-PopKQ%|=FaeUL0%J*r(aR>qxXF zj?})zQ=@RxDjgl?0SQw^o7Ytr5^hJhZ(AN>5dZ$l7lAPdSclfl3mq4{;1jn-*+1pJ z@Yvxeer74EII0svJphe(?d&!tPxW+`2 zdn>B%|E^u@#l2l!X&AB~e)y29rb||;ei8OFTgfdcYU}yXspQ3_vBf&&3>@)%xt&Im zGvR_MAkbGdZ>-Xb^?AOR^Z<$s(1nA1m$J5)dTyYg0NF`2G{6H5@|r;OGcduVaFxdl z8t?4vP#btQ8}@+QgkM5_?XU1~Z~;Gm?q@-ONSMh7Cu~ii8jGC#^^Y#rtGbZ8Ag%UE zl>$g4Fdzdk5@^HNW`IJhDx20?Ccj!Jdn*3o0^6d_X0uhZOt;=@K|}?0!#paPq7E)A&Akwy(apU{G=~ zgcIQgXZxTWNQw^{I{>HzKsT!&>d071c~%hqnG082{s9mx&DOU-MW)2c#Mn==u2+6F zzLVQrtBjj+C@BR>$yXv|nY#IFGFHN0fe49mqcYLm*MTq&7!Hp-q(!F(PQ6({Kk-LW zgJrhsk`*#XKYpYh9}qzNEL=vnx1b5k7*#X*gDsr&m+IR<7BxS&vb5Hduqm7E8ViN< z^yG0*&VJZ5Ky?;=9o+k>wWK0ijK<) z9DQSiaZvovyuNY@dYjHCPHnSb48NnaWAC2{T5%ygcp88mI4cJ=Wp;aovv*3BQ8WrQ zeo5Y)c(kSd|3AE zKcpC6C?mNCA6w|x?)^%f9;&0QjoaMB{dC_POT9`bClK_rI4t**iQV^*`*?!;CGU}k zm9?UbV-k~0Py_!-)c`XK)OA5X{DQ&dXo?lgo{<{-aeUq~oF_VJ6+}@$I0|=|3}Y(< zoF3GQlW{pf;wx73=gy!dp+@>rC_#r1*oZnkv$>An>Hc`krB_?ev%;$sA+u;h5;SW= zN^}BjccbQpm?SU(ER_qXzLq<$uS4qz7mWva4@VHZ#~kh}n7KHT%SzVavQp753dR`do=+C=E9r z!M~<)Igc)%CW_iK@)udBQ2XgXk61-g`|c!Y#uK&m#cjod_02TNYc-8yc-AD+Cw19M%bW4MD zgMf4+Akrz_-Q5k}@BiMsnU7%{W{`Vf7|z|ZyJy!^2JSBW$&Tl7Y*mbc5rUnfqoYGr zQEAjz+yQbCO0~0%@bM&i$E(ViAjb&n= zQf>Kl*plrI={TwPhK z{r@M&;!RE3Jn_;$;^83{<{j(V-QjmK7%Ys_m8t3J`=#<&EYl)3(nVmFv{n`tV(0z~ z_h;BBHcL3U)~78hR3V9lL6H{H1UyC>?S8x}FpbsMsG>MsR$E=5yWS|@#B}mzF1Hy7 z`z*JIMcLN=3oTxNWOQU8vBE=t`;kO0>pu*|IT{Jd@<$95ToQi z7JYJzEWeXJ*i)Ubr|I&8T#DdciX=IRCY-&}AU!BteK&sH470iP_<2mK&1>6MwF+Yp ze%5nOwcBNY7&r3^YcOYZ(%fwe<_mVL)4#0NIJ9>Bu?5l>(tqm|NsoBr)xgDShTqlH zW;IvRfdM(o#bFqg3+;e=;VX0KX`hYFE6V|=!1WC3f_Vk@P&Ir7HotF5R2fzfyS0et z#F3x&5#}-lb#)p&4z)@ITFRHPx+Z}lOOD@;!ha#SNE$CFyWIiZu}dG+@hVdA_4K#_ z&iML6{`(uSRFLqByFN${b&DQTpWKnTj_|yse-$4@1|C;VP3Z8;Pi3)HWD2I9bdodh*J@?NeIOw_cjF;CDcY+j|ii z0>*lzAKiqH%n0_;gfzKjIS6AgMn|o$;BH&!+rycMtov!ln<_$0PQKX8dqU#0ba-*P zMGus2-y};5JM_AE`1a zX}!OhnQ3s^)gJ}nE&maoGO6nquZL9Z(!K?cq30^~F^gr)RKq@#W2I42pPn@*-PS3o{~>J<^$_OS|8a#nEzSW@9t1`2^$zkmU}9SmN8m-z&s`GX%*Ab&9`$Wm8}7){={~ zgB+0@2N}F<;~|n$>w~zaew3@oE5|BF2alnD*X9|2%MIkB$mEh|m2u5;Qc_YZ%*}Hd zlfj>RmVhF2f^ z*bKo2)tPxM0iLdhAim<;?TPW-I@|BI zO2f%ezf3F1TBmM7U06Tj;5k|g(83v(6#GB*dR4mRuH#BvonUw#>N@wR?Dlj?BOqI9 zJ~Q*Qv?YuIq)7EY1o5}~7j^X(=f%?7f->8c(}g-!1B=P#BV}(3zalC^$74(2$y()M zMv#Z~Y{UJUe?bi)i{6o>^}>21^xVFT=f&pQhY~Kqub@ROOc9=$G^A0rYyXPdSn&Dp z_a3)kXgi73EX;q^n1d!*PT8rC+oG}jWGxZ(Q6IhFM-CpDy-os)z8Yt5S4WC15h4s@ zWd05L{YDX9M8Tco8Yre1KVXnU20ckz!=SZ#>^ACcE8$eOSAYP>hp1Y!*=y&1%-6P`xOK547%ch4~ogNiB6tkoU0R2-r zqlicYe<~lzm*zkKT%Ohx#PZTdo|e?b^03~aR!8;XVwQ3l8;fFKsNjPPDYsZPAJ$M6 zoFU72$EY4>u{>b*usd~Fc}#t{e}}&{TL@@zrJi8TAb!5$3PW9V@#f z1uLP|tShPDC7L@g_sxf!N1w~g;-u7kBEAc<~bfwMy>iFh!R&7`uB|#fZK#K zB49j}fWdj!i9+SPrmPLNLz&-!x5F^=V# zzg^|JJ2Ns8Z;QBJ=_@H_7jKWna^vAHloHp=3*@3r=ATK^`Nyu7TSD<%ZeKSgI27t1XQUh_YXq(41*Uuh+hUprNO zb@o{vZ0`mR^c1NK#$qBb&~``6@?m&v%ulEabLq*KYv$QTh5 z19IkmmX?Oc#E|l;Xx`#b#v^L&N^yd4mx%E2iARB|MZYB%ptukd53f7W;~-}$>j1&z z*5jKLiUJB!x%X0o__pd8rG;PfY13xZB0v*hzJc8ZtUUi4ae#vyY{1IK%34`bA?>Pe zW^*1bnAm{jz88U8kYcPoJyT|5Jzk&xP@u8izu-u#pQ~O9qU%a4D_H^l2{FwZowTEa z5cr~4KkeG1o?#2~Qb$z&w;fSYflALy_qI|hwI0b?kQ`%RKnz@LeE*#7Cp@3Qve;su zf#3L>^h7Gg-E(sKFn?K)6_VNSNZNdA6+2xi)F2NIg2D0@C7q{8t8q#yfCQE!c=23S z9OS=qhMQ$T1G+HNyqPxYFfrHv|L7F=?IfN5ewhsoAd9#byn_#_)9mf+Y|PEgz`LDY zd89nc?r3d~RcSEXxH@qv45M_NW;p;mdu8(1Aaq^1EF-E4L9V`2Q$Zm*>a!9x^Rz-I zSvj3gnfnzM>hy+=uz3kyi1iSrCH59e0PhFNw`DE~ZZ&SOZx3L(CEEecS!#b0_AXta zZedH>R@ud#hm@(l#}1t+oKQ@Pph!WGmnfC!d4Dg3&gQRlnS1B;@Zj#QULxX7p(d}% z?BqenTkLP#9P@f$&v)vl`23Vptmw@Cww2__fnx4j^K3&r=>QaMRzX3Qg9W>9SKcI% z$rJUVNTrkUp~>R#ci%>d&A1xIUYFEeewzSVPJ<29Z!p0QJu4m^P<3X_mYwkT@hT3z zcCEze`q|GHQXU;wo&3M^l@i|(_N7SD#&P=M^<=0XI(@3EeudVATb@3db4B9{3A2*$ zkY8FVeHL(Cw>kPpbF}s=zQN+rrGKG!y;Sb?O^$o(LZ-kM|B!0O&bIrls4n}Q7Mf4v zo3db40O-p7jHu+3z#YrggaG05Vcg^CtDMKSVT>o0pUXQ@{zxLy5ljUuVv%@>%ky&= zw_DwBt@_RXdCV+DY>l8K^5h8q$IJTpkntbM+O;^J^IeB-__XXA0Fpw245<>Lh&k^88h=3|ur8bfpSC9>jUCF{Y8c&#K| z^!GbMpY;$ygY-`mps10zZl3S_H9-ZbSXymy`2ix6`}BJx$$td zq`wWPo4dXy4s0ssrNXYMm7)ZJZWB}>ySwkg!egr$3b&%xOzNK>3GQD<;^t;7V z3^cUNIOzN!fRF%H0bchJVM|VZfvY1vJ|1jSaBy%S@X8Gn1L#V?cmBs@c6yq{sLfrG zX*aV9B-X*h!sZA9k4lAhq-4^SWuH6BebFvAeJ*> zi8+aih`0ud<71_O{RV_UfCzG6vN1KK44h41oH#FfIBoL5IccM#7Wlj=6tf8cXs^b7 zE5(GDdN`qz3fDzk9OfpO5~bQ^=(XDlN4ON-D*ID1f%`@{8eot#%POLy+oPj}ldMBK zG)i49#Y++;aw#>-jH~MkqM$S)o1IvI94@PGU1>a#uU^11?etIWvv+#~&O41OL;FtN zspJ@|UfzPj2Nz);?yUk(SAJi&Nw$M7U)tQY6gqCJ2aPz3><|t~HO-O^aii0iM)vG- zy4)FU9LB#3qwqo()TqJ3s{Xl^Mz$EVW06z^mpHbiZ1@;!kJiD^YTtk9>S+cF323FI z7Nn9fMMfk^|Lup0wGIxjCS^52r1{lor4sDlyM5oK+F&3lj60C-uUdh3^_M=Gct* z9=-i59ukI~TQ;n7SXo4j&l{rnFOFw2nORqJjbi7n*Q)8Vn?eUMGGDtxzQ{Yh9%T_Z z0R2i$M)mO5K<91FyKhBQHRc`QkFR-uQCV@`6*VqTd57ON5Qew0UXb{aP|)d(pd0$4 zzPntExH%NzV(~r4WFkb?W?iNXWNG1imlUk8gCUg}2&V41@ob^}0S% z6?ZB9wzvF@(!ASIJ6DWg>80}L(}~Et!qTy}NBB;SDMSoTAxq?g1sneYwKcI-mej_X z+_Z;i8MgiL<55=YF(s%>wB;!ui+~cI+l1e6~rzz2!3}3CNKZSG9pb9Kbj!X}At)$7< z*Vg1kg-elao0**j*3=b^ zz6mzveKtxkrReY?LH;esc>)U#sPO|0LHKM&-Uzz1ILP1w176AmsZBO|`nRzyD;{xt zF$l1*9tEF80{#gc8TtGBxAJ$VhLY6315!J9 zl!gX8=pHrEXFJ|t#a6u~Kx_TV^pzl=0NyURhIyQ%TwBzyDSbj7QxuXw{oezVF*|h!IbT_AUl0i zB1dg4q~rIEB|-Me{tn#)hV6cUj(0)z_}G>tlh`ox#}YA#AqjXtG9*6AJRbNvGt)KG z+ci2fp*^Np>IxQe%UoS(#%Z>&1j=BBeuWVh|F{D@NlwtPqt017?+Jph1VG{nXFK-l zlr!GN8WE#nUqZ?XbSfdXx}=Z*9tFwY_cF5dn0U)A9q5rdw%yfe&d)qIg8jlotqU4&RN*T>E*qO%V!zxU;ET&XG**OuUHf2r zsxx<^yeLd3-rJO6OC#|tjkcU9iBIvpCN~tuWlP6d_6iDVpU{hi$ctHUV0eUtMD>pI zO!y<8rh)H~4I-2sL3;SoNl9<PJIWC#*&gMVP0gyzPnC`a&5yPiY;U1(^2zuREKm1nK4BEs zk%W>@Ez?!o9itzoxNM;ZNNbi($r-6>WJ@#Yd9S{(#C4Elexx94LYuu<{}P+>%AkAO zmRAtdKTP#~5-0v0F;WOHH&vClaTJpR71(@Dg?Y3{^^REfF?06HfWH!)mBWzg6kF;A-6c(D7Hl z-$U}ttsj}Qc!hR_B&S+U*9o?Uh~N>dk?*(fp-L^4;%5IEToIl*O>X5?uui6s5} zEKbwn$t}on;Z~Gq1}0H<--WryR!fuZubhg8&r%bo*CRTBzM+8p2Uh6mn{*^^Nt8W# zWpU!lwl)bG(Bp@LP`T6-d{#Q75 z@AqV+w8P~#Qa1zjY&Bhd`sCO2Jza3<2&e!pt$NFeJTS2~HcTbg6ZI?JSH6O7GI0O= zhb)?3*)Z|ANa=@G`J9OfM=+(Za66bv(mt~#;DjJ3Fc5r~ppEH@(>p~LlsK>%wKcW0c&>K`hiq9u!j+HA zu69Mz-$8JZgY#dY_C=8hTuMO!^u6~>s$cvojI1+5{4LZh8A&nG1CvX9h^}fuw@W{W+T2KD`|SWwECn zL(afHCnhzwGQ;$tfXwy6p(9;$UU43kkR~0*v9cxknL&|3oFfx|r{i}{j^4XnQ*uiBz&cl^QmFo-=95uol+FLWY9lal`Eg#HdfCVSB{&P1+H^2->I!7YVf9R^%*(l?8A8CP!M(JQ74_t$^A~ z_y%nre+mh;`cWW^I2Wlb^y?nX+dt6Z4IUk5Sq{gXgM%_*G|f^Ql+sdlJ+rSC)bdU) zQoSBLeHzpznAVlFQaA~SpzaME`)3%ZbhJm;=TA25!n4nlkTjffPvnm5b71xsp|{4M z%%zc4FZrvJDSL+=6LHy{)QU~Hd$m3XTnc0!#V9XQrK~YxwjWbX zS5*inuGstg@+6ECY?IbG|LM)Dst$3bPd%WkH4qO~SZS}G{W`{Qk@{z{f#eOZFpd~n z>M?*CM&WOEM=M!L;-rSvO(7iMpsZS2EDGX>T2vv_fOSF9q)}?itP?_tj3fO z-_K2(EZ)=1_`!K?FP}9S4Rw|4?n>Lvs`XVEJ6srjx0%6&HfOw6Hy~xgvI;i94IS9> zXnF&2alCQ(+R#{CsISI6vOD@N!;WXtdFP5?(xvcHqxj`V>N!-n)T_IuvpUTKzQ^&8 zwy0Gb_?M{vpw+K7(=@!px2{?SCspf8x2J}GmWk7F@%xsW;ZUYIS91fKyvy@bgy9=MLCRi$=Mkxd-iwW(hKQabR)dR*?{;^P+= z7st}!pdlkOva#`Q<$`7u(7ObBTYkrEhf7iV`T6Zgv>fW&?9lR>XKE(W>n6AUEGe;6 z#5<3iRKS!1(iaE{23=?1i@=${dM7N5xP$}@#|se6=xAwI=0(Qjm3O`@^&2+E;F63` zL7&u^4}oG;(723>@fexka*3{A(E#oO^72f(Ba`@SY5r7xH*ZMWj}Pnxf#@l$hWa`> zZo3rE$=MNqHvn`4>=@X`go|5lz1xK5SBwnURAPz|P%4^QIh`XjV#~{U$JHTn zO?+PC20~bL(yJsSmNDpD2ndj*1%be}sZpeFg$?Kp4d|X29o%qy3}8jne(!OH#mLQz zK-4iBE^6A#D^=+E(Yl0%yP&YBsP?LJioIltJ?#p;Wde)+p_be^QO5UR$|_`V9D$7M z-u|ui=g&M|H@1fMkO*XHw2PPq@ND>rcnA9%>q?gw@NeaJ17(cJZ?Nd+A;y)I{wlCY zPgFD%mxb|27kkd;U(w^$#F&|MDs&6W+!eKIp^cjZN{sW%Jax6S3mN;nIMs2(-_`Vg z%oQC?KHu}^(V*Qxc(}LP_?|R`0u^34U*P@1GSD}2)&Az=IQ%+=-X`Z0cF9x2wLWo2 zOnnwKb;Ls?*zfe=l^(yCAh1CZ3n}8!9Pj;-cG>k(Hc@I%?&}aQ&6%S8?t8)yN9#O= zKec2Z6EP&nYW6CySF?*Vz!jSFqxe)X6ZU$Jcg@89pk7K5yD*US1$l01l$G&c0wvRJ zeATZLBKD{v5tJS-un!&ymOI(y=M_}_?uv2IKawGOv}i=ns56FN-nel^fK|zO9O>fp z#jQll6{a^POrIZD+HZq7arcq)dA0MeK%<68%VnPOJP199Y^|fYJEFxW$xs)wuTG7^68lik({tn5W0ByJVc1GFkM%S~?jq)bu%=x=O}XIqGz$vYEyk!2 zJwfl$l{HH2H5~U$<&r_yQgVrUzhU3&5U{&pIz~FPvBEFhh0uvC_;726d1~8sU-!S|88rVeG#v3bdgp4( ztV2(Hiq`+l9vrVXHMuJq4d6PYt&7x6&#;cAwpP~P7;Sa+&KqFej%q)EZ43-AHQVZr z4&V72b8POHR;j#_L_W~=)X>1g%jXIQ{r0}UFpic2xC{ja1Rz?g@e93sI;>3Nztm;FCrk^|3__8uHeT?Hve*gAUQW^o{5QOhIUVwXWOOP$~ z?%lgwDr1lY+R@Pw!pQ~+H#IdK1mJOSFv@R&HhynebkFZuScXE)&+m0^PM5e3t;$=G z`r!05J3SrbO&s3pFeZVoe#m$LVa178SI*B$&k@??Bvp0FzsFLUHn~TM{v!d4)k{wX z_(b)pxORTLj`1o}PCVZD-K}nPj)`2hrO++*WsDU>HZjA6(pYesGlwMpjbq<~sk?K( zY;WURFW0v2fDTh%24$et8HEr%2$VJhDPph`s$O>Tsg-#^Sud zfmJCQb@IXizKzYI+CW)0MOeqRhd_U5LBpY13>9AGl_i zJ{)>aSbi-A2TsI;C}W?3Fhmfw?-7(Rze*3PZarjk_IXz}|21$zVNyU&lBh3S@E2U^ znx78e+1WZ+-#C%JENJz7Y?_$QV$R~#5!+QDfc&V?bPN~kun(grS0^TBK~qv6{_s=L zD57{9D{Z+H;yQOM zh+M-QKY?9aQ~)+iFOYTutrnZidN@9#^$ z83lYO-l7JjS=p2Of`cQ#d^^Z_O(E`G7dw~j2(lj*U&I3TDIU1^qL;!w;NBP;dm4c*Z= z!%@QL)0Bn?GCzGaBb84$5MKg+DWrO-PPKDgWLAyd?fX0SrDfqCnTAJp$0ay6<=NQM z7QyZ@C9S-K`Xm=mpThLfvyYvH)J$Kr`*Ydr zCvZdcaU`QpuRUGMXf!5lO^*8aSVpEGl^Pd3PuC5-Yo4(6an1bFH5O47D)0NZnM!fC zQqkZJ;0Evwy4VcQ_#)cpL-EiDVWOV(VJS%BULVq{54|KK1aD=QEHIeMKy zmB_tx!0b+kaG!G7)_!BQ6z<}Ko^!fo2udWVwx?>wUFYkYJifKE( zvpCk*HXs(jirEC$svyhe7S%5r!TQ(V*;#O0-Ux;>H@C|bJF4p=Zn;5a*m_48w*}QC zi;|z)Hz{Blz4}1w`d{mfVGC%tVg|A9z`8MPf#TT>d{G2ORiM;sbd;5WfuNoQ&HlgD z^bc4~^_Tijsav8zoI5yli+*qBu9bfyE((NMRu&d+Wh`yRq~5AMm;i8Qo&(Tj;tLQ; zp7D|_#l-x7|NgzMs#a2aZaj7#x93jy^6MA7*#Z+LVw6_35UIU7jlcm#lOHdjIeVTr zpWTH1C9|;AzJ;JGbnTY(Jdsm~iuGUOJ50k=vc*O_>B+NxkgMFYD*g5slXG8!%wA+U z17Wq@-Pt~?k#2SfTa{s4oj0VF2uef!gS=azNAvgLM5#j3wJx&i^`N#X@|LO5(SaHG zJcVmRl^k}G0T#HA0uaLp2?ex#1@TV;5Pj<}B5tF^PIXb;`JR#OjyLq*{k~_)3AnY1 zq^Po?NT-iu>Fq@kaDvcND*>BiWddsu%k$Sjfk`2v9(Ov#`VizN+nydB$X+_Q7Pop% zF29#8!KchMg;S{f#N^#vMjk*bRS=CC+BcA=fin?#e#cDN?B7qXwLMcBL8dWnt6k}- zR(+zh-|Kg2Wc{&YzTf?jb7jcBpXW=b&P)k%?RgYjMAKU_nth{8a}8!UEEd0R7IlZL;@(q=TbfnT zM64~j;c@x+H1_`-V`aR^I2C>)AU?(X3g*b0U4Q-);WyqI#U@9f(kf5Bkjgl|@O{u{ zyFLost2H>NMA^Ki@=yRHKhC__T|YTq4a{=Z!6-cLN$mLW$yl|@ybt&1F6|PWcxS$< zDSCX-CmliaTRFbRGnZcx`SOKDzLyQy8VG*=s%l&XSsDK8uG!xd{e$qGQ*rAH8#7ZE z{1kSJWHygFLXL&e+`hpM+nbo%yxA8#^hrL;yBZo82021ZB#Eg(?qZp1r8UJ&tJd-3{cwsGrIEf zl*#NPcT@l3`y!t)t39cMXLzEHfMXIa8xkJz%aEV9qQ#{v@FNTdZ3i9b7=!B?4kOoE< zk==e5B(V9A{DVM+fA>@|Bon^BYaq#n2e6*})DQ?67SODxf^X3D|GWnDHRfj2yb^!i z%QzxP6?P^$e1h2Q7ZD2wWwu0oVQruXklOtU4+9$;-=q2g6R!t$0P2c zIZ6$f%^f^2R{$eW{X^_3^3!rH&KqaxL-pE*nQu) zyuRdT%~3fuL*VWB-K{b&n~CpxNS``@5@$j~n3>aYDv0s;C5|4n>P0k1 zA-3#(O+Wm@Q)yFSIIG*5BH&5q_3KHGoRIqtbSwa;Y00xU4rf_K1&PMnPY$Q8hPdHU zz^e}AO}8K^51}meQc%dl!oZ+cZ7L1kXI^b_K$jbzJk1vJPc$ z*Y}K6ti;?jC3!Vd39m#}d;*?!2yEBxB~l=u`^u}T$jmc&L}JeInhlIV*fc0c&&o0a zJzehS8)_;3CzMI@8tUr6wx*z<0LnCguU-b1rdo~^+4nvQl~t|;bOu&cRlUzgLPUIf znc5rFoBv|@?N?IYCXj;({N}#$PDX$`=zxHH z*ABX*l6SXKGDIpg0z0eQ;9>r#P`{71xY&Um?WBf0qrF9=DOg;XU|1M$qBFq|SI zD=~HJ2@{2gNidv+3sm~@a3-Z_&3h6GEG!H_!j&}=_^xFg^YhlNGoSve^MNL2%Kmm< zh%Am~E*0s08mCe`t#dNLmH0@OaNm*vf+U0XOoOJN7ZHMtAe{~!uNyuFTRQ%q<t2`NL}2(e%03Px+BUQGOFRd`22e=YMNtbF;iXWj461(qv^gaAHeIi3&`VRRE}+Cu z{N=7SuUK@meW}y?vgER_ohSQR&#zz%&U|1fex0d?wpQ>k#vw70k%Bs#tpS8QX8S&bV5B^WC&I>%*y)nKBvUOIN zb!p=TQ%d~q&`=v$8mbGEGRQoQZgUjvyMVBFrc_m5Xg)=yM{vvj=0&k@sgeCRUg51K zV`ggLRftbxXJJS7Pbz!Ccen&+YF_G#;S9pO{t|f{S7x6a?*lF!h9&V$+)D~brH%5w zKY&3xS}ykH1N?}8i7$e-c{T5e71+{%C=pMDf2wpAun@|xjr)T@wS_t3Q)O|*)&QnZEFZ_Wo7$`-9N;~wXR0`;_dm@zv zSt(MZR~RtV=}od(NivC3Sh2R6BCnNu`NE`7)&mUBx8e&x<3$+FXGmXIQj%sI-C;fG zLUCAs9EGAg{;gOP_??sH;v3@*XiAOtMIWzF!(AHzI4X9 zx~g^Ez2XYdd#N1m*n$7vXMT~2DJtNyM+Y@8I3QDTE0}uoW*0h~v<<4`@sIJrjgUJ; z@Rm%hk!2aDU+o!M&=dZ#Dea|Ov?tb1Tf34vd20>jU(!OSrJr6+71t<6EFvo2pksrW ztOdI`{lONhgc^q$j&G|P%i?fa(WHf<-#F~Iynew~PTc8ouGd+n1XN$APm;gKV8EM4WWQzp>_Z~H)$bo=V+>NdlqD3hmvCaKUD z#VYMS_3wM$5M3tcEPFH#|Dnr64FcH@0knfnH2iNeWbPji>Z~v*fwYp_pDQ}M)cvm; z*|H=!i96WZ%+5xk-U%MRzC5G0H8hg$Pv*eI)|t<@ugRKS$?LYkY@vuacQ&xl`njL8 zs7*moNSpHujK^2ntY%c>WR)$QGDaQ9b-9*wMp#)24n{kT;bnlkM)|E^sG-PF_2cb+ z8rrIA7i!HBPWE06g{Dxn8C}h zk0K=|a;{U$lGOfy^Atn~Wr~_c_Z9PeUlw^B6IXi5jTE3RI~};6gn z+U~slSoA(vbgMT_P_Wcfm;o8rj)ZG@9`1`Hb)(P?ntwlli6&J0Dl&}9XKrNK4YiR1 zKsp}JG}QdY_91j2TC_7GJTluUZT0=8A#Ls!SjfQKA}Sxo>%7d46JGbb2KGWD{OivlkT+^1fI0yE?7{O4z}4 zPYX*#iU_7}%c{$%6{gyWaP)KS-^b1NFXPV689g;YpXuyPfQBC3N4yZDBI$bFAQHJw zq>JC|cuJ7!%4NUIE2bOqWBP2x z+A|F&SpvDsd2Q$uj4j=K*3`I?-3hM@y@w8l`58h!ts^ ztGb80a?xMXnz}N;OO9a(UN4bvmjo37^UF_wL~rh~`m!>{m+Q(yzn=9ZUcQFbX9vkt zY*NyHxJ4a)DG7gh`tV(bmtp8I{0UjhS=H#RQORE?2~EA~fr~gqtlXUlYE<;up`ncT z%B?KZy$jvl*3@EV4g1W%GGA6GTIS{p36JqaOK;=nf8&-F(AuYXyT5w0>aLrtBQ#{o z`KLN;DE_%u^7+MWH$v*Dfchjs1qRo!EtM&0W%k|D8;JDgT7s?Spa~qOP{fZM?|nIx z1#ImT+!$uGAiC{fX@AGXx45}1&CSi5{8Xp=9KcURNx8v#8rF6Lrr7-aJTSrW^Ye$C zT!RGbPeD~tQBlDt_#v_0R`m;ldM|K7$;s<#M_V;rfei!Q`TbUj?x3j_w8GZwv*1Mn zmh#~6uy0Z#+Kr`uS6^Kn@S>owURPV&HPi|R5f;S0fuRLZ8t7#O=a*p#4(1%%CKUFU zpIu$J1?j{3cJn8}XM;mR%BHP_`AO{G-qtOzuKsRmA(UI9jjId%oR`_ul*S7mk=vDKxoiUq(>DhE}Zb+vlr!x5YsD-4Wk={%iV~)gIO$%AZPeWqo^D=vY$qY#n>M&i8&yycO8;bi0qgsL0pJ4mJlgs z#E32Z#LT>n5Z)PbO1E{Ni%Tk}(9BE|I+a|L7N;B05i6Av*zF9PL`fv#eGA3e5lf`+ zJW+_Le{ghkvT+1WGgZ(wHGouCh!+TZ~f+3d1i*E-?{2`R&wOoc0465ZG?wA zliTMZ3L!TKt{~?jO6?gr0+ah)T8ydW?r=z_DoE?bVX`5z`9K7GglM>lxi`wA=&Yoy zSw>v;WNz?72`pz=;c4pp3Z**;u;fZ5^p;s%rX9{kKe#^UQu1q6e?;nVC&<$J$ylkX zHHCeBc-EJ#ZR@M{a`fSQu_%`9-01w$L2corcv#6OUQNIdWS0sw=99wh#Ia%~3t^Q-GA$@!Bao({0Xt zC8<1_74_loPBu*)kn4 z+#4&C0;IE379v*(mFh^i0`;ir2O(E949ql!_x?8mwqBKgg2g6OMfYeXJVY0c&wF>5 zqO1C?XCeGFWzuOm5Hv(czhjJ;)U8QVb90dC1emR%>!aA?=JE~inWAD+SPk-qSt+ea zX=X&L-1oD)$I$t6yYrI8CvVgDjERFi4&h{8hlStNs(2&x-jMVW$H~_fu6nQL?4P;( z+=OvZpHf*{4ZHq7F96(^Tk$Z-WjDOXTZ$C$%CdIyhZejt80yHK`h_mXPtJvB%$@jN z_KKi0^Ew(9fL56%>S1q`y#a?coYyk5AqX4lJU_4%V$S1(7QBTST zcqO&Y!vLq8l4T!=*5?seAtlIkuhEcC0dkYe_*G;+x(sUbC8U{FUh z5cP3fFYu{{5HRFSWXO@dv!hg`G1O%oI+)>+IsXP# zsNyzlbNfRFF3!%J9bFxN0f&DL3?uSK=K|{iRr&{GVTD&4A9{gTYDoK~!oMvQI*X4} zs893p^joL`xW9I6OP=J zdAB7uHH(;T*8CkduWgn|(hw^()^?n^_^}PjbH@Nj2&9sckzk^&*^R%E&reUNG3QJ= zesB=bGXf0_4f<@sQ94-bfmnUHGeUHEC6UX{$2W(W8q-X)&>!!(CztgfagfF1<}(+9 zB}e9D0aCR-rAFehlvP#5Mn<+`n{f+BSz6Ll+MwVum;C%WCCQsl;zFeQ+r!T87&w_D zBO}2&UvFY^l!$ZE8-28(?<(fMPQpzXtzUtThSpw8K|pFUd<_&OAPxbD94@ago*n$> z#$3P3ly5g0x$o@q60o8F)k>c7t1$r)$b2j1MUNs${_^rNdcsdj3l~P!Tf{hj0t64w zOie|F7L1<(Sx8D)(Jy%O?WS_BDj)J0!D }F`LPFnW^eo@lrubmZd7=^@Bxz{7 zH=htAJmyvn*bX&cQLNl45@e?wcuo!saXt5w3)Ax*vNwm z!;(jJBctEC|06M|pytew674iErZC`37sg9t zRhqg__4y&}D!0&?Evpz|aWcU`NY|57B<;h&vHWF79$kt1g#)k>kp>jFy2kMEtkom% z$mizOcuhIR8Z>f#9%fGyF(hM;&_-1_C|2@vcyLC<$mAXx_8v8;5gzF6U6|<_otP*6 zl*?s-4=xu~(opdlhyxekeaJFr1|+L zc`|_e@dFpe22RD4nES5kHN}AuQ{=l=KyQUJpqBA4 z46IC{uW#PsGw`Z?*{`muj=gnnds69Y*~OiXh0II$1fp)Y@rD0>Pp$!zVa6^_b8xh= zcCtSFvE?$@nSXS`GWZ?RKk2kVkoI(}Z~8~!Vpe3`&$YkwGUCerb*I2E^e8|t z0Dh|0%3LAnlDva9iOf51@TtEfs`It zuwC%=)cy7-XQrfuzrrWxwmuGjXkmEP`IV(Wj_>1#aJcPyUE!-}lbRxw6#?O^{aPxdF>SNJ#zT%PueG&kc_LdCPLdv9e2_SU+@ z#~$pT-yxDpt36q=l<}Z|Hg=ZJFJ;&Cv8Em0y-91nRmf`nI`NHJCXwKx%v<`z2YJbE z2`<9uPg@GictoE!mbcHN-5!BE4en$lgSYC(6Nv3$rl)6bh|Y7me|(I+H(GR{hLXf? zTPx$$9VZ2n{?X`#Il&3LwIMT}4Hvk*j{*Y`2sQrxP-d#^2dsNVy3EQ-N)@H0a-iA? zd{9<~jE+v~r1B>k48{L#gaRWUyp1ujXbIiC^_pfJ^|N@Uz)i2JIyEe+AyV6C@4*=nDJ-tEwj< zu)p(5EcNsVAT0yi7k~-S($QhluiG2l&5+7-%gX*es}k*4EK5yzokA%h;yWzYtV35;l4x!fz^$IyCe z-<%iv4x*}NFxEaL68xgadmK!VBk~1V(&Pozu%#?CR#tWD#4PwSG2fCy{L#qp!dP+7 z-^dK#bqMivnPD67TnWan4&>2=Byw#=#$l7uBzt;&HTj!xxZm~uvp25}8R1Ce&W0Sa ztd(+1B|18*YlE_YkbHG@O&t$!w#{cAn<54rnp|n)u5ZZO#VXkW%$JkJW2yX;Q^U45 zK$DM1swbIVnHUX+56I0js&p=*%h>+&(WAO~#alI`CW)_a);MP(;?EzN%N+%5b(~0i zMo#slG=*~-xSj|~Eu+%1U)oyd^ylN)J?Z${8LM$3zqPI&e!G)3y7Q1a%+JbMfy}@s zc$=0$A9t%k1fK?b(yw04;V(1APxy@y*}hs0>w4SyHkw*VWo_G1p5XdL6Q^Kj<7<&r z|7}V*C8FMU(GKP?dbBQ`;DKzEO`ignd7>yZ1QWWTU$tFxrDm&8T*JtoqUeIWWUc&U zk5(c#*;?B+z}568Fl0LO44=2a@e%&h88P|njXiYu2~qkyhb51C=_jYNz?cnaFBh#2-YR!eWbUf$Dte4>F=qaD$v?ex z2f7wKj+=A$_SG^B!A=*pM$Br@O+3Y$5i5ws^L;>R zr>>9Q$fNTA5%tzVS+#GpFkRA(Al+Tk?L&8mlnBxwAstfE-Q6iDjdX)_cY}0y!@1wz zne%g#a5wk zdLD>6w@@1Ov62-lQz=A98(C{3@mZC1{MAK5I&oeu%&_46JdS6q>e`(42~Kwo57V== zjr8>1zI~gPoh`~(=Gf8<>c&9|E09*=-QN!ZCFtQH!OUEEe%=-6oo496KtTa!yEn+l z_mXfztDzAM;MaS4dH`U97&qi%9FqDl%c`uWS}N!1QY>sm`NzfppK0{=%_5+>L_=d? zWgQ(GBkMHgrnY+GS2Ho$Oqp{2 zE#o}g?%gg)6ZY~e@@+bVlH-XQ`dOn;E%Lr|)J?{@rSG2O)kblaDbfS!WNic}HhH~* z+5M8AMv0rdLV~-_`YHd7Ny-?8W46De@DNmc(t;~cZX;yy8N=KF${S}^d=Vw+Jw8k6YJXi;M8xiO7ML)g%IlHoVyVb7R-x3PV5 z3S|tN{%U6_&?fZ}r<{v_D#MhH<#}Q+Wrqx7Bq13Si5L1&iclwAG%||R3Nb*ZR43@G z84i9K6#FPAmCU&Z)5HrTb-=LT;2Kb_rmda1vO3|nV|;32eF$=DMu0*%i)(2ZHA#0o z87{nZpSfF7Szb}m9BiP>e>K9-EcSKI#_sH)uulh!+-y4R!ywC3Y{{D0@ONq=BKi9V zecIS`cewaxDyheql_**MR|{{aOzw@wHj^eG5Fh$Oq#h@T@E;1_IX^kV0eTe?#)Bzky_a-uRHcnVl6K~15lh0EmTydTgb?!Uh$Wz zI*Fd3XJ{Ax&9g(4{t?x>g9fFa6h+j9CNnCvmPP2I%JvWT^QGJfHi>1uI;BT&ty%v& z*{k$yUl3G()ap9Qayv2=a=8e7-}^Y`Z!IG6ocmU=qVLzkr?vY}qE~AOjtwzYw`8Yd zo`ln5LST{-f>3@&aXOvj=IqaB>o+ z%nH$nW0WYNqKo_|KpnOzt*WXvlw{~zdr&hbaeg(jQz^0ViDR~9$kP5*=9}U6pg2IB?V!@~<@Wve z6tM1Bt!JoQcX>Sd4W&ye0w2E&h+ZdG=lORu-x3i2YN&jVYY?*tO`#f=;w`*H32_1& zC@SivSLWHp4@50t*FJ9s$AycHIlswVF_N^GzPW&l5yH>?_kuMX=24r|n1#w=aa0G9 z)M5EB$=YzP$x3lzorWR z^wAFZOHin4lo@k)yBTKLU?5GM6*LMgE-dM&Q_Q$V`FZ;+225SaI1eTuItyuxNlpx& zDoKNJ2(HaXk@Vn{9o856zbSPgLhOek%aq6aaMIo_MInV2-&0Q1XjBbu!Su&}@ki36 zpQI%nByqA~*(ty-=F8Wq;Cr{7@nw0EmAQq#vq*)75*~R3@*|sn`5#t%w!&nn!y+Rq z%FA0GnN^>OyuH0ac2mrs-=K7unb{@*Asi@zA|Urdzu*Yz<-3g`N6t<}rRjK`MI zAH|zB5`~33!}I?v9b$(HZaopK)?V}{qr^QKqxP` zA1!SW5J~lh;V~v!P16vr0T)i6)5YzINdzQP^S=oc)T_F6qJ6&T2Ss7$VI3z=B}i~E zpQ+2Veu5T{?(S~s4Q(SMqper2T0L8k;}3#&tGrkLI2cmKg79D#-RhpZ_r_hK!Ht(e zubIB!HTQ~ck9@NB-p)Ip2284IFDBHd-ALKTSgXy(=LBD=F3wxc}tA`#rqxapgx=tvZJFOOOv(`ZgvlkXGbx`ZcB3p@6oj)% zDtUpm87(Rq$Cfn~3(d%#kIGd~P#7JwHd)HMf4Ekb_kMBP6A)k^ zA`*Ng{wOaW-nfImv*Scz;2g!zY}!{MV(E;_lF8M-JlPdyW&6Qpuz6~QNT^9=IALgB z4o|ehs02*|4i4ufHtzn?EHv~2zI3p>5F!$zl2`5T_UDIA4YpB(*7-2kg}G6z@MY0e z5XQZ|Z>NuM@)%t|iQdC5DPQzAquwZ^epZ8y(X6g0vO3Y0CGUQvn<=s|AUCZ)&^0?o z$jdX-RLLD=qD*4zCn#o!kHf11%q&#fZ+{xRad)pDA!CxO_i(;mmh7tN4tW>5UDUq= zL)TDnS{n8>+rinmy)N>4)AIsuv^aDXEtJ*MI_&3vH0OXw18+N~MQ`@Q!n+%;Lse1s zvwi5D)v5VlmJHKdZ-@Ctog+t*8#CLRohYVxL>8FijMaq7=y?Cv!p>iol^;)!&Hxfh z3jVZT;`mKhZ;J3~S9E1e0{tW-Olo3DDKCFH8)`k)BD_fRyf(Ai%! zJna^wB}ll@Aa*p;@K_ zel}CvSR>MO3uiL59(^Q`fim*aVij!9mPBn}-YX_oCIOPw+&Jtev-9RE9m60Xt!Rfd zg*PM!D7a*Bd)foORPNf2`%t!_mUwj7yz0*X*~Mj7oOW1SwqJc=S$?;0(EPjG;{&hR zZ72i%0+gcX*thcB@JUXKMJHGtt|mdD1k(;{U|=X_X-)btSJi1vZY}KfR!}nRQ@RIz zaC_iIq0W&MvkMcl;KKO+pE|$$VX!6RVGJ(|1@Ss^>bfF6)M}&yAvL~X~ z-Cf7rq%_NOzV2Kvjh*%EeaAbmD7jv}>cGco^$Y;jz5SPcgT9X}+T2w#xRHTWTi+8n zJA>&pQ08j%d3640E;jG-KlXSynYzBgJpHOFk&CIj9=V3Twqdv@4M@(PGazMa23W%Z z$O4m++AGCnNssa-&atBM#g*Q{j^V-HLuDlJCN0vwnX8+%yLKU!R9bx_q+>NJ-01?C z+iD0917L~)g?^vd>=`yl+lr%+2S_(<_07uapjAT3?CaOQZj5A+tMSdaxTidjHtN_7 zr-^sJeRyas1pDLjpSf$0fefZxpa(#99dVk6>n@4{v+gmDolqIFbl#q&7Vv^*Wr=)Q z`{w9aP4S-*3!pThnn6Pxz-kbj;p+2sf=1!L@Q91k=3c_kx8|W>t<`H%b&hjl7+a$C zvz0i;{s}2E6aqjQ(8vEN{bNfwN+iup0n70tdnpHp$o#+hl%t~~AgBNhj;aBnk&*AS zf>j?CRx@IVQXqN01GiA^OOm$U`78ie)h;{&wLb&Pj7oeP`{hYxYU?K+>8^L^fvSt$ z;IsJ%&DA>c%mU%d-~%fDO*_^6E3N9jC>7kPBuax6%35eb3u&lI=}{2UeNB_(y#`-f zZ0&|9DPSdNNKwFUy<0mrw@^T@j7DxCsCEOVQB0nqfg7dE3TB29-PM)e_>E3%4l}u5zq85db#Sq0 z!lPs9=;-n3q$P_OxsoyY8_Oou^4gMgE|J6dtdTz5N{h#7Wy8JvY&3(@Y^5!O-8oLCZ#okX38=s zXX4E6x@ZRB!K&=iEEX#c6Q~YGx(iXU=E7NWF8|o*_h6{WnM{Y(iV3l$lpq6oVbfY7 zkr=-?QRpUPGn8Qau;H$Ez%VSn6_d`BAKCZYrS;(MDpvbNZq7w)(A!Q=zawAxJDb;> z)EA$c+sBcs-8FQDGYh3k!3_3hx`k^flr^u7mG$+;O!0XKG#6GRK^!VutM-UG^fZLA zy(!~0%gUvH7h6nZQuUcBc`jtX*3?oATO<|ltFPhQO41RB4PW|&dLA9~R_$K#1!CWN z?gH#OYD7K*GTCj+1#!4yssOoY{mE~X*WS`U!qC&Nyb(RRi?HBn24^8ccII^7)^u&o z5K$d@5XnE{92^PSVq_rJQRTGyT#{B}l;x&-tPAm6QQ6gB^&|x2p>mGbbS$&Z6I<F9Qt?ompetMw2E%p z0MP@he1YHo`n6``wT)ylH2wJH|t-(`C(UczNU1I zWG9k33vC6L+x}6h`(`yA%H7qavzF{tG$*@x0R16=z*z1!JHT?y6@UFS^t5u-9xAjx zyL(A%5Xcx3VCG_YTwD;`APiJ>!A3b)k0PT zCF%yfepVwah$f^>(L6N|qMDO8Riv1S^5*+Q=^2{pgu}v~_iQ9^@T?ur*j_+J-&$Gube0_P7z_JAHR@`I?B(8n2qybfSc2hssb z8Y&rmSfW)1(wAPVn-7MybmbjyUu*d_=!8wSfC)7ur-mCfi7lLJ>ub<$1_C)I5;itA zP!9m*tD8`k3^m|%+iL!Cv9ni#L?K~e1KRk+|AjBE;Ix?%5d7q^({JZtyES!m2(2=kE(uTe2Y}>COq-3_Xx3xPcHJD7ce zI02b^lnFNsED6E5ZONU+!A1@0V?cYAvgFj%RIiDHloY~dt}FjfkhGDNW$b&N89DQ} z4`>jo|A*95SBAg|Q1+ia3?MY%&?SExr$uP&G2jPE0g=A_TswSeb;F7!@5I ziwr}7QtbCx9gnsDGs3;>zZx0z&hp+!{>=`>Z6P?Bed}*9ZSp!{qFp82#6Q3EpNEAE;A#JN~3`SP2AIg5(XPgXer$sfAw33e{ zYWJT`N}{v{17x5Ux7>JAoR60b+qJrcNhulo6t|H(XR2YEjLgJ^9RI?7qiFy?(hQ*BKP>6`12C=cr-Gpdtqe1Y#hC{A!M3=hCf z5BN8RFwj6vEA#{gs@)fg)r%-T!zUO2^=G)zc5H8#wmFDz!^Ca{8{c78B&wM={^ms9 zHv!B6+vN$%=9=(_(|}scXdaeAsyn|1-x;)VyyYItj-iUtA zCUb#Z*UNS%acS8=+Nw&dJD*?3r%ty%$w8)qF{<+8RQ?dgN^mHTmuZTO(D5dBMd?Z|U6f@72n@ zb?9JJPRujqpNZRSc$4{M`xiqT?;)-8!D}}Mme{Pwezuq(NQlY+M*Q~1zNAww|9`fI zeLI_|VjUD24Pw@;Z0aF>zvOA`Xd&djd*6BwnB7*tcP&Vu_X+1q(MsEE*e@&)=j62~ zZ4qdHP)YnJ?Aj}`?n+D!swv~$I~RkwzeD?6Ycrq0+Hn{9y^9f|(xL#j)9d(^lc>1U z^Dh_A=ayrD-nTfjvPp0EchSmrf5YwtuKP26RT$rJQIBoH$7B5lYCaB1I?VVI- zvj8_c4(Q?n0D_#Hj$P8Mm`H$8CGD7q7q&dCfQqo=aAI;j)7u+W{rbm*wNeuLG>d%S z9+D?Ss!Wb)`sK^P@nxQ=pJyqRZG6xWKG*K<7aU^K;p-D1co23pAiUheF}vTr1f0eg zupMB4A9Qq}h(!sa1Oi?m*?2K>omvZ3peVDj02Mv@KtTZp-YS2qVZ?(PAcV*F$ zp|R|C3(!fd36@}B%m$@kAZGjbZ+p<&0fM1?#%s zf`3zPHywLX`%Pwt&2_T|`UJ_(?JX_$*=C7|)?8ayKtuqDwWOgj!yTJAWs4se@BP1t zQ6O>-oD4t?9fqruodcl%GFn;p;8(hTx~Kx_KwbRfBEq}1i%3uQzpHXafjklTU0 zg8Y|0FmSsI85$a9RUH781QC_$)h8t|%b%0=$R_TkC`Uh5IRFo{?Ca2L0IKI9@go&r zlTp@?Z&&enYIxxU-}z@^bhc5(?y<1Adhlrf9Y|!-JE{g)?(a<$_6|`a3@u3M z7{k+;9G4h1eTnFccZ5a?Dcq-0ZJhbDRu{=ToA9#*ASpkgTkk|9ei4k_Y%q>(A*FD~ z%eafv2JE#oeO9E35Y8_zPW^ibUt5$uDI%Q+^H0ET|J|F^GwlveqHEzMWRq$vd@B?k z!D@j2o$XqiRh4P-DUrykm(oZVnAUWGkGd4dG_P4h;k9Pk3JJ{Ph*c1D( zpLYX7z;8xDLP0$b`d%}7qJ(BE3o|Z#c|+0s{DQzZ$x6$L7vHKEgZ%yLf*{5n?Lprw z*@rLk`&qJS+@1!Gsmaaqiv>$(C@_>I zB?{LQyRRP4Mr+M#_jT~8?YqVGK1M0}th{Zlv?I;gpVa1;4|+5VT-tmTkX3opQdELl zul!HyLVuM`arU*9>EGbDIF?!*bH4OxUU?hAky+jFxkEj?U|xM@x*B5HyST-K$}dJZ zUK!A94sCZ#bY6HY>$SHqa)(dnz{%zbO_>+tp5FU86jCi@vxmt{ffgC5xnv{vnH$EK zo>A>598wop48pCjkM7HW~AfI9ZhindQ0XDctXs&qd{aVjLVrfR^ciXuujbp8lpqs7^@9%SiI zvo<;GBd^Y77ouJ>U+U2x>b3V>yM>Q#yJBqJRa>5GYgb?$kGvtFl|l9OJj|dxv02Ay zt%f*uMfGAuYQIxvHB=MPZE5uSVH1i4ULX_BKsnHkPJC|dnH>v>IvSq(!!8PUI+wQ+ zjksvyf;J4@<3vvNohyc6(3f^0&Ulx*JH_?N)p?ks4T4wLIC|cA+nt09XGBZC;>GwV z1H`sFMLJ7clrc8f3yw}%5-SNlTYnyDA{^!vZ=n~gU z2T{g5r zc4vkSzwr7M7}S3W!#wOks|xQo-WTkquKCURJgbs73OgX~eQn6v_uS#l!835BMml__Nwo7$ETR{!kja3%14ZiokEmw7@VMLdF39ybZ6`!dfK5(+=W z^|`U?T-7BxEF>_|Di<=iaRHT%j*Nzabai=tZKsTTJoj5vGkO-R)pw!Z!3V$;6gbu@ z@_PLCxWZ6=uF1_?k-2*P>uGfR=}Gg;x_uzTjJ+KH2SFHO8)ZRa_hd1{FE9LTwinZM zB+9A<>g(&X4E{Kd&jkqGt(yG47t4>LPYSUX&d$z)*q}>6Ei)k*587)_{fWq_wTtet zrhj}spD?5As~u^0^1x2n_x3fWX!z z_}1l~HE%6OF~f8?&vnK47HiZTn|3a)IGXL7vALp^izKXs+^cM(v2f z?deoF#f93cVJT87ztcEoXj|&y=THr3qok6Gpl4#@B18rJ36MxTN6OOcRQ#`f9QHK9?A)zzaOBRJi>vtqj&S_0c-F1Pln!;~7| zpRfYQdrn>A)k=uYqX>Nac*Iw&XibWFlj%Hr2<}@17i)q%dr@c)tLO%GAB^JludM~0 zSD`auKb~1Y`#g0@%M!n!^IE5;w=Uqdb&o7TeJ}m`EyB5w_yspd?cWD-T1~HYtyaX0 zyRrsxXNCu>bTlL0xuAB1L3#5yJY}}H{lfTnJ#L5`S=?K5OCfIsRn4iaY~2dcepB;X zP8jf{`TfKZQ;&xX5>)Cki~PkiyXYcX{wnqH5<3%Lytron3Q3O;CqXxuvuzyGFXuuFVcP1u zEnLoh<`J!jPtor&gz7LJZup#=@gDB^oFB=rx}oYh-2gnROwMcO!Y%kSa7TF zNTlGx`%HtK_((!^N@BYa-kZ!Zt_Wx{7b!)^l4DQRS#~?i%A&tXGVgs;?j~L?%+gFa zMl6mSL2Z+yPbD%K63xAtAJ&hVZ*{Gy2$9m)CE*ZBvWTGSi!5{IRix@u?w8go;;Y<8 z_ez6J-|pB+&_++M7vud*k(Menk!!Fw-gctFCR^2BefFU@J$sODB%D{8^*yl&`=Mx5 zUt38E`^H_2&gsY~kK7{#a-?-&=`UM$WY@}Zers@1%ssXrvg=bVBI-Ai68 zgA7T2--!~dDIRG>*56L?SN5MAk5HXKrlV6v#tT(Y5%-GO0MTPCvLB{IingpV%fEP}9|m0?suM;~$)k>A z#J+QiH~UK9k!+l^y{h+g{kC8!Qy*#hBsu3xHIC(&nV4upHllj%vpz-{{r>vx_#&0~ z$G_wnR;xD#&{L~G8-J~^R%4oUxJcFM`FDJBM=Lv%KnDJBLBtv(_(j( zVI`)fa_o1jxMnaizMVMe3GrvcuA!PoecNh4e*n%>9AAw;%IdYhJU?EaO6%_X*`Q9t-zR+K%Kyi{?Wxk}`9*f51*-z#FfkKj7RzcvZWPY1u%$&KM7iF@!^ zI9k{ol(W>Bj`y8+clj^Jj~Mj_plduau(dj{Ga;rpU*G7K_Zc(h<0MRvogw=UBy&s& zKGCe5C3~f+gZxp%>NJ1d$j&1a>~#Ftd1w0c z_=>J=B?~g?v z1#zedQ2pvgyGZ3_)<8~!A*I^!=$F?eefM-4p)M~~{SGacW8Kd&d(UZ^0&`5N(DVj8 z5J2sJONw$yNjhm(HbZEN-4nfW>Qd)FFSP&dijA|pC)7cPH?&->EM66NcS$%x zt;-XDtGdHuzD}WiCSJVuDTepJ366a#s~Gw`aC9M8o|>`ME}(5R~{Em27i))^54{h8`hpkxmFv#%`YX*@O$>M@jRGy)wE7^J{ z*Q`tWjwZZ^=4~CO_?;SqG_~|0 z-yywl7DuS=ARFYPQPI{C72*(4ja`SIHz_y$50`eP6)NKnc@zQh1zU!>x40*bww?Wr zrw=X9H@{I6j~SCRTb_}c6ho$;4Eg{7`}+U3&>&1kvfmx#-)fxPl7Tw+b2w}*UbD`r&o4PNk(kL#XB21Fm1eW0M#FR^w+ca-rCYp8gY?|B z;ql+~FXp#~erdE(Rbt7*<1AdxQ>f2p3x?;hWVsiyY`;W0_+4P-LLbV@O?M3AMp)Ju z^Woyi>=UE2g$~BwuP+uItrCCqjxq>F_d%>!?AN(SJ=*3ScTf+_n|R1=)R9Q*+fmy? zV#tGIRMmoGiNGH=oq&@_BH6I!kQKycA(Wg}ATJu7Ykgts?O)=1{8c-kp?zdhG2gp* zjyFG7gk$JAcHMME?7Rn>-bHQuwaM?DhxVbHN3TRZ-;@~flAtfRLnny5&ps>SF7Rwa zXnV;d$en73?xnE^X+nleCys&xgpt7$+W6RisJ(_)a<9{o`#YEI6l!N4U3o6f`zlB9 zMPW^`V99&T%-9dnaawSE^moUXkM<3^>#ngZmrHF&Q_BZVPqg1FHOe|t*TmmXEp}5p z{`Pmbw!2>N`6WGMYXKhXe@B_;AJrX*DmKnb$*ptm;05$!xIMV{&dkP1>Mj#@ck-e8 z+XKLRs-EOFpZR8KEI?(VTT~3O4OY;@HS#Lab*5%*de}!@J&soZIXyi@S(%47K@+?C zva&~`f=kMleQ;V2EAjB{=o6J{LYds<70JJieg5&!>tfMFvpKY21LEyiWT0X&nozCaeL1MmK8W4m-k`r=#0DekU~!vwQSh^J zYrq!S+OlX)Y5cD+_A#b<%G34y`;tbQ`TwnwHAlVpPWQ6#!7-FwkC0vb-)oD;WF3(a zYjX3-3Hr0DZ~elfNYs`axXrh3*V%1^X$nPPSzA<8^9ySba=+uF1Jh?qI`Vxz;0&!Ss}*3x}3dN+G;_k=rtVfB$$nzBCxbg`6cSqIye z%^Zx1V&8tqGoVyTRhXs0mc%UhV2x9E2n3U?$*z2r;1wVO3r=OoMxL)5%0^A5k&z|e zHr4g-Pzi3TiPK@LMf@V4S=0&|anGbpbx|*{#NyB7uv2`*U8d~6R`E8cEEz-?urAt> zv!MyCUkPrW37xo|P=B3*)$s6x6t2aUT)jZ#J#LgoKDf=`R zjpii6%Ft(T-Tv;o5=N{)vo4bIIyHy4_VzCA;g=)gDW9R_umoxM{S|>$@{;>l=79*r ziW5`Tb}Rb4O&via&YS9B{C^{|7=bqPnKKnPm?lM|JTas;$3?avF@zgCR;ouEEUq{yRbQ^v{^O!z*G@D;E( z{1?${UrwI>yq10&uR|M;1XuTX1=V=u%D7ovAgK|K*Ij(b@oCr`v!Ce4lDj#tnaR|q zpqjH%Hmvx!*LBpW?=&L_Oh0#XeY3P&{Kr?fR9dTx_a&bhC4P^avM%m7rX*4jGimg| zrzzbCmA5Q>%+&0B)bxS)eWvVuHuWL>LGWG>W(|fJ6BgP|H1;2s+>YT|b`z9ZsF9pY zcoSMZ2O4>LbY)5fKbW+3Bh(wWG=HW1rMLB{wbQ9(T`E@|_}lek8(PVVV~6nEgvt<7 zl#ui@nOtAf0DGC;ytatJ>QIuRao&X^{>lW z3vJ!c9Gl5LGWM-i{bNVAH9jW>lNx{Z3;w}l#;`MKiZuK5vrcXe{$3bSlid$H!6&7Y zCb&rYtWSQU3&Nu*xoaciY^hOrkH5rv8=Zby)1EZVccWz1p@}$L6^q8~-8cy=y&^Cl zWS7=#c^SB=_&n3kn-VcC}pV2pk$^kq&C&LyDuu^P)v?Y zO=eAwKQftRA0rn>+>?_zG1&vw<-^=}FGr`JV}5Ti#qx|`spWz)>?l@FG`eV^LPVjc zo3<5Rk9Tvq+F|J%AH)dpW*e*Eb=IM=TjBP0W9>U^Y-}yN!#!C8UMRmq>_2>repDU3 z^3D-rw78x7K4u3$s6Ljo)bYLjM&@kv4LKezlJ>yWbam?U(#dqq|>aABHvVFK}l(84h@hhdHMs z>B6M2K2(2m2(=<#gkM8{S%FNf=d45d`o_E-9v>fWZy#?9yT#0rkBMiA@p>djx^(0x zq_+uwx$@;<6W#`!GU^8m-?3wnXX#8o(LyNYm+-6C3;gfiSz4?YS*#`)`})Hd?OyE4 zpIjXqar^zSzxJW#zzzR(i|Z;h4})BLv`$!f)vD8e%fwcooCu)cc_Yc=_m=^aI(C?w z$v=MVA6^af%!Fp7rmP||)|TwdF1L}GlKEYrGGeC8hU+P(;SGBBL4O9}U((+7Z3q&! zo5@cVfB6zeYEVYNlMeWh^t80TsCP?tf4pX865`w$aKpfAc98BZ5s@Wl>S8Atr5kjZ z0XG9wi&FVjAg}XizKS+}U-^p~YjRJIOtC_&QW~|A?0&}}9*U%dgap_E0N*7D>+tq| zPT}}`f>{1)Ds3QKuE7Xauf)W};+Wz#HrhXhb~sBRYz4`oh$GmO@}K@3ibB ztP8pJe|_214Lv74UTe_ugznno7ALa@pr)*;m7Z4-3>?Ia7X9e2BLa>b|)7 z88je`(w9&X>|s0V)@8Js3#r*9MZ#2D4`*2&H`r+Q%D?w?kh0C#XmHzQeu=Sq|{*62oGX}{*9J+;cmOA#wyMDk18aAow1zt8|8M| zZ^|NtNmdVd!+Uh^G4t`>FMBs0d&O)yOxfZD+K*%(W!D~&tsm9S7kOi%jkLY4(i|6< zk2g!3;MFVLBYVQXLDVzb98o#SkjBP3f0*Z4$}Zjk33?=!>d)n z;9HtuE3kH|X2S4x2uPGoSZ#AsQSvhU!)K9$q{hm`FPm!SguGL4LjKmGdg|CiZ{Sci z52@prRJ7nK`P6|O&-IN+w<#fFkDhrhWSgi8hAN4G;B=G`C{9xX74l2FEJ!{_Fmk;e zx{xN6*4PK35=WnO9eM(FO!S3BO4%DMo}63uX}-%%+2UZIm4?m_n>u$!%uVQq*Krw2 zU#g|WP23MG&Z%phDrMV$`~w=69sdQ)Orjxvh}QRGeIj0*J>c4n>>0aZ7g_9*uVbs4 zZ~-H^o^Z5zlj!m{EXi}MGUpSZHIZL*$-7F|3#eAMXX3($=Z8OB8MNzwW5gxxiYg%-5NEliCf? zNfiwgG45b;pV!>mZ1>}Iew6*qX8(asW`D1ZN$ghc?b&1Y6Oq6f3zC6BUGjM^^y1#9 z-vtO{GKI&ZU83HXMrHirL7th&BNmY&^Vz!RwD3KP$t339fV=dT5tpPpebja`3dkc-re1Wg`p%5 znQ^9qPMz?uu%@23w?0##;tNno`w0x+gI&G}gNBMQy(mJCyn+H#a6b@KqAaf>iP=-4 znqOj4_;_!0D!drng4X>Oi_1vJB8mQMi_W;J|7=^V3#cHSBc>@Xq`&VzGl3Ha%A1nB zBbP*nM^)iFgs3f$gc47u?9;`Y2_D+I`wNrs!*pzkQgO|KjX|4>^8i}2!ns=t5d^b9 zK9N2wFZ0$%G|?hCm^yyIhUepMHY=QXlS19sMtuW>IFVsp=iiqyT;q|D?6bN@vX?8@ z)dy}hUT(SMcaa2X=UDh&5s@X;8;LG?ol+W0p?ZQ7GBn==&ShD>-Y&RuuLO;JJ=}rT zWMJrq%aqx(wi_`~Va4e4v|V-SeYCs7Q5$N68CQ!TSv=aYbL4QLEz^dM7P7@q`Tjr# zlUq1$8JA>8?j+w%=eMs(dhCtfXacb2d`I5;B%_eRXI{qVSmbx-Ld^{5= zQ&r;*ghmav_)Sg*@d0^g7QFnNeAyfc;{er-kePyl&+d%{a?T_?=0%&`yp11|JhSfR zxBf|su*iQvXGU9USNU^-*DHOgDZguxq##Y8G}Zb*c_W9zQIVCR@j-!pN}B+is^&b; zhFK6zQE8UC$J*pbPQG?orc2Yla)CF^Q^1UMhcFLIRl>r|1BXl3Fg1kL+~H5 z#WlY)Hz&%@PE8$1ijS|9U)9x3#kc$woj0T3+>uX0?H1*YI}$Sv!;D0b9C>_rAWWi6 zNnD63QTdFCNu*M_c&{Af=XW&5R8<--?7&gu1nIPYv9xu1&|R{1a=c|>@Je3EgC|-C z)8{Dy$a4jli`+H6ZvlZbITCr_i zW8lT_9$3*rZFxO>HBj(hG!?H+fz1AZSUOA5r*~t9&7&lK4+$J`k(4Oo0XY40Hrg}R z%^mCE#A^Q_AQ!QX%66+CM#N^v-Ud48RQmUak4kRun&6Z^jV*`}fArF`gO2-ipU~ea z4|PpS&XgDxD=7;=)RVO#QC#&{xkGUc1*NF%$yZFEDF~8R>;of{FzI>n@^;Z<5{JDX zY*Rl&21VB^1NAywN{e=5TlPfDWj2DvEc$9O<@m%qdZ826{lsf!!liMyh%T0uYzDmTlW@c171=k0tQZENN&D$n zYo_i>iNC}67-=jfJFo8o^Zxa8B2g;I#I)Vz*_`M*xVSXSKg51{&&zvD^nO&`c5!Ue z(dxJM;PCKKxtNvUbFf`i^3ZlrP|()j-=DgFs3uAq_{{nggdRJZ0eWG2+S#5kN3Wu2 z`H((LjVPZpRUv-@_<$lvg%@pjii?VPxVeG%=38TDeUKx6`HWmy*?KBhZ+Gwz=06{% ze0q@b1oV#a>FFQU)u-m?=YK`EuBnrL;rAy8yGaeW&KQahO}JIU!!829sqp6|SJ`5H zhbspKsE(VJEu`~qXWdu4&#+#8tI)^A$Aj`jvT9Pf{0ZRp2MT*&=yawP#hB*^%L5^M zXlQ8QJN*9>wfp}!QLib}00WVrkw1o5o8&Yv~PIlY@P#FsctMMZI3csmH$RCI5bIeWoNCYC?_bSnAuQ< zBD);(&n2o`TT>=u;y5Se1T9$08n85}8Q)pc^$CO`=OAU-1QsuD$l3^W2aV)i2#Y(! z-=JYWlzOC>ryvecsIqjt_#bTJJ)@zThU~dk z0rd10h=MhFQ3MU`3>I6&xONg|{+m!$em937tW3y?(R0+z8cNMwCQ=Ht?zoJzB|(hv zMy%U1fmkpi;r(d4?A=}a6t&|yF=F4{LBa8NxY0KSbm%wd=a;u{3N#%3{3voiiF11( zQ3)j|eGcN9AO30wC*MH;K?=k&K~6tP!LD2|VU-@-9r%Zo{Z>MRd3^xl6$HsqD>G)H zoyak%1JNo-phxO&q~m;!WSxLS*#4)wx7q_NP&7zH6#Z*j@Evay5DxY|?x?xR-!P?1wck7U7R50$x-HAEhd zOFp5MUDJ@0ubmT#=vVP_4^JoB8=hXifUw3&Jeg-!t!VGs5UkR``9UmHp&^S@Y(SEC zd8Xv#4yD{{6P@o4t$!)-=hD~*K_v{nS1#uZ>8~=L?ML1(1SQv=7F!PE7tU97WA=b=y;-5J_bQ4iH>tS9u1gw*b#zj8B-#y;lqu)TUT#;sxJ|kWgPfDH^ z<_UXVA57GkM`sDkCR$)1l}KfGY4c)x7r2(3BsQC`>#~;@KYHGMwpC=sN(=Jag0!hq z!|cM&4}P|NYQLe5d6$}mP@Ctp6H-%cjO(qzo(3YA4GiAl;9N3~cA9bu=MRO3Rd``y zdna6~mTCaQ%~oIJ&(czd<`vfDpEb1ms`ajG-;P~85vdom{*o9 ze1fV=fy~j-=}lt*b(HDfknFku$WVIP}Q~^Ku2_CDoe| zP%$A|8XCBGc)|+eZ~VzYvNOo_2hn~QH9n6mK+^sXsQUiP;lmE^y$G}ySdppqHhI0^ z1@2S9jP7nK)kL|Od&E=K*pglocOhz!p6-f}X+WCTX}ot4x#837LrrZ}vw-^J7gey} zums0s;(J~(qO|Ds(U*Q&nhj<>#lQ)T=QTWZpq&$<*Rr{k{VwbYRCR@{) z<@pXn;%A(qHWU2|P$G?zhj6Qp5E>~j5)bXp@E6vbEaiM7(e8ZLZeUmJBcr||gMwcf zE+qK`u4DR;Z^6VD^{+gG1N{{qk&H(#x&h6l>}ib6RS{a##+8M;W|oej;-9>sV@O?O zNiAl6XNR=znd-mLh={)MymNnx7Iu`O&}lQtgCCOn)l}cQDJOCfxD9?Q(gYO_{1HG_ z@7>p^qSxJuV*D&)b1+U%g0840kn~YZLjx1%KmE!iYg)O1(1*q=$&vK<&SL;>{E0mU zst|Ps)%5V>olP2dH%lHvZn&Y5aWlGnqN)Q(^Q5h+z*RN9LfB!CUY!cVZf6JW7y^$w zk1qWfQeiN{kC4#vbLWI6 z!$QHO^uzv9XjLIoh$TxM0txKGmXnY-4kVe9mmMIbkd6qU)XS|k_6QgV+l%DPC+g(J z*VyRL;0P3$z{(GkRiP`e%s?*&2tEm;VfDT_j%(s-qv?}-3j9!wF+5MpyqO|VQt)>2 zrY2g?Kizrj(=t&#wnc}@!y^`zp*A1U<4nAZg@WuwDelD(B=52 z);O;-x0>-gF*3Cz{A=usS*Pt-PPIeMSI~T^A#+y|HIT*07d z*M0xr+;8q>cBokvW`XB--t(N$`rw#EJ%h5L{5c1)*^knIj${+a4?EnC4xqt4GWW;K zd}QM*^Sw>9v1=7zN){;401$=?gk)TAb4*fA%29MY3&YuFu|suvT@buUnWaEqx_k?j z`(ff{$*b%&)EJN-Gn)xg#!|-5$S04;%g($|_R02{>!0DjwVoK%ybYJcc!j!onde@3 zxtz#-C0h3K?x{SD^_yfoLXjrK(!c{QzIUTGLm2-9R6U(E41GSy z?;TEgK4SdeKM3L<5aF9Or-H~~SF+RpL8jKgY_=^f67fzFPAMu2zio2kwCdZG2fznq`8O|(o3)00r$S4ls9=wg$htsB#N-YNt3VY!pXrnH!H`-5l=kvvbD?ThfW0S@%+%A<6Cg9H<_?|t z0hs|(vD#3ZLNv7gdVmnV&2-~5_<&p2D z4DU(H%El4#?5>>!4Xxo`OA~6#!>MYRBoEt#MdaRp9d%SJ1O0Qiw9Fb!`nidT8hUz} zIXQpyoEA1?wq06BEQsIQ;-)%HZcZWod0(LglqG-|2U-@@uRMZ+4;scrLf_V7r71X9 z0_wsAtE7djBkAesJ(&9bVT+0~WBVPmf(l?&%zhrpB9HdY27(v=K`$`AX=`8t>R5KW zy?=ly-e>pec2zDbXu;?ME7nI7F4+pQ_Ys*%Qnsn=S_cSHc)^us&hFITRe^9sToFl~ zNst$kZYdrveHfNRmE=Xs%*KsFQx4r06Tyulip+l=Njw^spDMB)s<-%bJ9}C~;K2V6 zv7^zV=_;FLyD9d-aaH(T8x-n^Bxes={l3DrQOu#py9(H?nO^vd-Q{*Jc@M9I2q=I3;z=(@dtA}~}ppkEb z%jxDO5M;f+fGz#i+1c6E6)CSxLi&OUhf{v9XxADD9rN#ke(?`_c?k-FmY^yO0x;UN zF=3KZUsu;t{tX*#h{V^KzD!ePe6}0~>&c}?PWoK@UQ}yWFJ`EHW;8M5rWOC8^Tg3YR(xs+qo|KJgz}fmH z9lIjfW(70FA4>S1Y^$eCsP@3)FFYb&Q!T&Kzm+UYlF)25uf{(x87`|DCRB*-XAGT; zw1S`TwWq|Ppx!B4yH=peW+LDzm5`#p6V4$TEC|2gSFT7Yo_<54;vyHrEPw-MG2qpK zP)_lx&q{RPxf?byYS(xq^L9P@ zqWxC~$Dw_y&&X|IYx=u_Zq;ZUkkAVNxev$ube6Y^fZpWw;j_&vyv>#dCf>3O3gOx3 zoQsYtp~hF19tD6cyeF!yAHRtqY?q67c%kzC1mwkUH`vy*p3e?nCW{ve(b)Wf@P?ur znzkH3b<#Fj(VZU@G9Pb^L$xVTOD_~!@=hA=OBN!90w^^K7(^EA01wUJkI-{<`P?Xy zt}uCT>BKB{HT-V!;W?&QN8sEf`VbezOZ2U6?%a(eyq^JZf&JoclqARJeGhFtQ@TA_%CY&I=OjUvFI}t`Ggvqaf@LVmJ~x?K3b=M1q&X$kW-Ot{p){K*Qy7fH8yf0U z+>vtJ;fR$6i7A3dMdTO#Lf^`?m@CX~mzS48zW-zBvb*Pe@mgtujg^&EID>7Ie)K@m zoUOZ{p}oDmp`oFMMxs#-1-FH~gM$P3%-&2&hVox58d@9%#jmP(@x*kW1Sw=`>|0g< z4L)EtGBQ$8Q!@eHjE;h=)rqmO89*i6PH*zJcSKXl%gV~q+=D`sYhG?dOs;i0R8j__ zAL9M2fu#X!dL`=t}GBxy8iR58OcXb@Is7|KR1Tf5$J^udkf)yx^Ks6DNIYopbt2q{8Wd=Iw7e zIXST>jBVrBq!&=_dirzroTwSY)cMMH*T6k9cz;HS%Xj+??iVj&4_VJr^*a|Kmj?vH)>s$OTS zjG4O2+EE;$8rgaeJS{F=akH5 zoxT(rO4l#kv)l9O(ZX{>a_?r_&Fh10s6QU?3vtaOgp|JJD@wCyPo?D{vm8|V<@u4< z$o}U=g@hIQc8Pgw-`QUSGp)j|`jm1O2Kp4NSiOg+&4;Ph{&F`~F(fklDi!w%oZ{3Q zMz2QrPZ^j>C4Vduh`5*vu|Hyp1{VH&!fy<_g+X|@2X-xpS!M`cUTDO; z!!xcMfzYrI!8QKR54WdcCOv^cw1n4SCZCaRAG{^p&`@XLSsWS~T3DDE66@jM92TRb zP6`4&}{KX(wBMt~_8TAebS z1f4fYnLPM6I)esNI4pDb0Ct=@ZA1j73%?n<+|MngQcj()GmAIzLy5><5z+-oQM|U* z(#1G-Ty+rmF*^Rh5|?ECLWV8Hod?ED?T^#c+H7Vsl-lNv^LWLiS=B6T42Rhf>ANP; zqUwGf8b7M%_WqDz{%Ey&cX^_=!-Kz1Opk4u+COPvFOQyukKkZ%wJT=A{3NhcN ztnvOT5b0NGR>UV&G*L7CvUDYMla=R>lr}}usm9wxSi~w;B>G}Sur;UBzumg{rL@v= z{0kU~jcZ}e`2p-<9tooX@*&`g;;#s9A^xu7@2V*;Hy7sGF$u2PNgmuICMq&stQ{s} zsRk!LI7$dCJ|y-L_&2LuAMiE7KGc6RQ5|EmS>kj5bTS*f4vq2HJzt2(5ky=HTsjW? z*p0U&+`X4JlUQgLq@d&LbN_PiXONhBQ!n>Px}9RMxZT%$X_kGL#gSUm>+jQW$e!LJhuR@{SM99 ze7tbdPbct=n`YGnn82#*P~o$_j92@qe6($wx;=Fyluah!F0kug`W8L^)MRQ6LvpV8 z^_07JbbI8EWG>fcWAbHVzR&I9Z$*C85C8CybF>s9kWRB%OXvGtxkN+JjaWB6NRpeB zZeTt_oNBKZyIGfzYMbZYKrkC`v;Z+Y^Z^l}(N5-6aR2cd_<7XUyC$v=X4-FEJH4;} zEj8#&l&AQhlUg_wi{h%V3&q(IS$jLg6*2vQpeqo-FSCfQtSpu?e$;NdaN z{nz_f-S)GFh6d;&Wlm)Vu~jt-|LL$77ObtU(}Cw_ex4r4Dk@}7oXc}hnNvqW;S12) zfjGb)KYobK>3FP3hSOndq;UQ)I_Afa6%=0HF$|SVOiR-?Hhx`{2QhxYu?cvP zveMG$3Y5HygLiybQf9CI7e=>t(7q(0yi&E+Vr9a)g&Y`#cKVq5FX$^+5IttTe5u2P~_mc?~1=a-~br*zsT5*6;z>OOT zU5PUjE?wabSgoZWV(FD2a|KK6%G=_iUxXPJJKLnHYT*S}{8cdhNL>j1{qo9`P`oI% z|B|OphJs0S?e~&*^Tc^J)DPeK;7*HF`%#v*WrBz=SXMwor>M0Up*S6EY{zhTB7UT^ zE~^C1oV(rsHHq=kl7KIow83!E9)N4<^rD)fz@o1$5(CM9pQ8qon4+-_us;0xvkPS6 z8$$#E|H5?o8PlK>Ds>Sen9D=F37|AjsFTvV5Y(CYl1Up37RT6q+fedlWy@6EusISM z8{>pa^trX0=2d5PBau;z9Q($qJuBcjnm1&$J7%NObuZ#Ez6p?;Nb~R2KU0_-JRE?=i|fu z-TmVO;@$l{G}lKH@!Fc2?f~)Z15rjsett$)aO32Jb6et(tdI!h3k&1^DcMJaY6X`~ z-dol{t-HBtAQ-G-UE7yQ>5x2RjU0mID_YCbKogSl1}mK=MP8sbhe7TR%H$jmQiyu}4&O|Uwo3T{;Ev*?=z-On3J9)oLa$eLiJ-oaZ z308&+X-s0vqbv7#@^gP4(E>jWeGkUJomRoD)7But9=L*l1t@mI z5-CD3{wVU-^HycupL3Pc8X>>%zN(T{jj;I`I-q5Ou8iN!8q(F&jvJ`HgfrRj#!(_GAz6-V6 z7}|5vo97jTXUAawW(l#JXN+xU$G8$h;Rl>af58F{5?cnNr*|n<`T`Cfz315`o4Z^7 zfcchyf;u>Z$pwD_7&eeAmkY5lcw z0Oh4H26HO9A#6sf!D2dGt{)SvV%n^ahKLgIsp`7&yRE-dA9Et)rLGdvol6xn<=B% zer@uNB8v6@*KVl&S$OmPCox*ZrU@K4)0Pz$78W}@J5YQ=M=(A%W+#TNTanV=A7N*^ zq1R9{1FASWde0J$KhP)ZRcoW&mo6OPA%~7w{AW`6{{8pxFd>(j^!xXzfEbR!;muTz zjg19*I>0d8qQLszjsJwiCWuN3+r%Ykzi>XN+m7L4SC^N29>dly*#kv1km%iNR<8OW zJGQi!m0A7D-~v+}PC}R#J2o!vdv!Iqud`q-dU$Zs4A7vT<}L<2oPa$by5^*S(v?56 z#(%=-39OV)T}tmirV~88#sRssJjjHlyB)(maq%mjT3qU0H`Q)G6-_1Dmn~YQAk4Es z*!`7BfRC^&PiS$Ap1iGX-<%;uTy$?h6c2mZ%AG(nk_@ZGtR4kd$)`{O7fkm<>ziG1 zDFh}6?G0%~N;a+wj*QZKm*}Yy*P$w&dN(@rh&FV@36f=Es|B%!lUPT&xq-MTvN;DIvV3V#H}8LHDioR++0 z4)JOeM)15@_pl=f3hLUOA4i1EJssRl=y5}!AF?UcouQGSWW{ z!O_Mn9plD2IR7YE^+AEqQW2hYbMy{NQk7rrXQ+%lSNw=I55F>TG!{NNF)2PNAvP}N z@hQQ^9xU>Xgc={?2m;@|2jOxJn6(ok3+?X+!E3}AQ2-)VzQ)GAP?5pA&Gsep&iixPk5?aa+(V^AVf0pxBVh`UlMkpED~45HTkwKPP7hu|#ig zp=qyaS!gUoH~>(a;CMR`uro6(3U3I$WUXDu}Tvj^%Mc6O!ep65p*3l zD?TIssB%A$sBe6Gh*%lmuzS)qtG%lFmYD1g{j9x3d(^5ch))HUd1@2h(=2NcXt;k! zf8Rinp~XhC1J(&9jQ5c$2wvYbMQ9OO$W?%E#mHCYb{VlUp6}AbC{XnoCMA`{qb@33 zRUueRCDlKT*#L*ZNX5|S(--%OW0i_V!-_(mB*|NT-#Ec%j8@58dNk3rG($+!q?(l=WB2)xf&7Un{>R zcQ+1{Z%yJvEY6NXEs^4N-ZtyC#;hHjwf zoIQ4>tWk!gdJ4Hg!;x2>t6IHuqZhjXFV;i@{UK1yMWz#MFILKJ*8KraDD^LsZ?&lb zc=rYj2(=6Undd+Mh&-?UXV7LU(__gX!_r5H>_+fcsO`A+zE;Hc=vVWzC<*!ro@rWJ zy?p#`1L{f*4OctK_SMeaoJj-Z^{>i>{P6#CzEo&2E7~v4&ZZV&7-dQr zw}l(xE|?2uCfET2t@8Wrg<_AlV>=i1_4NSThJ}TJh645_rSzeh9Z5oMB$}|OPU|;) zgTjyvj!@~L7@|v1r&6fC4Zh+0eB0_jc8ue-P{t^HP|~unz(7k&`Q{>lpw+16Ys?KU zhJ((F2hEhv-c7!LI}i5U(KT6*v9GUhI=2-wZgC$faI3VhuIatR7TN6ijabybX3Njo zHhHjjNMV+YdHpc{tQnqp(Dk_epY)C5nc(=J^%ECtgVi`X>YKvjY16_@UgGFplkjj? zLR3{x{&1q-=GEemct_-r%I3aY04FBM{N{>)Irl zTnp}?KmsZirudn%Mk3{4ZOo37a~0O;P{_0PGYP}><>mFY69v$)zd&~dNxZz2;QS|_ zqom~LWK7`RLJWsPKnx8FnGBremvxry1H6+EuFE0w)vD8ESF#aH)_>Zm zZq8srO~ea2O&*OZsfs@JRLL5MG;s_!H6(14nXc!mnGpv+xqv(?8ZQoJ)@AUh?VXr} z_OY3U-@gy47>k~yyu{GmH&X?4`Mn$*k|f4(%u`eXx&}$~%Vm>Tkk&5~1fMcU>1kL) z1`5twSu<0@KhjMh(Dqi0s1C`dBzCw5{Ts*IfUF1LX^}VxoYeV}?AM*2*0_?XG;ttq5s0hfVfRH$O|!E;ZaTY> zj*OQ@(x(>qS|rK7EK#>8gW@)a>SrDHJ+qMF*CfY$^LYbNn@XHe1Ho?R-83PI8w3 ztNYxqh{wV^Uc2<=*-oOkic~t3Qx4}s7c?19P2p1I1^>BMFbP8j{V}SS`h0ytedmvC zwrGnic)55HU5BtKk97~`nRA%`RC?$))u9_IcKGX7QaMFXeU9+=Z1dM8PRlD-ikcg2 z*Yex_r%qxD;M!jrkj0P3ls zYQ014$d~h*8NVtY1adQkmz)0vY4jq|Ux|j$UUvwRiBv!Xhi)}K1_^zxAYPt;rhz); z+!4h_Wf^mWre;18nLil7gqN=|3FXT4G;fM(YZI8&TJ)=P-F4zWHJ+$(5yyhykKEYH zS!BUnb`Fl3y1K+7tJLlEDGQhkAvTqVr%UlyA+LJ=w|Mh5xPeLtp;mG)@qp2 zJ`m*2^CDgI5HuS=TT8#KW$dmczVv|7zo3wN?e|SVW0G- znBpS}h^eBX*{XYA1OP73t^weC^5xItiD9+2W`GQ+sV)2-E7mz&!T#^d7Z}Cx=%Vr^ zd&lnYz_|Tf_K^Rhqi?-T9ajbT6^Hg_WBP}NKEGfMaDD@IG_G&hql);lt9h_vqoV^#O|cPKDiirU$Y z;BuxU3Mu8dLsW^1nB*0U>-NFFwFq@iZz1w%UtcSwMA9)`yh+fp{6-`~`4v0cj-r<^ z6DvW%kN&^v^d+`oJLaXS{fi_0N;L=gY;s-v;wz6TA0o#QNkT4xDl#iLmRxB&Wurn$ zLoNmqtGiO9gomEXoJO3%jP4Z8t}<<>iDo0n=sk@V{jYm^yiu%+S{Ckd2m70}8C(=n7#H&=;hv`i(Qr=}B z^3UE$zh+N4#Y=ykutPo|YnA?do6><>lCG$osQQEvXli^-USOCt&=Xms2ZBcSTF(xo z8bJTZb>_XUedYYIR*^ST5w^UgFncrw`5-D9G79n=bZ|RExw=I;yFMp5-cjjQ$H15f zf(1(rsK1l`B_ds9VGzbfz?@N@V_J~klk~k#CH6O`7!npc@zjLU6RO8nh^mn!> zRAg_GQ*qTRTS2_MK5sj)L! zX7%gzS+px=EKihk>dHfz&^$GZ=YZ~vG|A0QS z{1eNLCdrp+yEbq|j$rn);u9~j%7&pUfq{#|yg0DO7vT*dQzf|2Mb3nhqf29y`J$AZ z898P^P|^xO-_8etny#8klGB(WV|x^f9xHki9-Q;c$U6{p zqWbN|{oMoc5Bu3@%~>Ug)@eWEx>Bki>K8KH({{`JHcOUYcZ$i5)d~$$C2Mf(!)IjZ zjt#j@bNHT-a4#-cIKiYS{=4&NW|tetkxx7@6aaMDV>yEUTI z%O1&0*1TovyC1(4oe1xSp1hx~3&fZ({~FMX?!SM&EH@K)gCjdZL;igDbuma&Q|$$M zyL^HiN$?7dpBhnB#dB+Rd*US&BrUGgiJ8tw6GUjmig3G*{rpqUFA^q{+)KE-B=2qOw?atZVt^fE1YZ)mYBqZLsM;oD#FFh z?!oWC^hQHNjl&5eUT;6j)ioQse7~_G`KvOyf=tbrh8t<5(Z!6-6ULUvMkS&n4DIMn zZRypdcGxX4g2N47-?!JRy@=OeFnS{+-~KuNu6+M%S-)9(tWz5G*%&wS@cLnQcUP>% znVgJ3G~cOZWo3C8(7Hfd@t%1uzZ|a<6EsnaciRDi&3TaKbwm(~u@-W9Z*m6f%&w)W-A7pykk^f76{84zim zmzM`t>!1m7YGVh&6GuL=8IgIehq_*hx;_vS(l~`<;2)#T$jZ*{XlDoV>B`j^r5!8z zvccTV8rnK=16J?0urP%1r~9b?E@VJ`(bUocXlj&D$z0XFZ>3~%Md@Po?-q>ZC;^-C z;lqdQoSb9IeFOFdVC438${ybprb{0KQCJAUrdO$Y8X8k8D?<9-A2|uXZ(;v+X$9el z?CIIcWmt&HtoZR=b_X=}MR(bGBr4L|aZnMTmomSS6?_6Ym9*YFYX6xT>b=`Q*7HE*(DJn&&M?ou0eM55>L6g93*`tv^|h& zVI?YF1j&q;&=6mrE;RE^xaeO%7f8F1=t@?$Nq)mR+?Im-HTkcbViJ40)mUlk$QK3_ z2s!^5;(U8Oe#$SOF6(mvWMvZT4yQcNY2h7MoSR4@AK#3eV#Yvt8=QAbu%ikL16C{nY$+*AjC-<*b8kQ^4-&vVcCT zYv}i~<({Z1jzg6l$AO;I?5&2(TMKP0$FT$(<-nTr5Cu1SHu@xda%?QXejIJ>ZJk7? z6v_`qPNHIegBFCfEYzfj{m3X?02QK|6F6-gW~4#+t3NV1(A({zgzA8ixhlLy^Q#I8 z`*#W#N||z8I!84`gwh!@FBN$mL34WX`iKnl1Es>@Sy+oT8ixu3*1=ntOw~NbS)_hJ zFP}&18Hk1X;n5ySha&V1+SM(_8`KL7WQ2QF35njo9Fa))S2J-gBT-I8rb+W zRKYWS&2}NfGA#5jQTPV+F?LHd|1~C8Aind#sHeDH;PW3Ey~Z!LPy@5l-f_6)(h7XW z8N-|O&Ogr2&nZ2_IiRd*rdbKnlA9bZ)&|7sykB{~eO*VEV>;o;IXiyo@!N@C>{6>G zs~PR>p>v;YK5ZGi8wL>J5NY#|n^;&t-Dc()BaLiL^7bccwwt5ql0F@U zee$}X{GXQW%U|u325*+^MDJL)<{$fE$0`mHiX#uXG;*~oXH?ynDjbF8910N%zIoQA z8f2-mt1;-Tj94CQJ9iLvt(7m@B&}ELIL%l5o2mN8vw6F6kFj(YuX`V_dl#RjrbC=&*eY; zA*QcT-QkO@08?+KPs&6pqiY4djRAU`}||7*9o+=MBI z>WN&}rY@%FD z0xTR7Vj?_Ja&k=EZ34`VldYqJ9g(q_vDH=c!I(@(ot4{(u-s-B~weOj&#~wH6{@Sy)vTAN@)UDQT zSTcY>rq>qI=jP~iYoR*u5y(XhoI_<_W20dGCpbZ7-QSCkUU6x? znTUN<&K3FNR%(9BKMH!d`r_}A6Ur5BsiD1_h6P2Ca*E<`4Wv+G8u&mji}8on5BBL9 z_W3#Z=~?3GcS59viH*7m%*ywo0d!6O zj7H{HkFDboI$viJ6y1&-Z?iC7DH064!{aBG+laFEV-vv027yn+WphS(rPv;t}e8bLPaY?HT zGk88|YpXQ7efe=ejuGL}nQ(VALS!8F&HF5MzBV*L55y$RR*b?SV>n6D+#O$c4M z)-GO13RjDFAvVOZvex|; zF0@9@Vez-!azr}1Ew_HttU)!eAq#K$VhL~LMBx;X#;5bdDJ~=~jbENw37OJJi}bOa zGwduQG?>_(e$ZW8=)W7n#WNm#!~)IE9&c+GR%s55W#76%O5c{`ed9|=rLP}Up35rN z7a87#(Qd`BUs7z=E%#uVGc9TRH5-^o%*nV%lB(pEB_nuZ*69(c(fUX6d-G$p6=(x1Q%+#yX^%26ms3Yee; zj1xbU4QyqMlJV~JW4vAbc-fDkvdBPx9BpxIfN*0dc%vkElTFkw_-q4reb>D&{`fxp zd2zn2k@|BL(&JD=_*NFNjyT)lSBjT7k!Sjb&g(P`e^|oCQuh}nio3i!c%N&{Pn#{l}{GHKBxD(}BxT<7#Z%hvnVr6197S(<+`b|%(0OJS~PL?el9~F%e9Tldd@2fvY;+(%H;9uMOgvkqv92|0*>@rVI z?3=u=%Ho)?-&f6kKBPXH8xDz>^QkTh%p1e^nkDffazmwW@-CW{l)q+ERoP#xs5`b70 z9KdPTO;{^d@Pvam_KJ*hI3Z~_H9-aSJROn?J#e8Z3gr#SFBUgK=0A`NbWs&Cg)YCs zEh#mY{4jmG@iRcY1|b3IC0vu}1p_lRuOXCT?UU_v+A~rWIreo81M#lrK$8}|8}9r4 zz+%Sm{0#Z{*vQy7C@2#0ZfW6rF+@CM+F^{l@N+-avUrK2#DlnTBc!n2komhOXuOdP zk7UA4q&{GrjunhLNL*bLS1^*#>-6V`n*Hy{?)dHv=V6wq?;7UN$fH>ZXf+}lAm9?8Pb}YU1+Vm`@&$MVYnH4vjZ4|Bu z^+|d7;<8gHO?hx7<8raB^(+Rwq(3zIerkXEE>lm|@(Dxa4Jt2201EYS%ZcUpZXNDg zQX4IlvB(tMV8yhmL_8Y{_#QSL?Sh{mWF#|=aSF%MyIvAQE8#srbaHb?+i14#!TPHu z8Z95+J0u|7WR}CzyA(#Y!SlLMq2hlqrP9un_+Z}a)H3Xd*oF3Y++)d*X?nbzP)wK#{xjxchjn6Zi`@xMOpQm+7rmW_Sy3yfivl7yJC9mde zB0uPPKQ0{`pG^(1ou++G_M6l=xPV~WnRG2-^E8RCFBEq>sCRpn-i*X9lVvxqygMY< zty%wJ&{A*wZnE+_i%tqYrWaAYTUEc+M%50d0}`nU12ZueE;cbH?lEu`Z5;swD=_o? zMIG0WABRDO6cTCFUcAqb{fr~lJxJirbJau0^{wvF>E4|qQ)Xcj)`zGodMPGaF|x)d z=rx+>!qYy=jF0b&a$YEko*5qNd-@Ax|nuBVP z->IsKA3Z>;U{qO@GPDIub%TSljopT4AmPUv&g7F(jV^1Rhz}n(cJ4c;Jf6l+dB;(G z_Gw?pmw!7Oj}?q>I>YJYtnI+Pi3AHeqZz9+&ko?2i;If`+r6n0&;F*phdX7F(Zn0x~+XJ^c8gWROK(nnbIx z*T6$ZH?WhAN1Zs#Ra1-u%qmwp);ksE53lUlowIX7ZO(Z^TMDI+P)Vvp`5Ylc%k9## zGQk@gUz1~R6Vk{v)Oa}amUyK!RvCGednF^YHJu_89`L|+#r`akQOmY@9oeM0#(nv2eIQ=jyiC3SulacGHU|} z>nM~L2__A%c%h0Z;|@fWHmC}q(D+di<8*}+gSLhu(j;*o$t;R{TCVO->kO@Ht7`_n z`6<_Kpm$hei5D#m6nGd_Y$-X@ho>hb;Nsws;bRl;Q$Ss$B%~IC@T0Fib{oV|we-}v zP~Pat>I~dlyuZ2jCu3Ei5|@TuaOYQqm`};>l?nPwe#_iO3<`!XV<;$T5Q)yFqf0>c z-4Ef^rZVA;66f9am4hws3b5Dx%G$#pS=BJWBz=YIu07k>&p7KZA!O%}h-%;!>=Kbl zF^*W^(>UpzJzP1jj=#L^!v4Gu=snO6lAG0Wi?_Ur5ta6xO3)h`dz_>H1QY?raSZ6O zdKmah@;QTTnxma%cear`ven?lP+&PL>FU|0}MKuwO%cEp=( z$)-eKSt~s9kQ>s8P`M(1oi!{&UpXYn-k1=~=kk%5vClYD^_v3S{IccerLzy!{ra89 z?41@3svR;Mtt9+u7Zi1_6l$AdY2!L>$vu*^XFyj6&&eABvS8*#=E?lp4yyMA$G#2w>00)IZ=Ye;&7rt$S?E$sDI zj6JC}K7nf*$KJXtM#J~G)SO>wV?nR)(zEmO*5>Bk%APBl$4Ub0wh1gs6FVG>;A2q>p_T zz?Q(1-j~fr7Mw8S&eZ?#!N zPED9N*E9F7Y#%aXFn)I=Rm3;}K?4rHHY8)v-xmZbK)X894ni z)6>%v6F0y0%I0zk8Yxg>E}q=9y6%;MCdhrXAaUo_+v4mU;m70~SJKEAwtVOpbD<`S z5p1|sb~9b|-SD&W%Om9sWq*ksM2(7K?&YzSnThpxKnEpAFAOcoi1b@po|ng1+eohI z3exhe?4Ku4lfQ(di@Er`G9)-Z&wfa}6&=v?7FugfsB|pbP5C13jHYZZC(oOPkA;tq zhYHXhWlmNhcUK8Pc;yEVa$5RhoO_*0WT3cDGvDSeQ7rPiUkIvWX~%T<=`tWO*1P5@7_ z!Y_3EhvDQ81Mg!qbNoqKz$GZYwtnv<99Lfc?{{fi>hp3Cy^2z3eNo`BQhI4wRBTyc zF;gP_Io!E29~+V`b%>l?co;l9+yl^zdwP$%+&ar?&2BOZeoAVPUfF5d^WFxCG~TZ* zwr2ly3icfa_Kr)dJ-z~lgK1k$@esaC>yy}l#Ad)JF3K=by3o0mF}<#wPJ1Gdai$0P zIc;0b#FU$x8=yhEJU`FpA)hj~Q>0atmX-$gPavcWYvOw0Q^t;q7l_rdNiCnVJvsiz zPE3khtxKib{LQlWi{stQ`uh6nsv+1QfipI@;eFH!C3Yk(a;Q8lD17y3_k%Me5@|Q8 zak8=5KRg5*Gdo8|*)Hf}9X4F#hWdISVtaUe1d~-xDrQQFTm-?u59>0}OU9EXTP7xN z<8Wx$q8{`s+CcyxDy%hUq^<37-ylzkNy+8z;Bd14-8oYF6KPF(IY7tK&S4XKRdcrK zT7H03eb#t+R0E!5VaW_O>_}OI#{Yg4IO%5>rquE&8`3&u-p;X=rC6|yNFoiAR-xAf zBV9>p?9KgGC0bif!pT(&xBCtyT9Ave209%L421tGk&wry1E<}sn9d90jWZaoA}=$q z>&wx-y#sGP3iOosNn@wV3yl^f_G4g8o4y;NDqa7T$s=L~ooXyjdG;klo)-a6w5n0q zE{d^T95_Rp(A1;nu|A7XFTOCJfJ4sdE8H>s=MMaa9fg-7cj*se?={qR2ymKt>jpu| zk2qac1}+X64mmNxm(S|`n$FIi&g#1I@}4&G(l!w|Y-sU?(lShC|CZA((AxPiI`Fzq z^L4pTFjH(_tor?fZ6|9skHkz%p9s`hyr)sAlj304)o@ubw)5qnn9+pcj3nlshOCZh zaC!vAr}&Q9qhQkgNt%h^CDv>V5ss}R6rr`=n&zW^tAdli;uSBlqu9du!xtmHx3R00 z2pJ+!AYxVZm4qm}*?T&_(TaTVgofjRl{TcI_0AQ(qNeBBl&s*`F6ooUeHx@UseKcW z5rclNk)DIw0|}Jwok(zY_ryF@WKi>vSLDb@`)TGIK0G_p=yu47ox5|iheNncflsa+ z9j#n6ba5A1l2iQ-d768`br(C<;UZ{YwoT|VUeda5>+j#T9e?*DzzK`i}W!GkJ!7fWF)zVALpFA&*s!msi7&cwY z1u66k%Pb152UjB1`(GN&dqk-xOi=?wQL#(?I4E8firH(W2r@jhg;7p#N=-CCoQqo@jtSvc(8zfS3Pu_wp@Fp%Ei5 za)@A}IL9u@fN!z1O)ApK5B}7^Ub7JX*d&X@BxS`cw)F9|v5TF0Upi4aG>wWl#u=O) z@1mbjQRh|eJuQt!a`ROqR%mmTh0E?*4BI7SV8p7j$rnComcv(Uo3Q{2_FFAB<=+wI zZ=5()iB1(N9^on-1MJJTc$5_6PUs@8X&LOjUFmnCrTK0oLtE)?1UO7tA)9b?su}z9@#|h;$ zX@<1eAafUh&g+{S;M_9I%QdX4VT`i1vH1}Q&dzc2{ZmJmqod0{KAMjYKT=aG=;*-c z0sVo%ywKU%393}VhX5afm=lnp!yeoD3#gvRWi)J?vL^P5P4dT-V_rh~OF+mC@F{?= z0cdh{brsY?(P+nRdAhs5O{xcZI0iG?g?M#KX5LzKuJih`CSp7zZoydAa1vVD+D16o zGNG^Ft94Q$Dzz%XxgUrduzC6Xh>1F9F^Kp%MRwth0=Yx(&NM-7O&?9RkuI z-Q8UxAt8-)H%JWKpfpH#Hz?gWbc1wDm&CcB_r#auV!8Y<&MZZ*{}p@x_E!n2xIr3u zjXbqz5id_6BMXaNOn;3}ynHW{qA$Mv)26<`FG|?a16jIpAPx3>pG%282}qaIP-f}= z6Ymy4wr7t8!8@Rs_7O;^YXNLMARVLF9B?`r(c%F)0)VSUuc4=fUJf1f7E=DF&={v` zKerx8*vDM+akyASMn(?*5rE^szoq`;z=h$TOu-bD{vnUwz!))ky^ybOCp_GfghU7q z-j1WVP^|uBb1~#H@~ljzY>N;OvjfB$KtnVy0(|ilHzNnAaVM%RmsFHlwkM=A`K8qF z9T&_&EkT7qaUe+d|9}%KX!kGC{vHty4oQeJ(0C1>*RW|z$mAviIt zHw}gy(|?fUj+G(xmLF|vH?EhK4rdx++0s#Z{iilekr~1$a?mx~OPKwO)sissrj7{h zp}zFYjavVEErlvA2Lg4QDm4kq8nF%yb1gkJN0_o%w_8VK{&^xAsL6Bi;U6|^Bi1Kf z-8Sf-3uD>BCq#b%B^4?bGMOUwP5-+X7Y>oJ7K+sG63%EP2h#m_3{9jvg31{p|ne(yt;GXYy&UJH< z7eAP7vhEaT{!61SPus{q#e7ErlOC4Q5?x9jgFc3k2olebmcu}&hlV+s$TY$>@Qy0i z*q79QzBhRA_HD-vvHJz~F?iYu8po*!Q<`K=O+Dk#`<3E!Sr@tQ9`H=gS04X%pPc4- zUs}G$h!zzQZC46qo%`-o_={PKK5F>Qx3csZZM86+P&fZb8@HmzAiIP5#bXcN&@3Mk z!Fs=oqmKpd_8Tj$IK~T14rQrCx(STm@UrCPh8Bgysk45`MOeNaa7lQ97giTj#b-Y- zrI+k6Rrscan#B0I)(I-!_Q|#QpaPmF8_dF-4!pI8&xhPl@KDf2sKT6PvFFG>;LZRfOZwFguRJ0?-7vxd{;%cgLx&QBLG zRkJPa4CF9B7btF=^Jy@S+F9sm)i|{F*LXU~1_a31zT@IetJG*!D(pTT2PhleZRPo9 z$89RqEV9LUtitjz=PPyeYoSs7L#1?&_#+V`MyS z27K_Ffjc7YFJYb~+LD{OcLWOP6ZiH@NYCCSuBOLY`S!LsIBf-xoRkgkI9C%uNMZ&=aUmD? zk6@Lsva*7koRnVz9aaI%d2spyeK;WQu+$DX39+$F?l=Rz)mFvp=^!UsflVW!=bP`| zpFq-VuqIP07kL)5H_%G`ETh)2=ShAb1>NG&j@!a#xp9Z>S#$Tf6eQ9}Eh@jOJB zeIHKFc)LNrw?TXiC3+PeZzZa2B)dcKr%5Zppr1gI*bY!=eDPfuFoJV`FOM?r4-XDv z^Tc1{Dg2YeFBZ#sB=GDKf5s;t z=D+!#8R4BMDJ;_y5ke76msrs~ym{#hw~6IAWf{5LGBf#LuH4Cw{#Ue<>3|Fl=Bx{i z*GAYztFa;J^vA9)^FOP&7J9=&{;u>Icvt`U9A9RI2)Sfz)u{Xs@s1CUgUtLLl)8sT z0xsmy&$rXkD_Fu1IY68+|5cS@qB}>7)AgyuPA59KK(tTT3-{wciIOLTcrGq257Db5 zQ%`{diCtl#=`c^mk@g%OzoqDJTtGW>d5ejLg%XDXiHS0=+xlwSW-we^9N~;^?(%MU zfQMfqKTf#U{|J6kwHw*#^4~h9&mH5bea2_>G))wU#jYGCJ(Wrw0w}j;rZlFeG`R}g zV8myc%%mR4P}F)qEJ&!P=rH(qwcqbiY-N-}Ra)+9Sl3F~M}C6C@A1}iMOEWh0^Dr& z$M>pLQ>&dnYfM|a0>qYA@~hH|hgkEcoSl5=O@_w?Sn8c@89!&e!@OwI@G>D+la#!g+(Zu~5nzoae3c~^ zl{all+@L4p`zAxi?6+0)ou`VgkRVl1Mly;eI5w9Em7% zK)#f0a)~&HKO_~VL`zx6X2=HfLjjd7hE{#H-Bgk?QrWDW+v^e)_*v^8-s3ZHT<gLz7saCp`IoUr}QsC^?y>zCx>V|cw+Tp^do z@(0!BeIL6kVfqJhbicT;n?!*_0>f=_#}D^pumWEw7ez3u1UJxqN#K67<+k_Vp0&s1 z{5gsP9qK;HqXW%N2&`cB-M#(&t;3M0zry+4)5w#DExBQ3w{40^zk;7}cT+2(8gzx4 z`hAq#c;fdYY5f8%R=midK0XmD0Zt|iRO!wRVM{M>AQmW{E)uY9X6uqMFf=8KBbCjc zze0U4a_)(}Vkd{6GRXypoWAz%+d0vN|KOGSW`OA*JXFPM-pQw(qQj>mWh2_;kl-xUOF zy9%tLusVH{WX3@OcOlTFf-EBt8x5!lK-FYoLX{s57nEC3fnl#_XqYuxwld0`Il9C7 zYKnMGk@y)s9dbjumuJ9ALHWha0ydn^pD5Tv#!*9y zHD;usSS3SX)n4E#I1^Dj|M@pM9<@5`?;UH5;AACv*g!R{7fzdNi^a}%J|Ar4PB+4T z8@$Imam6AnaZX1%=Pc!r0oJmTV5P|v{Y2^HM4ChlDs|cWvf{KoX6(ri^>4;UUr7mh zg@z&)Z!4fP4KI31c(vU{d$UujlZO13$ zArO9X68v(`uc6&pQRM!IW|Cu0^p|mi{G2Pg_MFmAD&CC}L}4;5L5wyXT%bsah;fNY z@ZW5lvAR-1hm*w1ru3+wQC>0S9=&f|?{1|rhB&6=ebIObVktgEi&nhL;`W-dqCKR5 zF(9HYh`+Y%kQ>QOHi%MA=9T?V?c}aLI)|6h4Dk?A4cMb;u6_yib0h@*pym6c(;j3( zO}Ft2emW_eB0WnSIVVaEq(uXcKVY|tD$nu8C^*@?^zBa$s{gA6z=ZqQ#@8KPVwcbi zD;Bq2AJTjjQ!+0)DDp_=bH5!uc=ML~BoTd`lWU@6%m3Bzgs?byyYc-a(khJy$=@Xu zKK+-#raEoSxe}%djS1FitG!fp;@OJ|Brl_IYTGVquNWaWu5ZsZ+T-+!w!Pm(I#j{J;)#VaBLoBI-R_Id+^dqhR#QuVG3 zm9zj+^L~0?dV1f&Yj3+_9QML~&P}TdK9YAF*@~+8v~(BX>x&3btWGOR<{rIDHxO3nkuBHPC1?YNcBYi4*&a(2Yy>-=P(o z`o333^HbaliYU%gcoblHZ8fE7?_D+yQSsZK^^eLYusUE<=( z*oWrWc7I`?duJV0>{0W!a~Ag^Y2GgGJ-TQ{Jn4mBUT)x)ZPR%3GpDCVA}#LE#I&)^ zYbxk&Ho3gzTgz*k(=g27i;Ic-%Z!W+)L^mf6mXgcl2ak_xXHcAZ(M`KkbLR~Fib;# z?Xb=>B*@_;>Xgr>%}c~)lR<^?g>%xE zpqLmh;$eF>G7?KUpEsi7t*osNtg0uW?E^c`ppE2u1V%@Cl>Cm4H}X=3tdyc_ygTbjR%+>V-?ZT4^*i}qHN&R;r}`S(A!4RavgZD|b9v8t8#THUTP{`Y+3}o= z3MTUipYywA+ruE~C_;Xew2(;ZRR(Xt@9}UrFz@n;m9jR)^0SR#AV`SFQc__9Q`BmI zxKwJdEvQiLswi!jx1SVCfl}u0;_&LV#Y|p+>ED-#PREtKAWPz-)08n|`S;hL046D; zB<#nly%VA~e~nK~%i*%CUa>@)^z%Vq$lOM=NztRI z$?!=t*i$a}htyt(N|F&zB?t9+p{R<6(_I>;*Qf?r?)PEC{&p3_n#o;|zx;t6C}BT> ztVWDxx)Vd`d+>3gD@5@b9DLL!(MgA5f@1Su*iDQp^kyC|NTG2j+boN;w#E`E%|n+X zC_brD_V^pQeHjzx1wCFHhWl_3m2VjJ233PCXLts?NV0-?6ttXfn|T|q&JXR=i|>#1 z1e|(MXb(9?;Xk{G&xZm@64jAv>v!7*)XS)|5&g1)G<_Fj|Mh}kORT=mf9DO=z$Ej6 z=W|{;#Da~gvle;FnroA>T_1Ip%w0S2Gi@kc=ox1!vQV0K%1nHvBeU{7>IrdT2VO`1 zhqbnN{TA5nzt$6{9zE*-t&>c2#Ju>9DYkzje`YEH|PZY!N_@qhrvStI& z^mC`<9|+`SeZ_CjzCk1e)Y31+=|rsX=p{!?@tEmhna&sSaXl>Dy%lY?wif(=GR3l00*)g17Rdmf1iOD_0BeRqq#EAK_3qL zVE3drR#d^aGlQ=??cq*-^{D#wjfk!9701@<$7ovzE>{-l`&%1Z{n^6zhmZWFAMk`- zxx|>Rze?du65x?+Q*7*=Y$1|KTdL%o^0+Y#p}A114`#XS+sW>AM@3;gnt&bJ^xK)c zzAa%#7ix8^j|$lK$SEBSzF5dowd=H^lncf6Tp$~GaI2P?&_W#6$1xs#k)gg6V$WV9 zk7qu8={XOjG7Fc&g(EHKxrfT(pZGXCJFBXydU)IxIxn!TOTQ7Jn72Coo{>Sw9A9BD ze0XSjaJ|US4_207UkMikGk6XL)a-2X`o(C%&&|t%0s=B>>dF7*-B1%o$(B^h*ok?2 z3rMREsb6vG58=A-uc3wZfPoh1+=1X8$Vd^8LG}(O7ngdC2GI7uFAd~>Bf>Q-hJ6fA znD5jYOR#zeBcBK;SYYP}q(<#+ZGhgzim0vDqNA^`FDp9;25rM&l7_{7+P!m6Jjf4V zjs+#sqMo06BPLRB00yK@=-L4X0=i0ES?G@Pp@y6mbwW#r zYD}yy=s$f$)^~bZ4XPAFptz(w&o=`;K#~+I%Dy6p%}1k--06(LM}EyllFkQ%ttFiBsP^`id&Yb}I1z~D`+*wx@dt`T=L?PdwxHcQ zG}qqe+dJNo-Rd9Taq-3zNGiqXMu^~2C|Iy^sV!*_d3wh&AK~qRhr)@&4)Rk;o^#rz zaW+fqAEyn}V$oiZ-+iwB=Ic{aL~~ehqR=|Lxyxoa`?~`S^Y4~a7}BB5q7pRF9E^n* zQr1@Kx%_qU4CrP2H-BrSbA@7<*IC|hGov9lYihNR$=HF%`1qIpky53O0}jdyt%CEj zk6VJrC%14-e=QtVs1Nkqaq&`y7k$<7LJ$=?5}fjyO!l7eE>c-T!GJaHwPS+pih$i4eG zJnIg-{hA_cibA+3;6Bj5SEYCAA0|34Nt^Cbed_*6)UbJDmXAt0atUu0Q0=&068 zt`bVF)FiPng@c2&uQvJj2~ZSY-K&|S9i9_I;B*qx;We_w=tNLFOf_rBDSil@^MQisg_Ei16;1!p0g;=G8rq0Dh`bA_#F9dbcLr4e`p>iI~S z_*$DsLpJaqOlZra%`3mz%_POhl=VxwS(Rc5&lVPXH-Kx=sKj_P%=%P+YF=*ftd418 zios{PIX%dG9@8wtCMfGF#`k@Zb}P~!g>ehwBh$U^&js!iDx^omqVkWA zndj|)!((@!(_)rANapO`vv&2e*XXaeiG7^bF_7LR_;bTut3R2BN4XX=5fKBy>>g5| z`Oh#!#dL@hNsZe~18=|Z&7)76A9htb$8&R-wACzbQg98P_apX7rW`(sbW$`1pq{>b zOh-KkP~i9*BkJ^soEjLvpULm?=6ASq;#e@8jxNzqk#R@*>^gScL5xhS(m>|`3VkB& ztj+aK?dtW(RsbRdR3YHAIX(Si&g6~xuYa$e0L|hHYj-UN>(Tg>Ehp&fTvDC3C$WZ=LDct{j&F_ z-f0ff)aoiKD&S>6Z3H;1pkB(#B5&q_(h1&mo|3+O)F*bnfMLo&QJRNMjnK>aGQ1}?YV|b8r2(rhN`TBUTN=9Dxm5~7 z+@Q-hhJMg0qVLJx{?Usjmd)o~-uji(-i-r^^>y{2ghJuLnVSas$McOUP*-on2M(3| zZnOdd+{D{+~tWQBYQ-`^Te<2OaZ z*{c!7pdtL((cZ-SOZLVCQkt{Z(mOX4n40sNx#R%@|JaU+{9gob7Uvg8!zIamGXsvu z?t;b3njj-tiVK{93R)61e2-tH1Q^b-P%$Mwu#(pY+Wv8EKF};uX+?n;iN(-hEgJt} zS@Fc_M}R+itNQIY{x7S7JBJy^H!Wtzt{Q6*(+ny z9RIjZrxnY2bjU|?Jj|*eOWq}sB%JS5ZJHvJZ9Ykjewx}8Gu38b!J<^}VwYE_bG0y0 zNOg55R-cx?uE3^*C5+Kf%RB_37k9c>Vyu5rhkchhX$ z#LrGDFE{_%Sb#ia!B+1w-Q?NA@51n5TbXclHG}r{3&DCox7D&{W~C3mF!KJ>U+J41 z%qjo9;s@H9GZ~Ewa-$_0cN{U%^gJtN9j(0~m+5o!B)#(O(LN+^&2%kz`-gM*XHq#gOYM@N5=HTuQSQBZDfu`h11F)&bIS=ed$Ko~LKo6fK>nXpjl z0^L3(n)n)SJgrT56KhxMl0IY>4kR9ZX5rWYm?aIhFzi5UQ#d6r1(>nqY+8gejkfgu z_&Q*Dc!hjgsFXQMpWwz=(g(Z{zFG0bvX~=^<9K3<_ALx4IE8qdt{REru_O0&HF z`(|4Bs?KCurPm&tRM(CN<4d}*8mfc%&-UI=u+5a)43QJmFct8RogKaw;}@Cy(*OjO zx6hR<8@{j~Z{?bwq_A|*=BmdddjFrM$3?VnAnk_tZ_ub&aP3{d^~(?^{~Iddruc(S zJn62-IJ;RrhXE^KWOwF=gZ)@)UR2CAI-&;;zw*)HGn?Meic%B0xAj>g0@W?{wDKev zNXS%en^(G`zd*GETAEM^bt9uSplV!L*dJqMt>2-P88$WHdGDlCfx~R5zqYYf&g}J3?6H+l4S5;1_r0=f~<$%#}@U(+6nJcMr>iz zVpFg&Bc$@j#>T)r420wr70k%_Cx?e46BF+7R|)ko-jgPZ`*|!Fle1T6GCW5TPG=>k z)s}s;H0nTOlbSjQ1Vsi0zV}?OFWI`|z@H#yfZt`;)x(2`fPg<07<>#9GjZE_ zW2IzWhm@am0BmGk$ADVBeN|*hFKKk=IVNF$zt4*`ZFKA0fCSyKbp;%NG9I`eR8Jnk zUv7pdX7u@Kt3>`j|C&0kU&8Od8glpqBFN#CDHLM))ToAeyCjwQ(L&bp?-v)O$Bo4+ zyHzjtqaeVNEaFY>v-i$!GVgcgWR0$U@->FW`^pRcLMi7qDO;Qke8&Z){E**!XAwAB zjRK=CbKqW3)UJ$tPOn+~RTe4gvy#HN_K-4Dhn(tMMrqK67eP6BqTOOn%@Ib^kqZV% z;B%y%SYGXhhg#2l3aTLTG7&rDGtDO{6h6ji$8%AHEdwlguhMmsKt6GWDS17$7YM54 z*cJ1S!u4NpkLw%n%F-zGiCoE^2EO{uYPMf28`mV|n6kb3Veg|=^95d{Cf>#>b#Ef! zn`WN^nKA9>8ou*$2o%Zz6M2t(=l#zU^8=yEe?Hx0`J}g)@=|1jzaaIGDM)NG`Eqoi z7sVuoK0MqbAl-+DB2RBpC%w*{$kK9dpci*8qNRuw5KPl}$2&~EI_`bl34_lYaAx&0 zc5ff7^^kQF$H^{QQ(zz@VEvp(lggRS90;=Hdjl=L5xm8r`{UdMrB|9vnkc0#U*29F zE&cqFmeix(gZx(H4jyci>~4Kvf$o%eLE_-c3G~ayinUgm%L~?A?5B&0^W*BJ;;tzn ze}(1~!_~4Ul4W%Le@2yls#skGndf7y4_$uplVs8UC!QOp(_J1}*KZzse9j7fxADF@ znRL>mNG)=poz_`wG-QkvDEF-j8si*R($7oWR``kmq6$>OQym2p3n?3weE|7kXX4`G z3gJtuQ4O%ld;8o6&i~mxLJ#iu^?RbC!j#CISr=shoNa)wVqnLA&%hj-a`)>`US0wf zRYG2#x`_!?O#o*05RxG_VEZAu&SZ)@? zlso3Iul?~77LhJ`xvz5uQ)#9(V0BqGkG|IYGW9J;cSyd7Y56S^aa>b~ldna|8G4~1 z@m*Q2UVcMQKerD(unC`S4sYjYb20;Xme#!PmQkHM2x@BhCD$aTg%(%}Ib?@Fni45t zA>$q;I&2qcP+Yz~dT_mEn?CIz-S=Jhp-=-4@L4jEa=(Z4FY~yolE_yXIp2L`|MfIV z*-~ihO9CNiC1dZfF8dGk)lfM25MSR%A>mH2t65pG$aVOvhWM1ssEJET=GBO0oFhjO zsq}3yVgGeNQ4HJj-#K_*7Cc0Tcowrh{E!Wzb#cJq7|$hegGhyEm)!XVUN-1ksN?=i z{mAz}dYcccs}=k%e0&p~kv712s7yb-1DU!O?xdn!T3hocP8&G-$oc)JK(ZB zv2VS-naf&PTU%RJcBs*}$Ps103h4flxJnb2G!G)5`kb7`c3uN3cWl*biVgiroxN%{ zP~XaDz3Zve)6Nx8AOc;%jv_wbc9OXsiyfzq9Zdu6UJiJ9ssHCNGP z{6E;jGK}`37{M6bv9&2?h5infk9b%pvS2*Jl!{6gkK5AKfe`HPr_w85+cv%GYRm(xY6E^^U+PrkXh_HqUi_!9XonFaMInss!DJLdL8IBu-V)LxEkTeE;-;s5_h zUhsKU!Sxn{9v1cZL()EmJ~IoRb?S#q&xEfk41C^E>@>#uTGA7?X}1-$x-0J%JHlHp zTW*iKP1*cn>;u>~s*3q-PZMaXOQ5TBwhP{ACW9(Jp=ekSiC67jpIVz0DtGranQns)`pV3#fQGt962yP{`gI5kTekYNNY)#8cz9s{ z$I6-QHA@X2WKL$;Lb%?9R6_F|IM&t zv^eK|=5nv)sV%i4l@#yoT5(eUptssksj_TaOaG^{AwpF$1=8_`k+1H0kQ|8!4LPU7 znkH^Vs!`1$=R9j`T=OCqEh&z&zIllw4dD;iB(tA>=(`ShD@&FZ73eoN7G_!!tAE^kyp#QXN2CbWrVVe|@oeFL8ue%h!9W3`C7PX+ zBU<+ee0`DqZ$g7Vb8=i>!eW4Tc+dWGY}D-4S3T-dAkwk67N6=VDx#M)Z3nO<8yhA7 zi4%_ps%@}AL%}U#hXDfs=%|c#xvRW``hJD8O2DR#Y5wYDV^N z0us{1#Khv8zfQofvuD`tIuf^Ln9;3 zU6}^dP~6h1Sii1hg_%$6ElL_BUVFjlQ%BdjE^`7php)xf4-E>__8SQ&jBV0FCH_P# z(=BB?v8fL_5&x%b@ea8?&G5ZBlF4V_@NHXm{VLVj(fJ7Pn?Pi4s(}%nL7BiY>+SE{ z##fEPR!YB&T=L7U?*uy{+c)%P)zv8;#@D=_%AOeT(8nAxsHiPFmMDoz|{t7df1#Ic$l!ar3pIgp{ zkjbk%2wGjReWp7T5ks^z%RBPFkBuaJACqVeroov`dR@z*hCzz6|99(17+r$Hl2!n$ z;b)xKI358#1=bg@7)5+sCsrZVoWO+wR=GYi4lX|e}IU>XriG`l$4K>s%TtUmW zEl|ow7q|SB$YF8NbJKC?s2eVYK`g(WFN$|WNs+`=Q9rtQ&7#Ah+-XqdDYbK{(!rYI zNv(Ygz3~p4;IBu@cDV2HGShF7>i(`p$kQ{{&ENH!06$39lhxEP4YaxAJ710A?^f+4 zXQB_yS_x}~HO&kam)k{)Uj+=Q8gZyw16eGl`71nSOzo7kJoT*9)N;Gyn&+9Z0S2tq^Q$Ml!v$fhp@+3xsr%2E|5pk*wvbvT zKQMuI8v|AG^H6Q_I5oc=Vn%3PHok9_^H3W;g77z5-z2F|si^iEL5Q>>u%V14gT-PT z{ycJCiMtHuUSKSs8rR-*Np9nhOf>lXp{p%VYgyA)uddH?8ELC%d_b0BTC_&@wl8DJ zuekAF_e}R?_~{0(;Cj@0Q+O+&v?MM^6n(Mzf{7TKPhDuSFN04;MnO(UhL0Z^zhCho z8%29E^FYLGV2q0Aa5rq`h^VVKFzx6o>MMHX@6n$7pj`t?m?pn}fO0S_>Ne={vgEx% zFPndc8jS2K9pdxt^ynaOoH@)!iQ?UJJNi6`BFf5|Fv?F`At%R1B9l*3?jggtYKZ$8o-T zZ_Qt@{>Rr!XkY{rt1dI4uC_MNeGp@Wfm9`+sdH`3qbvZ%WFYCoZIcKRQ`6Gg9uqUf z0uQpiy*(NxCOin(zKKz8oOicb{y#2&r*ms2t-R%!b7_cM|2epBs=r?chXari4TY*3 z8#}PSX60fF@3rjP5fhF4sONg3cczAnH$FMpoo~|!ayu$3$4&452cfsT{roKLakDlZ zOZJz}L9uR&cFpPL%Z<_aT7AZ;IC4fRCRy^71bQJlnyVwDeNY{Gvf)5z9qaA$#C?vg z!zRh#L6~Ua98~_Zv^SmK$0qHb} zAdxRS+kZGI$R4ly7)khxEfHR0fXtVT&k1tdI4L5yc#XP=ORS#Mv^Lx%C$pnXCs|!B zY_GPLk!o2UOXX%t74YeE7Xxt31&PxXW^^J&-F^Wk^JR}f*3Sh6i4IZz`Il?EYivwhg9#FhCah^`c zH|ab|1i~W9K1hj|j(n$@rZp1FZ)&kL7Ny`kC4RkEkYD1Y#ghR+^OBNCq^48UQG?97 zms(zb)FALEzHry0j!m=~&xsy#_(->^*%9L^kL|0CSAh54<(NEk~Pjd?4{@~ zj_-_r?~72qa()z2q{picy?&@3T6nlL^SoMjUzHA^$+|1p%82JOA9+kG*b2cf(oC(< z(UR^Tae6fvG@cQkYDQeU>BqV6-hDqH6`}W|4Z%arjAIs@7+bFxK z#VfrMK`ILkD}jN#NWnQ07SEoX(xQ4mM~Hd3C9U)5iE;2bMCgU_Vy3)6&UJ$NcXs0s zxY4oHBMeiz0fM{&Ln0Z$<%@kzMA<9`ZoOZDJ27JJ0u7mZ*AcG0|`e#BqtoiC&(m4_`#6Hv@tH}#3nlE1Hegn}5)5WUrHv0!$8$xDb8Bcam zL@pk;j^Hcs2aguo*FqzaPd7K`H#fk^aDEOuhM%vIflOheXs_a{p-qB^kFfVU9_M#0 z{zP6LE)^B7iAjQqiF!c;Hz$A%NC`Vuu%jSI^ z!kBT(wMNk}}Ov4%nhr{}+~R zHZOcrEk}zFF=x{DQXW4WlKUttD`7|$U@leTTKcIU?a%l3!P?~rifI>NVK5l8RtWCj zv~VCdS6Aj17GSZ~!wN=GobUTUkMf>me8GhE5gj#46VIl*uDe^5msb~5TrH*;85%rD zpJ^>%@G#-Fvp;-h`=v$g*$3E?fHw(F9^eo$*VnG_&W5Mo9O13Bbn1i0bK`- z%auAuJMsJA5^U=`=|rU-zPBUeSE5n+=2Y+%m3nbAYVik2v`|xO+CzMLu+}SowPuWq zm&M>@M4h1Is-xnQ9MNxD{As=r@5%NV$w2OkcySsKFG;ahcMs$8)LZ9OUNd2mUxz!% zrmoLrE|yuijRv+mQ3}-1_}mRKtGD1E{q6a6Y{B5~13N55=FL}}Ggb=PL|Ufrv!n*$ zOeapt$|9-WodkMK3Ce7vJ3oibcs^T*!BEj%COk`WjvGf0Rm*I5px%#s^;NNvp8Sr( z4(}{*ZU6gIa&!uBdlp#QDp@p7=TQ=+ z7A^eG*mq(LAGJw$npyh=eP(9eJbx*L{$ik?fdO0FE6*uD3PP+l`G-5WqlQie{2M&7 z#?2nWYTgL;s~+pv)?JehyfK|%r%R(XBX>D&rfl&)=)^UO6;P&OHcf4wS1gi!naedP zadLoG?mBG{bQoWKO##maAaGdh%b5Ca2|NU?guLc*!TnuB$5lq5}` zSgXS=P8(V6uk^41J22rPZ2SQ0bwjhAkXGtpM>NqbIa?pd-pEVu;d#%Py|rx zqcs*bofcA2{b4_4q@`V{aYtWQDj^Eo==v#$1_NFi}9K9tyJ{MyKonNhG51FXBj^H;SWn72&3~LofFYH9|~p(Pk(tp^ZKW|9qO@4u|8_#((OCp z+~F6Ja+%#65&fz z?^D2s7BpHLLDe9IeilY>WZj!Y?&RDXgIxsjFtI!wxk9k*D%3c*_AZ{2S*Fx&4m8mN z#@igrOb@YFftMrZaD|E0I+xKhUo7aG>ojJ89?s+R_mEtFPiR@8A}rDADM*?)pPEKg zD4ae@l%oX}w6vhtNs-Lo&N~Q9go@G47Y1{|AKCW~C`piPqTO6T!Enu326VQT?X#Bu| zG-17}*Nvfuk`?IXcSt2Xb?Y5Ps<3DL`BnRAc!2m#5)-sN=g+!#bDa-t!jw^l-g>&ha;Ysb zhwExtwV^c(?j`BfL7Z;hN1GPadCnXPi@zU67uv(F9~IW7n-$278NAH9uJYW zI?xfu;M6bAUdJ4EkWiPye6^;_C`27DQR;s+vLHkS|1}(HW|nI$!T^J(9w@a6LZ?LR zmu46>16REd@i*GYZ6*2L4!OgjUEoovcB^5mm5hc8G{S~H~$Ieh2 zy|Cbk7Ajr{6KZYnCgWIdq|uF;%grmY`Dj<4LP4e-`)i)|yWaKVbWL(5$zs(USQCbdGfmZ# zmdAhfwu-ul2LBbQc5G^fxJolwUhto|w)cTAS}6!7zAIqLl|>GJ4pyxv8UKqirh}(m zjW7RDQFSF^KEPL(X;?Qd9R+W{0Y*s%00(@wqh*ShyF>UjedJ|ry%LG`#f+x985qNZ zKvVU+*&qDJ#8y+&Qdf6mW_8^ktLRq?#W06{q5@QEeYP+VNx(XnF1-LvM6ATBoA6qY%V)2m&PFuHR# zhKz&+;&BcS4*}!gzkJE5DT|3rRI)2ZMn?B^X@qBY31ohM#l>U=*q5o4*2wz06K8o^ zFvMPY`vL#0t!??VBMG0Dh6af6)ig8Pq6;e0uRPt~x3aYz9Ucxclrm|b1=R3_goLFf z{o*>FWmLfShDez<>Vr?JI#(VHl{zW+hG*N`+2L={ZvoBL3?EzCCq&>XqvI8XV zsx*d~He(t*Y4w>G}n& z+T_sEdwC=$i|qUc65B%!Y-ZXo?Z(e%U!Lo$!*d>aDRC#eaUbtQb`LQx_(vm}{PQcY zCdZPF#sj4y3Yl5sb_1nARA)#?2&`LSe+?fu)kq>Ef^#h--qN-<65r2d($w^q@JQow zXvR9q$~|h`^~onLIL*YhX3s<_IZEmSH}>$S(aiu(x=kyEg>u3iO)=!dn^fZa_~?|E znXkSIBhsR8&2|DP;g7^~J7Dj#l$0K_qSIeO&5PDa#XX>L!|;AEQ>mW{rsV(X`>K47 zyghy5y*Sn#DyWvO@KI>lF#0@cn&0)&@I%xd5fd|`MutMNOjK+v7B(hkTZFS|Llo#A=K)`ALIuhT*5)x4>G3Z5YV+=|cYgkwcz*Ggb}6P!36etg^&8xEcS9$*7JqfM;b(jnrWX8=TaH}vZmSZ zrwDP%c9~>9KJ#B-x@?m^Xxsj)c`v+B#%k&$%JIAM^qVxd?k57Sl+acM7bNzp^7j&m z6KRp(-iT!ViY|+^SU5$+x!VE@AY3JUreLh{~su~Cq`px8o=a}Ew}G>8H$4`M^Ia+KM$ z)f<5rK>-&&45~QB&H6rxDh>J>s~_I*Kk}vg6PogWEv#^KNY(H9-_uMw-DYBloReJ~ zrVZ7#?oJVE4jWgF91{P z89M30!NO|q>iDWX5I}1VwW-2WITqv_Vq>eO$L?%xHJc4iWIQSly4_cy8K{F1@G6c% zUJ9-&Qu5vI9m}6PmL0Ws2*FW^XirY-q#Mvi8g<76>I5-Xn0+4NPq3%f0Ur z`12SPaK1_|;Ux=$#wS7(HCU~D_Dl&>lq$t@phg4IUSQvHaQJ(6=IG*5uTu`B*~bS5 zpt#lQR|0t&Sn-31a-DJl4Ki5cU$NQ!sCs>Qsi=2lkg6l^%5GXbf~bD5p#m=hKfe-I z=KNLx7G}-Ow~4BB;y7Sd1U(**-=c2+&|*?lPyn14s!EVw|KH_Z zjG>&Xuf4<2`_Rx(ti7jVYW3o?^Rlg!s{djayu+hHv9q#44uSInX0OzM7uaK2+gJZn zAi^UH5Ol9>eMB>$!OQx?1Ah~YfpP`FPO*@fAA^I=E!>dg7~4C6Bw8+GF!eWIm07Y; zeOYD*aK+wRe3kdMOENY`@+K3_f17`z?B6y`l)RIUFfFbrSPaN58j#0e9d9R4ndSao z7i9;MC2CI2Si;diP&G!y(%rX*jxqV{#MQjGPhP~5EPg2-r@LRgM*setL^+5;p7Ydr zzQ?3ZH^Y@TPExt&qNGFh-hNVzZhCbcx^RUcCx7AlYAk7ugX)vwtBVBGubh5Tr~j_g z1lXuC{B1?MdclJ zK7d!zCZ(NOJ*1das84IrsV8~%S)od=2k-2FnJ`5r4pJy1EgKdVii8LcDPcp=c?hxf zAHj!_6qg+N_*1kQhW*f$99#a+cSg;krR_qMpi<0~9z;_1MvqNFZkEPx=Xo9Y&Kf>m z2UfQll$?mJ}|vLQ|~3h zZd80=jTc_kH~jJFo%!u~1hU6@+G^pku^6{|nPPcu12b`$wNx;|#`vCzP;6#zV$Ev? z8Y8hfb;3|M*NR$v8!c{>fck&*y;)a7A=!Cc7A>vqKG6h&$VNV5V!tP{RE?jX78?u8 z0bso)e*X>|3oa;Ga`MkzMIgsj0PH4l09L@%_oEQ0K@}Cs1Q=dFZvl@v=3gTziL>SB zi0EIlvR1y6h`mNfyOW{G`CnYU1yqz#yEZH#NXyXOUD6@V(A^;d(jbZ;9nvv$cMc6A zEuwUHBO%g_NQdONdCxij|DDe@%LS}q=3&;e_rCAzzJeN=l^{*gPi#(>{j1|QVS%}x z`<5659e?-=a*|Sx$yl~9UNGHAx`k1-WVL>85tN}|0x_;mZAsrR4ai@n#`&Fb5J;e_AfQq7GPJh6ScKGJK0pk z#9(U3%*Hk}HWqdQ@;O3ufIvQW*5UQZS=M`M!breA0~wxg7JY!kGy*<;_8WLkO-#fm zBp{yd0Qu;!H89Py===H6N3Ysq|G~kRS@aEP`M@(06M5r@3Hy$LO!bRAcoHW`bzA{9evN&K`Q`_6kWk9qxah$}kP11Y_T=327`vx}D=5lr9t zIy)8vcF*sJ#!2rL{W!6_9Fm1waw+Wi=74^EgC#Lv$%XwrC4FdENLV``87B_4W`mxs zO1w1@GizqJnXd5#s#H}Dp>tgDad!K?_w2_9&yAXO9j$XT z+SsW6MoR-x&8ZZFML)NvE}-!T;vn2 zQr>gnr+oQ&RXZ;WP4AJ2Wz>zf#^QZt$H?LyM6X4BXSe$c9wLmI6h&=X$}Pk-e@ks7 zJ)v?5&4r74Yx&Ffk0oZO6`Etdfw%j9{al0~iqi1s zy=?P3a1}Rlv(Lm_QmDjl)nMgtw8ISb;a62gb&9t;Z}yhdQL1|SXdX9Ap` zf{``jXc3ak!=PL=N>eYJQRrOxbumJ)a4p(%@2irl4adYQ`Lh{3Bv+^@#e}}9ODZmh ztcMJONn#Oe1M7*F6$v3s*f1%HdVEDxWe@_gA1R}I;Js6DMc*A_9IPXdaCm%t1`b*G zurL3>BpLBXGZrkt41ZGdCRYt@cT-vEO^I?z=j85`jpS70$n`rMm3NdrWG?`nD-(;# zxt*KzSxC{6q!zkOuBMSaQn7%}9{mo>3wq|~%ql@aGBSZ(c~}yBe2Ak3pKgzK!o$8N{7z(=+?9{IqA`JBk1{lmL+#lZCrL`1 z>#shFYtMTk;b*GO#pUiE3(&R;S8BS-Tfm1yLIeo2w6t_*?x*YY|5ZD=1ghiFV$)F| z_jpvTX_P;Zj`Mb;8;{M*62W3}(iP~TnmH!10)p$OTQJ8Ts^30|rOj3%oh~$VHoSex zrhft;su96oznZYHs7uATVlxxFRF&6BqMN&+Cg!wMU5vGG)0Yr}JZ95^Rl~}~1ju_| zvFffWBL?F}wQ4VZzYfHYeiDsM>6xj0>IzSu;LE7}JdbG_W$$4MmkI?sO9>+^On z)``%R_4W!!-NI(O2+A_(SFRXqUp z+WYsRZkEw<+Pb<{>-ltabbwtpFfj1-brvUcvQi+m2EHo*-OrnL^+1f(@p7p`|3E&W zT)_kj#Fey)K6MBPLZ`?ArtWe5)amVO46i4_KKqP!;oJ^2LNbz8$*i!gNK zrw|6R%{v6x^}ib+@dQhh2LQ|`JLW8GG>Vpri5rA0Lwl0816i9_88@4+uz9ds_wO&b z`rmHH9aL!?{$e!pJYu``C}z(Q%+iIu4+>1!|imV)bd!|y7faM;RBv^ zm7v^BKwxVwRa(H_sRd8S?n^qvf(<_&>IeBz0KBIspRF4>+%*>F-$#)MTjZQ^65H(k zvgYv|fH*HgoJASdm<^7Et_l84^f|tYV?sb(_3wH5qPj8=9IG?3sni9XhTF>>L>rVI1OpB-FGDs>IP( zVXngrgQQ1)%!{ORIaBsGStAjZm6L3k*iOy|;l`hNa4Irjvt!-+iYP{}{Aah;`RB`P zF*k>GWOEc#(&@RG^1Py%HG8y`3?WH0YZFcEti0j^F@!QO?AR#c_5AzRPpts3%rS`z z>ojBVrWDZ=rLL#Y{S|Ye@uaPWsqkVbE~S(IV#9@2u}szA5pb{K$W}1eGwTWqbpnOh zn0sws2p9+!6g!jgHfX1Tkiog{sVKFXIf)H@%cBNdru&?V0A zr^EOBCQ6iOlIc;I&N=Zv*Z2)+3#DLJef`7j&bXRB}*F~g{+X@e_kkqNL zINN*;{{v>_PHrHykCj=Q6>oBC;xl`kypC2U2iNw`87I)%onM@wp#H-k3QW4N8bW5% zM|^d?Hxu~lJyQ8FgR%$sxu<2Ypiuw*-rCo%ffQ_PO;4X@HH+p9&`<0Sy|ur-zH!y7 z03GF^s@6LZ+;7M~Kf$1R8b>Z7@7)B5D}Q84IOYI&>%$@e+Z6`kk(XCHiM91f!@_hF zTR2D+nl`U#M=k_)PD%8QnIe={)5>ZSU|oiWB-5^gmbIX51p3RN!<7;ZW^{CPK=kLv zWaHw><$tROl0$)qk+pU4jD5%%lI(;sIzeAfk@7=kT-^A=!otMF1Te@15Y_Ap9gsq& zq^u00JpRkmqqgq!$M@@BzqS}zh)(7WrB`!_%PjqtK!b^dgajsmH3r6ddOs&7-n<~r z`o0A^Qfq5#V5*#Z&w(ilUTRbsT7?JL z5XqaxCLqStiTW6rD^<+I_%WykLxHf<1I92N9h)kqOrHRToW}$Y-n0{u#M{{@lTDyd zwz(KHSeJ$q{mZT2*H8W2PC%nM+3h{#K@W1zkm8w-Sa{12X=I95N*kn=Gx!=63@7~E zF>z1z%=al1-o1o+gR%1AEsD|Afe_@!G0SR%calG}9eTXKoT|5a zcdT&qOz>pY-BJsWcv*P-+4}BpSETj?uj||B>uH@-sEe1 zmU!kQRv}S;C=0$)As~XRufJ2Kpi-^6?<3jn6NHB-BuPit%EQZqpTP7QAYzRWj6vME+^#SD=gMm16_#(m05CdPGT6Df-Mc*4E)=HSydN ztMRKeZ)gGldW8UXDshv%kkSzz3Eu@iRM<{W{Eml${VNM~g>24W1zKTNsLuAME5BYI zQ*0FBO=zK#wMM6y(60?3BzwhLi^bDUar271tlj*3ij0gLy(#(>1^Foo3ThY>3hmWe zOJmOouhekjhjmV48cM;+%V9g2^6W;jzZ(>r&tmqO4*UtG@ph>(5rx1YY2Q5H$OnC>fOO)Gm}>1W(UK8W>4Qb8>X?$zJou= z5u+KT?+r-=UuLG}jH)UkFkW^;g@U54{y02;GV=?=JiZ_IDw60lG_<|7s7N#stzXlM zXJwfP7A&1_v36U89su6~4!L2Wp#U2KUk@+l)r0_ZQ!#^$js0_aS|~X~ zs`35Dj~@X7@9bQwZH=z3UZe$vmgi?@paaZf26{_2R#p^L)Pt!n0Nn?>9oMH-r6L|~ zZd}U#5NOqL*+bYL@umIjxVSjL-EHlt24=%;TD0-gKYzxUO5j5H(^WtRy#ChxKmi}6 zcm5OL07}Q) zg2nAj(@*1N(DaucJdAt^sVHrqp_u^OJr%&o5B-Jdj^obd2tJ4|I%#tjkmjb#OdD?t zAJ3o};nLI0CXH71vvM4IEI-r;_jmOMj>=bK(Hv zu}}w%)Zf39OH0%f;>F!yftm6$$Wx4CL2tHMO-NY5Y*kFWuHv+=Xav zMu9Pj6cTMOXiXCx&Xx;b-pkXSBqIDvj#5TcnF_y!ekBa4KVu(I8AIGH-OdE;1v$I2 zF|xdD<}#G07#1}r^iS?O!yl)Nai_wy4Lh+LSK9+Jx8~5%#+lE*{AgYFPyhU&N{;#5 zYa|ywNJv{{Y^4o5K|VfKK@WitkN{UA{FUu(q^Q$^``xlaKhp7X&2`anw52pWv^SN{sabxq$I2`k&aK3dusA)z}!aZ z2p7?a_vyH_adMENT(@85;QX=S^wSWiM|_)$6?Hly8@yb4#8UfFK z25wn7mqyRMORp!ErtJ!OTRWFPE$|#pUnEJly~_Nm*Cub#1A#3@Ce~^kzRnz96Q2*Z zyw!ZE{0@Y6+k@?O49`+kDiK_q>=l;Au%c9h*3A^f=gA^g1s7}-bIkRtrrlA8d91E0 zg-7|(DGQ62mR+jj@21|k0Rjx^v8A#nn2d+EuLnGod6tsGXXr}@X9j7d<4YRN&_r|sPJ_)EBk|;mdV<4bLHsK+%IlqQ zdyE8htmyFY@aPD5Z})hq4qy{cy}R2$pXXxJ3k&uQM%fqFb!`#*wOK$fIXeqflUwzFfRY^S zE}#L$bJ~uIic$`=gFz7s>VZeb3(P57K446YE$U)vSy)xY#moEg)^3gyPj;fa8=9Fk z7Xp2k+~i4Qc9nW}4tCj!8KA3rUt{oR7K{~36z~N?iMjZ*pTSa+l0b_bdwBQ(3}m~i zK^qJBxH`^C>gr=4PHkjl1V{mBN`Rw>k25P9TLt(Vz(0l(bY}pxm4Es29;gGDN&prI zRG~mY4~*tHo%eQjb^s_xQ-a`3N=_d9F8QD>$$!Xi#J6v?tZAO|d)$udjqvJsGeV;~4hce|G?YM)Qf8k48+~Iwa8Uk35SHtK8y7C8paD#&1xaL^}Jh86Of8#)liawLXB zk|7mFng+&+b9@SCTzy0m)NQAR?_;c$-_GVST)Ao?cp*MfT}~|IIrHT`p;Y93qdno5 z$TLP2)sJJDaqAb||DX_jjWi(A#!#>=AxM*(5O6|;h{clLgN%8SSHK)@hA59FiU2K^ z^t}E%ceOp--xpHuYvU&$^T}iA>)kNe;5bc!_|Nf*usrnQwQS;7jA&krVyxRy%d*mn zigsIPg()OqQs$cPGowXM;f>d{-R(IkxLil=9-XhRV|ch5czkeCLFOARfE0smiKHhz zBqG76x%JiW#xw)x+_f(yPh%-yzc0aFuimoR_y)&j9_eJ2ATQO{2`fh*UTgVey;)~8 zAWt|2LISqP+I0;yA>>{i(PT0YmryvK*i(Nqz_|*MhEF8v>t9}8 zl6`dc@DdwyKv}xI^?5Ia5Ux;Oz9t~xoSEtQ`gMEZ@+2a1VS2h~3*{L~@{p9{c%+(s z02BaKG3$U@52o+{zz`tGI}idw$gf|2Qo_n-?1>k|m*(t$?bBjtyb;MkIXgS!}>@n6z|YkGUPl zKO2()H6EZ&s4z~+J`oIkb78Y44aXjv9l3hJ%{}2DpnSj>P6VC;4lGL^5(idvq@5A# zkIv3K#z=nB*>0w$ra+V#`lhxR^SAuJ7 zzKr!o2UnRBx}Qk^qm`EFN^E##Wd&5-;Q#h^$%nb=+1c6UWeF8E(6_c&;2{?SJP&wU z>3iLOIjE|Ctilt0Sg#T}PnF`ChxM*4xD@=MGSWe`1)Y-na)bn6-Yz7e7;C*T7+Fyr zdV#U_naLF1a>0M{bF4oAfIkN|U;GrTW#CP+O3E2JnNdoc4rWX?TE$~&*ukZi_PmmC z1gSTxG}A(PH|rSdMb0@oS%nG345blg&{s0Cc9tAp?Rl?{Cgu*PR6bq2?GE=*ogBtd z)cVKSUC>U4V^=I;dua#unm-5c9n<4+2H1=17&nHv)vjmKRPO;tq6&9deNB3=!}ovJZt!J>K>EVlZkkfsdTBJY@;s#^N~$5t zJ~YixB`o5%q-Bs01(((A@|TSmloF&rw(&NKsN{6veo(klIJAd{Ftf+JyJp^nGL`fB z3r!kj+Er$auPWUMN}k z!37AV>NtS-BPjSPCt-vOM?2Yp{nSe$$WmGBMd`t_RFe-8@)UX^MMWQqg0Pk^#!cRc zxbD>-JE^N}773W4;}?Ut>qP{f^P{t)<71GYih+h56@y;V(^Ea?1R)`teRjs^WRx-- z3e{gO@G%QB+pZx#`aSGvxop?gcTroH@VD_504 z;C^*#;6}2nI^#sE>T$WpX)kTlPQoE6fcQ@~~T-Ty0)kEIm)V78x}MJBok z-o*WI>242ss>Y(v#A}z~2Jgq-rc4+%g|PF+W~!;U+n+h`F4;MITdFT9eRt*xaB{rt zZz91HM7+*+I)YH$4;EZ^#`C+va3n4lKdN1R-_v%UbK3t|>3#7>*yrl#%j+M#RJLO| zVtp|b-m4)*CsBbO~UV>M?zq?^tFdItYcWi$2w{11@; zR4% z&_PT-DJl+J$swnD5_}oqY#)GD zShB~#0coxhZT@+AaYxntX=w(GnXHl|&QYnh_)Mi!^#(=pJGCp3Y^*Qedn5YZTJC(@ zj(c^;MhB#oQbEnQ|7MWM|C%PAjC};K8ZX{S6N#rEpZ3x|*7NR-i=R}tCpnH8Of44D z;jezDW z@qy1qgfUPq*6O33mM|(rg$#1=3d;V&^b^?key*>gwjsbr4;+!-&vhBrN{N4qN}Ewn z`nkUA>6{G|RkG%ci4^iS{w8n@2380!cQo}pz2Z<}>hvns@4cm0Qe2v)5HSyI&tq@P zU$F6;oK4Ojrb}(XwtGRWnzfs3ieKi9NyUJpH<^0L3lbfHph5GAZy&aLFu+b}5VKyr zCRCs1Vb90Gm;fQ6B%p-gl9CgW6R#Z-t!(cf?ysZzE>r%c{QLf||F&u_!pI5s^|<0J zJ#Nc|{y-7Ut_OTiQlU?Rd`yLgEL*|G9!Dh`RV;pQlDnySbuDnV;5@W9k zo<&vqX;k`;sbTNI;oo++;!@I+HyF;LKL{ZW*?WPk?ELy)lyQePohjuC3$x(W(IiBi#|C6914 zX5IPwYA&!+ok(pQ+eV;6tjVlk4FR?%7!g*?Fw)cSxO@jNJLr#sgOQ`MR(3&V07?}xnn%l9p(NEG$L&Mg?K*z;}JhBH` z#9ow9Rj0s%PGGH_AHSp4k@Cul>?G<^%uUpOtg%1G5tqmC-WTtLWPn*hfYvl#SYeqg z{&0Z&-*Qy{A^p_tBaeV*gi2B8IvMRBK&&0)mVywq5)yL)SyZUME^XsikAXAiS+*dJ z&A{BX`ky`~`Fkt9-4>=cN$f04Uym@encsu+k>Q5fP|YS*u~#_`_(QtJH0WNqy%XlN zv@$_5h<8Z0&CQSOr^Q9NpuPu11^lL`P7zSx@PHVEDBTqZ9QJpPpTHuD*j4Dp(;0UE zMNE1%m&FnrD1G)ZaC;E{`4ul8wG~Cd<=4QtckU+VJoDje=(Kx9q{3^Nnn@JW-BL`9bP(m`d}cFMl_y(aq&fTXDq7!?EA?;!Q>> zD^WOHX%{1^*bnUnI0cvpW!sW1pMZdXh|skrK7Zy21qH== zeCfQy-`!m&$P_3aGVW?gCk))NSa&dvw~umt-Jrk=28 z*uM-0yPIU5pRKKdrKN*|gO6x7({ps)!oOT%rkVyJx()UmSLPKCLCKf(3>yt%%d}&@ z(f-Ju8@_R{4ZlfWBKmW6ZHk`h&fb$PNac#){yCl3Pt3!uZ%~yKuf4h>fUUf&#nzhuy zt^qWvkehY?5=6`*ZKt8+GB_jMQ(iwyyz7(16r6|w* z6TZG~xo%!&<4?`dPY5tVU5mPFScg^jWb_GGQ}6xg05j*E80Dui&U^5qfTC|$FviR$ zkmUY(a>{JL>x%(x@-r-)=y1%)h?wwb@Q4Vn;edw9$_C3VIGh9^NPTL($9~}g#F&64 z^F%_3Iv*(2(?zUKk_HkTuq?RFa9Z;DI#Qo1Rz+5y1s1xXn-yNTqX9AUhty{nV4z^r zt$ii>U1d;h{MiVjon9;aGm7IrlQkE^&&3iSbFQ17#@po^+%irNjj*g)8j0Pwhq_EZ zCjC$H@X0!_ji@&ZyH+@_eu^;|cvRK8qiO!C%rOkAAn-(o$&vbd1;uOV04XH~Kj#Db~xoZnr2zh6Nztfo=jcuArKn3h4X| z5*>&iO~hj)f`RvjqocZ_qEk2rNY4SBTu?z`{~(U;1*IQ|NUB~sKf2ZfZ{>J$ne(>! zc1RxHsDj8-1&qFg!|Qx}5P&^1R!jtTtWEdHl?yCNmHt^2%jB?V9^~CV(-u3Oo@0{Z z!kFk$%yt=7-0Ucj;rtR93?sxps=0Esn(pdcX0VWI zI#v-80f8LCzSUZ*Qps%FIBR@XrM=^86W3Eo`|>jcwj0B`!vU3Jj54RHL@f;k-Zln? zEYq|nWyomC?OYPO6mjf_7b)`(^k&8H9izpAPt@a*&(L;LAEKsH?rouxW@2TmPc_di z$-xn~(OA<8H%$z?0zynVYi?h&^s|_r(@HD0ipD>yL1LRd|HB1XJWX?1a)x`S+1fs3 zov2qaOrX?V6Qu#8aPYyqSn7Cad@z#)1`<^`8nEv_qNRC%n7|*Ntlt(6NIrX}NVo&p zN60ZQg2p}`ghif`PSF;bRw2pLh&7|n;A}F1A<%y(qn?mirsMh) zChEz0^(8y7=aS_*^?Ad=UMDMiWK?xy8FbxtqPk7$!v_rz?*kfG1BGvQK*tY^DChL!w@|aQGEG;-DQl$(E=s~ z&zvKJ%FjBx6bq{0$AYxXf-x~Lvlq;WpPE$$Cm5eq5*mK`Qrk>;NJ_I++4)m~-h1!q zbq#MnQyX1Lt4!2;M-tIxzHcqEdomI~>2i1DxLo@i=?TQDWIpvPE&6VscBeGn{`E=u zafR@&9UYz@`+`2jR!5k$0U@!tqR>uBv0U0bIdX(&nwfy4kTwXK#4hU!0fD@eY=ygN zw5CD2j4S6bkD*AetZ%)UU*Ed_Uu7H64(YBq8a$2#TC=tf#TTF;>G>H9y7u7$)Mxe$ zBC>GS*ea@9!hgR91#X7>FrN_7Oy2~H>*<0c3zbB_5mnAKC7$;R#aoO?~f0t>D zonmYK#5HG&IlpvI)@^sPUjbi~a80L=A1_Z%YESj#C)X_2ca0%1`wjC% zer2q9+u6$QK=0(u9*oaPM2gv4OqTm&jw=0vmVWB}e10@EjL>w6*mHurKxi&i{IOE5 z|H{>XBa-NzOva|K+H2~P9LK~6bcT3Xlp!~%E1VtX6$IK_WN zp?*g!s|l`iN7C^0;I>`ETFW4VkkepVl*C|n&56}
cK0u)2!?dr^(@upYMqSgr5q z-(tc{G+@2FES4V#Gsn@R%Mw1PM@)(|yQUEvhE#eeT(p1M;yqNAIKg-^D&aE3PwJdIVJUb+lyS?K z?CyPbxqyp++A96EmC)%%z-6Lk@SXwco9bmvkdlI$b!8@r7U}Shl!AnS5K(&l4wQ?C zh>}aGcbJoj{Wau*3m*-qks) zFpHwB`~bs`DfeW^8A<`5?aE=(BH?U zE~nyK6R~k)_c%?5HSD}6`9MLwLWY|wIBepW=A)MGqek*ujjW^<%XYWW{UTTX;!~`{ zC%O-JQ@2kaKMp)Y!_D6A1Z3YbJ>6nW!T>|fQoRk_6JzO|=%HFCLqf)(ZYx72yK<$B z;)HG6>T+l^fBKFpW2mXm>KWD<%BqO&|GP+d*#5t&OC=b}Pa2KH4bpl+vjXg)?6@>b z*Z|qOHV@*#cpdj9oQ9P?;l*ca+rEQN@aKsC%%ki>8-HFm5NQCoS-yA62bv@)B~&; za@WVPGzYV;?ij5|s9gMx#aJCqw$#!Mm-8PC%k7%d9|AC-^C69=!UC*jKSi@^yxqKqfIrOF z>A3%5jD?UIimWdMrPO@Kou2C+o`=pK)H58p3W?{jCNA;Q*eIx7TM_Q>pi0p6NyxfU z!92lo+4D~F{TLo90RM)lJQByar@_#Rm#>17D4j1S3k_X}I;G5^q;|2nuIJW1FI2Q# z7?qG=u#cVYi`&`RXG(zp)d#`Kxdk{)h**^Ok1yuC7y0MP<%`HJK2ZOs$N%%f>JD$G z^M_7LBP4kQD%Hfw|LV(3BmuE{I1g}jvL}~>gOongeqeL)O|O(!*;zS>K=tbLy=L$C zW6uk1$A1(z6!SMEwdWo}mY;nir9Mt}DzWpE^{Wja1f-?Pg>je$-GaW#w;AN60SL<1 z_tv2REx z5pd@wW5z^9dWiQ?xn2b?FK*T z?(Y8A@QN4$A*aAoLkbY)tBES;rU%t$W&hM_bXn-d{pQtVm?arDPmV|5X&G<$X3AxB zzi{pOHmdbT3kI$tO&?7+ay#FVYg{t2QH->XS1%AtI!~S!`k%c_NV$ii3_iq8f4WzI zCps#y-ML%ZPm%DFbR+jNC8oBgnK&BUsyDk43g4J+G}QH91VwpMrLr4Fx?)54>%u#= zW{4r12?|L{`Enuh!6+zCude^KdoYke7+ixj$lNV7D*G{wUqpr(n@*9@i1;M=jB7jPQj~&1B~1 zt}!&4==|v2Y~1EeKHpUaXzHb9BKR70bmvv-u|duBKJsc+rvAVYh4LSk=RNOumdm-t zq~}}R?2oVvH~s+wt8o~PE|@^5SnAk*c;*3<=BO)4WlEEOK)@k)IH`WetfHJN>WLnO zlL74%wLqzCY7~&z(n}yR890E zM(n9kuEWnObYdmwm%teDKRBoK;FLgmT-Cs#=xBo9$#N`z-xbxo_LZO9M%edj*XOXM zf9#F!H4INpwRE*@JGNhidor5OK`}GJ#qlN_X}wgTv9KNP=LcTRs_ON-$3HEbO~M3s zkE|)U+0uz8*=G00Rk{8=+&08^_kYS>DH+!VZHq!#d3YTWS26O6A9~B_8>%?gT!Sh{{6g?|p9>hz*@x>7CHkUyK1{P`gl60o9Rs7*4!x(wX9x*4X>Gj^ z2feRX(Vz4M19A;=hJ|$2hT%<5n}XOVQ$=0UYVW!Rxb9K++CI?;Z#klD z=xhD?hec9w)`0e}H{9n9wDn25%ib@`&$o6MItgkoRT+n5hHl9U5gx?woI{hMeC?tB zJvmS&iTEAlC`ZYAq&_AFYYEbL$JML1hovImMxP_G1Vp2klnET)vGyrx?d9W3RVoPv z@yT1MDYw$PJQzT8sm`VT=p@BkoVfc^n;IgU=P=4b|D8rJCZ2sxc^Uy06aV=II{zT$ ze~Wu-QJOvd(;C$pfOI7Ym3YiIiu@nJ{3+TF!*{nxj}D6RoDfSyk1|#U?c$jNX99g{ zMApZ<9aEu~Z9sPsnZjNzbqlD1^EbOA!X$(5Vy499{pvRP(YC+nx{fgIiA;wOr12}K z*gj`N%aQCht1g}XwiDiup@9F@C&bVIu(&?taCc#is=YfYNO7#yET(|8(ByQs^(ij2 z#5v3>#Z`LWcz`J6r(wu)vSED_a6<=HR_pR-pAsk+!<7bWw&e04Ef&$v`*d(5ZPVf8(^4l5jmN&-%ekX^Ceuuf~l7g#s6^#asZ4w6^`lT{M=vqZM0+&fv3{};v zv#*lf19Ruz>CG(QJ9whEb_a5y@N$ny57(?R5a{q#2X2NjsCMuY=_VC?zk<}?Y z?iW?h3D>`aan)m){~wsvnBbe@f8ZmE^V>>Pa2H0bdw{Ws_Vq5G2@4ZbpDo{lMc>fp zo^xrq+RH2mG9WQ)8XFsHXqfrEXO2+nS7c3IVB*SW&H#6HYHBKQSxetOT=>KK_?m(P z-ov>r>H5)7uw_3yY0EQ{q%C#whdz_Vq#i}2m)0|e@z>+|o`%crS4Y1@ei_rJsKxRdQ6OPf&j^{+9cJe2qX)N(#XxP>e39y^^Me zs`7=`uNXY?g z@LgOJZoWeQ<_`P6T$YG|O&^pt&8`Kk6P*uzOP>CMx_6GZ3d*PzMJ|Wge+9f37x~^z zS(ofCd5^bTqJwUvb`g>F8Dij?Sb~|Q3`2@hC5mG|5HcTYb88B78whA z)js)ecc-J5MA&Eg4IjQZCu-R0%)76srswNhn{3$v6^r89|30OWH_+$&3l(vRX1v8x zy<)}kZOUje=rSzbVjurtI(?L*{n0cK@78AKw#ojUoc}l}BCU)zM+dE>GyP}9yQrExyi7rApqR!J&^u<1O4TUpGvr(Dm{>r#g1NOg;*@_94N=k#^ zs_7x;RnkUA8Cqq3qKR(CcvoJ!h`eUTUwX5C`%VW=j$QI_jTXqv$qB|3KkXZQPg1M1 zZK>!)#%pIb2i5mEziAQ3&8CK8u1z(+55e z=^0EzD|_+2wODsr46PhW)J)L2r5rofhVX05AIEKh(~wB?(n@X2vi5t3<;NhIuG?F? zoE(!c-$KY=MqrbOAUAY(uHefvdE3|sy1P?R<>pC}2C+ShOyJ>XSxgd@lHxCmAuZS% z)8{qO_w;S{sC($e$g{D2im4=>exmg2ogleHr5m;Wco%w_cq~EQa>3`qTuh!Z3@uw$ zFIg1M{H=M6P?H5-l!H0$<~&65zz+5<_fDd{jy@ya+g(&s?{|xPHE-&ECAfE5i?fZ3 zN&Wm9UWr#DKOAi^tPMNU+fOlFpYi;uhge3?brzPhgqFKhC#V7hNkj+$*f@_8V>+7molTJ1Brn{yo9 zAFio`c~KY|qmC#N96M-YzK(?=<+lZBGT1}m)?3y=BOe?f*J5+SbBvCEk_5d%F9P#% z4&6NuMNb_KPPXvS=ro6DQf#SfJDpBBzr={QQc86^he6;+Lc-+X&Jp1Y0-Be28_gxi z6{(@VH4_JO*wuG7)Tk19759PM5G+-*RLt8g65%U7gc!DVr_J#e-qiABy(4pdPoMIO zYbu`!aShZKRMYzNj5v4xe8&#`ZZguXw>u36U7rlQJQce>>2{eEt~TS7wMJ;c#1Su5 z_nw!cYY^o9_dOkOPmmY4vmEID_m|R+iwM#k;NOq$x-eb`7%6xm2X&b7q+_B4VcSgl z;REMPJiH*Apg)k2Uh^7wLBYI(K(ul*Q+0duYBVbpwEMuwF)(uX(wEKw!W^0f?9fMidoP`hk?$d(;~3S%6-JE^9Je z0hfk;+TIn+@|m@|x2hRx5&)DG7>F366rU5Hlay3AW4|hIERZ>5U7Ln`c5~q>p+r_3 zXZx_4=CwV__5nxX%o@UNo>UoKkl2#>qpm7fUZa{Tn?y3At4N8E5tqLbo-?o!wf(QE znW*-C*xlFMe5JD%j?t6{cUl z5b`IXR66=c>&hcokj89BP1YBwWjQsy%BD-1JJ@k-xx`qAbcYqfm>u6CT117rAXNAS zb#wgg^tnSspX8K1YCS^3JoagPyVNt4)oz+;ftyP5uXDLFRm#s&v*g?S;sZ@52FGX) zC#F2^oR6^f`al3egwzehHuv*uijzT}-XvjYpF!;x-6VY#`XZ+ybV3$v8z-P0^}V|l z`z@A5L4F`Vzp&El32s#4$F(Nv6@4m1(6`vx+&DP5)G^vKGw`b~n{bChuH<-NoS8*C zyL*6rvI0t#t2+F;!{Z!pxk0|&hUg3!cRFvS8A4y<(5Kn`LkvmbNNMl=_dI;IMYP4Z z#dpy*z-!*FKB-J;qi_==V!!_8z@y8>TboCaex z9fJ#b)y6X0(;?e`_HXP0w5zKNiJ0WiY4T$=-<|j&q4R%Ub5n3ZmV>|lJNoH9hbF&O z#m&r;?{&U)k>$~ea>zNw#`@Gi3E_ujLyG!4?aW;4fZs&zJD<1nP!_FU`jqFl-NwS1 zsFq2-Tu1I8w$URICF|Y9pQ4bfS1ZcoWVD8-4Ku9bGr2#||g$!1!~bj7JU z(H6X}(7n_tT8${aZ*^fY9s2kbZx#OUlR}jJadF8gr0?L4BP4d2I~i~%q-|_$TwQqx zgpI79YK_MV84VMBNM^NCQ;RXC**^A65K`20)3eqqHm1?H)3MvN1LP1V;IAKBpgK-S zL}X)S6(4Wu;@|@6Ehi`L+!YMj&aB0(j0MtYy)J?eco00fSjy~-6s5ReAtPgbeSH%X zN&-BF2#D3DrLMmITfBz(rg_)^jGS}(eLhWMPn34I9bSV{bZt!;(1J;oX`({|zh8@F ztEDES&^|{?m`VU(t?Ro69h#Amp-RV6M|*p%QUb*IJa{d5aUNysu0Ps|mw%G-O(Y+zlC4rMuhB$K&=5(7UJIcy24;lSz?s z++wb=i@`ozez+*{3=O{KHt?d)NE#hsBly{nXi=O{XR^WZNy4M+eI|v?oAQD06c>-{ zv?VFuBUqE&v&{HC$NO}j<=Pz>HXu7I&&nzqtA6CR`B6vXQYuyNI&mj_ zI|K0rIiIPN#l=lEKyVSZF$P{D^|)w&(Uza2?RqVyaYCo1XBJm16K8)rLy|a-uWY>f z4%#yzYJ%T5>j~q^RlE(0SRH-UuhH@5cw#4*jL<8FIpOEVk_(e;C_VE%1uxr6sJ>O1 z5DM5(`u)+V%@1N{B_fSyP9z{EM%D#)wHLj;)jKO4*v0!SzocfUH);qDIK3;N6y)a$ z_%IQ`c~KhFVRY6yeQLlU@;=Axp6qNh^S3}2a_(#7w-;F6n{*3*X47LOKzw$HZncw1 zu{8`%Cv>|~{Vc=p2^4O!^xl90{T<;N@gDtqBk?GG`*ekvT=`*>UgMLd*_*z6;oY0Q z_D-w-ULqO#g%@&F5M4%adWKOU>W33o)I}Dw1aZj0zd2FTX<}9#KMiEQ$O}lyNBJUu zcbUUBjseTS7T_1pBoXi-#`gT^>~?hIa$MpWB7gPKqa$7ux7@?cNT99Mc&?nzssC4P zG=jIAf8ugrAJt(>0M*7yFrxb)*%z-;&akh-bx# z((#vu`;i;~^ANMzG||8?wAXTaa)2l6s@fn)A07pBcyIUK&TfLyj;??XBN81f1wFMC zW}~E}jA^he7Z%DR^cjj6XJ%#_zBZUor&x`Shdqq?QMw ziQ~}dOBNikN|XES>oZQSI;Fc|Xrvnk z5kxvg8fhd(KtfVLLQ3iWj_-T#x9(c=2e=l4%zDn*d;ec0_&ANIO)1UbfBu`nElZLWqVqt_EVO{5WAq9(*Q#}-D|O%ydSRJ12V z!-Raa(Px8xtS68Wv{v`WpIsvGuyz=c@Iag8X|64~!Y_TS)P~EyJ|Yw(J-^VSqpq0- zcB7KZm#UK4JC#nlINY|S-c0=9z99E;oV4^I?o}bS;lickU-WxN@{MvmS@iG-i!zgr zF|l}%%^md6o1RvK2JRy-dj!?zY61xw?N(}~GDC3kL~T3%=q8~T+e~f-%VCT&R$k^) z2Ry8Mzprnv@o_PuYZetu5# z-x274`^WAQ{Ri0aWsC*M7&`teoa&G`-*Q=Iauj%TGcz*_P7D+nZ;0&`pW8ow=Jd>z z*@zznQdM60k47I=X~Tsi#3pb);Q`*1@vq}w$0nXV)4C-~w)JxMa(d+i=npU#(TIkq z{YwF?_{_<}gzKO=Ix-s1iCp+>6sg3ZGi-0~a8(X}nwrJ7g2xGiRzVzEafRCgq^zs;#syZCy!d(}2kq3;VT$CL9@ zgTNa9Ib+-hS5#$J{nuv%d{h&0D&(%^bi)mZCFIxPQf~2=AU9gZ6 z_YH~)@^*c3+rn?JbHA-QT(~dbw7pz&po-6?ZKQkDV>ZG4+&?hx?Pfyb3AO-9M-;L7 z7UA8em^2HS;wox|EE3N}{2%DEc3qx-rr+?`6u~Z^r2!_H(Ny%3! zndSKTk5X(wWA|+RbtZxJvsyQ>VwQ~gf3*PLj&I8JmANk${g>QgptE~a&9;`^@%mzx z1ra8QR_oqAjRK7^$l$InqEQy4mFlzEU`kxW=2nWj)K2Q;l6FqpRldeR>eweHf1r%F z-IQlSJ(7ouq!SyzGgZZFJ+pmaqQqSBt)3s^WXr}Tr6_sLX|sbVM|VJ1{~L9#cJRSz z7hR8D@kJe`e4fpuC1j5!wq))|H&_otlOihZ3%0AQcmP|XX*g@I9(!%jg=WVkhFCl; zf?D|-a-F?pUkH+6^0Mn^Qt+FIvS!8q3j}DBTzGTJG9a%9BMyQ_!I(7K)uVvUDChUu z4-^p)4M z-a$>Fmk@1hc!QG84n?qZB-;*jg+d$L>-iwMc4jiy`??6AI^Im*G!!@7B-sR3G*Ak_ zTYPc@s$vt0nlujUCePZgPVe;q&u5l=^sfTwcb5vX>m%D_;JE6bpIV{# zNjFoqC=Tfl?8$;=8E1jEqHnHdckk!+&gQPxF;3Fa;7{(>ob%TsOK9jZ4H5Y#IAUSDEKG1-`+2|W2{e@;Pj=H*e}(iDC% zJTkH{FaU&^$o~E%umgvWT>gnX^^=r0jF%h`^VYn*7jf?svv~sDbh`g8F^T43UQ+N< z38VzcjqT~<3RF*(_n%_+adavip*9bHv9-(H2eS=>NI$lA?!GprJqC$+`GYetcXG+7 zKnz0B%lSz`{|A>D7D-4h9|gmcXW)ED-P>FqR1_&r)Y)i|HVem%s1NUP%LPap6O;6; zp+_rUTwnQq_Wxvd=YZyvl#^mB!)(6?LP_iV06B!`>+M=j7f!=Y5UEPc{j7o(-u#TE z&?n{mqn(}}^D)9IA^j>sWl)3fP>}>+rMTm~dOOh} z{S;SPIsf9ZC>l6O``L26nm6|5&q+Fh8Cy6V=O^5tjc>xln5-Q10W*`_>nQu64& zbZWu|vS$&-g+|oI(zR#{;!+&jT#vl~ItU(TEEoCmXDLq$0_@ev%%O}%K2YU;! zn^2ixb}w(Dtyuj;jGLoqa%gmJ-;yVA!|F~`Ry_cx^0U;fQ{j{ZT1P*6BeF|u`v9}>8Q z2DTYtZlL5`nSazy3qj+#f5-Rij#Iw$llfUYj+srjy6w+*)B$nS82CTayAyq|o_T%2 zAw|JZk$Du3*;uHn)xTPJVrQ?Tc&ka~CEgRnh)LF*5wAa*a-T3mK1qNr(!uvFz2A zKSuPGz+7km%pfg|qHtuClR+&PT9rD?M(SD^B6loj#3fgC#u#ars*+5$B4YRLKf{!hd`_1SEf-^ zPULPOv{$#EFS!LOpwT!q0s(zTDI(v!&YG*86PKkA9)vEh5#CA4siZ|z$J^MDK{ijV zuGcrFTf-thk~>KMx$R;yJH`06dil5{bz>6egqik9EoM12b#$?+W^THd@kt_L$m~TT z(OmZfkB&m9^SiRmRU4s-RWy-3j`&~&ad8oDk;$9aW zPBNRJNoH<_0dHL*ihUS`nVL%0F(6=zn7te)43<`2R4ZFHwYjkgRZ<4et{HPqL3%+d zrb23b!g1?mD|o_j6L2Bf8zL$~ToNBkN=iID?5s52$yar&yr_Olm13)>sTX7(^xEr} z6g`YIjzxdukN`fCRu9IE2fB!d16)8WlAe}fwe{K(Tofi51=-Fo;1xf0pO+GgjJlF9d#TT&%&|N-t|FQ)kGrs* zCh+1Uz%6Yd;^K->-;Q!?9C5qq)yvJVqS9x#7e|(uK@W4i7CP^Oj&2n5+@^*HG~GRL zvtP;fvAHonXEh~Pv)QImeD#uMf6vKDDWR|S3lcd$Gc)=_BIFm{xLH&xk}wvnStLAD z$|y_bsVYle@f!E@sqbZqU9D@926cn96^%ukE7It{vYL&HcglMH5bY@7E9^e_v71Ei z=tucTa)KecXT@q&l;h$VMm2-@9Qr$PsknV~l2x(YI;k*9OZ+d@mp%TcP8aN-jUM1t znvT6}iM>Sn9g?Us{*oG|D`TSi4fSmedxuudoyf8pEkHp4|LMr0%tkKiVvU=!om{LC z&j};aA#&8XbRFcPP|2usTP}y}heK1;rZao+Akf}{%LokMnr|- zw0KJ1UE}JE@Y?TA_aA38Vn>fvu&>FbzFbh)NlqYM`>t;WljMdX#{E1J6hgP;#42!p zls3*+yI-koo<)8$k286Z*f1Nl|J>+6PK0uhWR)HAu24}4VT0p^*m}1rTH$tQ{#ow% zwc7t}pcdWG*_p3gWm!r6QD`{{9ytTwZ3?*2d8&9o-LN8tze&BKN4AHxgV%13y`?im z2?0E;?&&uZDYg_)gk82>V2Z7lH<%dYU~*tK4Y)Z!D1E>q18pXKS96Tl=OIVUaG1m6zYvk6i$CJo<$dTtKfHbEIh= zDLUjR`u6)Va}wov?QCaebZF7o?WwTqj#b%WkyHm4*GVF(wm>K2y zC|42oUQF?`JGAFXCeT){Pja+ZIE=5asGjG_r^@x|PSEr0in_a2GX9P{?>zFeCJ7wZ z=rN#~*XH6JViWl0W6vV-GJXEmz}HSg-<%Su#>3BpP->jqd=K(#{~V*| z19E?if+t>UU2TJ#@h=AC^u%455yoItERv9`&su5ECQj0q;fE55$YA) zV|5f6cv}3h97+fQ3DM8gR4K{fUY;3g8N|dSFLd>rnp)Ntnd6}Vk5coC<)mdD2Ut@a z%g^$;^7_B^!1Enni4&?)qz`9gHhT3c@F83cfgNYw80Z}23{!=9IXBDtB&ochsJV$# znJ)ha7Qs^n{tMj#a*-4H^Q{H@{nv?pl^0dI03B*nHFAq5{|IG(q(eza$bhfi)5Bw9 zW3x}i5@5TzIk`WH*5N9>DvG}Hw5em%+x{iXZLj|QG07_u2ge61Jdl3LkN6NzH_wyP zV=U}5c(>bH9Zq^iegPMI6+^D)#swSP#>A5MKKbkq!&Ep~xBg&vTcIznkz(*qRm3yp zjM=yI=%~7q5^BAxL=0<$f%4HOoUrNKLl7oLB^!r@`%8ccfmO}PA2;-oK+o%Kz92lR zx_z&2o->n|gw=mjd&n16kvU(Un#jAaP;pA1U@W35<>_7;bwCp8wie@SKd1|jeJhpM z2-U*I>AQ!Uvn8)D!?DQ=|MD1}DMPh_1lU#Gj`z}+%DM-f5=XyBeGN{LaD&W$=jP;M znbPs)L^r0U=&?YLjJmkG_WevnxmA~G8$5Y7$pnMeql{pS@(c5ejGvz&JU!~qPux#S ze9@z?>U?{8%dsBC>i2TOVxVMhg~ntzSDHWY$3xCLG1Xh1N?ivH5%IeHU`tJ}0uOft zYa|tuB{tL?$IDDRCaIsf@reIj}YN#GIF=@Pl{OidfBPwk1u- zrf=8tN)`AD1}w-s4-(fSNGhO2g1&XwLk5O{Pac*{{>JfBavwJ9 zbW_BrQsgZ;xSo3Mis3mGoK%n)5Urtz|D~tTPa@vCVg3xc@aEiivP?wl|JDpJbYuP- zx_`iOG1mk!!h4u}lu+1+A6u&#TDT*ioD7WcJ5J;edL+2t!D;yU?Po>BgJfGbyE<06 z@Dy8*mmV)1U)UMifeHP!*J~H%3T-Zcz{ab*;3gy^?!mjg>AiW2WC8QVc_LIempk{jVgy;K?2MCh^qc<32Kq8Bn35O=FKFqLqY6qBw87&!)A0LB! zQ9zd-KmM!xr(&c+4e%*>Ig3>A-G|%R@tA9lzAP8e^G^Q{pj8K4uiz8fL8-r-epEY%=fP~wKsB_c!Xy0YE;Z|XJjvNH)p1muJd9PXD zNXg1Qth>klD4z`rUNm)MX99SBP&=BvN-8Urj0_V1?%?U}1?KTTe~z&p9Y4nX#n;;} z`TqIW3C&U1i^kMfg2Nm&t_4B7mCdaV^LWv{du4S;L{Ecq_GUy|a`yUt)rQarT87sP z<_lq?H@XU5*qS+ak2)@;5L9dgW>QfXLqU<7w54Ns>}U=1V8zi|pGf4Gm#w&cy*|IK zX=gxxE*1P$S+{bVqkbiRL0gE#Yk~PWc1|8rRyKEQH;w1y16CmT?egN<*U#^hn3&n5 z*BAAZ6jY}u9jro`+m!NrsT+4(mFdjkP^CIIPA_>3-mcinU1o{b1Ujah?VsSy?klyP zWekv4f15^cynERs2VJPO5}k>yNr-Z+G~OUNrKFxMY0jQc zK|qc}!IgMZPazC3rZ&K<+Y5)DR@dNDs|7H74Y`s^iEP*1nb9!8B%z>(+f6BF*Z5#w zYW*j6BocRj{Nqo6LvD7fnVBu?{?^1l#Q1QqW=;K$@$&}nXg7K}O4H)Qnv*q& zl&?e!&fB^h&Bmv1wdRzAweb?^KmMd6;JkexWqtYRbk#H?%+&R~L+;fb5u~c{-fYI@ zzL*Nfv;3b#<^SWe!S7LtA%R5<5a8;2p-Zxshv zREs5DRTfq^%^NXvsuEA*uCCZ5JeC|Q-K&y$}p zdgN{yDg5C>>5>*itJ>_zP2YJ{iP`N$_vDD*iwB7u-Ey`^qU52lXdcd%iPcf`OO&UM z$W%O66y&!OmD9_7oSS$EjE}Q}9=&Uw43g0+^9L$aA1mDw_O1|>Y4@KN*^C15{W#dzCugT_-rjG#JZkBL?KiMK5(2uS zskV_%WE@|B;)LCr3m2=Q7RDW`4~Te*J^GZ0#D<2yT*EoE^=~lveHqS6lWbk6Yj2LQ z4X&AdE_Dve^aKWEMr-KQGr*A9n~)-K$@~KT4Hc{eTdY$P5?U_| zT#lM)f8#BeqkZ#y5AKEo8>gG>Pn_B~=c@AR&D0Nshf2A$S zkP#CX8wdDlFJ}=7Mb^lr?|NVibd1R0$YX_U5=b}!(hq+|dZBiQJmhqbCLW5VCUtO6CJ z_O`Xu31iTP?UFUWPk#s9m@&(E9E-&s%K{lZgVg4=jh?Rlj>l)vn}H*&57rF50&A2& z+h^!&==7>evrJt>lbeSN#8vlj!a(mg&Hh7Tp>ER_(CQAxzky0kmf7rh&I99iMM9kR zFAq%RL?&S6k_zuuE14Z-V8F>zQqzS@#`1dupmZ}^sCc?10G!p#83)uadh(p2HEHGc ztc8YO2S|giC&KRcn|%ZGY2hMXZxuItr@1?ye_?>7y4z;aJ>O^*6PKV*FP|Ao0nqb) ze%_*Fhk1yPSpEP}lu|#xMJbXW3XgYuj?MPk#zXqndG2k^;_@Zw*Fg2eX@lBOnnz7R za$@T^Z$oY)1hj%O!d>bth@;eu4+f}-cBM|gBaG9%qE?Bwd3L&ISzq@WgJv7C*tvI_2(qLv1)O`-_BVfjN;mN)Ah&B0dBqC$l9p z_hVdYM}F0q%5TCi(U#2iubp2%og+S;RDJ|M(}Vx?sW$%-O_5SwmdV94DZw2!u!gCu zMjnf%>5eB;BVPl_Z%@9y!Ib-V!nUz}w$KcYWV%{ilr(%ER6x}!6|?(m-K04aLm#p7 z$R+`=yp;Tx+j+@yz@FDm{Y8tM>CMsn`)9r{UY{Nk=#VsHL)MMS*8PoF@>i9WMu6Vr z6`J9K>}z63j@2A|f=Ql zi$`Op@a1;RkeG%+xBhvXFcS_PH&m%FK$z^cDv}?&W~neAm$MJk-`)|E_!vQYbf_CADx)1>4IyzpJO#x;e(COeD z$(Mjn`d<+&i&0lm>)s-ro3+Dvecu)q6&YL3l_9C$wvI}+O-CaIw={D`vHz`z6s zWG)pIAJG^?<*WEu$4ArZf0RSlW}(>SC|43)dEoC!O4z-JliZ6#gtd{&DvjRqiKi-D zjvHIQ4)*rfX$iJzdO}){k##tpsBD6!e9jp6P2OKb96hC7Y4>C>rI#H}7uw9&;x1veEope0|Fs4=?xQBd{6aal9D@ z7ULHdY`p+V{gP*CsZN}0#JGpP&*pL)GE`SCNgdl!V%-a)UZ5fp4skkzY&KVwtfVJ^LbV{&@dEJd8m0 z(r$^&JU1zPhVGk*!APEn)}%P;)kCWdY@tVaL*-ac*u*5i%7pyd+*$j%w_)aDBk^qk ze4Gpl+}vL=b8&;1Q`q(X=|uqfLCyrLJZxxa@$?E!IBt|ZbbSg%M2Nkt26kT~j!OT$ z=`q&#yyjgO3{IyEsY%sgO)?>og%{GTVf+Vna#Lvap9(a1nWu;IR33#ZM+g{%W|{re z4CpgZfbx5^M&%dqvRAM;e5Qxww`O$!CbBJBqw_PyvJ9Tdb?+OX_jEf(t0H26JmaOG zR?V~JNL7!3@}Z)Jov0A|!xL-6jwqR6Q$6ol-?Jvg6tu|11h_7@Qow&U3@!F9mg}}O zQAJKLZe*-ZtVJh-Hl9R+C))G{hvPOq+XO54Sd5zBXTv5Rzhs8=U=Z89e*ba^0p{`G zAnL5BBe`6Ig{vlFvNlPrv4~(`3{*1+qD>DjVEFY;MM#>zvx%faK<8VE8u4lE?DrW? z;gJVKTcAS)B}}5NNCrjkAE2E>DFsQ;ig&TI>!BlLlut|s=aomJP-_~fr3h75eM)z8 zcBO&7l;?ALW;vnpv8r^u5#k-f+qFttCGGQr+jQ)IWalGsC1u!~$8Uhr5wue@=E4^5 z5}F8AFQ!0bWG+=awc`Bg{*8^vnk@6@{>w@95c%jllOVx>0YTIyBId+gEwwE*5^i%V zv2Y54hybcrOL=@j0!Mn7WMtl2S~8|9t3@cRgcO7yE$pXS4NH5GJP4m*a@>1y&!Hb9 zFyqXC{jNW#A!8NcXFDG@YhRVOlI(WT{|b3&DKoAv*Of%y=w^g5Ufisgr*qHcb*sQX zMP@CFFRYDnOE_)mufoeqQ~y}4+ts=0%WSQa*Iad}OWew0pP!|r*jGKHzI?t^+XKeO zqY)h0l94%zF=iH823ay=D_|FS|1ffS+-q9J;p5tuDBQZnM!s1lq%vkBE?UDC158dVz*2c|7ZeGnBTe8CdkSOAmE4BJSdeAV1D&FGhp#cEjUMBzNe)|SqRp` zcp3+&QFGx%zB}3CrzhXBPS=kZF!gN>c3N+~QPzKm&f|;oF{gNQ8r`UMjz1ra#~sL} zhu4`Bsys(8=I&w|VnFb9075Sf3g3@ zt283&8TCl1xZ?H`pkSB-&EW9%+seJllS+?b6`vLpga)ZjvEJ(PC8$+VQ5dC46f{&z zlUSSO$+kc%0~$z>BY^Ds$3fcHgOTIB?hVG8e0E2vXu0OhD*-NKF1(mJoo_p>ukHK~6An*dj zs|dAVHKnRkpbBt@X+D-!N>*aF|N7SJjW^iub9{`8`^ajFDIx{N==7BL;|qgjPWvGF z%C*k&M}g}6R+%_?&*%3PaI3nC9aG=Lcorz-{~aW(3Xvq1>Ax;_N(d=I6HQhQh*|5P>41#FfxmKhz&o( z%nH7jXc3Ex!lAK%A~eVG{0CQTpOKsK!gSX`zC#}O z;Cd`wU#tr z`CLw~ElG6VP0d%EcHIp|rna^0N&8{Yjx{;_9$oCoXF|%1=SeoM|K{<>E8Net^QL0< zqu^~?Kf))wD}~&-ZGJ75@_vyZE#YywvG&Cu?>;1UYOCZ9RKb<;fasQQE_bHQP0{$B z63kcN&7+$GI;;oR=$vn*?%mcl)}-2!3ffPpZ@qK;w$^I?@ws_RH=}R({wdvlP&E>! zK;7-#-Hqy@oIByr)aR)HNX#+L0fGZP_?aByGV<~#d7aV60TV=pkFKSTW$-@+mb5G; zm9x}|G*LZGJxSm+Ces_GBm zm-nhL=>0=*Vi8dH^!CywbbmOdE<$V$yTaDknCl~#f3S{Ej=C$wzoYz01eE`-mZUf` z-sKgVi#X#hF6ISe_NQ}>u5``Thi1Qj?ryK`fJh?>>Yt-)n4+GKfZ(eAaB>lK%VmtLgwW;||-# zq9T;nQ1)SK&YxCp+5J#EqIm&0^?7`4XUEIUQ~sZL(aG0aqCvwgZ~qP&cG zp@N&iLMNki-&?*KA0WNQje5on*>S1b$woC(^iHUV1p^m~Zazn_R+BHOXYL;b1kRRk zeaF;#)lDN2XS>6|wX5owP03Q+&?+}X*F8El)lXprPo%U9B!UPF1K$e8Nlc^VJ;m30 z(1Ln~XFRTTqh&yz9bfQxR4HxscbBX{FjHXgD+}d7 ziei)1b3D^(>o`ja>L3+^2$@8EfpX}rFSMK-SvMUZ=hjia=2i~LZ+Tm{A$ZuN+>@yf z6pLdfmxU{Nv)NLD@GIK-Pl+0%Wb8z9usWP4gb>ODt;ZqtI!vJYp{JC$Mz#{dEt1qZ zO?D31iU)-8JV+^C?0)$lYS+zEe!?<q`FWlui5iI%%6@h=ZB6 zBYq#6l6yolEpgv~lc&7qSY}2g{UR&qVKlK|nyE{xv0X#{U&w9TIk&yrKN$pV9`?(& zGgYUe)(^g`M1?Px&fL*w$K+)kbB)jjg?Lt$%JOeV&SoVVJuu&_&*5=PW*bh;2CZDj zELSx)@inRBg0R-VVMi&hda9!tx+VJ|AI$l6P&9Z1UVkYa?|9$Dw;y+`8F>2AFt04# zJSer;WMqV_`98ps30#J^hl%Rz5(eZMeqVcYKJ5E_JY-lj7(V?y8*D(|Ab?(+({JP7 zk>G%;AqV|6vOI{NQeD`ZO%eFr>voas?1_tdyer={PLaKa|Fud@I&MJ7;0jF{Zd0#y zz}M-VbfL8`ht&bqk6ZYfVw{m}!IT})LYbgnahDWpUIV*^5o&GUX`-nvZx?=j*FIj3 z6c#MeTE>y-T?un@+R`gE&JJ7c>z6TIYO0O0S+pT~!|S>EvqaQ#;<10`EC(viY0J^Z zYw7!)`8U5uX}Av-PMf?r%6Fm>0GYZKbU!`}8aLznbd&1?;2eV3NT+Q!2JxO4=$pUp zP$Z&nqwg&73?z;kGa$ndsCCfFX?BUHz|lHODlNP0l06jK1iJbn zrpF{7Ngbupr#{8{5&NU%!uz*G1zQt_il!HJhrcEEG9A4XAXQarx%ZiE=EeSWDj}0((bjsXB z9=j7uabvF7IApqrVe0KsT;4==566koObuUY)_+1386VZ%8`{QV<>F(Wo+!jfnjWTL zgyp6HH;B2jv-4|=6n17rlFCm>)~LW22&F(edBjm(F$0;A1|P{IZ5E?%Dk6z&Kz*Eb zixG${TmFcb<`OLVb>3$2BTadhmB9LN7Dr22)8YiaBwwr;wdSY4;2h52sQuux zu6YBEfDV|Cu@Z2OhGWfHd|rqr6|}vSUw=ev^~6FVF~Q~RPV}!Sb=Qaf5C5S;TxGaW zvMFhB1l%;LpZul%MV`GZX8yCWZcNdFcj&j{V*U3UAItNzC&}VjVRF9`Q|1$hUVqJ& zvJS{*?Z!sYIqn{uT_GnI75@CtjBrLsdJGrm4Hhv}k?iY2!~SN}-5~X2(BOLy;2*@(1^0SAYz2>ei&RzrHS73c-re5u z#29%Y-Ig6*H$iTe?+=%~9|_@dI$gB6jLm4xC9$&<-ve&1PEEZNa9hy2iRaq%0;koB zV*9f+JD=T0FH7EEit+cQk;=WTfNM$JFSgq`wGs&DWciTre3Dbd6ze|S6jJ|WR`jXd zVWg2m>ImgkZ^eSU6utDpT$uN_80c^RK9Les;hFrY*BVqml0)Wg%@!9eXKU_*ZYS&A z(l6Z#P(m2Sk%pV;GrH^iJo`j7C!;y2Tqu$jpIJ*6eq2K{o0AGfECY-gZj?}JlXp(2 zB6p_`Gs}E??&-)CbzXRbc+EP&1dm$E9+yKEKFsdIh##dvv}^x7T@O%IJuvdeERR)# z=tkZvBlewCIaL42nPF1AGQ0v$|B9#(mvr0#x(qZ@}kZ|URZ037Oeluk*j&sPcy zaidu}TZGT@H?}Fw^*Uuq@P7=q-XsI3$AFfY^RnN&^ck!yvBT9>;1LU=m1F4C&?Jac zJj#kyF^Pg2ure7Nvnp!(rynm~70r4tR7>Edy~o6%_``;STZL(!(YP;CdaG9oPz2TQ z_R%Aok0nEQFzO%QDB&dzcWcFj1|=E)BIIvnjGXKv=f{sUD|fhKYb>@bUpY&bj_>#S zG15^YE%s3vF-6w!HA8Bu zLxugLc`xW~2e_!0xDoH;xGSQ7hL|KbK6drUyd7dv3>XfeqW+zt_g}(_&5qsZoM#-d zTunm`$3Va4%X$!CZjcvN`fO`6jlh}*ab|aQ$#r;EY~nN;Yp>UC%IYbH?F4GcLB_pG*3gg@;IaFi=yx zwy9icyi!{+E0c1#z7)40^gnolJ9Oh{^$2>dBqv%bo1SHChg{f+s@ zaD>P|KKB+t4!Y?FC?O%AsOF_}jcy;HXcm}+eeGBFPsr?|&FO90`ysXxO>WY5rRqe# zQOq%QMlScurEE40z4uw!*mTK&w93h>f==I;(4C_0t4&e7wWQxR%O6YSV#xy4W6!Uf zURjd6_S6-UC+%F-mGvuVv~R!(zhEM582VZ691p4M#8IF-Q6CKoR7Ekn8Jo=&Tq1Ys zHg^i%caJ==i+sRxF5bOTb4d9`^dXAt8-2>D~>yNhPC-R*_HOm@4Ro+RSM5zJZAJ&K^ zTCsuw{~2?(x9A9bsbp~bv?k9cz)tVe>{A$0XcK4WPR-97!VJx!|Ev|eK2866pT^2| z?x#-+Nj3w-QC_lYT!Oec$NSRwy8z%*o0n{#t$Dj zI9OCaz?vHyJ-obLZ(1o1Dz5vKrk$j1Ok3rdcygt)M=dzg<{}U+Pj7+VknWI)h)t7v zmLNAb_xR{JECNc`rh`B}*1!>VA5RDm_6!{RF+a8B__)P^c%RE%N&0>R`<;CT zd(`+^G+Ol46~kp!OOn4?Eq*>lh~Gbo`x6)rx6r`&M|NNM19Rn60g-QI(#pr9RWvEj zJo4*Q7k>8$5-8gh9v$4`m#=smMFaF!V>BY;(GgemVsa7e8jO~#)<^E@G010#f)5)& z__ftV)NBzqdM0T0V}hRTuT#Q2ZTfyQS~QP+S+^YQRnOKuBg@{_aU|% ziDg|OO6jBJhIeE_<9TuqdpU@w&%)REaV*}WU=I@tE9~uqgzfj{hle2C0|?$(}rg+)S8dz zceUBs9HPMsjCEE+HnTgda%XEySIz^JG%6WwaQaffcZcCnnZpQzX03Y(V#$IamLTTs zrQM(@ykeQjWg}+E;^->Ahn!9qLkxzzUAhN$+XvC_%h{=R`E`Ep>bjDRcVM1ReXsLb z8iT>QOl5@NLJzwcy*p{g0iyB=i!}VQ!E2?Fx69GFtT^Ky&<9StxMLrd-_B5A`{%Aq z)vS%Dl!L2HwPO`f8MA-95-@6pgiyZOtlzCWy=?o$N~fv}4$;)?8T*|a1Jal})35qW-%v3wDaF^vMA=0bFnPMN3mlsr9=xc3&pQGZjrfKk#pQvoo_m|0o*( zzv^RvR8=H%zB6E1SX$!I8R>(#nY$H(p{Bet`JZTv-8t{D1j54=jk^Q74}=PG$z2wN z&&TQmb#f`j*(nh3JH6V^@8e2O?;$VWTin~8+kTK@D`zfODcKB?YZ;OCNLU>#QZbVJ zpJE@_!+;o+{2z7$Jir`w9FyverKPQ<;s7No)*~m{0=DBiI}RlT=u_;gjH)83TU&ZF zwf-7XfA8{Vl@c;8N!|`@FE(So`r|lw(;ltMWiN{$@4V%pnu#NIJ8Xx4P<2s8t}#We zhg?JmIXgds%`;O9M&=zuyoV*sshU6S-GXFqt#e${W)Z7p`2#>KzaL)~-!liYK(Dzz zmFe;2?<0PFD!D1m&1Z>tPYw>GJ3AX!CuIu=2EbZsF;zpx>`$7iiMq#Iwv2jdnMtOt zE<;hrlMayidvojWkEU<#I)Ek!xgBacx00KIqnb!DS6jT~NH`qDqK!X)%Hss9l~ zDN5byYoCXS2?uP3aW_kI+@SBDw7P!(tgrx`W`8|>^(`bX4pW9Tgb2Q>f-07Rg2$Y* z_e|(VD%KfG&YpVXV!mywu>(N4tsfAF_PR3rbd;#y(SP1e8tQq(O`|yccTS&ptM!$D zByVec%r1wJSe`8737tq)>!s=L`5z3W|6CzJw;WuBiotAOOzy344cCVoZVmMqIyk=% z3KWUSrp()aooycM<;4afx5ohPp#--r99xs|XM!!+#xZ0o3TvraOg?5awYkIa&<}{+(vAHx97XGF$w6^LD z$1lc*L>3ejxu|#ckPt7&Uem)Gz; zY|VBB-d9e$%fwBS;*A;vaWP> z^;Jo}#aG4y1f=qxMWoK89vBb++fzdi`yju73I91=B9ov``AUTHx)3i03i=4Z@Vvve zGw1&g&Wo^xnZwKhqzl9eFIn`kLB_@=bRA~IvZTd@ zvtyXQ34Dt;K|GIaY)7$Qh7Q zGNIs=K9ekc{Y1|<=s8UM&AMU{Wz#4Ddl!-QhypL{ zqJE*6yq(N*l=gW@307b)JuAfpAz^}`fGb7m@V)(ZN>{|tj<2Ig>@OKSJC1<;=saRf zjUSHsPo4By1K`c|JUo6gH!b~dR^t846}nSLvn{tCQx2v^3R~G1$Yu}8ouy6E(bG>- z{m@yE=qCO^#qbL}&;quTMT4~d#L4XL#liv}j&crI13g#L{-WnpDrw3Q14D*6#Llnz z`9Eh*Q}tITPBI}!&H8CS+RR32nDjXna&kKmZl*l~YU}5=x2ju5;a?bU0#hc*e{fG4 zh6X^Qk_OBE)T^1T2jt4}eX?r!J@DApi?it`BZ~`Dsz7 z-b|6b)AHkI;5o3?T{ZGtH4=8}$Z3{NFi0Wl5EA`$dh@9iE=R|KahN{u9BvslPkUQJ zye$zRkJl-ebJBp7)VuY>$LG>)^YHvnf#UzaAuQ43RXk2c0~wf`r>QL{j~Uhe_E6oP z9qSK>SdCa-o+Qiin)32$DPtPX9WK$q1q4=h8VbEbpf&9oHmE4{oFXTN%@c*7p6+d* zN1gNIJ6l+&t&ow~Q6*sH2Y!E;{*ElOY<{Vh=yo&CFNZ^W`^+rQ{!sgr&<{ImMfBp~ z_W9IE^h$7?K=VUrG{(djn1JS{YOj|wg*ytFw$jm6wOPSA?7gDvw5v%lotL6VF5~|7 zDeWrw^a$R|8_37_PShc^#uT`!Nf(dr-d(@XFS+x%-~tl#2WDekH>BZi611`4!q3eG zdAtiyC%~-Q*svw)S5$uh=9tHEk5hG0fx7i++tWIN`pWjo($dnB5+*j$=y*oK20N=;c8ZpuTOzqiSg~w z$Z#0l%&dKC;{r3tZW;bC47^qV>3Eut$AnxqK>&`Zy0iL2E4XKN#uWYtf#{Ih^77J7 zeUg81bo*aopbRAW``XF(N1l^fS$u?sdKS8jH@906jhPmYbzqh!?IAb`Ij# z;9gpcTiidngJi7My{;9=dUCms=>As=P_1LOE;3l^pzvCfiCpjzBl70Cxdo@F<~S&C z{8tb?-b!vvIoED@wz=9#`MAcM%b0E5#Xe zk1^&n!YzzR;7?+ z6bb_}@V)To@2K}_91}SI1-t>iSKB}4XF4qnb8NZop$|*=RPQqtA?B}1!;c`)s6kG{ zWU~xxfEEE6E+1schmiY+oy2{9Et|>D-Pc5uDJUPHrS=*00(rxs2u(T}e0(i3(_pPR zv7}_%#`x^y;Za&#Li^vuf%vCC?~i@%(`e!HaStCt#%c&y-yK`olfD3^zpE+w_ud}$ zbk+{xx`+$~ZvR0p7$-6~FBUHXnm{`6|A=}Epf>xbYq&*=yIXO0cXti$(BhQh?he7- zDei8C;!s?QTXA=H|E}KudET#+$qbN-kS6=v-LvPM{prdQFb=@8IeS?6dlOi}60*2- zjQoPBMyldmF5(n?=Nf^eIo(zUOpYe~8W3U4O_6fkH%@=p^BoRfIj7!U5&dV@WzSRqTOiJIo#laa zzUR3$mO$ZQuqaVkyN$&)KeHHPmCs?IG8FcuT@cPSqb6(=_|{tY^4ZCkuG&&umtSt3 zXK0C(C?>x@qENJcD}L}Km6U&eSaYB_0!&H_?+PLL zzIFxDnaPaaEivi5pfS>2xyK=((~TuIP*LyZ_;Y`{u2rV0OEgbFKGiDff~A4Q6;@S+ zMD<7SBqbmSCdQTkSYkjDE+IcE4|uV_pb+WnYwD}$`)lOGGz4%>S5;MQ55|Vc%-S+B zG6PlxxHsq;<;f%(c?TS?WmQxsuP}Ih!S$6-Y%}+gLX) zG61u2KsiG!tfE<)AMny_#^PywV2v|aYz7ZC|kKWNj=*`Dp_}(EUS)!0W zU8ZJ%X%{2@XH(ft#?wG7;&VuwB|R6De%aO(73d2u`JaRd12Ww=(W@}8Rv#ZU?^{Og zSB=>O?go-{dLnKxK9}lLNoeD4sUZsS=TgmDz>cH|`R~0GQx;`O%-#w_ z=<@CIP4-(w${X>2`ti!)`-G5x*)a64Q_UDj_}U1aAFDj1RKuCTD*VXL5*JWFP_ zCXB>3>;C8{#H;RIgAN2W#^-!sPlO{=B9|nZPuJ0{s~`f}r@@V4cR_Ow@V5GP@ps1f z7H*N}y)RQo4F~Nz%5V3gkpM@pbct`+a%BuZSU3gQNl9t3!yJl=2d^c|R3%g7P!e6s zVTNIw=yZvl$v}%deuzrp21e8qsXrBpLP?ncbBiL!Uuktzlur33WMX1L4($mwIm|&4 z=`D}QMCY%cE8lq++E*c4OpnjhSCS^Gj}fq7Ica7puc6uFdB1$djoG5C#?f3)D-ut0jyfMm*d5Q9{*?50KH zss1RjvViQr9|Dcg_qZJ4uA|q z)H`esG&TOzKGh6b0<3(N%!yUFbE~SpkEO9{_*Cr3dC2O>0_tTad8hR^A5KreB7>@; zEVtBn@!|^*@ilg(KtP93h5%A)Kqfmer;h{XgC}Z^mSA)p9VY{g-o}@n{RM!~{IRbM z>L~W*5@zst-wW$fOVSadCM=EO0 zAgSj+yqZBC2);FHQ+UD(I|#(lzc;Fwzvk%m`#iwuEJIn#6y%p@G%ohj zF*+~qT-N9olp2Qp&IQx$O|dv0Aq|A=hu;TQ_PD$sh!+A7!V}*lf+A^j-UN`% z93_hh#r4G8K!QBM{)fcja;&7c%P`_aug0zsPQE;kZj?t0!cWlccSzdpLasn8-z}N` zhAJ-(pgTe!*iY8&)Xs=c&rZt19|Xt7gtv?RBlM4do{Gul6FVh^m~NI&IBR`n5dngG zw;Em2&Q?N9Rl&1Zjk0_i!KO$Fw103o+i1~01kL7rYL&**cmamF3LOmFi{^0Y4=bCD3-DZAuJ>va_ z5@+kN$zxrOB9Hr6G|G%c5L&F4rBtwx{X|FM>B)P8juhD;fVH-;i|ScIun#!wG(nVU zGfxq;55Jci)yd34&b|~VhkV`S^Z<;W`k|`|^Z>aiE#+>21pQMt%_9Nn6dP_$aQs1c z52OZP@>-!=xy1JrfPp#ny>_89zg(<1E;%VVide9<3_$JX_pKdS(VG?-v68WP49hz6 z)+|}Ev5lnie`TzU(t$LPxz;Pos)m`zYD&w8hC7IoX@VpOGV#;hDaT9&3HGZ7gkGOk z666|NDi^JrxB4Fc1~e^*=es~2JF4@h#+ULnw-&el`t>WXuIH$B&)N~VjxDS&`ubnb z5L9jC(iIvSdd&HUfBmZ*RZ6&>hVXN&Va)qU&wpVrTP>B3lNvO!52bbAW>IDlf zejmM%+zW6P{4naa2Q8VNTaWe0-yR_`0Y;%Mqt0*5@AA{l+ZvV|Sw^ zKHkFOa-)KqyQc@UvfwMRlsFoF${mLODcV8Fy8Y9>guCFkaKR= zOfB9!cWTpt?3e-?-D}T>&XBNf9fdbNqZRbm;q#4KJ5qF?6Ad9v@cb+QXapG~Rba^M zq%XCb21{hqP0_bY7|?-=ah{biYR>Qub|Lf@J?0lCQXK+JC9=iH41OTMnTsYjuCrJl z;Fh0$Im+wbqF(>w?%;HgF|%>{+juxMoO*36qg~{$Kr;Sferc&wxkL?E!lPGRN9pI^ z&yCok$p;%#z^aZT_P)R-TITZ`zh{<{JYOrPgT!-FfeQ}SqmSjbN%{Gjwu}_Bo*&a8 zx06}W`{_U@cFU{H{3Z_FWK(`yS55}J#B@_tskcB0Ic93Th3I(aw3Rwv)ZR7fcT8J*2t|XqWDUDcitf46FYYIXQ1X2v3MuPn zfSTRg2hFqdi`mwsFeB7eVd;6E_zWS9x0}R1etI=G@2S@Z-`d^nPo?zIes2TajG_LF zwK{8l^ru}K3l7c5CvyQlx`5$vnJ{o9J0S7Au2od~VXXJWGX1}d&i`-Yz(V-9b&hQR z>Qp7cf(8x!)%K~^T9&X5fyG10h@rzG`BeL@ms3&@wec;pA5jr5>)@05N1_da&$R*} zj6ACV@L(?uzD67|y=!$o?0sYACVXKx6OPeAInro2;-o<^ODHzBSNox*VmV&k4Abx0 z*}I8J{pTL>N?<}hmFczdcxHUvP-*j81^o5pXjL-e^i!IeV6=e3x%+neXxbcm+)=Yy z&3$y>dq=k?n9Xjf%OyZE|D6HWkv~I(qJ&z*a%) ztmZ{V-Jp46E)EW^6=0wcC+GYSz6rDf=9!P?`1=54@%{0quw*_kDW%GU^ZJ+O72-=u zOUrS&ZS}=Xf`+X}W_C7Ps8N_fbg6)WqwTkE&lnWtaXlYA1EX~v-;io$ZjgOT^)bMP z`pEObYi)bPdHHH3LW@lm+<>2nK}UP*SAmEnnjq=b%;VL$0wO-wgR|ppOp9T*S-t?y z9GX*d0v1HlslnmLQK%X}yz56d<3ZkwVbP1}zeyg<@Wff<1e_`5M0Ctm3F(#jSprO? ziW7TOl$7E=M!=_1Dqrx$>*i#Mo`;7+K!A^_r;IGvXR=YGg1u}P@>V?(^tRERcYD1q zZ}gM%;dkUlK!{KLGxfaJTQOwUv=S}NpA2E8APmnT1vJLfmcdE1(EM)G!dyia?V~O% zIt6jA3^6WTh~`}X!w%02PF1jP(9@;E=nGu1^hEw6bAC>VCzji{^jLHY zCXA>|S!5Drjo94U)Kam2a#K7!9a->j9giX0{nzK)i{BlK+LT90;ai3$eu2EN1l+S@ySD&EAn0NZ#NpY9xG;2za!`#hf0(%BmsF& zU!>GBKs~-6Lj**&A5sP+|8Ll0%u@kZc_wA7v49yj^tWllwI!!hJivx@Qy3K6 zl_I!HdpI<#ekxP$?Z2X{0EjTK!e>;cx3)39s_X!`(-Z8CyZ#oxykSr_FS>y>xYSWSS1UA*xJ50~2&u^M>?YJINL6{!9HD6dv=9RU z3#d#Wk8zU$nrTOmjWPZ{QAiBX*>t`>|7>nXArOihBmIs{5G0XoUBvFtiA(io-Mc-3 z{~=|FlEweWJ&K{V+i~81Rfbx1*gsSfgCqA{Fc&ME>w8A5GPgi`htI{q-#LP9kb;a| zl(hJ7&yu3SYbaV(k7BveW*juExt&}o>lO8*&By5yquq|5Lgv?S;S$1&$JbjKjnsyy zis_Ou)+Obz!;vFJQjuw@=8*v9%n{f=3AD2;G{HlaS}HR3?&=g_zh&i=lrUs-BUHYj z@21LE{roC8XHG`)^HT~U$x{76LFF8EH@`3h`#!=B4gB(A{PsQwpRl+GxD$W9N=x}6 zDJm;WUhjbqnkBj2kQU^LNZ7sSV?X}FF`~IbYlpakC_QOzavuH1+@ltj=&SJ2;5%^$ zKM|+2t&S5s!!kC%>NjmD zrQAQE!nNwyIN#g3Q7#@Gt#am;2xCMgri~2`$zlFd&!7JaSAd>%<+k^Pp*lC!gvwRWf%?h?AKBU0YTRfk>+eX-K$` zf$mmj)^C;f;>_XVq{N{?^Wq(gHQzItN z@g(0~HQDG%|2+ytLeL{g{(!gphlDeLWPAe_VbS8_^VkM~{NO5fjX_FGTU9`2nED^j zEwi`6$NIgp*$Y?em4cm;ihU0ymLhX07 z@2(OkosS>5bfZlWcbsH70bPt_BJgw7_q^Q)L_go}D4Z z8J&dyT|(Sh2P{ z9=6OcxfU1{tT*oIU7E=l4QH|Y;NNlpO{Ma7gyVjraWDe!@5TV)a=u9m?TI;2Iam0d zRc6+VR}*}y&+m-<89tOF+B%~Fzh2YE+5TAOX1WG;e}<;I+``+??04Ev(42FzpS}KL z0miLO`}8jT_Ig_%*%ZG>lraEmk`7&m-iPj%o=CC=xg&#ohr2%DbIu2JOD1?PD4_a z%Upt#mX#XTERn_?OX{y??Ls`}d~5Rlo(#i<7{U z07&i#4c_-$ph*OLF7vq$X(>5#T}6QZ0S^t{vd>kn-{j>-H+q7K9LrMXftPF97mkLV zDJdsgbVYz9CUpUA^Fc6GGT-gOWEV!}X3O!Se_Ir?{M?o9X;K{J@#$%Es-w-W*><(f z<@juSW_)>h(17nKkJ!a^-t7pJaGG9-l!}rQnHDu zK+}v#|NY4M!;n93k=-7_ChLCb%gyrMh|!ZFN~fe|p7hNI>@2yTDy*+)Onz4@{*Iq$ z?}QTvPXVm7eoX$l$ZP6^(jv=o1EdrSFII78?ktD>Xyxvc4!twNI@*{{f5=@D3aCj@ z{qe)JF2k2v16?U^eK9}?8PMU`s`it~&;Y0%6i$9sY|MVoiHfv#IamyEz&t%$Mml^J z`=aR%FOe_ikRjGzz(^*|Ym-I7`U9UoG3%#x`^9V0?lL4`^!kQ?>&EU8(D>$CUMvdI z70-b0i!;u5rz}NR^ao$d4rejgCTPRs0b+ME^l*v6e7GEp2|wo7xef#22f)}%=v@-= zNA0fYgZURH)faOIR+EktIZSepCZ*@HRv+WZf$OF5`Zn-)*1keuN8G`~Bf^~$p}{d1 z?qDhbzG&ex6T{nwj z!D9loAHAVP&hrgwKWf9i4>_f3s|!e!JmBOo@5hfhe|c*+}K2e`^WK(K*Rm0+3c?`U`GNf6;t# zBf+LO@LSqJ&$5@rx%1r6!hH+LQSaV9jM3T$_d)PCY`Xy6A;pG6Z5aqriu$2;!|fNK zUvp)q1Ba}j2t8=n83J7f(3UL@#@-fv?EsbXf5d~A@gio}Rl(a~-|TzIbHy*m$L8(pO2G|VVy@yYBBK-i8lR(sJF4`Zxb{u#b z*2&|x?0REdnMiiUGlzu8VY&rWg%UsLQ0%CZWz7o5EIIb}_vw@1+kPv}G>)5Bl$R$A zo3W{yH|bnoUo&dTE7`^@*_yOs>pvW0p^nVr2?)$5w5twrrU)ytJ5bb^?nx9!&oZz$=X10U1ot zlp*9(>iRf@L92A(?Rt(kRhE6wo6?JEKZ!raH-S%*q z#C_9mNWCxUvg>@0wdVaTWwT=;2^NN7GS16*wXcZUZ4LVgb5`s)a(_wk@zH={IQc-4 zOp+;;SwVI}Mn*zsGw%z)FgM2fqU|ojKus5un3a^4oKA&y$!VS8oFxB*7!a^sP@;xC z_0?&bPkeBdgQo)WU2@xv=pj3Fo1r(GI_~cJvyB<_vx@SuP$}eTJ;L2+n1~uEiK=U2 z(t#UMF>pQ~7BMdUhlpW5i=rW{?@Yk^^oG{WwLpSDFSYd3OwE)bY#y~$szHUYoPLV} z%cbnn5UskRpvJT^OlI4y3MCyt9;!#jKsPBc5zxpt=xB4jJi0nBw9!(n0*;lmwf(rs z4Q(ZL)d;m&*36IL)`f6$n*xocoO93I3$(#7)lEh+Mb>-G$=)go0+fI_lB~@<3}yr zxMWm%2A8?>Xow+kUSX>|+|X37$9 zJo($!a_)OLT_pU6Sg6)%a3M_Dv$E^yaAFYoWU=MT_5h@`o%Pp!C}9$z+RagA;b+Ie zo=pCnide6TZ*M#v?t=qJIle!?EG$sl!E_n^c<&8Kq|UBEYOUXMgQ0nNyMk%1zq#Io z25ZY%EK{U%O;SeYqxhJz71 zvPKA1HUT-TpuJr{Sa{vGS)KyDJz9oh>-zC)UE0Jx4i;8Cg$@v-K-~k(qf}KBQd9SZ zuw)a^!4i2YX$n;49V#@1RzqLR*zg*zsBnVC@_LNpMt6yq4)gSx7Oa~f0=i91 zm{Lc#FVnPkF7?`0nJ~pjCRSGTGm0xy$jx~Cy>b_mEI&%2WlX%Ugn6!D)Do*r-QwPL>>(#+_bpKcSO|K;bS zf?y4IM~kl>+OZJFY!l}b5}91{7r1!cZLJ279u z^PiLUO|PM8t*R~UaL{i7l%EtmT0t&GS@zG6494{@IdHcnO9egb2rOyM@H6pD8vC06 zFWJ?fCM#vI>l-KJ_*qgQnUcC&YTZyVMxvH*?S0uL`5%Tk54}&M}_yDxcr^}c9G7As-BiL`;V=Io&^3iARccN`0`>$rvKM@< zO&I}@o{JjKQ6DE+nJ8MRzW3X%-%kWI`+ksr!{BuKW!$U3G&DTxFIA2yxma-n0hgXW zt~?NZjTZlBR;%5&TZ=Oy)KDQTh6@{PCmp6~tk?oALC5URcj)o4A4B+kSk(fg}T$G=1#M1}>5T z4>BoY>%^p0>Xcg>t9>NxOGS;41wPsNhQ*qd5ecsuA75V!N_GNo|xM){py~6Tk%tx^81vo(> zB?Lvr1>e;fuxB_FL9?7jUpHgSXmS%65c3JnV@#i#tjLet4yQJ|dY z@9!s;0fhG=REfY2$H32N1ux8iNe@*UJ~)A*Y|ff>-83c!$JSrsI~T#4Bn>8zsoD8e zF^m4KTATxFh{0%rk||3THDZ8zK2=HkgC6~`e> zUSjC_*#?YXRR`$pA#Hp(O0uYwR3_*0gehXlmga$6j`|@1Q@|1frxQ;+A9SwLdSfUf z+2Pvz@pp0FEav^xaZdpJ)#~T&wM4bu^z~S1vZykGcl(0zP;#>koB&ojv@x=8jkv2K&`h`ttuDi5*Q=kRNSsd@)Ict~&1 zo5CZWhMo{Z>$mO(hon;?usd_=zc!!43I}Nzi6va3HH6p9C5j6GX5^k!@%0ZxW zX4PFL=mdCI_Sc8qEz}-hg#)Yh{iC1jVDu;b8}RLkqn+^Wl^_8=7ckAq{}?vvLVutA zkpMZMdBN$2UVk=gtn#d zbx@ft&ZHa5K4?MU4X!Iwr}-$A|GBQ8IJ@eD-p8L1ep)~(dvepbqS}Alp5ByvoTTGi zzMAbBeZ9q*SJrrfM8(v-UQ3QC;^sYFZ&|8N->Uuq!pG|~G1JfhMLs52 z0$6UEUkWTItkge0@8g<(N_<<1N2@**qcUGp+tJZ&{DOaY(>kt&D}Bj!*9@+>j|S7m*@YQ-EI zbHv2{{!TacTS7v@H*B5HsFob~K|S4sfxKY^4BcgKIc7|C|56^Me{VNRY!OpYa#R&)>cys_FUYN9=MeXQqK?2?_W(I3!qjSfTNjDDT8?Z-POdz&^B4(QiXZJe6daaE>x{2DBCG zqhYwE&jWu{#CmT+i($X~l$wzrf?BTcrsbVrI;lk_Eqc^Zw)&R1`u=|DFzMhMWaJ|}+>M3bHG229 zK*`)neaAyk$G-wa*ZR!u5Tp|oPZO%6@Reu&9<3g+DAaBQ2j`x=LRy9Vtbj_0*6RU! zDv;Bv0vTA=4ZM`Ci7jGZQI0p(`koL8Md)Bvgm@aNw7RU)w3gDsB%U#Chjvv5KOIHL zBcC6Nf81p+ZoB4QKWQ&6y^TW*z(?xP3%yA3Y6;rC6U^tbU#*v)SCer#4 zeX=k==zYhy=m_5!W4jR8p=&RKfNb53f^V;m&?!DWrG{^>3+X%Mzg|8@-}!*w{wCWS zSTqer(Pf-|G+#0?draJ`++teBe>rog{c88QaiLq+asBk70_VMI5`?*gP3~}DxYHG2 zhYTBs`HG38RAcaXO!PAL6=fWtX@1ZP=&FNYKz}8O^hi|8UgA<*BJfp*rQX*-w6?Y> z{VB_9@bO?a85q69XJ+mAH7}j-3t6FwO3(l4P#sSe&%h78X|NYpAx<)X&`n$E6MCD& zGLAn$;+Ye?qZi7lnX`7`TfH^T68Q`SW@%-mGY=tgP4wqa4NEJNler7Wtmw&dMdl5> z)YP!#Aei^1)4Mv8K>&^O{6q@WoJu9n^fF03F=M}0VbEPtJK3)7f9b=3f%vS_1jyi{ zFI?Q*T2-2n{a+J@gMqiPohlIyAIwL{m;EQ`9UcmzV5)TCIK7^w!Qq$wN~~R-c6CZi ztKD8F11kI{JW`5a7LUVsSOT;71ELqxUmpKh#ogT*^=;!?&VRC~dFo`d7W)nk+y%(U zzmk)ECF?cm?IjZz>m?;VB|2gvIt83scz76q2`B?%u>f^R-=;vK0Mfb*PV!y+EeVC4 zZ3&g2oX}gl`>urpz|(p5g*@(p1sE1t_X);F+x37N3n2643tKsaU!!_$ky4C++aSO& zP*5~YQlte|L7phf{*RE0kZ3Rw#%wTlj^>omc5I^5gtYMoSr&xv2z z>(P_(JA0Uz4pHI{E-q2Qe>~IQPpIK)h@j4MAS;laJ@>ZzfVs-RpJ18B;dhLz45swN_BS|QmIsqVPiF-l*Xs=gHK`^#D&bG@2gm2de(jv@*KoDl z0=0eK(5FE_-GIvVUNx|x=saoeGijcE?rJb7sB3Th(5(Yx#)&&;y*jQcfA6VYpSfP2 zell(AL;>z+jm^=vmxU~d;#>m`p0G0(oT=3f4%MW0nIIDw_ck8KN964W49}>i@9Yn@ z%~al(tCucr7wnOMOc2P9HqdVa@W2q?j$vbb&EEl|ZDZ6ucLfb?3p{aOIC zD|lVm=T@O1I~=L|U34nXNd$cp_j*<;C2Z|Q&->hVm<;5`;$p{KF=w4Pydz4Np4zv4 z2@el%ZyY~oZ8pCR9n|B`KUk$%p+eI~bbt%kB4d}&S)2a_9AqxH2b+KX^mLxNe)P^( za$7dc_v}~`-=M{WzrMQKapZNf^e$H|Q?Hn7y+2{E*##&Izx1os>0E03MLx6OB2vf# z(e+FJkBSmv$eeW(jG%y$I1MJSJh{zoA`7NCU#^G^XjDy@@4v64hLGhckS40Cg7qPm zO10gudFFh6cv+_Z2bFK9#2xhS8voXR7lk}yqI>GwzD_`A$G~9Q+E&HbnnB;1+1^&= ztsAam1y6x4Z%q`_)~OTH0nQ26yjojn1`YYLow|7yl$$G5AKV_w+n*v zBH<2g0V_Jrat#o-wxKQ)D{ct9*-w!y81g9$la>19EUA3rB{?RF2+J)&Mm(1eh!xIr zrnBEt`P#OKidH}lA3_LE;;O<9@8v`@MBf}g?5-OpacK4M6 zr9dm@)FTG5kO*puY2c~^RUW`;S%{C7lPM^ZA;DtL`jINEr6tEkBr$)}cb4ZJ@W1P9 zZ9e`xvyt2(r0kc*Y@Oufm%_rnR}pWaoZ`dY zUNMyV!_M*Bln}AJVbiNcP{kZFiIDefDG1oW;Uit9UOr`6T?Vsz>AoOQq|by?U?>nP zLva;nU#?CUEk%wA-~W}hpbq#kd`Pbiml~#vqL*ff*rq*Cp(?F7XmtX^D**`5b%npc zh9|ZVL=;-edC%k*9fZ<8NDdgb=UW z7pZa@a*d=PbbaKM;LN17!>4Xik)zM?F1PB(Pyh{}9#|UC^<=eTu`WjObjWS|_&luK{y9S+(xx-E9FLB< zEFt}rEK1^6`%cnqi?))fJCsCzKmf~GnO2QqUS1E{CTMEv^77K^uuP10c(i~Now0`U z8D$1@KbA#)Pp4ipoov2Yki~Hxo?VRKIqQjerRS)Ph_lgFGH-%kKj7+FzkEWxH1C$W zk4@>ITaxG@BovaG?KJ}RNJmhjNE)Q~%1zTiJR+GrpYOYjO1)}&(&4bFMu~uf-C4)= zT9n-WsEnaj3_>EudWDUXq(qNSQ66b{=uNtb>T3zMM4|?z;AQw;L-ob8!(Xz4Ze$sjHNrKt{@PNZp+CK)cUz&)^ik# ze(wkS=MBe3=;I_ei7**O#A(n3`LBCu{Nn1(tVUoO82z@^C2dqeD7NnHT>uMP7t7L~ z9_$0n$P*aXxMBf&#k}_QMtVKTdFA_u7PU7TBu1WG2_m0uh;x>2nlJZj4;DyXDgRRo z`~z|St5NmJ02t;RldwVei+_u2v_Kdn`|N7SR^*bOp080Rq;kmW7 zKTv(!zhx=V_qKT!WMLILYCU`y2w?_bXy^ql1F*ZN)%OvA;EQ3QLO$5j@>t)A3Z~N#sG|_1=cnbRWTN6CV?gvw%O7~D z&CT72i`z&`yI4#M4t{XP<<6;6KbA}(lYRV9?^^hE2eZ7~JBoK((d2?kP=WK8OwhW^ zMwjJF;K6__6n89vF^u39R!HMl5<(&VJa|Nu70F0nXzt^Bgzru&D4o(*)oP_A?+jE_ zeD2{!z=cenj_`2fouaZgVNXX|?YF%9zmnUj_vEP+UC5?-zlupC&`74pWThl0r=?*M zU;s3KFKFl|SbaUpzj@-)<{yGZ`JE5Kacp<@*TwSQ{!%P_(O&gwdxpI^z{5oaFk?14 z0VW|n07jvf=@B#5D=U1rx1PnMIm&vaJAY*UYTu3?B(YqqCO*gmY~eB|O&-LOWn*i= zz)0k+%aS>u%)n0Vk;nc_QO=0U|C9)sfvK2S`b?5K4zz_QC6{(2ACLchrN|JtrtAT> zJctjf_=J%$gED3EdSy89l*6NqRt=B=N_v;8&dS+Zbq&l)K`SoZ(ZX*O-iW)Ap&0rK zQdn+UU1}9}9GTRbEuWSj4ews|Hw+Iu-zEhdA>J~ed@H7`aCXvI=uSUdyT23Pc5Mqk zvU5BTy`Q$7(RJl_JpmPefGzT1{P~3&%mXxBYlZU?v<31CL{-F8M?dBzw7x%AfgV!l z^66m?A^-h+)ysC^YRdocng5G0dpmW1$^3f`%|Pm!h2viJ2}PoyH#hzZ86Qk>vsaw}+uUM#5 z%mG7&Mfit#dq{|z*kZ0;uOwu1Nwk>h1{43+P#fGSjmqJGK7y6LY;$MeiF87S2j zQ(U!9odFf@jmYK(nQTf=GT`J+0h(+4mdMe~QWA&JJAUJMY7*?hho;Q9u?N@U@p3|F zOVz(I6*bm4=IkJq!9y>ek*;J~2(GK;;KWN%`|*zhRptVr_YtH48E<(EWj&xaZDBa- z`#PG&?CUS%e5&-mOF}WBDIzSS-B0xIM4}ACT{iKH@rP$L7Qq8C3KlBp#|Ya{Vb(tfEz28iL^_eg z5@8S6L=dp^+ucPC zf}+3Bj3PYT*@H>z8@f&;CCg`DM0K#xo9nye zT5_CHc><~Q356wQ6n)eKeU4t-sSQZeeCKXs_Dzc z2ay+MiAu}{bl|}ee2?AclGl(dJEtMs4MMMUSCgzNbb8-_`Q{+ny+FX(hjsFPZnlww z`cb@}^A0Fc^6)G0<5E7ZpT9haQsBH2Hx0k@XF$CyVUfV`4Cpz{2%^d%wE1yE)}XRXy*&p98eZjYjEG<|@TbTJ zTigAv@ASm6)R^#9n)He@X9>#QAAm2hBavW&mTahG69O#R(#JOK-ErOUqX&Rqt<&du znq%CCHeM!5%0x*CSt=h>GF^cxBHvwr*mkTi(mTmOJZtf6~=h<{T>R4YbT<1r~H zPlX3x@Wl0bPUB7_e-XR8plH>$83PK)dxG=wMXJE$&d~5Iz`u@3qf8x$Xf#iKAN_VI z8cbl!P*9Nu-)85XD3fGW5oV(vzIY&5L1-3F^BeEHDunUcJ8V8>?Xt0GAG=BgH3U9i zMif(3;-e(yNI!Dfq}Zn$vQDXPwaa>}6$aIz2@HFUv=sQ3U#My3pcMu>{=~77ICC=@ zQ^)F1?8V6NPM51q#)wN4)rK65t_#~IFTJ35Cn&Cp>NV^}XP3VPk>Ph%v*DVO>wLco z(kAhPli2h=%PGpo#>Oh|^-<+jzd+&MU}E854TGb0BqaL>2Bk}i2h1#r92$1M3MryN zH~xgWjsYw45mcmpKkl&6Lsjrb{u@;(%q@PbObAKT0*x1R#@(G;ND}ws1{cY9`eP-j zpnOnH{KK&YzW$`Bcz1!P#lg!LK#|6_i#B`l7cTMmwOMRQYtp=gkiotIZC8=mhw*#^ zx^|n#-B13&iQa>KU;f-H&Kh6wwt^HP;*%~j#csN{ubi%~x3{;my1KTd<+-6~0KlK$ zX!%jSX7Ep>Qt`c)kR6c}a{6$?S_mZDF&UJ!%2^?cL?T zONL~=-+G86J^L>M^(cP8#>)+$nesTGSr<&|izF?KYkByd9-0Jt7>?C#uoV918s1C?)nr;otpugUk7JV*gc9LjKFMcdCIs(xTl5 zuiFiRy=N@vW1g7VUEwyq%P#~%8IKG|e`-8-@AY2pq1$->hqC1zAT9+e$km?N zrqt{YNfX=Gj}Y-95+X2k$?~ghnSe~J$?a{ua`*ZXDB#Q+Xp=`O&@xqM)ajBnE3odJ z+aT4-)Fa4e(=}}?CjnH%TWHS) zdJrQeB}G$HlWp&ZdyzK7yd}rjV;fFOaj`kj)A921p3z^{!=ht-f?5=w^^pgDcFzyzN&}#LT zG@wQ9So18?r%MS3R_Df|Fst4#INmci$lR=v<(*lyx%@bbXfQDG4Disua|qZ z%?qaWqKu>lXSxy1{1gOU`tUYoNl`yFg@m*e8O7fU3lu+Ls_GJX9A*JNx3fT4ahaN5 z8=~^7Icrb^lIn+=EVHLJ$6{Jhxf30Ocww6o5}^RR56C)d<4Ys3)2_f@Lph{ zR{dH)5Xvu|Cx=NkiXA6>vg|A}AU zC<|gw#=mSdoj+cZ=a%U3Ld;0)tY5I`$!LVlq5K;s*EnJ9;Tw|lGh*i#3j%#)X4Xk# z3sR5FEFf!R_3eMi&;YOf3Ax0%cQDX8i}}Yig1I>%O}5xOe2@xjsSK?ofQvuqqc(HW zbWHWly0{EbdiI4S@k7eJAt3uBSi1cB;i-5h{3D@+-@{_LvZG-Tk%4(GM5o9nyi#qtlsI(S-B8ihJS@uR!8n=}KLFNfSUMq{?i1aokhN~o zEtsN7mIH=-us-CUdTsv|m19WI5FZnX`u49^MN0sD1s4&B8vw`rTGz5qg$CttJEqT+ zT70++0An354+c}#O~7CP@($epwMo}U5pW<%4@D+Ait$f(Td-~RDpdpmZ_4s!aq<7- z>MMY%j=Fsn1Qd}DrMr>t?(XhRY3UZErMu7C@N{@?-9-F*qc)?ssIrinD42W zeSmV2kyHyJWzLY0N6F87%cLY~N#$RS&Uei$D>on~H8e0HM?|_euxMQ@`>UU3sxNrA zh|$bZ?V{^E@IXoL0oLmg$37)EQ{X*TG!o$-D4qyBQIty_(SQv~?Y%FBFCELi&)V5H z1mxHpOx<>A?RGdy-|$4dYgUYI1b7b{ctf{)qc2^PW)7=gP((q=ZuY!^M?lye2T}9jifrt7;S5evSLgXC zvES16YH|b+4Es}eu&0+E(U)5Lom=x=0p~laJGpvvY%2a}XjE8eM2I}-2XLhnC7sL4)yjMZv$zki#G~r1i z|Iy7fODL%cBYqODk;x&aj~>yF`{U(VeuESc(d)-*75DnkdB3+J4EL#Dcv8Oll`MaD z%`TsC?a^oH2x!<-I;eaKMdV3MC%d~3OK?7}OXhMp+?@`WrbC9gV*Dn4&)uFGHz{qy zAg#sDW)t_xd7AF|!G9_Je~p1i|HeQ$y{-*G6iNbSg$fB;6tqnsK6QoNuXvOvQVcTK zcj7{lCCeHupp?o}`h)MFw5Cl|fC7b{W^=NJZPHk`C!DL}$MJ&YosX}Gbcn|G7&1)5JGOXqD&?DR{Rg$lpGRx#Uf5FG1P}pC(@)0uwICPh#RFbRDs8f|HNIg*IVTk3_p9tLbolWJYY^Hawo1PSS{Vw<$ z`E`|Fy#338F=pu|Z>0d23p}d{sVb{qH5N*)4Amy%)9qNNN}Fnj+LMgC3v5aPQRhrv z${unu>Kk_X?keuC1aDK9uL+sh=7}RUr}|~3DS!6Agw!rS;(vVlBj~M`r2Ee(>G<>$ zPCUlxlA-d2J2(W^Iu1;bPODHK;$FTkLra_T{8M@c_i8HxiGV zk!j+~nxdcDGv3s2ph)>~>J8HFI1MEO3lAwa>QM6KkVwoM>`*J2-(Om+qP_YotPW)y zLDoaTOn%AS(ZibPX^-naKX$KLo6~K+wEo9I*X^V${DVlshpcwDm@9SCFrE85wRUPA6to?*O;*JLKaNGHdRK z9vZ_0i^x<8zA=>GF3lDoM19*W)F)v2UBt(mst^v=+4sIx9KwSiMJfqy z&q)@xOA`ScL1ZB01ov0@ET9f?kxeQztl9ofe^~t&_Pz~HdA34GS}$lw1ztr^0ahVE z0qk1`I}t!}27hj)A}9X!tLR-Io+%F&={7o>j@T!TktkKuS1#?}I4e^dS)aVNNH^!$ zp4OCM0TJI@YpD$MpXg8T9v>gQ0@_!z>ALTAYP2GnVctNsPtQ#mQ^%5Cc{GE?uKoQe zZ{NTM7{(tkI!^Tg@Q5wK+6sGKh5ff&QHv(&{)pJSSmcm5_;Ag|nUxY#0SwFG^0lKk z_zuB^yOpBaCF`PQ{a)cFErA*qF+8S;BaAW3GUt}2WC4dk5nnliDA z3&bW>Xk;TM`qP}w$xEA_nV1uhsHpz{FJeBA7~h%yF3{8v9Gx^h(azZ;lswYfuE9TF zx>r^pDb$b@p8GI03&K2{b-SQ8B&FsFy|?OThxmBmxiE>+-C^@N(W{09G9{$i)r3+% z3VwQjsM(eU|cdQw>S*Xz4cU!{q(1uRiZi% z?!m%>8opCWr^mn7c}(<@82h7ny7=ZLZpSBcWR^QQV8z*ZwV(I|+pD@kyZ7){n?PUT zd1l8!8blO4q`OU!oZn-LUKzM6)~lE!4}7f*T(2G~>FVlAo|_BllMo|Y=o~E%E-%k2 zFW0|0ZgF!um}&NO)enj@(i*T=x(USjIdO2c+E_J?>%4paKLF-(-OH2L0^ECyRXHYPqQHdf|uG*Tpvl^7o1 z{s;^eiUf~*B_5X)Z_7nneWoLd@`>j04t>i$(nz8hL(0p{O+^*h85#uyuJ{t@9<46N zPM<sb1I8QBJ%^z|2ulFC#4>X6K0>U4`Ze#;oz-x538 zxfe26(amA+*q~#WPL=#L&L|wgT>jITxWLc=g{lN3q^F-nK}2kzAcB4gwe*(UdrxFG!UNJJ~u|8UVzN zRp!wAC$x>p*?uDMJb6tZn(^|2^jhfsn+eYo=ZE9NA#1R!7W{{^H^+XDeuFAONE%Hz zqkMLl*=%rwKA5qiIqKmeuaFB*ovDlRdnse3^`&>`Vi_-ymax$NW-_IBrvmIN_NHKt z*=boW$2y3abymn2Opb9Ls#hC5h(Oi_!g)8Z3PzoDks!VA#@PWn z*t$j3*cc(zVjdG7Skx_!$W|7gr<^0HoN;?xEL-kZqz#DjnBjpdNc_UFxt(jTK9vK` zh7uh=s@Jymg68{Zp9xbyyFt}o9o5gpom}tyl(fQT#@7PInXv=Ny(}WMG9=-IWs5;a zzhry!@B~y2w1WUB)1AwmJ@_D=(lL|Kv>Nhv@9Mt)0B`TwLy^+w&2aBsJUn3Ode&Ypn_uYP`^}xvucy=& zEIsHfZ`D$cG^#MF;@fZSb2uv2Y-RH=(C|N1VE(w+b84ztNYE-UvD&h3F?kDB6aa~A(hzt%% z!&-fl^s!*X#o(xb802%Sl3k2n3}x)s?c9Pqih_JH^BvPotex+~iZ{U5J>@_?>G_G( zDaq+d`R>3)>|DZWH)_H(NpVo#oGXdB=IEQ57lta|yU?DVZjsR}b_%Nz6H+cR;$8kz z-l>6LZ2`Wzn=YiuDtE=RR2iFVz37Y!j zeAwM~%TL9gUbb~KuZ`9Sr;N$kHH}<$sA?87=7z1Dl{VKWIk*a(m8;z%|5mCyWPZI@ zQTPZ!zr6!6wjTV&@4Cdi!dhwFaqg@|tjnq0p7W4G=v!OaALW1j76B*rbvD$0AK}v% z5141H7>l2Iy4cAkU@wR}v@sCOkxGKLdiPgQf*bkA$aHc#!KoiAk8js`{*bdgPG&`j zfRR};R;v_KqhQ#q>hBR|xM38z^Gth@Sap83`WP2amr+_yrn4F%SeRz77 zWKg8VWM^kD*Q&AF8c4wHt*NdC!UMg|J`zQ}zo2yhdrt&}I3yF^9egKI4DUW4WE&x< z;3eQN<2Vh}yCsq079~a*tV9=;y*Krvbl-JBdXo6hxSli4Q55tWQB)BGg}O9mn9iT- z^VDb^IdK6^9{{YaYG~BUaB*>gXgB*Iiv=lIo3Gl-z}~>&WIeN+H(1PWbbYy7{G)fc z=YvP5xV|p|zm->?nksbyP#Ko0z1LES>+gCQqsZu?@}XfF$wJ_|TUpqd`9hLJSH_!Q zDa~H?vJkl*r0|8pDduk|Qctfs$>-=t__Sw#<^xW)C-<^b2lHcPo#i;4HDjH#PMv;X z3zg*q)TK_z=f2RF-Pq-CenpRJNnX$eb=f2C?XtdQUZ)9{N&KYCbMidR#@9XO7ccf{ zP0h|laayAjJL?YQgC)j_#?O{6uv+K6jMSo<@^u8hMJbx7KRku1(Gg^>raB@KcW$}1 zJEV*L9w+kMtE`2W7c{l7HVk_pDS3;vep59lCuw8Ex*FVY+B+KCk5t_2<)GU7vdHiN zV;lQ~sr~F7P!-F^-9$)W5GR-}MNp4%#C)duw%k?3Mi7||wr04YN`LvDvtmbk{e;`> z-&!H_%G1MyuIhJEnT-&&qLea8R{G*tUHAtvmo%nmelL?%D|_r#Gj&yW=Vj`)-I;CxT~s30kE_bbZZ z<5Vap%EZJziPvYz5-j8{f%KRf%Iyu0 z?ku)??yn%CA{}NrUR-b{Ez@vbSY5Sg<(Foe@xt$>mLr22v_&|Ro*JK;n4W+m0Ac!- zUIFQGHxF;H{WRGUxz`-8@u*-bc=_-9+uHu^B?}W(sAp`w34qpi3{%P+M zRjA}UaRHEBb=FfNNF7G6Z2@_)47m`gO%=*rb1Q?al12iPrp>ArCSN03vm4jCozRN zg-)Z7q}?<=l?$G z|M#*!g@4o`y&q;@;mDA~l*jF@*ZKTh`dCpYwZO?4o>H$NXXau-lcwyqeNi^1~tV`J*B35|bR{uJdEW!GnC z7iG6pw3KC!=Vq+6A+cc}js$HPp)J z-3&kE3ZTQ~f2Jb_Lx;WE+4~^p?CcDVG@To8iP>6Myh4GjoZNUcw|m%wf>S&Vj;91J ze1Vox#m85~BG7>}#HLIsoogC@tTm;j-~S#Q8@Z8`P{|p0Yt{pwgW<B6D^kcJf`pcgC)e!bFxaLhP zHY0*#t`}6-K;Ou5qA=Wc5(@}cJ!|w-`YqCT7-fBXv*)FhXC9AX_f#4m^w*QI!S&~G z^#c#Z{hr4!p6${EgrxVirSFfuAa0T?Qb}F`(hku3z2fW;sPInUwcyo=(5=nl8tyUU4Sk~Z{u7`X{%w!Lgk;uT7RT+1DNhYf#?vaY=Pu|5`V%JtFzzCB@TBc0AImrsI=y{^RO$?BnFP@B@wtA|jDu zQBz$B4?jIWI}I~G2?;w1FFP+U1uq>p9UToTMnwGPkEy94@WgLkZf;iR=Bm7rK?8B& zvEwvQ`Jk{!I=oGQ70IutIBWXjgh~e!xYy)e1+Rr3`c6GQ@R2 z=y31ZmD;*fGDo@B3QshCPn2I4XH=|cg4VAhfk7rpR$uR)A}#`%Bq@;pAP7-Lv=sdo z_UuTdN&ye=%X}a{niVY4&bcSr&AEkfCsiq9j{cV;rIpn}+>_C{pEtHKv;XDqbs-&G zC}`9_^@e|p6dT3d1bH7dgm%a`s=Av*6nVUJCuHz)Vd9EC?&h$fUjDwC0^BNq2V z1cu^eeOOOrWrob)C^xJix)iChnN^UH-Qg;InRn^?W6nbmHaJ6(}5F^%4s!E3kP3GCDOi z6`a7RUciF^ats#{PJ;#N!<1DGK!ypo|-&07)p+ZH7|Kko2lmnz3Frb5WBwfy& z@(7Av5eT_ds4Y{k-FOf>LE#jDj1deo(+fb>>P}4v$L*&JG-!h^-tqb-V}*CGEvVkU z9fIp%M+p@X%NaLdI92aGkt&{6Q&m0t&Ece-A~Q2L2Z|>wEG(Eu+`4!~6$OGpry`b9 zp;c<|murvmk zLJ6ixotf~_BO<+r?{23FLuK3HI%K}0ZPkZ@>ixnx^8uh2I*DE0i(QV?KDQIPlRHo2 z?2hPbQ*pNWP4+?@;@L5ixAP`tPZROpE3#pG8IDG81^a1F5Tf}c!a%!4Xq)(gnRTJw zj`oZj+>vANZVgq3<=R1f!tb=empzN7_0om!H=*r6_-`+Gs$JkK`gP)SA zZ>L@32@7&@o{ct}-y5<_QcmJ0Y`DrRfpd|s-%s?|Nw?XR#Hhe)S@^cfdf6xS2-k2n z-i$`imV`+U9Y`FJ!g=+?2?JJ{>?q#KfGgpYmi=8)fV z3pVuG`HFhcxrJulznG##QvL^Y_`f4e`s07vnQ3+Xv+Av>Apy3VzP^xtllyn#DwOEJ zvOq!FheJRB_uZp=Lj71lCf4bsri<4nXjOP za2he>T^g5waE%9l>@O5gX;IOcM>DJ2`JESl0DM{rmOYyFqIxG67kL;M#=vgZ$(piy^maRIV~Gx=1?Fzg<*!l-Yh1f!X6 z5_To?;$BKK>{@O2$EdO)t~!n3G(K-4I(pORM>#GsMIs@Dd0p6)+(!NsN7ErbMLyev3LnBuLv#Y zoYY5P+1N<*GC%9wm63Y!*FI-&5W#Vvc&4i(dm%qG^gs(%q?$;K^)=Y4Wt+2WSZ!*T zM?yXE7P_7Gtr54WfI-c2-LSYtB4oy{tvuezhTX<~>4><#~N1m<4j^p@ZLT?ZSK=*yE%G!i#X4t(l(thYUxXW$05j}lb9TnYT$v- z5hYG29FR^hB@3G%wzP~XsZ-F=q5Mo+NK1{3fe`|KK6r64);CBu*j~*-(MZW%%s^4_ zb`;&jG&?3GC8|2la(-{mf=~{gcrtz{J|2O^p2A0oI5vr#EZ-o;(k~7QU(^~Mj!Q6y zS0m#N!3k57{%NTZ1Bs!g40M>iTRj-~Fo*7k2CNC&=u)Nv`7rdFDEK_*@srsM8<2F(6P3U@hSf zX*o#*QAn=fcNNG76KABQrqn&YtWR}<_50bC!V;HvhZs0y(Cn0rqsG{37CcLDL-!Av z1R!}^?mtmwxYO1f}661O9P4n$j&)Nozj|7h9?Z+=m zw3vY4U`x|XteLmAt>vDA{|QvBAPX7HLq$bJ+1c5A9H8B3r~L>u1;YLiUf>-UM8h%L zgTPwpRs2^*V5!Oi=t6!Azd{4l!)pdClPXY2fb||hc#?%BfIyM1c=mt}a}Xt_@ITsc zt_+}x1rpkmn{wSom;P9?wKs`|$>1Hq5Pf-l4K(Jv@mZHuAU*>G6UNz7bKtZ^1?gw0 z#L3l8?zuRs;xgI1{iHgrI^D8wrSB}QJvi|#ulcDtVmLytbyof0V)jm0+(y{O+nAUC z5b+_GW*rHR`ILq23zQZO|fV?r{9dVeE3Ky-C0DTUkt=5e%M4Ld%)20O(BD9OYEj7kSF=FNdvG zdCPa)<@D;EXhqa=LEX*cSDJ~$=Rqkim^Q|bZ(cr#q3W;oT)Zmj!aHt6iArvui=M@O zL7EE9da^dyDD21*l;~ytA2f8wodZ? zEIV-S3z>_?*qlx1oNd}wBCAz6uT{ABJ=;S`sf*Xh?N0)Z5Lf?Y-?yvlU!O6*PWYX_ ze{Za4?LGDd!%KAKPmYPzVnWoR)QZ!Pcif=cU59id+oH|#tw{d|-}ub0jI2!Umk10I zHdY1NWona3F?vcxaVl1#7(eQiXs8Ql28+U&Sh4d=G((%JHPp0z=t+m==5<%D3rQ*x zLGnalh-IV)&o2f93{&HD@Yt+c|rzzAukafK!rH4i;L3#p#rgaa*};-Sswf4hfyAOUMIjhv(Y^TAb}EO z)M|-^P6@DbX65ScnB%g={t}n%VXsh^#M7_M9{U0?0@$grbnV}UTH!HasD&n~Zth^3 zn40C0803wFwK_v*{#jH=AXRJS7>BgvgDM3bj_EdG2bSMSrr zl_(G(*3kmlZ4cxPC|IL%@a|$u8>i@(*?U`s!wM8IOO8vVj`i{FF1C>w^z2zoQ z8R#;)rdBlsm|rKzaW&|CE-xoDge%*>xC1+r{_!Bc{TULm`tQA3K%ohIk2Nzr{Y?v#t-Pqn(#i_- z0{}-=_4MR+TdJfzu;;LLgR+}xZx?J`IdQDF`tn7V98FXapbw+ZO4JE}`-D&ysZhU5 z*>tSeDoq^RGO$>+=a7@A_u`=e1q?)SWvT?Bo|24wVFA+;Hc&^6TdZ0~)h(c41?kM6 zjkG+T4^mw8yKH*D2eUz1aL2Q&9=~bbim%dS;_=)mu5{KxuA)p++%vDZ-m#Kyz-99J z2iyUvhH0`^nC@X|J8?;=gqyEhzG6AIhFz43QxiEl?PxmJRp6PEwNw5{f>E2lzI=hF z;Zp;b=Ij&nZqJ971ZH^KhvqB`xqUB*ZC!eZ;G5uKx5H^8ZdEOZnVsPV8>lRf`7OIc zUZ2}!E;60Ad2BKohGo3W$gk5v?S{I1hq_)r-sAZ^4aj&|l3#0vAPskUVy@eCNsiB1 zlDTN^v{;7!-3;-8{;-Mj8x2ODMD-AHk?AEeLm(1jKhj?4!D09tMF7IU4PW}a82P>W zgy%_ZC}4DJ$-Z{;M*Ww1*2pE@Y&C7}5P7)Nwu+=?Uc735x)fD$^xT$Fv5s|2s4QxX z9yOB$b&b(?Dd%NB*r2o-Ww{$@tXeCM|Bc3K8A5Dn#{t(Y1*$_$IYrhTmBWnBdNtj9HC`21iE2v>Xlg}X3S}#rL3FY_jJuS( zl%h{m?it4+C_facOo+yL;)aB|ADdFM^7__v?S)u6AEz)V|XU6yU+GKno-v z_MmY)Iq7k|#JVkeVcNWYQSXbh;!jNS`IfW8-#v86JHn9f)AdaNs2u7$VqXMF3iEzd2_WKRtD_YdTn zUxOxk^iA|=F`>Bwp6?|S;{}R^tJpNaGj~cW|12LY;P$L zB+#2g$WTM4t+uoWqrQn8930$DN4|8(7dq&Xq6*ro-abc-bI2=Bp+K+SWh4)8+lwpO zFJC@90Vvd?ITJ#enh$jO;0GLBf%>!O#Ky`h2$ej!_uY>+s&~V&9@G~Qx##R$GkXAL z5F1r#&ix2FaTRYVuc1j4DYmf?Y)^UGiFF zDZVyyi28+|>T#if8=baXA z*(MB0_8SJNO5sTr=@L~8keQ{-k)q+8(WJ(NU52EnS%_>QSV%L{sX{T+(W?^2fI%cz zLJ15al!cUF7U?Ue?4$2J&NFS3tg1xD7u_Eh@K^RgMQn_cmk5gp*GI;|$%TA18%jsv zBth+llTGvZh`|e$&2Za*I*S0ml}Bw2$dt|ZzOzAG`{)0?t9(t z-TUp~a70$z+p47h#s(kvp(K+xPDheMc}{%p zF1tM;PRkR@@ZuJs%imDfil!%$CbZkiH@3ddl2>^Vb5V363R-wPm8Wr5Nb9AOwX!lL z?gupB-}(N<@PC63VgIQRI-l( z6Ia@BPbICWA`e1>1S!BAOo9yf2M%5f%L@?4Fd%f+Is+?PRBw&~Wr-TiTOka17^imV z-Sk}0;lY<~vB-928fHj7trExdS=D4Rk$Q+w%o`Ib#*#)QBaY7g)9)|YKA+!hA#-*+ z=x{Iqq5{kfwzb0f$Xyy0w7}RS8H@1bK#2}tFbNRCPCD`Sp?H-zk19R$3CjqrQpLet zqzeofWyK6ha|WCrm^t%if9B}af~R{H4%3(RTmW5TW%cFJ`MDveVS8q~?6?e6!DG=S zfIX*+SA2(eCFQ;4NjM1i`#_mv9I8X|uX z7}!3ccB{l|I80PSYOUSIMCc}pxqql6g&s31OP5?a;#8rcO*n8f8=8~j4spSK4GQ4I zD`+Fp3j4NqhwJ>Vpe0^ezb8iBVUr-bwP4>0JtnuQJr8W)l_7JjCv|m*ZPbB8q;E!r zq^t3?CGdO~Tgw4shyuUQ{l&;-Yfhq9myEt(A$qW&@p*{SMuj1P)4Z?$kyLAU^d+IK z>l3Vbnpdc(_5;J}Z9&Fuo8V!kxOFWG_hHv(oQgp{??zsuVCQ|d_h*rTZYx4fcI12= zA1}WS$-GYR0sINOhE)Sn`Dskb?ML>FlkRG#VCNa_KZSIEcG-^{(hkS%=5ki5d#xQs zTIYX0Ob(tPd%nmvJWSkVA<4uS&y;*64eDyx{Rag}gkz#J^Wem6{l@8?CC4sV|rq3mX%eFpr}$&Fi!=AS~guKCKc0wsR}5_vu4Xk0-LePM{nf z=;F#nr7NNAqZ*PMl#-T`4GWhK360Q3M#JIt6?D4vGRW~0Hy_RH3>W(r=HI)UdrC&+ zve)ak6XnHcv%n$%iBo|jK!oxdWb9D2@tAxAe&qz?9D#@=ju z@U);c4%EC8TrDoC%kiSqZI<#{#{cRoW)=RarGTo4t+BK|?`|%qDDNGNFZtH06zgB1faAM34@~`jO)MjXrA2L zJR>7itk*$YlOUB`IC9Aumxv{8Q>)SXzzpV+Ek|(Tt3JUbX_u&Rx z^(|A%j|~ok%53d#63p>*9R>V?WWN+B0jqmkCWK_pf(^8lD6`p?*u=>l{J>sIJ2=5Y zmo(Tu+-Aa5K?^k3?ml#=p|6CsX)%G3q6IBaYHt-6am3KrMlJX%q_by%{6iz!nL_!> z-?6E&ndO;<<%OB?nZ*U2jdF*E46SCi%Y8Wu&^|qQwV*9*il}2YiO7>>Jlf%Xx%tr5 zHxV}>=sWqrHI503tlTJ`FXES)I2%r3Ah}0OsNNe|BnPE8SFmRqps84h`Q_BrQ{u?* z;?u^l+@02BO!0@CSh2Q*&ZrS1bvIPkY#kc34k@>9;>PHIZY;|@ zzR#H`AMTn3u;%;4+?R@!+k#Ky(>JtTwg)A(dVi%4xg?sZJqNtyG4;HQjUHtv)D|)$ zq*-judya;z5K`4)&4WrWk;U?!%o;{zZc+u=^>TjowoR2Q&a9_k zYbnao@Z{oVD_QibOC7?8%2GM|^{G%Z^>vB8+wYnUp=O|`9j}k_ zMvBBKD>fhXyy5t zckVwOd@f^@EYj^XJEtzk^R*Jf;v_F2Os0~Crh;;cavm-oN>*A%j#6GmN;*PD);eA? z*0`(Vckhk1hlQ6ezix}1sjx6P_MmJ*f=R|V=(nQ$I#&96l?%j%k~vAxL&*!?VDCsv zeQlSX+K--Qi_P%9JXhSlyc(LW?LYA-*$ky~u)`zYr3(dx}THOib0MwD1sRo834sxl%BExz9JS2mef;e?rZR!J(boR|J0o5qJjE9 z zZvwxR2F!&iGA@n0Do5|R89#n_lDdo@G=F1qrZlvR9J7*hw>Pq0dkqK5(q#L;k1h>-y=gvnrM;vB-|OUWB- z!3?T>yBf4CgWd^O+%9|``*f!%%r9Lo2bVT#MoEEgqcUE$!_fG+%)OriNTmRaE2GKnwUAVV%lDdbvz9+e736PX4pa@Om3(gyLWGFC1IkwU% zROAjYvkqY`uVxZ9vnmS2XBZEcb&7h2;a(A{_dTI$>9sr6d@dQzs|2h5SIpg9lh{&v zfz^4ANlN=|$9W-fu%o6f@oe&VdB`b2d$_ZdxS+I%<@ zM#5>~(lV}S*8#PTKp1lN&LOn_UCMl1Oks|qDtjACxe;bYFTx5W`G?4fxP;UANpe1l z>?HAmZUIXL6W5ziGn0H$GK#LAUNQQRvS^IZWcWbYUpF*JMB@jlG$&XQt;x)a0zh%)le%AqLL75Fk929Km^)v0i+HVI05M z)h8kOZ!G}UPzE=WsLF6Av*&es3bVQ3^Tg#|jK9t$hp&EQvzCa6$fna~a~sL{?f1Ie z%{R-^=qivBZM_wt&sqZ|=>{V$Aq~%R^H1^^e63$+wDnQg);Ijv8INOJWyDh?cE@9G zquSc!QGcdrTYXGfah^_@c z(L?L$!1gc!>WQ!XAy$)!@3B6eq38e8Vgk^?7g(UmiO0vs6&2{8DHl_!{r}~y$<|!e zWapG+M~?3CUCRi66*m65k*m0(0hVV_;89+d>U=i;D3+)68sa~O(`L@|3MNj$4agTs zGvlSmf+>7V>ve3a=7DSiK!!pN+PiD7`ZY_{;`&+Mp-AOTfPMl*Ke;plwS(J=JU&=F zI#pd;8!keeAO(hrLaBJej|$vnI`x$W1;O&#>qw=u2RPW+)mldt{Uoh?{9jo}sZm2C zLqvT2r9ia!?9|lbZs<76kxSzp+WQQY@NOW1FsnMlFL^9bDgvbjz#zzB)adXP8niJI zLuOUOX263CG#P3j^h&D~(4-#`V14+FD&~wTaG79rYpg(x@bcne5w>))M(6z3(1ms8 zuVHiwcM8Y#jz#;4bY|5FZ9GzmmAPiBE>BGSTXub#)jg`?c%{m&5+9SWW#tg41}a7v zf@6g!QAM#mCUPhd)eNbJgM4k0;*0?=Rb}^7><6tk+t?pICSw-{x;Ytz)%JlaHpQoe z4)6DbFdOzBvCSnsP8C#~vY%feO;+A$&+x5z2f}vH+XP3_>P`JXt@DIgl99r?akAF= z!1c^y`_Pl^0RpFlmwwf2Wc6#TH!{-r>+qTOkni{A=_$VEar%Nmeh%d%T2hAs@2FoN zOt=Qf`4f^q;dUaLybYu{g+Jd%iSnB+U4<7T2;vJqVN=dQrm z3;r|Dt@lE4c9~d5W4l^c*;+@9Z!dW)rlRgxD}64GtKu9kUGYtMaaBoou&8XikB0Lc zX%~B1oudfgEhpnYM|-O;trPhsM`V8Yl^f8hB}Xo#DAF?F{b3RY0x%hR*2$-_1UrbQ zy)++GesbcU1BpXDDIsYe-ki(HFl?o5B`MANxiF>-YG>l2KSDA|0|}x=4tkcFYKC&y zs6yo3WL=*_QuygT^rjXmGsEP>AiYJlJY1+-8xDYsgia_FQT@dhqJXZH@ym>HiK&NH zZxmrEH{A`gduVg<`8JHhmEPfgFs1lK>CdBw=?$mM2E42@`_Uyef*O^iI@lv=YwKf1 zi5ejrf>At(&PJu1Q|+YGVw(ELS?0uaAFvic%4zINgWaG!^OXo7Z5nVN@k0~i@!d;Yh%7NlkR3b{T zs9^yLZ!VktsZTL6Rc6E+f%O;L;PVk=At$BBCjUp+4IObI7T%>=T4<+wLuam*)t>Il z>Ab-k+uD-+w4k?skxvC5C&remKBJR@W zli9~6p}DpyXec$pjp}##D|#9GByIwJO-Z#q->l(3(ldmK-brh>5-vX^`HA>$XVDsd z{hvjo8ma(06nOu$N_3zLH|;rq5Q~wG&8$MhjokSW3p7>Gov!w$zs!_;;*Yd6 zG9r#wI=k4|*Z>)iy&P}>?PE(z&Gu^@+uLRonfqW|*xz5Yt?f4Y_QMfOE-KXDieA48 z`_ocSJhP>j#>y>00^#eac_`1!p-%S3+-WHY5CQCGhjuPHyqR( zk#O*9iw9UO?N!s43z1sCZ|D#gipVo^J*wg#M>5M}B0a4I6Fi>=e}RXm4tw8CCQ3Qh z)TE-RDHcjoqm=#~@jH6=gTaebU{}}??NOn=_BQF(XQjy03C{WCi~>8iDb_g#2MwuN&dP zL`^XTF3Mj#MeX#^a-!}}v6;>LLyz3pobtvre&XYn@w|PiJZ-8xe#u3<_y{s5LeW?m zkFZJSuyW2A!O2wDW~%xNGE6!WjqrZ*VN9L z{nw2wg=^;AgeU4syJQTrATm$uR@aCX)k;n;z=QsxNyMF$i{H%0+RNHeOUcl^EMF_z zE{ArIB_dnm5^uc(x~l=NYUYvG{1#twLp0uo&KTdosq}S%1(~j%;DD6r0BS`^osyD< zUW&d_qP9l5vO;`?+wbyBY{J24no&}F+~KDO&3M70e)BN8FbSXMawV|a%Xw)8Jmj zU+_rM6aN=}VXm^OLZX;7_EiEA3dFbvsa0ux} z8l<~JM362iK}mVHzkBc8`+sN7C^LF+)cNl7?6p2?Jqw_n007RPl7v*05OQZ&$Ex4f znfv;7l$Mr)jbavD=eQjdYw>ScLA?Q}i+qwL5LDXqeyJL)3vhO>wRTZmf>l?a6vfTd zsV_TETxWq_i;IuPsv$lxm~CnOcn)|^5%TyI``x*B;=9ikxKv8CMK|5LA&O3k7M0i;E2xH*xTCLIyhkJYTEH+m6XsI%@C`Q)8Q)c=kL_W z(&op|Nebxi3sXwmYg3h9WO_R<_p4Y;UC`e^DO6ur^R)nfmzC#p9hQ* zlxLx!AP{U(7`E68>jbR4DQ7J!`imzTnfN(mjk0V<=I`%$F_kg@3U)V)+BRpp%f2c? zM`VBP9Zu00CmQ}3A_?D^`YCOVNPAmhky3gAJK=BGq&<-Oak^%iZj_j-osevlk!_Ha zZ({sbP0x^#Ny=VJ+xQbRi$vxwwu`ZzO4KL`&ZI~>^pdL%Cs}h_j|ne(+guuws?n}t zHxwmKmM77p#r9Ft6)P?MwzrNaa4*5#7Ek4!TYQ5Me*aWuNf_ zcc%NPGL-IX9P1xj!09#BKOFaFFXLPbB{fyYI#yvtyF+ZpgkdwhJSQPcBd^7MY{q%) zHANyG^*^?5TbDf^a=7z(_Oqp-h4M`BkMhtl8<1mol1yYY7CTCFyi{EV;+^TR1b*dh zLn&mTOBZ5AR5vsXotU|xmHJJuc5ChMyo_;(`oREz-GwKIY<2g{;6DXe{rCzrgt)D& z2RS)k4N9nn07XUK-B!sVrck}ALcLxkbHuQ`5P}a!g7xLVa>jEmQyPoGMS=L3QP5}7 z{<}K9Yg%oa3mO-JNFEbnl&n&02A|(oV5MN!glhTMp>N`;Z~1y#DV8bX!@n$5bcndE zA~swAQ4B5Sf zQy(0vLj1iradUA<1bh}N%LG2a_9mjEW5KFo`6>C4u_;!jiPTXjQ%T?8Xovf!W=C(+ zRI4?lak@85r`PXSlAUPnA99v|iMZ@c`14ueanZ-E^bdB%;TO!cNOTF`iXvp=uSRuV zBR@V{-?(%372Y0xT=m{p!NN3`q%Za`cj~D@Slf^{K>H(Ps>w&{1seRaKOVj57Zaru zy*n(-KX<}3)BJxY9PzTAM;j!6cHD>CqZ%opF2Hn47NQz)9XNp9rpwFA!^85rx%|Ge!yn>o&_R|yHc%ntMcd{*aR_{k z!z{asFLo|(?Ntm+H!5GI*oLID8gyZt&zUn6CYjSMz|uXs3Kj+ZYcF2B0B^kU6$R@bbSebmDypkNlbV0G z33ICC9Uq6Nr5>TiK{kLjvO&t0g;G6!h#LT@v$LBX?VZK|X$9hLiEZ2#n7ZhL__9jC z?*uaxKQ6G1!7=L0^`jAobk8dswH*k%At51P_7lvF6HCyq`u!j1%9qV{&p0HXLlh-# zT$8>I7O?S?#W~wypv>CvkPV%qH>D7@9GdOX)i0s7#rG=#h`jp4&nOV!aOwTdy2EKp0i}5W!fN(J_FMdsU3FQg( zp?3GUjPaI+(aT!))OFIpczH8#23)7K$LB~QsrL(+e`u*wkyHyZkFC`q{)dnt72j_$ zr<5M=KK89;M0G?gn3nPW?rBm*T`JAcC#b^mkm=*NQ>3zmP@f2f?4i6Y(c> zC+>VV+Tg{$M}lYlNino?V-uw7Xhj>x#!c;y~>o)*fA#(HrWGu;)nIBa3f zZ7$Mk#tStn?x7rafCVXWKPv(f;iz+I9I120jz+1jq06M6_75f_u=p$`#%31 zjaCN{qxh~u^-S3B_A-;(YCKcK$5CrO_-5vxJZ)i7yuE9grn?PjmYC+*!-N~s;W%<{ zQ}}KSdIrQvsS?V2!2gP5?YdET+)0g!~->CqiV7l#n2##+h7FoZKa{-Ivg_D51aC^kH z=i`^hqQ^KK70Cb8iqE*2&(JB=&wt<%TV9OOcUDzbhwr+?$|8KvO2W(RH-F7DS)`|lr< zKp_9`?cnX?$s_@bj+>ju{QRQUlGdG_-ChbDatptTY<&v%Rcy90pSdvmb^NEYB7gLbWo zg+7S~|L*@bRwdXV;g4#?@Utsiw&=$XuoeplOF$)_#v(^64-%{HBg`C2V*`I`wsf6Bl3V*4kg^>?HZVLq zTvkplh^kM{s=@2VHHC?Xhi86%9&rz^ZJ}5s!e7h4U~JAhSEa@CeDlYTAAsGzy#+>iyBUt05#9Ix3?!Jj?Ruxlqe22H!6OGQL8t}PP8o-{-ApM%f{*j7>!?%kbo>9 zSPdj5;Rf=F000DU0?3YveB>)MDYGu{u>mMxa5wH*xgkKL^@hIQVG{c0z>pvD_v{N6 zk&&B=xw)dNtG=SEx1y`8zP^sPzKWHsv5t;}hmM(t2NiX(z<|I?Wb*EAL1MZAT4N(+ zH>^xt%Mi6kOGAS;Na@$CxtCrP3>G8J4!1lUbw%q;Q%{w!hblv^-rCvqp=p|y=)mV+ z@Rdx*$J^RsR-Mg4?PT>rzCpCFY!YI<-LqBJV7e_uD!!jy?z~W68}3Xw;pT?00!LpY zW(deftF4&_1Z3s-UbWFD*HF8DExN!yG@r$su@;(ckcf?1czreQcY%-mofq!|!a?37A7Ii3t ztF4z=M%ltC1k#VsX=awMm-|!t8!P9JVaLIv!5WrP{fr)%8gbD!LlbBm@zU!wh8z|v zCqx3(nk!Rgl`K5rj#<^}Nvv|8?_*k`svQd|4&^5yg2Ke{`gEjHNDApA+5^-~!!ixO z(78YSn&WDq^kT}3H-hG2d0jSGPyM*tr-~up2C-(9=*SGxMY+dc>YFv@SemHU56|Ue ztbrkTZxbr5nS|HCHHU@Kp3x1*?wPcgn2Ac${7if7ZL`?M?qu?LFR{hB<== z<9GBfSZ|saEi0x!@3YC5!&dVIEkCm`ukv33;a+Tu!l19@|IIn~Jlg#?9v)WIcn-P< zb3ZxukGnm#_Kq6exd0SC*t@~|elZ4MZXu;JbwF*O(JrdE4*DLUT)VKpyno1B!9Y(B zG^tn}l9xb%PF+6*wILeiDSIYEnz0H;^0fc#d!34)G?m-SNT>fo$7eUbAWXQlDG?sO z=D5dS4H7^0d{P@&Wuzcrhd7D=!;KyQy+k!NSeF@;Mu^%)pi{)V6M%HcArj?UlB2>s zj-2n@1#^Y(fDRt$_UZ-7Jk=#lr}6st?!)lt6!=Smcp`xLx2s6B4w4D0@+-1dBUqBrEeip~n4DJr@rtK~^F9!8KHAWE; z6%`c}{5mt!TVDyXPbdt48E9EGivk8AJ0EZeJB@4R4j7?_2M0kW7hwImj;<~@1_C>_ zGh1OLiN7s)3-FdP}+XR zj3$5On0lPN|NDn%u)lv`aBygVj-Hkl>C8q^R^N^==Cbj)vGExEczKyK9`kK{{2siX za859XX678ja{fj9%%{_K_tHZ;8fy#cDJe)&FP0lCrGp~sJ5nf^r6FUC#oSf%P!^u) zR1UmsXGj+gi;}vos4GY6XL%Bo-0S6@`H(fpL(FWA`a&U}Zw_m*ZVNcX2y58~9~-Lqv{5f#C^pH*oREZr6i!vEp{fjpBQfjhxD(k?w-pxy7O)w!Hpd3J~T-> zh|4#sX(bqe!4DKifR}=;!oi9y_&}4{>~nR`?5CxFkAG!7dpv=5R5YM%V19>%-5mdX zYwTcAOjod4cV)`5l7%;1hDZD7!nMIwtWo%HQ9pzHu5yUx>ZH~iYQ9l#d_o<^+9(pK zFerN}Gn9o6$&%o6*g&Q{dscE%USdWP^kV;J8D3zRa#|E0lLM~G?`|)L%QZ`%5+HGs z+QS~TpG@TY;S?zD8W927^7Z@Qtj2Vt;;?A%v33~x~49uKp$zmp;S_7aamG4n!C4Rc=Di-cj2D_uoN>|= za>(t<(ssAo_533bb@BP5cq5M^UfYCqXV?oKzib4(=&oo`cX9Bk%Wr6@KbrzCAJF>u z`4ncd|L^p8O`r`lycrtTPCR{7d0?j)OG_y2n;g>g$-I1g?pA7ij9&-m%()Q`+91CsXN+ z#jP=atvD;R+r51afR7+ET7y+dQzjkY*K?URr;78RGq6}=Lh-88^zVHJ61w?2^Ucjo z+|8}z%`Kdl%JT9m;H9Lbps1*;M&H=PJyKhk@6?8{U7M|=yqpzPHZkr#BF*Owg(wLsrtFfFQnvI~$yr0EOTR}lg_3WK!S&M}f6f+vMQymL* zow;91;OsMchAnUT>D3Q{6}nX+_>^Z81lZ?j?^0%;soz zzPy=A1GD+dL*=I8Ub@m)^RQ2iu=;{p#+RY6j-vf3Xr357t`T-SC6xdb9St2f2X_rm zO*X%8)Bj-s?wx7%yA9{uUvPUifmoCU*tsDy6Tr04l~(@JG+18Cu!NZdo4|_5vedei z0Zvavn}wgBl$ev5o~WB;K+RD-uQhD1@yQqtKHj8AA44o}C(faMp~vqfTj&;VZR)mk z!XBQD@(pIBXSv7b4u&C=MXwA_I7D`y&m*`>PrhrRKr%^jGy3m~jB+By=a-C}FAM=S+4IR8OndyEAh2Z?} zBDnuD+1LLiFR8ulX6?Bnu!;uC-W&z=O=r3>H!+hTKWsw!&Fi$77Y^LW<4eIq+(<>5 zQDn#-aZTT_A{>?6H*zMgMV}l*o3IyCxUF8U^-MSHugfyXI$ZqxUJ#Ju7K9sBTwXo` z-cF-nJ4=5Ch(QJ_;0DgGtmtWL^BzcoZ;zw;qaEZF@bK`Wi8%5apI087d#XepQDq|u zhf$!WiJNq+*f#^O(B}ml2E5RwCeReo*xtVS)8p6oqFM?l3|zSc2|Zdr83F>@=;z7) zv5mbWA_EG*q?6S$f>7zxhmeX!4R)@)-rK$J5Oqpz8P(i6U$_A}SLKBg``QdUt?y^- zn#-fDRE9gKqkxf{-DTm~(ox5+$#`g%(8m+dMgsKJY%wv!_-9nH(U8b!NDO$ze`#yK zmJU_iO2%eWmRC^f>B0ZA#!$3)cR3Hj!x|0GzRortV-&MZjP)$@aC2iJpNw*hPO^`V zu#b+hJ&&915ay9IxPU~1rS0`e)R+3C<9?v#Wyfy6Ki$-!yj7B>eBR97uCHt!N(Q0x z;A9&Z=MjgvEGDZKefmHa6&mc^U`D zKDV$gAPE37O6=YF)Ij4UwY>P|@E8a^SVm?t*Lk0=O?tMxQdYQp&^7X990zi*eOzjJT{#8{Rr5DXHfo;Ey^RVm zNK8KX$WMlRPAYPh_`Pn-Z9uFtUc|B8y6ETP>ScQ7Woh>17^Y#w*In%ldksZRsx-pX zl-=DOYk(Nhmlo{b0I{lQSN7rYI2XlpZt?G5?cc-SeNGSP#-x(i4C*^_`xSCTo+ltZ ze{Mz>B)Kv@o5rr+Mr73JmVV;y^kr;U=RBb>Q7!axX=~(h473-xG&7g?mt+VSw?A!5h8o0A?+KX46rs6m z?{hi>k4Sm0YJQ~K?-Ds}5LLao%Kb7yVYSE3)9A+S-cWua*tDjcag2t*Q4}k~j2p&b zS-1?p9PgjMye{6h!Iz~VAt1+LLN4lZol!`pM}Kvh0R3wpyOaO$M3jR3X;gS9vYd42 zfV5oD;LUhSU$By7=F~nNVFav0c5PAl3R9zkPjl6=|I}A_Z^bX@)Hk}f2HE*4Y_Mzn z%a9Z0im=6CSE$jiQz?NxpW$0PM0RD*mz)zlZ`AvR8~d)Y(ZrrIhnaM$$_6o+7M*Qu zP%v-wc8A!_eVNAG!b1nW)i0UXAIW|EAEm``3H~}?sNNHt>GqgB4M6($#fH+S9+MYQ zip97&J+=rBV=p9Su3h0K7O_h7QaZ)>GKDcT(F4@9IL{5#gOgW(S`iNtO+DA8rc{rT z?&FLpcmfn2V|o0iy|c3#R7S5X4Sw*)Ntg8TqN1eB(_UR&sg(XomxO_7B|RD7OL1Go z;W+t36E0+@M@PRrg}bt8aTWCRR`^p%e$gRHyk#X!q8<7MKul*c22`-eGX8n6LXvc* z7SQHPORdj02Sh|fK+8n*GN_=B+ft!_TkTM`Kq6blI2)>;yNL9FuF~9H+tt*heV>cxdQz z8Xg{D@Ddirz4{svAr~BXcUE?GCO-|w7(!)>jYGJY-S^})$CY&}nXcv$Wfu@-C&@}H zp{Feld|m)2iOea9@z^PaKh;MwxcHC|!L&a*#X3HcWMNIPXYsgU230$V46^O|gxZ!4 zYc1WBtSXK~ENgrlUkQ?kEgsCfdn<=XtU`Su z0`~EhVx*VFYc?qF(CtT1BvfDU+K=cO zy=a0j38v^$Bd8T{rmh{PeEY%JHm2^&;Eayc1@95SpPdDipT@*5b?J#*Rxe zJ(Zwlwce4>^*FR&JIE+!f(*95#P3#qf9ZA-PkdHSAYr+lred&66TN zQ%-17I@)uGJd7!3#>wFk$k?cY%9K*5-{ou67+LA?@G$f`$Ufwa!&f(|82`5(&S^C`4mNM)EwrTV4c+V%B~?7Kiut3}b{k~%qBQl4D)PAVN#9CTb&0qC zl)Vqy(=fS3z1t30-g)!cU~NgF;O4p8^#exIbcnFWc#I#`noM^P9_`~jIrY3#f%X8= zeuV{jl=Q0g!0%Y`*+7xS1E=11UFfUZeuXSK3fz=7dqgVj|1 zTef#Fcz!L2LxU$c<#&-z1=v*vic~%uS~X-+qJq^(Tdip9ARWEMPo?-By)o9y?)5*v zY>P%cq*qNxhyIu*Q65ni#Hc%qskzgmDJ44%s|)%Dz8R44{0nM4o^)@1zTN? zx-gKx0QBLG==UFvV-x;b=Yv`J7;-u$Faxo$K2Duhe=6VfoE(06Rhh>(trO8y)KFB@ zeHt;d)KcISv{Y7JmB_MfOymnyeUQJzkV@-5{At*t@%!bk>8+vo8iN*p5UiUkQO@Uc z5Hv4BjR9-gVK~IZp~xwT$S5db;`&f>sgRIfalb!hSAP-p(eO)5r6r4I%gTuP&5MfO z1v%Mj*()gt!{9D13I!w-7~&ATO)73>MC1~Mo-aJ_=6iTp*mxP}=vW+h{xFG%5DkhD zSV)y~OglX-vAC~T34$h56xa?2+w4C>}t8ZOj$a!QA-xS~l^f$WoC|wzp zJ>^e(TV`2H@n~;j)JEQxUfq)XQZD?rp*)1crK~w9g~7(?P|e{ZbB#N54N{?M(ki$l zZmUd3<^Kt!c@*V*id@nj6lQa%*?hg%8|gccbcXzHy@EPxdp~_f74QcTSV0$4_!RnXyz!F0$+%K1%iVtQ>sSWLr z9+2muW~QbWrGL%#nwNoqN}Ys3Hx+l%s>+&tp*8048|-Jdu|T8HDGKeausCdu$W~uh zJr&*dQ>I3G1rF|nggg%o3FQp2DQ#9xVoF|m9?b;%EFrV!=RxIZWzwxD6IJk52=93A zz+w8PWyI^7*D+oKY27u$-n?dO(yp%{*8?waK2&oWwT?CZ#5uW;yN*8jG1VC+wuk0_ zEm=VP(`clb1F`B7^TPquJGMyD(&dNjSY&%y@NhCq13DdvfEN>qoNb@Y^D6yA7o9{Oy7FiXt_!IN-BAK zYZyCbX(d(Z5M;as7DIiZ@hWdVsXoNvYsrd#`*F}-vdKL*<%~}r%M(#tGfJKBgb%n} z@V6i%SKJ$|N6pt zS9^maLK;8>V>`GE-bDhVdbcw}mLZI9_d|z3om}hMiDsyBS3A|IN~~;A7`pNt*$~*; z(!O@$%M#sj&{Ah8b z)*R(%wLr!Eg5A0g=!|jsY}lQmh)-o&(@?fx*S;oNV!*huCQCD0=iPZ&S}vVf@#G7q z@Kn5>^=HEqH$fr}V`1w_vi3CqEj8*_$redODS!%z;OH+urfqnFWeJ8{@CWGv)#(a( z^puCkdr#_HCTsz`d31^r+W5aZIYB>X-RHVWSWL@>?01{(Smen-QII6;(S{FD*<`5aYHLwxxiHbA#SyFoV>vYeD}-NSjx|S|7{TPq zr5vgHR8N)j#J0Z&9}S|ZQJ>I=WQF}k_FdT|r0axYtY%x8VRrZV!%vE;s`Yu;q&94}LQJFMr%byk3!r@nZYxT8a@mS;O$z>&tyT z+kN=aXNUM&p})P~F9<*W{Pk@oK7-vaQ0$cNiEMh_`$Lm2?pR z2tVfe)r=Igeom(DlWmwS3BakJ5o1!MM#DI70p6&TE9fwqQXX8suV<}%U4bqmCnf+Y zXAnP7`MH3T!U8C}<+f3uy$-l+<7C0#+KXgnzASfLrb-_(VL$cbu*ZYQ)s1THpT7|j zzBjQXLN)`UfyQ_!1y_6RI>)a}n_u1|!{ERByQ$u*``mvp#r>Vdb~d4|53Q8x4ln7< zFCgX_mW@B7`Q7!%{Vp))VmY8Nae!)B=aEiu=KE=#?hA9QPV!#|g=^N|^Tq!PUHt#% z3ou>G8_)?d6FJyB+S}Oir>ZZh?eW?jz1MS$Y0OWqW9S!Wg3k61m~s{%I%iMp0%L|f z9b_B+Rox$5dB<&mr~~MD>>04&Qpe||&l6fX=sy~e$M*`MW{yZG6Q5Rd6OvIUkC&^& zmHAyHUoL31<*Tg?t|WqMV?vqf`x){n|D;$M^_1(bX);@GzojBxF=bFpmd_st0u)_k zx`k@3hShO#aez>SLeaqKT>t}GEl7si0|*ES8Tul6s}<~%8?k7`wVq&o zZzaHO{o(6Zq1A|p2oyq0o)*5G06r;eAzg6+074-7;H8>YhW# ziq-E|g0c)9g$xxVBa3&5`g0i8adckOSSYOrLwo55irwgKmv$Ale#hfw{s^w}1S&85SF)ck&{fXfDkKs{P z#EEM?Fq$;~K$z3WxGI)D0fkFhiT?N0XiYzWHT^j>QGwXP=u^sh=r>r>Dyjggx5kzV zkGv&`{Xa!@LC~G8>eFn+(dD6cZd=+6&r3?SupayZ4bC!^<#@4m>B$J>5(F!|9*n>P zO8Y?*N4QSGYi5qMCxPX^eQiv=tED~^O8F%!2h@%Dm6zMM+x~6ZT|M2P@DKI;V0qgz zHyf9$-N50o5j7sW#G;#5`jeu>%3V_%)6VDlq%#+s*@Svxasr|XQN5IbmF5bGp*1Hc z;@duysANMM{b}TRsK5xp#LIw5rOw2{V8~pbI6twJj(H^5Vneh>WpHl)_3Iz{ygQ0z z{zu=@&30NNBDPU$GhN~jojan-!l4K*Op$C8F2 z@U#S(w^U>p4IC2TMtAkO{tZzO9b|18t4z0H-BT<1yKujfeqrEfU2`J@mRp<@(i|J* z*M2`L%sV3A{z}x)K*SmQ)6KGIaYx+%l2Ym3Z-lSAGjev^ zw;A*8et!IT`*J*Vdp_ejv@By;UV@zzKjvAw+MTdsJ`vT-dF=DQ#~y_Y-GA}K1iC=i zHy`tBCUy}TCJr$v=BXJwbg$%&`d}NoX^$q&F_iM?7MtoeqvoT}Dcu3Voma1r9i*_J zm0}XoxIC*Oc7t8ymgy*FPagINk2M)@e3t}q5QkPJjVTg+k-MMr+a5#2?MUyDqP?y2GGel7gX@6j>dctbR;6_090!Zpu)-XI6jAkNKYy1ij9`2?BJw zkfrZ&SY|P zjWzkZ84QA{sphnwW^9z`@u)vWx}qT}GpFJrN+ek*E61+b6UKp%C!n7J!^fQZjvCN@ zzd-P=rcD#B5k*4XhLKeQfk1{X|465^8CETAGtdB8BN#)fGlO2RONqY7wynC_aS`-$ zSr>iO99IQH$$xdTzdnw*}T!Io^Hy{PV-A&}w^IJFtbrBO*Y{u28$6kf6}? z{_)}Q!B4$5b`)O}c0wZ=bfd_O?Cu_}9B1b+vV)rgpSr&+~5+_iG|>rZQ+u zIyXOV6%NHym^4^T^hYI!Qdt$r3o`rTTNL*p3Q(beQ-FZ0o8jY-o{@6MAY7B$VkmNoOx zynf9lAb^J~Vp&pbQBqjUq|3+w)W|ZmJe$ORLmx)jIqI!}Cw?&cm$k6`^JG z<=C88`}0lS?jl9DK|OA1iHHx^n?d>)6Z4Y%gnDHI(>-qTrX_rK@Rj;St@^?Fj$Yrt zNV_aGT*rpdViINFm3bdf44MP_K3UIle8vHh1V=3GwKA79rq~WcWkN+u0qiLH=kh#^ z{HQBYDnMhnNEsGWHb`w@^jJ4Z4`YqTnG= zi8EdLW{a$+z*#U3?L-(t!48D|{Zm6pAcFc~*e9CD4n0Z?r#~yZegAxraU$%XQ^FIcJpl+~5!&iRZyzcVP9}c~G=}Kd={L{!5Anrj+n1u;awNu3$JU@wO^J*JQ zsYOvU%c$ss?8n2xW9GMaI*_I)l0? z?C8rmdUK9QK+f%qrBCIHbyrr7+w*-Ov*ya=k9((DUw~D3owx-SN7EO_5-c{bj@_{C zCs4-(^rh_G;N?ZH1hD_lqqg$_K4?R7foD`C>$s#956BI$r}htLV}v{IsaWkVlI6d zS=mNMlC~`r5^N9lX=>Sld@&HFFAr&&r9O=C_l;C0&;j!;Ci5w`s!fh6k}*t-at2q@pk~4SAkz{V;MZL$Ep8vX0;SW%@?mT6MWaINMUqPd zWbc!=@;r1@e1brXVCSWxW8j4(85OguF%x6gNH3JDZwj|WA$I=yLxk%TN<`j|)-|YA z(|>r%VZou};wRkg%r>mkcE*14$r^YLlUS`N-89Px$$4|TlT8A0 zy%zYSWj;?1POKilLQ#iK4eDF_oby^UK$vk!AY{ z)3rV7g^aHMbQC$Cy~iZU8JCdH3F$VV)Ir}{L&Y&mDX*vyP0#q`H+I#;b}+g30@`7H z)nV=%NS-g}!&*yi>37T!k9-RKx_EH$pVqo`pMF7cO>dWsf{4ct?ZQ+)@F!OLEo$%i zhzjSF;6vj|H`ToVXmu>aFMy_*5!X{?l2un@iYp>t-C_#9$wOd|r0MNG3lqgX`f96f z7s2Xdzn@&doyp2y?%V&X9{eXGbbBEAqth~j#B>?@PU)7j1eGKsD_AA@UX}=;`N*ne zy<{S3>FHP)7_0!Es;sn6;mtiW3EGGekQg}zE~W8>W;&emZqSG4%^M-II4BefsC@u7 z34GXfi)9D6KEPsud?=5tucxPHYz#(wh@v8>vA2uZ^CN6niQxl*0~|T7b73cPqYlqG zet=ft2^LIPy|=TIlxx}^E68&`jVVFY|8gOdk$(V%J(V6jO_xbquM zS9%~z0CEDL!eJ^6PiNVluNSSyybgf>fFV04tylm!ZjK5=Tl0(%@?%wHrL?!wk58eX z$j+UgY%_O;Oq(cIvaGT7Qz@66f)1#{jkE+0`7dyf(f0BZ_!K^Z`2AI5h7x`HnD$em zASvowP>aRF!UFz<1j}b^Ec5^|M>B7%sjI1Nuv7j!QqEG_GOTnnR9#!$$Y2dL$Z%Cy z{{FU-Ym~e8s|^evyMM+{^On|D)&zV`j&H-g|LeBG$pm`s=4qlzX_0Ez{uKady;TD5 zm;Vn7P~+z&nCr}FCOLPRaWwM+;|r>fx3aPS&5p@kY4+(k5KV~+%XHZvbG`nF9=bKg zA!gQ8%*?{n!h-a)59(ITjy*(%ib(cQdUGpi;K6)3&5eq2GU# z3mzIXPis(}D1Z{j3ytY03Y=J9NKw%ytY`}c141g`wW!$na5B;c>4p%r&}^8zm6Q;3 zz%9eZC@U)|H!F*~PifATYxWl<^TgQjb#EIFhe294+r$X+IFFd_iwGE}s$NPBa*=pQ zhOG;gX-U0#ZX+tAQlS$Qx-UdxF8ImYkg|Dg6TeNzH)>T~iF-YfKb`m%c<@2i;0(z<5Nce)kNOe<$haoANu zqcQW$WlV8s|J!XksMbH};!cKi546DW0rM%aCy=5;8i`gBU!J(UFZ{hQX`9rWVCk9} z^>%`aKcSAop$`0klLt?*@r-B7KsiG9HX2X=3&-xr4bcndF7b+SV)Yre3a^> z;soO)Gvx)o_wx}PZ)K#yd^qp#-tRXo+T&|L-+YITW$Lva{N3wkgKc;&?ulJcCeF2ueqE9*9`c`SQ+%Ak0l0v_37oN?L zUY8K~UyM}N637MNE|kzE(UXz`q!qHe}%V!3;KL;8_~Ad{SZ%=f$~;GOeBVuaIU zKv%cM!~6f?hxV8RiTV78!Jf3A9v4N=9k|7?PvQ|pe0kkQbX}v|7^$Aw(~OP!atE@} z{jBlAQy4XhdW3vaIe6oRazE#MG~&S(c&G%REJN2$*1Fa{a(4%DTpu&R22IjfbN0dd z%3f2D`rdvU-Q%n7hO5DWMk*^YxZkAhOM4DcyH2WIc#roL`V9j1cZ6xu@I-B91Iu(# z6CZ5veO55ss=3_%%U4DQDX9sKB}@UFNZ@MJYl^)X!;Mp|1JHRL9W>RMehV&eNUXnf z5zGadfqyG?^YhP4Oi~%2oghl2q^8dBu*pMGOS?DtCpncA6rvR2oBtLV{SsD9qTRgf zqtPhe#n>OaZ>c?cxaPbH(;yY?7xd91He4El8v-nh0jdzgW2c-) zndu)SUI{GeTirFH_z$y2o!(9IG06O(Ph|ZV%(V`A|471v#h5fQyhW~XGod5p;*c;a zU$adai0WcI1+ZW=@}8M3YGOYtfmJe4?I?)DhdX&(=NoyrxagVD;)aOh4mJ^WQNda<$f?JtwyYU$uoSkJuO44OJ#Gv9w@u8t`6POAGtD!Mo%Yv?`M5UKVdT8b(fXF1N_(P%}tjn@|~3MmQ#Qn<%v` zvDhxQBCsT2bcI_Kj?!}T+i>sap2Ax{n4aFp@?UupcD-RdMa71GGLg6NAZS?CF5$%& ztBo`1N;UZ$Yx0pTA=(j01vi+#e}7!L!$M&8o_bn9-1&px1j?Xf@KJ)(TOiWt(CGO$ z8Ede+l8%vRfu996`IVYFrjfKwP`izUi=CB+xuQO}#8|i~*}V0fE>qKT#?R$AdfZO@jCYO(0WQ z9}ubE64Z8~Vg6@r#YvRNZ3E#r6=C`8Orz}f8ylC=> zxxShUR_mUa1TpBJ9_V|L)S{PK-}pHa<-y9qFPxxKd(Z1NXr!@lY%wU;LOYk}n*m8b z>cFn*f=xf)J^r|M(7t^|s}Q#m=mgs94i5+2xL&P8@CUkla(CSF!8I#+Wd7?{ySlgY zc2^mMD8m^93n=Pf@gT5X#A9&dX!t(qR3yq0FX$A_pw1YB3j7JS3FQe&^RA|(K zOKDBF)AxI?pRay?5ZZ12*!Xek=)`1M394~V@&0ri<1T{E<=V4LA zNoXG=449oY&im0*(L}DFG0POHN^*-Tdf}1-Y7_5ET-_B@6k$2r=e(K*Cq^{W`J?#Gcv0Y5!uj%r4&b|QHI&RW@AG} zF5!Z!msmV6n$fZDuvhw+cW?&)K*jwo_$Wesr7Y5}# zT3J|cA(a`9nfhyW7lm`C6($;aEif;X>+v+q_f+!kbIiRz(SR6FjtO&${1mD*b;`O> zNAf~1@0OmbiqVCTqgpZS}{&uKjModM!@1@DcN6OqDRF* zBctP0lp*6I$}DLXEZR31Ebb{A3z%7P#&#pjc55jPFXyugy2 zSxPKSDByWWhG?+E#c9x@k2qw#R;C+cmm6EauXECO49F&r{7{jblVb1HCRLHkrqg`v zzr6oL-rT6^$?tq7MifOZ;;q%g*gXMiSN>dGJy>w4Ke^lH!mN^j3PTGA$pk}GrVds4 zFz7>wR37lCW`L0KBNt}-)rN=q!jp>@tlH`5F#$ILS7Gcp8YRy>kjO5DY&w&HpZg@H zEtF`PlShs{eB9lyGD?XlqCgwe>ko&WlR}f4U=tr-HqbXE^4o{F|Ku1RAeOh@pgsr;(gA`;^sx)_(jOB61O5 zyP7xLweP(%IL3pXjz9|zAzN9P)*cb0zM(!q97a{x8zdo4C+PllenbDOoH5<-AsR2PSpAqX zwJLD9#!tIx&#%L`!})9AMlZ85_q6tjT3aXK zk5c$$(yQF7L|7!oo7OgLPkdFtG*e&4$YWv?ElumQ_d<^g(M4ur%FpzG=F&7X)e-q z<2nI<6M}W`Q)50QriS=ROx=8zirWKQ(4Ras_q696Z&YmkDG&E8fx#sUc1EAY&BmL+ z|BtJ;0LnW0x4l6GX-Pp^x=T8xySt?uL>dI7ySw3`yStR`?v#?2PKmqypL^bW&O5^} zz&tZN%&>oZ@AdtxwGJ^oasJ#3j{hI>_@n8S5BERafjdgXEN8^K zr2qmE{vqYF6UwEJ09)cn07@Jtb<5$v0MMfY6j23jb20r}hhQoQ%wQcVNv3*?3n}f> zuI7egDYQ!9CXQ+=!Mn|+udJ-BuP;#e-RT=SSb5hT9bcwrGA$aGfleSAqvY@{v0^_( zxdaQAk)4xsB9phNz8-5RHBy|+Y8^*jZpI1R_}}O%ZapGI6FP#k0S_NvyVKG%Xt21s zx&nUU(X5Ycwk`n7(yFM_PS;8Il2DPs#K>rs*8Li&%e7!BH?B(Vu|JvXbC>M%Xgrq2 zUKB1`g{%II{;(UkVF)s-#JH4^>0mp#hmE`mq96Xy5bUT@Zq*?<8pzX@zb8&Xyihju zvncs4T_l$twR~m{Vm?u6VKdlB_TQ)?@|@?|TYj;Sl*Cp3XO{>7`G;Y|fNa_sgzBEQ z0A_~zf?q6@A2>Lm8+HZ;D1>IfV$P09g2&8`i<^#*|M*$M8_tPojL4a3Oil)7)Ty_J z4Q5cLt}eXJF)X|Qmew}+CpjGr)uDF1qi2a}S;<&(Syijd!>=+HCLh?C{h7a1f85AV zx9}5yw&$6wJa%FtRyTCbVQHbmW+{)#r9sEAxnl)Q;0rU0;v9z?F5SRkc=!x77Am z|Lmc6I{2-5kR)B{IXLTzD(EC2nYz*5<8$s&u6Ze@&K8|W?J~DXi zeiagy<%Q5?0mEsZa-@s=!@~H@iKXhwTJulc@GJLkWwm}NIVrLu+rZyq>zwt{xp61I)ghQ8{HKKKL?m97T?4qby{b(FK|2&|Il#i z7GMr_!yc4@*?6sVp|W24`BbMmntrk9-7(T4ee}gq7rXHQ3HcLF^wUZNVP&qXfdkX+ z;`*<2;_;Q2A>;071JFgajF z@Gx0gl{9veO%HgL!oe_6N=0P`jQtH$vU4yf;Ja~{qDub3hG2^L4;-F`ctk~uaz}w{ ztYGd1NR$s8By*uB@HND3TVv$IRsc#~Y|PB|IjGh4WygH2q^+&3r>BRClRhSn7NANC z6uY^GIUax1gJi9&YgJEB6*tVk>!Dti%ijITERV-OieoZA3v2$bJUlyB?Omz7mv0eS9j;zz_*^x=Z;7kp>Lxa!Ri&dr=UY7@SDrgHw?(~yOO|g`9;yWC8bD<0_zW^N~oe7xj?VTl`jmyr6jf+DNw^EnZ zcCphhl#S($>(r~TN|SS8%GadZ;JP z-e|ctN1KjRbk&Dws&A-drtV?|^k!KbRZ$bSFYuorfLnPPqE!NPADNQSISv6H1`#$o zAr4_SL3UhXoK{L|_#XCDA0nNkCd6#&ArQ{2!M8S zB5l{es3nunNw0E?3#I*65;6SiHMPoVNQy}#g@kpmDRB(xG+M0KckAjKPD~u%vYW^J z(UQ8g&w*o_FK@}>I(509{~O+fQf^88fH=Y%Hm9#qc~*nFkFoYFXn9fuCy}1 z+5ov2NL*l2e}-?*ruPNMwGVTZ-N)GV*buBgposm+wO`64{>s@tYU|nSGz9Z_?|Nok z^*fmH7f$8&Zzl7-D;5;Tl3F}+EQTL*+YS&#(iq! zaK=km)?urEU-{%1_N@o8T^hr)b$$PVCE70%bx#5j>;1sZ2PE9mMDz^2Q%QH&l^#K0XQD;621w~6M6!x40VURDQba{l3&7r>zlFw z+WDN-^;`kClLi?QpawS!fPM1Y4+6mD=mYx!2rm4}Jv_MOzJB78oRkDIfj;OX=mqJ1 zXyT~=*HY(eXK*tGC9fPsV?W;GCY{$>FkgtzkEWGVuJ`K@s<(|q1@+n0aNBJCOw&x1 zrbr%9*p=@%1m&(k(ZWXTOW9wt-aF4G4JV%23 zKq*TppW(!cuToQrHRk18l9GW~?*v$4zkJmcctn+-O{$}^K+i(E!oouCmz-2#-XD02 zi15yoKQJ&TI8ZD^!p$we8PfpF(CXP}X*nn*3)fr^KWr#HMB##C#ZV zY;Zz1kJXqhP5T{p`EH7iLm5X`PS?k03Z|;}ggdOm8`tx0tl0XLf#(+S`T_+iw6Q+k zRE;(syI2(4O<%}R+)Q2CNZH0oHXjE=Oz#qtQl6`#-`(N#u~!N+HnUih8t*;k`*hql zTQL{YjwUUECb1ETbeRE-;xbJ=F%;BT6h!?lWXQPPkXU+jB}MO+70LGkA82E zs=RrQf|BFym++nUppQ5Chg`8cPL51x}eqy7cCn}-qeqRe4<8lOp+(!e_22a>&`|qm*W~i$_tON5EUl1$e0+G zVn{N>JbV=*n&`|hDRX6GHL`nnPqC$RH%IYg}a+P&_Q$ZNR+f{f~*-nMTV3swN=^cbwiTSj*M@?EW_Gi-t|E1!w1M|d z!(Oz28a0;j7PA5Qa4mfgGblsRppcF;0UMx}R;qoJqMqJbO1I`~G_TlVkX&lPW~>h~ z1RGXPIt}H(tuq+}xGYUhelISwPwdwSWkm*$1*LzfGe1A)P$TM1r(7otnE+US_v?XE zD~s!=X>HIft*2KpWdZV*qqbiQ<&ZGNk;iVA{`~x$}4GgJFnx4{XZ$o9My2t)O6f_MJI+jM#NfXhvxTsq^YA1vp^ z-w9z!-RHG1<)Nd)luCd%i^C(%KYLe9a^M?nr}nw-r;bicCNo;N!fpZ@*+Ah?DoK4> z3z@#LJL+8!ibrELMEtW*2rWezu#|w%Re?@Htj8LZA%lG2j)aQ=K5cFafsb?rIm{|0 z;|uTe-vxK;fkRnxRZ*jUQM;w!g~s9^PKe!dW;DnQ>2un)v9+Z5skM_| zDM>m4n74^hX({Qb@TgGaXm}(9l&ts6m?feEpCFy5rKf4}XqCX>^cw6k0fC~TV!gcs zy;6o|hV8{{7!}d> zz}lMf>8|@09%TCW9*{QQqENQ&esBzgFt9Wg?gEMkx0G#he>#ia`{s=zuY7;tuVZE9=;?*pV2pCe%-2CkgkEQ8nr6)cKM z@?~GsB~ZzFeRDHEKmV10iiBfxH)I`Ap$`+3MDzSHWqmLAPd)}QQ6Qg6y-e*_iZHAy zEw=E#Kk6Hrs<|Ps6r=)AaINVG4=*p+#NP)AF@q}VO!+-0o;ACsB^!0xL@;$Hfp5?r zy9B+FRPcTf>bxnCa;RxwurWRDXOsY}JAmB1y1r!ylJW8J$)2eF=LOn7I)d@MxxEH9 zqE@Gp?`l7%;NX6brEBQv*|Oo4OoFN1*x&OCCuDf9|gdeY)UzI)`FFi8M`)1e7AtgLIyS#kUfzh5#VYpFD3U$ z5{v4>Lfoiv8w^j9P-|Uj8jLXA&rybTh(_FxD<&7-8Z&wO^50plUcbe%?bPkCL78ia zv1{!!M*MFUz-Fd(RXQoz`hYZ*l#`Q*pP!7I#qxD1T<~iINhbi`VN%KQ2~l{^+Fwv_ z3bzVY#S{SUu{xxBFl8_$U{NX8LO!=qa-2@p4tq)T(BpcPq{oJ1QsYRq?Ht1S@#Ax- z>9ASwZw)|xNRL7GMDc9r3)$4=aH(mWi{1N;&=d*twCbX2U^wq|vYW)=W?~t5#_^%)E ztx)#V-v_Nd+@qETYP7r$)XJ+k!`-`bT=OsNoO}HB&Uz`Xr&G519kBZuuhwpt^w5-Ct~m z->1eyL*p{;m(5=j-{8GEMawg&Q7O60{+2!U7Fjto%(M>(jhpC(Q!KIj8&DUBtR`-Z zLz1#C?fHn`et9M-{yWa;$*i7Rtk2lPc3mnQU)xv9>8zB0yn%w<7fqmlVMz%0hK}7; zN}+#IuwX{Sh<7{oT;%c@ebp`j#$VYYxzrv*e?RHqRli{y4DPT)^1o1CjEMHw+dSXE zUwc7v8|^VW{&naK^VTP5?M(PWtc~3MFaDmw;JwLsHpzJ`2>+frTj$7hR$Zx z{kr1TjW1*hq``r_5GJps5`tcX7^6&D41ZhXVms zz8linzAEMR`xwSI_+WiZc_9RZkc6;s#{zk6EnmG1cyEG(g203fP&IB@x65xj!oG)p zL3H|7kHKH6N(&-8xwx7^xY1IbImjP~6!+(_WJ?41{<$^6KX4DZheR#!&MH!T`|l`RmJXZ?IyyS8 zuC6jNNMU@!N9YwZAd55@=DimplLV%!xFLm99GJy}hZ;bLtSl_R+oT`iA&9!T_*ym> z7EsgOm!r(2S^fFuc!@E&EI&UVxcCfl8?;Zpwg6U`Xt8jtsVR^o+V?~fl4wpa0~mmjeE0Nv{>0ypyyoVG-H}pu%}4qr7Du%m@hn(291$O z_to+1%=C0T*v!fDNV~g5{QUsY3lzUz+9`CE02Oz8i4E#pY;EM0_CN@CiB_K$;6j>c z=CG|wBj?{TkMj6Gf6e@Dmw0vmn4!=;9c2V0dl`e#h1I-Q!cz@!Pf#Ka%Is+u;&OBJ zwok7nDFt6_T76*nonl?aT&@f8Lm6&y^zPlpBPWX18<`&eFjWTw9O&_#=i}P1w%gv- zbEDxgxjn|1KP5v?t$ermuIDRrcaF}pdd@*3Whh6qsbU4K-0$QPl`N@D>6K)+AA-1# zGrUzM5WS~7F3;4#b>$J(HH~p)Oz*nhVL+!J=n!qu4sU%X{yaop5a~S@18k zq*xy2&>gD1OO_pY_sa@8RJ^Y@NJ11YH~?VjAIN!t5p4(7SD^lE#F=*YIsTOFpqIXo;aDFHODcE!66bttv&*MuOd7vA~{ z0a!3&6=M~)6}FDcJZ(ICjT5lQS@hS3E^M=m@AhotqBqF~_mGc`uXPW0HnM~wHMmc78Bpx}TY zSlD1F4m|i*^DwVo#X4a*`;o;^%|}Au$)K@FBlgAcz0UTlL#H@!+M_Kh#855%x+ z1lB-fQjs2EG>l9TTdp7h$?L2g^u^j859h|g2ovuU@1q!?GB3>EEijeIRh-RNOe`6M zQ(nk3S7&}e!o5((@R8Pj6nE)2q`&;3Iz-2P_*bo!&UqBh-#gaVZoyfRp<{Lxy49M3 zzuK3m^}B9^T-}X&4sypg*XIVN{6B7-JL@ouD#6v}oj-~Gnp`~nCH>>Uarv-zud&Y1 za^*4B(p%>o*JSlIs@d^vo2mW0h0DT0RTX>2i@&1kHVf@ZLc-6>1Tk4-Uf!bUBVDUQ z0~n(ObpwR{dsl!TZ`!$~b~qDzPC$PWb8Rr;bf>LatKNNp2(5;}WSrqGoQo_LQweQ5RJOll3Zzvx>Rb9fbKOW91R4tz= z8eGb5YSSIA?4kZf8=4*CMn7#>$ow@-L3)8jmVOuw%Qd^dg&ITlMENpZtnm}xlW^3K z0MiM_Yapz{9(L#=JH19k@vl30VA%F|?g~*ozeEzfguLfPR&ZL3APg$TB6ulzQdxf@ zzG;fC)*%{O`bO4y>p!5d=^E~X^S{n6An8Ow{Xb|95&xkWPrr}!O#PIFYT2A%YGY3S zeQs`Ud|yZ)ukg2wI*_@>%%vhRMkf|hp$(%2HXU$qst$5i?92+-f{@5oy51opP$>1qabq%7xx4FO_M660O?q4&4wKZlBZ>T6}w+Edn(@MawJh;CyZOb9qUFe`b$omr+=YNQ`kVqNlIde+YQKsq`KBZy7_fRL${ zkXMO%*b#~PV*DNadTV-mmp_18$>!9;{?z7l z{}_CIMfh2PtJJ!503jXkvM?Y~xum|lT-NQuTJ}-$%Jor?MF6A2E%o8;3KJ97Njt-y zg!n5B>6l<5B6JKq%Kkhs*{CMKJ}b^iz^cx{A-aanlZ3gk-kxHK7NiyA9h;;wkUwne z4^Ki=2&@gE@;(vmU~v5oKT6#5pwmxC6DWO+Et zylHVuKwG=ES^h};8JJg?z6tn=a_SdqHKwKUXO~(|bB!b*(^0U&8h@Dj0a*V&hs$Dz zXEs&H{@V9lVijsUEDS6>B0O|L^hg4+Sj7bD7+e$SH@Ou-A7o^5^Y%?WuDxi7=-gA^ z6c!QxMBI>85h%^EBfZ8sNL7RL60A$fa^>jwLfBzbc0-VZ+{d&^(`MuPJjX<_(a5>g zIZ;g&Wi&z1Pb3(^U(57Zi8F2ILAsZwH!V{|#$j7q@wss!=604&zntc7G5#q#4su%> zVt%;Kdz4CN9g)r-WNP|g$E#(poOrmKQL0GCpg45hU<*{r<70tJPx$XsKN%kJK8eZU ztc~bhBZug=P>PUye_;vYnh3Ji-9X2&v%7B47#&n%1nFZLf@M*Rp&3yHjciP-GT zyiZ;Y>DrcnbXO7o|0aOrIf#$*l2?0m*a4#8#;(xc=Y56sTBuoC&ve&RkY^S9&&BWs zF>%&cGV8~om|F>^JDgQRS@N*iHXtFs$`vtJ1^P4v1!!pM3{j*_zHaR5heg|E^25f@mj~m2| zeH6rU`~E@;$PUR2I`hlRhja_rc7~6k#GzS2f;$7vi4HOQVm@$09*=kDNQ|p^IN1dF z$!LU_IM~>j=KY@RI_BH zq8y-WsR|5wa<uPiBm(tlPFQPe}oP# z%%|+_laLS>3kZOF^BN8S1IGWV4vS>PBQJ~4IhnkJC6tmiBDjp&jB+ic)uqi0&4{uz zL~%yOnujYOX*6EMJsHN629SmI+(bdLp(hfKC-|f%_nfQ1ZzNc2mBtITGK=>|B|niG z_H=WX+#(O#J;Ry=lN@_4Et^h|+Fs%jqP@fUpBQegiZD+%aJ(0+Lz@JWJg?W{WbD=L zTBJLk`K;WOq@p*stR9kh=Hi|EPF455X{0&!>OIP{pF0tHSra-sG#EO=&g?;S#_*zr z4s!D0OntTE7{-!W#S0A?q4Gdx5R&@2|K4R;-S_D0Sr5s0j z3M(YF=#6y4@)arYT>4E;|0M~s1ct{>^pC52pR^idv*YiupC*`cA20P{Bm@n!owxK? zu6&@#rhakS`r7-|$p$}S!O&w*PfyI-9DKVlSX?_bUf@pz3XrrQ2I00wiBIDH!dV~h z>HZDhc`_@()%cfck{C?5yln}%Fm8EllND`PAEiiw;kz4OR#X%!lTxlMW!=h&v$OMH z+NW=0Nlg)Im;wNr_@My5?)Doc+C*?~&XmvE16_$z7NSF{ z`fWodte~4U5J@T)I0mrbUq8{L|7r1J^kr+3R7MHQy%BN;c`wsk9|)@3py zpz%aTW|e}%biGII_m-P{WsGO$71lo&ZuX1$UpLn;pe=rib&S}6ILyxGNGzGWz=WK# zppUAsw~q>>O-c;(ih(1acps?5{J?>Sf%lF8BW(FFHm~3_H;>l?a#f=T^xlWVV2hj- zA|qVM$QO|81`G2zV~cRNS2+2{h6t#qf6JZ>DlBHaeD6~Wgr#YOtI zOh0KlUQ=BlhO^eys>G{o8E-?#NI~JF@GJjUuz+nN1R%_r|Kxm`*)|^`1C{d22k2k3 zmQbhT$SLo!Fam^=w&J$pSmS0crt1p0VGo7hQvs{IEuoa_LCOblpDf=_Us9s}0;WAv zFK)6Yo$}8Hh|eh*oxZG9AG0O0yh_a0#_r}l!>hh=y|gCBxpoqIzevOr^9S&IA$wjx zHG29?@>fx;KbVX++)6XHX|?PkUN2WHC#DzwtUD0ssb$@!jD9}Ev(n%{x6wOqn_GIJ z9eb%&K9^>2H|Th#rN$!sdenBT`mu`9{7YHm-AkP-(WIQNC4SZ zh1slUU90X-*mNU*XndP^ea^tEn9hR^^LV)xlXx4Cf_%){^mUO#vzPdn)s`FP!C#+9 z5Xc=T__wT__Qpr|Vtd`Myf?y)8*2MY`|(($j!47z#|wfgg|;sopu`t4%>*uVM;vfq z_6jf=-()zAN%a>TmD~ud602zIVlZe$)0EPvXjdS0I(t&(85Tc3^`ky)4yHRy0x|63l^op# zqrbFZ9f?6o>`Pkg3#b zbN_CY%9yVHGSQ;H%DV>JWIrUnM?(=q3%vUF8g&8w@qH|H)b`WUlRw=X%!e>v?7!1V z3n1{t`ZA5dmIrF>BR8iFGBag!Q0EgN0b4%A*vZL0J&VCWNW2jKo{M z14WFGHkp16SNHR<9ym7oQ^L*aTv3hB%`WKc!L$|+hMNCdyN9N|$iaWVS zvp3{)#r+gLG^^uJ^=7W%)76aoo^5G)DP0v-Qj$hu0)q4~ZFtxSQn>UbQrP7MqT|;~ zLv4POyo0u)IUwD|FmMkqvk1|BC^ippOBfONk>^CLSu%unr9{|Z#;BLuaZmPh@2ttYP<7QLcxyTqt%@MD_w*^8#TF;iS8vgeqIx*>OPjasruZjt zI?renNBNs6j+WmXa_ARw9jcxTU%N?UbKt5h>nbZV{WNJni9`#1CqzD6Dr&g(_){37 zn@ioEv@^R?A5mYPQNHT8+Fc8|IJ_wBFV)u4iqLI{1a)+Bz`1-I_o`8 z@67=5;Hqrn5Z5EfRqz#%;gB0G{(>1VJk>h$Tu*S{kZzIpmswM{Wm|@u1&v-;@Ck4u-&?Q{<)0m zF8cloYZiMAj)W!;*;MfWm9EyG#puDPHela%w8lj{hL}F5e?NNCLBOizDK~SlqKZoI zMsm(_L8{4i&pPza$}OE>_&LgS7B2!=9iL?qiPhiiQU4EkQ<>I-N!vmEk_vFVg5_sxIP=%m<;^b@$_S=;c4qRmELhej?AWRwJ$tG#gCQhnFcsjGD z(&I%p);Ef7Pf5~u-)Qo^vkz6cns>9-v6i6v0(W$Bq{m(V)x^Z)q{H#Ht%Vx#Zb-WA=tEJVO;VXOY01 z#&$?yy{w|LwwC5=r@RQKdTP!lsC{u)g|dx2LQEZdunM)3bDw(i-b844zrfxk#@8aM zxK!hFXF9y@4JoIa@(V;#o>6A4WBq#hRazRUtW@R*|FyCfp(rHldwYdWoec_$$E!~e zjg6JF+vJO^Cp7nG%$;1@g9Uy~&)>UYWC}muh@VC2S8(PtYZdTl(#FK73?A-+scsvpEqv;7S_Z z8NB*;zMI#8w*7o6jqZ=#vJ(Fu>yJz{&?+f&W_&;t*fS*y3q$s1Td z?L+CFvF%sUF}(LG{x)mXGL(9dRJQSmXTQ&lzKS2obZbLE6zj_`*I!a)sAQ-rp+{FO z&KPU`@@B3v;E%4|zFx(f-!eV@6g^IRthDQL0n6V-XMg{cB%>x@4p5(;?G}b;Epb~O zyq~o8UT-JguXydtC86A5P$OVNb?P1e#r`f~HX&m4Dr5C{E6z_^D73l~BXO?OSmJt1Gn9tMhCYq_QQr{*`(DiR?=gwtIF7-2;Nk(WNyd z8PPn((=@UokTsGNQo|sVftI{5pP)ZBj4hcdcv_MQ2^<9?nBNELeA@cfFVlFhWAo9V zX6##ESo;{YxS&yKxVQI|^K+4agxzYK`{vU%mBELNi{E5_pX7Q@|HnS~pGCPt_T}z_ zQr%Mf*WF>55{fXRV(GH9(o)_S2G+o1bC#K0W@xdg5=p?+EZQ{oh2tp9wF;Aii4~|I z(KrEFb%2HwQ^E)hAeRDJ75aMASfCVYb?8_I0j5E_V;~*@&R@MOQ3g4;D1Kl&R+9X+ z&~ZgX`N*zzm-iDGb+h5gb=Ulw3DAasW~9w8Cf-YW2R@q{`1yktlusm|{{ym5S+L2id`5YFWKy?e1FD-qpD4HOrR)kAt^1sw z>?Rus>5yJH(64DeY8N)X>*b zQCHGa9?qW=S+fx65wCOnfIl`mDn9{bcWtB1UmgH26V+Xs2fi%B-!1g5n+)#riT7)M z9p|=qk;$L!);;$$Iz#rUz*m&KmD$};+k-Y-6jrUk`8p9SUU`mG8)bXRsih)9&0u18 zMDO3GVP!AtUrxjCC%lkj_B)ucbe$D?`bV&~skTNIFbHMpJ7cCT60Mx&Qpzhkg%s8F z)V0-9;?px@Q?t^NYMI?X;DkO4+f(2M4$Q+qG5o zsH*HqsRAKuuUnD|Hj|xf8@)zf&M@_$1uU)2}h)Ld_iW0pL zxSwU_x9L;2Y}Opofp>U5wz!l`qaa}5b^QJ=$T*b!C}fu|bltnXP6RWwBz;W1tZ_}W z^2;j_llkFdIOQhl-IB_AkWX;w%f#B*Y0Pm6mxFaiE46esL4Ht2D}{?~nbHA_fD9=E zZ7&|}QQ1f-UHGtc8oc%qg0+_t>1<^$_?}GX;nZ=;|jBwh@EVM#pa3*F7A&>K*0vHpZEy>hrR{)&+CtK0X5QMR5WsE|5%A&rm?jy8eLsQf3?X5)WJJ4vB z@h(!_xJHv2%L>eL4iCcywre!$2~e5z+ncMZm_QN*l@19S=s*GuZ(n2GcST4%+0}4u_-hvQe&Y8gYA2uzaLEYe*ON;jEfp9 z0$kc?-*r4ZJ;`K|f_rK-LC-H8UL@QrXfDjoUU~T79xpF1d=492F#S3>2p!mFMm;vR zsqNc72hn%W&)&GNo4N5KU7VbL=8K zl4ESHH-fS!Ph$l_g@O+Ho4{*mO&8=h?c0y1cXK^r5PS(#L86Bl1wlQJd*_ty2pUez%_`KsxeKH)m?ZJQQES7C?%AvQ(c{tb)nmUn zKV>0HQ@sK-Y>q9`QTjkinO32=4*hvthPI=S3UBbKppqu(mhz0WSF);C)S zah~=NQ;BTOt<{Gwv2d4*oZeF9eZ+HxzZG*ZP(4AUmPL(Vll~%|KRYjj-C$H+D5R?W z;d`LyN7g!Jm6=~mh-jhmG~^y!>!W{t#^aj=b-pB(VeFDB38_ixc~OKRG?>Kyq;w9( zs_0mLcD@Tz`GMjy*MV}&XK;5cF?i-cCOiDNfIRj%?Dx%1?AaCuqIB2n)vZNjHf-Jj z_5C2j7RtJ?(?(|5EW4Pll`u^Fz4k)^?0v+60jsmvi#hb1n5%r{3yr_JU=2yOW-KAc z&Ix;&{NfGD#g_Tti9&*bQ`t^)xT=nO;{NGf<`{9>|2%8o&5?e|k-S>5??QR~ia-%A z2!I+YxzQV^_I7r^FRDH>!yBgBORube-4hIGTU}26RiQODa{OWI+L&P6zWw`Q&oB5_ zmV%?>N8JxX%1!3J`jF4|RTG{b9^VAA2eutfd>pw58atXwmO(46MauM*2Y*X)&~~#+ zE&6M8WH_p9xkn^RoT%;1FPeE%pVmmfIdKsH@Qo`9%0|x{xrk3nKeZT)<%= z!jd&rwrmc7cfmcIw|~iMB)RZVC3>dZ*w*pvZS8H3EW&%qeo9tXbW{L8xV@!;tAZ=& zre%9~&EaV)k8caP)fB@z%zRs&RJ?Jzm-QkOlg4TOhroi<=M$|GuFr2s;V@LLB9=N9 z2tPqI6mwQ__HR{!NSL~`&=!-nB78*=%ap{#Ihu8)rBGN{XwTMuCaZ0^YOIQ->iR^q z+<7*xQETT_emMLWkFitl>$>wrWcuttc2qR6LOFk&W(&rtRv6Rad}A-$m{8(MS@nu3 zB}}OZigaN5WN#$c@~wKy1ldLP@nD6ginbvqxoM~T*TisB$&lr)zM&E0s{=#uiX&GG z9a-rr)Q@GoJf{8_73iF*v+9ZP!$>mW;lm@Q^;(8ssYm4lhd$(up#^bBCOTtSI{Qm1 z>KG_7(3cdCGSQCzLyreRbckN{=MU-Z6J$zu1@M~MzW$<@xzbqbVazO&Z1WW-_&(WRMfSE!)%|v* z&d$B`s&<9ENH2f+h9{eA!u#b6=AVA`@7(?i2wK0QF@0ggAO=29*FxqLGfZy3Xq5t$ zH?KWKV$qsl{7)4x*INbmZ`uFeEc)&?O^7J(tQRj`C12uqwGQ;UyP*P_wD90{6*;K5 zM-9#`;tMhaKk1Mil-*Pb6gK2YcObwC??VkHLxU$@oK)zL4TFG*P#a#xcL?<;qe2Qm zI!I)(!uw`Ol#qK0-(-U20Gu^EnLL?{o7AfSo1M06;^gGq=IU%Bg~AQmDLHrpE-^zFv)$5sBa-RUi7h&h4XrAw`;ei zl+mI-16AlDqMWGP!8C854vMlXn}6G7)~J{t|0qcj$5GuB2%M)-(E=-zG><~L6rm5l z?+`8)QYnPESd5lGr=g0t6qhGPfgLDjdJo&z;vTq!j34+pAu+0ubz13NM0fqeYhFr5 zqD;y0?LA~j4aM)St%Li| zjmIZ5JQE*-eBg=QjmND8NhZ8r&srs~Q*vJm&pm9PQTV&Ht860-T4D~9PK6D}LAD+< zR&6XeCrGE39L**&*e`R)rf7tx0FybI@t6UWu-e1gVGm!l3ftK*#dy^Nl`TRpv@jyE z*uD7WqlSy%>L6R}Q%0+3zW7pi#`;<-SQCFiFd&|J$ zPY2W8e$H4bQK&Fle_sNe{|6ue&sn*_AqM*G`XdIu5>ryA{tw>K%RIXIB_)+(OiG3v z1KfS%Dc*ff95V5A5|5K4_x%LLSPbN^0+|*GU)?y*=T(h9BL`+&RocXvOGPX(z>>DD zA+Sya6ab71L^!tS0>7x3()$@ePm!RJzzc(9w`&hgZLB1E=2Y33N|0I)D3E_)Dh;Bf zzF9KlVwGBLa5v6J^R|oChBgHGJylw5W+o=D&4!~v;HMAo2Nay8fK;G zp$bvxvqyGIaQ84;C{ZWhRZ+Hg>tXAg>zfbDjefQCQ}1y$AJiGJ=VCsvqbqLe2ljtZ zOH)eKkBF7SXcqzsm@|s<2gx$~(o(zEme<%M6`jrbkYe0LmfbxV4#e_9s*@Cq!${!+ z>N0%OnZpm*rZQ2&v{&Xhk@8!)ugP0KZ~E;d?9^YW0!exyfiu*4r__Ux!R3A@mcx00 z_1g|ExZAgByPP~-zkG9?2dhw_BY5?3q7VjCn9%*ICz#$|SPB(lJj#PK~)mk(T zt^^`aiXBFt*xedtWoT)t=Ab1eq~rh`bn^P%X6hV+X$mq1&CKql3y&uEAw5}+e+FP> z*DvWYGC#V?Pd}1}h}PA9yu9$u)-+YK^e;w?hY@5cQ^5-<E9dQEdVnxRoK=n|CL zX(+PZNJ7k7eD(3;#dW^n6K4b}7UhUS{^-ZzD?K>>PFu0{&lr~mO%%2rM2mr9@gcQVdB+a1e>`LD6he{Gvzs>%MT(10}Dz78PGm88drl<;XB&^9`s zzq?v9YWRY(RK!{+Vlpy8s?@eNE=N^l+1k>QDh2`IAu<-NxR!z=2q9_E221H5fxUcm zE$=u4_BtS5kuQKH*`nJiL0+mzy$D;R6xz*pV;O}XDw>l$z5W|8h+wBhhAUEPflz~j znVADn_(B~901H17CmzCo$;&^@>V8VYV~N%Ll;X+|B?Y8ouHxXo+(lFn<9_a@UZvGh zR;ABh??GMj7Nr7DyYB`-UUOv{Z&6SxbQ@T6-&PV3=yESE&-09_k!L7(gVjfLtgtL% z-LV}l_+0%v7b)<<<O?4aP;0Iod*QI*oX=!o4f3J0L@FU6+vO^uO zK4F@ta&954{WKew7mvpil=mo1eD(B$z3X~bitlyo{xNsm-YEFjS=S8#L!ECzhIU%q zilJc??1;`VrZH}5*l3}sk(*T6Rh|3d$G;`YvcBO^|0Y_AT79&bYtb0_fT1^Ah0;(= zK=j@;W-##@Qh11G=x(XCsY=e{Iex5FXFisK@cgQcV9&>ai?S+QF3LlFVq4o(9<8uQMu1&@J%pM#43o3>%3J~k z|JCOF9n{oJ(TRmdFqu`hhGCODwTOdlp0av4q?=MnPQ+QowxV1~R+=SV`hcvVLR_!Q zpXhoDzh?)VEAF`-f6NNMxI;K;5dmF&u-4 zn3!L`wxVi%J6jX8ATJZ=M_y}Exz6@lume`-vsL9V^KvrL@lt(6!c8cUonM!ePJ8Qv zdlzpu*0U1oXiu&hCMlyZHas3sYa!&EDyhq$GH+d?*9BdU*AvaH;I-UPD?@~_UIXKP zB@s|^fnXCmI{3n}ohfTMRfT)9r}1v*V~}2_t;jmmv*ggH1MXOw>}x;%TX%`g_)q$2 zJqho`^kHV=I7I?!j747lnCMMqj&5!Ah=74?I^U{>`p&ilRqVc2lVnuOr;dAe0f*3_dH=GfOr+)7^Lkr-K-eFvG=lY1`TmP(xj_hrC1_ zF4||rLWgC#R~Ii8$Cf?@$`BZn>mc$sYJWfosqD4;0JCg?GQ}6=W>Bm^CWR3NvWtgI zwkrFhiX~mu!LrPAKC;N&XL2 zUjbBQ)UAyOC3{p(`R2b@8O1Y#=(zX0 z){}ue>3mL3K7^*ptVz;V4LB;Td1e~439gU$R!$Ggv=vlYTr0BmEv>W>YnwMsY52xD z{bo)J0#1u%?@Ri=W+9@I_RR~O&UuMtzuDfrj?~^V&c~}RXrLo=+?JtBeB4cPH%W2B zkx7pUJuyHmhx|04`G!L{(#ENX@zs>*s!UqL{q2FM5hYbVy<{#w+akNVZEZb%NfDad zo+uWp#_&7?8hRWWYTS;@B7>31ZuPb3)FdWra&kQ#iCESfwiLy&YRGJytAboYr|5^v zRG0Vo$s87>82?mELc|(Msk#vLFQsLXdV+EF5Np9S9p@o^nKeqcm8!o*7{#=0GPVyW z+YxPHmJjI8Ti3ZM_(hzj<_k6^=Cio)O4;6tgFDf-k>v70I~ZHWMke_txir!`zmidZxK? z;rYtq$Df8(eXGU2EprAKzrEZaU7E60qX+ze(=-mFYmX+~c4 zb16kdaUt4t;30ObK0HYbmyLs(oV{kzXEt~JNM5q+7S?hYUMUEGfB+CQ5MOxz+<3Cs z_#E1IpVPcI^KE)Eu)Z(vLNiw-nu0ReJ3HHfB~KYmWINB<4|c)13B2`fqxq2-$zuTl zLrN4p?tp^ARJ5YPLNc=3Ecc_|W*}CkF_cn}>=P2GnXPEeZWL8pB`$)PV@sfz8(94% z`N{r>q&F2dza4>KZ0vUT+qPzP8jhsYx8MboU2sT)vmIM_u*1NZ2w)?lUSPe> zQ|RL3@&77YU{{O{l!i77RIb8RYPbk~>+K3f(}s-4GUKJJXsBoo112KyfLpQ({XnP? zFPIWg{87>)iA8}|Hno2{F7a9dtEfoZdKRZlG^fwBIyn?QX95APvYA{>5;QQ_CR0hW z%iRSxHZHnPv5FIc5eUCNWJ5f)|3f~hn>F7mRfRZ$?aEH3{9 zI%t*Nnh#N8a*;-==<3L;MJMRKojkB}%$xZconscN$&(Y8V%`sfWHMiS&zE3jFDH&_ z+cRDJk40SO)??G9AP1OCDu1@|@Nq(eqZuF&MI-vfK%T9QwGR3B9}cuQUpR1mM7 zMV_TnZHqm@5@-cD-I%51NR}u{9*`g?3*{6RH|M7cWOJx5B$@3Oy^Fyh9g$1svOY;| zveWxK@v{(lduOyKIQuesX9Unc93&hp?tAFSckDmZ;*e(#{dA$dsASIJ~Ka6m)-!O%5Uzgj7UUD%Dnk1(KeRiHwVh z>s>68k)ElGsIj>Qr>4Lc3NzkXJOio&z}(`(UeU#G;_Gn9KBn9Bep)B{K#Oct+Ti#E zCr?3MR95m)h}c}X3}3xcyUmp2eaNnkEtAXCrq9wE=SGlqq)59(>2FPG&PR)zt&z+~ za?O(%iq{B-9*nq`d@5V7-(4_Fb?6@i2|#^EPZw2jRVcDyP)99H%E z&HUgz?u|DUaxq1HE|t_PFIr} z-n_&dhU3rKdpd!u`HUP^TUY1YrjwlSx!@r1edjy-;?j~kZ^ncv_s3r#)eD101NAM8 zG--@vp8f*4|5sN#WL0w1@7Ti%0R|vWb8U?vq90hSRZ9G_`~@NGy5Lw(6o}>oiRMto z4eD1_Hp>EPW@;aN(wvFHG&9l|iqDcC-_)qzY25<{wVDz5$YVY1(l>)V%*%dxsmo~c zsDMuazYROA`&crM5jm)~zTSl!9{|Z!YI?Jt-Rd?NKtIKsL5Ca!8j4~Dgdt#ERUk+G z^BwaUJjP$+2sw&@A)FqwRHbCWa`y1LG!%84xk<~aW+9$VceN(>&0h)`XqS`BmWGys z1{3pB?a8Gjwuy%X(4}~++ibZX{Y>KiCoK(NDROz&V_Y4 zbn;+*Ou$dguB_k%2@`$^AW>vMOi687>KGRfZb5yp1wN;L_t%?#8^=+=@VL|ScKu~} z&i&N5cOPMTJLPiPBf7R0+P)O_d?@o=BKbD%`-5VU89hQ zCDq=ChEgZ0WF*JGpE}6050@#)FjxNIkn^BxdsR6Zb^;#+&bmhB_gA&a14Cn9qY5$6 zHVk71NU!}+zpW%2Sp;79Zx*ChJRfRjw`9gb&3-7mOSVW?dew%bbFf9KvRf;&wV& z9lV?|gejclfo<7u0TTOU3^mO`od;Xl2laMQer&&Im#5g6)Ff%( zCiUug#lLhb5qsx{mPpaouk`2^@hPmG>6LU0+tQ>Cbp6FZ%C~_O?=vO`rbs_%B2scX z;1P1`Zk+LC;P^Y~^Eem!$lmmK4t>jx>f%+8a)(#?wTj_Gjy27X8=!C1l|PG?es--d0%oLCeQIiI z^E*2TA>zV%uT~FzEAzwm%oLEHou0;)mVLo!U3!s(fxc!_e99KnRux`i^hKv-b!9`OyMpAZmm;OjNv*p@L6BA$SG_u0DV#DE}y?M$rRZ9Mt4Q<!`kTGfL7#}D)@bPt8e^mAS@fwu$6BLLh7WfFRgq(@aSH0i(y>UXCR;-fqUwcC> zzg_uPU^Z8#IS2lN6BDllXdWng?byRl&t2Md=p>@gQmY7QngP2B49?FId8uPl zCuCRcZ^GJJ!k#rTSzW3IJn{8%+NZ#~rClrtV2mkSZG2m>8H$HO&QUxmyT~wr1Ze6Y zmM|H9HVw@HXs&z>8waFXgJKG*igf7`I-}eiktSzYj;1^H)LNH4#f;R{?%@5MG2PDQ z84v;a!5B-3E1xHSMyS4<*Ou9d+LL38#a=Oz+}9soTuEM8Lsd6O(vO{jbqR}j5#%7w z2NBvlS2%^7xN_|FjYXR9@}GF*{|)X48f}yGm^NEP>k;lp{zjP3sGg^x9iya^;w7v& z$@~L< zjN(OG1e+IzE0#mV-3sQ^W+lEwiL$_bbheV8tW7^fud$;R?np#9oSW1+ z7R<2r2PmNYM>9GI1+WnQ@Rq)PWxY7Sbrabk^-u~E);feV6LnqCq5+X?v_Wn#v<;=B4x2d<*)moFu%>Ay3_Zn2W@ zieT?jZA9;b2NGVQUM2G}CS7FED+}=XQ9{5Cvq|yNjO6@!VA-L&{jh#jsaBJ%n;SQN1WuS} zA=gs>${%Lje(;C|M>#;uU;RA`FK@fmN^@P0#cf`Xdw^IcLJv_75fRZ)0^Nszp8u3K zlV>kiDEh>FwPmwk@lLhz-0Z;zp(UbUK9$TAPwj(1rj~GNQVT09;{uyE%Vy&Q5|nY+ zVZVT91MD&4hb1w0cluR{8f8Ehb|e~2ER+@5^QTgc8sw6f z%v93}#DXmZkXN^E>zF;2-`R)L`NB6rH;XqvAjiT)U+0A!>0tVkSPDR5^UVT!vXm%6 zLNPn0@yHu!@A!E19~c6-!}xwJgs1_)y#<QZ-W7(Y~bs+ z9G^ErfdeQ#*;$`<2p5J!y;FS!rdk!y#)2EkXegmibMucWdsaYpmL5CiTiASX9nVkB zPOdJrH@eyY%K8U4Yl=+46v<;)V^_er96JeO4@iK7_J(o`8Q8W(6(Nx}fUSIB2Vmxr z`)@S+%b?4S{x{DAyNTcy!SnMJ`ou-CA*JxbV74l-&@fqUa+ThHo$iV0c8lrOfc3=Y zRqOIXN?L|rJ%KbH9#oG6eyzyXwI|AAsOI;8rja0MU~-g*SO^v|VWROcK`v7G-$fNx z^G5wjaLWe*0}!wr#inRN9Vap})i5!6-wg{7Obpbz1jeYb4%(8i?qeFyk}2V(p@-sk zH$#5KyB9NYZMLT&z(XX=1RP|Xa|#jS5bByqy@Y!P>#dGEIUfrZ&za~{wd{1CUTaqC zJVO(Yz8p7oQ=OoHYgJwpsWF*hyL@tcC0a+PpqQ)+c zvMOI8IwD3A-?Z~EVf*aD(1)i=104%nRQ{C6bw;e@@;=n(bLo)(I599hocrxJ*PPg# zLC0yEQ3K>H!kIO?ukfHoJehDWzrDNQEyXn#$SiwwLWf~z1Pb&-vAw=4KiIq8U^kew zZ7jWe?6cC0^I{$|98BtEXynTnwx80E97~uQ_os1B1sxYO7ZDXvDfM|e->rN0J(Y1C zDBJxiNbdXZp0_G||2NDykM>_ioHzOty9{Ye)id`)9T8Vj8Hst7+I-jp3kZ1wLK1Lw z$X7HE?W9=TJ=tw$%?OpS)1bbWkx5>ysPT!(`WP`{_X11RsZEHR+C0h}bU987e-fTu zs8hj~Bn>teOhlKqRo_r>eB5~nlpaZxU_oXacxl@fJf(xP=V3pW0&E{u#AX6B6^afw zyeR@CUs*NOXo7L8)>yxR7!g@vA52Cd&BVNp9+fxagYj$*Iap}8@jv)x!K=QR0~SxK zhL*ZI7TouT_ME^C!jcX|wwj#$c?uj!`4gr$j(p;I3U?<+{1OzR2NDV&5d2vKk~hoF zO}Q5rS3z*f+vH9P?ko$5<5f-p6wbDA=16QoqPXKfsVHCS`wNhRh*1%a8K_-T`9^;6 z{F0$YzZAEh>!;^ie0i&7|I{CQtUUPmUc_D0!UM`O_A#2d^}~Fj5!bd`k|STC38n6X8w$cO#aO4lKWajLcHyH z2ALe3Z664&rT(9xTo`NQAw1?$C;9WKT97eHMg>$axwYT`FOnBWQyhG+9yo}-CmOuL zKQ0EQqp98P~Vq*rI4sjLu%x3L7K>`tE3aHsuZcKpr!!tn=M$|uCoB+7LTj3UQ;_Sh~(@w zedY7k#zN~_zQJ~gV!ps6n=hSc$)@>!A?9~WL~aG@%3;2MLao{MFid3(6IC1aw^nYX|e@t zr*ibXfKmt0MqZvs$qbOB(4v7;F3%OT`2)z}Zb5yspP3% z^XEG|crY(6E<$^I0Z_w~88}8sfA_owX0Rr$@UNJ$nzjT$GB>4PLG}>=rl$)$ z@`FTN9$Y|GYl_f__jj+QulxQm*QUhiL3O?JCpTUpMq}SQ;D8`C>t*4IjIU?N+C}r! z+1HUzf}$SNx(*fi|62bWVCd02sJJpAV&wyIZn(E zym(K7$`T~p3@T z#JQ^*_8$P6#APyjq&}{*zmAG*G_XvJY*Yl;%9d@(0;Aklhj#j)@)ey+!D_U~9vN@ZgeJ1yAh?^Gl3>t|*@?3Q9qz8WAQMA#*rQm}028e+CrR*Sh7=5%#3y^rD5NQAkrW#s z?b*G%tg*A3WMWcC%!aA7+zZ8GdLgE_uU3QhI{4^6%Dxep#AH023~0U&aakYzNl8Wm zI-IGs5>un20ktHBt_`qf>%!jLIz;5Yb!(`h*^gow;TdjzkF71jbG*7|}ExBnb#K69AoP;n(6NmO&cWO;&KTE*Wt{}R+=Zt;S$$t9z60kNJk;?a?D z7zZP_x_eos*-##0R{9jBM(x<7Re55_jP1~*6^YobEgoH~My=Hg-vD@fS|y{OL@@)c zI&`WE2vMfc8AiKgnaZGvs7kG|84}Rry~!>!<6iV2*cI5?WshCy9=f7Rm=5&$zobSV1k7tpu&|N5YCs6EMr z#I>W-Jq>JOFNGO@JrfU`FY+Q$pLh5Zm9Fjv3Tmst-ORn0W*+yNUnNRZKqh za*2J!&7IM#SG@U#h~qvFb(Cnu@`}|3jR>!;b8G2s=>bna*2*Sazs6#Fa6OXz4hdiy z4f;`EJ4(Zdmn4*wC3Xi6UL#X1_-=%Cmg%U!vCjc#IC>^59$r$C>OW4zcc&cwhJn0O9n9^lj=4;Ly4W|?NBVW0aP{k`nz9kJ=#w3)c6 zJhRY!auwLO3zfeb#B5`bBtXlDYZWe#L8Jd|*{DWVq6(E|3buUs7~TwBC3!7~0)(p2 zs@P8u!mph|p&#X^^(r|2K<+q?PFHHRN#N-!=;F8_i!U|I-7)_$O!3?kUu>13yu%QQ zoRYIWP~#I3I-7+cYm;IGgHo*yZIKlibjpm&;u&jd{+-Mzz%wfDkdPe155DX;En3_1 z-{8SI?@5bdb6V_3XTCE+2&f($&m|^A(r%>Z;NT#kVd3GSA);cU;^In)5;?s`^2+Q) zA~1W+_IOd(%V1(U+AipEzIJFmpL#tmyHykswXJQk6v;(w)OVm36zFlVPaz9;emcs235O3 z?Kj~d!Azsf%E}6~qDGb@!%QqKElo|;oYJGx<|$DEi%1!sPK(RPK^Da~0FS=@`MUC- z+(z?5@M^hMo$dGS^ z?^u)Fcat9zpjZ!DM)q1XPu(MLxbvO(Bo^u!np76>hHjA5nUTn+cm>0;p~W0ek;#x{V9j}DjXJz@LpGy^(^$b z9-^rf`Mmrr2`!@1GV%&?T5_0wm7=vksJ8|kWLs$JbImQCAUh;JHab8%OhryhM}eWD z!ZtHYA>4_*nh&{`_;#2Zd088IQUSSsvboALeR>f1Gsin|6Zsg#?qTuH0TS@Mg~_vA zs<|=Q>m`rMRMf{A$*W6J41Axy`J%&uJ(cCNgK?Je?8haEk zw_LNL8}+fvpzv_+kPQh-_GGH!G!t&aE7 z&WOclBe?o;qdOHk6K&-8VCwJ846X#lU*4{79%2(h?NjX2L{@WDdmXbR2fnAco36*!DwAo^0 z+`oTSl-1LZ`{I7t0w2w?^%D-45L2bM+sVGk`?k|p&!PW&&IXwZZ?L`BP=jol{Qj_a zO~Z;nW+Rii)|ftKFzQZ;$GWhnK-mjX($+R!$_7jv~DpBhy|Z{rnDU z>Ppx6O4sCS#q4aQl1Iej6@E~KL{9*Uqx1=x*_Z*`+7sN` zvFHnp=nE35UcY_TfM@uCE2UmeIuX+7Cvv>J(jftjwyf9d5M;F(Di*7zMN;KtZ!4vL zf(3Gp#lk|1#PKkMVr)v7I<&YtBXC2+I7;84STgf*;cQKtFicKdT@6pyUc~}s!pd=? zo~*kM#uUE$L6c?d>teO^*Ka!DOOl1NsmW8BoJL!7oi8zlYUnKT)t&5kk?S5j z|4mmUlMmyn?+;ISG@h0vCU3|1J=ryHM)wa)u zR!ItrmM<2Kt3^jsmXV*h@QL0?^?9V0g?j>?eSQ%iJ}ZMYK6*ub(xI_*mJq)ziOZc4 zIY|wAPhKVe{QTU!ynGX5LnD*zE#qCZ9W*qI*jThU)!4Viu+U$>i3sIDsRUQD8%D9p zQ|Ox_^6l6^ww4&p@sa!X+4T&1sznlzO>K1;r*88#5E3wzOP;Dlz0iyBt@%RBB~tT6 z@n*Cxq}L)55Bub=g?c4M9 zA$DgzV8^iqRDXl)Pm=8 zkBNAdzPJ@f@+@`I29X9O$n^4OQF_?noAjZ}Vjxugj>v1hCagufNJ&tc=z-FS|D&%) znZGBsBbP)p&>~jC=D0MpT?=J?5xf65+gF`Q{AdQ%@>5ALUn=3&R0 z0rTvzTFJ8L0mG>mjn1cIZ#=2INqO>KUZXctbS&4(3#&^&*6_sTwtgP)m?OL%Z1F6r zsfvkfadq<4O=ND%w5kOND{Yho8f@zf3g5VoXKcwA^lvcIg)h92UVwyksSGZbu={5m_?h6>WaWyGV2 zr#i$DQJ!JhHrf_}^=ndJKoLh>9O==>1{sfkm7~bJmEiU6PM4igR5mFnD6oJ=nnS$_ z*12-S#7M}YtTqe2KNr1jQp|j5m@|>rQz5dIxVVjp)|GShOtx^xHNv!CzYk^QZyF*R zPfZ*zqcrX9`mu^~jgI*Y>!(ThtU`IHsoi&y2vV2_l){HNEXYa~P}3}WeM_xdlYt)E z1%GmRpG1VNkPgqq60@^))BT=*gkL>{6=TRwuGpcv&jkJ{Mf2Zu+0SCNl@MRrNYBka z5M{~C_PKAaPCnQ`@DJYkr-l$JGqp7z1b36iNXq`LR?3jj!bTQQSVLET6UF6xC4@mO zE+H!`B{3qN;+5shaR=+{Cvw-f-G_!o;!}Kq{nbcYs7{SIRD z)i=F<-_`+Baosom7ZRERvu+p0iKHJ6f}u6;WiwuqBb>gZ=w`UC^{`;*mS5q>aXw2w z896bp+}e(YWPDx%fT4TVda)}uZKF!PwB3Tj{tO-W)hXX#!y8Y$|83F%n4$J3c6s9a zZelDzCu>5GPK^-r#ZpKP4Q!zKiJd(|i zH$|8|33A!P;4Ucg6b3Xlj%=XJsNdD(zXui?^f?6=N$W|usaxrsVNs$Z^qd8A)+I-W zp9B0dsl2U$EBMzgJgvj-&VV}rIAYibu0-OVmS;bO{-Tfb+qO+fa4)!8R!8=nT%4R* zuI7L>uySO_J*(KU=L8dun3x#2J;09uoNQUyw+C$E4`{1~rQOReU;Bcoh1uDiYnMOL zEi3qMVdAOPk>A3Ao(ZsUZ7rUqg5bHSeGr^+d;~sw8mlbu_MZO$17efw?{N6s{Xdu=p!`zG?d9~er9dBIv{CKRp*rBfn zdjxhYV9vjtRV~-xAZft2RO4!O1PYQKe4TT7VS;o$Kv&bTubZILBdwq>(b>J-C{qQb8!CoQ&rgp>kND*C!XX=UeJg=T8JRzslMX&3M9$e zYO!R6lw~Ct^x{f}m3mek+^a?EoW2ohff+7Y_rWb9z@C0~_2#z)pETiwT}3p3tH1Gg zy!JvloX{6O*WFj!!cDg?<6J{GI@JrrE&E9lNruMJ`};;QD~34l-f8Z=J*u{UWu}n# z7UAvNdHG(1;9xI(>-nLX!xEh~oi@j|+xF83y4@rbHa4eMy1GV%dvuHn=X5)UgaEr}S1HBeR4?e+qj#cF#UkKHc9+<-$NoP)8z#mL*QO=GAHDj3Bq=z7=xa0PoLN zZ(y>B*U&K8^6T}(<1)617?icW_lo&?`h4DJeOen7F8hv8AN4yQ119YW4&+P_E*2MAMI4m3<4mg5Q z>?jFRbJ))}er7z<@#QK86p%(H^P58#!RP+ZI|-dI9+b#WJ1N$q7Oic+ouC8S;h)yZ zd=*aIa7255MDa1U^6ZK7otAY|-tf|a`ksa*JTNAmvx`6mRvmo^*CXEg@N*-5TlD59 zY}&)MFA5Q^uBw^|$H7>N7&1B1e`%a&+^4op>nq99q{;a}6W4^{M;7qLSMamIM@!bF zJCAqriE=JqjdB%KE zy}e^1sh+f^Lbh^wD=}DO(!ZF(u1EerU*2_Y3;u|cZ-XBn-lMGw*^ea0YfCBf2t?u= zgh|hFuYhz1@YK8Xt1{ow$auV4Oyah_on=Vd`SRf`$`uMH>kgsvyYW()o@9 z(5GLJi%V;e^1?H%Pe5XSzz+9WcgH2hrH{ z-}&XPA1l8SiH2jcxJ)O8UKwVY`iW*S7kfp<)MyC3Zw(3%ggCmVF3zntwhcHIFZ?wQ zI5-SS?x@YCbNG1Mp!kNAeo6S@vDDl|taFu64f_2AueB2P%(n74uWqU?qHnfBo^*MM zf@Y{o0H|%N4-7FyP>9(WPBnHs7q;4Dc67pUnA`3(D50^o=5Jr|_o$k=-+|kRQl5_L z%k=WNM7+6BF}_hV(WKEiZTO27YloehI~!gk9Vl4xN&}+Kk(*7gYA-E%zsF2}`B^C7 z5qavVY!u!zif$|6jqII{jj4*LsH3q8*m=KN3D|f*)FDNsxq_d|fHkIRRLzL7grNkT z>e8!kafJIpt%?(A(04$ZjkCT(7@tiSKzH739r575Gr+}`8^ir*k9)j_; zPvZpe2PX(hcpsE_KFafAl6w+ovVW3KJxfSC$Kc(kbDK>InI9#RZYRM=Fi8wp+VC$smaUblYF6Czh6PF@I+iM;=Vf!cW#_ z{%-6>@A5`zwHONAj?Z;rpPPf9bU1HD`tH9)Hdjo;D4>YT5VCmx&pYe=a_dgP!ee=6 z9WgxQ!J=QH><9n>dco~!^_H|Z5G-HVVK)*tV2lX5!50?+Venu#3cDOg=(K6AtE($2 zDjK^pOV+71g_xL-_0SLW0~J}toGUFE3nn6axF;X-Hv8!AB?%+*Cz!98zc$bL#|JK3 z*G^5;XRR7sx$(m{^}LaXk*^<~2I$%D;w@Qm#xC(A3glK4FBmWufiVn5pwsK^Z!C^* zDRGLdD}|4~;xfe8A)@9)QOWHkoEmuH{x3!%-B}0nm7Mb?u!7#b8``Z4`t9S|Pdg78 zE(b*fFHLbSyQdz|Y`7jefmUyP#?L6%%|Fm?`n+>Ni1M;RU5AYFsZNLKeDDL-<4W6%WO?Mt^k==FO7yIFh4D*$RY8Qp~+jnV%YWIt*H_ zZB`*quvjTjtsmx#SRW@TEL2V(KU=b{d}_j)LCNU=4%&igbpfxp*k>G>9|vFMo+4(# zo|)ksc!?3(w)9(f_5jt>`j{H6Fy3A^t3;SD$yH?cFv4;@|M$H-%j>AUXV>fgv7Ocn zwBO9!H(GzLZ}%z|4YZrXTP=CvqYBqqKFPKXWKSM!RR>RQAbb5Y5~GOQpG9{4g!=$a zcxQ!|@K?!wKELd?nM)$EFqpQ@BrJ78RYn3*4;5l$zP83Pl~VtV9RqZc#FB$TcciTe z*2|jX<_}9sx^mMUOa45wC#^YX@)IKlNg@mryr+HHp#x!u5;23Ns@N`trUDX>uV#=U zEsb&or7xUiNFr*>TaNlO&=Z*7>t`6#HXErp8;@%ee_rC=()DDh8+bUOT#DF*f ziNeI!o`9#?we*nf6?pvQqXfCFfcFHfh!^8mwG2u7`(TT_<7g6bhBXq&LnC3#Q-Ub# z6shhZ#l0=A*3(F(muK#-Ddf@%Q_IFy39@Fg^1w6Z78LZu~oYVFy)a6I*T*o0h|J zg&Tb)2ev#flxfiss#>4iU)zk!ZQc)FX1_uR4eYn5zED2ph+T+zb~HR+sSYd=h~u-< zbo^1VUt+nrR{f(m^2S&d?^M?HF6&{z{au9``JJ2hR*7G9Mc?&^RKUyW>9YkHi`V}- z^?%t?`4NJicTD$G+q~a>243sc$w^yUaJFKz$>WVcUly!@7pSvf1_H@9(64^nR(7tK z*JYD0ije@F)RCjBg~ef`&E`FG-z9g)kMj)>Kfo&@8tHno08e-IBtC7)+Os^_D-Dz! zKz=a>yPfUPu?FfX+H``mk;eo-`T~8&o(_t2z?cXmc5HXkxm|8faih|X4WPy{Q<1I+ zKAo3tUob$$o)2N^tmi&&vwR!!NiTdbyHgZ1{6lQ?i!3VD)0In}UB;ftT8v=!i~kx~ z#|9A|_ha(MHj%(pV&U87Y%ae&l`Iz?a$y7?LE>4ylb4{7ZZ}Wn75TZwQQe&9M7lP4c_T)BJ}s4 z4ijtPv}$KkD3yVz`?Kn6R>~6U7)lWT8!VX%0t_pO*(&I{$mqZuU>KR0xQJehiwWRO z?bS}?Oc7$@G3XNy`cu3mv#<(o+5bJQRa9D7$6>Z3ALW<}u^O-Xw zsuitO$ca<^?HXxntOBP*{T_$6^aJwKT}xbaKhYOv@=!eX@9UWYufMt-oPFwf^;VW3 zCMgZxC0;T_k}7wblB3X{>?6^)`o9vcJiA9{lXil`gP1iIt(WydH;Q=vPKz@ca!T%8 zU1tHTM-z_y-^#8=&yNP-@~IGxE|F+05=CLP zNP0^_a+Q^>&P&8b)k06#k(*iB+9(VmRURm|w=IL1bxxzV{PI6clO;N2g?)?{pT{n# zX<+_zJkpzsZhQZuzZ6}y|Eeh*mdYh^Z^9%b{SNbyptGkUZ{^C%<)yTW3-lE_u zS6`h)v%@Lk&@x3k$BWC=4X8a_BR)ebh_P$?4HIYJfJ3j?3y9izEpg3USpTjfH z>%DI92^p1FKA`3Y2S8EM@NClY*o{5Klcm$K-!)!^=QJN$*IF+7j1{IO@Mpgx$)JgJ zYm^5;paTz=B&VYZZuGhrT~cBlPiTDWiV2ec|H1#C3BV%{J~wi2EZl|m07d6*(7jvx z=%{S?=KV5HZy>4&SP2q00d_ZF2&`Jk^j`%xevtpOkAaR~tTMqTP)K7TBqT(R>QgNJ zm$qV#%VL(gU@D0ne);SNH~h`wZr&-|D0s#G=a*bZo)Hegt;5oce_Ix^)NP51Y8To(Oz&UjcHd*>|APS6#5Kp$(&~gRrcPhU{MfOdHMSaVDbXr~#qR;Bt z9zYaKU@TF^#byGlCFxYnjnF8Iq``(TXeiP*DHs*Db9*3K^L6##KtN$@{}-IXfCw+1 zYkKRe)*n|GMFt0cKY85FbfxC|a|?`&On_xPJ|1ll%}66{*-|+wc6FO+hILVc^mW`` z@Cc#md3=DbD`)L!7`WNckmvWjgtmI1w%Rr2nGz6le(&_+y&tcI(TWO48`V@s$EH&8e_C3 zM0A|7oVUBnlS^*&A5Lco-1Gm&Rglnmyo&x}<-*@)ZoVscDDy5#69Xr_)1m1k-RR&U zz9hUNGDA!IaXPuXU=Een-RRk_WN?(4b#)?08>6!U=1BAPP08!}lGiuiUM;;Rr0#Qk zL-X)+2ghemMqq0;^UuwGS%`HjQrq@h+o4Z}b2^9d$2ZCr1KTCP2j)+(el2kt73`vO zPbpt9Yo!@QbcJC=cs^U-8%4X6{@)QnTaM5Vz(Uh@kc=}yar>kBst|OV;);q>p%X%6 zzll^34PI5n@bN9-+isg>Py+?(XyZz^eSa_j{Io;>ShK?Z2ITMi`@c=o2|24$o=V?n=Jr`j~%jwE0oiv z7+*^64u+b>-DsIJ&d2iG6e(_re=)_KkM2OPfPG(HxkIAVpjm}Fxg#k8|C2)wnE+l4 zfzr%Wxs$*z@@o!*2f0YLL67J{1O4s@hAgti-#_)Y_Kv;Ep`Z3yRj)~_!p(}*fRpfi zWOR$01X^7rD=6Bq|+Oswh+kC+i7<|!9cr5Ou*mAGF@d4i~MoK1p6s-}ZR%0}D4 z(F*EcteNRLKB~-^kSK#_7*p$i_kjlx*22p@t#=7!mhm6)H(cE|b9sxqV~vo4ouYCaln9d;a@J z4%%0EQh`h*mUQK4MSHB54=HD4v+`mI)ek!es%5Au)LT0v`o^-^i~VG^*%C@hiaN^b zU#I{HJwQe4^Zx#7ICR2*zikFwyAQXgYZYsB@~hXcJ>Gb3eEt}8Q#JenkCAwRE@N28 zsEN%}rY<-AhL2x19k1Rn?X=%VZEZ7AfEn$2%3LGtVPx97pM+JU zo+MCPdQ>yhE3cRK^5O!243a+9Sjbc^l}i zlchX_V)+^|XxxembPUAkZ})LVN4VQB8?Lr=clZ?9KFBS78@b(9kG;T-&#dFa2)$A+ ze=s9y(k*PIt1&w``61&zC$kw>N5%ih=hK~^#r|Ko!T(+#m@p(rCoa%S{gyI!#UP-Z zvZluIV7dg9O2$%AW)TaaC7WW{iXnB^H#K2ElfrfNgkgYSafx^t0vk5GTvxudgvH}) zz~mO+BSF6gqMTC(;Ozp>{^sw$4AwmOagp@;A{M64dPdYx777B0{!2J!3e2RuDr3hcV0YW4}9X3 zAawPXb@YR2Q3PXZ&$96z6Y(JRFFJ%1aUyVh8g-tU`KoFyAmWoB=V7L7E7(&85?i}z zBB@egc(9tdN-LmWEel9(>(Zni|n=uX#C?>YUY9FK@Cz!`Mr@SU_xxl_WrP(gw4C#Et0z>8L-JNSl z99`2APN+n^<7=Yg#_HDr>sswXx#fvcLlF_-7hZ9D#p`6>M3VNZLPRMHB-REVZVs7d z6R3h9U_qxO<74GvZ6c|vF8`qd6$Ht_%My%??8S3hJbb&G|7r@$RGo9Y^*0a7o802F z5tNZW+XE&lyw#)XOdIzVj<|)7(e049Gz@3ApfgWS>~$H&*9wXeiY0RrblVgxmO_?} zhL(Lk+YV4JJ-p*&rl5R`226j;JWkBG^(@^rt=IF zkGMXh+MlcHV;7KktO_Izghj>YcIi1?&l8W9A-<6JvCuSpcR6&pB~`CvJGDpX*%Pc4 zh}{OWnQ2 zCwSKw-dfWoQtf2erAONnNRQ%#YBD-S3l6&_WD+@LWgNLAEE73(gy>8wEH&;qIqf6l zz_%N*YeX z@6_?S&i;@6LPB<}=|3O@WPTUI!xavhnVIpi8?s>2qQ}N{SlFe|kWUnZzy(at&PEgR zfTWrLl3_Dv;zAHzRaRDpv3v;^5G0%n){A*NlLoELvoByVn6c_*KGOLMpC{3-cM`0T zwQMJ#t^oiG15IygOs!gzfkYbRPtnc*$@Bt&>mbR|R1>LtZBv8@f#E`~h}DrRVIT-% zL62>1WhE69b)5$P_-@6D96i?(PfB6TYaaEFrD$YO0*U3hUlVmaCXUd%A8$f%F@@fd z89~dNJo@9j*rG_2POP2>zD#yrS8DTPhzJN27LQpz+9N%?gMo4TwbD1C#3QcKBRPt% ztCwi&@bCI&NYMNhU(3XvR)=Tsk7S2jyRVX>%hL1tHa1AUGpL%H*;k1Zwx=i zf|}6~%RUoot(7#DvhC0!8{`d2@r_5RsdSaz`*|K9h65)FXe$!h+UwkjiaxlS7U50* zqwL3sFDn{NX>$e7;mNheT%L2YYPFx&jmqytXuZ%ni108d z39DXG7i^H1xbnx#jL*VQp>LvKSa+VqN^t_mA6b}JSwsDUh5nE$Rsp4i(#B~Rexm|uMQTYK*ZXx~Q|%Z0&n~Aum|5RB3Dsgt}b?TLCp9(V&WIXa7Zjy7fV6UbI-T2-8@UY4LMA)!-E6i zT!jr)AkUbb1d-=shy{reY4&Ol1~S}s^} z3Jbp#T0#r0HBMN7NLUjVA*b|Vk=${xbwKr<^*r<6d?k?p0Xb!5K+6I5de1ofjc-rP zS~48{!u7LA<3|Ek;~gUQy)g$IfsNmOkJ?HS^(P^Y2fHsL(AR{|s2|TRG`UY%6zpoV zCo7pOZ`3#Lzg_#ugsc>hF|jnrgVp~Cm$)-CX7xjlJ!U~3Pf&VUP=Av5l@eoHEV2tr z$9|+c?QzaCeS#%Y zzS0S+6IUkqVzd#p{S z_$>PpAC&UzFxtdP7E47Cb*bjIlj;&{x&Rv{+;GTb{ryFq9HC_ItN$AqWTHg+cv)#; zVAPIFNKsY*Hc&-M<)I|;hS_KmBs2I=$5(B6GxEA>BlH!yg4AFK^~+rkj8rH(ac8NGP3+Dsl61I_DP2tt|;Vrg@NmaNMd^hnop)bU)LqO`P1=;M;8xc8v2uviHU4(ERQ z2Qre=cFbSDB!r;s2{;(Yhf^npMia3kNQpwBGSE{q(Wprka5tlGg_OF=@vY?wA+A^y zQKA1)2`QV}*Ih@lA;Gcj<6N<5{>$vNhO&GNi%E6T|K+Yyv5GL^@k|KZ_vC(h6n7VR z1AUy59bDvh*OZD-Evn~p4Ds@f68z0l=YPLJ+559^U0spsYYUt=G%T0{K%>27YXIv! zVMyhsyJ6nJJjHdD{^42@Nba4)8`^{GX3>(V4NFKX8c^u}{yfNR{Jp4UcJ#?>Q$t(1 z&gW6o`%$#50L$L0@$ORuuK`LdCvgXm5Dpy!dvyAqsUlY`R`yzT)<~? zbNr96>9Z@$9;TOa{lX@T5f5oOC?7XgKc}CkIC@ zea0j3uuQG2j5_{lW}etQo1UH~C;nsp&=z%}SB0~ZJ7AK|W~l_kR$XxRYUqY1v|P362?u33aaols~wx@%sFbFN3EANFzD zkxSF0or3Dvy;)rcmyQ7xu?}s}+}HkzJ-1x5CX4XSsE9w^;zR~z!~nry^{=ZxK}KVi z@`1;`BLr2#GEbE+uL_@kYEnKzHTNUY{f;V-L}*8PTXkpL#->fLKsXb1G#Cn zfmNm+sd{2kGS)WESNaJ=(g`A>dpdG$N_esLO;kKyxW=*Wtb&j4!PXGZV%n^ut{P@_ ziGtB(IExm{*^)`?XTKR5%_XJv4acc(U${d5;&z7~FA6CHQy{iRYU0$XxSM+{3 z7f)$e&CIn{_QKEy`rL+$GBn-b#!?wYMREoPdWLT*Duqgbp{f`$$v?&xh?u)0z<>b# zf+C%}7_9ph{Z8TAtuVSH^Et&6KJk}h)q|X#DU4#Rr%e&K9L6J>L2=r`zR}Ix-h`z>hWCJi;+cN6--~Y!rS;m^ zUqILKo&~osG+I)6Xjo!wV3c-vC*gK$jJgRCWjMz;m&a}S|6O6a zoWVb8Gut4+Ix6y`aPxRyoI?e5v3pF#_|&GYIboNHoJlMYf=7PEa_QKH&1zX28Jy+! zS)MCW3Rst5mw$|@_+@U7vSDjzq!ep`if#)9Sq^Oaa+=Iql+~=!iL7*!^gpChCGd~8 z|CkW5*P*@zOSeSiz;!ZKU?ZLvXS%>IF>S!CqOLv%ZhqRZ_>+~xDIOV0@TmaM zB75osoRYr2fbZii^p7C>rUjcg2~o75t-7lP{w7BvF+iju3;+@Z_+i3Y#n5^VuR!Ap z^bJs&GBeEpu9TJ>^gyxU0bXRlq>H({vXW7;BhlMZBS%G7ccj)v*e~7tr~Ds&0d$IE zj!82zTea316ZYIfX`(<%c^UxHKK8jCWWJodEITYs37ceSnAFP`H>bs{4)n&<)g;J_ zD7$PSb6=tyzXV-B1-to;!1)#N=}-Pb-5XzW*}^K^q2X`?P{!7#JHlD_>)2>Ls_DP4 zbivz{6X9H(M@;@nMk-Ylp0M5vVY5B*!reKy*V`gkp`FO(qgW%{gmuuKoxSVT2Qq;m2+{kWNdJBV0dt}e{Ux0diG-!?nm?u!1;fpI!GlUlKncd zC0^)UkT=li`Bn7c4LO3p0r7t_dKu{yt!WjMlQO5ziR!sgV)qgkUWM7UjJiE7e|z|s zuYxfktuG$4egcmBxq%A1-U8<*V(VLW2a$goZNsX#1Hia_QVlj21dWmY`(`uDK z`5RVIDLJ6uZ3Eyl|K8bG<_ zw&w-;)j-|!?%0im*a;u?AEc5!C0|J#=LHkbN$5U}9IS?WK6u*FqY*3y#uV(t#4T)0 zv)!Gm{sgaWNXoac4jd~~+;PA09Dk8-NJJbqd#CH&o=T!1B>uuF9Pxr~P^!#i`(7$o zw#xB?IF1#v<|zyhU$jBdCmqD^9W$eAYM(8r-fa5>?9FU8uS(``tauzYyDO0eOM_}(O38_KVaJKnGT((PXV~Fy z#={Oq8+)9_CXA&i%O#)p9k!GmrnEJ7v^8!l&7L2c^TSe=Kg*O+aJOkh3b&_bu^fDd zAvBzhqfB)8bcJNS^(AOKvhC}SKgDapgle;PCKaB8W(IJg4mo;@1VJ{_Q8S3MxW-{! zV%m@*dH%Tj9m)TPKz)Atw@(Zt?yUMfc*TMMPoH@T0$AB8`2JMf*a-_8D=W~-62=#X z+_Z%3wc?RwZ(#wl>B3UhzAe}Q0Xe9K0wOB-VuS^2CqnOR_g};h#iCK-d1JfMLH;1O zM$`*E90K&)hgX#3*>C|G^vN3ZW^8!>$;b%d#T?W5db;#QktV88ekT*=3I6+GpF!QyiC z3vp9brT60i_*BJAl0b|Y>ftWz`lDk|Ha0joFnknuPLZES_BmRr(pc)tK>`>J2AJuG zV-cSpZeW>&cRz_jER6+|E%bclBrOet+f?!@1V>cel=@o6B?$26zR4d$OSoL{AO13K zdB|e&epUu!LQ1Zk>%4IDfMHHM#g@dJfxNF_Gmd+Bn{^!pG{7Ph)aTbT|5uqSP$N;q zTD(9#`KglAUegPaBOG6ZWl?+z0;I_=U^{&L6EF#xL@1FdC>CYY;t6o#uuiS*`EwszB5SWPWV3B>eBREcR9&g&w$WA-{Vb1OIWa74oX*XcvX~sH(O@$|{ z(QoQB1v6M#llE0j_@~84|OI zK^sLwj;N89x}zVnW>a}u1QYW}R&Jgq+v_eCV6=+jSKJPK8Bt`-zi2wm4hm!ezb zvOZl{`*syo{(n0L_dmLXILd`_fYTQhov%s?lLP0PRT0E)mYE+6`&(1Q9lB?*k{79M^5AgwgN*bM0s zS5Lt50TT!%gcd;ZDY{OB{_G1uceMgFbe%Ft%puJO3;s|q_X5NixPq&PiOd~eDCEvA3>b4pj(HK(ISw*w;n>9g8u=hXZf z(3Z(W?RWB;oZ}wmPc7FBGUNgE8 zRu-t9nX|*P;t1<_W;fcR9rupUNO& zt5#_)51&CjF)`dm1%MPoOwg)VTz6spz=kU`uAI$b=3-B%Tx-V`$I1QW6fKo|F(m35 zD(_Vo3T~=G*lYi-)Cpj!xO>}NU>aN-4hqWPi=uB*jiNM$OpJDT`zEipl6_{MK3{>8 zp!YMz0HR+K@2S%0uLm~u<6p^@6igZN98K$SpLWjE;EPb$RZG~hoWwL09ewTefEf8V z5Ly6z!dK9BSCJvFmXk$>Nyzp^!3gCizW^lzA1fITCr?#z4jh75Ly{_GMYN#eFFR!A zF9}0j?DNLit4kZalZIY4$#>fei%dHfomqh$ANzdoS?(L=r;*+Usr_JN^ip6=p3??T<|t~Ty)k8N&eUiSWD71HaBTGA zZT%8o?N;J2!o6Ndcq9_Chx4~+#gE|Ao`6@@{hH%_@WVog{kHwma-Yx%?y5!1XPX)S zAT>+{#Rl=xS0G6|pRKd_6K5w0DB579^OE6~zyU)dQ9|s23ias2B0o-8IPF9n+2{O% zsL_L@(7}8P)o`c0N_5s@%LLL;ZKFh6g3mH}L2u<=q|6Nx$Xwd_Tzb&COD;NTx1Zw! z{nEmGVrzDK+dgN<68Tjhj4s6ma^}J|rP{5SaQ#^Ed~!OxlCGEo4D3jERaT&VD!9Zd zGsVj@rOL7PcWc$0G!dH}2o{!QMr|o~Ik?R@V_6Re-h-K;1x+PXU9x^@V=BSDOAW*kuFNrsa?xbg$8L+N~Nk6 zcP3R*TH{i#%wODZ$(R2E2s7v8|5 zMuGm8YF?(eCS zo2I5F*gzprq7%~xYDv1j-0H_8zp1}fmM{8y<2*8#6ouEC9M^Ef0>67>BI5FXPM?Gyqgz$IZkfn$ zQ~WKEaV=N)$Ckt?(XyV$-wtyt%7}4#FjsBG0OA6d%RZ0pk%v&Arj{F@Ojp1cmsk4% zAREUeClgVH=EB-f!SfbfYJQ{~+y*}dLq7w>^=;_7AYocoa#~VcMvAhQ8nt>Nxbe-( z!t*Z~vuS2cGCrw_LaYalIW_EjC0sX>B2zk(c^_)FI(89J31%vm4fWf;eV;hCuYd)AR5TmYRl|l4-TVg_Y2% z(r$Hejhc^uu6q0{=QvLc_|3@~D zn@Cll@B7aBj0}N@w2Afa^ENSJ<-YEySPceAFrp<>L!~OFPGVu@km`DRdA13v;=N+9 zK1CC_#-;Ch#Zk+2$$mWom0g8JKon<+iMf@SggH1Q&8~`NW{efK|CR^O(O~nFQTWmX zmO~{9%aW+i-g4oZWaf)a@aeA3#-`3j6wBXzsT#APZexYxorDrUY&&-3%! z5TA4(w9RU*5SYpM{^>XJEYgfPq>}{`gJN!A5Yv>R_M9b6i6*$Lw6v|XREJcV#-xoAeJIO&XnSafNv>{>DfiE1Wqf2th&HSPq;lu6J)HQm5jdH{(6CKgEi$W_qQ z)m2wl7ZG_Qgm#JqCP8;~&l$+Xtf*iBHPeB=0G>&Co$bX%eVtED>&W^k8mK(`>A0dV zJlnwn18iH)d?2eU95{4aT3P^i@}AX9uy^nFY!gKJ4wwX-Vsi0@Ud>*00-xL-{<7; zmWhTOL7GPC&=af;&Wp3wAGdF8jxd!kpb5F8KkGrcphF~|1uVyKAfOFq@!%!S#23X(z#42x!*jOU4sY}QvQJWbvX{*!lh{F};o3$gv_QGc-iyKa(wSDvYlPa`P7IvoEhM1a~ zklU74e+PEoK(tkco=V3VJLef2OrR}0bz*FL1)X(YsF)=wr)~|liOi9AvZbZw1}nwl zF_tc~EB%U@I=TBJ_!ZQQG$Fb&p!YJ2yKuPtyXXpaVstbfJ6>0LkPGI4I7Zg}h16$Q zWISGzy;x{;&^|TH)X$KBO_QipA!k=pLNmLEd`&X3fH+`^A42K~EP#Xw>-oxIumi%u>-16nyS4{cEe}Vb63}vVS%4 zIK1Zpl9B5}q%_er31JaymZ>NgW#>j0^T=S|tDid?ZG6Q?)x~IURArZEmnOx_JoR{P zv#h@hj+A}p6YM>8OT`a!P_!+^L`|ODU}U5(ibhAw8~a*I2)>m%skUaWo6Mn8R~4q! zqNk%%?x$r_O%kt|wPR7@sEcWwyC)dAy3B_^I-+@;v@`6+>Z*+DisJdzD-Q!5^?;i4FTzl7*wvM)XH=d`b6x~ry6AZ7}FWY?FOl0-k9jSJq%86t; zIt&#ys{gcl@qr*hGK@hnCT`mF9uZP>Lf)Xz0wyuQw-Z}5p|GtspdhzYptfOBVVtIZSb%KlD_8##sNg3y+ zdO4N4t`MWWaR8W6tTxm;f0mBih2=F=tamQ&Eu_|8(;aB zqcAp645q)19FWiBAKW5ETQSQ~h#D!b-J_i-MW|?NlTs^;P3{jzkP1hXl8yk`5g$tG zB`E1=Qj$|Z(+g0;6<`&BFo0lF3NfX#&&}mBCV5y^VkhxKDo$xqin;v0FM%nu?xF{F z%KzO726$9rmVX>7g~eE}*C?^SC{sTA+q0B^S(;tz%(7Eq<~tsGXhA@up{;G*v{WRQ z+2XL?1&={F&K3pv5A;DtpOXy;5oTPO?^|v7)Zr`}#J992RpVjAVWJ9{^{AkS_TmnF zJ7eT$6yvuLH&@qSVNy6gP=hTIA5?IG9U+DW{ml^lNgAAC#1xxusr((syjV*z1sq?~ zkl%~&=P3I{&FB1=7NAeZ;`Q8dJ5<9tc59y$v`sX%T<KEoXmFFJrBm(q54qgh4!*n-gjCvF?z*#`b1pus58grb zKKf(pneockK2MdOkmK+U!k%o1G{NV-5w=J{TkN^R0Zm!tth0a1drP?EEnOToGllUt z(|+HYJy;b+Wpmp-xjkfw>>X37+z6<89-W>49<~0_@8f-}7#GF=A^l#zuuMPiiTEl} z=*$mC_KEn74&u3ZHaJ9~vC5xp3aLIZ2-|d~a<-_3R&J8f0R%Q+rGLUw&b=&C=Csu_WBHDURu_bz{NousFNEvpsK)4t2Q$f9$sLyVxicjj9QTQ zDkgg1mCdC--&J)f|2r;(5^9GqR6HcxDj%or}K)#X2}mp-oqTeCU*?^2Za+|WuB6ULJ)wJf_KNg0{k}?D!^(`UHlOsTY12Y=vy2y~s5^Vu8h5vM z^7eT#dINv;yX-TDD!z}7TIZRw@n~5c)qG`N6Mri%zo=p+S~52{t!j$kQ6r=yacLZm8HP31(g$1|FiCspvLdMR{$hOeJ-4G7e@6xy+@cip$5K*>@lA%@o*#etO21T7S^_^N@B4JOP)}ec759$c*NO4X8!iD z?>KIiVV|zWY(HBKqax1YAm8q4HjdTWoM2AGl=`@*2f!ZZTKA7znLC6{tsYxsO3G!( z$z@5&r3<@6l4)gxUQHc^Yyhe6!H}k64Dd$_4U;=6w*^P z6mkSVHS~4Vv-7{T0$)l3?VMy>eZ7X7nieTTLZB*b$kNTS`=fC7?~W}V9PbUbLG4{`mEcNd@!X?k&SkU4V1 zOnN6q;o*Ihcxy|`=+)ZId&Y1GK_9S^|8tpu^in$fZ3!B%3!@$lp;gm#|~b=jOS9V6faMvCXYudNP}dx!JQ z6*u%;9!g%?M?*%S#Qx=j`@T`R0UFsQFR?Z1OwRa`b>Sxg^>sK*~+6gGzS9IJA~q&hQ1IRKT$QW zJ$diBk+u=u?zJx`j{7TLsr`uoOHLk4(E))CD@A?d7+SKPq+QFb@6)@j^*WESPNwGF z_k71b5%BzDL1Wc%At$1`7cVT2?IeyNhW~Y!c?{SS8@F!TlrV$QU=$N>w$mP=>8<_Q*ey=`$_q%pXX`i zwsmVjKoTW8`Gh-2uep1rIn^dZj!m{2mJIvb=W@5Gm0}ejPXNy_G2qM8L<Kj3w#3} zeQf7(QS&^l466jy-mX8dcjWp?WH0%w=kb%BmUf)V%&ISzifN*v9bKjaI3un|) zhgG3V-k>XH+XB31W)LAuX2(seLl+?Ltm#cEkToDg%KfGY@P%l$=U;Gqb%F4UKFb&Xhk9SsE~6$LGD#p)y75b$`e_MQ%8w}kw^qR`#Ue<+7b zqcctBx>v1eXOUisycoK-0rgl=tyId;_Qf5ExQS*Xu!!Iybr~oib%U{Sv``01e`vyM zwJLn*58wiRPEY*)4I29rs6z$Z%R!pYu7`wxW^%Ac4yKp~FVPpdtljPnVhaf8zdl2F zY-*uD?_>Ia>Gd7-B~Bdq{*`Bfv+zeGM3_J}*_-BW=M(aV-J<`vVOCbEhkNdiMMq^U|_b#te!Z1T@zu+Zoyc(jFg{u z#wYwp$?ppbkcE5sk6A_U=MWbi1#HmPA6*Y!eU=qdePp&-2UlO{fqHh$?nT9IKRB7 z?D3qUXZDsIdgTiwe4deBB6RzQShOXoohUnOh_$~f}2wFv7t8t1i(Fc8&Z z)$RJ+iG)vlYmd%uD5|_cs={on2&%fC7os5KLj4uFmcZy=)C`(giw4U}m;xQeS=cZX z;*Y$FoC3h*>HGBXvz%tTLzeSCpHjmbW#7O`p> z(@Ic5>Z!)i>P_F;5XH|N*l{DZv2Q!y+Dfl~)a32)%F7GqZcA-vbViV_r6EF_BPw%B zNS5dXS3jh$n@>wIMAud*$&qc0Y@MdxmK*Uk{Y#g;{Fu^ zU18ySkxw?3Nb7(*HjglVl5raIK60SC7u7h+;<<2kJJs%Jo1%PXR6Z4t3(?z0VsyG^ za`x1MtAsZj zOySQy5mo^n^;R9m01{>-3}~o6M~yQRK+wVfxC6M&Hv3|-Ic)L9E@EedIr$!O5TIYv z4|OSdA$33c3V4%wCy~GvbMT#@F&6l3N^j`_KK17G?Zpt^=FC!6l4|i5LKH+vy@aK- z-Ykk}iZrMgzu+CBbz`#_2VNtOHGCn|mjm63dUKY|43w5s;breDbpBeU&`Lmrwg#R0 zlDfnqu8fBK-3sW_Shf6pvGr{xL4c2x%ZE&ONuVI^#NtrB{*Er(Gv$o`H*5@CuJzqd zmfx&HcP|S(sHfBik1tgcO#AKT3CFDqdgkVC_cp5|e+z|#CE%chPuj`aMbV&3J_I04 z+LCOn-gkuf>r%z`NZRS%)P^K#NYF!ReAldS@ucYn901%U61*$hh7KbjDd)V zI9(oRLOp)T{^8o|C(Bhfj`~`=`R{!4gIS&9XWcIt6+F1V_G2725WDW)_&*Aw>90@k z{k$Tf79iNL?7mg;JsH^==a`0;*Do{xUspM=&)_uEB~0V^9#`} zHq|o%)jMe2J6zp6G-CA@WVDq*cAIjnttj!zov8cIanI{N%yS}+QA-cPtXk=;L`1Md z#w?7Hv9;_!xQeHUhgj6R72v7NNSl(_tLT)XrBH(wj?|uJ53#lieoiu09zHTUK0a0o zc4T_s;7uy^3>C#dM~_#I2az}D=XD@O2f;LKg}R9pFaBeY@$90w$tktV0k6xMR^K;R zWUuUZ*^e47JK=lt!O^G$aaGM@ye}vwUG()ey_%ZVH^IZym38x~TA3=8OpLUnL;p@c z60%ZqM+;@UBVnTU`wr4=HL#Q_!nEmd#}}IKZG{yz!}4Wv>n$3J7y3UmIw4eCG;4j> z>anu&#b`JC;CdosbmG11OlNa)sx@KX_-VBKS2QD)`&izbtXZ;*(T;3B6*8F?UiCfg zXNr7?=zAmObY!RYM$rQ5WXbd1-r#uj8exqIyOAdZuh~`Tb*3TrhfO-N-}|| z5R#OTqDnrR(jU*tDg`+hCAJ{66>|&gO@_CboVcf%rG9t|>=g>mgJnf>wEp`gN^Ltf>t?z8y4342bLy5u}a+5p)~Qwzt} z3e-WHUjViW@MsdWQ2koHDv*jkRVa(k<&-~n*#7$yF%k^$$K@n|2o!*v{#ax4h5lj4 zk+E#ov}{KO7hs6nu7{c+Xz1<@gz3u4Q(&rnLnTIG8t(60YfuFrYHFZYEj%0{VPNax zPKQzbyYB}$kTzIJli9g*)D_ct0u4>>nb&do!ZX@xb_|oILl{>j`%OT>W=VFmlO${Y9tb;(%1kmD5-bO+CV{G}UczS6i&av$evGMDy`+%eG zk23RW*;#47=RQ(U6;V=BPziH*vb)xM-4KCymW+f1v}NQ!X82XuAeK=(6p3Oud!oA5 z0|%+d@0=+d$k6N(=kd&mkJ{s;ImCH2B8z+VxT7zLu1Uk3!8tlB;2M9ce9!nI_^Z^k zk#dq{fs&@9p(049GSlMjM?YRDGjIC4oC69up1A)k3c0Ahx;0nk_|j2UUeR4a2)>nT zToipqC6GBs$J5);o=>Q%~Phw9TgDyUt?L!Km%<;6l!O$wt-ab(QZnYK9USx_sBh&!{r z&)z*IVDu!-303Zu^cCl!*7Dpq;1fACRc_j856We|-GVTXy~3&}5&M9p7PBhTdWDze~X$Or+4t`xBl#@%^Kgp)KAX0S{CL4|c0{fX|IhcTMkP(_e{ur>H%d>_0_A zSU0`pWsuRgq(-Gf0!YrBc`}5;$=aEAc}e4GXi=l3lNu^`WrG%q>GV>aU zy-cPhT6&Q9a4e-7VW%YDWK5}^N7_Lqnqj(ch}0si&a6{)lgg}0@yZDaO6V8~p4Ug9 zzHAwUg3MNU-TdX-DEl0f<x#raSg5z8h^I@TJD*^ALIqJSc?ZHBg2R6%%8f4 zCu%7RUu?|PsF4+BG?Yr|lR$n#g|MlD)i7SBZeCr={=3Wp(|Q(49&<5oH~IiH)i%3& zq8p^1<&mJ);LFHD9}J5ZOb%uqjgQVFynU5CSMn=ld`(PeLu8P;hxn}d52!OXMUV3F zS-aG$j+8%QkZp}bDoCUg--rINvbp{``!zoDBWBIzaZG)rXwk4x5t9pR?sERF=GqTV z{jLdlxO2h)F6kD1%4Mdwl@$0@%|Fgiw|g}w5)Z3zyQqS|&M)z0m88x7yd-Z-XyD_E8{|a@;wa;~d{p$W2{Qk*Zs+*%N%5z+H9;jp2CI#jw;K7+xsMavd1W#uTdsN7 z!Gk0T*3tzBN@1lH(Is$e6W6XXARa6(>G$Tumo1Bo3L@s@{KUli;quGJfTQ?H;o#aH z6Gd)a)5t#DlG<5Lo{;En%CWcqG-}7s7-B`8*qP1rp65CnZ{+*!S4}b-rn$^$V?@1{ zc%c#^rtxJEl3G+gFbocjjSfr6OT*Gm5b=5G{EG!0S#=7uSW+dy#|anyGh1MdV=*Wv zAtNCtD+x*>hDS!}7^&mKrDvRiOUjWx;!%ezL@dy0*6Ro1D$2{gmtew`tICl1`~8r+ zZQ9Wdxe9C9>h8eq=#pb&58HDL&usI9+klGaZwt?J2Pe^lvYMSzwZv(o{xK9!OG}}! zA32xi71Sp=yUt?WzV-4H{MG&h+^;_E?aCOXjBS_f!Q^1^-H`9)bUxxekI>w2X*$OimHbX}20B^s8A8>{s&e!Zf#dJUBK6UnqHMkQ^6I`JU+ zGczSSE-5oPD=t1AW*b7t$`cteN9s>G6xI%-+LYbq-@F{6_tNQ;aZzY<@b{I%sU> zE5-~8uaO8JC4MC<*R)oGa7EJK`fGM`3b1erlO_*^7fc$_803ge#&=C_1fb6+sl;kS zs{=sR*N&8}zx(I-aOBY?TMkk%$DLj~Iv5?UvO#Z=YWF4!tmi71NyvjwbX(o5J29RG zkcw%e5~je@=kIdsN%m7RHb2vU))O!<{`bD}48V7hrhj8R(C-PWa@de2A#{Bd%}H^* z$N26QbJ`&Uqo3c^S8_U~aw*AukE`mM3PwU`n_Lhh+OzyCT+>e2xV&Ncpc82YRej&+ z$aYaxelb-dvr^R4tb0P6ZL>xvhB5IJmi497aTjjpxXUO~J`qQ|oCw?Bd%o0~5o z?Dy2fVX}$HfUfUKlDSH6W2wWfHLFV6CKv547d^6*T|RHTWeGPR)#&Cb1MftiHIKnv<1|kDX!LlYDV~7KM{2 zOiz`h(LOsS0&NLG3!ZY5O02c4br=2$^%81IrEzp4i!41BCYiHnhesG)8D*hySC{43 zo_DxwIjdZAt`6`{Rt?*AvOArB4j)ey=k|5C)@3gP%Th-o7Lw{x?=bemM8K|~3fu1Q zltjwWFq6-`M~*k63d{Eolx<%$o7gOlBegYrQH6ba<;j~(x9ExAYWcR#n#}bUYNO!u z*TCmi)+2m<*0GLW{x0PShSp_wTUe(FkD&#cy8XD#fx_I%6=Vz33Np+(r#2l-ib0#u zMVo{}B=jV4`XrnriSvk_1&_P51un33SiUC-C#B&ka86`l@F5EX593l6Mho5t%%yNg+NVFR>vOT39cLo#f=fX#;WPFWs&!6{q z8oJ}S4CiihtYh&jNC^yEmu+j~?m39GDB}hqq(K&xLlQQ25_WPTW@yAkc=$PRQzIZ= z{4cJ)Iw;D3-Io%i8>Eqvln!a6Q#z$Xy1P3Cq`Q_bX^<}IT)I1!?ymd#-E-rdnH`3~ z{ev0Y=Y5`EMqbulIn`Y`)?L-IJJqsnAtw(0DEQG|o>Uy$N>9qej zi_h&~rj-5r`M}XSpUWYN+gEE(RQ3~K^#JC_?dhr)yAWou750DKGXFI!o~^JkenH6O zeQkelzja7m6Pf_ozM9D=tF3NSSQb^VA+*@N)%W|A>I{(}iF{0$;iDg7@h0mXK2O&N z#!buH_fwV)pvL&=rs!)=A0SYS ze*y?>_v9zlH1vDneDC!-iTGaXTK{Pn&lg$2;7R~}$wQ5D9kfPc!8jd&=YpFPifDa< zm20_kCD8z!{5Hx-S~J=ib5Jd*OZ+!dT``I570dg`^&FrC2?N=pFWjGNNjh|V&Fn7c zzeTS3mTars$+-SzTjN}3HPgh!*Xs+_sOt{-r!dbD^OOLIRg%zgYp1f27_lS(CjrSd z7rN+xy!ifSQEowl?|<^lj^j&>lgH2J1OpQA?FWAR*+v$YLKWJGVYc5d=6OXkC>lKq ze!}f>OSkU~sw4BKpxH<7QjhgPF37(w{_{lA^TtcSD-x1ZWE`tfL#c}5%o#m~f;K50L*3d&+8lVaJ_T2qH@tWB_qbbBSV7tbjgy;-p{ zr4fp!UM~vVaH@!GdLZzhz{{Iu_6E4FKbmnbnhqpB`p+$?5k@JS#xq>AHRH{&Ceim% zJDQi2M$N~LtUN=PGp;+~*OA4mnkGc^%q=}FJ=G=9zKQoCMW~jmYPs;H z%pQL{QDV*o!IpbenzOfCbF>>GH9LL2opBskyjgVrVeo&n0FWPHV7u(ELOkK^jT!Ea z$nAFuW+Te3eR5_rzyeW9tE_8_?D>;%aW8k?YMJ=DZ!0i9-l(}kwKDOjfxcWTw#h<# zxdieH`g$R6bQJOUviZ1QeXkp}OT=#r!)c4c?Ul{z)@rXAd9ShcBEPtT2b+;!sk1?mKUvtO}A)_{c&5xSBDNUpeJb%HN1a_aD~;%gHo9r ziKGTfw{ES&xa##D`GL%v{Bi3KWHj<;m>t71Ti+7z(w9Oqu9+xKHuF(ar{$l)-5ZKl zsE(#-VnsM9GDtw!%H<~g=n&K3(AdQI*x2aM&}b+F1JGzk!l;OcUcUJN|9~TSip@pY zeMnV;astl(0o)?F=j>>re6GjNW09g$N8C$w;6K&%z!dSiJ;uxy{2#c-TgSf-DSDqE z_iFdsJE}(@8V}AQe_*?tr2+&p+UN?Xwk2H?3N-`_F939LvY9_*;@G+hps|c2uUn}s zD1hSaaJh+DTxpZfGX(U_YcwaJ8L7Z2ya zxYuvd;_^xND_j9?o%a(OR8N#c&+o)yJUe=W&amU^OpbBOwg`A#!y||dD9~BKBy!Hk zL|PLP8cw?-sgwLP98qWrdEVPnXXaDv#BS)0tkJZ6=ma4ya(Ym?V~OLzR;VAKCT%?O z{i6Zum!hUZlaZM*eg{AN>e7%zMbFF(t-^SCbeN8o(O+uDM5#q8>ytql#Mq87GA1i# zTrZ~L&$8#6;qE3oU6n5-??oJ>E25|M?kL%&`del+8fo<0g$a zT(+VNt;X1`+vHaeMB%Uc55Znf2&d1~dw==(aRml#mWG(t|Bkg}WpLzV@q`fw#u2lO zsx6aMLbl&)XbM1M4;^Bp%*B+AxrU6>swE{2CiP(v6o9letWuPxrV>!Fr~@a9Ybh>agsM7YC_e`` z1H&hFcHqTF$<9DY$<8D|$;1TP7WD3VVjleM!)e+tsK+=13*{<3#1os#6GKR)cbRP% zT2oK7-#yyq!A*&(FvxEYR)Hsl<^SFm7&Pa_^1{H+IUbsuW9(Qy1a@yQ>rHn~^HfbA zV89t_;W>^18Zs>{L={1xbfuRCaD4v@7xnP)XbT0>{4`WmIXF3Av?~)7ih-oR-Q8Wl zBA2H)2=u8~Hy$2ZR?S;AXn%?Oo})Cw#5;g^`Cp=vDjziO(Wa<$R}1wc$R0OkHgSeK<3uLfK?C`Tf$J8 zH(&P0j?Inm?0e#M#VJjCC23Q_NtG%^B4?!H_EGr^`rgLZhH<5!>W~C*!xc&E*^H2% z{$`(~SPmIpd*dgYx0c%IDC?+V5O$~`WjZ+dm8wD&mq?-XCLGyfFmm(VSNWRIa%tzt04~$w6%A z-H&CLv}z9=S`P8ynb2sSXY;{NSUKE}Oq)+w`+_uWc9;S4?w?*+c`s?P7e~b0s=;H{ z&P+sFi0ThUT>MpI>SrXAfCLbjIJruU8O2 zy5D5yPFOzc*yT6^l2aUEP+m!h5vpr(zk%xDj*)}3h^?Nw8J=Q9f1LTh?bY?r-D*I` z4ljvT%tNDDhhMc`0QX(UdYg|RN#jHma#X<GvT9xIWyeo#c%C{x>m9bc&mZde( z*FU?jFIh)J7q7?F{(_kn7Tbjx9;fRd2*8K7F=?$Xz1a)V3jj6O#4NwdW(0Lmn4tc- zp(^Slwk(&=T6`*v65lcs?kyBuI4G0 z^;`RRX4_!L1ye3)qH~PjC3Mx{*Rs8Tt1(}b2_^TFt8349De(wj*qTGndQhwYMh%-F zd-nnH=jgsXj?`U3-O{gWjB&WhQb>`qj+e-Fj*f<1=8iIlWc?z`B=?6odxTU=bs7_Y z3;xakb-$UTZ9SPr(s`=7Wp$;D!Du&W3xc->QFU)7&I`)>JC(`HXr->5*^j_L;3JF5 z_Mx+zSAQYd&aBg^2H$9Qmay+NdSue{6tG(*nmU$(RKEi$r>PkkDM?vL*>TD7So(C* z()Iz>5q}E`g8#y0dw#t}BudETBt`oA5iz7RSGNVYj&Y2}bnH&v)3@`kcp{HV@2+oV zue-l-nzaCU=G(AjguTlDzbbUS-2+Geqhvx(#?ie*eob53Gkz7KIGCr(`VE?R05Q_Ci4)>;IT^$`D#6tvwL!R7IaKr&Z1^5YJ z^rrm>kzW8`64WiMlsJF%()ZN`f&2k`-cpS7b z8(uyYApU^oLN*zlF5MwcB4${|ImdNS(k7Rus3j+pqOxx)*UoSpL^K)ETO+QLnSrMR zfDm4Wl56|l!q>cT;37_2RGKV5J1&b^uV7TvpeySK&HO#4+HK%{rpZ_~$Q!vZ>kC(_hGu^B6%18?U;=`V=xx(0v9^1=#I0; zDds%0yY%YM5$wvv7sJPFmS^GA-y65g!kpL-c->jlE5*`x<+&aa4fesA?2pXykCliag zoC326lmQ2bB{JM3R;f0HS`cp$mX={$0n`Q<)D~zIB3CgzQsLSVHS=zG`4{9q4PwLa zi?1oojfBBxPZzA?hnsb;Sihe(g^EsySLGs?9)w01acco3g;RX39=2qV$dI^Y^v^G+ zE@9^BD5G2ztT)Ny$4;q~N=wLX-ed;=)FGhK0}G8(bETT^6ku9h8r`&M%Us2}FniVe zT=hi4`J8NlcrC%K#rjmi>SXsvz2i~6>z9E^*@4Mev}V0k)TLy11c5qhUIAkcPBRSf z)W+dDLh0uw_*I%vFi6vjUR#r%E>S919Y-0=He;BJs56O7a-C~$v14GiC1$$^bGJ2X zqw0L7v{#cb3Z74!&avNTW-k`XCleSs_D){)Ox0eo`Fkjc9>3 zFF?ntsCW3t-c7(#HX2&?Q@wDFY92x*<5DB0PQLd9c~~mE9<2b1LIK#eaXZDYYp=?g z;YJ4Xt|iHxN?S2ggMvZboZ2&NN#dX;cX4&&eY7w`Q68*LTP7){`5NdZo)KG1@P4-4As86^v$LKM8}Bf73I?;o;-%?(UhGnE{@f!h&;))`+2q z2x-KK2t-8x0D#I^+IpC+lSJ>Jf8FnJH;+DBY9Qhm95^}2;&pjN{jfy(^R@TnD6JIO z(8qoxpCA3V!7%paA9IRXzrQC?1UCOEkw33bHe=l=nS3$vOo#=DMd?2SX}_zsKy%1{ z3f9t#+V!fy=2X&bcu~#&q#TDwM^&XPfIk)&7x!21l6B+yWMmIa;pOFJe}Dh$%M&(S zHwy}*R^a8gl1Gj-IpB`4ZR$nEelya-8*pgX`-TBG;NaQbQCmB;>)6fkb3MQMV*eYk z$8hgcZVK&|ovuDmbh+-zrcQpR;Rw3@wlmEVPzLTp>w@_Hhcc|q$7I-QTJRX))*mR~ ztY17-BZM`Yp8WH1r$%`GIWbQ22xaFLw}?__r|L}l;ZPd9*go`aRmby9W_x&XaI|J& zFu+_liIT7yeibi3(A6)6J8~}Q*wm>^M+R}M9q)yUo3czMc^3|DIl)KFWr|- zW6X@z!49AmnU6mwKDEmktYbp%cy0*L#=VkJvZ#6o4gh6`2^mp)PW0M{1Xne<;rkAn z?_d*a_kptk)&Y@xOW3)nZGUQLxr-c>aK;H~LiBWobQWeaiv> z5Ud69Hyjs4jWPK9l?5u|@R}{{`*+pMoP;NKtdq5TuX$TtJ7uaz+1m&A3FVcdEPw}1 zj!TZqO4CWzSET=(EL)(RG*vOp!{~{{>P06x8pZWDJg;Hq9?xu?XD?=PRA2;><@O7K zdyAQWZOo~uN`&MhK;6pN#H~4zq?Fg%gZ~DNSUqRNQpPAWvm{ZZ8shp-ti9+ ze;I4L|M;{OJ9;s3Fu*+Nr4O&_ye+yya@UMs={BJ?B%eO;GgXc=hUyT$wTv)xlQ4|g zay!s$s?rV1R9(!pez*ZXLRptW1t&@7DoUh<7LvbjmD1vNc7c$q`1;F_88iA#yyXtE z#*l}9tUf&cP6SklRHOWfliZTexC@4+sELUKrZO{NZY}0#N2J)J z);>xVKqpxxvkLzLjpag+mCV*I^BaJc@o@2W_WpX9f2}%#Howc!Uxj*vOOo{F^d|QI zDo^|KHCXTti18GO-scp)B7;#B%-u*n5}MO9Y_Uqo#d`VX!H+ag_y02#&)EM!$DD~k z+Z_Tw)CeFX7?V;0&}yBrMe0+FV9axmAKg3xbizl`&@M9%+T~z{+uJViiK~X1n$k0a zuW**azC902fNqJA9;YYaOOpQ9xDVntF;^+1C~T9jbF`d=lvW zX0g5M<07}Kg#r$K-CnVg9lR8tF5i~&#)iF8GVtYH6o_LQI6yx1#Da5jE!Q7F4XKIn zS>Jz84)16KTR}h?Fb(GB!FJ(J5S)64??N;!(J}lA_xcF6iqBRbV3FKS&)+E~;<&$) z;%vTy#_juj)%a-VaERRF1ii5QQkC$Uf_RG}(t&z-P`MsBsML!de8Wfl^1-b=b{ijY z4~1aE<|Z52zow;w@)sFEgWga3AoHfT?GJ6xu{p;hkrnoQgO)cx_JGN}LnUXV?w~mF zgWY%WL4cI)!))@2!s}D?PAJDw%I#p%v=E`CMgQI$PN~_IUAPR9Ge^@O;0U;m`P(eQ z!;O)DXh@Pk5-kirwtT2XQeiyx#lRl=R}8%~ATw7woIwhcmY)i>AJtwCM}RJoW<3Ge^YeLjGKpSkJ1DtSrYluuq0|kFUMBQ^_1vx;ChPN*V%WMOI|6Bh(@%6XW>AimtqN^?0Ans~iXtNg`d2y3`t_1pD1a5QIbg!yVy{0Ixon9e3mVcfIB3M1KS@Q;$~ld zW}6R+%_@rZ9qc%#e45fv-R~$O^GaBJAZ|Utv|S~&eONthW@u(bPR*M>fZm4sP)V{= zX6qbUZgX0l=1k-uVTI5jOP{Y+1a7%YqfXo&+LeFLBdCpXc<@m^f0(toA?f@w*b z`iK?ca>bi5EOX#NWr-ebEeb-_VUm~JskFQP?j~J-C;*P%kHR~fWzvt3%K+rFA#)l$ zy%ix21ej40`ZOAYGBWN|>B(`~fCwrTiYjl_>l!lG&Zp_!{&a&h=`R1wNtZK!P19Ej zsd`wi$}7AetJ=?-KgRq8arySqFzmm91M4jR9`tEAkp7&b`CldTMuIMqV`x|(Vb?|IJb6&#%_s5 zQ^&zP6$)SGs zUh#<+mW8N+XsI`=f;SvUKEf3EPWWBI0aED`VnNJON5AeF_KXgk7arp&$EJYfA7+>X zTF(&S&QIrd_J>ZSeI3va`;k6eyq6zv1tmgrKEYH4jzI0de2_>COjI`CNBDbdO7HzM zvWvIq#d`-LU~Mf>Jqt*}4a)bSug!T2oq2^UzHV}G27@e48L|5y zFBe|A%%{TZ9v|ABE94nG6N^C^`0OJ^?Ckw4+ce5dy%GJ;<}PGjJVp*)(NvY9x(?0e zrOIklaR4vZXdzx{CM<5zvvmu|B!7rElsA$s^27OqYZ96du2!PdVdz^N&|4pr_PY1e zV5_Di*NngUu1kpDwU1g0A(cQtOe+LlQ7(yKoGh5WdPqbxdT{nAOuCn`wZlLNw|F4!l}~vbrMu zINjjH;IN!D&;}_jEhPu2S2bd@1zPVQ(AZxMxy+w36~kqgWyQ9aPb@6jH0cx+0G|My^zmN2HmYJNp}ygpzz9Zm$q0(w=` z&*DiXvz8=4;|CBD)Vs+tdQ`8;2ta=a&HyjKg9Sug{R`#O>Rcy7rve&6^s2b=qPkxT z@B0?48zUnlf%XfJc0ElDvbRsb{V~>QRHKm@{38{ zvV##8XuDjkuNAmzi4FMlrlcMQ;<7gje(>0P!>-a+S^hQR;@ENGds5|vzj0C^i)PB% zTxt9JI0!$M);^>!K=-)83cj!@yj!(xF^(}FcelQWs@JzGpfJgI2&T!dBYe^E zTqEu(JCV0Ue15p|KVtn#yu7{55eo7{73}wYPgU449el?jk_AhzwErXcfbAdaz)Ilz zmqdT#{t3<{#z6nmO4a7ZcQT9_e1m{#-H+c>8Z(uxJtS5*eE5l0hs18D<0MPYmDrxG ziIU&tyk!b^B8+=(F}N$Qc%juVBLE`rZX5A_@a&JZb8f#RH`j^egXDCitTm)Bwgp@14vzsVc!nG*0d#3e zKEK%&!p9G@6eYt(Nk`X(GHNxd@J`}|+R;-clMBbZDBSFsWB6i5YMN&qVx7=48=Ir4 zL&u4WD=X@@o4UYOUqgget%E-8rC$`=Hqmho3zh%PPeRBuX3aHT*C$oCBPXK?C{jd} zT?DM=dx)xUN@6GEZAC)_2Pfx}m8ZFBJI>*DLp_;1P==#HEQA%V&&F-owQ=+ubYpVcMVsE-29R4mWQTd9_S5 zuL7h-J+tjk>wOVDWO>;fucZ407tuT{A@%j`U_slaP6^A$s4mq(tQRu(-$+fg|8F9^ z;{Qj8Bpz%#>VXO`%0t}ox&nMA&+dBb$E;p&@ax13RcU)!K7_KOY&!xmJU>44o3Lpy z;)RQSL=V9NV!TE3FvOLBTmHnA9R(XLEblKha+X1N*Pq!ylEFW^C)=k(Pi1!_vuRR6ir-8VO+FC4n z&Fy_$F5AI>cwpy!*Tc)HN1uRS5N2i<)Tscv^&Zr+fT$$t4~nNHs_3{I@=5ku7@iK1 zs7FR#mbB|==oTega*4a%LEfr)U7ZMYB7X&<=*sk?1&6SULA(dASm^oZW}gT^)419) zTI&rDRm6lkzJ?o9JukBjU#?X+E47Q#Wkzv2r{&0V3}iik|jWUN?qu z&2sTMai_a3;%Nn{3fd5^6n!ko`IJSOcpFfCvF(DS(2l;$pQo6@2bOKiZ;V~tg z88NX+{A-o}l*gU;n)4fdcQ*Bxb2J!<6Mbkd%NCT6bTOS_+xQNL{8dCgBzNCGc<+zq zuSb!-D%RhKZ3cQtyY&&0mqpteo}{8Ja|-f5svCGAf3~5+`5{)GU5Mg1-Jr!$G7v`}7G09(Cyuq3Iny1}7S+uuhym z?nQ=mX1CmdeDJdA&t@BW*8NnGg`eV(OVrzcx}>aOj|&xWDYJN(-q?bxqRW6l@&Ph< z6T8|ssO8xf_y1@CGQpM%`|O6nA6mh*X^*~hfnp}lCgDk{1kXRzgi4h)S`Yo-@1qE@fY z;Cy7P+-mNKjc(h-guFuqz2gKt(!RWsxV(u!X3wX!W}E4t+asTC@7eCrRBiM#n@NtE z!OK$+g>L(#R}XtqsUl8^Tf{~fxF~!#t_c!+Wb-MNp-&z}?u!ou#jkinNhGLD`*wD& zF*$&3iNCp>%yDK@BSl}m>l3Cfo0JJ~$ew}T_KqGC8r1qiViEz91lf*+-p3;B#O3s5 zICP?4zO5!)wx-6*`wN#-z8HILHs-7PO_P(WPOcb}!C#T1shWkI8($f`lc@S9K3=6u zMn+mrMnOtyOT*|ZOs6MxBSMjbD&cxKy9zCv%~|&w>L=gKv_|}7Jy>aAmjJZ$+3ROd zIy~|J|LH(3w_%nB@cVY}(OL{Yy>L23$h9Cm z6b4GjSU&tq*{#Ahl5f|GC70qMzV&PeDvgQJu;CnD4y?I!e0*Mh60jG^XK;Dn+b{ft zn|OC6nvtHanSA5f4&+{J+5;^kkB^UQ?Os3;YVov|uC9Q^Q~{8v$DCpK0kQ(b?fokv z`Is<-6CnnO8GB!!tlW&CBi0zv1KviDH1E1Jc{!J|hd?0L||d^M?iMt&v92t{j0% zKGGBRT>Qmn5W^8N7F)lMZ*j3=O+w#b|M8{!qU z@|9ok0~RyMySV&Wm3fjkA@Hl4__E%he)BTR-DkKGz7hPOG_iR$FcYvzbc@|i#SH{h zk}f<<1j~seC<#Psi-+VVNZ*Wf~=O81QDGl zpy!?mguY%gK6Z;7?y%nG<*zgftSq&zGR!$5C)cW&v2A~v7L~-3huv145o6Vcn_VE0 z$(JspV~Asjq*AVt`>bX~j?3i4)1WXaR;LbBfU82$FR`SO@~0CBBxUi$X1KI^b!*%9 zaoP4ln>{I+-AO-QxTU_NEK0sg2;9@TOc0o@vR^;`SX?IC!?WHutK6rlGLT&DN68Z7 zj{W%9fYC6fY1+>I-SjGWl&V+~v64hBBN{1Msca@$Dv4Uz)S^A+IjI1Bp>O5Y3$RjbmH@lI zxDraQW~Dk%KrT@XHb;RE`cL%T;mxCal)%bwAcUKlIaZ8f{?FbfbY5~@W1}m;I|AlV zg<@>pts74t4nlE^g2u*V07aw&@x*ATtD_O~R0B?nygb8|KMrVNl)eHi;y`k^7zJjy z`N+sfl~VC5`tzb)zYfkXh@CGx^4mQ+P4z?f-QXl5AObw~Md(r#EW)O80i{$G{pgT} z)647mrn38uB`$0cGG3nTIVh0=y-KS;u!DvQD*{r<%1F^9T`lo6b=&(CCT1tJaQ z*E$c;m~a^-4T~lXzNr$Y@GZ|^%Zp(H#F;9INiu4E)R)Q;!{*8hn5f%a$r{>0xFW;c zgir&6j~&=Q*4^lzHugbt+bHCzf9E%NPyC>@Kr{PLvG58B!1;4d-Q$LK*MWHY&irfV z{>L-w%*Vj}*nR&x!E-`$Wu&%Hr!yFXNIy{up}?oU&hABYg9I#=)hC6x<8rtgysrG) zs`t}(z=SY-jj8tYIA#{6ZaE2go+IhkDkn)AgFV>5q2WN5`ZpzR3m}$UEfLYS#-P@; z!Cuve1e1HMS0sIC-W7LLoIkHs9;*>?{NU{T9?2>g$ceQxJK6Wi;bdl5YYv`- z2^X7kV_<3kq=F1i)ErNE5eru-S>vB~%PdPBPF06PPVIV~RGt@gTvSUfU@jX$UT0$U zbre+)$B%kGPS5;INl*wzL{S0FCn}n2$Rh0A*c$>lxLiPXUPWnedkKHCxTx6F$1@978%dN;<%pGtLLmh>NxB89#<5xfT)>&GAX` z*p$DGz&`#hxvJy(N2Ah>S*v?Yt4l7GuoyHRX{p0vZMN!(56+InlQjiCDy7QQ(}z$W z8WwzuK)XqroVg$|V`Kqy9ClAaZkIT(*R0cBHzzCCS{<}09le6a?7UOI*tI(*rwyd` zC*;F5?$n!!S_ZQ1O1?wN$4l?LOP{#Ycqt#Q?&pFTkDQS2YO>=M z{gR2ssCts4#0@TZ13rQ|^GB6s zWq@b=!nlVVEJeizbe96_12-op&~-Dje}xIR>Dmfp{R2P-#^3FWUsQ;G3|J9=>1>{s zaT?!t{>dnX&OIEkbuR_bJ47UJ!Mm|4n?J(4=qS3lksa`%(L*d!A$PemgD+@`d@$B` z-b9VCu6E%kb1>fo!h61Bl#z=SWy=0tS^{4X2BA+x;wSVvy$H0hy zZaBjyfK4YTDEqP6JcnqXjSc_j9-y0g8W#kgJQSnHd)oL)GsPR z5&br#(7&j!3wjygv_LuAfAOIlJSSiw1m0=y+mIG$pFWmk54da5D)#sy5dLx>;s2Ae z5hb?48R$h;ECh4+-u^sRxKG*}ae?;Fy2kqnD>%304ZVS(rU2WS*IDqH_|sa4>Bz+t zFc3;B2g3vfK*6MC=}sdW?;hB zIt=;IGqg#P;~92`6BX3t1mL6yI~Ww@4_ZUAz7fuBt&fg|rvbkrQiT(fMAnU==&qBQ zh8blaxR@L%?kCqYh7}zu2&Oyl)k1ce#n9V-0X6Bqi=I#Q?;u@q<~EdAFs^*uCuXc464>Xd4HW!B_gFLf%8$>LpGx|qw+z2eSucs+|V_lnr!)CLC^h~?sp zN`0FE1d=0T44>)alaotuenncchQ)oX5NQ&?bDmSjU_za7?+602^#sZziqBlyYs0?W z;N6|Nt@PQYr7#0BNfS4+okl^3Uem146QS)Img}LM*)^QwxuS*-5DZf!fUB0qWy=#x7Ef z)_3rgf7T%;H?Fm#JE})E!)yt1g$aY4Hjzp-1%T=GjSBbW-3O%dVB2=w`@YQ_DCL8{ zREoSneOa8&FO~1wfbg*l#Ss<+jVh}Y)e4OmeNPa9HPCnICPuv;L6sAU@(Bm>3jMbq z-crxb@%s!X%ib|bgQPbenKAhV8=O-57#q_!aoNHU>UbCj3!qraS47%3fQPx0hq(%P z(S9ms;Vvfs)Jo3BC&a+O&BwqDd_|LEXLp*KX7?~iPfJFsFFZIffSsBG7LJ`A)jv!A z2kQ}X0gW7a_?iv|OMnC1%Yd+Hvp2fk>uyyH9cokgf0!;ir{P|8sXTXwlX!9-6XGK6 zTl@@R{!7i|cQOA9!fX}+@QOj*T`WK6k3yspLA36gLEVZjOQ(_}ODTumk&m zPloB^s_E>h(ceqNp_3d)4n`EM+4HQY-=d)X&4e`l^+4{=I7B%`%hWMT*~XEaH=Vt| z%;qIM4s*MP09jFg%#x;-?9Wo^#Pa7ZpSb;`VrZzF4n&Mk8`3hBIp;>-G)3Ro z?)$pR|LntHL~gD7PvmO2e|rgo3T;`3jsQ)npYb8P-Xg?eWE<+|c04>&KG|9=Oyz{#~!%fc9u9%3T-svQ}G1(WhB*&^*|5>JuaPQ$__*S4dY7JqK+6W|c1LJAW5Cun4M9n+sU`3?FaWyiO& z1RWaLANT!^bk*zjFzr`jYGOPJ@wG5RdJgmFP*v66^JSGqIV9If9|4|{wV)bx zqqy5z_sN$*(l0}qo*7d0KF=J^KhHaketZWNBJFVc7pHCw{W4R6cJ9 z(jqyecOsWbAW&8^2c?wEI94iHa9CM~lTyl2S?zkqC{{#Aq7h4@6HWX~?~&K;lGlB= zauG#ppdmP1;g!60N#C#y>v_gK+Uu8h=PSDI7SMc0ZMMy7yQ^p0jc0r6X)D9P=gGzH zOfTThzsNJAHXZ)($oofzNX@ppP2y8|-Ig}HwwahJZ`Ak76uJiCQeFD9nbND9>6at{ zjj%O6VoxhcD8PFVxO<$N+b+8gI3xgYm-6Gq4=N<0WGF0`5*s<418;L4?Jp#iIsuc* zqqmYA>GR669hec!QNwyo9}zMxyabTXS-p66^VdcN#O`jFqx*#cfC z%bx&J5nNnpzx@C7P8*$GFmIo+US6NhEYcg7Pt0CT+0uTahqnbRi1XZVVzUrN199Bx zS?2?OcoFGxMdloqY-z`?d?U3d(dYJ^dR4JOgFIggX@|Ejx=bcoT6p0^UOy@WfmTUL zNrE|5fYn>S)A!=73qUfZLbD3a zj{Ud6OW((p8NM6d)wlJjE9UdfjC*R}H$RmeA@gy&6SV({I6p}=1WrcN-h2 z0eF-A4b!gujflK}Wp4V329a=6AFf>v3L$5oQk^+yMrj9OE${7}JtR!uiCeH^pKfRM&;p+PPVUB}-{W;SUki?w z%cy*X!urYB#S#x?CSJ{dU1@#bsg z%}G&BfdYG0Dvp27)F&3~=%1>$NC$~6*R_=U{}#ZFM#kN~Jqa%OyE6kA!+-uft~h>f zTLFFTuql;i0J$kJ^n(nbn z@w5}QvNq6MiSAg=U9SXoNPrmTheHQd3;M*Fhm4VN)Y-x+^p}>1Rbr0ph+|nqe5ac= zhsJGKXh540V^JSJd*25@u=QmzkYzc}SOe{%>im5N>|{swd50*{jpSn^4SpFr_w0^4 z`NM#_)Ue+yvA(irPro_<(eO5_>y79!${Zi(w8Ic;4=$R9SMphvn{N~>n(WI5{E04`(G#0AQ!EEH*P z*wPf}nG$4%O_Z}#m1&a93$WxZBFe-nXfYZ7_FZlnSt!NfuuX#~y5x|NWZVttJCNj% zot(OdgGM=up@wDidai#Mq{qF}eE^8mk6)rkWU;XmfY$jpNxyRB0sQ}A&3wSVcZ-80 zF=)IGJb!u-dELEme;-)Ae8Tl=%9XJVbwm@&{wA7o%S;Z|FV_Hyh^hzQ_p-!nZ;5hz zK*5O6qwE(`0vZq_L7K@SB{;pn-}ey%?qYc}8>P3JktnJU1g5QT?@d$&To`O=fb+Y& z9OxH%i*3JxiUp0o`6;}6SI`9a)pOaT&Zcop!ESwVP1cjE9rG*sFPX2H@5Gg$l~i#s zaWOG*6&Y#qDh4CSOAPFObi*8abiQ3Z=bXufe-R#6IUBFN^3L(088I=tP4IEe+3#x| zl$tl^F#53P*leDT7V;IShDJq2)vHROl70XI_)BkfKGS9iW9?c9|MR~_vJbG(k8_VEP6+)*Z&xT}SIhY~d;j-!?Et5NntwW+oqEj)O zzPs8}{QXLckZVQnFigQ(~Ls~+YcE{R?SC!C2hP~L{3^+33q67Y} z9&djiMOfsupek{^;GW0)s$6I?wmDH2;jV^Qhc+aA<~LU7-Dzciy4%%DFM8LL495Yq z*~<)hrxdIkr=cm&6@4QS>2k0UH#TV^iji}$fh=uaWT16@K*NLyNu7sA*v0`if7BDS z^M)seCISpmNSE1KXV#sNdu_}?F2_zRHRsVhibG&gY&Q|cx}es;HO`rz)VUolOvYnj zem4=&=4Dmgvpm_wmGyS;eL^Jg*?p)v4F8+ArN~^n?vh%{*LnV9^|Ib}k%XDbg1H03 zCS?g46s#-`k1aY8P_5PLT^?3aa~9l@2^H^xh|u+Oo+I>2skYLPh)^!>*jz~>O?zmM zGrx^vq1RP}6%3 zw9g&c;ign!;p@ZmdOZ--nb1duAuGjB&@N#l&toJ`{iJsu6jD+uq}O@33!-N)qBe*9 zL@5605DjA!tEeQo(tOWqDY&21;TEgr1*zst+hOQrqwJ)oq4mLq+2O8@>G)aO{a)ua zfSLS5`<2>eQSslTyNHof4CaoAP7|~e9T-s5{nqD>+-Ov;={4;sf$YKtB;TdDmoK29>0=w4AiOL<@^_F1JHfoFEM2m}r;{Jhe(K#z;11WAh*Hf=h(+LXCPiO15l8^8a?a2#p zM%dx<2_f~*kt09TFa<7&JOYZ>B~T*zJA!?O;B4ECKUvuTZB>kO zh&3cY-`cpv^;%fIQT0#`^kfGemcl9MW>2_Xg zUVnYTwR-@4;AEX`^ESzPITLT_!Y2!&znBwxaImeLm6;!1!-ZuXk#-Ilqc9=RCNZl2 zpqLSY0T3C_Y_uz1B+r-BdMoeoI`(Ig0Z&@RK@%xEQ$wuljfyx zrQmPNt!S-<5At4c;2puV*($e!x7(?Da-77BJi?+3CPv z56vt5?NcG!u_E&0gtE#9^R9p1A-0{k^8$L8^GFU~KZ4U$nCg(>t3&b>;fJg^?p$^3 zJr-k9WP*BOer+j7Q=F2#KHj-C80h*|S^J5Ug8Y=O!-6h)Iwz>5LqmIL;!9iUDtcC} zbLckKYp>E`y)xs#$y@RxUy)&#)v+fs3>Y`Qb~l^Z%C+AN%lYTT()F)46n6)3u4mV6 zVV+mEIac4lz@8ma5o$-o(~ll-R>PoR%|dGHoRka6!NG{w139Er^jDMXwyV!{E2juA zMwvgw5QwkYa7ij~lSr-;il_$B9(P86&SX}QEhSUYM~Zt-isIwg*3gkP*!QhN7;N$ z#Xz^f_oXF>YUVC!!_U{m;+E=MiBV<@wTbj03ORPQC9GI^9+cJj<4~teT`%HtN~lCO zdschz<=eM1NB*u^8Rkrxx&>O1;o178uUDsZK9!trXl%rt-P`yDsa_}V2Xn?c&aXr5 z*+Na*VIFBj&1(2VjPeRHP@8H44is4rX(_Gy@K^)c1SvOJ4AisI=08|)1~PE&F@~7! zl+*;lKlj?dQ7G+`v59_L+6hAwczeEL{<9GX+ySU$g5JR^6N29N@0-n~ZpULuxXqNG z|I$Su4p~eqAc;Gn)~7okHB%&7cO85V?7%7hEqO7PqjoakLxTs6U{{XsNH58;~E-~3%xXn?G|m0E#B z$Vlv=w_IU;Nn(kZEUE_*Y(XKCk1bk!M!t%Pl~e6wfQ4Bo*3=YA36s36O6K39FKq1c z(x**3qBa&rmQ(c{9+F5bNo;c1MbuqMJmk#Ll5#TD|3?cDo6};me5-#MLGrZvKW5KH z)0Y5!f(SHtGVMydUY6{AaSK=|dt%9H4mumWsNLhGuI}Q)HYJX)D#M1U7g7z!pAI_JR=7gwTs4+BMxKaJi-QK>%SkU4#@!*iN= ztOQ8iI0yl37>Kxd@CN)TwO!K&EIe7`AP_~fPe*;dv;WW*ax$tL|Tu7@?i{W5C_ zs9OsQ3xT!A@WZ0HkUi1cGRXpMNE#~=QJX#C08oY=K8-&VU(6g?XdXkV2`3LheSAAP z;vJbambz|wNILgwE=MJDL;fwew%qH*%d^kezc#p3B>TU(`U;r30xjF(R@|*fad($O zffjdnC~n2wt$1;_ix+oycemnxad-QtFEjZwlaK=m5FjDzuD$n?xBF0}N;?N?}5;PV~#47Ekp&!6vTaZ{^Tbm*7FwL|$-dUFK zhi$$oB~T9?Z(7=K4)lRd)(|7s*YlqYs>lZrT> zQqb_o;C#;>6HN69p)ZO)3;yY-6w(IX7j=iNIr{G9eV9sw3TGHN0c00$+Sj6Vv zS`v<*5_&I}*bf^?B0HaNhZnsClb#G}e)258{m62?b{hSw39gX;^GLhr`SpeYgNMn>68NaCBo zzey@Q;U5-Gsw`PBSiP7A2WJ5Og^r67 zJ&_O*@CYyqU!T^@6gN>P3Yw}Z@K3#gb^0hYnVMrO)qax^iL&UQi2fL3mmr{_s3$hlOwVOKEwZ_}QB?^3iTU*w4&31Qbep!B9TOEUz%Tu_T z*kl!5UgCTrRB2W5@BE=|=6CLTlCL1)S7Sbx-9yZ!sz*w+7Fg)Y5B>!KzGUZzyE--* zjyT8WCa1HSp0)XwC$ZMIfz@jsWIw5IY@Zt)*9Y@GK;G1OES*71(~n7cZm4tC0r!+N z&Dpm?l;Vc#gU{#5L>rBe@2UYsG4FsNk$@;axZtX;J?lF;9mx8{CmGF~bFHs;M zrH9>dQ=Lir^y4WVEbRY+_1v0)iHKT7k`%o>*>Wf9O{0?H107u8P$_ubtZ=iKM@@?1 zeX{r9d~aUa_9?S7$UF^(f7RO%(@K2It%DqOczAw~?p7*Mvb>)YzJRmJqqdk^I|?T> z)o(^Ik~YEmHnC2%!k7T<;7+Q+13t$vN@-J#>}TU6?8_K{G?8vOXx*SF#kg6=6W;}WjCn262;2hO{vt`7pv zJ6a;qYD%&hlrU}j)!V;Y1?z?hgISMCucOCfZG78Cy9 zU)paf5fNj+$o#cNe42|+>WTCL!NMVmD^lqMs;in zI+@SckO*MQV6I^iVc%ojcFEM7A~*~xp{-$XV)-bzoCR(C)dY`jRFt{x=k8E!oIo#BR?(#$w;YFa8+gs2f_z)JVY%o)hEW@;;qttyDv zmT;Yxh)25^kk}1&cw_lK>pd;=_Yw1#5uTqEf!Gg_q6EEU3AI@R(FrYbllDt3Kp{PU zzDwi#C(W4C+RzqE84)m&jidKqQOS_4;&px0Q#qHowTP3CpHca%7Q0Bl!PJ{ptW_+GE5bK0Ndf>5j$Y#Qt2abXhEMO>(}6@c)$L0vETM zvfix=Hvz!BhX&uYX4_0-ebN11@0~ZTp|8JjUus)kULMG<_ik0WN3BN_BIbLp|LJ|@ zS-*3Slgxn{z7lHdxPM9ttqlX33F0jRMxXiI!c4c;goW;#VNW3`_#wn11>~C;bZUzZ zNeJ`q-R2v*Te1P=4zd!in|Jh$2MHL;3-)>=ie#NSgTK0-@3qOpD{y#ZZfcJ4{-w$N zD;gq$11CYCDRO{>FHK*4MD^(br`H%VeIJ|!r#-upu4khq2V~-c3wuO+eds0L*XydGJ=M}gu<85vQ1I%Jo z2AyEw%Mxmk76Q6X1KzVBK8$xk7WXOvbFI-EwW|GwO27BL!)on$cIytf_!+ftMzFKa% zaz^J;i*@krUuQOK?5tJlHYcpM%aYr6yCC&-82K}(`*RHLb2Phkb6xj#x8c1UyI7Xi zKr2f_I;*e%j5)&JCB-56*W)-exT+=WSj{Dx%fpAM7Mi@N&5z5EX*!uACOvh~rJs4B ztT?sXn~MBCCb3dFd)><9mO#}pL7ygvUsw7Y++6W@ajrb3-(R@4jjg>fEjkArKP8<$ zrJTO_oeGT9cMdh4;+UTLg-;hc=e+TuwPRrE&;{Yb=jsV9^*@@{o|%s5eGONHmstLt zdX)m7jNbT}hUYzC3u;6mHFShn3Rj24`r!hd4V9SFvhL&8!Kic=h$A~{`IHaze}NVQ z9^2I*2vI&jfdcSNY0>GRxv|}`Ri|JkYLd}Kh|FcXzEMV}i1bYTE;apDWtuK$StY|hw^{;4nafMD| zUEqJnCPN#CT&LKSB~lwTl#h zTjp>ODLjQ_)z?OG`@&3tC#*ScF6T%hGwvMBO`wJK&cF zS!iL2Cy!#oLjzPUJR-tdXaisOrD*lE@*z*J5;Y`1l~XlP-9*(yT($qOv<>tUSz6cT zbb%-?3RU-{-Zrm)tOBgQvmd^^UuRqwG6LcBYhG@lXwCY+R-won{fDARy~^=)P+p{A zHpsyxu8r4cyk)hC)!f}2GT#W#&u|2g{9O^sjISz#P7k_|MGT<)WJUPhHhP8USi6ZP zCv!0{pK*-7Jt4tU>M~!yWs?4+ztClJ^WgQQ@BgOQV>f_@0)8=Uw#`cEOt?^Iz=qT| zSQEG(zJsDOPi-WQeZBf^!G|&|EA{aeMu7K@@$0A1gT@ZZd79J2{JiJ<-gN^Wgj~=@ zZx8tyrj}P}XYBB;L#IjBb5L$)(2O)KLE^qpNWt|KTcH6Tf^+qOkU}XzLH*G$sA79+-rpOo#Ct>v?E+sEByh zs+5JYQRM?OlY{(%LfLrT>%c%U6AF)sW)`Nad$Ww>JrH$02uj6?RNZN4ima%PF^X8& z_N5O2bBB6R8s#Yg0l}DnxB_gX zx+aPM@eu`f@N;>sFgyBghW2i*-vUFwvH`=yCqw8)8d%CWz&g?6xeuKqR7 zM#BWvZj>}SRAM-n-JjMM2U^nc%>+$K$;+{W6s!$D(-5>t;0K zxT%F@(ffPiqcOoen0(MjyeL3hZ;Y=r_e$g8tY&%zqA8ljI0E&a>C4_@4< zE~I0@VVKkcpX7CQ0nanBPSLe=QX*tKe)EwAjp&hw&?&6 z>E|q417ZYd5%YSjW_vv!AdGFrnk#^mCLHp^3swYQ04arJi%taqh2JTZ6ck7gk^p>r z%#g@aL@DTJ`8a4FUx$r_bt9#1Wd-=D>Xxm|yyAa>c>KiR-YtM`@qQyiypRL;^znU{ zR;Zc%OE)pa7y0z#dOk+E?MQ&&a>!@fD-t;mI7_wA$Zb_KObbtbd(1vftXOvnuH&Iyl$Qu>P;G2Kl?{%cK=d3p7v*}?0!De%Lx}+ zWJgv%ixhQ9ieAb`In;Rp~u2M78W+pVtm4xE&-8_1GZLL9FnO(k|=UIb)3o)%r z5FC#pGZ1hg(Ut3P>})@KGLcs_P0Z9(C0+|5KnV_47T`@)8Z1yd%KUNghzgdypS;c1 z_d<0+i`B0M3sbz%E#IBmebH|BWKKvPNpim=*5p8(l=u?l!RFv397*H+$)L}b;;=Y@ zPb$N&Me$Pi?;8P$$AH?^W{9B0@!70SV>gd4Eo*INS=nGoV1j@T(EGV2@M-t;xg~i2~quzQtsVS#Y7zS&satnXz}KCJdr8AqQO731&5QB zMH9;i_c9#|_zHsqwBw?mnBn~ANq^=g9Je&9G`34!D%jnv7C7g8p%2<(nB>ZmGO!4AKXm7xUMpZ8oUph8CH1b_iE|soze=w5Rdus?O6q&^3 z4dwt9pKo{ddg7J%dWxh76j%=`0`^#u*#et6lSAX9BkHtHzh-_cpe2Z)$)eyM-R{7M zJBf3yOpQ&Zz_fVuM=;mwd1pG8i;0u`os}0Cep-Lp+UV{^H8_}wURzjc)LJYHRdIU5 zFqGrom>XH(Vx1GZRE-Pn`05C=?yB@{gJG}@#X+C+`=a3!s=JdVf+69sPZ z)D1vwQpB7ezJ7~ry68drrsuXbq)2UZwKFK6!9hzVBU=bEZ>)>I!T{l+}HjJQL z*iTK-gDvbllOH4*k3l7q!9X2OWkzL2!;a+6 z+Wf3`H7NvpNAls^*Zld+bE_ogL0ccY!dFe>7A>U%+l?D>ogc;_&_IJ3ZxQku+2zIq zx8-jbV<=K*PniB$U$SIOGVetM@q;*uQLLDBtF>5i6u25alMA#4n`%MWWd_-%+GTp- z)?Rm%KdAMo5|9U!`i&}42RnViW^#3sXjl_L> z@{SSHv;BWySRd7eSxQ%>pP00il!vD$KOY|fAt5o!V5O~Fa8i?+;&AG8$6L*$D{?n)SsvPL>ZDG7qlYc8R z-;48eY$bC*^{ta)<|zz}+T3k;c${RAIjn{y;97f~fZRPn<*mqUdQ%5#Ng z*>T+lG&D5DB_#kO1BT9y42IK$;}b@l(M>5DK&h#$%x*jo84?29xp98$F}Y;K4Bvwv z3*JnRJ$+jTTA%N_u6i3g&42wUfnMTdOP7!?*?Uq_$#afuMj)D zBMTxwa}7cUSA~ZLOKk4OMrh16;&M61uO9 zM*;UroBAlDd#~J(8klvO7aNn0Bqr^i8jI4ANDalcS!V9(*xKp?%PhN)q!e1ECoi;W#Y>dTOiX|t zor0dUL)zIwDk^ztsr00Tq=byDxU|HytoW?d^wiAkys7?;xs}97oY@3~QeR|raZOvnD*IG`8eAgz8sY#XM$rXJ# zOw=CCWc+-?`!5$I(Kjhe~V2_%8E9gM%9QluY z0X0C(cU6QraC){L*w|;Ik!15YTPisyc}Qrv$Q81YC@Hf4A)_H47iB@*1EJS6MV6F= zs?^o0>v*N!9$7t?fExz8jG5sli6KLUYC7J_FaC&$H=g61FVR&jlj_-LHksptH7Ul< zcGI;||Fn=4(|k5Zkgy?3gmsLTNOo6ZO3MHYS>;1xqm#pn-wm+l4HBZa4Nl``W1bO* zzw;`u56#yhA`|DBbZB^{YBWk&Yay9hV`-i5n4NF$cXYXY`oR}nqf0Vk>p}H|uY5

OyIUGB^S}m3Q4lL z`V0){oR(u?R%4(DMp&<+Bu&6%WNx>wZ!SL{aB`J#XiR58X@@A)Dl65*#Q`o$X=xdm zOg2tlG6;;B;rOCHdD-tWk}~5-K_H2O5H5lf9)kU0Iym;)3@bY{l!Z3#&skY zVF*1Rn6~%ai=oDsB>CnjyJ~h+mWB4RQ}>DHbakOVT9>Pl=hLHdrdyn3+xV5ArG(AB z<*lWF3{JcWXLw`O-9IR24PWYp@on21#abKjKQW}b>bC|y7KP_LX*a3(f@ZKRsYXGI&O*t4e4Oq1k~sp--g7ePn*BYZ^f#WilhD5q@xLU zAOa$9=a!ZFMF&;nC62$%(a{UG_3x?VrLw zRZUZS&eeYXG$+|hG#0VGK|v}Z`6{jfxS11Cl|EU4$e%k8dsf+$lK z3?Ks&O3pp78_2rY{S2h(bsKy^6T=eEI)M9K4211!m2=2yGvFv0chy zn#iq0%wfum16rmZ6}XRVjWf&3jH#@$5o~TJc-yq)dWoi@Du9<}LKySXje*BcTdyky z&t4a>o4O;Si(Uo69}maX>Z8SE+EOomdx^W3=UI_ezwkM|wxYn)Rk>J zeabnl6bTf#<~{iq&~`<*#5U>Mw-jAf@roANq8F0ofk*u`JzPA6ImL!bnSIU@9a#1( zUQ7tEJ)O#~A4<)V2+v8~odx)`k8@8{V#U$wTY0a}A@3}825V>M+h?o77UL6b1&w&P z41=c57@V_)QLSqQ)aLcwbNV|%jI9mHl>*w zSaC-u{BO}F?v%>&?y7sqq`nQRUuUrdTCW#t`VU&1mo;t7)q*PK-Dc5r?8LKam z|AeOr`F$k_m+{oHzjd#Rpu*!HGc`!(TLuN=R}~KJxQIei)1n_gMCiR6$m!(^ zrbyjA;zuHnX(qZfWkE>J-@R{Ouw`uO;?DkC3!o{ezc7;QogCIFEYOlpJ!!#)!pI1N#JIwnw%JmpFMa4|}wFt-=lbZN0IW8wZIX*U~ zPUD0a%*3x9pI9(47BqgsMkXsa5d^7p_>O>qsay!q`jPKald_Z3w5lm65IA}1JrNly z96cQ3k7uS;KeC+XITvmlMd_Zvm@grLtHgF!uJ2LW55#%Gayul`g{a`B&tt)GDbvrv zVa&W3dOs=Jz%p*#sZaUzJFMz=y-fXb$qu2?K!VUMPNQk9wr8@oYck<7n9KSn;X-R9 zcdM+`+CCu}ORzL#;nI9u&kZ6%qMi{oj--`;Cb$;!S{`y%ZaD_^0!LGi?(_yO<%*@f zE~)8C{cI-SqY~(r&u5gB!MW2 zJO(nrnJ?VW?L8v-wilyS&V~2!?(VLkz8)dq!-tDUFER_q)-^2gOdrL(VRL7VuQ0jh zCUx!-j%H?Nc6ODkHnS@${PO?q0S9BLvrBUtIE>eDuK}`M7B7)ObD~;fP59HF->=l( z58z%t0t&-_%#aZ$;)M=c1dr5~EnfmHA1EX$Dk>@|ku03~kB6Vv87Mh>*Jj=TO#i)G zfGi$M91xYs&I0n&4kF6x-(Qz) z{X9a(W%|{d{4~VQK4PBHY#obu@4$XrlERrXmb z_^i{SAvC#ZuJusol%o~>+(J34w~Il6*#oQ$9R0mq?izU%+??%wJbJ+muKVm7dC;|D zou**pSNxodlvj+WplCOOwn3Ibieo_mR0b1BlJ7~605rmAXzcRHXm5nXDHVTA{ChOK z6Nh-q2rr@g?COJYe^K4kiW-#^YkrTdVN9*K7KEDsl8b>Tn)CR~F=1v>1UPf4WWthr zF$a5dMuy|5sAZzF<5(!|EsfZ8W|iXNo^5Uq@tdonX}>WpvhL9#KUzjeNt@q(G};C- z%g@+$^pNm-Qpq(2`;wyhjnFxgGxkWY7Sm>eWfmuJK$z?9l%arMY#FAN^*P^8Xr5C|lJ!CgN-ImK@>_|0AaqGFcpkFTi#1N%tB!R2Tp|yaQxjd6)5f zxUjd1Sa50`=pe&$B8DG47?n+`*g>m6pOzAr7MBW$Pu)j|qSP!nMCeAK;@2!L;lcup z{sbJoiQ5qE{-}F@xGc1+zsx7T-@KmbFHb9j&0+%JvT@H>Y1ivC z+xBse_e%SNll`+If)-F3DpKhx$VCfqVQB-6XPhcyO^~GMn#2@CDZhDKv|fwQE`HK$%)Y zvo~JUlI)ub_Dkp+jp&(;tQ&+2nS^&3^u7<`_>3ob4J8mKc7Z<)Nzi|Sn10SF>hNmU zsDZ`Og+WY0$PI4mOuuh%%+f5YbyxE0=?i;p61M*^-Ha^00}yscC1Ssj}RD z(Axg|@Ai7*AaV6z`#zq_l+YFSAa5vfyuMSUS3j#^w&PLl#2j^oMXN4;t4=d&6BcTV zgKJa5${Jd_ZL-24v4WoE5~-E+T4DMs7#V}Ty*pU%psylsAyMuH5w1flE?MuaE1Bm) znj+RBJO3Yj3`=T==(8S<5k}gq{jlD%6D2S7HbZhqNO7n2zf`fLToCS%oj~H~;Ro@e zS^OvoeAD3!l{*n-EL9zyNW-NVh&*5SFklVW(b2K6u+Ux8?O&0V^ABZ0d&%_0?WVN9 zBT2lGLhgx89N#A;B+e}?PNedit+%;5u7#<;rPA zaWQ;oFWdCO@vTp%K34xvo-uo(a8OY(8<5==Vi@}!usCO2Mp0}?u;2lijb?4zmCyOZ zKjIY2fG|gob{H5KfEog(CEz*&;2#jpdV6~d*c_vxqJWP9c&vA>2i`dAIaTLXu@kZP zu=fh~3Mfq|#VN&u`-5Y9zBiE)!NdIsY~$Vx9zDN(5EO1$)oWZcY?MmZQKs72%)WyE z@cZ3$tB8n!gf<-HRi6FOWVg|=RP@stQrHu+(UzA~>xPK%g?`5~)5Z5g z`Aq|Jt`nBm=n@5G$vG$20|u^##MPYe7_K!YdAi81T1m78r=PP7F47xJTVuq1og)(s zaU%IQGbv{oT_xgK%C5$b50$WQdjUnsuFh3=YFcHzU{TEd83K)r=?_KSTSevyy{)Z& zcBw@tM~tlwS$qOl^~^h_`n7m!6s&`!Q+=Jmva+kxRmAJ|-$xJx0jfE*DLAagd?>L8 z)de^8hxuDHFoxfKtrGg=^#Pp@I&W~xJ;(Njg=3T-wdyQ6XK2o+X+ur^li9Rymj})M zk~k`sz?V!nmK;_#kT`e<%LCSWz~X(W zddIMO>>;d5O`<37wWpv~ zqu3YeaE4gAvL+nn^1;!g%Np1=5JYA1Ktu#%H~i6U+KE~at`kT30Hai%UhceUX#zg4 zCT+=~`Q(a8#=M`)-Uwl&{zKeKzz_748j(i7h$F}?n%qJ#00iu9JE4YWcFG{ zQkF_u9+qk@z*Qr4o+q~e52`9{O;11vzQjCGOuY3VB7!+_5451o6{h_O8aRlY2tuOx zBIrF!x!o0CTat|>jt%R~3pyXV&32!*@G zg(o!1KEUS(#YuMZ_;YeQPH+^w0yUao#nk*R*wETiP{(#wZA$Q$6&?f_87V1&5_6!v zMVR_qsY;p(olYJZdb=MOhPbDMGhc16cwVey1T@A?pGXx9IXpZq1v%qY{7F_l-;8Fa zrnY9TSxO}@m!*9Omoe z4(&knKWyscqdIq%@foJHkj~VMX{sS{IXL@iB201Kbban<)zHN0+Dc(q0u1e=KTB7d zC z!v?|x!|Y8v_zt03`|VqV=Y0?9v+(MomA6mmJ^h6xL03v=RySsDXLo*bbaHlfc6f;I zmoF$NSYE4bb!-(O9igk2ylf=&3>XmKJ#Z4ion`7Z%ho*6qjl5f9I%iO%fFeZ?JPM6 zu*3o6{T%z91up?R7Jxps6c-+%A}i-fHncd3-mRa?%9ygVSJ-rk?0MJHF4WB z+dV*38YtkW2oDy*V}MZl+8t)NS*r27`_ko|>A%9qwyZAhd0 z8AEh!vPC~2%j4PVwZY@6snqzmH+yi++2Dn9MJ2*cY$X{3nfQky=YCjJo7CAfiyQj(wEa%5E!Mu;fb`6C2|`@CkUc@&Jn9^)iD@@q zAyKeeZ0YDIcMl&Ga^dtW-{(+Ei0CE!_Fl69`XG;R27l3r&LxZlgW^f!I^K^Tz<5d~ zB8d{lOrTLUdUgkFi{)k7)RNh__(EW##_Mwx6t)8_;rKmnih&%}k0e4T0Z0?VzF_yS z6VIQW=raSv;4H*<-Z1Wy9p4-#nh!oYP2KZ@Ly-x=@}cOd3XF&);N2iv<+!-`nHgoa z+8IYI&Bs4FV%afTu*!-xWdS7?n`x#O<&Iw_A?=5;7gV`#l&1j#n#Bu=;zjl8QNruh zYAd+0yO-I2JVs-2%|_QfzG;)L+8DuHyN`R^q|}Usl2fc0>pEndi#s30Q^0137HR3E z>Hc`Q9G(zawtEu^JZ~~qtqb_nOV5)d(kwEAxs_ZJ?v0F~0~F;sG0ly7*&lnFMVGx4 z>{)5rh_EUHEOPekwe>s|iB3;LE_U0&;iD51eb zVX6cH8mtYda9iAng@Ay0(l#AtHTM*Av>SSPngDS=| z#=}cp?bT4VCLth6%OvV~fWUQ|g8fx3F2RTX)vX8Tp8JtSdljyssgcsuLj@;wkz)4owdriVKPzBSTgOAL=HDw6(r=6`?O0Ej>a7g)nMVVG}ml{O#@@;;Q2LEZa9cFzH1?%`E8XUT(kK1dOax>$`ENa`RyzNKZMbsu z)CCjTkSpE9tc78spJfb?J0}7c zZ90&Sqf)6E>!qSB7EYYF#vb>Qi?I7TK-W0mYDho#k2oIOUULg1*Bt4Mzo;&qMEv@@ z{Da35s5z+1Vb@HslvRr+XJiz#7@2zri>Hbt6m|i`vkt_v!gzqpIH6BsPcO}Whw5Vu zP)KZB5>4w2^n64TB_5|xXbb+xtBM{jp7<8)rIQ^qYZMukb`tr*jf)SPd0{R*ywwZV(Wz6^@SxK1`EMbeDpiAHi5$jgWfFAtCY3TR$ z1poP}0J?*_(#p4M zwEIREG!H62oZ=#}w=|`t%7}l~#OwD$uU#|7I)NXzvgh0QF+6`%dp)1pETzemMn2DE zLUZ-c6DCzTmrEyD!8z@r!!gaoe$ZQnzN#n2n-^IbjXb^?==f;Rh}H~`#RMfzZxE_9 zOrX#Kkzj`by1$+tTn5)#Khnz_u1qPQI_GUv2M^+dOMJ6w-J%#h{ONr{n0>y}bg0vG zAYqlmiE{_`9DnIX9GEQ`Tih>YAV4no%F`|)rYIaD4i5?J^vhrkp1 z-fOc1%dG;k!pi><7S~sH$#wp8W&YGgS9R-nB(src)`g$_lWT#9Rh#4A+UOu$VoZGp z8LwfX7eDU@h$i;k--2hq`UE#(zk?4JnkFeB4!IYam?;bo?=cu(wYH1&m$!xL`@Jb1 zFE?uX+nHat(Vu^RjW&cM&b$9=a~R|uT{6iNpBGxMj{VcHJ#m4qlkfmM4 zm0GNzMb>uruE@3hUY?}8n&kh?+Wx|Q&_1*ng7(`%%htdg+bL$oopVbVsSCUPO?IYm z@z{iqE^nqgIgjQ~Wo2b+D*!I2LcN-IwBdg$O0uTej2BKc9rq^=Pfku!7e7<;Hn`SJ znx`r%Ybz_MZKFOB+lHFs@}i5*_%kSG47k&u-?e-Wjs=#P)g{#(9a*?OR6cy8-fu_m zPB?%Qar=WWk(X|giF+2%ul})js7|qH7LZJn!*4q@@78>NbmPSkDV+z(k@Kc$W+j0F zgLeY;AGG?fvWkb8F=yeJA~{j$D*P;7-%*A)v$ot}iuCK&>)L$K&ih z+;4D~FzZKUP0eLsAN}fzKT+&{-=zmovQ@%&L`9G7<}?jUEZFj zt2bLD5BK4v%`+M(?(G|VCV3Pu+j#hJoYC*e=VlkPsSOR8+->@JQBUfCIp-sBhC#0V zIP_J=jhoOb>ypF|L-F1-^42Qp9ZqMHaNv$NlIXT`B;?Lvi@N#Zv*@l6#NAvaR4lU5 zg9n-xLO?RoTYo^M`qkW|>4|Jvdl=4fj#Prb!JH`Uc+-k`wP77MQN0Qm=B($h3i@J& zo&L6WvH_oz+|D1>=Rfoi@QWW%WU!puMm(}j$SM;~F2;&}Tco|qBYu1h-xms&nYGv0 zE~*sm6nL-xk(3-={X#qtrnOOcS}ED^bU^9jfoB9TLBnYQ0aVAb&bjsaY*Yc=_2%t6 z;yAVnB5?1S_pYEB_ z-+*EIKCtL5--$!Whpx;xEs2ehmXVi|osv=eZqDq-?%t0-4z=~)qX!a78);j)1d@@5fMyic>;gCEPCP zQu#d$IMmd+vuGtuIYM$ww+d*`h$c#qVP~>Ro1fzx=o{&_D7BepHoblNF7Dbvdg4yp z_SEdQOSskV`e;*$)OZfTEljTG7^4aTDKPO_32jWldf%8hixoqM8q8U3ma$>09?9}r zGTuxd>=u~rQxus{6`2*9(A8i)F1x4c)Qgme&r2v7gV1DH(A3zEtNlm~=?kr~BWtsq zxgFOv+k8<-z!*K(BHaZn6m<_;3Jr2Joyxy#ck*I>Vz*Mrzv|&}X+3??e&9TQ@{K&F zr@A2{_DK#SGDOnf55ND}AA>--^5I8bqaTRy%dS*j7#qQfY3-sBLaZ3A_&kdY=4b=k z*vGVrqGG!6vfuC)_#xOD4CoP*9}r50O<0!D1b^c=En9IUXnh6Fs{KGar4QXv7@9u@ z9gzt+a#?wzs}uZ$kiW+2!fA^ar^_|Y+GkJ9f5Qmwdbnexo2pBnw8TR)QT%<2Qnr(f zkEBDNFodGTLS99gE?SD5=Rjf`+}kYpHCpm{m-v~tQW7EGZh3pXez5&>?o3R<;3Q@2 zq3c2urqSxVq~&a7zS-_UE~UO`fgLbn2XV6i+e+~39V;_G)p;TbrF%(&UfL}<9@X~> z$bt=PZ}?ws*N0lU&1CXvyN<^J)7nb`X8u^(@EQ#UGYTtV)bWomNq~i3XBHSZ_reL= z_0BKdeo!1aG{ff2_-_b$!%ct2=@GS00Hd}0*oi2L)X`~eXl$&`2w2^f0VkWYGh1Hi zy3*28XEm#@#$N#jD5B`k42~zGMOuQurN75VL-_R#GLP-&p? z8CrzL+YcytBtj{j4+j;$(EpPcGJWhVl+Tun%m0YBN5`0I07wiKvG#;0@l8-V7CKjp zX#SLyF%U$dsPH0B$@5wm{tRpbYUiPI0UKLxZf;v!M&V&?_PZ0spK0?kQ%4@6EKVym zb@gN~-N$j$-wpcTUnYHouQ~xhb>fYX3YXIi?w^A9eTvHy?}gb?R-?f{3<_m(>%p_smgrrbR3D)=%g#hqB>g#J zPX2R*dwKS0oj19@k!=AMQ6*l7_eY+}l4vk~X=fRP-3bMNIl2wq8te6bw*pY5TQ*ZD zsITWYxUX&rZ;*6fPAj{8+`+##P?KMs-SDn?%f1JA-{?y-UfcEd62TQf8O&phdovJU z5YHvCWlsZ+k+z<>>DMZoVS6;a==T&dxgjj<5_h>|x)7 z`}bK{$OACwkmKUZzspO@OJyXnSg=_;ko@zGp?_v-GFW;%&?l`#V)BDM?Y4Hx4_Y6H zJd7bC7XH-W*8At_f%XzXfsfC`(!odx(8qXKI+%J`y2xqC>4k_Umdu%!I`LYzi&~9| zD-kO<22me}?V@YvBN!b?QwQXRkJ~u*Fn$|9} z;tq2?`EV~lB~T;pwncn7gn_u_|H*!t&wdzr0fxRmno?AnTc16? z+#D26XYcDTBaWW77+W?Hxpx@JOQ)+=LHC&-b%CkCG(X?0$b^oq=DNmFmG`klpj@(G zki(Rq8~XDe;E+wYGS&$~lloqrQKQaYaaiU`MFRfa1;$Wt3)W~8WoVYWn%iJXuuJTb z$o3PLp{!)zYCPN=jC{vC=I{3CFow)#{nx|AqWwUw-j>en?#H~$gtdVjZdV_2M1iL@ z%r?vGf--pv|KgQ(oTx@UIAOA^$uKK3>&&4l9j6#T(|u|5k-08M1nYJ*sBXik65EN7 zS6Kav`TEfExLQm<0o5{Fcx9o8pmhDOld^SbFt*h+@_i|ZhvDDc$(bf365Cyv?2dTMGc3sJrC<6Fx#MmjQIY8saHp+00Od zlYj8r;Yl*V59ww(85E`SMWo}~VRd)`MV3ZN7z0v4z(dyNehnlwuG!wpqf>xz=C)ik zh}Ceapuc`>+JQ;myx|GlGO)L>H*q%kYTO%{gl}VGqpPdy5M(YdFR!hweI2=<){<6Z zuGz$L0%#tX_~Cf+hTR5QUu6ZuNPkTp@V_Q8;79`kY72`)KRU-vyyzW7L`0sm_gdFa zQ;G@C8zdgoH(xx?O*}JGGlf>3Z9UG(^5Z{!5l5@a)u{43-TS*TU-}C%iQcFimWIYi zoX_Yv`#S5uJa}cp|k{#?;Kr)R!XNQRoqe>mp(06d1bIO6!Y?2Dg6Zd{#UZ zApcYBPaNh;8_wt0WVR{lj~qWdH#Ox)QS6_|A)7vKimVeLT}Od|aK!wlv=o@Gfn_JS zmFZ`rKYLD;GP&Yz9(VdUP}&=2I30}UFD{AVZ(1cB@E~2FRIe7*f$F<&yUN_#V6kFCf;eX zU4@H{uil~R<~&LZ3gAKPAuCKd*@S~ZT12Ie50^HeF+4KEX!2q-4nrCbkzpcn4K z_1pcnP$8l{>sBNzl4ZT3@|7=iG_5gI9S~pQ1!NTAJ}h7f`Ojb2`57~uPwi(WRN+=B zK3R21h!lfG!k<6Zjjc353|Ov9hLJ#^1K&68i!|vHWYh@_r_soIx4607RYG%_2kKrq zTlwSZ%zbxpJ7xVShRl58|$d`=Q*=ZQ2{o2R;A zWh(g$9*dU;1c>dBoRz+?_%B|2yR^!MGRR9uy*cHd=2^$H1YPf{Y&pDqeu#-Vsr<0E z228NvWeDQk68qspgp$;-L*C)kxH%#V%V_AOUG~~Iwh-&9X?ysPiEP48LT2kHskNr# zJcdcxZ0=XPlJQh>DJ+IBKvznL;PvlNlnB~Dn}heSE4_B8N{W7B@{;1zvS~y)pf6+m zo)a1FTYljZgV4q1mK7ATbfYSN9GsdWO;sgo7Y?beBEaDU4Y|Q~=jgD>5%f%~6)j^; zXA(Q(_el4Gy~53jo?bB*J@#9{JFD^8j;L+D8x3KdfKlowv@gOId$JuvVS1r}RJX1s zjIM&}TFTzFV_{p#o{F}6*YcyLgH54IVj82Q%2 zPrVM;yq5EHraPBG2PpyShXFSKkE^c$%BpSGr8}fMq#LBWyHlh==|(`hk?xf4l14y~ z?v9rh5Rp#luJe4~KL0s;@0m5sVi<-On03APb6?f?@?p6xzCK`#zpKDV&U#98`FlE> zXFS`|D89o+RPI(Z#kDr~M?=)m0%rJY?4S;CEQbGtK2^Q-(^cS8!iOKP$sIm?!IzgO zK?@^JVxT>JFVeVVH&323SgF%Cub8E8qsuss(otS4-Lz0T@Jn!J2-z{H()#dqdNox| zr;htc7gwH-&t&*eT^l);Dfyli-4PD;HJ-KyIXA{UGqfs-*|tXcrLZlGh*DmkJEnG+ zzbQFv$LSvf7PA$WZ);HU+~*d7a%LhTP^I-*)ev@chi)rYRO2S)6@;8yq46b*a@Joq zy`OrZW^30)e9?OtY<*z{eW`(gAJPBz#CIXQhB#B)8m0g_lYfXaj<+aSUT8z z-JF}73-$W=;IFNNU3GOOPlieW91AM>iPLXUGHjl#34pp}WMuR&Cv_}`SKcn9a=N-q zsm8V7!&_}_G&Ho7)YR8#QEqK}UmhQQamks|#}Xr-k4_9LwC|suL8K;-Nj@@3yn>PE z_UzJTa&P+uvY`M|%`ygD%|#Gv-Yk%+Kh{A163>Blp@hYX!XX2VVcSIPqS+YK0Q0J7 zao>$bVTL=FsW;f^-0J)G$JU?k*%-hgl8J$ZjfIJkiH%Y8N?+elQ(sfx*!xFQRUumS z-RC>8$_$ZTv7Zz6DDEmq1aD3_f=C?OjVgG)y3wJVEhagNVF+-`$c~sei&lN_NhdP<~=FC?aodcb8;{$0p=BH8sw(4AZR6hs#fBZ+dyn3S(Sn&)}-!G2fc zC>2xgSJ&&~`?hTY%v~hsLQRD-)kCzYC>;W+Zs4^jVBH~_m;?Z zs;})~HGn-?zKb(9b8bBgZpv5NFMSBj%Kh{AXRk;DPPufR(5RE}xX9U?o9>mz>M3d_ zTj79?7Pso9?_o|PTL;T~=LlcRiEnUis~vglw1}lE;zl%ZGBkC(<4A{PW;r*LG(T)4 zzu&;##12d)Z`q%1m~AK~`Z;PJ$tzcy&cN6jrn@K2V>Yj@%8Kq@BpKPG4KH#vkzE;m zgK_@sT2Sz;S%3Pm;8efhl(%y)&-V;q9hW^sNx3J>Z4E=viT?O0<`bEvy_lrhQ`xZk z6mG}(559(bE9S2R$m8xXek4vU(R{14)8CQDV_|$!yNy}v4k?*rLfwdlu3hah$J}O= zxl~w-%MqfixnDIQv}ewx?>E7FI|Qk2E`AjuPBkj}XsxZL!!?422<3!N;Pl9Ud64?FN8dF68hdyGc!`MM~K7B0fFV0 zbx57UFcsUcsfRJ)gVnj3Nf6@y!eB$rPGIx}9kMJYNfwp}!W&B>Nvb1B927|G6-c01 zV*{YyT@lzrPd@26L7Acu=QYCyFgPNnK~vPe(p4c!=2;k;Jispzs_>gT#Y0*SCPk z@Lk==g>WB-X2sm*89+R6)}C9c(Pn}?q>h+_D%D|&TFnYoMn&}O$1U_%7y3rW7k9xn zrP@qQ?^wzi{oxvEk$QJ8bie^RC1q}L5!9SerIs^9{ipCCN0k5x&XjP+>OxknvvOU8 zGlM1JPd@l={c46NT3T8l;sH_~An39DCUBaA|JciA&zw36USZH5i_;j?-ZO^#Yqa>B zoE(O>b+kp1Us_!R*dj(&>C#ll^UO~p{sfN$j=PzMj-!cxT0e#uPK@vbD>^}5sgiBa z68Z9L$)8&w6eRJ2&PBVEt!%&c2SX@XkYYX%{KB*s(Um&Y7C+`gx+m+$KAZcU@P?$( zj^5%otXt9Jcc}PGjF~v2Mmxk!zZ@6G_c>X5i?i(ySZl7BC#^=OhU}g-uU75gcbV4w z*_^}>=O%=7k=G6R; zRwS1x%gVcrf2j|```H-cUKHd_L8B`DL&JO(12yXnwf)XG(YKxP;9iJ;>n`Fq$nck? zh`pBKrQ7lraDkgI5qlA*@E5ybQ(3U4dsReSupGFIQfgrZ`C7=m(_QeGGM>2oFldPo zQzmak96t^`c%91&g7Nqm$&U~$ZEZzOMOE!A2k-bi7M7CHuV3zE`aVLM22&3QlulmN zdW*OGQF#8#y85B*ZZ{4kD_}kM9%fj^$uGCdE5!4vZ==M6aH>oH$bhwxb(7$VLnpet z&~`>oaw*EqvP;%^7+JOO^*6j9Xpx+(2Egr-^92RB$R&~y;(}a%rf{avt&*1wGAUmx zOlg`caR1aKyH(Il;N+>Cj%4bELAz2W?@3R1FJJ@bRn+M4dYI(u@}lzs?l!ea!Jqs7>X%Yvs@)aesvk_`@}RG2e`lyo?liU7 zmBU30A9Qpm36%Pz&oAOT&hE@}RKeAC@!@n=hZ?TzaTgOhUUEVM$XEtyc^XpD~DrbGbGPqA(D7NZBVZBQ` zt!5W)ePO>=qH=5dZ-d-F6J58S@_M{XA$4H1GM!fCJbzrWv&1K#=z;g&ezM@BPF(=W zNqPfK_1kE}W6?aP{%sm;g?vmh_;{vNMH`vmiE^~bhfNQ$5XE^tSeE*Tz% zk0`97yj)y-)|~T6v!D=EqS@Qy%DjPk19>R|dd2E$vU(G$#CI%dy}i9rQ7B<%X>3Nz z5J(WVe4^=3Q;vv2U}*vAp+hd36_>i@(o>HVG|3~*q@d{yAo-pFRtX;n>$-djsNAp5(3^&9v)y8b{k2e1@@lLGM{muxJJHGuVqRWm=X>ifBN3k^ppn5I#sQBvrth{ zNr;JMedXY52qg=x&hAJBw;FL;yq~W2_0Gph-J7M;nfqu_LbL~SwDX5!;!(eUDxb~-=wBR9;mrO@KX-KH~J92&+DDi&PEKL zwVSK)c|IP0W)bVGFg~Ps2|4&v3znL@H|Emsz14822Ofk zqeeZDD$1Ey9o2F*^D$g}0-v_*1YJENy$fQwL|t0G#1Q^-+BDp!9^if1=TtYbLjU_p zdLfmsGTkKf`wdp=RZFew9__%~PgmYQBg*PfW_`DAHF?DqrW?YsNUj+JPt)|fPxG?`f0175vP*d&7Q4$i1 zBI2&WW(kj@Mb1#)B9 z&4=lnDxz$LdR)on$=qmJn^_OjTAn+igQJJCUZgga2sjoh4&tl?T(WdR9K;W@$upEB z6N)NRpT+jS+E=jYN+{09DEC!3f6HvNLBk+B9%$`-t=7>L+2r9|V>~G`>@$VsTM73v zAo;BG{!gqVq}mtaXL!~XSkQT@^J86QJ!fh~#;2<|IS#VqaoMt|y(JpuIg!v1ZJt;5 zUbGO~W2WL{M!X;dlRS#unjIZbI5m)2@4B9~{{dpjpx(Odh2onx&3@7r44xECyg@@_lE?f%wxR&eAc zDf%6LF!>7{l&$Muuy>Nl`QAUs95FO*g^ZzFh5ZfJz1t{=JrB=S>Ui{?tm*72?S#~{ z53seZu(d6+bu6;om9g#ysgPXfUT^YWO8<|uZz$bqdQSI?E)8-1Yirnw<3{~z)w0>c zD+ZPsXo9SXL6_B$r~xc1@p(a5SXiYr76Fp|JZ&bKrYn>Z7`}Cc1@Q}Rr>$805B_HU zP9{!(LD5jq&{3HOhhad>%E$5X^Diy_UYv!cwDIxrnJuK#ZrXAd@T88n-D?Wv<^Qh1 zlnQ_s5WV7r60d?me|;ekUK7Xi$01U8CI4QeXq011&r2dxqDg|9Me793_Y7=o82l4p zK%20XTGB6qz}d#BCosHE|J2q|SNF;cG}F996Mk1Lk@R(yrmWIts;;U6u0x7HrRiha zzzs+_4tVaWsw&bq?^+FO=4};{z%LAXMC?ABCN z?;jqLjLtihe_vuD9RgNDIAhp=C`twFV+bPap4GJD_r>{n_|A)!<>iF-djgReZX;l! zTv!OxUed4r)IX-N(_LBHd7u8Yg!bz;AOJ?!uvJummKj_;tbD9enTaLCqw_mZyo#gR zRg%BnXwt3Yi)u!HA^ zXCpOpqXy$PH(JPyOxoLhBjYAh&An6mNETLB>Nl?$={Rkl+fQ4+Sx&+IQtXp=TfKGp zFbG2vmA`_-ON=H9OT(5=0`FCnOs|&1X|X(4Fm zHpvuX7%=)s7O(&ui!q-fBcH9xt=GG#^Vf3X&W)i7a`>E{gHI!d!O;07v_EvN5ejc& zK!IqYcak=Ia+?-aX)nsVra9J$>=iyc0U|rJ_GLrc0P|mhnt-IP3yZ&rn73A#XC#;x zYA2iI-g#Yq-<*HpY^2^q+nr$R8d6^yvv5~!RU)*`3^aDdxut9@z*O%oIDf*kNcvMH zEw#gNMTBi(n?@r*E%cg}%pyj1h*o-t4vIG_Nmi>tbLQg=rv=f^D3%IdgRc{*IGT8@ zv(Abg3J!I4Hnq8|l(+9g)EznALVLATe|Eis;yn;DIW=L}s>ZuWbiBj>LYo-Y*E<@1d1D$2{o7~svv1A3kVnrLDG$Ms6<~;TNNpoy5GC=0n zFJKqp&R2f&th>4? z;f%P=j9j-PX5hY%xH3xitwF-qInG0sy08v->;0CS@g-H9=9N(BYK9-`t@}Ng@n*Gt zF(QwW=dm}V(H&z|x5Smt*jaxSEB#rQ>ueUCK&ax&^RE9Mh9nM>3MF^YG~EBa`3;I} zRA>ZYWD3M(@eCXFS^GEuoq$dd-q*vST$e0(svkeZ#n0bjK9Yp>iq*NBkq;C}fDFE> zujB0F-vu1F)zVYaz&7sk>W1e#_lnV{%rb#QE7+T2No$>O!BC$fnl-NBVPd zadu^P{@484n(=RSlXr&l#KT&~s6mpSC4=t0fSs_%lp||`JRY$_Na7VY@x;FI!^2-O zSZtA2c%=$$l;HJGZ31yp-_7dZO=rUnW8&d3rYeSt+GOIx_3U0S;-Y}VEQ5*Qn1_Uh zwu3|U*fwzxj{~nkKtOZ}{^@`0V=vWdQa6sNM9mjH;B##>J(6XtVyG z;GCG2X+{&zYoU<&2CEmQ3hl4zOz(1mD+PF1z}yS=nzGSvJb6~eBm5D>ma}==#^T5l%a)}}e%cj#x$6*{klcMBQCV*otBr_MiHTKlPo2lba%BixGG?M4!+*S^2K zG@-t)#X5JyJ^zb+PQHGgYi=~f755U@>oLqAaY^q5XR1gu#qBR`uvX@<5?Hp@5#%m9 z)|$62a^w0pobUlZ^8t;t>Q2m=qpm&x?I3kri11;dAdSY1-GLv?ZZ7}|aT<}q6UxCS z+NBd_Ic;31n|!ars!^;^3%W>Ty0R0M&CCZjd$a|0f%{m*Mc{x^7>}XJ%7|U$(f7O> zQ(@7t;!rI9-I6MPitRBQ9`mr9XR~%%W^Trp6l?+xVcaL-D&$5uXn-l&@Ek3>x zOJjCl>P?+Ybz|4sdIe3@XF+Ps7-9==Ub)X9JG2>sBDz7GvRH(%QL*t+k@0aVF-r2# z_S|oH7-@0pAZRw;yr*-!!!D6YDK`AA_}j6|O$hP1BlIm)A@xbTi(CsbRYl3JS1y13 z*L-T$4XAf&aZqcpq8#y~{%&W4zdL8FJIMRcm}N6?=yv^}z3f;=cU(&6uks<><_Ia) zug~;F?!%Dv(W@p?cDx6yoc5ea@8m>BOU*nhF5U(`wQqV;&PhXF+fVH~7!p2N`48dw zT^QIicJSw%LG6Z=?AXIRF!jB?tOl)byPkRH{nV`58(kkO+v?}-^e2`a$3QrW#?D(V znlIvrQQ7B|)2?MiD-Qjgf#~uN1%nr_%uD5BmOQAg1Hjeif7d5#-$nF5c)xceRrVN; z)EfNla|gVnQr{X3$}GGA%O8Wq-$#CjuJ%(ml#aJOR$8^4I!zmzep8&i@@`oX{y6ph z$}Hd3$5?MiRY-n605vXh$Nc|8w0~}HSCrS)LZ#&>i%qB6{*jmTY=6A-6|G&g`}PwJ z0hV(M2!k;&Fo68!nW}l9vg+zteuFWiSio72{yvQ6Q(rue9hl;Qy5_Ulp~UqFC}?Z(-l<{>i^~ zF?xejZI?&%7xI+<3sJ(}NPRqi9AIGa*^rKaRHhgWWZh_1;5txaL}1kESM$fU8M1wr z{B!dl_i8+^L+#s7LlcuJj`0ZUUydHSy1I6DhY>FpmGjGUb6X!Pd%UBN)*AM_$4mN;LJ}zFqkJJN{PmzWL~7dkp+;FgGC~A%NHJ zQpIFWRSZaHfpqf?G9nUkPQEz!k3GJ2aywog!xdB%YDxIi^EAbsmBCY2D zl2-?*uZy?&H{ni=P|Tmoya*|tid|SUo(kG#sSyWWk$z=sD3&amQ%a)mUd=8=yvEX+ zC=Op{Trlvf#;Kh%*}~R{mOAQN4m=~Mti7N}QC1NFE@l-f5eXTY%7q<>&|_#<3R{JR zo&H^#e}QW&zw?{oLJ!nMk)Gd=ECEB&t5Pd>R-Fi@ZhaE!J(uyit=lA@d%{D59tJKP zv9j3VKSB;l4E6Z5>LSh;k|s4*lWKXqd9tNsvMl)NA%rkQMT|t0AGk3ZXJDEAw3U6e z-3;CAVQz8cHTBKP?$=2IZzm%KWATgs-7DB`c{@YROClm-}ao779zS*oapFf6F zgw^xDx#pexh1gvl06!h;&5jpp2mePfs4dp&@AlqRa!zRxAOX6d= zYCx9aEmXp^K;G;Uh(_%ytLtlQcLdUBdbaEJ3rV+2bsLy? z{+$rpDiU^^`5yp;q_W;67$nAyEkY|Rv8qxz|F5d|@Zt^}qtaOPKy#_vk4?2!liEcB zT)h0F0j;$8%PZ(sYaMqTGnaySGYfcpqAiUC2Je2xRqHq27wvdDc<8a{R-3D0+Y@k~ z6iYO#-`eqJJ^2Ut`**G!m)dy4!J&~p9`a6-M~-fPjN2p(E3nD5(5ujng3(l=!%;|z z$fKeG94S@==nf+t0;5yeY=t@l3My&Tu&FTTKuZD)%x1TUJP(4GBkQK#}hK7c7G$Vzsjf%LqxZm$; z!Ab6V2y*ud`>EFd{AHURm#gXcVtG(ivuB*^@%dMK)Rcq8H<$&=(=nH{*0K$bAC78)UT#-!7q!m9pV?sz zS$`*J>d8QyHOP*ff5QxI&qtjP^dC?7%Or=dL(7?k?GtpDVczZ^O6e#K8gZyzqGk$0 zoibQwh=nR1LrXSwAgfyZLQu@kKKX83@4b?~G+Qh4>&_EHypTC^!Li{h^v#wHT(YFv z&M@9SQAT8>!W+mNtYLl%URc6ideui{Y%&QMz(A4#9X~>mdI=I!#^7s{C*al%@3H0} z$>DaPdS4_jLd>9^32qC^p)IVP!!_$vMEj*etWVXp3IS1B7wHd&Cqs7+uL03;IeQbS zaK=~x&6HWapn$9|aly1!)#Qa_^2SJWOq<6AJ^F5eR`TR)fg1#D^=rIRy8O6qra%2P z$wQe6=mWgv+9_k(j>xC0tkp~v$rrJKzXk)%l>;*ANbX~IQKHSo$*i_T7sLv>0@lVb zrgJsige8IrZ!)W=;W=fKHMsy63q=^K5)l&@4K6U(L@LF^hIm)>KdwPr+&oN6dRwFKL6FL7tbWC=Z#v zq9wA&g>=41NH+Zj%DrRCqn3ekuDKho$ zQ6Qr{J&s2B+4RRn5k@@-!z9aMN~Cy=hx*yTNJ7|^m*^8LC9@ujJ=7)IY3)}M+PUpX z%B#a83s1-MzSN1(9ck^QykOIXlZWierQg!2ovi}AKs^cjb)!7^gJf>E=Jm2qWR##t z33EXsZDURFOzP~9^Ibm2yRnyLq>lf84*M_kST9C?yh_+Z;-^hjL=LWd#{wceVF^G# z&1Q>afjH;5mZjb(E+=b&jCt|~Lsnm!$rlqnqo2zQ%PWg3;5~ls6STe{2gfuZC0pw1 z%ZrD18s9u7gr(#o&BXn;5Vh&Q-%Vv4Fxxu+^Yj?MZ;T^6=pnB6!dpd;#^7S)MIEmX5Y?&k)ARViEdl=DL z&$2Q<-{kzK7wbVF4k(E)9-g2r_I^@AxVR_nxQVkS-U7(b(%QUv0Q2{~>^&{bMEfxI~z)`}l*jvSeOoA(+XexWs!w1QkV zju?th<3h1oK}EcaH5KtfmKkkYOD!wwof4weaTx76v$##t?nj7g?0T!t>1t0K#riMI z`oCrGb`citIF*lmDY{h-*46LJp81^{T=QU3%a7d$@2C#F(_9>b-`?=qtQb%draYmL zVMZrmXl>AQn^ri%?w4=p6wrA)_c}of)5Zq|)6F7^yP|j=0)}zoq>uRiDL)#STvh{- z!COq3%rCsT<7`UhAV;ol@#ei+J8<6iC5<^vW3bTUyC+!8dzU#4^Rp+Hm6g!<(}SsO z0y7W%H~V@^)iOBUH~JMehhR4!0e~btaeuz5q!X*o6BOl}jKzlcDo|*UIf=eEWEZl_;fhsW1|0v(NZb zU|&i5QoZ&Ac&BbW>hHdGO43jx#w_N(`>NmMv#_gA?;{Vcu4`P5TTsrJB zXBX-<{`94FL+Sb}U+eZ1vJyGo!(Z$+M|`1LJOehwC`hJ-p#r_uwDf~5z?D%#oo|#M zv?Wj&K5%P&RUAtzHQ%BsHSebf(VC@${q!;ebkfoTfnq^WyeNILIJ4@d&Wie~g2N;_ zmP+DPb=nFe-0hlH+Bm$`J=I0+`DNsu2bBz^L1tNcoynWtUjB^iEa8WW67A}**l7PrFzuWYRXNYk%Gz>U`=L{am@) zGWzZ8XZi~+#Zy7n|6J@$!}%{FKW-=PA+=Dak0~T^XH9^;_V&l0$Dbr#0WT&o8`wLu zrT?Sqlx6(_w>HcLBjtk2IZQ37I2}4-d4AtfVnHd{*iqC`*;ZNhy{xv2U0nfFu!q2d zm&Klenf+qNYl4@Hxvsq%$l#K31msr#)IKCpBK;c=?7&N+kYw9*zi1@SmhRKBrnM$@ zifqBD*Uhdr%RS`6l!^i$`N_@g^7?xD_)|h)g*sdUgF;dv165i3*f!8u-O6yQFr@-9 z1W3&b+`{=)tXgIVbhv<<14we}0A6(Z*!=1$=~07Nmiz)2C8Yb#f|E#P7KGrnw6v6$ z4{v{bg9b!iz%d0j;U|L5rzZ{2aJ}BuK|I;*nk?>7S2U8uP^H{*MXALKsrpxkjdS|tz>3&xiKg1lbX<~Nh+ z!BJV)RAa(LPtfMM4G+qAQzv)OJ{PV>CZIa@lZbd>tb^2*A~!v-Hd>rFUdDjK&F*B5 z(1)EWo7qyeT;XEu91b%on4*YSs$W)tu`pjm&h~Cyx=kop zP(^;yQD}zcir|xB**P~Da;y7)F1KEa$yirI{k9u8Q*wv8BPS~}FgQR*2WlV6%q`1y zW zXTWS{BRo|f|KhEXURx~UgQXolqolzC?^x|DHl0eGStg6wD1*!JvX&dVn)$q+JWmf z%`mR4J??jF`SiHcO=&C}1|Ic!gs++JiLF0jjk$j`r1x5V2^wVu(N#WP zbIA8EU49+(adh`*a*TW-7D<^M0LfoIJiJ7c~0c%ozQb?iXTg zGU&h*MOu|vuowmmQjTi$KyL#}+$Mf>2`F{>{{4GNQ%Pw}X-nhMwtI$yWe-gqjFJnk z1P-($(-*k1Aw6}&z|6fBkoQL5aeaAtd2>Tew4X$)gpbJ%6q(#AdG=4_E+4x7f*tSI z#X}JCHnz=~H32dzYZno@ldN1-wITka)FH^F`qj-p?d6Fh6Bwp0&t)=;Dj=%J%gd{d^YTWr zu!kUNY#UDEi!$9MtNFK|F|yQs9Q<)O&X9dK;#fL$4!pS>|Oh?&Ulm(@XhxVd7&Mh z1U}9m4%|JMbZcj?*r;tYPlGjcewA=?U^nqH>jJ4eF$D<$5f+iC)nt2J9g$X1Zz45V%ush?vQuIUt3 zi~bYFEjdP4#NU0XyN+B6PRL!(t|W(e-jC_myWo`Y6H@h8v`z@KOI0Sda zFXY&)Zi?s#Da3EW6p`@gRWzAZ{Rft7vS_m1I;WP`@sHnS(e^}Sz+>8m3>#U;5+|oL@>2AbH%Jc{9V7xyR(c!M_5v3yTXDd-83XLBO`6YCL?$|$TsynIyf7IR}+{N*G-$nljAHvcA zLz0lVfslw;hLB=0{l#yVU3n3iFzdXGCA8GM^qty+_!fu{BcF-DKb#~&FWQ5 ziSn1;A`KZu>9T)1Mhb5rVl%>*|SBM7s zPTMBXu2qJHW^_JFJB=LnBmF)seJwc+1jL!-(1P7lz^|#xu92Kt{U%#5^CPVkcuJeX z<&xv$^L~)O<+W1f@6({H;H-9@MPjiDRV4_EqX?xebTYQUz2Sah6wcRd(c{^CpU$sXTHUh^Xn}tjU-=~p+3@5mt3;HmZkQ}Cnx_s~U49E06 z^eu8Grv(#K5#WMQsfwtA3_-v@Evo>R5UX6$YposYOHSBIbLl2XX+6J-M^HgIN^$gp z$9XmE`x~bEW5t3^;(`YX$=@QY=etWf1{tUxb?JXM7yQPI{X<*L*>6A2zy13-@hG4c zyi=09(tmxW{^mz^EotD}dzr@Ch4mVmqX9ukSwRj{FUuk_Hcw7b_qXC@mI^u%gT&0l ztnAFxglzKkgy3$5kF&7*)?hw-3hbkzBVu?z`qpyS+V!JLMNHBtVXLNk1xrHg4>!Tu zT!!gQFE~AA;!%02R`RLYgH_vDm74VuO(uGRsd3Fe%YtilG4xZrBdDI|RM1_L-HWLA zhhBAS!*)*43EF2+>;bRDXR550`U&p#2wLH58)nxw`b;)U9XcPJG^>UBh=A|{W959+@JUY*_ zLlWr-RDK&dRBMdu$E0iHe^}XtZ|;9@r7P_@g#E|3@~__Uw=GNnI}LHSfnsVBfmirg zqHcn&j!{#&mxiv#BH(mP0HqT^L8S#70vk=hZamjs-dxk%*gj{n?(qYf22UAgK!ZV2 z+i7}M*r6da+p%l{V~=L60Sq8zv+%vjkT7MsWH6Fs9C@gfNXNNr;6h5K4A1=$Xo#(| zbs2EML=;F2+}JC}AZMp?{^07q+rL7aSX~am@LFC(Ur+B2*p!PkD=3k`<4w+}JpaSj{pw)baR+pk+$UFJ3 z>~WBJ7Nq3i!H3P@;pWx|bdZhB+(3qIYupI_NJf4+Lx&P>BqARrP{$hNuSq>F=6j*HdjjDl@3v*K|yK8Xy5o7HnjZGU-m(SKTsIWvvMDHxjDAJYjDZL;G=sVS^T!)r;h9Fd1(W7 zd1SYT`Cx?_de>sk^-MK+<#+#ts`&O~w~8|e+AU-gaam1#d1L3j6th3uSE`yt-d&VT zr;^KUbDogp|8KZMEVMQ*)b~7fh}jp9;Bk1;UuE_4h<($hWsj#Bk}uCQ$k|_>keEQj z+miU7nNVaL$P`9lVM6p|2A2nULbR+j6;sq!Va3l@B2L0(& ze^kX)+H5Ndf-P-o5i&R(9UXlC5-n!ANN&n5Hdy@-)OzW;ro@5`q?>u%sA*+3XpF4sb{A>I}&%Cft*4E)s93$@S(lXl& zr^=CnA_lo>$kIh;3N|jtj0v&9j`v`T56B>mHAQvNBZG@(-%tl{4>mNkr$E?jH@;}Uewa7=68QXodr*+~Ui}ed9AVQ!=cBVAB3P^1FmS#B=bU$V>2X{Z+vsj zz$f0l59n%L~BMeSwuQbaWELZ?j*C!7|eHxJ#;KWlfz?bQ#o)YH3mxHCSgx;;By=u+tEnSJ;;m#YH zUSZM(Fav^{Zhd{@sAiDD2r&Z!8!vdTXWuUNsok*)FJJPuUyd010Ds?DW65YB=_mB# zVQGT3&bOcH)6#(%h3IJ(A;Sk#_PJ=ruvRNS+z<2q;BdHM20)Oj3|l`QExAM-QSuVk z!6KeA%*3ir_`u^zqYHuXI$;FuyuaG)1LL3M3yP7p4@#Fh@jEpgs%`do;zFAG>2-sbZXM6+W z5*lh&&_CmZ+82Hokl(yXA49?Czxt*A!=$(jEX@gAA!=_?k-wt694U^cgZ1X3>UzI4 ztSN4)MbE3nv${=NDr`d_ehG>u&)B1;B9NAm8|)vXp@C_&mc>tsF68v4wVNY6CjN%w zv74OxanxW8x7pdkNb(7#z#?bKD`(oLZ90Ggs%W>XyV^Up)tSCw=36?21>0SW(S>N+ zJ*y+Ub_|9ngWGQyE?IVjZKYJ$?5<=NKCT*>lAY_OtAh1>Lb=(KS=ifo#!%Wf7_P z%o;7;cj00$mxnE|*w_5~hWZ*-JCK~?y?kpcMOtrwL%%5Rdy2CqHfZM=wfrxa%m@!C zj-(;pGZchJ2@zycP`I7G6x?GJf$?%-V6wu@qgdB|H|qw45aVw?DEiK))&byA0kB)1 z**0nggzNZ+>v(19ctxwYC(F3T%J?+tfGeOvCg7|zR_M8~i$(G~+5d9FWt+hSXwfJp znS052sW_k~1qiNUK&WPfC$c<~C(K=!fMFLrtTX2`;MoOF@cHQZkFXy*X*&Z((HbK& zV2AT>ACwS)E&yOmUzrHg1V}pZIp)T;KgvuOYF2pWdVtL6zAIIa*P)CWa_s;h2+^ol zFU6vz@lZYk_lJLKk0~e%;8v;B{t9I&qv{+?sZQHLi3HtlSO4x`Zn|ySwh8Qf`Qzd} zO;A1uTj*sd^9Fwan_=Mam3SpfO3~dweT^6(u%X?f_C)aAf-{2>1VZ{cleT&n*#3^=RK`8!kFem+Vh`bARhGoAAe za@D(f>_jr{+mPEyB;F|H9(lp2`z8&tS@0YsIs))u#Qu3uRJd960S8Mk$Xz)jFt$`_ zmeV{#Z^lVfCWs0lE`T-(rGo3y_uQOXmy9%wPjii#l>TJ(Tda+xVc z#-WeNs09uI_vh{*ZXxW zxf(#lG}x_KvaR(Q-qZU0l=yqTIlf%GgeqpL+ttGw5NC4VGVM`YcPm@q*YU1Hm8DId z!MJA|(|JvG@Tc@oJM=UZLx$-yf7VS+txvRONj7?sD0L7PN@AVj(p|a|OS%&CLHbfE z2m{oUMm;K3VF8CQ{$t<}jr0)OQw%*#F)h6nx`N#7HW6rYWO27lBmQ#eda3u5xEM`E zbuubiEizUmDk{$86&9>N!_H)Ul;Vutg|ksTbS?Kf4?=qw)dA5*EEQe}`Q?$sUoa5* zS7Xw?pCj_vHvldW7dnBo0qfi0=`f@l#jxwr;W7f3;O$ z(svQkqUo7hMA8K<-*}jf;d*4LG>Tww(B(j+_U;>b)6SYx>aP!DUfoQ0Wh$ShO3{5L zA2Ue3dH&Jwo4teAai7c^DF_McR*uVx#L8AEV&ty8 z{lL-{h}UdvDtb(jUJcH6T%$ddXjUkeP$?wsdPNTe2dhBN%8ePtc|+8KV=nNcKX3Za zj7ZILqhO<_Md(*AWM&fQP01zEoX;UnI(_@uZhVsQ^w6`Is#sFU0Cuixk-7bbq zsR*dLSdFaA%tAzgx#;0fu2dSIB{kl?TlxiieA*!*B4*^{Q&8Z~&+E4L`?)hPOSJCI zt423BH((}P*LbODmXg1$y+z%ea-Cv+TZPn59Y@6V364;NjD&0^7Gv>ELCvuMy<1Tt zRF1fxo}03-vf+EuhE+fTm6?|TqDMB3Q%E-}r*bTD11kROyOM?S1p{vWs;^}z;#&+R z7O!kg53Et`D^GTh$KZD1gAcKLI#f@qLL9EXiyJ&qR~-^9v_>{Nl(3$>j#HRLe6|9}FX+uJxgYOUN%ItA4cMTId?Z4;v=9~(4EZg1=bzeeFOc%z zhf`H11_G2K*?4jhI!Xc=F?NPPn5Wlf#78W!eiq+$$IxAUL;BL#78gyIa&rg6IJF+`8szDYPFxPhA3F(qX%W^;Q$P@mjUkK3` z2ErMLF!{A|Z+I|y!#r{Gd110k`j~f!vdHVm*dX}mCBIfb+g~W*r14lIVsRfTr0+rH zUg*!NzxdH>*U9ek0bSLg)H&YwE~BjG3ASUoxuEwnkU{;g9z*%1hyI?PmusK5urrGP z`;E}`<$_bJz$#{CzY#kXXK{X^v9TFg*21;#JU>0PcXaS@^JuSX<1%V%Y8YtfYw4>h zt19Yljor6(GXD6Ekdem~iTQ1Y9)N7)rc_jwT~cUg=8R~%^bM4i0p{Dks5EVD>A4%4 zzP%%TztL9!fvs6|COmN9QrtubRx@PNy~s+(3VwcX;okw!1MpFoM^Bcd0QBepZx!$| zCmc$bErys7%`cEIxi;1R)H)sh5wITC)byy|RiRC;r;qw7^*@}q!%(i+)RYu%!q{Fh zXewR;l;;w$0{t5InTy%RQcI(`enEGi3vpi)UpI>;0btfiwR!gjEgG_f*`Fg0B?zeqvsGi0C}9uU?r$mO5)~L9l|2Q1$^NM zatU#Bf5s=}0C!SW`p=AyHn&=l<2Km!3o_V^qCzxHU#8V-!fbCT(I^pEEDOq zu-`yj1slM1-Sw)!LrEfsR(s}Q6!jFBiA3*91W1ewG`1cb1up^0&JKM8hY6K*Ydf`D z{cui~#OS&ohF3}2Alcu*oD;DYPd)?9kx?W&6<<^c#f)Tx_DhNdk)VJaw~)?@P#0!l;H z#Yfo3$*MnIS2c%H<)HLJmz`#=!Rk*js~4gUIt1v=tGP6W?tG8#Ikf#cq&Vu=UB&OS z%+SE+(4x43=o!xRD1jf5GvsUSBuh=tzz@b6U44ve8xPs#uJBid|XbjYupw6tFUL>!KAp%Do2;bSI?Gqs63xDkju zr1qs8aQTtLB)#xvY-{qLJzQCQ@#_hfx z?>#V(KvQt*()CP5pTdP+?QF0r1Yt`7634uli>ee@9YF|-B@Tz)!_!(7KY%m;(OLK& zh2U>o_|iQY0ydGh5&7I-BZ?<%S$Z+1M}%$%RC+BabuVI`NfUv{rMTMBqqOi>QsXe# zTECCjmEO@yVPwra%Ty@ueEy3e8?OHgfOxT2_;<{kIi<%=Cw!1{!~(b*5iQ)6z{CxZ zOOZ2i0Jskp;Rpas?Mdjb&yG(4XGmLX+jEPWs+!xqN6iEPv>+-QpvlTZ1Q-)KhKaIY z<}BFS|56&3p*9k~f&q}!sY#mwA!zDg$8+PxOjA`)=zA&#RG5b%fD zt_0#}PEG)iZy*Evfu>=(5?K1Cybo=727FUGc=s<%)pOHozR$67n`0fJU`;gjl5uMo zQC|`dgDsndsSAu;;;VD#8`GMcYY3vE^#VuC@=!a4W24vQyl=ig`h9mt=m=k17W|&; z*?&Tjp5B>GF?GFi|9q|P!@nt&1FU&=hT_hBr2!BX4WU%GwY^E&_B7YtZTR0I-WQ-mxrH>5)y3x({RML7)TP474Qj#)F}vF>;0N)++d-J|Vy zq|xGXq`aV2+P0y(qr*$gSMAEyZSkDO{iUhg?;$+tto-RFn%;GzRC_21xi~f@pghG` zL?f|jW@UYNx0=mcb+eSHNH1;cjs{O_hth=KpHC`=>_`dH?!!%td{MHNjR)jSjQ+1h z{YiWBP*Sx&`^f z=e@#fSE+dTvWSWp-1=<>D#mjnrN4)cSh7JDz!(n~4fg-6@9f_`S$nxTIhl`+Mz^#a zp&1CH{3s*IJ4jbPco2s#rZ7qOglsJ6yU2%qh$!B4AH|*C;_uI_*BGX!IyO^M^u1J- zt)&(rX@-DS`a|*8#AS>d%WhPliOb!D z;oxC`L|^m_B~zce7njM+3i6jkHPJ<&i0eM3NnIH?vCP1~J zv~<+86LbOB;?7rr_H1;VteD#~Subn47gX`Q58neiJGW1=f}+PyZf+_Y8$V2cOUVKf zW_ej0(^hsl0ME)>1^P!%GY*|;bL17@WP;#&WiRI`5Z3qNgG$c!?uH*iu~EoD4fY$0e`^K199SI3dWSW1NvtAj%aOTx4%l+1nzaqh zlqlp@a~!AwIu|>+mQ@BRj2}j{c&EN7L+fNx%53}I_3gJwsPh9=P3X{%aMv!q3v zOC)2mf?C%JT+rz8(fDMS=msSb#E%B$z2-kOo4n0@02-yBvs-gGVxXvkGOgl1qq1RK+}SVZmyvrzE%0~hrIqJ#X7QRxLul?0wijRw zi-~bV=R5l4fBc^5SUe)LU=)bY`I*PJb6rj=yKwo8U28g$wxrLL6|bsjFZs6_cIa<7 zR}aREKq!ukRM=$;b8{5ZLan@JesXf2ChvI0-TaY(pFc6fC<7@SHHC!>+CLCwC~6wA z;S(l*X=xj^F1ym22$=x8FIj|TBPwrzwcSmk-22mav&431=|)zGUHI!qU0zRJrMCyQ z=f=L)6Jbo9eyt}k-(5(1p>l{k)SzV!Rk~-|YR6B17xkr(9ql3i>`l4L*EYprc41yi zVW;|&V;C_r;Gpqb-669UkxMpV9iw3ILLg|wD<0sCz4={M5w-MKC`DKNuH*#n(4^b` zJO-$GJ;CPdVQ=30ObIu~;b*${yNUB70#Sd4cBubeqT2XDpdpo}NaF5S^#@c`-4r16)imbxz#8nel9FY?3Hwx>whaT&{S}o!YFd zt#@dEBeu^F5cQAM6C%KDySoPci^QCOEaw~l>tIpl2@t>y3~DyS(0-LFfw*Glh(Gnr zdJA0MmmilD%gpaN#o)6`ccu7MuYPmh4;lEofs{q20~kR2Bfet6l46K$iz~V*<#@~; zI{JcMpHZjF!D<}b4qJJB!C@9QH+Z}myo9O?6|S;nN9(S#%jsI*^yL0L{(cN)w%0MH zr(sVf7_Y6`P={Orv*1-w5mE2l1eALz4#BK~F9pe^VvuTyg#38J7w8%U)qFjOD^0Zf z7a4==o(LY7PIXVFbWfBRpRh3Xev7KlOS3i1L+YK8u8X zAY@Y%EAV~3<%<+`1s#^biZnHR14{Wk>7fnt(rqRLhFMp&A*xuI83;Q|OawOJn!2jy z^cAIFRhOg9J4V1?JA63kw_u>fDWjpG#f7ew87d3UGg#WgbA1p2_4Kj25o8+6X!biH z&w-ga`1odCZa&HVXe5^pWBvYyDz#2v}dGE@N`@Lxa! zrY`F0dHd2IuC;0Y5Xa`pRc%bB?=IuUr@kTf9M{Bt*Jtu@eU4weCxtKz8h&9kypUZ( zfW9K=6`kqJ>|@Xk>~)EYJ_#(IR4`1R{XTu=DG3vEy(zSF;Gg&T#<|I{+q?SE@6$3J zc?YEHX+xLwJHY8TNBa3-_)aGvmh%kLc5dJ)mvC%$jp?+PSbt>M29|2u)*7jmru7w~ z_mUd-lpELWcuE%$*u&KEudWXG&(&L2)=PpLaR(tHfmnu%rp$D7n?Q=?zZQys(K$W@ zHnAnLCAAQ+KPwQ60z!N=Q({EPZZD{CqAq#kjMDz(7q-!O6F&94E*!a(I}3R8Q2O7X zp@e~oiwBQfyt+03CKMQK1qfYRR;7MMi-RuL=FA(){H7GCDG-ET^l0I3y}AHDx0R6! z1}O@u6&nsAv{(Y0MdHe;R^966W{y)0+usM*2^3{rg4huNIXiZTo15FKCY~4`SC@!2Kfu}D#|`{q&7f|eZpN%lN1F}Qt-b}(N3Jy+jmn(xhnL%K zQbUm6(lCt4?Ht}7JqK@Y#kbTrU6=}R4J0+I8!L&*D%hy9+l{@ld=rY9`k8+VFyRQ7 zK!qkKt4;mcGP7VUgsU=9A$#Ll_sFDsg3j;8RO#9t7^nYxk#VP-X{&t7qyo1-zpars z7^eg#^wO_6+f@5f5R@8iEc$DJx;oErAlSU7rhhL;bzW0Z{ijNNZccV`N_w@YSW|h? zLk^{4eIdEhDH7kFdaSY%%r_C=28-AkVt<|t-{+J3Ra9E$RQ`Nb(ck|f@LSF+E%ySV)DYj9 zTmX#U?fGfZfuDdUvnpFgBlpt>xet;iQg&D)F;_DmHEaKf&<4a9+bq^9(U~`U$|W0m zRHJVxF$=V`78cY>HpQmw?%^KnWAE(-G<#vk6$4=pCEu;$v0Uo=%zlM80w#igX~=uO z@;0@$7Bm*t7Xpb*$$%~>sPW=wLv!C82Tm@381K3ARfbL%5V~>uvbs!w5};Ku{ZRIG zLL}bY??Z_{F;+qx>BJiJL6}|egA*vLo>-N+sJp7L`nb4gl`=qjGkDC8>*-oVQXbXy zp2-(kCmDh_bch?_dz{~w&(D;mK;7zlqIuqt@4mIvYw+6XxfB%`wgmk4?FiZcah+=r zqEg?5LC~@bTwYy2`#&8tcf;#J{^tr*k%J_Pu);c9!tRi}jW56hUwSe_3C@yi7mCIk ziv5uwWaXPXa#6-o1I!`<1tJSzpdjOhb^sC|*6Zg|_Y0OA0XylBaLh^Dc=K{pDvblZy)oj_`P5aK{Gm! zOMK<7Kw29jL5iVHSLerH;Pg1^D;cDBBo`JX68L3Q!AkvQS&jFoh|b|Z)!PMe*LCou z1YN0d>-3@;7fl*h2~mOejb8Z~WhF(Hz1*X5T$KqNCyHWtKuLbK=qsndd1JCk84WM(W#czU4YSUe*mRwoz}_935t zCa}&8*VY+^UR{x1U2CtJ`P)bFUU7C_ZJ3|8W}dZ1G*m65JUmQ1R02Fa230vzah8l1}5-*Loce8Ef| z{^bPQBYme&wX-<9ag25TG1C2a2CmzCG|ARewF~TjFL`uWpwp|X$EdolJ7fc5A2s2Q|T}w z#i5rDoB9NW7mEKqkrkvuDoY z*CVhg#D@Xkqy<6&n&h2R%xEH&ZOeJ5NZfTT;}QW^n2Cvru57>#6$k?T*bf|-*b&=Y z0LOTie4V6cDp9C_O)jbc@4ZsRc->Bf@6eH991?PfQQ`MevLNjWG>kzWXX|b z7Ft9(9+>+0NJxzRzH~q0_@nraFX+;il~gE;OSU2QE_NZfIi+&VhS{}|xdvho95ogt zLpwTJAz0iEWeS#4tEP>Tu&r>*Uj{qkhor&m5`0igRu;PqRF#Jb6F2P)CuThg} zVk(cDY>f9m(=YQYxk%fa2w)vU51>LVkMi7TSb11^IH`J=IeVCUN*mEo@IqsiB$5X( zIZaeAra#x99a|OEjazxq7qhW=T7NWm7q#@5|YuJ&Ug$QIF1 z0QF~+sxZafU)z$ZCgCqfR#LU0 zr>1A3rl+H(XP`bAT?7u!KuX-3#fp|?Ekk@uoGihNL=}rVJU&gc_L{ z{b!~&xSk{Z`+*AC8XK84PdqJu2un;7Rb>upt#@u|)@M7|&tA-iE~()s=fn_CkS=k4 zv}Cyh=8yJ&U1kQRugY-Pd{HcqdW;%gCaY_C(@2mM%fJk--Nn{x}AX0__jlK7*cxf{bXxk7S;)qWYxqQ507`5t?L}xILX-$CgiK`MJ&i z=~Dx$dl9jw6As^le#Cw*)JNSPU?y}fm`q$t{pUBp4dag`W`y^HLW*$6ABnhW^%RKj z%VzyP2_UI}9Mqd!DQ<{-tbX$xz=6StaF=h6BB6>X;Z>$PZB>l(5y)=GD_W z&FF&CGL;ezHnt@jj*__%$1I$b?^<`J@zk+9Lrp#yFo8QBytF`wxrWO1rPAw$Rj#bV z8CcxR92>|~>Y;X7ASi=`G z39TwOjH%|Ey(Bbrx}wn+`29biawNJS<9(x*{eYB6U6*)dRUtq!2u?+w5kRcVgh8w5 ziHdqH>Zp37>=jR*=p~c(m3|ZeTy88+yz!rN3Q&SR7hbv1cIL!(j*4qI&QLuriR6va z+bCB+uyeEX(>HQ7lKPg$VpU07)95yZcdN~3Md!N~t<*-I7oA^D#ZvbvASRYK*S<^i zuvHq*nH3oIyh1W>m^mM%%tvKzl9~X>wU?Uvk=1LK^XAu7*&qM8)78@EDwk)k;vF@& zn+BlNe4Y(R@wx&@Jh1@)dz?LM=nq37dBfoaR(#oa@x(rywar~}u#agMZq08Wb~{

7m1FoW&<{<5(1l0LubfIFs7J$ za9#du3vHSG*svRf6zc|ed+$tcym>ct$4|G>VV-hStl8Ot_3GJk(Om(ktC#>E)D}YZ z>j#H-u&&aD=%?kf4;xS@3Ag44Nyzpdvrd<%Ik2e-bCaKWis3Abq2y$Z!^=Lfgp!+I z?b_sIJzqr;_}!Rj`Tuta1d7YDBp_DQAMOf-q1-X>CU63Dl-RQo1*I8u(18$AKWROA zABlhgETi~;lBHFErgHOq@g?Vy=O_>;9{8ziEU~{_{6Lf`EHX~WfRWTsydP!N)#iAE zb}c(xla5(n47I69(s00EEV2NHL7UBSTNFFfiLhjXz)VZsIc|`oYp9)jq;UvPsQj+C zL8Y?*{=(QEkO%_=B@XTE`15_DkXFK)y1ty^7W;FG(lN02z=TsWaA_jLtIjW`U+jht z%zvld4Dw}|Z}#yPs4%V{UT2D_2Te#B)HiDk{9Pj?gfE*|X$gq9u^OjJJ#MH8LP2mH z1nKRo;Oi)0jm>pr;q*u6G5Nyoh_Sq~RfXIk zI*3Ct&Y#++uV!9G{WWPHXW!KHdtq^$q&(#5^@^y{I`zs<29K{F-_zMNcj|mgFn+=L zrhkC8G>(8C8^1)2`t0|;-MxL0R2QWPZK)cuBL=(vAFzf=`ZqAb`t3Le1X6YEX!tT> z+((BWnvED2eTX@&5I6l`H~rWJ_P_YO@CC%k`{4)8a2}PdmeHIm5s}PHNE{B#07&74KlX-CWxYIr}_=e4bxPRW_ZVhvzvN4)B>^0-uHnwbP`KS!v$JNqJa$ zqc7oC9sC>OY%aE&i0Pv}trcaR+Ksx>$Ss-@%%fUHPgvC2qOoI<5_aFY>(EJ1^z+z{SQ}J*TZHSXf11}Z(|L~ zOqEkM`8gr-Q{=T;Z_JgF+yxnef7cWOq{Vij*{>PNJ1B-(AX!g4)II@Q3y47TQ7=j} zKFLwkB{K3=!8V`wDvT>e-HpWf*Z43$6p{N}SCTVi1lb;?z>_Rz+>I8FgTe3RDVsYv zJy|DN=k}ShAtqQ6F&`eZgS%(2_!q zu-SEMP|kKeb9T7cBZ+fK1V&U`+H{HIh7kR|1nYn{kpN=UajnsEZj$@BQjm1(`q8*f z)7l!y2%(O&l2pwk!;kvisc%n>l>xw%K$4Es&%%EWJEu1m8T@Al(Gy~v0f@U^K zs3MI;M4*MxR)PToXkTBxA4WhEIkeXa_-gRwW@Ka#)2ppUG#AiTzLwX#s3RRp-h6+A zc^^32r6N_rRv;1+=rXy@uy2GXSm?Frv{z-FuvEK^01)i0TCoK|PGeDRT_ViN@+k&I zlUvx(qG>yGm^v@eZ%v~b=5OWnIkd=d7o`LC5|$;I08Y~NhPT1))HpEZ24kqhcM
L=l!NZcR&j~-{6DMB9J3NtR43cf0FhNj%htQpGgW+4W%}?79UZK8h(fM zISbBPEuyS3k3xWliSDB;mYkF{aY}qzp4wCerr6XWv|__Xg9|sA(rFFsiVx!H6g1yS z0pHW1L}77JaZ$yDOu0#8UTbCPJcN0)x;7m>N+MB}lUJ2p4>Ty73$>RT6WUPK0+HGT zD&Nt?6iJ0M%2u~GhBwY$?~9A>P(|@f1nN~Hu^E-XShR2YnMbD8s(8~&CcbC9-3wg( zj6zw8uj(psyD$0rCH`t%l{%msz)_u5QIhS4GQEMo-5YFC;TZy@ip@y6J!EwB6jXj>>D-aaj%KewIeFJa3RY zYak+(PfH4Gx_UM$>0AlEq5K8PjWR4a#ErKpZz*rNfykn3NA(iB@8h$9SH=2(y0d4B$j(%-c7Vp$1cSJawNr=K# zKD&PF)*1C#wa#n5wf|BL!E5L-(&7Jiy~JVz&7Zwkh`fvLg1gil+W<4!3nB~@-{Ieg z9Mtm$U|oQ%_MAFDQ~?ZF96;P8SFFnY$@QafetZEnkRCQr3!FR)O|+2(6jBA$#(4W~ z9YiP+q-Y4C!W@|~qzFH5{L>4ZB=xBqcR6AVl?A$0{CYTf|8)aVL#z<@P|&IQ!R(NdHeL za=B&FR_3d+H8WdItZcps>(b!k+A#7%O4LKMOlYk2V_nN7=zM2|#E2)yh+DsaXCrTQ zQKjlUz-+g~Wx(C#8r^D_O7)lrExOu_`wue_lM|8uf%f|--Tiew&*Ll2~IxdawspEHeGyEmesdBJ_c(|ojC>p_@iM!)zioMEy# zR_qYDDj_>U8#5ebiWZfRswxHLu&YOC^3xu?z0yHs(CV+4(~m7RFIbO52gAAV$t~N6 z$6_r;*C`2@2TwX*FlLnW8Fwk5O6LaKPw1@<)=~bFOw~MM^Do_s{Qsr$@4J`Lf3NX_ zJzjz94PetPgoY)C7?ejX?Q{JsMT{8oM1+F-G6POl!~!OzK0`$`n5rnLC@>(ri6app z9&!Y*#FR-+Ha119(1Oyrqi9hw?WhERP{W-KBZLrycD~7*?%+j%F+-aDZjZWZ@>uE>Tba3_|&{F*V!ra`Nv# z)Of3W&n7xM5GlCq1^f4b%3T}bDQ3ZKm>3uf;$Illb9s3Io*njs_}tf7)_Or#S9SMF ze$-!J1fKLV#edr5q(JGTRWgpt4rkgK7I68iK(=FXjq%+(=F`3DpTar9{Q!u zv}?r(VZ&A*UDHLVDFJHfO#q=f%}^~J3ZxC=x9?+fcg7;w7W{G-tlW5qy`OFw_a$L* zx8F0+CFg$&xtPvvTV>p?)`clO9Ip#RRO*zvnrD{BY58lOIH#$urLCEfo0yxOlg?4F zN{ug|)M($+{Ukc`KzGupE%4-~*jI{QbgtClLO5ihOX+K+?PcW!S86mhIWj^w%s{P9 z1ftw4zCw!XGp%Cgp{ufs!fYw<;}Opf34yKXkOdiA3w|O(hyz*WTQ(X&a)O1sZNCYC zxfNM9z34XIzIVSe=?-nC&%7IQ>zAx@D%*MoST;T~uRpM_KYUzx`Ls|^@`2#gBe6_t z0O8&6cL^7eQ^)ASiQ689x=t3N?xH1;Oj+5Omb}lheZt5)>iSoS4C0a+j~73g&k-Hk7Ycj(zV1wl%M7 zg7n_SbG%c25MCpPvkRan#8K}0ep-f(De!K$ph=@{SCZ0#e@ghepcq^Y1) zQ&=55IJI6YYsusi?MMAtTmQ|$z3s(+%Vp*qW>?3fQsm-J1#$U3ZVD2k>-|&~J0i!| z6Bnb(c2IM9kCH*XVbSVKrFp;kXN@YaOZPj&tNTGmrn9{}K4h7-G(4JF1wKm`i=GNiMpG!Y>Il!q#5m|7!*5-^$ubEdof9lo& zP(uK#X<+gv0@06I{gHPK!xFo_Fb9x0AvCWnk(U~)Nj*> z&IguY4}3TJxy(kw0PJ^u%Gc~b=>FAN-kVqE{r0y6%k zM!XjII4!2Pgo5EvKYdkgnE9=-P@y6rRLRdk&cGm2WimQCGBv_5984~Oj5LO1q~mL; zMQKyfLQ+-Uf=Q}=UZ4w5xJHP{PAE;v?XjW>_ox(&sTka5ujo10;;QsvE-X%+6tl59 za^lvp}FXSDT=sYmI?Cq^eFWfbIybJ*xD)6B8>CPimhx3T{$ zDj>tgcB6aoh&MrkXz^m0NT5@>2}vNek5uNiqGwJjPu6T8#G?XO@e7Y)ihf9ogfiry@PLy?P(yYNQ>1tif!uUTxrg<^31h*gQ}g`Cl@+<&AZPgy<^1bJQx@kiDRjOb3(8MA$ca8`ZWUd}g(21fJM&%ns)45C$X*Q;>9r0foRGk;(F zapOxuuH#lLc)btFHFu4P{#fY!=Rjj!Ov(U}lCrw3nI{0~o?>DDnbEeSdK;VkJcWbP#>jM5A3OG75X*y*>;NN*dlzbKC+*PQrH0edXX=7KW-A{23ecq9X>ymIoL&Dn{4EE--%kyo z90P|ilrZRlT0>?{Jw1l8D}NsIdAk;1fn>o3zJI2aLV^p%Uu#^pp~bMZveNGKaFmdM zm--2&yY%X^`umeY3h-0;%O&rP^RL^AELhr+eervbNGPQMcDz>4Gbn%|Cx_KM^+Zj% zod#A>RTTrjw7+fyprl0o>b({QWGl|yIG)dPzGeJ7BIaMDx%4K%sS*XW)!d`OUU7t{ zGXirh_C1)3EWdRmFfqd{JzO3x(Dl-v=5HEr#@X;H;4cuiW`ws080b}4Zz;`sxyzdu zG&0uJa6YImbObT0PyGX|QB6Ez77fBw@~SqbVo{JVEiGvorc8yMKNIMUFVMqw&m1;6 z>>g(OoIv``gVvI#92UEWs~@O(Tstl*0_Qy*Y_*R8wo~bDa9xsJs-8wwT`B#y&AprW2TN5u1jDac>hWf`{Mpu6>D0d z#EwS6W3CM|X{>Ogr}@MMk|>Oolp}zwaWIUU92py-8)u@Yp=X3QZ0rP>j><}VrOZ4P zmBbBm-<{zJ_5a986C2{kZ0jZ(SbdZ<2_A)Mf08YB;~>!K1u!m7y?#!EzPNUMi?#^+ zj_mW++~WrVo+r=Z9kX^5hK1&At7Tj)fqdFn#UC}j%8nF=UIO8#Md3tPw;U5)qYg|g z{nwQ*FjNAQG^irHUIZlVfv9@F=~A6WmF4;45~s|HV5bGS!{8pDj$|EZC0yzsL}L$4 zFA&-IWBZ2Y9+vWI7S4&pjLD@cBQECAbG*tjDs2bxxqXOKh8-J*m72y3{CUo|G=@{M zN2L4BB=rvSv~qc9A?g52KnA_cKsYjiHYp3w0dgi3jCGO{pA zX1p6{N#1*5?;}PmtbCa{-mo0?s^p*UKERB@Dg)gM0kAB4I z6*p4z1@PqH#t!O|Fp(}YxN@*Hu*?av`cj%evA(jP&LjsSVHU(TesT&n0D%4`{0 z`+(zj6xC6xY?Zja0B}?Olv$e5U6oRk=qmRWr*WEpnA7``9c^$6!%QPn|9*# zRE5(rV#>gY7Zn+K?c~Hd$EqAQ0DjCz6oLOp%x1V1-~lS#XeiW^Ejg85?8xK9Q+p@Q zLrGAiJ7V{5HGTpI;#;!t$=KK?%jTav+F2_MfhFHCj5f@C74}w4 z7YzL}!#)Q|02J|WpE*h>Ll7MVo^4OAwLcyVm`C5(m}%yQAj#huZS$jUL2|AN<>su| zrb_WZ(vicoC+Xpa#9yAWUbu``s(~8w-`~IOvB-Odpsquwu0Br3K*aq>xz0E1bYdx? zM=x`xbV?9q3}`{7bm|tI{4qxVBds4T(b5>BGg}f9liJ5-4$ov+9SlH=|ayO$z z{Nx!gkmYUw&5k&z=_>CFF@&6A&<%>_Q4eFNSbF}OZeo!74Gh2N#mYx< zA21!$<5&Yh&#dQ{Tnopy<@?jb7cN_{3@WXvI!*8g zQq8zxb0H#tjwt8An>VWX=<%Y&U9h{Z?h?j(PT%7N4Z_ys99s!1xX`FE>v9>F z;M|tQ9BF|oWKs3_s>iAa3)0=e=zjcaG~c9mExvlT-yi36g<07e`B(qU81(Co^iF>I zl~~O+{Hw1}s*l8{ZWL`4xGry14r$mwbK?Xb-pR--O@->;KJ&Yv;F5)g!VAfaytEW>6S!}LHivQWy?HBCs zD7%5`RuVn8jt^0BD7}iENa71Zxw!+?h4!$!1bC$a2qYKX;Mb&he|OfoQ|Vk==~?k6 zYN@jxHR0wm23d?N6y5oVg0Q^A8)n&264mP~s4IrTI)l>Zo&)v)20FR1bH`j~c87@A zY#|Pphh1&9VIJOY+J>giHBH@k17Mxe(dmuUR|>@&(DDJGVNq*zP5MZ*$cb-H#AjEmFZapXMwRGWxi(mke6F^T!W9dIQ=u?M zWRec?|8fBW(x0-%E7vM3*G_b|2qsiaZYc-1XCv#KoZDuM*_LCzbd(`g)q72FkXTem ze43{#SG&c7#81BvB)6zI5QncAnmheoZ!)!gkVB{I6Y)@T{Lo=%O5DZWx{u=YJWw6H zxXRyyw(ds!HoH7)U`591U6GnFs@uaGVVF@D5QHH_2WClUFf-c=g$?~SO`XBPOR1Gj zT}~k8kNctVK8kC9G!7ob_XaWD^A0h=!tHT^R+UVwzc!+0<07i9F@;C}30i~Q5L6UO z3Fjb1P#&Gkk+`g8Hb5`m52moS=>2P?sCyG1$*CDN7eld#fhGaJhp6g-M3mkqYTi&6 zYPe*v^R@d4pWg+Oq&*mQeQX4^{>milg^QeD!kKAi9C$OUplxD{-ou{)Hl9o!1Gfh7 z47qUY=dhQ0N&c7#R`*0kQ?^DY#qsyz zzr7o__3|I8lOx8=jN4>&$$sL7?}n0jc1z~;7=CMeA-=y=(6;mL^Ef|-#obhfZ~uwG z8Pt|5VZG-rICS`2tNSK`{tfEez7hH(M)7`J?_eSM#i9t=@K{A0FGOxrjrAb4>~=68 z>c$7&65r;)WJn!T(~gi%`$wZ((=2Jls2a&esL zQd$9$0zWP?Hc+&yB(~gDRsc*8GX$a)P(FwWlJ#|pG$-O)QQuTkGblCxhqgEZjl{C1 zQAMeXtHuH*4uPFB9Fg6hJ?u4pSaLEz&7;LLOJWVu{=%X%wYxuYkgD5j(2&;k{nP7i zWN$?a_hwt~(<#R40qzsfvDcJ`zkI4{!->n1_)(1EQxR9=s*(kL4GAhOD{m}h6JQeH zVWs0U`*l&cYlIkqsD10R>9Dw<5I&+GfzsJfMA%}*RXI2C&cEXIDk!J`mj z3CO!I)lw+-vhl*+FvUm`B&?X>PeilEKrw5>^;)Fok19egSrjdpG(T4|_CT9t^KZye zYcdDHlJmDi)+*(b=gH>vXUm%6&@lv<2r}&^jTxT2;^PJOeAMJm4%2)*kG>!T`i5Sv z8Fp1ezR>dzUK_z4Sn@>dL~wtU?)hsy?iJrA*ghg{iojY6|7Hpu%S9zn{~>LFputN} z?ZIg3C*1s|Rwq!%MVyp6@hLOAb#Q%T2o^@dTXfa-|#+WK@b5+Cx zHR=B>FMk7kr~o)*gNoe^@Wa^|luKj&j1%>HlgAZ2zc-d@;JTo8kmGGfff3OI(5Tor zINaRa{#g#$*Hl+m|Bq5H`nNF<0}c3E;S2cru;HtbU`GA^BA>Oia|!;3&HxT$T?$M< z@7&mU<2RbdVlv79e6q3XZGUuG;3Xiq{?&Xu4XB*A>8__c1G&K4<3-?T@qL<6u!faq zp}?PNj1>|?aQY!0HJ_aL3#47l?+2#NlUyg40OC!pxO+jhu{5m6e^^|Hz{pXfQ8IM% zntZ^j_!}*4c3v#vleq0<06>Sb{8U6)qbkG34nGuaR-7|3ncJ_&o7!WE_}se}*fVwC zT{rwV`S`~^rS>`DVvI5&jPRE80iThKyy4}e$>oz09#xx!jD~*BwbrgGJJ1j=QGkZK{Ld~Gu0LNm>G3(uspjFpAWyuMULZ|K#e^Szkb{iW;37}W`6P0dV)TvRly`X%Ato%sZ_Tt&L z{cYqX+W0lo*ju#jRn2juB+uP_lIu8U5$XMn_$qDy!6o1ge!~wjegA-YWLP#@m)(PHqOD?B8H>Pf01bV#n4vzY8l*QP}?CeGw@PUimE zOnVynU%RJxC;{vUzxUVs3T9iA?VkiC0(PGYB|r4t*Da zUykeWz22YDX|_3feb~@xWIgiLcu4_1h4^0ZGHzzk9~Kscg#Se(SNh3KFOWoS3roD< zvhbLi0c=aO@bfmqn~j**a-$u<3oAC-Ka2b*uY0O4e=;$-wR++rXXT-z)37xKM=szd zW8)A=OLvrm{|+lP)+1Fp8LLM(Vq(!sZXo0p1lExs9hodQlsMsL|JLP9ZujSSTzlzN z|H&QAO!9eDM{6QZN5^g;gOPk_f=WW+3s|R9xd|CnQ}3+$#K%ZUU*0Z7yPl1nMu|=< zQldall}(?*_w_!ncSfcQ9&aJ?XyK}8C-xI;A{j>DcQ#Kh2ay3UuimFQ)&|JqbLqKM zEQo1TbJ3&}jdGiLQ=titngy|y={(FGRSxjyetq5_&za%9k^<}Krh_6J+}Y>{%-g)` z8Bg z1m!nR@L7?}qq_m^2IW88E_96F*2}VRJI0?-oOnIOVTV;Mb>mdug_7U0y2p%+*z(Gl zc*OEMA;*dlXkI5XRJY0LHqMX!81=t;$Z2e@Q>=$F$(#4ro_BZA_y0pOcwoYQIO{l< z?}(Fm4N)M1mB*xrv@j9(uC!P>Y&C2&=y~G^aH4lNlB{H!!W*} zqfc7t>EE=LJ-<2ZTJRHoLs|uYCT35M0Yo~n87yn^Go{o<3!gh_Fz`4d`JF#B81gzV zi$2{Q_4O#I{4tx(g`&XU;O+EHuDhMGSY?0EI!G`nMvJlKrwoGI8W*ZqH>?DbVn=|v zX>?e1D1un5pj=7SH3BSobKffv_l_T{JmcZ)f;v<>__{L`U9JuoxrCU9{xDR{WXnJn zKiuEl+re_2+95ufKgN;CpgL~+_nh4i_9>Vd?>?wj7 zAmWryA>Dl9vn8+RK3&qQYY&e`eS3t`Zwt{#xy+|~m`37vK?b%UDyqkabI})2hh|qb zuvsidn0Qa$45LC$0!4TQfR~QPE;-6Kn6g83l*bGalz}~jFrVJfB*MZ^#BnD(3HKrV ztD${B^vS}MZ&0TL%s1zaN8wp<7NbNikA}3{;Rd~Zvd{d>)LMI z*i9PSb{gBZ*{DHdtFdicjnz15(%80boLK+e7vKN9lRcBkN`fZ(Gu3Z-M#L(6)5A$&{cGg`NW9{Dvo#|SJI1h{+Uaadn|0uW}d!K9n5@puFb`0XHid`Y* ze}5S%89(Uqq4;NKUMsjj%HN~xP4^)0LPA6EKR=sfm|Wg~Wy-?|fg_w!0ta_aoVmP6 zw!B$BYp7IP!n0R_#{nbJ|i`T5e@0e9Wh$Pbs)E2owQJRt_yRd<3*% zJS{}(q+6r~{`QEVQ!|$(xBa`aILe=MjLBgaB%?-!Hm*5$Si=$mo4T#wIj%-nXoz#I zmg`&O^hhaFkRAu{*VkZZ_;Km^(dbbV<0q0014WlSueYhRx+3p1*mG59Zrg;uYTryq zf)Qn;r3tF!anzPdzmSrsWaVVQfZsxieGMWH&PNlG`phPzp-GH;n_9^q5!Jv$ok4mi z__-wG-VJk9W9Lu7uddpNC>9gyD%L@{{0CM*D5f1VDH6-93q%Ivpb4zn5#hYa(|MT8 z%Jec=e9~Ne5&gB@^8N89?^?`V-8k#&(A2M_QZzWsLhL@089NNl0|ibS#Z4v}#Eeq>hMtq%ur>luBHw*=;rbi0q~ zYt?@316mb$G}HT_e8a{Z)<2*E(5-e(-3vm-V`TH9#&Urr=RsI+?(u}<_S_!UWY z%^FTI+I5gR@f_V?1t*D#&JNq+?t>JDjA!+71npW`E;Pi?xy>LHy0Uld?Wx{N^*_ai z2QgKBIbMwqcOm#AcA&AAP=v4_5Pjw#Hv%WKBY)5SabJGM#?QR4g2C@cr*z z?-KaSk32sM%o)V}%ShdQq3b_G7}n2PoBcwy&R4!Q6=fI!!;!qQbm?XTtEm+83ncYkDmlxd)v3Y#8upUcwNiSt~8 z*HCY;`^<4HQ@E$H8;@w&%x~LqEkDtclAv<%hggYAzF}BdU0YpKF|~kXYKMdF2q;^9 zUt?<5Zz^`#{y`*hAtQu*Gn>MUfK>iSNeTkC|I{n|BDaK zu%J_$aLMmEW6%&DxSPeqsP0WxJN1wBjo2|>TDu@IgHq^M;_Yb^d#y!R8|*HMQ$1o6 zPU`HHp6yP=hS367>ch409meo8)TJklB~XL4CiQ1^=|7C%hUxd^nwQe}&#|#JmeXk? z$3Y?PyZ8j|AtFfKd+68=0)4~=4ucxsxxtl=7I?4OW4s1PH*N+wc^x!GJA+4rU>_BQ z?_3$5$xOR`;s~H~{t(Ka)S;oYjt{X`hPFG$p`EX$-xe8TMN%f(H@fwg##0>&Gbgdu*+TbHN_r)F-=gWAPDk!Do9}>o8h$^5n z`wqUlyo&w1w#^)ed+CfljETXU>n`2Lo!gJHs$?%8Vp#uD{`J`3xuLC+|Es8#wz#-B zM`1p>m{`9YJ=V{$G*=X@>(AG-{j+V^ zWy*1fprFEIG)xREDgWRi8X2vYJgP3DzlfdPCh!;ypV#!VTL_|Y+8vmIz|3S3qp_3_ zZq;YdRt|O!;2YmA9|#x(Y_{*4u{{Ck!ASVYsj0kl)a34N%b~N8v!I`#(e|IKzcXL9 z+ke;njt3l$YGp&(`g3nKQ430(h<yS^I;CQvUe74Y)sRH*6>UwKSo89Q~OX=+>DDQ$CCyh(cGJa zvl$Z(AZ#Ud$gl zWYG>kJ>)9%s+421?MDx+zdiIWmxKCXOHdl?YWT&m$v$vrMG{=QxQCRl?L4mUMSfn4 zLi4wv2lTbLBwHm+w2y)Vm57@<*|IYOjH#V zW38`)b8r|AhpUJzl9z!B(}tX0Qrrj-AJ%$?x`r0bcdh=}4*GPF z|8+O*rcEzDJmRA;8Q?_Z#ONPGgX(cd47)p9(8wYWFJ)wS+dDq-C4!1>X^QzG{(R>j zW&Em2@Wp8`)(951Hz8hGMR{6frjAvxUfIV*-`>{9-Kebg*Q%;<11_CyLa)x=osL%~ zDRvi=i*NVwjZV7|?RouX=^r~*bahr+V7@{*VCqMJJf@e>pyT+x|FOHQ0BA#9w_e0OLovvUdMCfr@Pi!=@tI8FZ2pF<3I$-l8Bp8(!#YY8sMw zudo>3AR@m^MQIB;%4U?{cZw04HECMje~Ii2bJ-R0D!<`4c#r3hDxs?V#OIV$9``81 z6!sn#cxuq;)j!@lDBy~O4cLH|YLu%y(CC5>Oo8U_xsBfWuAofhz$s4*PgK7jJxEMLfZq zAd9G&=i4rxb>GKBlX0OU$$`a_r#l|AX^VF-2%!gTrYYjJS5O!%Z25t$o3ew|aA*T6 zDa*|CbzPnG^$lWBkXo>EOh^20YiSf4WiRw}e;KEv$K6U!w`{k;>rtJwYC=){*N^Vo zXQ#lq(F!sP6~&4@L%)*j2ua9v>$Y;lrj@noP;OGMW@9rt+$0WwLBN}=7P$NXpogv( z-*RLBUw5X1WiW`JPI9PSPxFTU!tu8DPYbMTjB_%!qf)qU%cHgx1dM2+lex_MA5 zVmvNRkLk|mL-K;}hsvy+o|YV|FK;raY$LuTL=wQLc2ra_dZ|kzLdo0!pBTuy8Wmv| zN$;kx&4n{?U^2(u@4O!K0g2VC1na_sr36h~leoLJ#>B?QLrTiYTEWD*ps1>nj~Qj(Ih zzwnZ~Ybxh!b5@g18En@*=$+mm>>`L}6#)e^1knf~+jn60j8QL|N-$+f2^c|oPL^I~ zia8xaB~4{bvPK?7NHrWez5cRzI0MD$r~K?mDuV{hYFs(CGMNZQj%lnY<6E?O?8{m7 z^Dom7pMK+$t}^3A8CId}t1^{ryM&fz-E)zL%DK<>aN9KW$}ib~g|KhdK-r`32r<2sK7^OYDZQp-sPIu1)o%&iP3;o+t;wHIRbJVa;)lSY+LZY zulVEZ3FH3AW4h0M@G%Uxs8a`QOm>ls+$J`GLpq>Y^0gV0pf%7_!0UN z*6so#V{y!x7 z7g26&n;9$L&7>L(p_<7Wihgs=up$P(6JH*Jvzkofzy%ln);`u*ym_HCfi%!vr{ zxe&+8x5EI&l=aKlo%|DT)(PT)EGahUhh3b+Z9Ht-rp4hAM6n>TmL=}AGE36<5K3~S z6XEKEG_AhSJ#&I*YC_K}j4QIL^SMq$Urr)4MSB&cQPm{ZZQr6h4jsbx!3 z+TJm_bZr)5Bv$wSF7TRS7FD5~Vh+IL1XdOv53tfKG9(-NLx*^oQ89{lc0POY2E`P4 z6;N*+<~IL{VSnU{+Whp5gb$I1hI~~CukyC_cdE)2*Vkqd5Eo{QNKp~E)q(%eY>#E& zER=QOj}_t{60I17+B=R5+wVCYHy>j1bywa|ggxqx+A>V*J1)#Tv)nnIJ&DO00+SWN z^X{ua>lu<7kV;@sV7T}~LPexr=f=awULf&sX6X^2XK+pVL?u%P0EU*{wY zZJ`r-eNb5T>ubAgk^Pj}e!*j)f=&=Af4@EQJztJt4C9uG?=~!#N;Ve^B{ix!>iG+F zRMI;V`L?f+8%P5=Qww=up47}^MnqS_Wp={5&m6?$;bGm8@++|Pr1`KzAm4Q=;oQzM zlt+F$x-B|k-6=0)wf1P<_qLghpODrMvm4G3ss>yW>}U6e0a&Ey`(O4)l2C zb-N@p7jqiE1~{Bs-7IpOZlLCxAeXCowsp;lVp_<4D$*uJl{xMon~`KAX7+ap;|Q}7 zUeUr86NH3@e-FSEME_$EVSybcJ|H>(Tv`Z3T?y0lw2IbGSprT8l1*xI;SO0dm9lI0 zel%~N$y4fPXqwZpF9}I&Wq01dBwg;-C>Id!*&*lflxt$ag@r_yyrHTN(<=P8P#6S| zpTF(ohS+V9IXQP(Hu>c5rOLqLa0^RkVl6$3YMPqHqKps{?d4%38>rl&hRC|agncu0 zQJJ&;Vs(>l<4Y1dYPPiW*eDEem4;xQtcV7z=aEtRic=sed`!Aa-FF+*_Q_W;Xzwgm zr_6QxQW&=3DeXJJa66**DPG|b65;%vIr%DdrCnc^_ z{%r)jp2SOLk7p>*IwLAg$B{p^r(4h&uIE%wEKqT%o3_rr9f!|0X-)jlw9hx|KE z6ym|rDdh_TcDAb0-=oBK`s2FptDaQ9j24H4vx)~Qk800P`<7_Lk0n7PM>5x?%#0P5zqI1AoWF4 z5d6-YnI2<}_8Ai&6CD>Fi!dcMF*QCtGcIj>-1r&_uSGOhNpjRZ+$*ZzhAD7#U)r;j zbgq?lt_kaqYjw(`pd>8bAeN92`N@eHOkgns_ zf69lcA3j@nX9vc!+Yp(3QtVb}ZbIzVUb!PH7fZBARgPIrMbw3%Mq_SC=Ird+h;)kM zaUL#EIzwfDKe1)h)=D}(eMwHvrXQuRxIb6xqA@)SCCsJ9^;GQkGn6=E&4kxb!-LJ- zV47aA!iD~lQzPZ;N2dVsECTGnTbCj=JG%7tv+Ay- zoURV9t>1gq)mw%O2G#VPBxZeUx>9RB4$6 zM?AkKj*66;ojz!2cyOyGh@?uHeEOTIOTn_(XJHOUnT$$SAT%2Aw@ba3r_9Su4tbA{ z$nUNg(@Q$6)353*`&suN`63xZ5WfA`KM+pF6dDQ7br&0Kr8Cw0)WC<{FowK*09C35 zW>ub(E^PNYOD4cRr4V)RucXg34L>k|eB~#k&x8Rs<6~>(mw~eh*^#O0N;%g7oNv&y z&U7R^QxU?R?7~GBZ)o7f-P6BusjRf1ZeCso{9$FRZ#WOt2{&!tB2()bcF7ss!({ju z?{9b;%t-=DQrs6aJVr;j&ZQm}(e3-uori(s23g!EhIN$|@$1L3pS~+8LAV)%_W_0B zHzn7##i!QVYyIttCyGLYe1*q8Ea%|~u5)vOAF+w{UdxdL=GEww)o5+ewfgQl?B5j^ zVjmx4E!75VC`{eBOATY^()Q}yb;t}G@NWY+h_Laz%w=_gE0z_ttpxAqy)htznAcXtOsi6 zrmvll@2c+8xpqZ)VTnCUK^v!O{&aA)Y64mg+M{h z%D&K)jl&)5?|>-EL6T|vLbpB3bQfKM2?V9Ne4aQGM2F{(`7=YSY+JJOdC5W+euHi! zb7tJ)eM>UwiS!r?JbSwrwbzSpFI@^%;J1>A1e^*J=_M*Rk-LQrAXOK2ij)+3G)Fb7 zxE``*9=10x6`AHrh+HfD=q;$n1pI(~Wd-_XIj<$Q8|St5=DCS;MFw}hx8EO!#_!_s z!KSKmO(i6+C_n<`O@VCHAq}{~PZ~tGtd($S>cOM5K*%0jl-bx%@(WmaQV5PCDY6>I z)q~F>2(W*~EG+V2ioQ$s=r&9oAcVs&Hmt!#_^$MtsTzY8Ds6;Ds3r%irXuM=m)AOn zWRH*rUfgM@->%kjC)$7aO*9R#L5aVQ$-V3o`-n5&UGVkYQ&su&h)9+h;4vc83~ zGA)kto|+TfF(G>@$9P~51gzd~5j_O9rt$`sGf}*gr%NEO1bc*DOx?ckQ5?qPDjnTZ zN%*dbcpZ>4c)uXpzrfY*e7{TQyxym)g~FdX&haqw%fxTs!>yzDM_FnIA8Pz!s(G_M z&iEd^0r`;qulnlWA=nM~GV%AU^DW-kcw38sL3_Pl8<|jZi26EG#fI`SK4;@Ci|~U8 zXW*vH@N3EOuyS{VxbGjfq>cyQ^KhH*C2nCr#rEXwOGBK-B;o(Rs3-8bbh`2JnS1*Hut<jDWwf434zzTy6 zlM0h^63p(;1$2d<2o#7Sj*CmHKXrYO6b4ZTAC%Js%TWf|<9P#Q?bK7PX}hY(?AjYH5=q!-l;Lu;$ugJi@N1i!YnYKuA|K@iMde%F_1<)wkbB;6{WSXcK zd@`F}ajy0?Ak*VPpNDH^sBS2cK|XJO?KuL(I|p5gv=b*5;M1J?+qlSAjVTXkK^qf7 zs_9;%6a0tY9B|b8w79;*3MntDvfX00zKQLMy@E4OGNQ6}sK28MjAzar45sw$cjO-! z%uHxo<8t5xWA+`=FZ8S5mgTs zAt$G;xKMbyfGN0sAGLRyffDVD>8g!1GaoUuvGQg ziph?2^>`uJ=_L2-bURxAC_OC^O=JEK_ZM>%rmO(PBaA+D%ExYOLhOSQ3a1kdZu=JJ zBbPs|3Di73ME$%gLzwpcS(mjb_Nyzq4U}6ZcBfLUhuqgrZ3<2+2BfMU_#_ z-9y&|AEl~^LXIZbByZ6+++ZL4N*TJ%BfqHK7e=BpaS?i=5fG2xoi|)=k{jQwwC`*E-aCiJE3zbLqq!=J$NBJbE1^W7>n`N}`C?_EQ<&1=<&MDD>p^eB*XM0_OQb|z z?`<#d@W~fx{N3y9x@9K>iBQ0IZy==F#~MAU9WcY)>>_3&oHwVK{~IgsdM z-E*{r?nlDk0Qx0>hXO33$+5B6ggGcxzkWSjrt9YpiCh}?{((4nd0Yz&?7O7oZ~y2k zZEd{@;l`FZjEp`V8rpB9V38UXY(!|{#&xxh>DdjA!}&A#?fs_ zS072Edn=-agj#`QM@EgLNIbqI!AcIUK<;bN^`KW&ug!O8*-mB0(xRgF%8t79pU0vu zr%)aU-$A%r*k1@Dv!&#+Aigl<4bNwcY)mJeX{0jjnR?}*x+Z5h3sSFbvR0jb&C-Gp zcm58tIJYp6N={0Th;VYrkgiS`+5_+O3&060E-9p-q#*C7>=VEV;}3g57Pt|CV-w5= zZPr*ozU`oIAI)la)~uja=o4-=+6>#)+G5g zEZdIOd|6Q%rL*HIxGI%-FUayhJ{)6kgW{wofyimM(7g6CB%&*Va7D{#-7?X~O*Wy#tE{}B&ZN_?5gYiXUyZB%&T#xK)vYBZzYSe}q1$)Bunqn* zl=Zy7gfDW(wjWmEScz~akn>733mHROh>-;C=`SB*d<`n_)`*d-E||}6j_m+(@Tn6_ zO;_AzVz@BgqG7f7xpPH?y(&p|xR0X^JfzKb$K{%E(qO=0F0NoLE@LiMgb$9BV?@5E zD6VCyDqzi-Uz``j{Lz5%`S>3c^KXcJPYu+V-VVGzJTapA8w6U@W0WSM>(3Ez0pCuz zpI=W9v)>mO4_eW~=*%Ygn(gp4HS>l_1-Mzn&j?y>>!C~5JDxAvQtn4jG>PP^1j0g1 z2VeP;@t@z;ExSTQCpx*SlA=DV__9VB$0HVza%TO!aeH$)*hFz=Q+lUCl@b*@D#mMn zUST}A?`-v0+P)ni5H4+l7Q8QQy`J;TiPHGX^z0OMM;@`pf2NKs+$F;%F%QH7*%})w zE2EJzGgIq=u0oo_m;$q31gEeHtA`||iv?QPP z84XaKArxH!?8`cg2s+x4xe*z8Nl9^0NpT+WwHEg&p6w@4p!6deHDSD>hZC9&d?VFZ z;WE-SRY~Wf&G)CMb+i3qpuur@nWkb8sZq7LGkQG$4?_G)umbpwxuVLxO1-*va)+tz zV|v*Ehs~0a)MbM1MkCuXy6wDA5lF7XrE%@c1_Xt(1A^_&;VOda)2Up*DNQ zx=;`R52>WgzLdx;yJ&GAlE}PAGw=wTK&3BwwthP#wguR?QXfI4tKg7d{v-z}e0`XN zqD48=TTYAH3HEsUthW|^-c+&PM1vc+C}+X_%0oz8VUky$PL0Z!(Ppg!9m5eAp`t28 ziq%X$vH2dM3^1<8n33x_{kE4{Ktby`B0JB0`XjX}ehcx%XHLp%>o2S5Xv<}Kl$pVG z5Y4@3gcp+JF`9D83~DVVys8rrc7@8pa5p68t@Q1_nA~~Me6MLfCcFubd0-=2)f49z z_{z`iz*~AGrRGxO*&$X~_W3IVL~?TXG@Pb3_fJfyI~SyHf3o!mdG$AlA1wc;xD|wA zLh~Md$K#C@_2px!Bnl!5#da4ei9;`$$l>v}kRxUUL*j>v62Ozs*ywCs#Ft^pA0CjW zm6S^e@rX+0cYIpxakf@H*G3tyd4E3NOIaSthb5trTkzQgK}DpDXU+B&1ncobwZ;+7 zl8#7_OchKdvyg^`TBr-ng?^4mVMycd9EN)K?=Si!;E1q3V&^*1!BQoW6d{2ks;jP) zu}sk65$*e7aQ&UM{Z=^x@&}PLG-2mE*Lv^YJU|F#HlCT3o}QfyjP*#*23CChd`*0U z3hwz^h_jXSa&J<6JTzl=I+8)Y092N`D;YU3$8*PDT24wvO1@}|dd!HhzW~StTY`Li zLDcO_bYRX1Q zT7h>g4Q;I(zIce5$>fNdbe!nu*q&*vW*T5FiZm7X66Uof3qLxzpqcy-HvMUeLP^fp z*yMMVC@TwawY!$CezYvZM@}@vqzoO6C7%1@V7U(opO$ml)=;cdlF0j+`N8HcCm8;_(4^{=t{A1F=RR&_?_-rB^MJm<`#X>7aAwP--&L&zB$9 zcWz$&b0Gg&W(#(JV~5StUZuWW09V+}%it3+s|KIrsySI=iY8D;a%A|HqHo_JhKjw>Ok0qDnC>?o~{zqhB>=z(@p8{Rq86s1`{; z2DH2hIeJMl64Kq*d2f85gRTpG&x#nfbRsgb`_hvnwW6s$@1DoYM`Su5KGsGes4r6H zgkGDN?GXU7EqA8JX9624E-rg$)Nrrc zHjnoUDI?b4poVRj)?9xOUoHeS8orR9V4+IIPcn(h&9O$QMw66tPLpmUo&50%_zK16?nH4c#)_n`F@8! z^vQVnFT3jB{*F5r$SXVN3U_gb^5lJS?O63D823TGLD?-F8rUQ`PHelf#A*oDcR({BMSIFhctG7d zw<8kvn2~zXMONr??Ztft3p(k#?Vis!$n$(ac+$zpyc@^{u|`(|O52>}_Aq5%oOc=@ zjd|ec1Wc)=KGVe&Jz8^Y-c#xJvkk z$naeOz?>JBSDIA>;`x*=RR)c2Z^a@;0#sh-E1U)v>5xaeyAaMStDSG)QKA`gZIg;= zJg%FC1)=>vh3tBIyVm$PKj%%r$Ol}4Dy_`Odd3NU!Q5hcV~3p+68pp6Pevd@JYSks zRar@!jF~v+yimp+W}Q3-FJeQYs!VzgKrC24d~}QYORCIZrt-M@$a66AWMur=uhHV( zg1e~GT(VY2ib#@U{7w0?P6DGx6EQY4v|p#iy`K>wqI-)LZ>NND6b_9!TK>rd{M7@L!iiDEr->9TT)mxhhMklWCBt|<(g zrx~FipSViQ(^AMw*??EsKrT$e10?wsBN2)_;%7;_T-$5`qA!mXA-_~Mxp$S|rR3jI zs*o;bq9-Kwuz>JvJj-USF0?=Dk+f+pOOSLbI5yD-jQu|Fd}{sMmjB8Eu}oCB-zy*C zLrDKmW;yHnsmy7ZSc}x6rfla46773b*NHKjV5FIHa%aPv38E<;jb=nJrpoF&daj!s zaY4TC8E#lWmU=j#X7YU#CeRq&33ucMe)sK!x3uKzMic4cAqk|AZsrc}eRSjoKYtC1 z{TqWZszb)ky@do!0o-6a42l<)QKN6~BiB-UCY_|J zB`)$wLXB)W*Bg-p6<5|nx;%?G(@ z=|}XLtCmZ(o(X&pBr-b&SOgx(?iSUywTo&i5|E6!X+@dwq-37zo%ZYVLH5EVQrNpM6V(xM#7(xk&yJ~2Z55LC_38q&bD!W zL53)MPn76828q|Syp^9Qt^|kAuQ;lRtf9TVP;%ZPZPPlcQt+q|bGnKemt)wc$PWc( zep(Yc>b7c~_9QpGCw-m<=+%Vd9$R0>e%S6VxdLUc$CY@iTc&gg+hQf;21D%`i zJ!m=j?U1ahpfy-F7Z^Thr`reR+Nb3~(-Go5neZA%xl!|f<-K8JwV#X9b%`#6^? z^ir)HmH>7H8O|0|Z~MOpe*ZUy@*H?jkk~DKp4G;h_hHUGpZ^8+KWnFM!oTR6kQ#*S z`x++++W%t{(SKX|@zYU*Lucs3L9OP`-PAz|qN!hl+usGV)qhZA0M{{|44AOjPO@2n zl9L*LRRc2#x5>Lx#3y~Gd0-??j0UFHt9xkITIwrfKD_D0ervhV1BuajJt#|gAHE^S z9mY^5H^fVzi$>PYv5bnmZ~2;CotZ$rY5E6E&?SeeqSb2CDTf6~=K-EaszC4-K_Yax zT@p7)1_HIqUz(*Du)CLVBuO97X%2%ViBiH<(eltfdEEL}YL>=^t18#F+S01eQ0Br9 zL-Jbk>0y3%cmNWMmUXBEE30N1wIu-1|Lzjj^PTPOUQAqEtSTUxn2Jk#XhYK`jE(I} zJ+QPWmZ2RS?TSYXn@vCn>Kw9oh!h*PwEX1Ua|M@Gno2&?@W(N+U*1&O=R@#(e^z~gwB-2BjazL`$*JU zCYZf`={^2BZ+@UuU(DSaIb^rYxUsReRaTriR{7|Y&>~u0a(#`!lBP|P90B#Rnu)h4 z!A8nQpA?svh(bt+g^P=iIaerUx-;0%#r|FhHX-1)4qf&b+K(D1M`B5a11RpXsj-0K zo*mb3Y<~T~{k=&!d(m2LAItEg4()%v04MFl=%V=@$FYZ*YWs6MyLLIoUT#^7&*ZgR zBIn`s>6QsYQyqA(wAVZ>{xNj)Bs`c2df`LqXyt7Q$FT4qryu$Z<;@Yt7sb$S-6+V| z=l+nFma3%fo0f#wI|cpEWl~^PR(|P75t;Zz2asns0e9{~&p%?FVIhl?F^O-aC1r@2 zytz#^A!OPJ#&b2=Vd0~-g{8c>&Mg`7?)$tMV_*F_fgM1IV-M|&^tvjhD+)bPt=E?l z8uF&P!36pg-uoWep0h9|v%wWsJ=r!cWMX;Dyco`Q8yfN$mr}nm;xFY@ZPBdJFhaR@ ztYULjvHp?BSZ9F;)7!%jcC2zH7@4<~@wHcPNoT%7oq-+kOaPGrdwH(ynK@Z zSJB6#`!-XhQgSSh-{w{n79*ZNa^e|0o%8Ym?RBBYNSO_Zf8X^jOiq#@5c?2A7k_wEhwzucmEWU93^PZM$C!7Ntc$kRq~65;~#6(w1h6v$F=I{Tbf3e_+WICY?)5{8W)nH;I{o&1)ObRaWErgqw854M}`M{z=5F)xRJ zhijhgY0kbN#?X4oX@Ogf+ZOGN3=g+xWYELB&mIhap}2hb3}Sq+15^}~ptX&64(qvv}%0*T$x?iV|1 z?hYSj^l9Z4;lu$0G?wbXJLQ?18s{=gOluP>H|A1r`a?7JnxK@bYs+JXcE#6!pY>cSi-PUF#=%;V%R ze7+r$|E{iNmmp*xeG>oa;M2qm$Ov8 z<4r=WQsdy`jhd~XZm0>t`jRx3TkJ&BCM5Uy1`nE@sk97cI29(+JsMiAStiGN)G@UY zs-HJRD#1=sMY~9ip0mspx z)<0GyMiethzN2e)w!EWKMSdQk< zbwyoh@>-J>8%tYzKXT7aAU=5#(c_20v8bq$dKt3SsmTi)y?piw*B=!{Qb`>~UP^wj zk$IW_%73EV^|fW=C3B-;+0JdK+Tdiy`m&7kS=H`g_X1dg+BD)}ZtMKWH?bk^i@jW6 zHhGhp9<`m0hvaNdZ@~$_f-ev8MP)9y!gvPNqzk62m13sg^|w_p*1JOY>GUp954`#) zefsSIQCr|9HpiWc$_?vD)BPFHScCvF*;4w=Me+uav#liCz*-HC=D~uoHdY=b-YG9~ z?#O>!{4Ma_lxVJZhY)DrkaK@NHoo^AA(y^K3!;~}fAxS$oZ~jI{^nvU9u#vgP-cTZXnCM45}alTC1fkiANS z$+qt@U2q6K$`{Vq0Tx?%2>coAmQ$amE>%nFX53UM#?h~fTDZNib0$o`nyyxWoG8}J z*y#Vx0VM?{yOEPetxv;$VQ1Wz!XQbKvUIk9Ukes&Y0RfzDubA-ga)0#iz7hqi2G5a z_kbREf0&=bW343roU2|*Y<{HQTk#CKz&9e`iSxNkSTxx{&3Tp8Z4vkK3FC66y9t0; zUE?XTvzh+stJY-}b@lkC3Cgkb^GqzOQ>clez+?$b>6xUu+Ol?Y0|z5}2ybvaNmkhK z3@#>3rD_$LR3R__7+?VUd{kyJ?PY8%?B!)GD=X{77Cy#li-(FjRjNdq3gwm>wMD8> z2#!qrUm|t~Fz^iT91QM)N6A~&R={OF8K$-553jdiVRN98Ot~|r>-%W5Kcm^daERtJ zp2v?FnBWL(@LSM{0>%r|8D+;fxstI0P&#;P!+4 zy1(#K#Rx1y1d}8jNw(TqdK388rKE2bP&}8G@mmGwWbV|D-LHIl`YA(1*~kzu_aW)2 zv07Lj?wbrgeUkP4^+r&Z2=@hG$r0wXn5E`QhegtA4P?1BATc>YgcP^?5|(rPTG-6j zH(~L6nvq}|i_;!{%;2eCME43sgRk#vdfHQ{!j|e&ANt#_iT^3`U+w%f1{@I4Upj>T z+K~p<&o+3Q3@9IZ{!tIP{lNT}_i#(VPn2%BC+TgH9Ik{6 zvqwp?)4t@qYj@3eqtol5<7VMx=>$R&1W>b}KKHb5OGz;6?)UR8$jEvxSL;)NHen!; ztsN^Y`sYa8u9p{-t?m|t>4t`(dAk}+^6jgCqgrQCQSWpnOG?m)trgtpn14%4ukJom z(tgIs^;Uja@9fWRU3o(4IyOcYPDZwrJTdpY7KEy?J+b|LvE=dBfqSX${km6#y#EZuB7t8k*Si7HpEh9GG6qQs*=;82VjiCJS~LtA+*cP(0{ zx*Qq3#%A@JOR{F4e#&yNCS;`zjSm`r6}BE8l{BwQ)AEWI{GC!pj#H5?`e~}T^7PC~ zFlXKH@B@<-Mk;epr(wGD5#7j51n6YpM1LjzzMo;}9N7_xV2ta{a_2@P)UFzRLywfd zOV;bj5>$(RM0kF1=AqMa&n%bQ_8rI#b6c8A1%vT z64^KlfQMZ4wX>3i&_jmy#>VExCJCyk36RsA8xr$x9@Z4^l^0uQVLg%*z1Iv;%6n{? zW)TPYqOQB4vkKb3S50vdvP0!7JG90C`-t&!B^$VSPbRhkAxJ} z|FMOq1633MzQ7es>|qpQ68;z{h}(|&xuS`qup8e{(TnvC zPfImw(s;>H5F^hLQ;W|@HwavujF?(maAzUpZ+%s)9n0SMT>cz9?pt4-LlI|4mQr2a zHH6#HqUJQQ`n0mmoDhp&n_os+LCSkXTN^xdW9Ir`JHHB(B?r6H5*yEuGrQ;7@j2zj5n`j}JD_s5}e zu=0$UQ;fn^sM0F_I+a`>|9QPv(*vR}JvMd*#+6ic4OGD6MBq=LFreogBFD)S96ykG z^rDWT9U8;j--qMI|)26Jouw*8gxEB<4u{W1J@MMdBJLMUM; zX_dFQmp#YbV(lohi_H2``C_|N{TtNCHGs~smJa}_BpRYX;!7~1J;E`p$E>2>m-zq3 z*IPza*>&H;got!VcXy}KU58HT?v#|4mJ*Qe?uJ8mNq09Q-QD1Oao;}A@A-du9oHBh zufxC(d#|Di$E;LNh7&`j1)Ek zYPL?*J%1LTgC`7(l`50_L#o&6(+|D{6`VSh1kklivM?<>oypty?lN_)85vN

E73 z9%rbQ!w0Zc)-W_rWKR)2+d-J@!w(P7;(nvEr3m5LHDlI0yf2`A3LgZBmc;rj{G^>_ zI)vln%j08&fdjIVw`%i7CEDKC&dT1u4BS{ck%Ak$9JmQ?ufW(5*Ix@;4bl=*zUkyo zd(9vce;k$^yI#(?Ufg}O9iL+L8jwb#1LhjtgDdZ6D<3&4b8%j<0Aj5M8d+!a^tuYg zMFkiz5k zq@27KAt}ZIxb=7$jXeYSo#$8Cgb4c|uNlqOjnl7C3ngL(6L$FDBH~pUEMNN)X7%&* zRf#(`9iW*y%YMoF*y-K8LHO$Q%Pi|0rf+!Mco!#3#DW?rin|B-d=PeUnEmjk*hhGx zU*YBA+UVGB%bXAJ(sWfeoex4!Agq$iZ;|q@zNV@Rw0oF(I47#1aTd@4;SHPoxW3C zZ9@*-!9E;Of9;bB6}$3{L_ITw@{^@ee0S$Sk4`5pk}sA<9dD6`9w`g8TRRE8h`|=1 z4A3f(?~=NGdfn-GbMl39sYvO9kf*)csMd?J; zn$i|Bl+%C^RLj5CbsLtBgh)SG%`||W(A2cWTo`k#!VRw-y65trbq%sgk>im?!B?~> zUxuK6a=hCZzle2u-qK0xqTVI*+y}~`p!KKLb?}h+r{D7(oAVX7hro<4<{njnkNx(V zc&hfuB@La6GCz)i^8UjQy+-`+2Aiiy4r{lC#MhJ=XOv!uPFKC+%%8hJIv3r2+pDR* zFVw!q8=n2ZDezx#cV_Xbp@5m9Mkj%T38-s)?=1A_Imw^66EW;2RhV_Z_TPS|7b4#< zPFXM`eq<(@Y;iM`csZ8F#FCf2tBE9wb;z|npy!3k@;Pgkj*7@)-1nKWl0OV84biK7ci z1%7L+6j=&XLB{l*f$&z!l$`lLQj{U7vii2>3~XRHtAC`0eV4Tpl`mAV5S7ct-WyV= zdqY0l6%8?4-mCSC&d*Bn!{uDaAcSCDeB28&26IhJm(Q>#_)&HLGh`13aZCUEsEu^@>Z z0cC}^w2nZs^Mk?7uUmIm*YF#g2|Jxa{o9=VKA0Q#+T#7#t~(`zEt3AP0$FY-ip!x# zz{J`5sk!E$dM6sx)^2BXplR)Fmh&UdTP(u*pLY@2K(?i zJ0kDRf(Qo_SHeyj~ETyy*`@6oYyh`G2^!$KJz_bEQ@p=YH)cTLifAIb}rJiuZ zX%f|i8Y-`Er`xVs`-^;RjX4xh>Fs^eUb?xquT1Ne*o8U(kDo$GS@!{45`nl@u4cAk zsF)E^;&2et5djf($oQ{!jvxJ3bkGv%cO3h?h%W3dDZJVv%nE?$qEOB8#Z?37f2zr$ zyt8%1B@?>DgE+?reUqgAah1hAKEPd(4|W%-9F%nT!Waxek_|_UPHP_ZP-yfkURAZ? z25yMp^Z97WRLH>iwJyJB?k%Q`uGYKM1Xo&$77Ud-aT7V#+1xj8&pgSscqU-pwirP8 zHX?X{Bt1H(iCC7Pq3>e7XE=yC-#5vai-KsK;{|@#GM*_-^Bcq=AYLyOycr$O)p|Y)$sxC`-lu=YepQnGKVHVD z$X8s)B{=kFDZtD3*H-o|3gJi3a>KdjlVk09CjH0l4h3|3@7uva(bEpMyR&NeGa;ZXT@iGpzxCj#~e&vl4 z!itC|9+GT6dgP}(0G{B*w+U$+u?Nu|&vIs+3bA;Ed7qO#ms$rs)^qaQqMc7a_RhBT z&fE8=d$Zqf;V*``%DCDpbyN$td@lD{C0pJEXolpOGJsWk*MBDb9nxDk6R!lssX05R zw>YJ&XN3$SiyDk&b!mxXrIh5NYzx@lQHLn`s=xN^nmT<1Y?ZQD^a05+2^lGAKf0yl z<&7xFeD`|zz}ey$E{$y z0y3vbCF%DVl`POzQ27wILY}Wf`jMPa{F1K1r3UhE&bVMP^vsmErACr zQ0#XB21?FviSa;f28i$*QMdlpb}Ze}*Ysp9JIkd6^)k$yT!6n%T{Tk z`NKc`90*#8q^b{4X`GeboO$}#Gp$&vZGQdq{ATOfcc1@zoP5R10;mFvKhl4>GC$uW zC}!qoaI%>S`z-z_M`hxHezCTNzIBCfe!7pXc2A0@saJLSOZ-jBd?^yM3tPp0&f)?b z<3asT&UBZ<77M+?(%KU>k4fo2j;q~g%5rNvc(eGNDRR0TmGebwSyA&_wgqm#Ktm1I zs`k!vHb-Up+NQe7(sFdLqE9B+A$6E|4>J)Q@mi6P;a%pecOxDs5sTfej0|yYjI4WM z&hE&nLZt-JD$AKXwO#n6RJDcD=C19Uar?R1quMiE z?kLYs)Glm+0)%0IXa}y!8J9tNj6wV1c3kRM+&f0(h&~i<00Q$0Lpm1`gbkJ7!{l`O!;_Q4$F+{ZB z=N*LE0RlG!tXfcs@SA?b!f;5XOH;vNB^ECS2uIPv!FkIIOL?n6X)kV>O-}}ij>V0J zR2gZf~&GxO@eEIk|pabp_Ytc<&>ZNL}gM5V^ss}oO)dT ziWz+Jl^rwA0Sx(*L0Kl=X(3h4@f$%-S|K^4XrLW#1mYuXj`DIh#7Alq?WeVh@c$pp z;*9pMlyT;!Y%t2M&prA=689y?aw(=@B%rEB(4xz`GQh$dwyTAZf|vK*tuyLL@#fJf z$8hbvm-Z`Ot_Zq09j;P(#CPggd?;d)7A2#2OY-8rk-6&4yc;B)M8 zIM)7rrD8|5^8J`oNkhV}t!BD{SYFU{_qY`cXqVO*74LVrYgaD@kSdQ38C&;*H~ zCB`DeSZH}@IXcqm($WI8Hc)WmI-8oXu(KrrpRUNr1CoL5%2vB)R9%xS`zboP#;Il@ zjltDU9+{aBpD~eqYb)^bj?9Ejd`-DM?nF=K78wg3lPpG=!oS#yCyF`N3X?5B#7;=N z*@ZSz=J;Ez@^umTYkeZ#wS4ZHC0pYjL_5rj1{Q$nYw!XFl(n!sC5yo2J#z(}Ypm;Q z6{s&*C9Vr}v>*h42%c&|YBsVZ8c>PhQLBCr=;s+sB~d`DFeEg874M}YbJ_(*H-f}N zrv>wuS8qzO^rLI$J+C+PhG*CRgTv=(0M~|oE_plrU()EwS7oCqwBzkJ`{&+Kh;zBG zjRX|!G}P^TLONCoIuB$y%FUwz;)+G3HjGpt_js2I>EJ0eTbbda-Zk zVZe`SjOUt+pPLdIl|f!X@{i3gTl5y^m>$>K&fW1^WUY<<-*w7N2}_i0i|d)JrRA>u zvzbaN-(NX)yVI_w11+UVj>qaEu8dSI7)zxHgWvD#>+kDjLh8uYwf3v(CDi=BT7EQT z$_)Uki*{NeY9aZQcIjI%*;-lyLp+XPCBBoI%T+U{Si1Xscb`QZ4lAywj6ELzPG%kf zp%Uy5=iT}3{O&LhzR z@KgXM3c!dI8X6fI9_6_}33U6)Vo}n}cm({cfwv9;lIS}Y52~c=*6sTS)zdV2zAv#0 zzVQoZXy%JlqY;=1g@v=9;8D z%s|Uv0!vsPK62L%*oMLC&K-PBNRIBXECC-*rPdisQL7^3z1 z#yWKQI-J-#RKEqSBTJ)l9({iD+;^7Qr<~F*i(D|9{0i>2elK#~D%85JSK(chkJ2#D z45ht__ATDKO9L&HH!W{m>A-Fb zRSg}mvS?i50@FMB4trj5Zv9z)23M#oJ~T-zVQH-BvV`zdh%oOT0t!9-NmmJ>t%cTI zRTJlKN_Ogp9Gx_ai;Icn6&$fGF8xw!N^QW5s*K9CLGVCh+D=#?0VHAUxS44+yXLPX zKA@u~_5!6xaYU3j^yREelHNfOJu>V&{3}Bd5i#QIiWNINoFL`yt`#VTz~RC)X{Xu| zV{l~SctUrHupGB67|C--{&~aG=yz9IK7Jh-1hy8OC?H=1H{~zbR{a3j4LI>8Ffjj} zkuo#}BNF_^UHfT1LPlooER#qO37OHsPe-##*o0*Xr zzynvi`yJ(Ly2N;Kh1luB`&n|K?3{nB@}#xVg*U!4B8tkmrU>YaqsGjFXji0>EC*du zY(5~iV|+J_9lnxjeyr;DpSm?kN|=)NYOC+eqUW*zMQBkU%>0_O4tK^2(XxyOT`Px5 zP^iM)vDsC8>p>gn^{8D_NKSA?B@5GF5v>Y_}=hs9u-^<&Z|%<(&O{!nR8U$I{3adT>HIk z@TWi1{h3V(%11vy>5qPxV%!zd7#tgWaFHtq11L`xBgDxv#xLlU5Pe+jS9VIi&;W~uv79p4g>3#w1*#1asmUn zHZrBc1@kfn5_NhPIUNnR$vFqugFko0V%(d-4{ z2MdyKQFG*z|7#EfMzW-J4-Ci-51F0ceKdj-%P}jRQp&pyiojI6VQTC8TG-X-zV(DH z$84k4?j82|OmcIT*}%c)y!3%K{J4kOkB4Fjs#&Z&Po^|+5L3jDg_}M#J_hcO*uUM8 z{Xc*9_4Wcjrhgikv9XD z0RBydeMm>%p4RF9L>Km@m)XqgKd0%xI}WHufF0N4V{qsCceKjJc77&@O6#obwOR3I zIoCxwVJ|Q5*{v(;NwD^q&w`X{eL1wRJ@w04#r13?fb!gaAB7x?nJ#Zs*zhtu5Ws1D zbDJAzaE-UEjInRis43@UYeZP5T+__;cx{u9JQ!uoZH~fU_TJ2^cwgXrqQ}~zb1$LT zL|NoPo(I@{^ihVvJSJMWY;C9&MMoF{mhK3a?=IU(`FpGmg==`j;F^&i*aqY5~vu8sN!hcY~pVS5QWiT2sXOg zt_y2IzA|)mp<)mSUb~I`;X6$YobW$9HE7M)UAd%cYHGU0pCS;v_sN7cy0e&jfA9%j z4kV5fFLJ2-(V0O!4TJ5DjU|E1z8DYY%*9lO@IVb7*DG?VZ1$5uY5g7tSKAomm?Fos zG!t{8Oq@|nS)LdfD#qo#cu;-hB|eHNy33(1cOQ4ot)*xM;%?{!V?!sy+WSW9p7|RtK3-7QW3IK8sjzrU zeruuZT_!-cc{jWUN576pzaC+s7gnSnTBH|gF(-L7E{S+Z7VM%ld{FdUUGyANdnXrY{*nw_ zJrIgb(ILV9QN`tQTRc_aqTSpl`k_b<4t{A$`kv|7JPQxy>a0%#u^Lj1Os(4Q>_|?edd1pWN#FHo z)}sad#bT$u`_iMRj&ctd;<|mwgIVvH_op=271i?TqERiOglxgbbMx4Cr)8E^O|6&` zwOXYr3B^WClTdm-M2WHKvFVU{=64Ng2?-fATRuOD_SlO!l9Q>vT6TX*iH}d01yv7n zp#4<%Aj|r(Zxz&~2fqr+4xx2s7XO{0HR7>}jpbL3p=im(v#@@lQus6z3UTfJ^?^?47(v++dd820;U@5dc0kke*93S$WH>?O z;Wgw^y-1q%K;;g+$u=C|;pD^S6ntMNfL2!qWoG4x__Y|=YnQ)@9!Y7&q0vsCirfqX zGu~(K_9oG?llQK`ttq?Gb?45%wUW5S?Q-5fL;yRf&uXuNyKLqxRA7QxKKui1^65bX($@k+T| zzwhNe%8>wZsZwWT9S7jD{x2Poz^7?L`iqU1BQzxf*@*<$GEARfh;$!hzO_{(x79=Q z!f8mlI!fOB{C>10e-t-1V!OInth$U?tNS(t4(Mx_t=5B-ceA6?Z@{y zXv}<=Q%FBkp++O(Uln_v5qsV$^bvB)5aRXPE^I$j>4%zmA-T4UUV1Nk|E4wnDU!4+ zSaDF2l$7oq)^HntgJrfAW3mmEQ{X-DunOXG@)OpTg$dF92`zHM&AZSALB@MvNwnSu zC+{12{9Mp3363Z|`j})lKdXyf^++e@ny9Cr&7@(0fu7&^$)EkA(a-|O2C4m{zqht` zwsuT*P0WQW8v8ihZ4mg)WivV_*axD@e02TPr8s~=`0VuT)Z8JdnGs?jW2rdKxyR#4 z`HBqaJ^G5`v@i6Y!#e8$hBK(N5iIJ+|psbgNTO@ z7waZ_w}B8umaT|bF@;`SBnCgG*j`no2>eMpdX18+D?~3wP0f$+LF&abv=|1QK~g@+ zFG1LP%?2IF1EK$ua)dDMrr}X39t!ix6)676Ibwdkl78Eu`TPAY9}kCbxM)Ta!HY45 zH$yC*rh!d#BYKO-Rv1fqiy64f8BHaGo~9uSMyl-W1;D2`+)%dBLUqOxeONX& zemBI6I=orhPW=M9&2JY|J4-BmO$<5~tx=TipGC^~g)|Qd#~OKC++n{RtbkV$#SOt;$X0?GE-WgHT0PK$NtRnVH8g(zKtC* z;>Mg>T>N0XvQn|4qRs$4!^Y0;=Zg`m8vX%-IR{;k?tCkJ9R zFONI)Gt+{+yo)bTRVkaA3T(5N;~jUWPvz8=GXLb0zu;%%RP`&#WQU5bqs?C^bcc`e zsr`#fd7*Y>p>d2Xd!K!ZkZr9y6lTW+O(Y(vBPJhKw1hhj8QQe*O!MJBu3!vlxA zXQo=HrHW_rs&ace4=06SVU+>^golr8eMNU?!jbwY4YYun}T- z|L6CunO!sKLhQBm{bZLbjHD;(1_iX4Z;BP5X9NVVDQm)sZd4>Uxu)I^s6DVRi69cU z$UV<+CzZaX@p^hbqbuh9wPDE{kXBB*R#0{KEbWGr@*McQ^XR3qI)aR=vFM32y)rtD z>NqiL7NV_hs9HSZ*rckbquR}k@%1xPRCrqU;%A(cn2dxB7bN2Hi5WL`Tn1agl(B*;*L14jY>fdeiy!^vAfB#f|NcPo#P#B#ab{F?DuPQ&uzTcL?+N^ERu zdU`BNLPn5`Un~?|5TbxH13yCiW|CJoZc6GfP+xcLOa!uH)UF1aV}ZKpQ8BQ?yG-cl zyiXQ){{#zeZAJeV^}e1fFQzc>(4Q06AucZdzCV-1{B$t^KZj;`MEVm_d|5PpY)8i2 zsjgJCuD0ptETo1}`X>q^nIpwx8#`UjiW|-fyTGP ztVc-P)o!Cj`<+YxbcIvS{JFRt<>T=6#lL?2u{cxd`-^s5t{_n!a@O12NBJs`+gV+8!8D4L;)c*I5s#mG9(3ylQPGJ zgx*(dtD>SjKF@V^Tg6<1qO?H(pGF+&2rNXxx4?Y1>Y6ePawTGGEBIyJ>$5Aup@`Oc z$BWgG2=NnOjmuU)J)I~W2(BxR+y7>CUt_Tjef+t91gx=lFw1d^`x6>$WOPxNs$Rhl zX^?pLW{!wJRBEQ19YxBIhzIS8aX9JN(4u;`gC}PYzMNv$k5Xc z=+`=}<7{NCV**72AK5fo7&w8q(>k^dGat$$%b3wG8i-lL(pf^&-BF&;;LX=vFMBp` ztDoP0GhZ4rSQ>+<6QpJHh5yLkAt^s@Kk=aY{#sw~njC(Z_*O*{Y9ji;Zd~M(06AQ6K>=7=c$NwmEgjl1rsW${hl<}_ zM;;fgtuk=w#BzaAqJ^uxD-$(0ZfMDn>09Hb)#6LF6uf}%WBhH;A>kbN|cFN10Pp z`En~a1cDtO;AL65E*V*H@{87Qk~jIaJ5`SQZ4BAuzW-{-xQ-Lb{}K}+qm2W4zyAnC zvO}<$iHVVu1skHA!&+@6_S$M(+>F0}w|R!9=Uk?NW58eN_fM+sq|Am8&PnWDmSXb% z=e>?RJcCZvK%N^Q)5WftRyb%Q34ns;m4DUYT9kH$44Y+TM}Suc79y&?3vNX+8+lS? zd`B^zYhlDB0=~v}EuFS<4&yqe*|YKB zUwd$(ZxnD(b$}ciS;dlB{~nRKfg;XvDFs2rKq%@nrBXD#hw?4f2Ya`0oixw`W7O!O z8)a2oP*i~rVusTVUua>)Ho8mUo+7E<=~(z+R%Pb>GQx>(vC$ISJW}oculFP$)~g%1 zC&of`bEv`#2$0gyLc?LigYIGOaYCWUgs~=P;@%*_sAE*F!?g|AiTPd9e~l(bE-tK> zvrV1j!UY^=4%Hx4D(uA4Z2+JRYb$A5!z5ZLD0CQ(0P)BzXTHPW#Q&t+=cIlAx~{wu z<;$v18(NpTx1N<9@1rd$g`J(u-9$T2jODOWB?_78RVc|PThmquRzO!eQsC?4KZa5d zo@W*aEGb^KFhp`Ivh{JBE;-_sT3R0du|^Y%DX~-*mN~XG!R2>%cW=h}M90zdfUA8K z_^)TSuaHD5;{R_Q{f5N>T+f{7mZC%bFY#c4(P+Q+oZ=X(ZY!c)D{nkoGRjjYU0JPe zVf#fpyH410Lfv}0nDH*7H`gOlt+M)n1B;LkJEKA+l^(3_RST72G^Jq?VOBR-a$ZA~ zQf#6_c$l0Gd6Odi{B}G|rR7Gvr-c}F<1HLi)bq}CGva9w;#xC$DLnSnq8g!-5;j}; zR+B9N2x7kFwlF@!wZ$$Ffvz(ubslNR(w()?cKA)t| zKvWEYn)%hwHLTAsUcS`T=F3kqIe0rkPF?LS$wKHU?2u7h{ehpwK_WjPaY(F>@`Fr- zx6>l)FwW4h@oyc1U?@y}gve-oF+agVA%ak&a0{#D8321lj36GNk1}suzywi}W$TbC zS#M!VU`ph?e9Ki)Q22v3vUj*J=*E6q;lSi8{ym&8$kkt41_5jQs?hOk}XrYXcq#Kg`&%`2ctQvWequTO1?WdY_kSRJNP63k(GPKU9$vjZn0O2z<@!;rYrGg^T)m z?ygZM7GpR@il|q_Sr1`o>Coj@w94vN%#_CQ#4Bs-6)>xG*0&;_bcOeh_SOPF5U(6! zpTl2g3Lhy0r=71{&RtZ7OsHaPiOBohMHMJkiNHRcvi~?==47)l#(Tkdz26lFaSe0f zlJOm1P=QlP@R!J&OMEat9>kXi&XgZ-Mle#s3Qi#?QaV2Nu4B;Mzw5quimVb6P~m9x zQCQLTAbA(_^bC2x&e8FLFX)2jH%SaV^Gl;WU;TJ%%y-PW-{>}P|L6=Zodf>02qf-hwoc>~_Ep}yg`E3No2Puu zW5gOP!l)dFlO6XOQBn34MC{WLi{9%ypOqT>@jrnkSOla?UqzN0-hbi@Ky%CRBgx)T zpH%7M2Pln_Rmqs+X-t$&i&f#YTN7wxDB<0UWvJAKKx$PqjH2AbGL%*3v`dhu`gDHY zo40ZCG8lJB%Aq2p^A?;EAuTyIV|W(3M-$W2o;diHja;(h-+2;4;_dlv$(){etqv=? z7kcwJlGuo4S3^m5NKJk{bt`ydX0?l;UM6MotiB<*xus+Fw=5F1a=EjKw8Jvuo10{$LS*tp)V$QZ^t|+hBuY!T^EhE6)G>rL z6!1?Sm>-rYm$=GpJtRD=DM}P&IJJTXb6h=<{$=c}iPtAe7pl2yxW@~21rBu1CGLkk zrvzWVd$=n+3~>)*m({GYu5SYe>BJ|iWdPNu^WPPY%a%lHC|)~-p0 z9@a+*ELQQ%K8Jd2*P-!B_D#i@w>Pu|tA>IpFPB{Sg1UriB}|d1+X@Ti_YWO%cyVBq zXwxP6Du1(Mh+1H|MZVMYUG@A?coXz3^Af4l%S&c7bQlIf3QcPEVPj9?=Td9QEYF1M86 z+uAKbL`xN_#&y|H3ZrFeeCiyHY7v_RyAO<#pW=L)mC}0|M`gN5yQDwUmI6x+V26fp z!-uLDa%gkfWoB2vMO!4Ut&tipSlgM|Cxga4N7@hg`|vZBh z`w==*E|+IAFN|sG+Pge%=<_;;%1|o58>9At5DMshVNKk-pZ(BJ?h6t1V)j5JI&Q*} zf++g_{`rgE3xWCc0~4?e?Un3~CV#8Le@X`N*OCFdkD6KTFWU5#@WW*{yZGWI(DAMR z_vM$TZV|{#{Wuy({ZAA$JD1^s;*_Dh_fKSy`bl1wUe>~B`kxr0r9c=m#U-);P98Tb zw}+o`#TPDIY=fxXC=U2$<`e#uvCgUV$2#XFdyi=nXqGv$GLg+=m>jfZ!Yq}0U>_kt68TCr{nop+vn(DQc=!ZRw z>w`5e`n8FbhAE$AJ`aFM+K{TZCf0AfM?_carwWCG5r2AuV!9DCH!;f+Hrhb%tIaUV zz7g~_{IkIB%giq48da~?&q^b(MEt=WSb-62On2nJdF&tdxE1P6sNR`9+DGBP>+(U{ zZ-3exW9#yw2_}?oU>6eugUbH$(*6E!%wOcoJB`gTFQTI~nk$;6OpQ*UChX(0wu;oL z`j_iHwI3L$U*dNjHtNyVCa$;nOXlR`PpB|;_zD@Xm z#L<~ZLgh!hr2Lfq#0|z~lHh&u`=a(66@AhQj}ZlLWMoAv6tSI2F{-l!$NFx=$t@3# zAh;yjoYG9#qVY*I`Ek#B!((Bqd)OM!OfH3FNqzo!LNCr`Z<0veoX->`y=`LEAPhGR zn@};s8NQ&#LE=tI6OEisdm0BKij>&Y*#1%atxI$%)j|y|8!Z&uGFvdGo9iu}7z(lW z$6x9~Ik)BD$}hQ3>CDA)g38RtV_)v_!!$v<+@l5+P054~Fwj!qw%GFOMm|icaIJEs zfvq3tlbTW-?DX%a|AeE4zBG4sU?=?qdcBB`38K&`JZ>~lo5cUG-0Gyvc?IGF_|i=O z0(2ctD=6BEZHHS~zE*JBg=gEoaee{ioF2xkO} z79AZX5~b=q95*iTCr+T_(X#TACzrGRMJ_(KGU=0`X~t;=XMM=Jnm~2iM)tfeq!qD$ zdIyVq7<1+oHh$(8VX9|M}@vllM$aD6hq?*=#!K~ zHOg(mrfvsbWyKYPa}~8MwcTqdVLXb#j<}ezaVP3+1SoO=+xl z-Vk>=pKK%5LsM9}9Uv7r28#8;QKSqHj*bofWSX3*pD?(L0A00Gd$S6hc`oc_HUa5~ zIkQs3G5^0DMq}Bla#!QgGT4XyuW~2sr&();jTw)D8UOB$h@a3q1dOo$G>pQ1cRn9s zVbYth4B>oMEqELbrKYAdvF+{82=MSQP}yR1bSm)&S2Cq?qO}DNRJ^|}^%a1wsQKU| zUc1&pSAb~1#P1#Vm0oQxipqSzT@*Zjx{X~R2&)eb z_1w-p=q}Rh&5!78wtwbfH$z{x$C=JfEu=j%DPeRi95dhx5WDy9euA+StWis66~$$;eJXC@0Xq!d7cJ zP8Fwfl?p4(9!_k)HmCCs=&$4ez^%mC;n66VT~kN62Q(;hB`49&$(7kv-#6@5BHKvQ z3(24{lF8feN{3w7%-)kM#?_C(mj7@^Apm#uB}L?`7$K8)kdj(O0tjSSuS}ZRKROP2 znJ2PNP5mJ&@~8LVPkz7ntqBkdN0nlZuK$e%0OU%)9?h}cF@=AXfX}Gshl!k+QOp*y{E^q?_Ub@mxzc`~g`M$04}+7B+hk+qy1y7ZN~!wS zg(a_{nDPl%Qd3;>`>+QL&S$;|hD;W9BGX?A**Z_R?~-1=4(#84vnLYOm5j<^y?RvS zo?2y5%xJ+BKjrQ>x_go%{S_Q-06j4^lMZQhdbLfM@c?-W;Lu0WP$lUQQ0A z03w+LPTmtrx>(TA>;-%-yujz#ouARU-rVC~>67TGYq({N3z;2(b*Zv*n)K{1c5Bbc zSR~PVO4}a`T01;_L$T!hW_o3D71d!vjVe{Nu#!e4e%Qp3RU)TcH|Go*;ss`-q5ga) z)i*9#&kD&M4*j{I{b=CupXBtf7<|_7Dh999F@OBQ9Y-kXcOe?>c_$`bQ zT`1?kF?P`6a`HxKVX-Ns@Q{<;sqq3$OB1HV0De_P*o|8v>`z@J$ys}iJ*4~z_q4UPfJhwT7lpUodR z%E_O~m2hOY? znilxaxmj;9F|EWk2gkFi8uiSoVQ2$vpG#D%<9h-@d*IM{=Eqd0| zmStLz;<;RkUZ|LGnL7-uypUR;*U@#&<0lGLtF!A_CA_gc=IYKP* zZQHO}1$BN=3cnt*Lm%|tUki$H zbzG}Z17xaj64f8t5@;GWlunGLP%PU(|L-}OB*35t{$}j$b3xIfE9*DXzP+&aIX=RY zKg-1x9*T1hk(Gx3K>yyc_wGbsnmkmH8vdG|0zn*T zl;2@?f&FX#VcPV9?lZt$r#Q+}(9r;UEfCPOa$zVA9QI2O%e!31nA+N)D-0@|GukZQ zvRfA)R&x*OFQuP%!5yrU&!`Yf6Kk1gyhQIVX)pXTruRh2At%)3MB+j*27d%Pfn@Sf z({?ejwmx5uU5GWvSub-TNid{$XhBSK*(#s$cfh8;d^Yny<6xnbx{C4=j`98OD@v^+(d(_HGyqlRn3AQYN|!_&hn+9*B`nkcb0ra z_mqCq**Ax`?UJ76^z&b0H+Y`K?9~|;zL_k`GZ>;~@er`~WHHr%kj-Kt7ZCDBBPR33 z%l}>dd@0GNLUfJEkCpX33+lZEgzpW&2%x zZ<1(Xrf%jc&qW=j(mC8OrAh@$VZ~9Jega?r6W#9gXsMsufx`1x^=8ifsw}_4lzAUm zrRsf2hfskVvwLs)9Dtd^v;&MNz!{QliPUQZC>|i~zKa-x7Br&EmQ2q^}4d5PEJ*X5i|ON3z?y zWzrAp)->;r5xd+Aer`HwWNow(xM=h$Z6>fc4t~k^g~irGuJmA{NQp^~iB0Vp{Jn+k z02roXaCCCC(x+@@8~@?W8rw>NLJ{CPXSu6X%qD9Sn*c+C@AmY}=pPu0hu)T<`>196 zj&Zluq;hL06ersta~}`{{tyDHdQx%^;y&LuWGuP z&#l7Q^0HTa7cl2tT0Ht3xO$VdOe8a*Y)~*K5g}u{LubA6$%^Yv_HAW#H#D+J+b~4Y zj8b-Z|JiIcPW!TTQAMqKO(bW#Pvpp+;_Q~Txhk{!)Xfp^(4V8+o3xyiqD;kS>?UCa z*dk`=8ElJ;DQpX&r)-isV*j&urongkqTNV_zxq*=ckSOe4y{5>C!-#USzN!n@F5b9 z1}N$r>T?i@L0EYKwG#C7d!GZ7uRKqC!52UXVd8^!1kIbBLOq`dzlwRHKvQVF+Db+N zTS+NE^$(sQo&dX>TM&y-E zi!&){G_-G^w;g!g+&p?+5;q6}kz@T>9HpRQ?Y!ABhx`>%{!R91GhC4)KznAf*tvXqY)ZI4;x%nFK&ZO238 zSV@5k6&HK1xGndA6XQ3^nZ7+OkODWKN+`_#!@K|s1ysfWoUnfOw12K?$zeO z$(DPVYvM}$X^wFqJMm>c6_M2zyGtjrRsz!KBJyHWXCn_=#SM`|{99m6 zhj-i-q2#T}>l1lwuaT|WFtdTWQR1gf9-{=_A_y|+;ggDYYwm`J)T?8;ED~0Pfe4qddY>}wX0mV?aZzS6V;PM#v!AZPAIC%5GxI`pryxk!o zeeaD54mrtb5m{lZj^HCs2@|nadXZ=hX@TL(t`?Ss-E^G^@Hu#wlT-LSQ~c6~T`4HR z=q>s2R{GEu#iO!4na~*%pbQ9)k19$Unk@qs3uxzQ9O4?KXlORJfsX6Zu4%J@#(Uog zB!GO!kjxqEx=#Ydr6!I8+{byJa*PPA9Es8j2<$1izA^dgP2|P81B_$*FZBm?-ZPSg z#q&2RQ60IhZb425{8s>n4e+63ZLO2vS@Z^fv!|4ApsOXshxPXPlL0lQ4^ZJ_hs5^( z0vt(>4uCVTzT)U84GYY{&Q4EH&-;sopP2psW9}{7qWZe`VL$-|=@Jl-?rxAy=?3Xg zx{)qXYDkf8sevJ-J0zsLTN(z2?))7-@qB&W>-huTxz07}@m%N3*?aA^*Sgnz?`@af z*WCuFLz@x#6{FVkb8}Zydw;1l{X$cC;IX~#UH}6bm8H?=b)P>ns!RFD$&EE8=2hT7 zk;py&BMZ#>(<71da@K|@xkxqA-ng{DLYj+>k~j&=bznrmT$V(rZf?44ZaN=0`o^34 z=5zYyDTfpU*-MqGDrdKBw_IvE3UJxSKLNe1OPoF>jU0Gnqkmoq{+?r|?Y{i;W9vPM z!~hIyxINSac7{{7>=ZF~Lo&&GsT0~tA9_TMkTRmg<*vu(YVlPdG%~w~_nP0D*^6mO z_f$~CwGedefOEEd>2q~}wb5B3)hbzqt9HK4*VrbV5~UmNTnop%VK2shD?}+h;A1XQ zZH??cx|>26&2Qf@?S3|B`w*j$FWe$p8T(j50w5ac63s`5CPqc2vpZ4}XKnK+BAJK2 z%`jB{lp`;}fA>T8BLV?z?2>1ZYhnHYpoFcHQ}wZ8hvrgvCTm1~J|UgcnYTo(bw4AO z#31Z=qQB7u8GElZ=e0#U8UZVVf=KYTHxVwCw}?H>4@h^XD6EUQ5=;uK??l? zBvT*|ANlTUH86txppt2^2y9Zfr?_DQnd0lGjHlw6S!}|jh7VR2Ti07l>cW>18&TBz zZ#j(@d=5+$LNYSIbgxw#<&8`NolZ((9zzyDcZdM`<*{u<)^MliNz8wVSk_km)l$n% zivycEChP-)XT6eDm37l2xP-s+8_NBaR5&5sk@4x)f&W+o0DbQw7htsJ87}Hx9DE0c8jp)yywPY1ib~PtOthIse!l$hcf&? zSNeAm5bz`Yry~JgZ`va=>*(;DpZuQ=zH~(-)obF18b00d#O(9-pYZnYbXQJF4uI}s zy2ymq<4xL;yIBK&W{rXT&UH1`h?3d;++NirPH|GIph*zkigBNcK7H#warrtTTE(hX zPPx`kBB_W*Ln(b|NN;a{+nWi99={7qyuETzQMd<^G;e>Iq*FOHh*q12|P6F`Gyb$(TC;n(x1^X8q&?eipx~eMPfWdx{*_Ekcqj zyzCd@W#@9#NAQ9Z-}A8Us)ceUs=4XjZKzM6Xpm4MdrVE$>Fp>#zzpZc1}3J@77+xq z&+k#N2e*zdgQTd%RUwjKwYZ&0q|~YBvJ<4R?S1ahmerKL-F;(#RAF%a*<=yC3OL#a z{w|zFOAnlE>3gnbzwt;l#_zhfz~^ zeOonkDp!dhkdmS<#|B9MZEy8(&l7+ege{Ze5=E>PJTGe|D$RIOZ5)mTxOJ6Tu_iHt zGdP;^>bddU=Y$%^_>3|KtKFzP=2zg>UIicn+$9Bk@cp$mwrAWQd0)83W8OE$8bEV2$?%0Qk%RQ@2^gFw>fr2SNZ z&M|%o3w(gi=^m6cFTOWOe!ltI+w4;_`ee1@-VDvTwTNH~sJS7AaIxn%+x-tOb4wx4 zT>0AHhogIFwH5BeCqh+Y_rEC>VO$PDe0uQq=5`pOjl*BytwjnY;Gr%eXL#ay`Kqt( zHB3=(+QGDIkC4jyy8w?`6-#C!AYNUyL!of6s$1^>NV$%j?s~R?Le|V-DPj9S{!Xg9 zGJM|@nYNEuCQ6J_`$6{U7AFTMz}MH3)v)25V=Re>mjRd+2R|RVZ@deL zvZq6x#g(12* zS}d{g-2{bWV-;!;H3mdo2K-*hY_*sIjffg*YHU>yZW2AiVFEth8unpOkA)XLzapHv zEr%l9_)F%EUzYSd$b*MSU9TQMD|iu=hjc> zTuJBJUgz9R@a>-kF7a>jcl) zj1!hl^qv-Zwin(_4K5;Yq-tU~Vt2l5Ev|9KoAg+?V(NBG=38V4 z#PJRbo0%~YsBxt&qzx1+00Y1y#p7+7F=HZ~bT+_YZK9%L&`yLz2sDqILY&9R%UX-_ z`;FNG01~7i4E{jEW^mYU!{71SVheeDbhOI1Mp+7~@Kw$A2fLVn7oXm6Z?fu<1aos^M$`B6zDr^Xnop-KgsMdgdaE82q0`1Vefa8 z?9+>)BKiW$?)F76*2<`K)1V2!a-W@NH!k#{EcSV#pLe~L^4|6UNZlxB;cnXU z$oCCBnM*3g)=nZk^hc%u;dgZZLwbvo#EEN+5B<|ATW_}0x#CIqYbp+m8|o_?!M&R% zkvt(vUyvN-bE&1o{Y)2pfY}%z1?6pliVE(EW*W6v!%C- z=~k|jizNUeas^p`3|fQA;5tdxhJ&}x?SF#nHNf0{UnBh<b}0ZAJlCkR z+1jCj`YTR6JZ_vS)&b<8dVw^p7=c6{|8fDu@B4&i3JF*3f=koe(a4u*;K0YV@bQI4 zpl!nlXlD4!Y3TuFsYsigb3VY)HN5zCSzu<>DJY^aZ0#m;Jh7YN?*765obxQx7q_p8 z?3o&}%KV7BQwoS6f8^Z?QcnI?@>9L1F3~`d6@g99${!G9$UTzoaJ)b$yln{P>~>Mr z_<3$QYyL#J=$DWjc<9Tpbu)7m)^bbFTC|XY{AD_S%RJvrgym}93W>7!-sdM$^MXaz zW>4xy>paV4^&^Ntn*hxR9HE{j9<)5^sg~A%oy8CU<7*@ zz1=ImEd^a;IjJdNN8do!LYYZLmj;Ah${?L!1>ySPem+kp3+^{W)+qGj&-TWum(zX} z`EAnXBurwRs2db%-C2;iZWCC~oidKlT}6s=dZu=?N1M^%4526oiiGy;SyA6R}Ay+NT?^p`chD$0FKQ)p`02OmC%XAOGL6K#`#l-{gd3J2Y zI?1=JqwX1eAlKu)f? z>4SzcxSE}I7#@4%(Uf}?i25}&`PHLVb{}lBIC6}iJX^ZiJ13U9`u}J|Y^bW$1(XB1} z%_}KPGLQPGUYQTXiW~N$9Jj_NOH?H-ty4K_r8|kf7S3DVse3F}Oxg3fM#`IA`q3(` za#^@>No)~HN=_i-PfmEG^%`HV#{$;jV&u3U|DQ+#(ByPKru1a7DNUIFOgFc{iVhW) zGClQ7+n%qBz0m{uwcEpL+be3t$K2s9QQDq{Ws#$lkclP?bcDu|N(~%o;BXyvHVd{& zZ4Q!s^*l)h>i%+#WJnar4LF}+5W#?C6rRAR#IJ){ksYiG)>E0gVs@is62G=-siiskXAS!ZQ z->^-}zq>kS0K9Z;YC{IvGr_L~nEKfqLDHJ`Q^dY*dL%G=?T{GD#a!XD@ent!-2O}L zs_4CS`@0~oyVup5PiAlP_b9h&%UWF}VRe3!B*7Zo7=cRxGPsmQc@$e8m}=?o{9?_CBcE~%&bhqErguv5ue3xcFVkR;(ujNN}JH# zJ-|gv%gdWM-fj{WU}d9wJ)y3A$L-(PtNMpYyhhQN1%z5&K~V1UNQ_WA~DNk zog)?adW3J1tk54W^Qem4WVM{Aw{|L~=VOJxc?D#OH)bcB_i(N+;HP5!P%?rtJWyP5 z@34ZdmDfh!_E3AViITt>r!+G6%)eL~Ua(_V(mhr!u%sMF+_FR9rK8$#UsK9CVm~!{ zedzUy1jhBq4^F)4RlaN518rWoS-iOm-n^GdcVCh);syAf!7!n=X@F)mZRtWuRX9n% z#xknII=Yv(2k;fDPPxY9Pu0Yt381c2Na@$xlQ^twcr-z+r84AgAn3=dL}4wxsr+)$Ra5#ZaRu zUjTT{c>;ib{t$)u0JR14(u(9F>=>U)EZsx|o*<3;WKysf^C{b;H50peA&*Vp;0D8! z?`qH1cFmU5ERDlpdDeu0`7Fxk$vyA;O=%3IEd8CPgjFoe2{k>xYth$ed6~ORdmPv4tSTmHv3d)3E$XZvGBz<@7EW`;;AXVGg)!x}zapBf(xSsOv zMuHDjKx20gOtvyHCvsFoergFMH3R9qWdY~k!TA(DdMJ8; z9UY@R>j_`RcrJp#)jNyw{Q8u{L)7P!z)b7)&Ma?4y8DUcdm4H~Kmw76bW5vF3d`hBuL%sZxTx=M<&3gOAt7e_qjAcZ zq(LwI%D}WWep0ZzD6bowq1ZC313hSp7q8&Cz&7<l*y)t&_DmHT&iS`9+K+*i@GqhUJ{LzSUOuFT4k_@#dTW3 zvBjpd^(;$h}ePnlG?Um;iS$;alXzAvPh4yqCSQ;y+Va5mdLI{vy*ge^$aQ$ z(98Bq3OahYacnwcusD0vI>3^nYDioaQ%3li{Kn5D>owLd0Oa=BOs-BmcSorg_#@n9 zQGRqkZKSE)tkFg^tf-?5I_uBe6viC%YxB*0GJ2wt%j zsBVFKgXO&NdHjO`mqHIn-_vFigDrk8 z!yhJ4==Lq(zjr|S5&L8h&BXdea=otyof$oG0(`~ zXy=fE<1j5CO5?0$=)0wLmPx$5B`SiTaH@xcxQTr?0b?0e zOGmvz>1uy(tv?M4*kS8cJ zSx7fH|JpHST&ba_5RcR>pI>b?v1#ql>Sg}y*b}Y9BAAzr5~y$ihl(G5MO6U}g*nPo zs?LSa6t%S>$&DQY5p0|!j?aaN*~h)Jmx3@mF5bMf(Y7`k-7`GjBkJgOz$aUjfGtWI zEV__}HGjFo`LGgT{_D$mzDmozf6paI@w>lr@8-W!*F_Y%pQL#5X= zjnUk*uXNK}6yDK1V$^}3Bv0x*`Rn<6*EZ*KtE^(jg2lH{YSu-v+l&eT*;5UWFFAr% zK_|d8_r}SP4u}(Son7B08L?bdkLrP2{@Lm zg@jl;2xxeZXZ-p#I1;E`M_%l~*g21j@Apczg;1**UBqD9Fi@H>DPb-HPQLDHht3qN zdXodEaI`gd0(UP(1#K2tO^+77scb(TVB-|(T!{L#!z^|#UDblft}dF#_bpoO%1o8Y zp9yN>MSWe#`AX)P9E4$~aFc_WdtB6H%oOP@FUVGkUR5bnXb$iJYC;ws`2Zhvf9gPg zOz{`Hf)LTy^df#Ub9b3tBBl51tcbn!X*5JN@e#Tvex{zGffPBXANB3>XezHka#t;` zvwJOLf^GLX`?wCNNJ3}GRNhE4E}Aa`eZrfYJr@FKEj&N#AI=EKy$v4)B28}V$^QmJ zWpqC-v+$JkVi$ESc*cIAxCaeovG79r7;sTa^tDRA?mAXf_o0GIbiLp>T+oVhRCh(; zz#T+MSbS9B`gvc|q)Nv?q3#Oe=H;nBO;FHK4kW8i_t}IfS5t|rOMvxvlKi*6Q#L{v z1x04W?$CMs5Pq)P1~EHuR#7W1g1o-%cX#ZoUf#KMaz%G`9K*ehxx?Wl?xNgeSG_|S z^hGcxlDm5PMOEkbt+0a&o3|dDjW@yc^~J^e=0?G_qIVD zyhtte3@Lh23l%3}n>4HMCy90UMRB96@uDwfk+zZERbToNNo8|ctG@dQ1gV2}dn;hv z(i^wFvQ@H`eGfg)2O(4L)H6UD2ap3Eg#g$l)<&x3(p(YNVz}{LsRxhR5z|Z?v&|zY zQA3+O^g&eqr%40V>bqwdM|_--m-`ZJAElEr(0%zWHOfiBwShDAJ%$2UXKc;*uB;@9 zq3gVCImAhf04>3FK!wiBF|y1bU?wDx>cDojAIS-@Al*balSKnlz*)htIPIi8Z|Up} z!pw!Z`B&Q}OiC*CteL=a;W6CAS!R&l-;wk3izBtbng{>`&tA7sHMQD0T+0jqlpW)X zBFe>-<!{(|5`~|XallzZn#9oLZmeV9wLHS^4;)ezd~r1v7>agf;!2b z7Ig5Ur+~m?nGp`H;=LC@qD{Vilic#8A=J6{H`d9I9%Kz78~Lzb?1+#>c<5`dsVz(I zr$5sVMqlNtzg-$5yPLr9gEqpsb}Exd#rVAGwlexUCs=&*M7g=t6F~Ilnon~fdn1gq z8FxM~fjXjFH&%dmS4GFi$`}ulmu!EOrem;-o}6P-KZ~Y2Ok~8&&t{$jnSZb_$)Srj z($QeTjhB1B(Z}&cYl|)UWqxzaQB|3RcSu&wcCN7Nc*qoUiq6UDL?10#VR}Nm z!Z$*g%&>t5v#vUUUwVnsLg#EL#}n%nSLroK#^7g3a|7IN@{xo3h$QlnRe0@}Tr6zK z(0~M@)34prHZTCBwl@aiEaNF0j^u=#H-5=#7(xpDr>sps?#mtom7@L?;Qt*YEo%Yn zH~$-w*Jb|-_We}?f>7~ys?ke+0c*R|OVg+WRgD-~T_#*07(2WYCyma`93C%(q1!OO z_)^2gXNSg;x@?E>o1P9}Uj3T7t6z?se)6X9=-0)a~D%_qze8qYy{de-Cy66X#3l6rFdyrEAN)B3kx)DX= zw(z4iBp}v2XVnhaHxKkPcfX6o7 zX9bx8RrgCyt|#`kuNn(ipj#A$(*TYC_m_@EluU4(f#v-S>1~WyW?#-Wa&YXn`V%q* zku$XW-`~kzDrN2C%K)3O0qMung61RTZPIP6m}a!i!gwFtgcgE?X0(&3IEO$y2Qdbt z3vtO1uOy;r3gZR_Q{Ok%-V~;KgyHKF@~cv+!%yfUT3@d=(<%&yjktVD=HQIky=94z z`?41YCrHSyp4OfDk~hI{Q8c=}0QYteP9bEPQ-U0H@P$fvUq^QX7Vz!TKy_K|N8&0~ z%kV6E*WnX;?~xCvb++)e%$WIk0M$y!S{J26UX`?U%-WQllUvh65zjD()aSxu3P*Q_ z@#Fc~uF=&O|J>gF|B9_x5FW$wXG>JhVgH=}THMy;iQ3n9iW!?&l!qN8tD&pLB*s<+ z2=fSVaW^-d_|uve^rMP3o|vdn+OcySK0ItP(BasUOnDt@!ZX+*SQ}$_zA~AcUE2MG zMfWnELU%4Nt90!<)&Ni!s2$ASVs} zsk+f61jp&kHLCTUXP@%jUcR5$FF-0rmA3{Dm6z1MpuP@6Sb#^J-^6s6|9tbQIj;4& z^pZBqU**lnBQU{w;#;@qVdHA6DuFz4dOZ2C;c0m; zYVM%i&F8hZ-gtb`s<;^M`uexX5Jsx(u*Ll(d+ICyQwL>H+!34X zj2ZSBmd6(y9eH9X)43Z;;T)C>Axl*l#gMH=*K1zXwc*ZbP59auf&^x5J@q;^GOqZC zBlu5c+v<@zn0F-nt>|w#dtwZN%hu2nivme{{Qht=HVqveI^eVJj9Rzwxv9xVL5e@^ z4M+!s6g}fg#KhzPmRgU5B&ui4#^5^tBm!75rq= z#p=Wdqok_!Fu-=r1X`{5L5wZY7Zhp!%w``=t?_kixM}?-?#h}q6qU^O^sk8`z;Fff zk705z4yA`o!-&R4mwWjB2mYJjYmdODQN2)LqZis;vzN z6?_GyuRS1AVDhC5AptM9`DPmjv}>{#iD7UE&t89mL*SPFBwO`s!I}jZ{wd~V(K9B4 zhW0Ecb-_lOnwm&E+dU%g3cCqe$!sVXKa9unFtGY;ZE7mINRTMf=ES^2uf}qBY|Oxp zc@?_4vI(7?tNxN&l%Hx7Qe#iS;OekOX&zkzTWB$`Xl-*7TNHfi>M1beuQA+4zXHE= zGUn}YJz~}^*1ZCz#= zs`Tw@S%9!=k;J8ulEI(5%En*A{rbBGjBfY%f-uO+wk$ID9 zH#0_lC-u-7*X9(9a3ggiB@823Fp$iK0a8*uE3Uy;FyeV0+tWbTCyf2A?+Q^tQzhEd z#Zk#AA<#m}=LeVt0s$yN*}=l{d5mFm^8$SQJa$=Dn^P5<$nF;>@X;i@9N4^@)Mo*iA4eaMSR*AD$4bZ3~b>)rBdr%}52l75~V zG*f;zZ+bGvq$V4E(K+Siox6)pn6&?`ALPeEO49Pe{Zh`h#wh$)O-i8`L$mV$tRJai zz_^xui`dGfU4CisK2-y9lZA&Lx_ zKG#YhhooAPQrv`8*^+0gRnu1%h07p2@V2tR8iKvfqRwIW>q#SRge&mLs!L_9M}GO~ zMuMBmDp3Rs!&P@o`r4*$Y6(e@-7v%WacBP+)g5MjMPNOu`-U_*BRVqHAcp*nu@G7* zV{7^ZNezpeFqv}MRV@Db3vbsHpHK=zvcj|k{=E$v{6dw}5QM`L$s0P-X!%I%Mr!w*v7tTO0a@Cj4TMp)ZgS&G0A$QZrndaW!$vP%^ zKgzmUXzZ?oE*j&#M#DSlyo&zVx!qn1-?(L>@{f?x{_$_2pSqk!$E2{}XDdd>5#H&g z5D_IYp~_qI4ty+JP=4_o*UD=6(^G)!<^p~1bCJQ_;RJkn+5TgK`*Iyp& zf?AZy%SgZJ<)fAT{)x(D)Y3OwpBJkxpATkE5#X_b&J2vIj(7fixA=-Eyg(y2?>x%Q z4IOH3X667KfaL-H4jFliMlmgwYn02?cBu+7la{8-$6xK}X1%jFp_b!hH#^qcoUd*C z!y>vT$~XHiIBFMr)XrM6Et~FOnsQMXy6icB#Mrn0D$z0gP4$>MRZ_*JJPnaiF9;UW z0o?*EO__?9hH`A&UXy)@%-2;sFG{2Lm#^_r_3kSgtYGcmKxHieftXls#Hd)SqjpgM zIaSWe*~!v9-|sg1jhwQy`<9Z$Fl}Eo4g^}I*yeboE4SU9ymKw~2$>}_jZgHreyqf77 zXgzI#*-k023Efx+y#$*|cn{`UjujSHQ z-n9Z3ccc?Cz~x`ONE@ScJYE`Z@jT4DiTK-Z0cKTT3%IU6{0)!43{I2jhw}y$pLwpv zas=&-@3FJ>wT82KrqMN(g6Nn1ecG(nkV*Tet_Jm} zC`Oam?}yP3VT4ocY&|(<`BRURB=AltG?65GFL1WVeD_o(sQNmuta}moLAZ1{AT1`` z>ZbFX78(TkJDMv z%ogQqbnH~4k1AW_(5Hv_w=z#}qOoy00ERAJm6<9d~LnlT3^3IJ!Youh&$*K=z?~K-vu~!v$m78ggRbwwC}jE<1Bx0f4>V; zwW|$N1=-2RZRy33>QM;ZW)`z8zTCJ=(P_}o9~Hn#DlAI8E{Ssm&jNwnbsLvKTq05~ z>}Jmr&%eOM<8gZY%X`5;!vqP#eN+NH`nJQ?XHBcr{+4Y?#>BX=&yJVm3TT z_Aq{1M>bBArbO(|!@S>(h@;G$^wD%Bmuzg+Pl4Fq&2J%jqI^rOTVFO(h}KQoD2?;< zdLhZC^338b)LmXE++*)V=AN}&X84z{lgFgkvZ;E^!LXq{q+eqN)bH?OdN7 zHy=oPV|5%@_k6f3idfKVpa6?frt?KKA&>3MS8|DLWEtRt@rq03j)=_>&ghv&eOnv+ z6C`xZhjk>hS6r4~FKPMsyn293L(n1#NjXi|dsK5|A_)a)+-~c(XgU>TlW;TH?2ac0 z)$<2Zc(^^UtN20VThvOKye_|*ayzTmlXrS6IV^_z(qiL;cszP!@W+VFbffCEgX8WIz8>G~^TA)+%aqO*)MwnYOuExC!; z<~)CuVS+KGQhsr^c5C^epO)u9>R*?tp#DjAg6jY^NBrM2|AvWw$BGPCudz$8wb1`f zQ~q+i|Mvx^7p1aJxd>7v|2GQwzyAaNCK?ZnBdzC*$p3lXf88B^9QQRg_ux%?!GE9r zcNl(`dm1WP6d3>IKQYFC-Tjjl3MMFJ)7M1fzfS)Xjy!vFMlg%bz&~34b`r3d2W$7Z-G6WKMYOj}&uo#~cl-e*KECz#=49C2_g>L2W(7L) z?=_E26d*z?N_D-p;6dmO})(Vuo3G`)#yENJ&ufvv&%_TI=ffdX!z-JC;?e- z{RRA4+1>C%vv2cjR^F|VQ3SKG?0(u4;5wzn=Q8ditJ%O)fF+3duO)sCHZG%=)NCIo z-{#1mmM#R;-yZs@9~=mk^tFZ@{4p*Hqyb~M?%e!mC{1_-gd%AyeN)!+Wl&SL3L5BCTBC8wT%7tb~m$C@uCzGV4ykhWSE7Q~8w=3cAT zeH)rw?OxVp6z|ef<7+!v? z2+2DJ9xKz?1A$mU#-)*}i}UH^=b z2j#1E!sAU1%C8Ew>;y9{x@lPlhWv!>Hj`AQk;1Z*F4C$Wz*>6FRu)r%N96mfm* zVz82dPS0)!tsHHqPQ4I(#9sAA#7G6hq-Gy0x7C+19>Uo=GI<+Bt8IGuiAa;$Ox7XM zsoN%3ffma%xm8U3w(?G{u=c6+mj1(u{QhcfhL)-Z3*W9n`%KRhU)vPq=;ZWfOA|GP z?iF+J45z+?GAOS+EU37f!;F~F>bB}bZ zu4ll!;z-_(5?BeJ;X3syqi0n7_H?S!n%X4&LeS|IMjKm`h<=@#m{G&6ZarCv8unJV z$qSaUHE!y~H?1BgLw3-hM%C~0$24Wk@aVstXdQA0=}i*tS(BD&hg$9kdrdD zRB=x!t|#3YVFpFkRtFJh+u=$%p&0_C?b9g;ck`Z9JKx7ieuzeuXHpQ*2`LT}ygPHX z@5In>i@L9yN?1dD-1p4-{MnuEFJKhdzMTsTjTd0`>xr|eBaO^!Q(LX*n>_zK;$u6z z6+pv+D`mBOKys&9@I`e_vV>7jz{@MA2bow$%ApzDSYGRg9aBK(RsGy3Q`@VS)kk2q zx<#$A#(c`{j$Gbfr$Jj7yP1JPRf^r+F?`-h?1BUDood`QzT2q0oRd-+TDcl-Du-)D z{&et!dR(xgG;BliL_^5tTh&XiHrAK}h31T!I&5T;k3w**PCofVa zol|cUyrMg89Bfc)yBnv}aT9;zU7-7%b#J!*Y3?C_xx3Q2p#Nj;bq%g{CCLgKr-)gF zy+_qg8r?96zfqvPl!CK>BmwuV&G+HEl=>E)O~(>I@$N>#do`%k6|c)@Z+F8`>+}TU zY70eP+0h7~S2twHqbDvEh{&~Mtgv7!l!*nOs^6a8{>tB_5BudE(6U*zJ-_JSpx=D^ zf%f&>*2M}NWMxSie4!b5?u>`Rf_qSI5n^FEnuZ9{EJRbPc- z?~X<@DN~z+H)o%O=keZc?J$wO`+glP{HFO7HWj%$-EwPaWy^pw@R`7Cik)g=)s#1M zy=q~!N*7j6Z5jihkJ(T(=jb^NT_Hvp4IeABG9)?vc@%QKci>SliXfF5GI<{z^fliIyE;U1o~0m(XX%<{GAHWAnICRc zm&I~e%x+*|WJI>A!&)3P=dbfk}N1DD4-~aULca-fyN#BT^24{f>-+0Se-X*@& zlY2(1wd54?-0&MPx zrak4!JGltShY>&8>8C1lfvha4uWhO~XoemxG_xtlHE~a#0}GK7ehHiIafzffdaAPxhyHMNI7|eYF#^S$?PrO zaC>E-El^mn{LKrADOiCGs0L~>QQ5K(&cKe{?CNFpm8sr94Sdwxu%Ay9 z52YQlsqOBsmW(7;fHd#;MoeRC5*rFt7F4nO)*qcP|7-1l-GeECBuL=mbIjj^;7}W1 zMR17sN7$0r>^6ro;C*X;oQLVU>n=OBxY;RoMV(|0VUlc3jvTrCQbb6L(6(y9-X(x^P)6H*1k!&5rLGjc1zPdmgMnRWI z|CbR2ATt6nukjtf;NNeaZOoMd>UO#u(Q7Uyy)5guqGM|Xz=m#0zc!6bn zyNVO^pc!M78Vg08vQ?L9rJr4=hSZW)EA`Bpxl43)7{kUsWS3@sE1<2$4XUM_PDt=K z6s)7`S(@u>FL-@1bp$wayqg8-9PkOjx#IZ`jpE{)CWBx3tCL4B{^-0(AcNISpG!mi zt62hwm>o^LKZoS$IE^t|u1`!Ejeb*kqzuM<}-DWlTP^y!-# z$vDRpp-p^l`@V@@D?tXPRmf8G12s1Dm8(thUcvs1)kJ%|%`}r@Dpx^sdXT|DQGL;S z2a3U1^=XIe!^00HM4*)EBjS-^NPzlbr)U3ksnN}9S^#v?^L+l}ea3^pqdAu_&x|Zf ztH#L?BP;9I`3yq$CP2eg)|N{j21G92hofsJD0Ylbw>Hxr0Fh&rZ*Yh%CiLX=62ck# z3+>po=Er_Q)0-LvZ)*O-Yzg_#wu6#NL|lAUM}5^cS{AfX9)0g<@_iFuHE(qtN&GY6 zKW3SQnn2R3ThCAUk3H%CUS0aY9x${CNMbGvKahKO5>I0!q%9`1YfLk~^-YfdvRv>Y zXH%*+993ACYeeQ;LE9*YE-bIa;xxiNYIj_-1PE(CY()Y2brDAx`0#g7v<6~9aa#T9+W>N%(v)VDZ^wSSx1 zxHsMAYpvXS86M@3d{&iTvhpL$bbo!+`+hk(0Y4|fm;dHZFZKG-OFbR7`o~NC{C{KG zAA9Ef>9Z%#p0$rJ32(ja%Bo&eY# zzwvjflf(5jMRzQ2 z@A(?L%3b#8qIr7v{tCN4(?#~a1IYUw=T|~2k_Bv>Ho)WdK|OF8*U2l=jf;4E10&sn>;^u^}v z&bU+m^1S@oU-u(JfJ;jvJcOeDewrf)cm9G&z~+Fq26{U zQm7%~Kq25HuTFhg=HlF}6^!0`8Cds=|q^n_EOE>BIl zgfvnCh@>=R6R@4C+FWFT-E@Og;E+}DK5O80VptVuMFMmGBu7gb?558En!ZBwzU;9! zcr+n}3Ae7gJa4W!UU8dn2G`#<@qlN0anxap$800f?{elF{r G5}E)w&mRK- literal 0 HcmV?d00001 diff --git a/localization/yabloc/docs/yabloc_rviz_description.png b/localization/yabloc/docs/yabloc_rviz_description.png new file mode 100644 index 0000000000000000000000000000000000000000..bd931b139f93b464b66b9fed25f1142e73a6020d GIT binary patch literal 475695 zcmZsD1yoeu_Wxx>N{|6TO1eQ>x`r;Lq*FvXrJDh1kOrk&x^Pr&CsJKi0S|{92LJ#(B}G|H0Khl_0CX=b(ESxt zP7Ip+A8cnueOCZ@{QaK~S_=DP3IL!1lw_r}yfP10J^hm9Zh(`WG*3Zn8wM~Inlv`H zTs)`ocg}D+Js~x<6C&b6<63r~rzbVTX2K8ct*-Y<^$27kWo}sUppfhkc&q67E$Z{t z>Z-kmV1_(MY#s5;(sP{`CdPL@HZpenHt?`a5t}HH0RRI4DGLz`9YmHcGy*75q|Jvg zfF9yt!DWgQL3nagV1XhAIsi+ShE6tF8RrH3eMB;?eH26f#&!IN47OYd5K)p;sEG3d zfap^^A)o;#tm)ANQ&;&TCkG$ZNPR>Hft2YU5CB+;1f&r-5kFQi2yls1i|nO^Qb0gQ ztsPfKtwi#{kBD6@Wv8D*cuLAZ>(onG94r8rC^0#xr?G9m_a`kK9a|AV5CNX_XS_)a zJqaMzpkc9)AOaDi0kpYbMcJD?+K^;rCtRp(;T1o+aw)EiVi7O_W=YW>X`kAT`V`xy z^)4c}#|q2e832Mx#HxNA9&+}OxlZ7QutzU+j&6*+$t1OiFI6_Xe zdqP2sP%LnYrVqtD^*~OLC4wf>C=?G3TahMT`!hDAg&ZC9f{3Nw|D22zg!QauUl^9c z06@@!(Xm5u(9{#B9O405rM(%P2a0(B1C3lrM2|>4`a|?qStZTZQbMdKEHvZFG{?3w zrtAt`q)9l45c-BCad(kBm`43uindHp!&o%BRvY25Ew-@+Uxvg7NdC^LyV6q+pqSWH z76dY843z~lpt*&8nD|s#p`#j%9@+z;fk5OK>=}s3-YIHgSz~}SaBNs)aBQFx-*_SM zQ(J?6vnc_r3__D&5H9GUastHc%c43>s5GPE?(>vfcqd_z6vhIPP-vPH0NGt4oves{ zvwMj->c!?38m3OWo5@^X!|uOKN5>wlNCSyi&jqjxAs-Ya)grKPQfNLHRpZb|<+@=$ zB!J?EGAITunyJ5AP#3|D2Zw@LvT$%im7%J9iGUV*Px}!YI7Bm^rd*K_#P(1?Mv)mU zc;Y<+fW|OtH-FSF9r+H-7SDptMn?pJ1f%EC`4fjQBtH%VLlkKU&=Wwwi-T-BT6Gv* za$X2}vAXnPC>m6m5E~n+7y(sQGz-<6f5nJ~PR7EZgocp^0<@$Rf*69OuoQ9B0T5eq zFs^1ugt8(7nj(V+4Vy8YVvv*%domUV0YNZC8pJEZ3XVwT#Klnu6SC#Shg4aG3;{9; z(uB&24{+re)Z^)p@lXa=t8UuAq-KD4~jrn4kA=$p{eJl38In00PkUZP^YD(Wu+5cV(?n2 z{Be^b&7F)E#t;b&d6&DPr5QgFsZjz6GJB%T%B=JOm-~lUa3dG1X3uTTA~Z-tNtFU8 zG4}yFAWa5EM^{Y-5hwv*v^|X1Y&bmjiG`fwQQhwAPn22c{7ve=f><6(1IkiiE*FZU z7$Gd*TTSwC32`dqlQV%ZO#p+AP(*2eEuqSeCPHzZNL^O;UA&ZZS`&Wx)gvnW(d_mV zw(-M+L+Y)n5Vbm@p*^!`>O-?;Umf9vu*vKW^&sm@Cuj&5QWz1kcs(=9 z3J@gH+?zB8qSoO;=J9}P?lo$lUmU&_~}!Q~}1`LD}p5F5bH`su1T z9sd_Q1QNztev}g{Bt)zkZQRg0c}T=hhPsvl$W0yY237Ok6V~$ZZ4KGcZzRA%$jOQ> z{uW$s0bD{)pHhcSyJ|)(qFrTWFAWX?O&RXzQn0Y4ye|Ig!$gx$b(QvBmR2dK{LWr{ z2D3VO%GGnVO;h$pErUCA2)jg7D+F5gKEDgCfVa)IaC&>cnJ|dGx*{;;_{HAg*-KJA zde&2 zoJ^g(UKonxVX1Pc!1(!|e^#MA3lS>_qFpK*Q9kSdfS@nJZLr>`$)ku|Q+HyGdIolBw>W;digc5%PNWN)F$k%ntrU_AI|6$N>1|?UgYauVC=nJ$8IOd4gu=c04w)ZUm1Ti7!O#TNZ2X&a2DydG_DZ7uwn#`e!9Jl zKzQ@bus}yN*syxJ0Y%ngVi7a?Vp$3hX)e+319I6Z45)uzy>O50mE32NP{8sD)KY>C zdye1mHSL^%ljx(?@o_w_vC49;JtocK=H3hKMsizV$!I$~bw99gblVmuHmVnB z6|@t`0+l^39@U6GhI`?@FUN1Wc)z-V3A3E#$9s3_d*O`NeNOA;R&PW+RX=ZG(U_eh zCyVZS`%a#?n_m=2Or}MTS1_A2S1M=!MTX^HLcT3lHn}NC2YdQGrT5)f2c5nR1|X|` zL&cS{vpO?NNoQv&gH?n;|49|P&snLt4NN`znbxK!^QOE-$`qLm7+H+-<<7EkG}Ft| zsI#~xlDQQ*4@5)azFsV>KC8^&Bfmtp1rLhK^=})Ht)x z#ihkkWOFT)(lPz^tdU?B(EwJA!Y#LZOm)Po|MBg`ZPN{c1_)~ZARP<`)(!~aD`)_e zhDO}XoLD!f1x8O|^t$x8f8F2rEFIpUteO%I0T?FKmGknLTP7O0(DqoVvZ!PMSx_iL z#h}FM;Dk(|%y>OJ?>hO61G*CELHxZ#$iqBQW+uN#IdGAkdr6DsZ{qoDbfwAh=Nw}j zTai1fV#!Llbm%+EA@<=Pt@7hNN+kv1+tikH_d-lh%JVU-|AxtH6<*;WrO(%Hx&0)4 zeD@J82spD=nJ8G=RZUOBsIvq^q3S{US_z7AsL;CYRwHpNJ_1E7=>)3jR@>sV!K#M6 z$HB83QuBDAp#v!l;_v&l*hlD&@#BXA$2Xe##1x&>v^Fsa{A zvNNE|1~EusojX|iGxJ+Tx$DHMOXKj42vz|XM(u=zm1w+ldgcxg@qMk_^=^9L!Na`H z4|!JKYSJC%wLinYwkijMgBfxmkW~)Bg9L7M)^iEf-<=+OSu6=7o(Db)nX_tO(TI&!0>>h&MVeHka@wqy!zC zwL6~SC~PB{5R6Wim^?x09HdN0OC}wU4gtw(7TPsDj%s74i-(6qgWo+BDp%sStLMCC zfY4w)B!u&VunU<@1}k{C;Ua`e6IP#;aloxFu!%HT(IP-8bn|Ya`YJ?< zLup#|L|)j;oLE6stEE2(85T1327+{a03smkiPyyL^_yM-V5qZhTMH@Ww>^Z=)VJ`RM~!&iJB^gKYuL6UZ$VhZTonjSOxs`BA3X2*4!0*^tgww;{{F;0tUuW$DEAqc&)b(wfc`STuij212QDwDpDFZe_GJ;l9}w%vf!a0-@_Q$z}}9=tRShgQ)rhyzE7R5wy#fXhBtmOlO1Foi&@!O&F*)D zbg2tdq!Kqfd+r;?f3X*pTdvsr)YYq_Xv0UIgiTimftc5JGgc@$Yfogs)s=H4#+`@u z*`rmUL#>dEr4Z;qGZlcY6dDH68p7Tl;?Uo7+kI!4^!oS-ww=1Y#0;#G?P}5e=SnYi zjY&;xt|%wV1b-4u>5wn3HWT~ciXNA;OIOiPepzf6_*(*UvJWOon1Fo;LG}4pI80{w$%BoMnDraz{*WMy1O`_NY<&uLcCy{{ zTiF>We_tw`iWO}TBnT4c{!!bCPn^Ak3|vm1*Tf+H+NQ%+?kNK{1zYKae4*Q0qa>Z1 zPA>38TYgkBS_uRI(UCJ?ZU^eMusHFVaE z->o?o7<4JhmK}ASUUpeULxyZyE?&J(NFzLBq4e?PE*@N&Hk^~8t!N}X-q#P^k^NlG zaZX+&Gpil{4NO&898E>VQu7qKClPfOyS5nqroHqcu5jm(?lRpmAlgeGg%^(s+=2%U8jt8!?0=fZODgEdKJUL}7c*~(`0-=Dq>bZki zy@*%UyxoggyQpzIx5g>AZ@P0?%!(Hk#8d@#Qgd{VJ7uIUk8xEjoGjZMiSJHE6G~@_nnOH(SbjpX4lK2F#9fL%8VY zLczDmR@}^EMg`CFpm0Jd|8prj+%I?Bxag&EGPyhL-RZs{8k)!mVSL zPej9@OhNjl<3Sjd22T164I07=*=4l>xu$)lG2`^%SJcIfoC0GhtIY?sFEf=3lJR;USOzRR~yLXS%le0$%pt90x z`v$`@-Ls3XcpjC<$+NFhS@4J~eMVj~#_v+C=G)nlR*q#@CD5v4wd$4vxULf9U`E9U zc=duTl@g6RNM)7@K8v4avo~a(3RrNVppkNU^rCYUJsUnu#|WJ!(&X#*Y`^!W5yFLh zpI8jUxw8men4^t8IJ&CuYsmeeXRjp4FZca24l{5oZ#%GD{{W6>fTHCpdJ17f_T?h7 zKUK%WV+y?)eV8W6>$F?m#d%}!jn0{Dzi7zL5U^T?A3<_W`YkxYDJ<^Vjd^C5lB)_j zxsRTb&B>gQQhPJvuWk*!tZX6D_Z%A05Y`v2e#8Oj>2kVb&y_1wvQL#Wj-02rGG=^enz%=y83Nf}j~9Rc;y)cW}K4%#~5Y12w`I1*O_qPRqFIE*K8?=xwI;+Yja zK%}zKrRqS=m12Xzf`-kmJ9I8Nja{aDAHUh>FuOblu3}PtBBl+q!m!LW;W3Cd2FgA{ zE6m=ckUg$AOSHQCI@I5qFio$}fP-VO?3Jmpr?$l*_?hLa+>^HvcmPncUfIyfoDFl;X`!1x_o1yEh*al#BISBHmxarnA+c^TuKfa( z%!Dkrpq=*18skM&nMnDsQi$28|UMSsruDvP+jC*S$SwV49RpZ3is``5s zt@{R~Ka+=;LNvF($1zy&RhTqY)D`Lfzy`h<1YyY1h{+eV{-SGr)V0HqBHVU-%9Fv? zqU#<{>NOIfqo8y}HYyt|>Xki?Iqt4UqT6od>fY)Zrd?3VB_}CEg)ja(lYE!)qJxQZ^Hil+NRXLrUCD#>Iz*?2AWzIMqiN>ydL$fVFr7?x6qy75r zWgqRE%394`Wvi5*G^B4#8t?r|m-Ti-nhb^_GYyEehiSAgWzE-n_HDVHojC8Oa4cD{ zH4WL?KNP`Av%MC4gyCX(M#_TSkk-wQ5$jM$2b6Sz(Ia+>> z45+0%!q~6=@K9=~d1ITRc-_;`#>VD#angTea6kLY$KeIAZj?ftMX}=o8-U&YSTi3_ zMOoQP;O}m8xS`?UIn#DEBOLX401*c3J&|)WrEmWtpND#AXlU)mUMjSVfrdsCB7oYW z{PwzPkWvUh*kRj=R3S=D32tOilKS(3Ynvkaw{?cvv1jEwGO7P9l-~3$s zb`w!iQ4ue`6I-5xF-U3L7!?$R%T7;${=F}u*ErwRxN%vAmKE_3dQb29PdAYd*KS`wMMdERnyPv8W<4ap#zF%k zm|u{YSLm<_w0rjwe=_E|sQgImvK*M>f4t>wdYiVaWlkFRy(GqTC-Bb}emQRx1rtwM z-N{LI$6{kA0$s}S?)I9*)c2|!Z-AU{9VA<9zZ{Nle07y!$+<)_GP*#YM8ROzDB9Mv zG*DEvhYx0IJU|HUaNM5F&jd43bqKy?t>lWcmy{s5!iicZoh=s=+{C?dz8$twzY2y5 z2i_ht83E){$VX7gMr(1^pdT0o0Y?s-wqrKtG5mb)dJpx(DKqw;D_=Jo>jX}%>qlT= zVS%B4ME~JQU`UY5)G$}JJg>kfyr(~jpGT`59!g(B#h&E zoqPE2PWpb;XQJE^g~wKLWwU}4GmM`kyr8?3;E_ux5F&-H_R@VlNJGolxmY zuYQ9jwDyzF8=Fm?-=Wd$K67>S-AQE*C=o&=csf$PsqUMMfbaSZtS(!%(oP-ISH%(($!w3<(3ZrrK0Q3Um-qZk=aK!^>`l)m za#fJkcJ%h$u7JfQ)-+)?X+Nb}X#LZ%!*1B&GtX^Tu`%{L+x7snMUI$3+CVm>F#tJy`Yp{du;!>`})(Zt714o+VlZBA7v+dr`DFPh<74t;M#PvzHR+u_PLcCuZa zHY3Xkyee`OroKf6)0fX?n#Vfa`CC}P^&LbP9a2tHRMyh6T>Fo7uO7J&HjDY1&TaTH zv#zrjrZD6=sI+qhAME`3p&HQfA9}SKd!hjhou-N!DGHGb?wJJXO0k%QMkgc zobQ10c(9eu&cC`@5&v8&A82)&-i9t&pXn|U4Su^jk$1i`?kSRG-XDVo-5UNho+Ej; zUtWEgIa;yzoKO)&^N%Ufn<(+xJi}vDZlIK4>%+)hcgSDq8(%$<(U-G6aI`Wyi#y;_ zemqa9ozir%9GY`m!^u%xC+9bAMsjzw|EN`g7P^9%&Vb$3@f|2SYLw#IWQqM=$*WCc zPjy&J!smE`F!5R){gkz)DY$*Muw6~!cRSr0W6n#Lw-bS#R82Nr^bq4^%=SXpZi~X& zvL4~wW*Ku%Gu`6xj*ts1&gpjNlQE_%PLwh`ZM(x&-e&Pj2`<(ZcO0vwp5gu^B8`{1Vo(IJEPUrp5IOW{8`CBEJ2R1;hhM{RV#Ro#8s^ZLISnpt8zuf!Q#49 zuzW=-VK%fr;8qugmwYvl;feHsTYFpkRr4{gIv=G`N<*Vk#e9410;SK^cf`wCTSEg5={`NHbw;k>uRKwSM*&BG{{#%P~Ebf)hKczuz@ zF#m>k!zhrIwU$vh!D~ySK=~IsN_RDAm?nRg&GCqssBcp|a`Ia0K2@71JE49k@PddV z4U(sV`^Hs$&(#!`RkFR0sKxv8s;OFBzpZ`q>^SdE+h80v`Ft~Et8n|r%Jf+?N{;$E z_i?3>I!AN9j{7wIuR+XPT@mW{&thh)Pgi7e{>16N(I)gDwD7{S^)I^Yb}+9rpr96p zmG^{U3I)U9^KI{3(5&-8G>OtdObolW#H>GMD z>f^w2t3h1XPM5$|-}=!+{R$ zpC-4gOxK*$9a0;Y605V%S1ho{+8bb|z8>HD^DCousYLGT9wWy^=zX@TuQ5@2X*{f~ zeHefXEGh+&`KE!|+w!XHDi|{PE+*@&FnPf2ib*WmBttk52=o1l418Mc(`%}(O7vulnpT(OrY%QMD!pihVSEAw*yQy3FNoLBZVQ^ z5*Fd+y#a4E35492C%~@t{{E;<_}TCgK>{uDVyTJ*>gVumTA%!*f?K`qGBpz)r&k1M zK(d4337n4_^_5-idw(N~WR1-vg<4lFT@HvD1JFACa$PUEpk?1c;ku0c#29`p`IvIG z#Zu)a&%9`YjyERivE%jLI@j|Bqhkr8FxjS~i9DI`5CMX)F7}=uogaJ_)QRoa>vTaS z?MKUxSzaV!UVN0#U=dH>#QNw+NkMyFFYw&w+|;zNg~_CpZbw~0wn1GEQ;^f=Vi8~9 z)2uizahpWi^}>oAMIDZowXC9?2e$kINOmB}n*T7pbW_#oNfeDe29QgzEHYO@n}lXR z$!hgj^#!1{R_nKea+kcTbvN~BA)unHQjR%E?FmFHp@SqNO_QyR02Zgc_CWtyAGN$m z5uVzV4wiAUw|JPVd(^X5Z#F|&AvXBV#A_fXdT6e)&CK3|Rl$`2Ypy4yI2 zxvo8>ndprB$&9?6?P6w$SgfWHR9vJ%K&XmZN zhg?$LJEe&{<6(7lfMBW2{d*~R5o5GARlM3~|C($bHzHMYuw?q~@~7*#>SGUoOKm!a z)>lT!cmRYA8!+=9ry^s9P#Lt)t)c-xNAzmXpy&mgX$46g#}Co+2T9FkFAVspe;>c{ zP1Punf0ZqET@WXcE*XgWJ(%P_W{I(o1qqD)@{>3{hUX~*n^BYBYcev*@VJ*})?#wY z@6|dzjE8DrR%_Q|U)m+-4?S>q?S7*!uj3F|q=NfnrQDkFf(h|$?_Q0MdwI$% z3Enjwb6w$1M^D!rEhv~|O$Ds7dybgsSi^G!t|sf*0|T}%1D&3)wbQN&S9B$`9iCIy z7gi4N*JpQDBqf}mOTyCI%tqA$pHc99Z9K^#bv{HmUM6bm^IA@P#8;!3Q!W7p(AXK{ zI(>{?)~@(qURJKht^94(Fwa(R*@Edm10zl|n!@W{`#Vu#xFYmh9URN}4l7=}PD(t> zO@&G|MYvR8W=N(7GUNPigN2plIhWqWb}!6Hq=AE9jd39TTHx|@{>$aJ0?7{NyY>r( z0EA61zkm2VEBF3Fom!_-b$99qC$F2eXhIon{ZhV{-2{P?r`O(MY)VM`F=o-s{L#s;e*Aky~^BLqbKasG$12R@{a!(W^QWRo-lyUB<+Rr}8B=(3kr zQICKhE4>PA*fKt*NH{%7KiSY;L#Jv#ACk6~2k+?@0&NmKw!0#K#g_4jKkv@dVjRu* zLnVJ`E;&I+%zbaNv&e{d!W~!jm2%HKzEF8IEH#R%MMg|xUe+v2gMQ1T{NxO1<8+_? zP_4}D*I&DWAV;HNf`~jgRb3cN+~6;>n>-_CD&VYqm6EBO)(NWI$?&88=6Q2q%G(0G zP(lOFIw5TkerIbn#FtkJ0`@}A?k*$Scx{>QR7A|3+o8y+-wO!UG~^Od?$psED({;E zX~SFnrZtyKR-(nQp<3`jtTwg(SI+9`P?80byOYK6BVVzcmCi5irOL;M%N$RxqABy1 z0cA>t{F_YC_5uL#jpHd0MV(xC7L*69d%ud4XhvKShchhsX8Y?f_a1;z1@{{MT!;b8 z@UIZWx#Z1i)acebH*%hQ*OV$&5D+oPI_U8I3sUZ(91g%YJ#{}cW+q?7N4#95zSX5) z;O0^y+!(P{!w@G zf|T8cBoCYC=Fol8M2~vE{E*TC$OSzcIH!xzVP$>)_B^PkT{@?0stjbLaTcE-PI9>L z)oJyH-hA0<#Y9QIiPoy&Nv?~aAN-~r_Vu?G%lRn3p|>{~RQR0E-UGd+kxZm;S@b|q z=h+Vtw(zD)_v7@En3)C~!pRQ<**T<9fPA!b?**A3_2lXMkaoQD9N)cV_*qG35_R+B zZSz-8rVL*ZPp)>PGCTXEwfNz$$y2)3%{SIf%bDMZp}?fg-a&rJl)|r%--A97c1qL) zPA@mDpDmxba%DT8o~VA^-y^A{c>Z#t*7o?iYvEgHr}U<1R6wG}CXHBgGVXzZ^&5oR z)Fn)H^hZt6Q*$p_J@2{88Tv|(!xU1Fo1bfDY@YtPeiLra2U>#V$7Io9eXk2FNUi1GQaS3XN=_PmFWa)M-?pRN5?qfQVKV|oOcE=EBk92+h;`+86 z<>Ktx#Lm3v;BDw*GDE*|PJcYsSZ#E5>r{jeKsBr+Z;y{Yl<|MpN(f|OH)R$KfFH%Z zk{tFUnVGxDbk*!c(ePW%)>Y1b`RNq+j@_PT_qP6*ziDjsKj|{?wxiQp@W*P#6r+AcjLBK9^k_Ktm=u^Tu-YWB^0Q!Mg$!azBjh9yv*6|N%AZ~spS{Ka##Jbup$D8T& zpt{qzJz!@_%>z~IF*UM-O1D2(4eSjqeM&+hYuzx#-(H@x1-Jl&vyrj zrr!w?{1(42z$BJ#cIM4QDZz72&g&;r{7#rj_*Kzm?yK-3<)U-q0i~n%>Pb`i*&pm? z%&)@cOE`56v{SfeI~z|q2_@L=NxBqDM7$qn%)zkCDz^AwM2mR_NcDmvdOW zIpDXI^=n*i7(!iCwhYH=j?|QTzB;rGP`x4gXfN(ELL~`b!VCieMt9w0QkiAshC}yJ zI^Wx6SNySMz03}CgxSFEWuC}@?5#ct?jP6~|8+UZT`C>w$7?#vKcT$_HzTS!_Zc}4 zz>Q1Y6ipKtxUzmMmCfjNAslTdFwGxX+ND;1lli5qo)nNJyr$o|_p#4X>V5hym1`K| zCUTzRymV9AvovjOvF@!duR~;#`NEslJr#RSss<^8J6t2aS4Doc5X}mWZPs|gxl6>^ zt^e8hO`IJEh?&XfPlKVfgx}?G46#$k6vyf5DdmG_13Pc!0HAx~;woQw0An)NkJV!sj3Wrd#AaOHW|1y5OC;;JOa z>J~ad)(nRUG{T0AGxy}jn6Y=6%F7fEncGeV5f7yXj%9uL4%cuTTtam1aqN`lY|oC< zyjHPGU&1}MRKHe#J!8A9uC>7z`^m@H z+#-Hsnv2BA!1|$G&(ty5o6~B9slyY>Sz5YW~&1JgmHvti@rnM zta}6^(_TqOf7^+*-Rx)-x!ug5uHXt5*m;@Zp<{S3o5WXlw!1Vgf#hgHUhAqI?pR%T zXSqJ-UMBP8y!|zn-o&?*<+)k7b=A?tZ#5VwA=!52E-o{wh1X{NJNzI(;_D^yPCb-Y zB-4LmkHhcC^iu;*zbdguTSvtR!tkJ6%?M+mW6TQej;|Qc{b|umI=>y0T6RSsIab9w zmO+Ql#qMN5N5JmNx;_Jt4~B^4-TOi*^~G}CLXmHC_qH;GMkG7`Vt07#&T%0B!LVtk zJ962>N-6DubP|f!%sFI!VDy%nHeke}fMoRMVmG}B*5YWU6~e;Bi6?xp;ps$S{V0sWu*Mqgw>D&RbFA^-vmnB6}Th`Kh71nz!Ip`=r;Q!cN<$t#dVx!&NgjImd#gV*eS zG5X7(-_j!!?!B}yXy?%LwFLoV(9#IF2_Nl4%G%`tF;Xn?D zQ{UxPxceD3pIfJ*0e(NbD6!}WhTz{W@9;Z><+`y#*xO74gtx;rF3f|+^ zI9-D$)K^QXnub#+c}J+LEi@Z9QXy_00Y}B^cu7GWh*wv_2Re-qj4{mdhPg&ZjBPlX z0)5W`Id%J(n#jj8DYD%Q?k?LN)l}T8Qd^xB^>Fr!>bc5SjdUBL6E`ZP{#i9)M}{Mj@T+zXRgg-~`9zq%s5pbo$DTZQA#_yFDUp(r&~ z%MnA&b4!%iT{I(RA&02h!rrGoLF-s?AAQY^Ifj;`9OrM1=79mf?=C5C-*0e{h>KTc z#X2qQZE_yg!8c>hT)Jxl0$aET=k?lar~64oYZvVWGDf%EFa)jPjZRtPgufeX{Kx1* znh&bl+L<^NK9cjl{f<@5{2=ooT4b{9HzzEfe!bC|4N09sC2mc5yhq0$-Ed*Pt4VxS z67>p3B?U%deK{Uul2n2AnlAC>7-#_ZO-zQBgx~05abp}WTXYn=jDe@Bqj_~94WYT( z?eOR)PyEm`V^h@5e5PXH0Jdy{#K9L)Cft`XPl+FT$DUxdC4o#e6sv1V7?ufS;qm8T z19Sl7$DZ!GCvs7Ic?pNF$#E@R`{^WSiyADJ09g2f$XzpDk|(pc_O_6>-;vsM^uF0p zfzSU4#s4$#K`?v1%@{p-n^}=msDf2(p z{S0VU+uGVv0TPP_9vjBKBhj7{`DGIP96%KuBJyhtjEGpG?AK|B(%K|logO#r2W-z? zy`m(O>zrPPm=R)=tolv2bS%k{Z%p!hg^*CVS>H0zLsskzl|L3vTDjNdMNkNpln3#A z2)n?MA`pK!lFNdd4Bh`$>AQ;CZS|~niT{^Pz|rH{6=MT0(raj74OD`!S_G}W)9K47BQAqa8b2i_2Rz2nVHWa zr6}?AA7aD+Agqk&L{)H!s2t9X|nW5|CE&C|c9AlH6&xT&K! zm_mi#qHg5&_LL-G!SngJRQ{+<$H9rlCC#;BU_Ew{`6hyIZG9I>M(%qTczfO&AmvY@ zc0PN!|D|Y=sUkZ)P~VnGc>QJK4|A}T)HEqmNua{Yedd2X!m{cAk7{~-jN&0Bt+aP2(_eVrXzZwE zbZo4LNY+09osuj7jR-SaIJ&%17|`PX0crkwl^J-*0yz!&d)kU?dO)4#Ul`JV=$^Z!g#yUH|AJfn zq;_NIP{_X`^#4LwS@%VybaasA?a_=35uX3fav!9T?%ge5Jbt#&fc-a3wKU)p&%Z&l zepPg=n~WD3B9#C0G_Dr(e^@0I)i|ln9oig^je%-h=aZh)&Sy8evoP*s9iPWOE2R&^tljg>{>~M_~ZB4nly7r#D zTl=FdlG{1(-qFipA)Z7xB|SWE#gvN7Wf4;pY3%aA z0_(4ZsSrU2)Nv-BI@kZ`>b%$-IsbM4uEtS9Er*PxfolrETZoM6N@$j(-QEg2p|;I& zY;{f-(!=NO+z`>!jUk5i*GPx53RqZ>Am$ezpH5a94D{&_3(Y1JRd==9bQ?G25bw04 zoZlb*ulrvOOS=3DGkrh(anpBzv{5BWoUY8`B|H6>*&izXc-{xYlnP(2B9%-pkD8)& zE7r29CHG;TE4QD1D^{$a2B#$ljF#?B@N)vXYU{?euU5SKY$maQlyKd^n@hyHBg>K7 zM)2-svyf^gC z;pljttts$qhVH%Pe6LCu(%V;v3Qru{OpXOnlr`Y*9LEt){zInbfzU3i7q(gq~+wn6~ zd}b5pO>;FhNrwURIRCV5KwZwa(|==opz{O4{Ho{c>Pj_<3-?y^+*?VL&ePHvs(DGi zgKyE9=fz!hQ=4|rSv~iLoBYWFW?ier#EZH#j7$y&Uk;!g%5{->l`7)DxpP*}`;d2k za0eu~57H=F9lX5yNzzo~{Iw>tVW^9dKo5_0`0;=vwZ_S%WVW7LO_lK9T3AkZf;0L{ ztr-7~2mqFlM;}a0yP9vFYBgWhH?da*I8Bi$3G9k&oaJqHuE+a+lXI{=J=lwlpNF!Dzh1X{aJ7+=*Qn_>WdcngxRCRXYZ>hX6u|xVq#f)1IWBB`@NF#39Ae1D*Om> zj+zKB7pvJ%yKMQ%TF zs3O(Ua47G#!FF0MHFS}VPA%ZW`fJv}`bVA&bK9P=gyw7%uV$YgAr&Rpxe7VK)&50}Bp)EM#&8pA)dgrZa0y1)Ie zIqLt6Id7HwK+QVX>=8CL_Iv+u%L_d2GVQh!l{JIgobuM03tzgA9uLMT0&Nm~J=ydH zVRL~gV}Jf+xGs@ncD8OUJ0XvwHQr|}o80Y=*Ne@Eq*i-Si#m4Cj{AA+aU4h@b{v}8 zpImKGKIlC_Fs73dOf#Lu1fo!@a0#mQOx7mEiryCGDrO|f_YJ)w+b* z2<%)*HKe5sMF`jnt79MI-j{YyQ3g7$nCiLM&*$Syj-iJCYzKUa=wi;sH2MgF~E(+-#Bq>1c>aN=QaYcsuv?By}>o)P~^5XJLZ1J|g}{ zYBuW&zQSh!6f34?S8-kRuez0f+u>WI=5_4Rg$2E8tNr#=zCW*DOhxW@n=a+{|Bl>E zj(n2Gc!vxA52K{!co>yj;}r;nvA?J?Km0?QJ|W&?tr2G`Z1r!U+>57nQw|Nx3jD@? z_1E(1-5bx%1pDyEl(xT;x&OZ5Y(F?S_$mwIuWO`_Ms8AEi?pVhLjKa@e%pLWm&do1 z_pr-<`qpkg_Ws|XAfIMlVJxzwzp}}GQBz$#J|}1WN2%>w9v+@bgGP~~hUs(>+P?e*JNa%qR}mE-c)N>A9@tE{L0nT)6ZGqYW&w2t#h6~e0%G6|MudUP~jIFCDu?dGm`n>FByuy ze|SNeUQ9mruuxXnzervT;wLob^6W1*zD2V=jVU|~k{ z%uS4#3RnN@Z0!CqJPTMtaQK?B$;JtC5WkHUqwqU3}P$DqJ)OCO&b3a557plQv=uE}vVRySW2;{gWl?n=vf3>jZ`Aj%u?+RY2U zMZO;wzgl@eKuIBBZ@q**Zz?C(C%ltc?~m|6z15j3@rdl8FdJZS*LcnRd!~;TD@^MJ zUvnra9|?-*wgJ7ZGOS5ge{2jdW*bXgd0LBPsa8wg-rIPa zdmTX)Bxugt?=8NZ4`CX&nH#dJ?(kTP7=1&OeX->Q02?s;hYdw4pEzHAp23ik?d$6U z)U~u^Wg`}5Sl=?|eei;lA-d*;n<_POUbq{mYCH@6>EG;yn7pm)<3d)NXY7{NKSg%- zblqq#){};k|H~hrsdcJdW)n>r_Y7${W-<80uT`qp?QN8iAhSlKXm2B?d68A@9piq%Bp(Oufo-VPKrbN zsDJNG=J8!zz?;I6&pZV>n9Phtw({jPf=+9<+Zj&x@h=><-X#77)pSMdzq_(cyu7^EUta3hzU_-5X8-asjgXL# z*W+*@jn8V|;l8ugF;iSorD@ZVdYb#9R$bt5>qXi%UJ{;GLPm>CU$u%3Oi0U*Zj2Q( z;gM|@>ae9z;X2_c@b+f74$o%MqVp=%a9yPMF4~TboF($2!5?usGBUF4)YW0y6|k|f zfxNkByO=Yao|?L!a>Lxt`?&+spy?HYyr}iZuMeempHMf5{t@#OW?Oe$gH4_8FS;>B z<4Ze54WxqODB)!7=kMD|Sn0$}iig@qUUhMqv*k)iY$29A_Yc-(EgKxH*b^?*SQ|M&S@~7Bz{tIO}t^}*?IP?5v;O>rj z)onpf2gO{Kahu1{&1k8wt6xsJQv2Cf&S@oGv60t}FRa6J`jw!&&HP#ad*p?RVC(@k zl_hMx@@Nq$x@VRBnO9ka&D8I-&o;c&{M4i^VES^Tpy*;WmK?@Emj6I>juW}Jvt{@= zb>`Q*BKDjk$;%_kV?&><$r<-n14k86J-uFLD{_-*40Z^=jaFlo=zjMn!HX_C4G-}| z<)YHNtLpi{QQP0(oOHB@(9K0F34XpsV>{D(-vv zudVX(^Zow<_}{;XhVM#mb#r&@O}qUuj``~36yqJI#J_6+ib%Cuk1Gv7;rnfknN8xI z*chd?I^PsK=`2duM~gUyu#^$7uY|11b|X zyMO67t+xH}*xsdTJ`bwwF#Q7`tY6L~?b5lMkiidPLB|r9v$QPBB(8UA_w?>*@$aqE zS1a!B7A5@joB2Ta`#9rS_%Lk^{=io^W;m(D2E!7 zjC{Uyk&ko59I&WvR#DYIxlA@O!}AX7Kig-&QyyQS_}#ynD6;;3M;!QQfR;guHd@Q| z=M(Y+r~KB?6<~=_Hk?A`rU-ukj+j(=f)*d#f-OB^X&u&vkc<}{7|Y3$qO^9{2YZD0S~>b&+lJ5P!+LQ&9P z2lTsB?#k%WCVUvPU)aT?O4-S?H*--iXR?fJg)!Ah{A8SBoRgK)2R^A#UtiyKheEVf z3tiQ(YqGOt3Emd1-`8HwSDSXVRX?kHx7k^L!)W3qKlRUo?-l2)1>Pa421;B{JK^xu zlz}Oo;;*QIa@Q|-v6Zet*k08d11LX4kc|_i5VHN-X%PjrkL|=EJ~j1|6}$v)0+MtS8o{=N7QT$50C&cB#;o?f?IHx0158y z?iSo7!GgQHyEC{2ch`Y|1h-*=4$j+oo_oJ_*Vl_RKW4g{Bi(g&Rqfj6E+%Sbsq3*O z1C?uCu+@qUzm##yUqQ~>R_?yF4@ZW3&3XSv>nr&FYxRdJwFRnXZT9M}`0d{U~u*6N!3Eu^Q3MHSf&ZtTFdze~73R&z4r&|_M{h{BpuE(1u1zQXN z!~YYT@*hn+=8#`5^^?(RlN|skrZLelNd(+abTcNdW@T6=a)e1i7o_5e@$vQEh!c8# z{#Tg9rIsr~9hM4%*x?FNR;!{(+otB`ro`3>Y4{t}c6-;732&&6V#@cYaVki>xJr zg*dg12l$76%^G0QXm=wnwN0C6FLR|;B^iTg5UtSFsi7m6<_F^QUSa4#8o%wr<>ba# z-?kyX=`n$ZE1v{i;k(WocUQ^ZS%1*mueg3m`0z$|jQ}+(Bfl%AE1w`;{>Aiqnr$Am*X)!uKNhgv0som>Pv+vQiG4p+Cu0SfBvu zm}6 zOy-yfZ!s3iOrZ^|<#x@`f72+J$)lv;PeVl&Ma1hgnaTUlRswMHk6_*lQ2tyYevSMQ zjCH(BS#lg#`HQ`|wYk2eDB^^ef|%DEkuv0Vusn+z-BH>3B`%9^AOw^|A`k7VVQh1b z+4f*?Qf+iw7j&j1xxTHCc`K&$&h(fW_5olDrumbxZy8FNF6q4tc7y&dH*9zv6XYU$;bGPsqJZixpQ7gj>(!KF3R|XMl4{vic)=XMf+?1G ziv9gJdVe_luBVLz$5ndpdJm>1_m$gIAWinNJ7ln7^x0JRgt%{3$R^g&yRj@#=*X ztU&xS+&@1k*J+6cb7I+lWhkQhh?q%ax1=b^b=Cxfp1+OXRl!kwFMH(lPn$Ge0S*IaLzn`>^K-mpfFg@@R*5Nm5C$VJNlR!zi$N;!;}emW6clCx@?%&yU~l+xxZ+wuKYyJYLoC3msh_=W|avkRq$P9ZmKrIhv2Ztam#R615XJ zk=kk1!uO6=A9UkqDoe_NQ)0rrC;A#5AzF$DAxq5NM!(VXei>%fc6BsCdvl>Ywep0>u~pCKn=iPIGtqFEI?W%$!%cjN26zf<|H4CNZ*hwIa{mo-VmmcqwU$=hVGmoa@qE--Vj9G=miM< z+k4`*IQ=3oRD!^dL!sUu#orSRj}JEK8INA=KyZv1u3&tM_$g}*39W=`+vdgQ+rf?S zYP7BoGnbVws(K4%B*t>fFMp0ZU$@1ST6ebZdXvszpA)B(0SGRO_W&>pe7_|(vZzrklErC=J+++fH^xeA{#D7xQ^J+1>6F`|e#`&XSd%-)R|4rFuMhKRm)G zzXN5n#5Z?M=DQzY?d}ewRso%`0GYwDCL=%8+NY^?-%w6hFcQcgK7rv4rxOzq$9?zB zSg%FIju>3sCR|lv4TV73z*P`!;EN`0n#~?9G<&7QKd4_+n?xiYA zr>7$=yu7@7YnM(Tiw{{;Qr;K)k8|@hF(d@(E3Mk614Y$y<+f`OXFjx4_spxd^R$w{ z)8Yf-4XOj{QK>rZu@|?B9T=nCyo9J|XenNb;qC3-va*rdRgYUS!W=c|!J;}kI-uXD z9_eO3I55%42L}g>gyhdmxT2QntmV&s{qXWwb-7O_ej>smLzi1)j- z&|ra3+0Q24{lz$HC^~OT+gRnaz7)e$XI>7)Abop2l`mLcJRz&EFLR}HeN>n{Napv= z@TNm}PB1+~AZF>#IAjSRDQtIeK--w}ZhqgGplkr;wOnbkTu$4P;rYod1|%Oov>5e; zNW_ptkqVQ5+~DiJ=erY}Hj9!U%h=C!+a z)VcG&>zNW69-GhVj@tAT z{)!v35XT4GkNUa@H7~(ehi(oQZmqe-&)+d%01h-Mh!#agVyhjGg}UjDgE6_wU$^HV zMIoT*c{KeaLVcHR$yscvlJrpPUP<|y$N0}YQ@%Nq2g1HK-a~e zJ`@+BH_PDW+rLF~FDEQu&$hqn;LWExRkPad-z}Pl6(){>fe}M0%uGxBGdkMu=FIG9 zu?p}ufwG>=l$4aj#O>d|Ydz1+QBY7wVgQsWoF$cH_Yqd9If`eYp^)XQzT8%~>1Ms^ z%HKvaeu5`_dtX0E{Sk3i?iUA;BVNySU!D)IIO-GI>3^j`tAg@DBt(#6f9OcKDI44` zK)*{Mf$X*qt)BIm-Zy(J->=I5A_-r`TPbjValYZPmUWkp+g%;n#?rLH$6`TzgS6n z6F4zcd_`)@gzL+0~YWA~2yDQ=v8TGreb%n0)g-1R$~-hSFK`IG#LI%Wfm(X}gc zQr-OzyiSt8$_X2ERM(J`s4!igWKCgOt%7{~+^!Rd8FCf>$KJpF`DI|mSDZ@E&-%Ak zN&Ig6NY_I+K%lYZiMbCTkvK1>8;y+t&F9PJ{T-Hk4t*Vp5;vDQp$bfnKJQf%b&~6X z-|#o&DoQA0=(S(3>!g^@)*t3Q-hxGX+*cu ze&UkrPMonjTF0;A5R*-fl)0lIlKARYzk>`?L~b8s27x|4OK4RTQ^^g#B8=5)vQF<5;H`lpwUzz&b5!)0vT*B9JUb=0`6`~pd5~n8Z@eIX zZbf>Ey&;rZf$v67!bCdD=iA}W`4J^&rqM)^(=L@=ufB{2#>4g(uk2UAHi_<(hv|(H zJfPAB8JG}K$K5;Pi?31bh9=2HjfX;hpZ_NL$uPQ+67JpRUW^QXgpZ~RWt{1-w;IaP z=yPXapB|M=!nwwO7gSD<>a%BTcebLE@OZ=c(Kv)hMHh>cw@o9eh#7->Is}wPZ01pw zhR@n*9%XM`tPI=*UxH`_X%qxO6iBf{_d<@t!dy)Q?KDSB2(pLfC)U50OIT8yISE6$ zu(k(_z0B^fZ=h3kY%ZtuUY@5$TMq7wM+YKidiuh4>bTrJVopcd6a8<5Ut2Pcx7Rmq zbpMiQ_8VpKHN7sfX}fwi)5ba>gJ(bEDNgO{Vy#p*m$RuaC=`>Z!O3iu)QO|ZEdUSQ zkT)+$uel@V`gSo|qidp(=nRwo=x7n+?YbfK`(S?|CHuAgw)$gUfK$vfBlcJ==YOqHx2_>fyp%v2|P3u$m^s%j5U$1i@|IoIjSS$io6Y zfkPMxvJgkr87uS)^{@A`op-fh1ZBQiSIn1x$v7P@w}+^kuETM47tETcpQXcQ{se0>L7Jz_ zly7hHKkTJEBO0puvskPf@9Ff2Ct(u$tZ^btw=RwI3Q$3-T5+linw@(U3nl%=VR$;4 z&9%UtzWw)4UtC<=*RNm4l9|p=Pw|EQIsgp1Th-IklbMB>>aH)alCf18FybxVu!h=2KrPc;it(+;Cv0A%H(;@?N7k7gUB^$5WQW& z2mm=)l7_GZ|Fi*I_apKf^vVlP}EjbjPgIUwFy4sPAYZZBHVl>W`doV_gD%lCRI# zr>rG@3>h6h#6T{Jcc>S-Dn;CAPpvTGPZ^c^SW}F>Zj{)hin21F>)|udL^|iz`Hi60 z1tDcs%OA_qu*Jp0e#(@LyO9pu-xu2*Ni@`JgP=RohPHGxtNvPgg7N2jbQ^WJKOK_srH#?Tq?olO?O) z>I()Plw^Ucl4^DZq5JuXR{~&wmV~GFH#1jDV5vw4;>F7 zN)_%;qGwb+=bd6X7+0Hd*eg6CWbZUhKZkr!y(2|(lGNvMKeIbRi&a8DICR@vTWZo( z{6i!83+7BS(N^Qc>?%?iS(){kRCp{AJBHi8B37u|pGLiU+}p?ad_^7Q(c*k_xJ5bY z?{LbB(w?tGPUgm(vYsY7GX0(E0rZ<3=2$-5cvAz@{s9dS^g7gDh;@MF67s7h+Q1-n zNnJsU*5p;suGOhfX|#Vr^GogAPPq{j=w+P^4KuNO=M?NuH}jFLs4^l-OQjF2Xrk7$ z-6=bIYH7xhE0X1RCu^HdK>JWiAhCxmu* zYi@R1(4t9#Tlm$1cVEb|;;6zoLWXLmTT(MWt6^ZNdAuEBwRIJjE#P@SIHgW<)bQY( za+sYYMx9_4<8*tq>d@KQ$;8Om^>}LoqGe>vk{)i-%v{vbE_fTEj}C$gZ}Y=7ioQF%* z828t&Vvxu-Q)kb?4XX5ZdK5^IKLx7bhNi1(0m%6UuNBs?@IJ%66Bv~#kB|hb_{*C zyqh)*-jfjDiY*WGu}sRY3e54B9IApbsq05~VpWesl{J?OR57nv?%vF|QOr(Sl$}em zkIe8EDfl-qRdWWMOOBM&jZ2qZWc{`u`Li&0;!`htJv5O6QCTT5PjQDy_q#tvIK8;( z1%l^e=bR}yuN@iu<0z>4IWY*{csp10HMqDWJfRXRBl%kV=lRxJHb zZ8_D~MjyU`tN+$)E>t~kKl25JV=_7HPFIe{o^K`%(}uILvlH^Ul;-7;gA%=Bv$L!3 zYML2>{jOE&_K8vxn0h- z=V1*g_8SUsTTy?ir6C*ytgs>D@hBhx-v?_dWrRlLD*|r#<2m-~>be$pU`)DSil0LKtsX9GapTR*tEBLlM zN-1b5;g1ndFrI6t`I9J|TfIBC4fpq~O1x9z-OO!LNF#E?zP9ND%QofFBc1NB`irth zNbr+VkLgEKdTpUj@AGttl9g&7vLHLd9#myX$+QEx^^Af76Jz6iO-8@R`_|@W1d!j> z)z#&=>-~;`W@~E;7$jp$%hc4=>&<~zfXju37Rp@}%w;{BXW@YN9%N_EJUb&@H4ah8r$Ocg?6Vh=tta?AY`NX&RN9i1K>^RcOHUG;aM_|KVCm(aWX}$Y@^qM7&Qw^m_Dnx|S#A}Xki=k4$sM*?c|5_^x2>Qskz@hd;Wvn zAC62=%9IGXi1?j%t~zBO3w=220=Usq^0ifqGdH>^q2t34ru}yR_NGr$%R1C$7c4Tz zT3idQl=Dhv2Ob(q#nyo4OLjp;6&8AdgDts>8+Z$)^inQp>bzfe01c=1=&x2uk_5Ab z3m_4lv~E*hBVxlWOME9^h60U{Xr)SIyK&&lmZt=|QhLA7@2;7c8k9s9|EWbFp_WI;CE6poom zR6;=TxN~GzV$Yp{qacZ*@s}+m&h0ySY(ZH;38}}^bf7q9MWA6A7dQnGeM?i zT@O23Yw-woaXlZU*F`51>vlP(E}!%}4s1{7{Gd9>J$Wju5W)^b99+*S-#HL6^5XUr z?sMu2wr$;l78B}>2`)~~g$~WD&kJ?D0?~F6_Bn1%d7$5O-+feMZYMrw%0fm+sk1CQ zejmXl2>PFv;Vfi5yWc)nmma)Zw-{0@(5CDB(HRD8(9Id*N% z>5VJuh+KQm~L$IB{%}$6)+#oNToj69hsh#~t9bSv!pg zKIu(?V(O+{3ujLkdd85839NuXeZ16HE)d=cniV3FAt72@OBQbeP)O8v20qn5psdnL zQT4jk)8hlDC$!N@MN=~sh;jhgJ{G;Uk8i^Od;B9X@YTzgYin!r*#f-wYb|U!i|$tM zi7L~+#r~Wf<$9amw?mIBU8Tf|`vpbCDe?7yJM014{Tabba_f8Bb98>icw#A!G`&c| z#JIHP`SH*OVGg2;TZ8Zz>rXC&Hy(NU5gXrglC<3=Di&}_8Km(lTR9)hC$7Q?|Fqj| zAF4XZPZ!kwFBiakyxF$$p)r%VcD|-oHX>7relPL+)SeBdTR4C7UP@da&LV7Iuc;J# zK%eG*2i{qhhGmpDr+?}f{B@tY!(}5V^T~TmLegmV`@q~JY7OKzOf7AkRs}x9M%?vn z_ECiew(PK&&aI;VHZGd--B{zowOpK_LpJ1Q%VI0R?QvJfjeA}?&cxQt!9v3aZ=?>! z<2>}|aVfuv>ELN&SdgKT{t<~!+i<|H(%dF5q#}UL?fhJ-)rG~Ru%ya+s*JrIs_$+| z4x0G$;@#Pj$)68JqJujP3o-QWK3pe4o(pR|n@QcceDTJF$+mlWy1s%rlYt?ecp%X0 z97{u;$?<5o)yY~bKqmu;fn|n-I5;>}e=v&FIz2O*F-Tb#TZ1X==gXGqptct-SwHE* zQH$r3IHpQg_fQ2x5qw+y@0)ZR8#CU#DZ*%jY#76#>MblMb&V>*nh|jxe~`V=`bh|1)Qxtw2}v-g6>k(ty3TMU13?l1_d^@Mr@b zRpBa88aO(8%6!>kyO8*I*W>f&G?p31PkG}%dc9fh7;d$Hl|||&_{g}?%+-wwaT2Z1aFRTvl;gfv&K z4xo+)?sZc%Zq>(}hwWuh(c(zxeMgS2XDn}TLndp$jy`>gGbTmnb+6fJ;x88M^#k~fz+s6F;Z#Bxe$T>rcTDlGleerwPSsL!DzQQq$xCu3e}5?NHPOPH3l`Gn%~T=%_lpA zye%!ugmbpv^R8O8)8brKYqb~*2<1-#gFf-a-*+^L$ zWNHm#f$1P)xVlra?x_qFW^8*x6oItzx64j@c zFse(oM>i+eK_rW*>^F@jX3S$+w+Zr@)8e_3>zAZMlWUGtygC#qg@Qh@*88@0hbt%S z1vYgoL09(n%Uy*4_ zy2T0cu5Xc@gMJu~VP3kZjliE21p1-`M3DHu{qDIqm;*8Z*_oNIK?;DK^E}%INw*pvj^TxvVMk#H5ShBqhed|Tc+A=gmBfz7wK&gV*(RByMkcm9{!owQ4_H3j+x9IqJR+z|0| zI~-3#VbJt6bM=CBzVG;I>vj3zU2ZiO^`}q4x^b#is%JLU@2&G*YBEEI5dO7pD+WtB zJJLIwkttSepx+)%gof{3_q*psla2>&e)e@tK{(Y9`Giy)Iv1vs5-UylQ+QA>ue$Kh zQ=6=|*M~zCUcIjHR|9s6`NYMQ&F!E+usWW`UeYlZ>2ANCn7t8u&}ppx;7FxlFvOZX z!49rdQ1H8wR*!WeKkNqVWUhRd$ItY3{>>agiASyFKJey?8@fLAKx)W|Zrx*lXC$(g z(fU}*3jM?j?tS(Cx)$9cHn{!#uQ4PjN@YFikmUU;YU@7UT7(>~jnKoDWq5TV8 z?1!l70D&`AbA*!GWv+%wiIN?uRG!D7e#q4X6U5O z>)kKDLNTC#=<+{FylfiZXe|5R?Gw({oKevyA+L?Lx=}p`ET8$^N{Rsn0T1wc{4xo- zl8x?2EMykqRKYFc?0-ian2bV`dZO7tb!(Nanwj+B=6q_YEgDvx=9)0#n|?2v&*+0s z>?rwueWt|2FQlFZS1d*u;cksZped^VU9~E4FS$b=$7t_Mkc+3YP>0_GA5hxpmzz** zV*Z>^6?QbCeQ}TiZgg0kh8HY+$5FrV0UH?(MH36-pPrY|+(5jUmKu&ULs9y~gz#%W zwoT8*BZHFlnzhCPNtq5-+RTPa)q3xq2Euk`{rk$ypd0sQ5o||1CUd_v#>8|pJJ2K`zTIv=@i0M_N59vZ zaB7_U_}ZM2G_N{SDqn?XknHck7L12u_LM(5MCXJcB{bd7->xH!gyf@tZ6O*U&-e+r z4g@D|;6ifud{cZ(;Oc&Z8G1?505*&dpR%=}0~Ma|B6nIe{hJZhm9w3(&kyMHr@8Xa z;$Iz#XJKk0!-Rh;hD3Q^fxE%hk_>ogDJR13UO$*A$JTw0aP0OOfWBX!AFCLl*|<-L zEh~nlyKt;@nNOJvGMWw!K58-W-CbXEyt#Y)+o$^p&S5hbd%uv=!t3Rt?{RG8M!w2^ z!LZ?r;zNMA7gSP;5?1UR8XD^BGnvX3#G#h`z-lc1?b}}<3{NAQT5Ge!?C|e^H&f+S z#3`aO4L$Lxz~Nol^30zT5dB3FQOMn?#x1Q06;C}IU+jN*fkZyGj+Ed9H=(23b05w8 z<@H^Q*qpZ=s@-{t+<_6}9dG`ITCAWnEBH*nAa9-oJk4X>fB%je@rt5%EE7$lTYl?p zsYYl7o38t30W;ZnHQt$S2!EpL7p|2_5cP6-D9OY)hnLd|OdJ z%GEnaHrmnoFxInM6(|g~YPT$`hAJ{3?d~?`*)tQ66WZ_W6zM-&iB!D*Y&V!~cLy~T z?ktA~@;q&~Bh~$L{Ab0UrohVX*6=l>!(%e(QW}gd=B6`z#`L8c-zi=E^0GPe= zy$QGMo&$Vtd8A>8+IlnOMb#U*QIZ_GvB9b=4CWQjk{>?`N2#f>Qf&8{d}5}S7#;ao z*?Lx2+b4qLmgcOhb?%1aD1Ci=M!lOIw*~Op)98VWymXSZ#_c zQ2Cqq>V#eRlHG6>acgf9+ESy#%io;oQm_z0+MCr9)h2uFV^o;qo>AA%HqoI80twJ` z$7bgE2`20Rk`t1*pUi5tJArI7c8_2FQOWm_WRN__=sOX?=CH;!KVEM z+RfIZ<}~aQDcCOSX=BMQD~sYZ5T%kN5w5|(y`jSE>4>lH7u5#HL6bj%w0&e@tm0V;% zUlVb8+3C3Tb>|F-uqgM=Z8gw=$gI;;C*Pv;njy6EflP^Wa7Vm_NPeO;eisS+@+wl4 zLdo$mIMe-5yVtw{h}N~a9;vUR0u+>Y5d#GhF{lB;kJn;A^(BDW;D5h}(m8@@e7#v%YDPL`K>wTrjuA_FH@^T&IfqhD4_2c>HQ(%1X*2zu@Z33bW_IiTX-g zvs&}-inW-k8{UdGgg#WCAF8Yq+Mm(K2r)m!ta zXu~`#r~9f;X8sKI$C5>?b#*YL8u=?T^E0E7kmBU9cea9`Pc0kjhb+F5$9?h%Y=(Om zCD21BBj#p3pOwigm#NYx9s0=7;#x0~R9f*x*G1}5SRB0253Nd@N5Scm#s}MFV(L^S zL!WHMQzNZrHrzapVp;MN!;{uFldGj<$myQ_%1D-)XA8@$D(Q@Bs})gq+MBI%Q7%F- zmYxvj38|`=m3umfzdfHT8GF5WOaRksRa8hr$iJ zP@Pt>PszAlzp4Qv03TX+$A*CZ69lD=`ziM1s1)Qoq24f_tN<5N4quh z%ge5*rUMK3NV>!;sI<=hCCs=oR(VJ<=(mwW5K51d*wR{koX|u; zK)!T;qzfH}C2~*58^W(q1ZKv@%BK?b_4Vo84v&DOO*nT&=sLl4P<|>ksKc29$5(*M zVV&s12M<867a-p+y6R(zmQDhj(6E-b`59%y2)QqO{?5LDRRZkwAwT^bZsWU6`FC=Q zf4^J)Oj7d{zuF(qo-4up`m*>DoEvx(YLKOw2TpjyxUD@r7^*e=1!=-TTWznlrS0mw zy7~euzPr5MjRRsc)M&`>MNPGQGI}02(ge3ZxE**OzkRD!E@SjlyfR6kmUD7<=jP(7 z=DFPlU*gNf4wXrt8(Da5A)c{V9 zbo=3e{%AR0k#1s=+58?NSnyMNm||3EZ|r&7sIgtSET&u#J^c5tK%mGYIyxGt z+^IO~APZ6?{zt6(`};GH%U8$|dI01i-w<-irgMx;PBK$a7+?SWvp1PlKugca7}@tH zQ_y=6X!FDb?D}*IfM<8d4O2i?VDs=WJw1JN$BEkxqPir!(-)d_`Tf_+s^^-+V9={p zq+g?==nFr%1v#Wc>@B`A(mP@fjNlO5G!>Cmcs8(14j-Qv8 z7a(=j+S+=wRHGmTu+^LF%*~6tx*q3B6oN&K%*}yVVzP8mUnu6()D&6(P^@;cTqjnf zd~kHMrPTP|(9GAcR@4URy%ST9sJ%#S{j_(R(@ywR`Ix!6`RC7{T~kR_r|Ndc(^O91 zOG!yJH8s6f`PG|2ijiIn2u7~}($Q^`=%VQ47vzexxPE?qAVYKWf2BmFrKLSRBBZ3G z;rSd0E&&n;pa2UfF1xt8a&vJZ;&(fqDUis@%me~+dU|?5h6JFhA)}x`q0pn-5})hZ zdZACiGYO2ydqZ+=GEJ?0!56{3K;7oxzyOf#r=_7O(Wub}H^vfJD{|H74;3xrDkkp2 z$=~q+PVW%cc8ASUwQCl35TK_|{_i6%Mp9mW5(2hCGQ7Pw0D9({MXX8+u61JQr2XG> z{+;OBJ3ej;oRN;^nuVvjQMbV-92^&i-S>&{y-bz*l6>~z%ZLHv4}-(Q=zGT^|GhVG zUAb9tadAL}Vy?7@H>RA4$yQ<_E)5M0*BuIca^%xEFcVQxQAd1~|K9~bv!LrF1s8w+ zdH@fUvhu8s#j5RoBydDU2?_`t{{K#;UpSbZn`u`C+%YpqrJ^a`D(riP6 zPA_ovdBFcYElE`BV|?2r%KteLU9Ep=Tq|c+Nu&;lr5y3G|7+N-W}`i{t-9fVF19ZH zAgYP`WyzK6|K4mLW*PoNy4orF-!+s`MJ1`4G2gs_)|<&hnZNkgTi}^vB?IJoW6%5h`?JJCEJ=W! z6F!pahw}rn!hm3taozQZ9N9qDfU%W+nsE0Qs2SnE%Ul`R*%ORXH%rQUdsizoEJ%bg zf-E1?+)vhg)&-hGav!jPhpTOv@xPteNBNAd2$Yu@E0Lua^AcgCj4?eL6wEX16pobQ zz6=)4Q!JNpTUPA!@;IM#wlec}1dW8`_fDHms!%t=mn)T$>RJk0)>7>J?u*?2lp#eQDuaS&f zPGVT$woi3zRo2l-ll+JimKa5l_VU^MN<$rkIx?h^|9lHaOLA`2 z#R$d4>4H{bzFmGVcl#uKm<31W}oK7&OF%Z1I%P;)3A!qF{!R5g3sY0eVGxV?V z^R>94bk6cQP0ipWdfZCC2TdU%qVP?$XWKQ}X0l4BadD=9dfO)H{%2st&Z)w9lxLUw*sRRTxz`6G5he0P+twOngR7?1cZ z+n@IeK~2o?H6y!Kj4dxUkivA-gvdPB-5lhSgn z%)dLjdj6r0-yt>FcV;l;IcOGb=&{Xc5#cPXHXesESCz@caHpV?q%(eEf-e}+%y5R#cfprLPE$QxQA7-eo2U;J7(gNvyp zEin&O?epPIkS#BH{;Kz4=AJu=u$fCKzg{VbZ1!U8$zJ$&JRcemmvbvkkz(H(KVeyt zKiTOoxR7gw$TLB`3%jz9^!m8e&>Z|K)I?bg1ezVvpv)oA!Y|5RsXZ{;B2S=s^O8+z z7`=#J=HINBGgA%5;~@J8HA~?z1CZFt*WW*6OwH7s?fG*sAT>WUgjSG-p2r6y*oX-T zAOK{(xVWg&X*TA-;lzE6^w+aMA`hYuMlJ6LNDD%#L>QrC!JF9oM9iVzcmR7jXVIW+ zr6Ta1WLw%)8%esiG)%NO_qAOogbxIw1@#mj<$fmaXazBMwq<8I-`LB4TjkFAy&N1# zfFZ6Fo2CETFvat3g<hI5FuwJT-j06>PM&zle!XE0d|I?{LC<8k^ zeR*|5pyERR><1qSbj}Y&DCrPqOKXL)5!_Cll_04+9#Tf8V28E<<*yUMIcW%Z&Z|M# zDU9FJFh;$JO0=MHdYY*Iyy%&SgMMPk&{r7Lo4l`gENPqJBinPNJc(%+zv+28FNf+`wYKRgGpYf;G&2t462!5^RJ7nkwE2(6aH*ART>l7)Tz| zq6(>^{5R~7cQI6mhh0J~$)Cfc;Sx$dI5=H#*b)?ZjEwzyZO#C0!=eZ)yxp4Cir`slxMO{VY&@It8BDPWoo@^wz7`SIMd)*dDb70^F>@wfp}oR zLXeRB{OQ(^YnLM+!48zrBliI63xEQKuARX!ZDDXw$&d+B0EOe;vf6y*MBtjLlQh{j zu0rh>)!?^O5(+)VAi!t)L52IR(PG26zQ8}z6}%H(v#K+#O{!EIEQ;}!9Y8F3>6ZX{ z{v3#^gj=L_USiB4ha(DIryK=4RO zH!3t(+}#n@*XHRA^9-lRNQREVy>DxjY`^;{O=|iGeqYoXJst`h!OTZkxRa6^em;8q z2Wx|@V@1e#oOfj<+_WD821lO zOw;1i9B(fB>{Z_&tA7p*aJ0Cnqr*l?l>AsCp9L^e0j2q_ygZ}RBLK1kpo7=#SQGf+ z+Q$#<%Uc9ga|!ON6)8}~71FG=FkOA%6f9(2$Nx8ZuD>7fsBH)0IZJ7u(evm%ZZFCj8l3g^ zkjXDX%mcBJDfoxFTwKlr0%_Q}1=oz8$x7uH3Ey-5- zX&)BF(HCe5LNotk&VLTa?d}S9?=V8yO^30(z303f}29T&TZhhL)D!k*dIvTr|3 zIWvpO7+)vtrIy)7VzF*lto24$R6^{mSDKVy{r+8hR#y(b@#mzQ*P^7Dl$3zuh%8## z2sA}bBmwIO;0`FlypN#mVDM$jwByoTjRREME+AmoMiwt2k%IZk30&XU;QaT5&2#KhR;^5KeoCI@VFN*9=N~Qg@^a*%Pf@Tu?YXT z1N;Y0T*mMp>6*BbIMc5&F>A&Lt-;zw%1=)Ep z`!Ri`X+D2+=ZbmSG)y4H6n^YiBWrVa+1dWA!mFgy{cTHq3bUNG98Y5Rb!vv-{g4WS z4lf~n{M0dz5|`+R{k>WLgORPh*pVCHP3%+t+d~6TaIxyn$9MYvz%e6%9(ujN4Vg28 zbTmqpI1Y|CSIo|Pzv}!*mVYdT~V6G*)l!hq@=@@@#)NHcm*erXYmXo6vi_oLq=Vk%m~eR;U5)ZlZJc)@__uJhY`K zOXzw7r!yIaS`L4HEwXB~6S48@=hhy}z@B!f5AS)!Cj}H~l5Ud|)`ThKS&FCd4k`ye zmlN)sI|3!p;aY#6zb(Xf7kg*HZn)*w)si}_FoX#oqAG$kjPs;b8%V;s1lzAK%_YsJ zac?R{0(E#RAW%Ud&->`sp{Tyj1cZHrTWV9K)yDkDD8L;x4nK4I0{HMWCV3}Pf@5!et4I|$pz{bW-!uPID z6T=CpwfyOwPKw|V7NYw1M@}XDC$02);{osaGxQ>xCdr#EouMS+A3m?c*9*tfo2;^Y zciqC%rG$mJk1NjKKkU`$UYGfPjwW(qsUhMqC574zhQlSi=<16=k+gIaXHrNgAd$kU zsV@Q^MW|%?+ds|DxuLH2wpX+Guyd~0nXdc1Vx}W|@`b!tsTY0aWnHK2fJ&Um3lZ@V zv~EH^N@TvsEa4Gu`>Raf7*&zN(+r8LM=F|coAqWmfttL}*S?+%?)gWzP?3Yky1kvY z@KGf0@K|Z|o1Q-Q)XToZQabyk)mKci>5_9L*Mi2+&PBl`h6*|h<);a%8nfs39f((& z&|*<}2UimQH-4h%zSkTk<5g8vKrkRA;z>0nM5v7jc+F70B8j2T0}ciK%y@>B5^hAX zW~Ea~vr;)goR*dlPZ;j^REEqe+6)j$13X~;T^ZGw>gv@auJhi05@uUa_xqj>V8bi- z#eOjZ#N`$W$2l4(HaUZ{BF=dai7)@fpo?F-!10 zpOxhgAV%tkS|3?7L20x3K3I%5o$(;sZVgx=#O}`Kn-0p$`wZ}NkY|n&wOI6eDiIMy z%m1V6D}bu%!ge=EgLEmNpwitP9!lvhDe3NzZloln58Wjp-Jqm&BPB|w2uRmm`2GLP zojY^)oEe7N=j^@Ldh>ao$4dluxE*2UeRx60#*ME64b^lVlU!fPJ*?F}K(KoT&56(Byab zvR|V|4Sz_qY%)S@ojo8>wiDp#ECloWUqb5D>f)oBh=%EaH!|0fcO3` zWf>-F;*G`?y0+r5?(~^+4^k9;d|_5JC*!N{BHmtwa-4KA_U4wl)w?wDR~+;UC8>Gn z6;}7TjyeJe0ZX&2p24?A&#jGY|BE+3Q@l$Fn0Zh~q|Y2Il?qMQ_o zeC~{C>KPqIKcB$C<{V0*eGxU&XGt81!ku?f_4`r#ROLigV0@zTueyiNlfy-pU3rWq zt4n_AUpx5`ni^USduAqT8hvr9mrbU!RUmJ2I9y>b^fNa=sM1Aj=9kWDjvIkYe@+SU z@l};PFAB`f4ZfuLG$iD>Z8~-z;Cco#pvuoqG4Tqx_V!reUDEYTe7?QC1(au|faeU% zDzU@E?{|S=1o2O*>1FYnqj9-+!tV>=x!<*)T?}e+G)0UzJxY@_T_1FDALp{#D6VOf3YLO#+c>q`vdNda$t^oN&gdDj;HNKMrYCimR7>A)v>C{Rz*MUT@4d&L{L zem#Je?Z?vpRHbtI&ZO~H6;K!)y*P}+LL6Xb7#OQmHMmUczz%IWsV3@sBIu}@WAIHy z3M_i7k6KLa-WN`XlPlEz10u!TMUGUMYDHF_Y}|nyA><&{t&5zFV(*Jiz270Ia`I^M z%G1kwx!`U=hNMzCN)T1dB!*M>5n`&!rl@ibhp>Uhh?aHxCduyEjiTsLncIi-rIz6j zZrY9Rri~BC#C{3_?JcTsPMrmv@3m>pG?FjeA61=Zu{vpn@@>80ecEuR>>B`IpEurk zQC-+pBOQ}yS^oYnE-`JHFHu`zLww>Yt@WC*yZ1s@sOf~+n$Ye(l?ILc`+Y*ehB3xF z&GDI>nX zxjH(Q+_bVI>NX)xBY+Sza0Pa1ehtiN4vEDKdkhFf?qepZzd6s4=pYRL(i;VWd8sH; zJaY0@VT}&it3nLdCjK0{h}@Jd#xvGWPnGO+Bo)SU6oVtcCDS(C|&d0=k+Mv1X|Naq?!!cQW}&we`}9|$NDz5CyPc#Mj!{!TTm3a zSSw%9bm9yi6BKmbh>DDi6r(IQB&*XIW*Y)kf1L(9J!k&UH8o{T-FUE*cu-!WNeGWj zxewS+CL>8$OBqX&c%EEx;p})PI>Y+o$wPA~S?J4Gn5pqoV`?lV-zbs$i0j2GO$a@B zu3z%-17ATs+f*DcRNpz4z2@%lFshNrT+Q0Jer(INS6MrXE%X_h5}2jb&zz zWq~F`?ga{p{W3;QOaKVa0cRXTjW)9h%DpeEldFktGHV`c9>M&VF-j_%_k+;<^0MLj ztO5b@xMiwYVU~Y*akopRCfI~H@ZGr+8YrF@c!_^_oU%&$G2QH%`%@&fTe(CroXh@4 z>whKqoaSE#2lk-!1~R$_L-#f%1{J{&4I!d*m1+~z#npSnN5H*6y3g9C3s<63`Feo^ z#kImMb?o=>uY3Pw*i_kt;%w}`jtMMHj?CBpHc?+xu74pNB2u5|{oMn<+!3_4-UStQ zsCYtP1Ef1gKaR|=WkG2GxZ@j8*)wNZ6f`r{Q+Q$ohl)&`^P?3{Q!nd(?S!{E zbP$A*{TLArXc~b70qGA`o;Ig2E9(K6$pE1l{2>|@m;A!Q!X%d)nk1Tf+V%DIfCK{o z0a#ISqUE4S*b)v5^fjWuPIL}cHk6eGdZWPU;dhLwk532g@0bWFQ^d1r{4urrMm7T@ zBk2BE8^Ph7>mUK(K9q+5-vUUffa1tR29omTCZj13QW{<*#nfg3y?LjJ0xX zU|cSEhd+aYQ+zrH&XNS*deKYw@A>0WWrMtIy!inf#Fh79fSl}of+mwF)59j`C^tDY z6g9eu83H4Yl$>Ga(^hpd1-I+1uxGSA02+(%$Y1U_9rv;S-9lZ*J`>h6->p1B zsw9VZw5q5D*HSj88)2w2U1pPVgErz*$SPlFjhzQtm9>h^Fb7&kihG=76vb4b+K{Ck zdnPrZidf%4)Wi@B_8y*%Nzzk^Vk!Z*v6p{(7U}~UzCYi>@`eLX7}skDY6WK z6O&)R$GR~bq=`97Ve2M6ntEK$&cuD(0l53jL=4r2tEo-|M(Bcd&Ne*(PlzKTy^cqz zWs5A3xz_pl-;cC^f5fVw;@>%B@`dtDKW27S??X#)cv zAHShSzAs_*t%9@qdhsgqZ@4a-DnmR@k1Ks&w;7vun70Pq+GadOs-tsvmpB?dTSta; z;kf};3whh4Utm}flwkWDdDWJtLw_2{Ci2X9R#o{8ZJgZr=BWJOX4w#IOhBm0Pcqu0kqtEuD>ncZtrh*F{u*S`G) z`!SnkQQu;FD*j;<0;Lsq9H&@zD-J`Ygs|?V|KFWox3XS7KA|c6DWJM%C@LSkQ)3fn zb6rVt%jcnZtTrip9EpqLEbhBxhIMZd5`iTH$5S$JM5>DaE7!w<#|Wz|Nh{2$(#Nz9d0kHF4EIpU6Ph3*0vFV=6?N;jz z*Njcqi+vGF3^v^IgpaC$>gA6hRY9lUX8j4-;YMRVT|UWN#>g%&ajLW=dY7oF`0;56AbQ$ow!OR;c(ngDl94) zqPGBD#uNFGF(ty&!bz_E(ZP7>kdr8!waJIa(ud)sC;P6(ee+O$>H?r4vr@_BC%J?z z>1-_nlCIDQ<78toyj3MJSsI!rPQJUk>&>cn>m^RRCQDw24|wKi5aKDl)QDrya(p?U zPPfhwg4lMzDC{&cw0YJyMmnD_zmWg>*Nyj|l)e|KL#=7VuM9l=M6wPQKh%1kUe5XP zHmc}oeumSTat(4P&zcTgKQ$n%b4b8i;KV!f!KCT)`54!*UL^a*w>fzK{xQYIOj>Y( zagzUBAWV;1DH|!Q1{2q2`FRa#79bJs_O^JdOhaZAsV zsE96E)>Fk0#W!M@uYQ?K&gdT3TRtG!Ft}NH^=J^98j?F14Co(D2mOn5lKL1}tVg>?iFGhF!T8>G~Fy)fm1`iG==}WKn8F zl!vd}X&^1KA6~*|d0_!*cZ$qJ#kbdqL|5=tv*=52yX>NhFx;Kyz`#I2E)D_Jlvgq` zJAdDi;E1ESz5(7wS2rD&v-OiSa})Vx|L|}Im*vMz1~5P@)`w~s9Uj~8GwNR)FJD$$ zJEd0y&wj1M!9l<6piD`kEK@my5!|^wxK8nOZo=sCBeIE}Nlux>>v@(z6l9ko7>V*r zHZ2QT%cXWq7sy!HdBh@-{(z#On~Q*InUI_u@N@qfc-y9g1?!joV?|Ns-mJ?}n2L5H zV)M_0#z>b zH8=KQ`0u-s-2M{06!T|mdA%`D5BBkKVIoCA;0>p)9D3#MgQunpv8C~xizx!Xccq)= zhYw2;;8Q(tHT&fMa2iTkp&#xq7}rVA(eX(y^L@Z}|1GQ^h3ubIS)<~Bc{E^w2=4x; zXjGm5oz{aC2kSw?q1&T>KmMIhR9o>>D3=lSd9Xksusk~ZV70Lg-@ArbX{Dd^1^)k? z*v0spS#xZD`oX{#G%9nh#~(Dx%8QF%DfWdl-Jg7op3t9K!a+8>3AC$0^We%WUu7HM z7V~m*J$;?Phok{vPUWn-XNpd_f}Gr5h$r~3oHPP#&ijw2bU-QQA)~z#&Cdlo5M`6w zNH1}b0#q=dhYueDhK<(EOt0<-bOl&l5|WbaSkVsBXiXpVE8VF}h6V<9LX5zzgE3m@ z9gLB)SU7(cC&g%3lDR3-GTbe*Czy(!>|N z%E#E}7)be@V;IE4qN1XHett=&k3#7I1oP9Uy)CBJi#5dy*4zA!egs?&%I4*r5XZ@` zWFL8O8-c1-#&0A>p6?2(J#^oU+vzRW6EPu7ZsAY=mn?fDbB2S3k#k262` zs@`(z;eO?;d(M6qcY{Kub@LuQfWhbH^tiCsfI}*$hqC{gdg9a|G|@W8#y={IH==^a z*DrAhP)(U~IYhx2Xd#F=FERf0jaR`P0o59jmjdB>^6pbOC;8<4g6=19Na4R81ip?{-b32aISnoyJRuO65r9zGyQZ%zEusl!L+@AaN(YZ!sT|KpFwR+EApR(kJ}drz9QbV zz99vV*d=J(f~%yY1jvP@m_2*SrN#(}6>l^r!I8=#DBjf;^|0xgK4WbM|LeX7Vqv|{ zRg)ghVASuYtBuslPaQ(Id)K)}R@*k1&x`zzmH@2k!K-(`;)C#-AVXL^gHwV zrPDsHaND${-{XNZMUjHSikztRzO3C8=5K<>hW+uMDH)U{&1y#7t`==1Puv_C%Yu%=SFsy&@di|rSrWFsUU{-vK`Y*P4Z&5c7=4}Az@@IZ( zv23U{GDHf-YeOvQpdrO|$WX_6gzk5KzSF661j4!+h5bUqqaC`ofk87U`}A^e&xq#% z^nS91lj}f*XYzJq+=Uq0NvCxYuMMeh5n)c9fjzHLdmE#r@%aax!U#REd<9VG=a8~{`+u=qDUepuBZ7GP1S z%zSx@X!sd}IGQ7>3q^jVGGPFn^l|y{X%@e-wP_nA?&}0NHRM!hK!~8)*7R$>L-do1 zls_8>JybwE;%HkP+xgZCQEZoNNQ07{$_X7hOqTu@z?oVmpW*9>MrE+cnk-ajs9Q7M ze7j3-GkWiTgkBa+T5`c_Yq`?7jtjYAjAGUTmJ3b1iPnCbe|8__Edr%_mRb}QZm>w& zW#XaE(Q^L0#u`R>Bfor7r6)4xwpTp1c9#j)Hof(>&YPcIX6lE}ezE2pOlSh~u8fiS zden&*_2usrbCwvN<`LPvVgDWVrI8><#2*b};(O}!+X#+6ON?BN50fL#M1U~JrH3`X zSZutJ(-p6&8#e?Z(vVd>TC@Py7f}I=Lc*wv#7F8Y<}SKl)_Xl;Ls8kW)(6NuFbpj@ zl9gjozfF(G&;*;JL9TyUanUsf3&bLKnaLq;_~20I`L`~%L$R&UDnqBm;*?lsQN7E_ z-mK660zjwdAEfdow;fV09-8HA_|HV)LuNbguF`UOct_1S$KVR{Zf^On=a*9>l__?f zM^ryr(1;R@Ouzd(UzC;N^=wTN(LWd$LqUVzU3fUy+S%eL_*E&{u&FBz=jQoAeK7U3 zXZ$MhaOa=pp-+n)l@~o{PSH4+e=6zeMV=KIUH!%!Fp}KfhC9Uy3$RNd zGe_@I9&Pysm)PFgOTAT>>klm6eS$^t#IdsUaPoPwLGG8grrdYy{lN>DA7VL@2|pn< za+>cBybnF=yYs-?Nh5`28gRTlWW0hP5Oo8C;SLJN>=9_~H`i!~`dV!dx7cjTINyV#0)$*K64E#Kzi0V{jfm<5^vT~w`!%7_3lP<({ zdeiWDs?Ca`REQESu*V2N=6Em-NLR?yly!-Ikg^W>v1T%lBFaN=e0zYdq~=ZE-31n+U@*0hz~OM`EuWetS2G(CMj z$sm5cOAy%lg|^H4eqfpPS+lmdLB=CG)Q{QIa%Xw8ikeyO`0>wzFN4DmZ<0o%o_<2V z52=A4WVVZXyHUbeAunHGol&8@Ft5Wsa_0F-N|4?%K?CyFE;k5lwU7s7#QdUirvqXf1-MzhtVjv<{QBf)C zYk5ZsD_#H)T%dwOh#`sE_eY2o4Q6Ne8xTYYX@2uZc%Un!qGXjytot2_s_%aT$1U;Q zyRF+8#k*)^XrGVjN-gGVi=)mjHDJ$->tG7tONYX`hyvKuis&e0L;x$L&ew^Y`*1O61>JIa*hrztNEk>LNV2UXOmFk4NRgS%VCx1+u@D zl?Q*%fByUl&`MsdOu=?WKGb9BBfHqueCU+0j4j5lp&q1~%|mJ!+C}s!o_T@>-Iq~O zrRB|DG3P*o5LbO|!h~?`cpsRLedtXx zLlk3)|6oZ2qnNa+19>n22mz-atdvD*mTXkE;nAW$f+z3 zzj&45PSp3QpcuUKgnd!yBhBZ1Sd-?EC5(c$eWIQs>8SE>4eMlc97iI+^|dl9hJE`wOunMRh#<{bbOU&~c-%X2s24gRW;iGW5Z|X*FKTy-{z}wDQESzl9^WvB44Pd#!N~- z-Tzr>8eh#=xpNq;)hCbrlT}8y=_x*jZtX*~oJ=J_nNEPRxUhJfhsy>VN_PpHUmHA2^X!- zx+{-NoyhxSY`S<80ZRFUP$?3ha;T&>#L8;bf~n_@pVQO1>e7PNw3JC8d9i-!Mbk6z z;{1XN>^;y~C4MCI;w@`F<~$WxdDFpkBLUgea&98i?^;CG;0QW4EH9tD zq@#uqaf_TSA_B~Sm{-wev+)>3YEPPCAPS;S(nQSdaSRTF)Qp;U39@ zlO3ao^*-%lT*l8y4n`MTa(9MIZXJ@8(Xb2%r;pZ?NkoMwz2^`k#(r)lcP~@8maA3d zZ1mh|dgkjZg@g(WhPNne$W?)MawJD{J}KRJf+2zDR|K_!Gk=NB_w)KR>;r!EF^s*;s z0hS;J{r{62j)aF@UN?-h%PnBum}dL9!q!8+YPzX=&%RRsvLnhWr$xv}jopD29BWO7 z41=I|0e0sbQCSH-Ccn|_NkYJ~@yOyE5)u?7yD!7|prt9?G)@r@OCJ%e4!O^~VVLMS zTt^a3*naNdAaI16q=eC_l9QLkMsmev(0bF;F?!vSp7FH(eagJK+hoHda(fbRpZT;^Z0rSn0S; zKgDj%&B-2__7AQmIu)#(B;KT1KOQB*e6TLBX$5ED6$eeVey+H?R#qBpco5@gtD3fZ zEr*#@%Otw`^a9Ia^{w)q7Cr%HXjo`^hhD|`=V#viaRaMDoc6b2$-RS>t`aJaLk%a9 z8AUN{Gm+{^I#Rd&Q&ngW7ux;N0o_JawCCBcEiH6tS_H2mrBe@=c~=B=xdMGC{wT;F%-I_=2FZ-hj66=A6`ntso` z_jlp{0)@F6bDV$Wv$eEmbuew7=XPy+m^)tzc=)No-;2?t;O<+3#7^ERzt)qZ zH$C1}It-hT7~AozNc>yUuMiZ6f(of=ozS3~6Tsz2kYhv7L)ak7$zWW%>V)m#QqPyr z+?a#*)m|(K-Qk%moK)mEsoyeAB`0S_8vz~=Fix@AIi<6G4V!&Za6MzsV$*ioQ$xdu z+$lzo^ZQS-Y^DyI-MaMqS-%WtS(t=x(`^oa*S}O~OkP2bb8>RBP46B%yAMq3jDf?!&q&{)0d5`M`sCIYTyBb-eF-t4mYMV$b<0`Bl9)e)!fmpLAq z>vG^X$2=og{k6-sBAH+Be>p=vQfvbzsAjHBPRzMLxRY`emAiWmqxi=1?88x07!aFU z-@+*#K04tVC0qBm*yD;qkp7_Kh%( zbd*kd)-Q+a2=^vDWF>np?{o-s9`j6($5Q=L?FvJN{5PI-TsM?4AwV;Jx2<74L4z>{ z3|@zryMz<91!1Axl0y@(f@p)O*VKGYhCMnkTn#0~xBuka!PiXWsWy?X1N-x?@CxfM zIv$0nvr}Q_`g*YU*0qd@zLyO|cX;?vT87J=CKN|dugUd5{e*ePP*s+Pq@F?hN5L#A zl}QZM+66TMaYr={;YVV_(HT4rZ>y^AUVZDuzu0?u z%9s~_PQ|d@Gte-SCXOO$cdmYSTRvM-Za1H}@JHRQOOpg{jnuO!*>%UQ0Z&%_e4D`T zt@gK91?tOP#(~A|inZ^^biz~@&lpo{%C()Qy;wJItl1nA{r%#!EP7L)*mdsK1 zSxvC9Qbjdb*tu+nx#>{)?6e9~-`aXVZ`(RRCEI0A|M6=A;Fgl*qYfIp&8`jQDeKL_ zg*ID)BFNN~n%sS+?ArMjzI|0a@nY<;qtWKZa1>%30(Anu%uDB7I{;U7#-%Pp1Kk$=QltAOxR8qnvBg2G%$`qK^&3JOK@)j+}Zm_>U zEHYA+j*x=9>$sH?4U8UuY3(CjY9NR8XYm`}k>leJQo3X0$q)=}iERaWpBhCp=Ox8< zCDB05Bgfr+omka^f`Z=y(@63#G)C@23KonhYIN3iG%V+frawVH?ms#K;ns_fHeOUxB_9p^R5!jN;qpP-4%yJdN`3oC+9FEPz{2zOKW&4fEg+TfCWGAfU zw*Zg3-QLqXzO|-Jw8)J2XjC|l0l#{K>^*X&6^DdN8g1!a^!bE$baAD{Q#;R=XKTKQ z)CvBRk^#-~!f(Is!5^Px{tvWeEmorp8QcI+l5f^e<03d7CPOJmcpIP+v8({<0pNs} zFESKRp+=HGaEEL*CUebj^N`?q*{{yipjsX=_feh^XH>L{Koi&paFl?MdWe4$F zqfh_8vO4I31gbFDA-~K9hTgtqpGT88K~_daz~LtZ-uWvV76|sb%UL^-hvPKq2qOT0 zEMOSz?d_G4mVO@^8XElX2n{V&V`$Q40d>eE4YQgiP{ggTcLU?qG6f%38v#%Zv|_-B zw=rOgk;)riFd&9)(U?B9>)kz<-Tu^g;-*(jfQW49UqlLqIKb89h$!HKUJht}c>G|d zb)o)iqOI{P?p`#sO<)5ZTuhrdLn0V6h zxKkyz)8D^a0KqlpRLIc!d&1y4_(w-a$At!al2PM29iR+H3Z{_30d~-%NBmx=HiuL} zUmRAt!@-QfJ@{YPvlb`}BpV zDY(CFp_?9#XiWz$PT}a$Y79j0i)%hf`(AuO9u^F-G~)%hrD>~8zz$|UlHT1d@urWx z;4hF$F9HMu;1+`TVKhTfQ$^(&T7?3SIU6Y!O3;nE%@vq^&)~Jsd}pqvHU+qJq(6XX zGgS;|XuJFRz<&Z@`ZlPn!89~xegLf1@1?YijQz_3JXpWp-lQC`#YhhjW&Ke{k>E?a z!};lTx%1zd;-o_ch%#;V>WB%2+FKApd)wIsU(I+PCZUL@2K>c5)09OJv z6te2c{+$H-AnNUSSo8SeV~_Y|@Z~_1EGR8ZS=Du2u_kc+#W~cx8YCBqz;$8;qaxMS z91HS}GqCr9Xs$8eqqeV{_v>)9ZmzFwR2@!nSrCF3Bj2W!s1~ujsb>NjNlZ*~t)Qd- zMAY{hOk79td#f;)_b-4^Xp@sJS4y>2B-ARgX8UC2tNn&7pHpo>fx%*~AP)6TWB0yF(t?xw zQu967qf(T|Wc#n(w-{v5NjE+F7&}=x!>iBY!OsIDm&*Fc!(xRP&(yJDR z#Szq+DcXjeJr!{2Ur5Xqk+SI`MEar^Z+yxT|E;^4sf*3%*z8Opcif^@hq*AdUvFh~ zHJL@P*=2hoC57}b6U@2zT%GPOweWIsPKrD8eIM=6*3sG7V{6lAtv5mR2cpIK3B+#3Njm=H3Twv9ll>I|_G;u#@6nB>Jcs(jWRC=^(f_;Bm z5X6!>h80|6Z6=c7?)6E(KQkmP;XN5`*c+WNu)AG1<{faBCzdKOv^hXPj;up|!Jys3 z8ZS!!p~@5cXWrgb%kQ;T45=s=yNrilI9qUgwU3YPT2lJ-yT*Wp={ zkpg1FQcq0$ZBx-adj3m$-)~@n>Qc^+O}1geixG_RV#Vx)BOy`Sc`nVF%|lZo!WKYG z4#<~fUwo{%mAto;El8-S%Rr$PkaDB}xWT*8i{njEK(;|4=tf9H^V8>wdgOXULM;=KBfxsvR`F#3diz?>zv*>TukQ; zYkJ`GzB)cy;bUI-yPtWjS@U7K)2dJ6X1}8UmyC-0(RFJjd}An#&`HL9XWG8}u|RF{ zpF};PWo{Mqs>@MK0^%MS^gkiAtfF`F!|0rx47x^0fP?_8DYZv1?OV#DE}rWw9R#r= zsfMZv$Vm?q;;!wWOEAsUuIgj+9N9XvQ{_n)616W9@tzN(xGM@RytFmgsO&IVPdp0H zAb4;tpg^lrj6j?o)$o- zGDi4R%gL!)j^=^?z`(#hu$)WHC%}TW@le0wMU?lFl#~QiBz`w1vw&);4XoLoND{^W z=!n7kTL2~vs3L!O4&lP|U-ZI_;3e|w)sqfQk7IJ7PPY92?W-1gv7CSUs@?c47c+&PlT%t`CPvZuvf1s2N;=3&^)x@WJGlJR+jlPG-;hTL(hGjKmZjx9wd|8xrRr| zZ=G$im7GXrWytTRX6}VZ~aK7e68=mENmS$w+ zeW}A{Wz+MHNiSF|GLw=*EopY1!1{qybvw|61s1z7Ki`480qk+F-%YfDn19YZOW5bq z#a_X|Ms#h_cYd8ECm|D_kr9&yx_kr@C6|6W)Ys9vA+pjL^Qij~yxbG7t|RMxs$H*>tFi7Pqqqs+W*__^eLzTK0sNg z5(+xAOGAMB6#&KC^pJP3K?(4)R;!+5C4Pr~svJ$C%z`LGVQOP`)4?RhyiM=s1`l=c z3tHMr-6jrpc08y;zwL6~y3*(NVsm(S_ys&9pYA|(qI*H!D|7Q629k|g=YUTGDMBL#jlDzU>w`q~?;D~e1L zhg634Ckakm6yoYVUXRL~R*6RW@DQ`_)+pFBvP1W1D$sFQYWK3zxk{KICv6ePI%N7@ zZUYDOt_63E0j$4?`@^ZGAeDzWvfzd>dvY6sCWl165W_5y%Nz4nU4Jm5Y9+Ou{qTw* z=RdmG%%Y{C*#I1Zg@w^%ye!Pj!;zLWje=vfmUeauva)2nc8m7D$7x^)6%ewp0!3)x zyD^EG4CmTwpEzDUeGxqNQ2f5k>_UP#)k%O-JV{b3Yq`O?Y5RfO_Q8-Ksij>X+^dvf z`BfllFl&?hPnhUWov8IsLec(p^IBgJAT&f%#5Hl!s+qK1Wax{Ewqih>rP{0?y2RrO z8mzcNpgZF*9UN3fL+)+1*cD{*Qs%2tPIX)!q-Jr`8h!YbSB)kwsj_D0F~E)&&1O|> z?2C>#yD5hQd@}*9QnnNUD@uB|;(QiV*|3ESWe2W)2lZq#fHwRPfj)OMSs-eA{ph|G zs#>H#WGpYoVYM-hr_W~8s?Ld=gqXMxG=X0pxAzmjDyaGKIv1S^2s(*6u5{C8 zd2@jH3@ARW4<>_q7_nO2rtK;87l$Y=#%vOo|AXpXjk zoM{%HqtWg4g$M_lPgpjx{~KMjmY%0C+X#F^$W~0uPFYA4* ziEZa0t{9f{DiY!=&&({*ba~5TO>B(Lt0oiQoaw7C=VJ5JnK-{K`zS6Qg%;6Ya&_5) zNwppk;p{38F+h;n)>=x>Tr!Wjo_98fg-)>pP32*&U-yP+_XVRCx`X-1jQR+UyNfbS zfAN+ye1x3!U0pyr-x8DWoK45iCcFY#1_u3G-IQJ)Tjm0PJRw+SAMVlhNAyU8IaCOg z)5eD7bP0`s=Q(|II5IROcQ6w=&z3g4ar6UgM)*@YAKXx_bT^5pd5hK784mY72sUklZv9l{r&I2eh2By z(z_fxESypEYJ{JpY1j~f$I{`5iak5=!3CcSd2e*=LCwKp_uK7?oCFL+*J?T?UQf=- zj5k>xe$~|89aE=s zy}|PMw(|2tYkI^-FnV>5x&X8f|I8iR!rzhm96HTulQe&SruN5#}}22k`ZCE zGQ>oBTP4U%e6QUX5_Oe2FJD2|o^Fd=eS-F$z?^}HxN6c!Ppb`|Y7LuU^@=&`k*F3y z*gxY61Zco9TmHtpV{sqQNZSghjgOD(GvNd*kvhw9Qh=F=mUo9nva*rWRwr)E#rA;y zi?#L7SHMSSHVk*&o+wC2NXXC6Kj^so;XWbv=leV7_jCn7t5*-Sq(NT-OiuvXE6}>l z^1Jm2$(>XVs;E{(Z<=DcQ=PGd&uzfIn}P@5m1JhLV1|kY4RQ#vbx+<+H-S6OXl3FMsfYyYu{?tl(C%j9<$pfN+Ke8vAR)39!*JZe76 zbPv0Nm-A(*b$lgXGaYxmLv}2~eD7D7EGMhFjHw8FJ3^FA1)j;B>D%%BP;7jUrv!U~yX-M8*$5MYD@2k{$j+X&!_A|k5ZPBL~+x3%d> zW>F;%QlJ0g+lf^u@;aH;G&VN=Ahik@$N;8Me)*cw?e6BRxAml=aSk@OpQyzFEg?}D3_Yp z9(;T~JrbQH6I5V}gIy;WkQa#`GV!G}0gB>)(t`1h8bND4Dhf*zd-orFv$*m8;N#>} zO_x)Zb8Y|~3nJR6yTif3d~Y4mJC&GyO+f#yrJi^o@7s#v`CM{(OobOmDm zD@E;SIqg>0=Z8O75U8ej!%7NLZ0lJ&y-pHQvkynmuoV!7&$sCz3r^<3 zzQS@sXLa^I07A}5izl^EA!kX=_nw$=4UNSEp0X_<56 zq42gZlzj+Vgh;`$sNtUrQ_Q3+kQYuvrAsJ{3shjjBJaV>KvS|Us9waz{F&qD5;PSh zTtcCpb0Lud@Vh^5M7)Fm2)j4wqRfyCr+IzsMr6kWG&F#7!gt~3w=C_> zOHhmeG*QH7=0hoQiHYkyMzuQofc^#$xmM^lIe{ggCEz-6vWa48(e~MIF}pg@#wz$F2-KBQ^n&9;ekrn4?sQTX;1*bycZszzOoeuh6ixj8_s^?1e&^!G z#(52qJ788f7r=WRMMXr~gDknc%&q!?9Am=|PivrgMI31gazYTwbQ?tA!FXRRqw_A2 zS}4TGDGdaYLRbK*;e&+&N4tQNQI6H7a+u1bX%Vo^?LA}VF{@@`>`h*YeqRBjU*}VZ z;%iH^2iOaFYBsh%8SXzoHI_YXm{GIhKES-1v3CIEj?K+F*Wv4YEH7SklZcSw7Ci&G zcRASjJ7twmy!Jk~C*nO1R?>VpbC^7-?YMBI>2CktjBW6U(zz>FO!W6CU#9C+PY^AQ z0^HS0Wt8f1h=0*;pF0sYi?DYQGF7mqw)8|c69NiwLJp~jO!X8H^F}qIT--GDEEL?Ve zkjrSBWuY)EOyXJGs~0i__z+!zMp>QvJWmhWNkOu{PK%o@j$(*q;r(@rTer^*au30| ztwH=HQ*d-VDtfp2^bYXrEDj*k88cHNJ}33Aqs1uc}8i z50^|tZX6CCmOcyaH{p;e0n-*4^b!W|euenm9%tdd=3O3Ljvd@+3;|8ISCVOhf@t$X zgk8)!wH83RN~Pp4uw_eCZ^f4%o7s(ujO`ho%5D9TJWU7em4IMN=HM#Ag(&XZq-4U9X4sAA~rOR98KYh#Ctcnv$Gp>fr% zurIUQ+R-F@`aeAoAihkqYx|B#vG^m;wrM0ArPwLqAae-%zXAJB>}G|bp-H(?r5J}X zScdz{&oMQu)jxdJULhf3INr51Tl(-7@_!5;k|#gZ{HET1HyNU24>*{x4?2`4#zeaf z_E~q=!I%OsgCm`QuIRVI8zq;|C6j5?o-xx_`yp>PR7$31VzyVVQ`%C^=I=}Qr^0EV zl;NDrnKlejf?}KUAH6`Z3;>SLyc=PAPOg4|^HbjwFPo)iSMt7_4c?BqdfPOz(Z#Dh zb6&Sqaw|ItdY|KA-mPgZ@_3n_b8~sF z40|iBg2Ht8hTr{gu+QG_c&~M~nx<0t_)yY$v=`4+C#8#48{0Qk*m)^+zrg3DMmyN^ zA?sKl@2${g$P%%_A2((IrjZ9O3ixeo3V|2(<`IPo8OX7IDpxx?iwAHFD znv?^aKuUDoT&iH8!y|%biuMO<_`m27nEunPkX8I^8!g@3tXIm=L*+sqho6N{NK6nqUPt))S{Z)I*-lhs-J?5L^YT~<**oCXPNNup zJevARK05j!!SFMWj>WFX?8L@ew7&2ct8#lgUUy+49jtctm%K3H`b`OC&?C=${h5O{ zYYy-TaH97vOd-6d~D{HD3y2bHb}9S zwzBu|L7=q~YXTg3?Z@ajKhz$%u}L8pB6H`M`Ahv4cfD|lqpZ7Y^YwwmlamvG0R(mb zecy1AE|D=NR@O5k>Wujo_XDs}wG9mJhB!xUzE|Ze9P!p-vQzH|VlGHwh&SsWhCih;##irn`oya|d6Dc-i3WAL6LJceRg~Wx+)gNtav9Y7 zKjS*Tpgwe$er=)t?cfJP1v&AdUvG2FF*8cRP9+Wi5iwH*t`B{=Ch@cBulpF_2u~*N zqe0QXTYsF^zLaryU}G%&JoO{#l~MK4ciK(;b{N9rOf4@yhpp_TGs*VzA_pazbur`J zQqg7eW+l^t$CC|LWQ<|gql3~S_=AWNOT^wAzwOg_pV+;6tle@w`FJqp+@3g;K0vU3 zbQX3V8&){k5Nrce-WZpo*wzbK1;AHs{dQ%O3R__h+`TX9kGk@JC| z?Z8jJEf|@fK;0hgaa2oRdB#?s!zGTs=v_Vc-i>JA^-<5COB@5iyY^>$pXs_b2$)Ty zmXFp*ZMC;|Y2V0b-7T|{9kw8)_KcTF^BHfnU;90=YJLV#-slK-zk<$~a5(koyiGNG z+&`!heY!pV8Z7x)#o&Va|FHEJKvjKj*f4wuB_*X>kr3%d8fgyQE#2LXlprM_Al=>F zAtl|NB1m`lyZHT|XTI;9dCv?p31$*(+!7Zz10>KlXWdO~AUFU46O7hC$(SLm8kA z@}S9}TmyuY!_~6u*5;;jv0(b&+bqGhH9#nWwFsJ*;V>M!U%!5ldL0YJ_HP_y0kt&s zT$JF|x}Vd_fK{GoXLI?XuoxN9Kh%Pr>^6RlS0l)62E$+9y?DRbyFj-KY0vPJ zUD2%Va|jOCw&~^?R*F@@biM!&STjHqHr0wU_i}pCYy`*4zQIi2CiAI=9TVi%oTj4&zn8=2ioP-?|R@-V`2TAdbh`d>>UVT z8WmGIV~Yza?LJ|VP-eb@QeVWKpf|B=-t&L|eZ6)9EKJrV5lD?9vUH3yTN;oOsQ4+D zrT%g0_xL)z0TyIPi{ORm5609ru?R$2f}HD3QEGWD`GmJ9US@eFp}~(S?(T*Rc$`$) z(m~-VO%}*rq7Q8zg#5ft-4~AEPGP4LRG+r69PjLmeT&V{%DxpdRd;DyER;9={Hp5HCS#kmUa7R}g69iKvDH z+gLZ2s2CY-XG%2O-Q7X4w^(D2eQ6GK#-8A`1Kr>z%nob?gdC%Aapf5EB`nZ#3C|ng z%WLD(#lpXQ|1bsPV;Z$TqxP>@MMoBw5))2WkNY2EJ$%oF5^7vPZr+Z=S#5~XpNCa9 zqia@_H>Qbw`UTId`<;=JvG6U4=aB0d)c&7zPiRD{jMi@r&K$6S+X zk;G+l%n39fH~oP$Q*}$0{Q39x7=`lzL)@Y~bz3pzgdQW|!$Q^PZwT{@oRq0f^_OP| z1~%VL$%v_b$UmxA!uF??U5sCQZshIWxqQbdI*w8W7*5f667gQdy+*yS zKa4x1C%Pb0;NAQOeOp~$%IL)Yhd-{UXlpNZQYM3GjwjzUx95ZSyb-oDgKX5}U+M70 ze@?ujJaYcKQ|RhmWLQ(2lKb;b@Mj|yfcm|NiZ@l#55kCAFf+7&98c z?oie~IS!d!38E?a(skw0()LeaaUk-`6YCY~S3{WlT*8;K92)1uey9*Zv&uLma+J82 zSR4k*b{i*2=?t8se!<1$cU^Wki^`kl!X-})G#brMNR5LU397lXTVE(U(~%)iRe!9T zjqZ%&Zx?qAZ0e^nDMhQ{__!GlL{6#{?;xM3UNBW7)4~WFeehFRa|t-dLf+OZOS7itP7fn$6#($KY?RH*YImhVKB-hPAZoiQOq!5mD*Jhm2I)a^Dq=<*@iNHwoT&Iv=h6?dAHj8w8?Dy zV-x_%0qi2|?eO02F0X6mO8&T+)x0+p3N5GC-&_|U%%Wsq&vrhYEG`ugaCUZf1yya7 zz+(fzql$`(5_CQK-v)UICbYQ(E*x(@eTa^#Ci5?w8jD9p@0C)<5~ShsUYyMZMt8#G zq{%ujZ+e7mAUmk;oLjOYW(80dA0LTPrw(nDK<(3Muz|yB%>U2f&n2Kr^-Ufk@@3}1 zW{lo|@!e_}C5dRLPXH@uU0Ug7c;K17;j2t7`7^zO z4fxnH6y+i*J;R759Ebn*4G^r27|*6*O9%^(L0;y-bsZ|J*bWq52PX#U57)q;7P>f5 zOrXjlvi~SQC~PO@)}IYa{Mv%zYE_JPgf8<{J)>yRsidGTzIU0BNBiYiZJuObd0JJv zMPSyYm*XUQ(Ej;6(qP`pJ8TARDE=FFyZ+xeaODrjv~m2*@+cIu^ohh*l42|I=?vC4 zJ6O+}Ft4x%FAT`_2xanuzpxw+8{c>F8p+j#z4HXe)fCRjAAfsnp!MxVpyy7hQrfU= zRI;g+gpB$2nm16Eb=~mm_Q9E*Nze{aE9$R)@U8WW@a+N%a;ymhIDl|wUpf)Sl zeQIT(rTq!=<;28#Sx0%5baWm@J{~nRs*ZL%YvG;2uVvzN|ASt=f$-*H2@|I`6`SWt zyos&G;>HM7AvcMX%JDILshup;=o^hPTEENb1j4r!YklO;omdb)!Bn$_lI zc{!=YXZ$x&hvN8c&*DNYSq=gsiy2?HlTsG{li0*FbnS|25Y^v zn+H?(Cz-*UWs2AgKV%^p3I|L0Mc6rI)@?p2sy7P0K>pHc zcdgz@C%{%ShxWa2OZNCL-79Lhd7Za#&AbF{a}pdItkW_i$vxf7Mz8?oKjWLwQr|qFdfNKu<((EOlUr3KUBw8*OlN;z+yPpJ8#jRRg~b0*Xl82!J+{b#HvZ!@j2hv z**y~rvKg=NjrfuFQQ@}UR+_&U7j;-w>i;c`{H$@1prQ;}3-7fZW#1pNp3~9iP>_EW zx@f0oBvoK{ZgpUqz&*V7m6I&29ZFxPSJfpJj7kX!=XGz8LWYEAqtupOCj4T!7QMG= zVri)JIcU>#)Q*m?y$cfyi7*z#BIe;MA`*bvS4Su(MItF69aMLHwA;K&*Lz%!ZxOXk zal7}0#&lK^#haU`6Rk=x-rjZgdY}L{*0mk6(c*veFc2(ZpEbxEgWbW zRsdEO&!{(Yc8@^j#bi12!8QTN896^9D~lnb3-YKVjf+~&KJ4wZmw5Ob+z~u|oay{5 z$!g<%7>clRKYDAL_E=n;|L=b~Q0)|!)YFs|!3VgUy2kfFVzV*?UswiRdZS+QN>!}1 zCOJT7jVQ^zP%&?RpAa{@r&|hcQ7&NTYXC~^$BbGg3ug6UmY=%`Z4&PhYk2N{t&`j~ zaA&Wk6O0W<_ScoCT^!@hx3|8o@#*ms3UqK*Vf0qDHxV4-j1m)NhLG2=*{`kM?D<9i z|JewG=^j2XkOpJy)&Z~$n#TLnB^bj2OqZ36rE)LBx?4@TL%x&bu=a9{8IF&SA3=Bc z$z`5LB)6@@C&_w%^rZrbK!8Qq6~{#2_`dhw-?P9vfDtwTu>bv!fvKq}pds;WCYA%5 zg<$|?GaLe#;1*y37dCv$bpU?=q*b3Wk zF82Ts+vIlK-7Q&d)2CV(iFmtEDlpCdqR2!RR5oiPuIXM%BDYTiSK1uP{*-lk9dRe$ z`$cfLX32LQtw;bKOXg3KWJ8I@UH>kbBLt0P*S*W+Djv?^h-HaW-H-}m2E4$kd+}_O zy0&fm!oKuMhZeBgR-&gX8@JQmtV@)EUbj2>pd8fmI_UuoqsQZ3A|p^CH(bnU^?0Ys zx~_G=9L-E(2Sx*d#lx;z`z^q{4}oxn=#B_X&^_E-L4($Q67p-H0OH!rmB42X;3XVX z&W`JKE5L+7xKKh!RtCw6L&$ano%k2nEmTDKg^jX@A+>O?mnT;rOWWY9xt|BHEjx z1XdV62SWk3UR~%#Zib>(NvYXhq-Uuny?{btor;z9axEgPD8?sa1&XiaFrVrwjNc*o z@Bh45IlKEy)fFv6728kA8tX2=A2m9>F_IeFFPZ4I#kWPmUX+p15fxyscXAN=_3KyA ztpUO8vhUNw6VT~-u`>xH?p%1`o9QNbe9kfQlY7sGM3Fe8gdS|Vm6kHhW(ZT5g*8bZf(A(*t&fgek`T64mdJlxsL zK{uBz0|~F3)%7g(eR_Q6Wv<$v4vzku2m0+I#?fu@L}I(YX*!nvH_W-JU26f{1`m3k z2erEL*D}KXXZO^Ub4ZX5{J*cwu%6Z7@UOOvCL8Y>v-PXHj3!0eEG!u$V`THs)+1qv z^e>E(3MY1)+6LIX7faKe2A)MS1gs`0T=wgS%}1ASG}27dXGyYmRRO>f`4>oK1tQ@) zJWiHIOK$gi_Vid%&Hxj+*By!tM8Yi(my6!4{K8GK|6N0&Wh9sB|E{6i6d*5?BcU*F zK#LCOcR)~B+tM~UR?W{}{7Z3cUS7En0xJKbiJ?m)^xgAc?yI{uY)ZM4J6=_nOE&cg zw%_yKM@zddOGry=0X%lvBK4!IjgC$#p4zqnCs8|M0Wy@cB~ckP365JM;OR%fV~~-S z-iuTKlU$-JFFr~wceUfvWS?qrca zvOn{d0L>EZ!FiBZGrJ<^6m=(%56L<6%oiR`!`X z4Gg?`*oc(_LS$}}A$)+1fyI;pXvICe_Uj-IUf;)iAfy^?|9ip>0C12`2Ex98?Ar%u z&>l(AD2A(k?929?r}Cv^FkT;9(>nBe{9i3V>7XKGcr+?%xbDC+h0$%Q4gU3R${6bu zlmkWvYzYb#Kfwc*lvIRkRkT&(>Iy=LFHU6wIzca1?ER8ghIMOxtG2#|qZ@c_!kJrj zZJF?!@WV7d;DRmOOaR*Sqf_5)CpQ7Yd%YGw@x$az$K}{Q8ddBLAjfaPJJR*J*(`5= zDj}(y8=$xEDV{6p&~h6r z{jjn|sVaEqJ>Nk7!Hp49cLWUF%l)NBrT9${H3!sLx1L;lrA0*p`b-6Vp`oEG&LYTO zJ3Bi76~~4D4B|V0TJ_?}PNG15HgwX$9_xeGb=}NH4NBLifNryXZm{79dl`Yi#bUMc z-kSrzverv*p0v)C|3!A5Cy;uS6w)zS(Y?z6BNpC@N4hoin|MCcC*F51M-wt`EmW=4 z#-^rlh&623eyYXngb`r&>3pka{VX0}g?UmVFTZT_hgSlntYz(jX_`9~{NxZ2TZkvk zkByCKf!hYc5uYWAyM_7BcVn--JquYRzaV1a|nBx?k_MH#Ti zY-s^F7swacd?P{%PUX_BJmi**&U*0llr34OiIkL-K$=3+oV5v1x zJE}A(bL63T1?imw=94Ce7aH*gF3sh=A`4BAw|gL}L=&h{z-fK!`N3ywk8{lFa)7R! z7^u}wK|%)jjR!v5iR5?3@bX_Jg-H=&VZPfVgF`G3W1SVaoq#u?$wS86#1DwEw3?g> zldOCI>jN%eZ(#b9g3~rhC94OzDJ|k zp$V#bRpxU&-^j0B=eThuFTX4)kl^V6MWgj{Q!Q9elRHgrK^>ThcP33!7x}HNtz4TF zQwCYmW#D~*&jOfg{uY^-Q9l3Ia)l%Uu9>5qP)!Q(VJ3uxiY^;M$p0lh+h9BO%*yGs zF>NztYcM1c$4=Jsf5%Z^9mC}y2Rve6Ys~vreB_x(DH%CKx3c5W zr8QA(; z%9;Niz!TEOrZgmJUED|O3}M0_wea2R(-V9P%}w0ho0H>SNK7$HsDhzE2?e$t!*^;%x@%77!%O?R9+&*vj3b z%4;RWmq`#nIC_IvPSBbGnP2~^A%*`)CEYjl*&or=VPGG`Wl;#Kk<5FzE8Rl2d?kbW$>HKaIY&~)2w_(}5N(wv- z-w%6)tyCEgTGY#1}r2^s=ruc&`DkQFSg27v8SwxGE9TX^{S z6%8VVE(kc*zS3E0B>%c$GPrm4aU0R7QoRYw5F{@#fQc>C)O|O-ph|@KJvexFTgAr+ zOzVQj;K>kG05#^UYXW5&-^epgP42!~?#9gJfAqYiLgfg5n2 z)y0Obqh(g|pAW^arG>YaLkY@3^0W$cs=za4Z(li!KF;bPo`fWb0fu}0bq*nGUM2-~ z;37p(1^_zX)LYytS0`nzofi?d>Jx45U?bSQ@P^AQU@90+;Z`c122!KE%*@VJ!;`a1ugpgOJP-@h1wFViak2eT_6MaX511M;S z`%Nq?ie}Ld=q!>NeY|b8y06AW(A~X3=`1Chq+<`H2yoXx=XB49@q{vryEQUpo*|2b zP-`{Q-ct=qpT2OqNoK|m~6%4fxwLhbZP&} zSA@Vg?dNc*){A&O(pD|t_AlGdF|VFC+rvLX#b?q7CPPr#Y1LVsfITn@b{I&&)Kpa; z_e})`2L^at_7gp_H94ePOF`2@2j7eT7d8C3fdT(o7-dUa;dS{DgJi0YxHkQqc9WAi z`3F%sU|#r_WC?Ju*;w?2Se}w}XK*HcaV(=$dZCd&{F4=-qmRs2hVBaURC)wv?%)z& z)A;n*09g52&SVz^w^q{BwD9~)f!*Q+W-Ez&JvfU7v|i139=d5e!H#N92<&_N{z=1t zt$NNC1Jd+nvfoi9s>QRSNgl1buRqRJ`PIBZ{3R#w5EmcM;d6ft^oTc}T#tbMT#dkI z7UpZ)uNnk0;?32Q>mJY~ot>T{qo4pA;L4AyXpn%4cl^2b(bzou)~v=)!k_B-N<5H| z+4!dB=C&`qBgEbs4ynDh*9|)yE0rF1baZ@P#u{%k>bSN52Cuuy_u<1(NC46cY--v2 z`?FDWVlF$d$Pq^Pa~d5EJ;nu^yK(XG`g(hd`hZiH%Xv3WFZhpMcqJ&!fkflHsJLvQ z$+@^aL9c zNRwjbd}*yGHkAzM5-g|Tmer)ktE;PF0)>+bk>`#aj@}~v3dN=d_Cr<>K9rU9#uvTs z3FKH4?;Qf0>q~Ufeef|VXlgEW1|Sp{6#Zv6*SDl~csZ z1>+!~rl=ipc>X)&IJx_qKPOVj0tDOT8e%S|6^jc7d0d1p4zOqKV zIT3Ue6lYgElUqRN8)s6K@)0)3El){V*$EsT;8LT2y%L;}kEF6R4uMes)i@^qrYz@J zo|DrZ8)D;GSm$bW2e;nO9T><3gPhpGl>oHo1NhH&wDyos_g3IfLA(igLM)s;jg0|w z18k&Mg9Q?6Tp;@mwEtj4qt>!4YoK2q!j6O|Yv6Uztcq|J&8`#ADq0?&Mb&(ft2{_A z1_vN`7hGGwaCLQW0eraYDM$0w`C7e%1^9+pG#&|hbYa5&d0S;Ir&17ry9Bi(OiWTr zf|$27&}o8W9^n-spz>amlG-rgrw}Oyg@l0c9S$(&)F`>#7PRWeYn^Jk?(beC@o!O; zI0c4AddWw;0I|NyecwTUydRlaw9s2c$6knLGbs$+iuDf`ML9?hve(dW-2I z00cc_XfUiV-ZSRc3V(yUva{{|}eNlYw~fVJ0%#kt6W z%ME}$e;9pl27%&Y8XbK6K!aZoCia4%%P}!A!ND(M`_G>(otKNYYI4^AKu`ogP;4x4 zlh-ZUG+P7nHP|HGX6w6Oy#e(KRjfH^ZN7j1UIP~;9jRPq&5NM+ONudlSoJYuj1ZiGo7<8cd z^z;1%-49C1*P@a!yzPcHDO!K+_jVtw+BpN@1dB)bfIgT@2*c%Y$(-Z)ZXB}Pt#v%x z(m~7g!Vb8|jR)gPf!GzSeCwx7*A;z$^1h=}Ey3q@*cb&$Mt}rIkbJxZ4TUzqImw=` z`@p*=eSp31w&DPzsVsrf7Z2QT02OQ={khgC-dE&v3A6+Pa!7??9~$yP%No^Q;9|oh z_Y!b@XHuub^S>Oy|8y+d;`5*7ok9qNL%Tg6qPwEgx@9TNZ4ZzUu%L997f`qm8c55w zuXu;!jOUv#{sEhmRO<*Iv(LR7q_vqh_P@GZ;G`Qnizbc7dH4BZL&$u#{~aJ~O?QGB z3A<=@06%jFb-PXL#SAe1I4sndgOX&}ag^_B{TpNOFQRnt00URgI>?0=c|Yb9`GLed z$#FT?gLq&w9(>g1`Ho|Sq{V+&Xx1rVLIYsJ;fDQ9XzoRXmmJ%-LroAf351t2c7&F) zQ?EV5Z0cJ0S9KQVK)YW(zw~}%*N)rW(>yPWrs_k8L(+WMu!;0!PHMbt{j4~@Ouxlm6u& z4vd;fUOaHwdN)xT!@lJqb789Y(0)4>sfU*KC=RFF?d2^rH%4x6?L63fR~R1Kr)*?YYIl_@E= z>Z?JPFXy22sD-k^{`k1bEh6lOok^Zbq5T~P%?~MS&DuP=c6aWNl=r`}4Lg(Ka$du4 z+eDTbc$e1jJE-=*j5QwKw$oJyHO!#oiJu)|C6R&IV3Z>J16j_%&lCT^7if~8?I6j> zz+|w@yF9rajzK$KUw_mI*fECI z^9j(%`hq43)OJ7F%oQ0&*eoq9kdcvJqJffRtplV=UVCz_nElW%I(cWDkl6+8-ciq$ z#iZWh4o5=GGVFIZlb2E(CKGtt5Ya1ZHq9x!pl;0F?PH7#_xb`i;#)Rw5v1ou!pB(f zgpaNubupeAQuG>v!S;FFJ9bj>7XKrWv}1E&<@bKb#_j2^*u3uFiLbLw-GgiMYKE|W z%rK_Fj`{T^OI;n&TWml&;H}lQ4Lm#)c;g;`^SX6b^D1gO)8A&(0BUZ#*5MD1ar7)fC1?q8 ztBKbanSI|4o=U_k*!(iVXC038_0;VkOGA_(>Y zwVHT1ex=nsi*Hn}&cTn*ii`H^p_k8({|2x!BhXh;P1|CnuW5hQr+97lK6i2U!R_En z50dZ0WIS9u(a%yiNTbQqu5VkVlcoFqwv~?anNnwC?#AMk?%ilodR%8hPJ-5V62ejW z<}Z%Hc4$mgQiP>B<5WiGn-2o_s)|^Tn$?OiuR>B#$sQx!pf?Gf|g!XZy5s*3$J`>Q8+ETk!Z)M&Tla} z<4k4-x4pY`?}>(`QsAYb<_eN30XoQ0a!|RjiLA_h34*9^KSon{Cc7iNCs_@wHhc0% zlGKe1o`!tHU?BC=YOnFsrZf}zi}Wls+wC$lOEQcPAuWHDg(}&7^gU{pcGp|kZ_zGy zGTSP9;3X%_62-9b$aJ(-R?QUNTr4@|-HJ05pJ~+uQOlACwZoWr!)_SN|&w0Q4R{C%wyDAMlMstKKFO^x4&t0B%O6) zu|9KhPH7pu9^r0So={&cNZ{Ubkrr__&W=fpiJ|3Cc}>a(Km4`k>%a0ON3`bL%$3)< zb_|^Hq`dMJ=hDLx7{k*Ssz2%Ct5qTtoeaca%jx;-OMbh3ws5lwtZNDtzdXRpWJk_B z?Lv@~lq7&tlvi_Ex65RE!`j3tn$*cHGNKT&axeND%3fBOuTbe325$*X-Vc2!sA=k%~}bmEo;WKvBuLs8JPQ%BB^BB52k*Ld&PTJ ziitvS($nJsK@MJGPn6@z_NT|p_T3ry$%So2HT_A^F>!=oK;*WY#?7;9z3|Zk)j` zZ`M@jB4H&J9UbpUD5p0VDDj*V2PSrabBX6J!=F(Q7P_Uo5eXlQ8xu>qhR8WhqZBbd z-Ln(9j7qaaNxGgAKo=e~LYgGiA35qGm-b)~zQXm#V(<&Sz{6qIxYg>D?xOw0q}JBP z`Dc8Smdh^JIym`(IEAdhH*^8Be^Vh1O$J&1%?QvLRu@ z<6I=R>ndbWujz>j7noS%zvE45S9qxGtQ1S~Cu#efVtlPCw{YAnx@ecE zgjX1Z1IUs@FNlAcc4^9zOyDPfr@8j|-@v2_6qj_ccu`g$i6U(d;Dw+8w6J*Zmy$w! z@st^DrI;kygtVo7P_sfS>?4u$^JM@9Ep5L=ZBe0o`3acN5|(uh&~CSh$rk$2t1%}R zP-cSdf)5BG0B5wH!tL1Nwgdq>b%W}8&=sM+6hXJe*>#{B0%KpmDSZFiU2VAT50%*> zbUnV~HPiPX*#yU2x4R_zSJXtfOKssl!z|H~>-XCom8IrGS*Dq&#YHHs;hFLZan;6DWI@o-yr++V?mW0r^1NkIr;8Lvehp>;d z$c*7yxx}RULofl`h+OEBTT??p%|a0~q5f9YhmUE@Bi!}LP>$TojkHwiWH~&81LUn% zvv;b`X9m|6ankn2kXs7B?i@yJ8fkvOggy&he3FQOGFy62_#cQ6gIJld)YE>q?#mkd1P@z6fZi!lCYMDO&l(yU^Mbh%iCRHypTr& zFHh+;TBG~ZZaizJ`d|($c9Ln#{Pg)=E^Bu^03pDOSTt!jVx-^XD3W~{P`pb~Qs1J>vGF*_w&3@O` zHuopnBg80N+1VK_?pe5$VsC%0@bCRxN{boC_?hos?LCY}YdvqYPcyWyOp8mCwk1d! zpis<_o;i9;Ns<%ldd(7T>|Apkx1y)etZt*?=@nv0i2SZ}BrZn}I>~pl*Vg&yAhU{b zWFtkAQ0QwvJ~z3n1z(Hq8!pq|+$nG}V}xCAe>u_C3Z#B0`%0EnkU$x_gB^k)^Mahz)l;~i4fG?gO*Y{jA#axA5Pbw#53@b}$aLhlITAH?tM=X-iQXLGoy z=kh~%1U~7gyBWz?C=Scz_T>M4*<(o=A%-YN%Ab?2G@avhxnxVy$B4c-|LY6OJLB!3 z6A$pvu66u$9Q}GmL^s^-rD-!0IEK1|_8;N?%(#P(Sx`Eo@R@QyAAoXHv;MfpZrzSx z!D4DD9z(?h>?b5FEDV6h>7T>-p6<^ephf2{FGftIW9t$_O9;MHi#ka6_Q!I4kqqEU z(7`SN%JUKcm2y8>a+@E=iR}H^Ea25%-*j#6zT$m9aU!XzHA|0<43UQ$1{ETh)d!G? zRL<@kj97S*1(#U2F9G(5UqH9O_(Uhku+-*q)lGyKN%oTlvi7rfw&l9}U;1Io!G!rQ zr6(On>!)HY!Yk|R-Dvu7M~0lpVUpAP3AxkW;bwWY7JF~qw+;ahNA_|JzO{sbdIAVj zDr?Z88D%8}&BAV@%U6aemd-rNv$H?5-tL=9%OyATV%lo%S`cO#)LiaXz5m9~&ecF(`btvN`4@yfx?N&UF=)xI<9266tq26k+Uy!)E6y~=(^!*;`QRnve%qLL`tv-2rM}*ypadz!vkrjDVd#Yyug3u}fFyef-k|hr(aYp)I(e@X#tsc?HXMDJoflskGpyU#pGR$O zV)sOOD?+i6_s^9&8kHHV^Il||K8eEy3_*YZf8+U;pcfV3T>i(AKLBE~wfPGyl1QJ9*WJsv5p^6RnTMQR3LaweHDdZlf~KL;TTzJ2 z?BzO-rX2Bg;Bnwa18bkuz~8q@SXEVVu|Xl1Dazz#Z?Rb3{)#9&%!-iQ_q3D@!>8CVI#HKTF)lFedQm&#@{dG%XZdtdyLh`Opw~H z-akeOKB4x(6VqhCM-I2%W$_I%m80EJG|K*hrNm9n^J0@k*Az=;F#`r@ysCEw%in0i zLgfIX1191KT+SIf{u|nf6pXcGTd&B3l%(H}Zs8q8-A@<(SAnJzerG@o3 zX4-DbR;@*APLjciLMzrOJ494%)lYR^H>ZG;DN$c zTe9SzKlYf>0 z#Zzyytf{7!kd$OmzxeTr-O22CM*&&eOZiy-FDj`Dw%;sx)i@VQagtntQwWUpI0Zh0 zC18*~NR2Huf-_@Wb+S3i4o=+O5X%j83#o?h9mJu~lIJ05bEVrNL%yK?GQa^BkM64h zl_bN-kANhI7@iE zxr1^9*w8kGG@HI$aP6E&uXsSqtBSu^&i48n+Zez7s{?PvZ9KACLqq5-qN86>>3`FR~oV0SvOm1CUbsw;{o$;8W3I z!9~B`bf?g6tt=@CAYs*6Pw~B+H+^0&U?9WpnV^#Eoi-%i_~~r$7lIrt6v5(1M8cFC zOQ!FOlQS(3y~L3>7rZ~x8ggsSTX;xfrL9SPI|9%tbjzj0Lbtv^YbcXph%7x;R=vQa zgJnK^Mmv29nMk%XOtbR9JmdjA{S_3nHIljfu1nU@_jInEm*w$nU~*>c*j3Q+J1dmW zFUH_`5hgvqW>}Z-Q4cz(t0%ULV?L|7#(oH5GcCIde2cVbx>9f{f`!0c|E#`9&?eDw zSLPG?cu_@_qLx+S^&|rA4ce{z6J+Yt-q5)x?yCQnQFS(^4f~8)+=T0<585m`DU)! zPYwnJPcmVzUkaIp45F?!F|x+VtuNFX-XLSCn8lbV>x(XB{~uZaC5t;c;rTUd5es#u z_4prcn(;1~H18*jCE5NSMRA|2up>IEg-bR3`fIjC7|2s#PnY1?YDEEp$67k#U?8GC zQ;z2G>}R+Nqyd|`UN;wZi=b@6@1^&NWJ{AJ$)7%bf&c}}*)6inpFE9r8x{KBgvlG( zeLXM_$pUETB3+HR@k2I!JMS;lxqW`^g}AK6yly=8zPJ|JZlj?)+Q&Kf^&u96gAATN z=?uM!T>Oa0hVbg^fbEK+5-me15r5kJ0p#3Q?|i;RD^~vF!GLtqC^3ifQ-@AcVXT{R zuJb10;ObKkaGW8K;pU|Z$Z_s@AbxS4)*M_UtGetP)l5^o3Gtf6Neata8DVIXxVl@l zU?5;527$1d2gcRXP_*BsLo8H$V16(@>u%O0WlxC>k4JnU8pfU>hx0Q+1lM~WF8r-T#hi!ko-h*N5$M7ql^<#U8HGPSD zw46V>9}~ek>h{D!zp!g(9a>#L^p#*Jq!_`rcI@$JY&5W}3*q2%oJpN{{v=F=6U**t z;27uQ5&~8AX!()M)BfKNEUQ zxBt-hFPl>6G?E_$HvfE1VSf0PPdqE`mGXH`zAM1DfPf`FmHV5*+pP9SRK>F}k*=}M z;6AdF_S2Wf$$Kfntj<^v_0j^Ky;Jzy^VhRG;e)I8uTzj8*4bkj#syq_buK@-% zEmcvsWmpz5uN%|*_eBT!00Pj^&@eD~GaN0SM>7Cs34@<3%8i2u< z_S^F#@_>a|dQ2li_1+uqwT5^>><*zh>~W#;0})v*)5wp$*+WiW&GkjsARNCQk8fO; z;P<=|ceVJnk?$1e)H-qZIL1m4d~vA6Ws&u%<5J}xkrwqb+i&l+t8niX*vf2f45qb~ ze7Px)3m;ZNXncsN%Sc70#V^E;+xeGNgNJfQG2zM&t*%8O?e(DwnltkVC{G(Y7aiyO zC?)+l3`weBIu-?U+kp<3;h%JR!#~4E4%5)Ie=Kw##t=X6#al9@j@@F5iChn$4?TH& zyw_vkI1g8^Z=vFt+>Fgjc0~b?l?&&X5%ahL^%ZxT7Xk&t%=HM?WX=4+(x}p|G6->t zGsIdKk3@#D&*!|@5elV)s5Owk!e`3J$RG!knwy%iZF#=yQi0d|_ZA&~FxCRo<$CR) z;|G{87)4%}{*K}eP_5`Qor5W_2l-&xCy{pZak5f=ZJ0O0_VeYOA0nYIf1;pC5Kr!O z&1m$xdxKc282mcl>x^rImPF?OenjOi$EaGYqD8NfP~Yrt;@AspWUG(A)9OV$ z2cf$&S&$kf2J5hh&!)}iR}Mf13&D@*1wsmiNJ&^JvUklzSMjEG`O~V&V6`VQ`3Ern z#_|J_Q=nO<%y>shdF_cvnE}?a&Dc44s|>`ZiXg|F%FiPIeNPSt-9UCKGNqim{HXfj zYsTIh+A^6yzj%pCLMg6K5Ep%lkJ@Kj zzI~pDd(rXK$%{$IhwnG~S!4Wk%#oZA&X7x;{yNr7*)|HMP3#j}V8&M@+F>VoIB5C@ zZcd*{saV#L8{E4{omZSIy%rXW&C;{x{~og%Q=67oobJf1sPlJzb-jR6d-U#--3EB* zKit#J%)JIeM4Db(Gc$04SbkIsluW=Uy>Iof(rEhiSnj&4t;g-1cevhPQibeizDf9J z&v_zIA#!wPv{C2Ai4Q^`ADND-Ri)mlb32c3nJgIl%Iffu_GslV)!RDj$TL3Cx#hMdbTyT8KDl}VL}Dhd*(a;QZaQ4Y4a_sZJ&VN zgE9-ItFE>JuQ@Apkm&tNWi9_4`Rmf7MZh+r2jiGQ z}?!rx0SZ(HyMRGM8%Him0EnW|PY*t5~>lFDU#)Z{!%U#bJTUb`cz{{&W z<-vpAC|i6tJ-l0avpEX^ADilun2h)nmx@Vr)Np>&yFPS7y_P22jB1>%w_@Gm zPpVNG4hEh*IShr|c^)NHZ-L3Wosvw^o*6E71pY6-$mneO7&D zyYEQal}i6}<*dKk%H1{xiGGEJ+a~~Wx}&@43t&;G;ueioOh%k&Je=AP%Gg=r&b1yc z>fO1G#Q9a6>eAr_Sy0Zu>k*U)Sz{T~KAQTy?K<``s+laXnA``JpyMRIXsB8?;OMXN zSHdHweMtkNL}BjX8ubq^13&=j{32V;Nw+(Fg*C^PTqW>^bv2iyTbniAMAj`kc>TIw zAsUWqu@0#^l!k!K6_{)Yqlg+p)zTIbgy-wiVStNsbY$cu26&?+B+Iw=C?P?uk5$Jw{;U8W3LfrCKsAa==&e=;*DUe%(uzB}SLi!|`2oVB|X% zPJZCLsxivw(?Wa6UFyOZ=p{4=muly6UgAQSjgT7seoh$<3RLFH{Np3^70EvQC=fi+ z__U(tJG6(?_LmtCH!ABR&3?oyEM1_=?6?(XjH{+9QB-!Z;3?jJhtz3AR&?`J*hS#$p8 zWMNa&6Q#Th0^Y*pphKqYVK!7pvq98N%x*n~+EK{n;{H$TsAAL`O5#7C4)5LL?&y4D z^29h@(em_H_Rfp&6g7%ISgtb?jrW(IT zee_a)k&hx}vY^xTCFoS#Ou?qoZrn-?1j(6U;c0T8J{{mMYTlI2TAR-Twqnx+uoEOa8 zR&h9fZU5`Rk&AqCT-vlODK9x8p^!Y|nNaQTIy8h{3h<=^+e3vsWP!NgpPHcQIv7eC zEeN!oK!thh3Dm$sJgh*s;)|O5v2oF8!kvoCEMA8AeL$OWk(+t?oAc5MhZAMg@g9ty zj>AF{{QRV})-}g1QycDtj@X?%>Lkk*TX8VNzhJuP7@%(7_Y1Ssayh~y>1Vomy`!8o zlKeU0Zoi_%>FWI;7?H{-Em-6W&kEu^3ci8JhjR_w%JXmQNpl#ShW6tY2L6#~8L zNr^BVK^Kt$JtU0^PWDK9Nh#-Kvlaa^>C_%@UeyUPzZQBWzv3W^?3Q5KMF`n8^J{~9 z>&=V3&^;PyVeWTq#S;XV`+~!g#mfXwOA!w*kkXqj%LVK#!zl+_n}>@(;^?stw{A7; z1O>c^GB`bLxQ9RVT99hKAg9dnJMPVB)(h`p)gQjoh zjVIJR91rw;b|n5(TlD;_BYY=xR8A#KOLjWpSs59n6zLe2*9_&egCZ2!AfyysZD&a97|6NwkA0*6<_E;ro+3OCHCg$F37B^X zdED%@v@%>>cOrvrwSX(3>-_B6 zaRc|wxoRdY$Nh%s!3Ucx`{Op&I%_$lu+JmirIK6ba-s%L4mDdbBg`Gw&%TMKgy`!V z5Mi%d6Pb0r?OK)mo`sznUaboB2}Q^kwX&mrXQbC%n9L@H3fsU}tW|ICDwj$9Q_l0! z>Fs##_4puS;-Pn@x!AH!8ob~5AW9Jl1)a!=y^y04@wSVn;W)_^yip|VGc%6x=PUV& zyMOkzAQaX)C!O$RnRKiAbKv%L>NRfJWirFp?tMWXco9@Y@BdusJNeFR`3>VVRpTPe zgBD8`6idefgS6m9^9*IBdMsZML5HvY3+AB(QZdA~%i;M08y@1=TeCK(0bw(I)LOXf zA$ku)s1B9U)={Qy{@+Xpit~38W*-_a-kp0_miZyADt& zGqWag%q?=`=-+Z1{4f1^c@Tj((rLO1qE)Sy#d#3B;2oiqvlkMZYO$BZeZoP zD60o!`7}aT%;p{gQmfImqRX;kFL$9v5V+4ZpKO=5igXWjYH%lSzpv;@qXwK=qxXU0}qm7tkZ zagog5|1pk*@`89`q?P+`v)t!g*l0!QOx9Ce_&Vz+rvHqh(d&3-xjQMK^x7x1 z;A8Fy+?wN;73)6HpP%u!l@B@L?$tEsuMT0e14DF$@ZhdLZ2HzNE>EM0#|XAm=2u=) zv+y7-QGWe~Cj0pg>Uu_BJDNdEWiK^peUvEY(EkWpe13I~vF4#*Xw+&;FV+=JQR?Xa z@{Gc70}>If8WY?&TiNYv@2;_-jk>mb=16pKsSxVY%)|V6G(*tKD)Cuf^CzLy+y{aN z#IPq07)xJ;IUpvh8Oai{>W$b9E`8qN+kM2fXfsR(`vmhvY)EsuElYd#D}I7kc3sHq z!h5xMN3F@L1V>X!P#sn#tYvr=Ey>_m+;uHDn2rd{1ZTN*6ZfPuse#L?c?8qpI5~5X z{eo_<%!-`5of(JHJ}@co1_?GJP-69e+lbpJaJCHfZ?$N7-uA~agLZopQZZI|EP01( zRk7Aee1aO$j^t+u5BVy^PlvyV#6a94RSCuM`q?rgx#ka4OvmaYEt!xTL_@4; zD`pjORiQn4Ay*e}LB|eK*MV+*eD!YdMX>Sy3yj7-yIi1dAO++;X-NpZld0piz+mt; zsTuUCv-^!qx}F^KSe&%GT5ccYBJ*Z}%?io)fG8Sx5zU!c7q9$Uy_~V&%yrI*HYQ?< zdy^6^7k{KeICi%9H#fqixLQkR$Jy}(9@g5qqZ*#+i*uSdt^e%D?7xnhmKX;>k0-TH zi1QkRh zu(d$JG(s1TBJtL4W`L&?USMC*srTIRO4Kri!bR#c03l@7lb z0?feCMEodfio|WG8z-Yqc`^s5+~CH2F2Vcx+2cF;sVeam38$iG(+_vi{Q$z=Z>1)9U3rdKwxUIyyRXa*(2hi}YF|?v>yz!0m#K zD{xfcyKZIxt!zo%Rq`~Ib~f9uFKW;-iLDmaLun(y5n`66Be9~f86MS83z1jwMU_H^n*ChY5GOC%e86 zG!P*J{-a;6&slqb2p_|yN;;U{b4G6;s3R`(T2Hg7C;mcA*J+HLlhdLrdwg6m68~7g zfGdIZM*k)a_K45C&ZgjWH?rMm6Uz+`%J^Dp4-RS-DTj+R4s z2WHy@lSUKDZBr4X|ELJ@2X4ckmz^D5INuH50nbE6I)=(;b;JYH%BNTPsIwejX9T&I zr=sKQQ|z@;H+r$o=_a8p>A_Yk|e`Pf1Rcs|PKL7s9}!Bcn;nGxF2N zi*4W2PB{9&jrt5c>7seI6bmb>!&5FBY^0E^5tdLRn$Un;p9|oo)u}S*26A@iCFhwt zAlglckFU}1dYwMR2I3=t=jCQFFdCb29aQi{vOOS3z1-saJ%=S~{e&+db1u&=HLQ6> zf0MTs^O5iAastf0hEo^~fgNzk{;8hwBYBn`hJuUtZ?e-MhiRJ#lDs6JP^;3tF5R*w zobSI`zrAyV^QUOgEOXgvZ5Y6bXW{DWn!#>84t0HRE#A2CZPBS0Z#{g-AdxeL*t|AN zr`Of3tB;`N;NiteSXa%GyLDAPr)ZXrO~mOwpvkIkK2@~v&irBQ^f234^irUR6b(9E6qT{1-0$xoguaNE7_ zZ>cP`qPk%D_3-U(7>)~%xH+4onl^oiz_jRy5jU!qxPTW3lNW*6ALIxC;py5E=H^(_ zI;ziby4Gtn04Qh$o&z8jqi=saCp0ra2k8)7$+|$%dR8L~ACSEw%GemP1)ZZgCj$lQ@A zjq_IhtM;-|Bo(DxeKYRmC}kZ+7*JJ!>f5XHjgdm9r0Vm=Gi&rzx60C^WKw#Jt5;hvo@ zaE(hAjOldm(;c3R>iZv~RtU>ZPM=Zw&t7=#SMa#^dD_KxE_Z7{>{ZZhU^B+kKX>>5 zvkGWC!CeLEef78|?s+sXHvh~>Ag}b5;OL$cz`gs~e!?@`?|7N4?%Mv8iwYwZkb=TU zVDSD=)#&2J;(1}?V1$GC4YLt2YH($ayg$7c$qvf$&ONO9{aZ*x0aR9&G+CC4WU(D+ z`Fm5CQ`@vua7<{YE_(&Yw1@wrt_FmJsIaiTX??IU0%Cjs17O?Qw5vi4ei8XB~IsZKC)5kCrj2EJ5ezk5w_Z_Qx0Xu&Fb384omTaXL; zxcQNP1*lo0Sx0m;8TRB#+7`g?l3$Y37pK%};TvAKZC#hAN0vR#9TvoH=$4ho%Fak_ zIoi(3%JNMhdiRLF7c0oVO%z3@QlHiToWdt-vYk+y`3ROIJT+eJrbvlVkZC_H-siUy zn7=7Blcje%DJX68-q_f92dC{ZuwiS%HTD-ufb(go9gFAJ_Se1(wZ!dk0$sw23*+xX zpxq)9F3O!+%Ov7-pmA;(f<=7)4-0W&G=aEuL$MBM0n29+ou%)>zth&E(CeHXcQ?6S zTjMo2ZB^k{nUvr#nGWMuRN%ZhAyP|x@I|5rN7CSXl8Bqs(XlR?Gp4clN`>$G#NPfC z?ta9ZLEDH(!DX4{ot0k9TQlbcY$Cu3WAW$fTR=vL{`&QF?K3xUH*5X!xcd6`0}ywa z3}?(GTCCSMjuDex!{}+&P1}FRH6G63tf{Sa0&pN+G~;6MLt+t_~wab0o$N2v5#feYif;?*ir@;^ypAMxk1{%nWQ0c9*rMgaH zh_eWH<3hUe%dzU##sDLN6k_MNca2F@I_uPt!Q?YPq5Ei1k{_ zrK_xle&CJe$y8_|V#L=-rs~2Jn)0;E^Cx~xje;+2-p;|+>m&PYbWa*-cRO$tW+=XA zV`7#r3Bjl>>pe~ES{a3gu@P-<#_B_V5oKD~yp%fNbnGu$Qw{GeAo**v1utz47M4Y4 zzZW%a()o&GMCtF>6SqsOt8^G9TQ?s1m452nPHaz7xjvV_#8k9--k(3%5Mp-fRq#~; zlMUa3JDba4t?uwI5Ag&ux`*S92L8wWSl+938k>}>i-`L@uM3255tMc#har9!qHOka zXu5>{C-(<2?Q1jWk^$ZO{ergk=97Nqx6}PZ&o|5CpM0z&vp6nh*yUs!4!w4WR!ohy4%k}7d_By7}bDA5cl4sYJ#*L-$xH}c+#InePmm|lj> zrp@|RF4J~w%U%AqHVxvf@(&4c>62|k1uHpKzH6p#c6i$^HxE}g&%%JM?i^Bx{yEM=4r_Gp z;xM}nQ$TkZ)OgT;09Ot^Z$-lMTy$l%5^T!;vGaJcZJldC;ca!s1zph+oMIv%kbyrC zK(YXjT&K=r3YmRTURU>|3km{=OJABCwm^z0aJPWxQe9Pbd*J}_Gh7MW`SKH0UmqB# z?$?u9NEFx-m3#*4F5IY&EelbaY4*-}dI^Pm?HgWUVVXJCBj1RrleTnKAssnXXNw|{ zG>g(EwZAKNKKH5AJMSY7HWCh*S>T~KoROh(u0Nv|Iqxnjl2Q0M%jeDwYtyi|+wDYz zGTV5qj;%yC&}P5voxLIdylX<666%iRKh#iuq^l;^X&(rA1 zrx`Do6Qz>q1w9&#i%Z^;xh-F}?K4fL8{V74c_D7QV~Y#h6uZ5~PW_NUdo^wDqj9Kj zgUZiK$zqm=5O#w5lkYJ*-P$j!%&6K#b$3X)Zs@zm@)So2Ui-m5LzT@<ui56mxK8>_kz=!y9`j_l6%zA)$#(#medXai z?E~^+6?KL`EhXrG5@sPGfJnFv`x*fF;tP>zVu*AV6c|Bl)jyB= zykIN z3U8pkcslmck14m^l-S;uecCpWpoAb{t=NwosTqm4+AJWRC@L6z?Paz1wtgHmf(AF8YM+n2TwZb_{-Vpt$z-h5`Docoeip{}ccR1$>TSgg2olN6~vaB6iKYq13 zjbd`J!puUq?IK!Rp{=++HT^4}Zj$t-XtCr0g(dq`?8SwiqY)W*m+?sQ{8IhMv(c(8 zllo*U(dj#jgW{<3Tzt3R7-F6 zHA&Ilyn@y@z&1u-E_ENGOlP&!Ie0x(JlaG2J_0^qw%M5mqKEw+4bARgnr>Q*5snXn z$lc-dO62vV19l66a%i6$+2CgR3r#AG;~VCw)|$O zHX)xE2jI8>%-`v$UBMfUh|Eu#^@B4r4FI4DeCSB1sHRI$#X6_Gw@HH*Xs@6uup+BM z%NJtQ%g8XQt=Y)`{2*)TF?e3Q zV6d15@k2^y%{4=S%Yoq1n~h_-@5#CAlt*)bOuM!5aVZ~?mP+xI>tc6JMx|1`nzx=@ zMn88F$LkQ&@HOqF4f3eX!G;67y)8nJ1Kt%f|&&z0+jSk=By2*h^IQLN0 zORh(cK(~Gd*ox0TRSw}<~yJm?bFSQ-5Y#Dl%mq7izr$`C@``RI5 z(_$GZjkM^z8ewp`)q=aZ`5s6EAI|1K+1dFQr&?G@nK@&@8mZo*C51h;kP~2{o%Zc@ zYMcVI!YhyXAO+@BRJFvf#7XE8YPin0(oD#;9k}7tD7=)Ef2XDr6*y&hsh9(xGoT|8 zGeQv4u-j7uVXhuksF1I*{i+*@;asaR)#33Q-S0#YaA_HGXaIu03_op3JQV(vbv~1%&ObjEGi$1DOeRY=_>*Y zobKkA{m=X{W_KaSbI#+{{Gvae2x<(Tu@pY>85Fd?n;M6Asom=cRk@P;KCVw`f#wnvRT}om8%Jr&F0pXKql%W>glEtgbrrzyi_4(~CACeJr?d zDSw%0kNS;4l)Y7kErWL^9BWtZyhCk`lM~xLygXL)EzDL>*i?`1BVD-KUd$BRw4TqO z$Gm$rMXxMAK=5}U5^>6(p%d*w{hs5-10OaNbrX|~mpEEaBt!omXAP1&bx(NSjE8S_ z@2R0YQX%5MUmS1N&Q@sUzrmNHFC;6GWIE;@ELLDgL7xjF`Ph(?mnZ$af@<%X=i7dn z!n>1&sq!sc?PXEIy{J^2*KzfCywG@mnRciu+a3AVp{i~#0e6UV^vl|U_p~=O?{X{G zW}`FSIII51^B*i@N#pK;URR|EGl=wLv*T$OU3w90AYCTkqa0<%8zy4oc{hyw;OXb)D0Hpws0TZDc@V)>=tI&~O`tBS^qR=V& zOCtav0ICCh4!xeXkm4tdAe4Y^nBX|ghs#hZ3nHNi6?X+H!9ZqZCeniDc10~Q2tD!I zcx=vP8fz!ih9L%W0(~-7fa-^Koh7=h^jvN3n>3$4*IiQ+E%OE`g&UhESnhvDj%MYA##st?3vB=hNSK)aiGHVIgz68eT8)Kia2t``9U)l?F-;qTwwhgUr6 z4~luWyh7DIv zWq>4z+bR2(3Bt?Bo_;15TAZArjY*PfT=-x+AKv@%GR;5Lk>4W3ZufQ#3lSHa49&z< zQZh{LV@=A?O`9I>L-@EL0_F-M` z?he7oW4je6v@(38*~tE33D^GOHuh@`vDZbBc~Uh$d%<~ARyMdY*f+;F; z6c3c6<8G+t+w0DyGr5S4Y4%t%nP0T!di;i1|JEKfTRh-Y0bno?^zQL^TQ!_nNp8jz z?8ov)8&_}B53DdIQkAgWEk?-SM2;cqg zho_5Ei*0~b1q4)BKadE$Z$~zy-fyJGbG~Dn0SAMz{4GTYxt*p9ikSXdcfrRqK=BC? z^7dVv`+}Gdv;Yx&-(%s3CDf#Pt@O9UH-V&4md zkNFwNKu|=f%raoe3R+Gw6%!H_ge=$6$HbJ4i|}bh0$$2V6VBHiqW@})t{xz0sOxC- zVXB`!tBn6mSm|wj89Drr?Yhxt9$^8a6ke@JzA_)DCN_(rqOPb&UitpaQaZ4dlIlBM zDP3cV#cZ6zpd{I*879=9Ee9fgpT%Mo8ddts7lPJ%g{j46D5YP3!?W5Mcpz~kM`24i zZ8_XTjp&KhPXFt5jE}2>QSvr4(r)rc{=KT^EC2ZTAXE0I(~0eN!X!JZK)&0vUUzS; z2w9(T!_Emvh3O8x@$75gN~yRK^qAC zxjg4&;Gu~E$@KLQ9J#4!Yi;D6kN>>Av{++vb+4UVE#7uhNp9JmI@>9_VH=_k&JTJ? zNl9z(uHJ(3Ft%y$>|EBaun}}xU?itLYIYg6R}aisj!soycmU7hpE|+RvY9H6vbeQX zYouxr$7SP&6=?EReZSA|E;M}l{+j_sw`X$!8;4RQi^0hHvd#P9Ut>x_k_*U)A$Z+? z-Q3-^TiwPwJN3cWbsy?)*$14-pr)iICu8B_rX?j64AF1n=;_3RMm9D!R=+DGlhZL| zDGSf@UdlJ1`BT>uJT*Jwz)(+Ket$}tmTv$wxhXRGoMFUxQzNw43~Yc*S>x7oJ$>(h|(6E$T6cavw&CE(UR0; ztJyR-t(d+W?wq~h8K7~S&U%hS1QEN5{v2^J@7 zwp$ATVN>9oLNp53xR%l!CDak{0Kn=D>?Z)jCFa;a+(T;o`v6mDq83E$4WnX5`W4$m z;;hpa;HWce31!7>)qbG#4VZ69T!_wrtopwtn3D++wWk-Fl-h`6Rp(KYYK0co`UaUG z4=vcMbV4SW?0Kf^FEd)UqfMLp;xKh$X@Mg4 zV!ea)cEX;w_SAdQ9;~^2y@ z^D?9;n7sS2;m`!G0_3`YK@&nv_tFx;+#drPJ1RW<*hicabMtOR8<{JoQ~(Q_snFeV zXzJ|jOuI2q6C`eW4bReJ?*&+4fNlvU+u)Y6nGB1?k$sd&1I(lkAZUV4vwreQhVcb* zVetwMj=BEb^pvz}z)-#<)x~eCDQSp&D$7W(1GphbD=mowt%U_9Tw&&-TZiN%nSWRy zkxA4GZOgxF_pa&-o|RGA#4JoER?CouKAPi0%!u*gt^U}bFq?L!piG+>jaWtMz4kwu z^id{4eOvxS=yY}w)ELnOweozgkCp!VPz_m$NcO+x9tnk}a~tXY@rq1Bafdj@L&y@br37<0fT1Pf_1Fghxo6Ys@B{oO(6+_Jz59%m>kpL3;5R^X57=y<)T@8Y z%OO)6_6kA7jB8s5nePnX!({kgiHF zPt1#T{CCj|IkAq`#1hqcc|r}|&M3)AlKEE!!=;HJ64iU(DIFCbMT`;y*HPH}_qFBF z`QGvI@GZ*}JKHr?aX}WMq|FypYxwP&y8mR%k{;EW3Ll0N;_y_!&M8dyv)J!-EUm!w@`R zsr!Hl8JiOZ7R#>%lJOWU3c~U?t0PfR_%?<#`GBYv&9qaP;%<%n36KRl=5JSX2ymPTL zm|Ejp5~l4rQ6K{n3}i$^x_?N-zk-Hhk)=Y1Xf)W+#rHWlI(mC~NxPMNb&}51XBm=* zPfd;@?>iO!XwO7S0pS>1Z^dQpAB!`KV~Ft`l%F8p zq5V5DD&FBCTr`219)RW+8V!ZeBh?5Iv7!T~6OYGbp)xgKN9_XmRnCr4skyxb@>1t$ zt<{_ZI4pzq*8^v+6l%;+df@uBo1Jh#$^}3$hals*Z1f<1kn^L*)+PTFRj!M z1`BQ#5~cmiqt2Y?h7BGpSm1Mfd<^zZfF!u>MV49wc*ZK88OyVv{zw|e91H%dU79Ss zp#>y|sX5uMwt&04zvZzX#Q`4L`-2ZEDk=!ULL;)$u-PLsO=$7MyGkqgxVs;%4MJpy z0wkwof7t!}dO71DAT0a`9EgJ4j<@gM7hH^5i%V2fQ9FMX&I3@qTHBRp&^Uh(jbw0- zgQMuk=vtG`=HunyxE;>q1`yi&Qq#;a-L0^g7*r%A5TU*cp#5`ciAgz3)1qAp((Qvi zr1|}UnnP!uDsqYr64vA_-@mTEmRuPAL55Y9-xEd+O|Xo?B?Dc8GDMHU^VScVhL+Z- zL@DSlJ}pf$&Ipvu+;0yosfBkSyw;8bpNNP^Ne=E`^JgMBfzE;)#AnXp&Z7fV=Rbe` z^e8$2wWzkXHVrySm~^bI+Wl9`Mf^rHgU=7nK)!c&W$-L@f=iWsqvFWv)GS}qNhHmG zTNXv+e1-cBH)@ebfKLxsMp44_+x8CZoR_y)j+Ce*=q(G)JmM6VuV* zA-z`P>cN3081BNOQ>0K^CJo!ju(LOSH-CNI02LMWJ8ztzDtG)uNDhQpJ*0u8(8#gc zPD4pJtejrkHJ?TMr?aut+lpA$*~yf!(!RVLsx?tiYeS-Srnj0pZ@fbP2mTpwvx-lY`4h6BV0fd1q3zQ45KH{f+8IX6sW zwtmyEAgvp{m6HBvE`&6$PA7D#G}9Rq%YlTP(~K&OoT38jPhJk^-v~7O^fLzB|7kx2 zh|}K4NRP6}w{ivwTef3_a$WorF5#>6yu;J&7nZP~+N zgX&1n$(qg;yF8q`*zAj!%i`JlS4N9E0GB@nte}*M{Qzy9!SB1QJTdB(PVn}vJ%}Sg z31v3!PXK2=c)lLZ{`#|kvFhdJb$@f>dv|UO6BXbzC<^!8{5m%FQw`(yu=J_cRJw%m z!TZCc;(QT#;rB_2Wg-SENs{Ji`iq?|7z$slvS{^%)ZXaR1;^HmuV_^wLN8^HzCPyeR{I0m!_5s-TF%R^-+D@xV15yU@yl*9216$x?+no=R7%7U`0ml1iS6> zqwmX&Zx4>L_Ryqazw*C40e~a}qT`T|km793!6YE6mQG_a2U!^4a*aylwjsDO=b|Y= zu5XHw1qt*k+G4+wO5#=PdBnyIWPBMK+l>s^6MHL->6}K>lW?WU@pe1poAJMk^3l=O zx)p+r`XGqzFEH5!7E2)^Aq)hOK%Eqi={K*|tzW^XA^#Q#u7n3z1Oq^`cUHgfLq?7$ zFb@{WRi?f=4ApMbqR$>-w_XzQJ}fC+V74@H=%Nro=P;pU1hElxoSaRirB<8LCj)SU zGh$Ze<~UebGoU?=!1@F@zqRu>UyBd`hfr1l<07ed1CZueoG_5NMMXuMo0;%#u zG(}C-s1yH1Tg}z%02(T2L2ZX)SRgq-IRRdPs@htsiGrwSk-XUGyXkRlp|-&uMd_Ut zdLItjIPsLt9xU(?fHi-YbY?yc{sa$!M-C!!y zNHEb=jm?>pzkJ)i?{FcJKmOl->cur%j{{uw9xC7MD&RIx)(|}b@LVt8CQ8#72P~g$ z_e3Vx7KaS+zdS0De)9rS4)7~x2--VERb5t+4}to#V5iM!@aHSYgaS`P8haohHXbdt zxB^B#cpW+LWd#MHk_VifoUCF)3fl}T#&xKvghRP^h0#W&}!T$@c{gY1X?$*}T zPPQ+|;!uC++l>rLFfyED(&{PXoX0}T2J02brvBUP0h`1ZfC#k zswpA@OnfT@G_x>KA^%_D5*;P;qEs(tY{dq(_&x>S68D}(jg37hB>(3~0$t>)btx9_ zhcmEy5+K&I=bP69kHi7UuE+#zPykN{p;#X!6zhJ)2emHQ8OOh^!7VN@H#uAH2D&C% zYH9>jR6rIhniJ3-{lh>@PToB~KM(dAf;$LP(dZh|98%e^en3LQ$;AceT0b> zDE$%p#y#uCUpj6`y+!r@=;3+?7F3jj*?&hv{$|uHID!*qpuPg6 zPo`@Hh5y@EB<~}Dl<|zOk}zCWAwjW-MdiwoK6zl{Oge={DL9LK6**0yMhCY-Ur9P* z>fpry8^E?%!A=L9_7m}WHJW%L_nXito;OBIe!@uZNTmG>2gt|sZQk4xao`u>5fLSI zQO!AhR-Fve4b^Oe(dFgkV9W=`Jvs4+U$jSGfzj@3peRD^ssv!_X^)^eAvlR|bH+ff z0$PPu*ApE(JG-HckOawB2SMV0gTBaG20;6Xg~Uj+JIPR|edzh?5zv_)A4jW)$Xa@y1!W6=ZE6?7o~?SRnU3^Aw>BfWaZ;w&&iZ0szfM4f1}G!KEpIXLFYSL6g~ za2vuoCtySYR#z>0OJ}@GVY!+z^C@Y}0#++(MyllL0qDN3=>XSr3rcl`cFQ#QrqZmJ zNyw=(z66jWK-=;quk8~KTF})gv{4fJtM#Q2OXlY%(9E#B`1$z(hZ`7G(|@Vd1EL3K z){^bf3|7nc5Rl^FPuBM@RPbQN79fvZTwD~35_&hDfQS-IKEa!kESVo29SsI!{ey$A zAXCxc)WmwF?N>#`33z>xAb_wBflTd!{tevf{-L3zI?Lo{?MVQ#2G{ZY{0#0O@ZVN8 z=fFciC4TwGOb1W;)zN}lesdcBRA`DD+gN-0%YD%S)}eaNGDITv&38uOVxD4M^;}m< z(){Bs3p1JccW6L`_dP;Ff-Q~-IfjIEbZ#hj?@vSV4|}rzeXbY?#Yb7#FHz@AXw}jJ zhgiGvxMT7tL2V`6w|oN*4gmpdurskpDBGz}kC5bIAA7D+0?Hr8QZinESX@%l!QLK+ zL9YX}Fv<&>^1>$8(Ef0Oyvb{jQ9+?)Z|h|YCE@FX9x~nE3XiTZ6`ClG03i)<;tghF z20(EZIr#-^KY${7Lt2Fh4lWclc)Pp1;8n@sb}a{8h_qp_P!*VNfX=AIrJ0!Jz6jAJ5+n~EwEB#^* zGUO_bKEMOt2 zsi~mF1!_Ru7MG)j6(5>+Ve~q!W`>3nc_N5u1pt;0zEwZ4JdC8XkBp6-f%gl1FQpV_ z=XZ}_K>`C3-F6>s(r+LK-OSYt8MNx)twMo^FWUB3nVZ9or-(Pra-1ti48yaM+eEQ61aUPDm_m@I1LT1`%S ziV(MxUpL^T261iG0G`ujiR0RJgZJ+EqZYVJplTKq5a8njJ)MAc)l!pVFE}>`Z#CE+ zLQX+x0o(B9si``!`6(=X0|6|2?9?_56d6oeSy@o`!QG1t3v&lQ|B_#FYE;y&^u5~x zxMv{#2AsYPtgK{@eX%S@e)W5^mV)wwC)->;7FAP680=BCHR)yV)YR0_5HbXWmR!Ci zpQA%C8mL*-&zPU7iu+Og)H~hrZ=NVXjLQw4#CKsq)3{;624=ll6CKJH1@>3jDJyOulyvCI>Yeh{(T!BqS$SXw)G< z+HTh)UU#2IPzgO9O>7qJ+iJdRUQD3-Qb`Qx06%^hf%(~0aq4_d^=BqI6lGgFT3Ses zfVv%+Iv!fdP{V}ix3#rF>_FBzXg$CO+(#I{y1KfuGP;QZoe6s#9Ubr#fj7m;=@LM_ z^JXe8DF#Ceqr4ThhyE}ef><($Um}efQ?Ia)WNca(!)FT>X3ae(4@OE!JoB=JPp!|( zB&-u0g-qtr_?+W8ZLf|x{kJ!Ae&i-eS2a9Sse5wO%=gTBYdT$5v-L0jYn=TBQdq$Y zi*dCQTv6Tnc)dT>^bufDm|r+Wg|K9Lz`!AUVPb!eb~5H)R!7LgIbd@ZUryP=9 z^hM66q@$%&tz_q~mdur>#6UPgiGDwtkBU;U;6ycHg-Y_@#tbR)p<0r@{bk@&z{3r^ z>kZgb9~~WWH#KW4{_^yFx~Fc+FgM&!CEX7l**TyRqfV5BNnDo@7yk;f#KOW9nl2WX zmQ;>;D2CP-;3eYjmD%7ReAz2sCZ(M%aM`AkgZhxuk<$Ol0DL-(A9!zPoMXe-pHh$v zG)ij=my&-7<(u3~JwJ^%&1{$NkLGsSwm*ez+@j*O0|J<;mSL8)Sv!M9tr=s;hO$4-mha&k+r> zM7vj3bO$&s1=ukaiP0GBZ^YU;@7Yoc-pXJnrp?I+r7hM=z*}-kKzC@j%r|^Mk})t? z2M~ge4yqsf!GQ{qDeBszJkAZo4UI`V7w+9EKaVjd7e1xBoR^$!v~z355dQqz=(E1> zxY3g}W;`3MQ>+hpzTFxYH;#GWD*rEL=T2Y_(nCqoFAQ=q9=+r?Tq_kXA_#IRs0b(2%h%4XCCN`7d7@cTY)&`o=&r zobnpj;XyJ(7lRd;zDedgfIaA#@*2b+!k3q zUgy~#U6gp=s5=_8ttYgVw zONtal4ebpy)&+5_C1yEh2*vPeA`bb7B2$57Clzk|8FTCVW&~3MG49^{>7^$U1b6E? zLRHD8+f#6JX<4Ha#yB%5eGZY-^Hhp*Pt|1{kLj7d1PeC{c~JG;-3X9k;ypVn3;WEA z9I311DkW&;c6|8Y z9{*8OHkCAuAvbQMp}TUi{aGlWAPJ4HAZDn8A#$LM9Ov70ESdQ$OGTM33P@{khzw}; ze&+OTIoP*W6U5)j+Ug87V23q`TQ?CxkRng?A*v( zJ%9c*wzPou!5SRzBkvo5^kxwe5fJZ4r%_v25(N+xMn+^xYhnW!eQRsLe;15`f&v;C z@SnvGY=NmN7>SU6qok$|C+h>Ve1*;!|NM>c_X12ooVofUCi9+>rk_t1H4W@vHIUEW9D!T{ ztp*!{6!GalP+05OkXD5)uYvBvu+Po>k{nE+aVk2XU-C-$W#MsBR@m#$l&ti>F+uCaItRbq!0o0`^VY>O`+d~v&t z;g{3)qB}+Z`sNgBLgWu)$l2=pH-y4#t@u|CaI(qdoBZrImlJVj_@(ul_F*A_&P*aNHrq;vZ zsQ-!^HEUC|c8`~-I$3S+DzgP8Q#Q5%#qwzLEuT+HyR-X!9lCGkufz{lOOB_Nr)(}6 zY3wb~0Yz^??)mZ4F9t(bJZE8&YG^k zP?Ff8Q*9I`2*>KKekyvyh!dYiJ|>f{?+7+x;8}VGLDyhP0%IQJaDelR5YMdd-=-s) zAU!GRJvcp1R+HkZ@>p|da;Dk_YaRH&q2Q0^8d(oH{lX4ekJ;+J5q2J;M9?7r&(! z`}yYn(~XqirR=U=Z~V)H`Aky_4mpsOL}#*(iPBnaFObu=n&OF-GTeDIJBLD{uMjO% zxxIwU_9jjr`yXiu?urD3gu0+1_LU;OJRI{l;qhC}>othA+qA~29F5qh_)H_()zlPA zw>US9fA`$<9QV0yn11?p8~0j1=|``v&eH>oLUQiL{ru7*w&REF*UdkAc)kU~{yT<< z3SciyWa>2LPX_ZUMq1j^v^0rZ`M4RugdYOXwEx85V88}4*FoZx20J*U0(~cr zVL?gBL9_FLQwwXEx>sbuUi0_~+ux&<_;}!zN&%@Rpu=MlJm}H4*qzjg_W*UZ;14JC zS<>m3kdnzkVi?nfQmG*_ku=%#G~SdUiD}s;TTam8z@ZYp+R$J%@34z3Fh55YbhN6x z2!KW0bhracRbk#GZ$zl|LbE$q;64ZPB(<+tF1Lb8FIV0oXWX+yBO-Xj8=SOEz-6k{ zq^5o185Jx=v+|y_El>>4_hs5Z&}3a#jfeF6gY)Ip^#P-U^vPfsmJ;=0>%s$%_o>`l za^Gi$I#Xq{{U=lM1Rgr7zM5YRnZ_l86FniWmriJN^=5mIwB#Er#I_HWXXtRQ<~Op4 zTT4pz(Sf0tr4UKD})At26Vh*imm`&brl}fte1=jrGpT zaF^;X?(_2IbEbDjX<7Gic@ydc0-g54?N?YY(-W8HqgDcvtMSeq-cSjyM$VSopv(O@ zmn%VfScp6^cOARQNO_rM+x_;Zfw2!QTnkQL)85b3WTuz>?W@Z_)v=(6hrzqSCC{Aw z8Lzvrx(a#Jzn6-mZ&Y&3vhr&Fuj$9e-Dh<&CQnEAj_ssnu^5>4$Mrh*K8X|uHQ(o!(l_qhIm_C~o*J&oGg zc$P(Ye9CpXmC;7_t-3`Yqb|@trwG;C-sPv!xEPGfNyFnR67L~Edpv6zj5 z102fmG;o3owqKWf#kipUfIu1LrIs`jU{1*5^X3v!0F5jjgPz}8QH(HQBHLSR2uKV0 zop<-f-%N|FZMc3O#F@uEkpJo-p{|7aNHSdI|;WjFCJ zU%vd!_(~NH2KD1Wl-Kt1`~bSyq7#|3%ge!mfdep7$ke80KK_41y>(nw+ZXP==|)t# zOG-+*y9Bm$OLv2SN(fSdbVzr1ccVx*n{K2_Iwju8`Q3Zp{imOEHhZl#*O+6D=R2NZ z;H@e{u6^}~u&-tycH*zarCVM3C%O>7RM+y98kU?=bkg7Dc)SMqk_(z}!&kJzKISQ2 z72I!HzznUoqY9-IOK!Bc{Oh$s_w(azK`#au=egO~)F$FIhBi4?e#!*EK{OKYbC2II z{&1=2bs`-v2tlT@n9Dvp=9kLoYq2!-)^DHtFtrG|NK&^LGy#0asPpMrekiUvo@4%X zuEH7TSw`xe*~ZbML*>CS70l0Z{a}v?U;Fk`oZ^Lz!!S}Y-^HJ`#Puuoiu#W?8b4tB zH_lC@m=MUe6Te2Be07BTe-+em2BQt8h2Y>{`!g&@E2HT`P1H30h<%~q-RKzn5fSl- zKWl%o4^75$+nN<^#q~xFZrTL%OudMq1x4hCc`HfdUm>Gug1zsxN&G;?X>6RCGEOhdd1}y9H3rE1y1h_3_HL` z_x2p7loUSFy3@p-;67XwrjdqH|Di!u2)?3t`8!Xo?TiD^IY_ZB!QigqA3tu__x1)B zGl~D&cH@I8*DV-Jh7Zc{0J%OsKF-ah^~b&fEw}C-9>7)(q&4H22vi^@(sSJP@6U+8 z;1DJ8G+C{d$d$_$pZ+n$M?!;%{?cu^!ccU|)?XZh9~bIUTp*MPx(rQBvL&)WNl*2@ zN!V!>k}aZw(LC{&ROlf85pbPzJw)?`Kd+U%{+Uv`7)st zv$pH(k58dHnxD>m@F6nvVYkbn-sVb4BMv>{Ya~MNd^jOjPM3jX0~frKiNvYc|Lv`+L`czMDvd46htzuz0zk6)xooT^f4?u zuK8BG9{B>cCty}L63bd#!vEiybjzP9s`cIv>Fxf^Yo+wsfqpna!I-9au>C`MVloZ>q z{4DGP`OT&Mcb=OAcxj^~WpDdw-W{ke1ACRO5@BJ2w=w(eDed-;7hpI!IXIRLtl%}O z#_L@;;+S*a#2n|DDY-VGeR6eO?C=p)JMf$;)(|*Xetl~;#DxZAU@KVuaG^@h<lgRx0l`d zOTtgEt$0#ZeyZ|Gx@9iOJ>Tq7>m4EBuzxdX5pi6dSy-)V0QcATzU`$_`j_kK*6iz> zI5o@Ne@jIuoO$71!orZf;2vaGDV5IFQa{ zqlolr7ian5@_X#34+C#iPxjp9Js4S(_**y543(C?q-&|4GM%L#7{q00xny+?^c3?w zY9vXpRxq#()Ku2g{d#RE+~Rho(!Kw^KGOgn|25M_9Q=yIePcm{p_gVZW!!11Y>|7N zp~?i_t3W)SdLDTB^!wGVrPAgKLE991$hUPdRoV|WPr>3>s>-Y04b(t;i(z2TlJ2+u zh#F`uu_pT7;jOmzzwS_^j~``5vWn6fNBL;>B8iHVI%T?DkU^kOo@~|R|%DJ_xkkiaZ>MK0$VTp0jR&$)G2B_s;~qY+JXZt@<90* zXyOKyPE*25AQR-}<`SBKN~-m-)Kks@r<%vMFvnv%oXgl{9>W{!YlSM>AdNRVC-cgd znBk7J>#M&Ct^PvZ9_Z_|u}J`h@np|d&l~duD~iFH`-OURs|*3j8q z>~c2yWPA*RBdT#+@mVdxs|j*EO})L}Q~6>!S}|XB(zU}CC|R&}G)ywJOpE}@l3f^a z+94m8AA)-qIt_;}O=Q2|p$+*~cS!JMEl4S+f!mhTh;Ll}S}DBA>3ws@qt0eJ%UMnb z)1TS8L*5&NXFv#uy(JTDKHDE=WW&{bcy211Hmx?aCg4f|v%cYd8L54F>w2;C{Xx`= z*IRU^Wu_9xk)DpPRXSm%+EaJ)HxXj!UQ_Te-X-x-jvJl>b@S}uf>zMz`0$l1iR`D;d{inaf z*HZ}@Q3q^oY06J=>ROf6hh@yHy^qVno4!t@*Zv|2xFm?Iu zu#GD9a%*E>Kq9QPNK#C|#lT+jIV37J~TYxzQ!1#5+N8XAw$2$2JP<_!L0BZsd1q<`;%AN9U3@Ns4ypcRr z#cyWj&)OGdA6|_PoURPJ#5pR%nr%-=Lwfy3* zn8OVo$6owN5|TVv>t7 zlO}?L(DbI)6hfwd_uVo>VWpor;lvnlt3L;>{3wh!jujuoOrh3&A7bwR@p%L}IXS4; z+5#F0yjVamC?8Fo0wMcJ+TQ%&4)hcN?v+_O7KbHS=-tUGz#|}l@~gSA@f)9qJ22)j zusgj#F{v6r6M&|4SZdD8n@Tdm^cAz}f)uH~a@|9=W?B0&$tY_>5UMffR1ZrYH! zNLj%e0skD@)#0}V@KjJA1ygN-(;*o9bhOy?5(h^a%#{Ohld&<}lX}AiwKOyP?BOxN zC2ZD*Q=jkmgy11&JA*OWEHAzT)Uz(S&?;HP=fMlimkbTXAT$^=Gno8AKU@58QvWkM z8E9zWHaeRP7Z)>i1va1Ec&-0HEwE0GV-mxJa%3>>PkK?q+lk^5@$9WH3C07C1Q@H= zOvi91AGN*uX?8HhtG)}=s-u+-impoVd-r`>W`o0$=7VvcbftQGnztXoreZmgYHa=< zSl@y`hY|Sef5LNOoCx5^A=fW{v?aD1$ksz`Ll}OVW9QO#tX1a({P=BCrKO*2QL9Sa zwS>;VT|f?SfGP$n`PSyy6DfGoe_CTgpO1~q%r?N$2!Ne-_V%EJ6&^keAhAG+HBd#@ zt+&%rSC@Lin{9!-=iu=7?&fSR8U4R)KUhWt@K8tQ{K|$BPhVBu+tb)DY+S6>-N+WS_Bek_>!DU^fmgVHEgAOXtUPHa;vj~0cXE)~;!D5?ZlMpD3@Y|cmYHp$bU3$Yy zQ}kpeVlC3UQInh=n{ z0qTH7%q6$|8ynQ^!G!tq%S#c!`2+mxqF?iU!W%V89Ka~HS66c|GQNFP0ZP809B%&8 z4+(^#8Fwi>aL`!>(;Q-BUq-CIdi4sjy1J^o|7IK-*~xAPUNgXTdY*28jdd0jdtB3t z0|UFkIss)`@aFu_9{EFBiv%T(?u3TKmZfQt%^Z&#r?ubmgS-r^RAcU3MP98*&+YFG zi?6h}OXVj^PjAlmBu`k)(+lCpqDXDUk;&(}6eXVrh?n8MKBI9KtDQpokZjBXZg4_c zZ8R>cV{SHSdZLJA+Y!Hv^;Rq#- zf>IMGeX7yLKB@BCNEJU5cfnl+G%B5`9awh-@6v!j&R2W!GoQzQh5*L};+ASfW)UZ# zNJ5!atS_)qR!s(9ZNlb$}3`+<`y zTzVKcw7aV6Q5UoQ;ntSSETOruv=m5q$RYkbg#iSlq>JE`BsuH(Hm0<=*hFO*h`=nW zoH_ygZlLfDJ~Kj|V&NBJ*UAm)b)ALtX(FJI1C+D5M(1_#s87##VaRyG8E;I#sWY*# zu|-BiXf~i1Pb$8B#&KDl&o5PmaA;FzAmw#6xXheTW7Z*}D(s(1HzIRdwPi7YN}MqMP4l>`5aYETsc6Ij)noAe?LLD!$4+YnkArf+S|>Y%(m5;?4bPBq^0AD8?vjHFmaMmsuZUmSs|L0@Mpf2#0fER%+CR$1M z$E+ONz3|5E&~ei5QN#o7ABNRtZ$TiT5c&*(fM~J+0#08v4M6jX{*KvA6;A=&3s|}V z@?9PbTwhuOW)478SO(V)hGo9d|MGCNo#B036dsOs#sd!MV6_eHgMJwxK)umeSH~U( zA+PY@5=cxW9A?2hLDD2ooCUB8V~iUBvY=t3llWj8h?FinV^r8dH9%qqv)C%Ri2$If zocPuG4a7x`aRrN6BF@*YLMr`I4}fP=u8jgj5-2z5f%fBs>YbCc$PU zDIr1Friu`@3BF8&35K)YW&(`oG0`%Rw+A^z5XJkzICD^t)F$ZrA)oi2)l#bu0YQ)p zFcX;$Z(!b4Q-P{Q%&%XY-cwR?!^UW7X@SiX_)IpFGr#wkEU|#^1Vt$C$NNv<=K`e# z%#NI1XxAvw?09?-Oc>O!v(ab++(hF612orZrO~5(TUeoUh)#2JK)L}t~O$T!sSwafTE=VKf zE9rmzR!_h)XeU#9hNO|z7KDw5ZGscp{p4}hT!+6e4m3@PETb<{)2|OJQ%=;#0F<#M ztzTzCT&s&|M#t?s_eu)7$6+^}(&q={D-cY^GR29AhydpM2x8!#jkT?P$CJ@pH59PNkZ9tn zXi6rie^S21`H_~`{#?&<3kzS(GMhPdzRM==jP=rs1Y3EhpXGl^1RXpLDf`VEaj3P4 zP|E!87*0{pmZpW4Q|vPr!t8*%`8Ao>aRe8>7%j3F_z9^p;DXZvb41_dF;HCKeZO`) zV4>HL?+x^#U+k`y_9k*3e-_HMNDgS`u#@=mo%x6SCdexuZ}%&}-UBjjOd<~8#9m~< z$(qmtXlrnLpL)K)iP*6)xqtGJ-)Z$LPs0x>K_-Ctf_n=V;}AZbw-7hC#*{@*7|~E@ z@~e4`QK3YFVi%;?N^mFq-1k>kJGakl<7ZX#qRR>kanJ(~EavkVE~Kd<7`PnxnC~3Dsyy?9sYLB(zQR=)!Rc;<%GgR z5s+!at8QsY|Cf6FB2|7ytL2_EY1+>%i^5r4=s_w_C>^8eV#JMmro}n+I%Ou%_nd=H z))M+f3Wb`6=He)qPSH5Zrcg7~=4auyaN%5fHUmOYl2K(Oa@MOo%Sc@%k-BuTfx$sQ zvps=~t?p-_0kX5RGud9V{5=sld3s8UAQ&qBjW`PY7jFMba#45-ix2i!X z#DfU=JiKoMC*oc>Bk;~OO9!GLBZIqUb16sc2goMS`vsCr5dEGoiurtS%R#DQQguCF zXB!so4fqP%!2A!0~(sR8>F)mIPuqUt84J_!)>TL&3#SF8?8l=#akAQ3CY9 z;>u4SLGv>}Z3r_)GeD^ZgwaVKTzq_RUKELza|JYCU!UB?c_uiOsi?8wk|BkWyyOXm zzj1Zj&@m|-_+J$=n9d&=oIIv;gEHNgyL1DKk^7UUeq(b=k$C2#C+C+G7te+ZYteIX zoB{%`nK1>qTFiz5*U-KSFxw-5%L6<^snU1f-u08uLjIbP5VYT1$N#v|_nb9B(0;xa#8O*PE9Iw8RJ`#PH^0}l6FAd?Q>LlCJveu^eb^iT zLFL86q~OE4y2gkzDVSdWJv3ASb)^%P`(m@Y&sJ1|7&hgFVq@SS1GA3$~&q?BfzFc1^mDLLDC*!`5iVw#wcj+#ERQf zWVI?r#l&Q0WE@wenI_UGq7LBC2{(oTj24s!K=wfO_5;|OK{IFv=!QoC`!jbTn4*VxUjsR=Jv}=E-ATaEkq2yipn>57Un*#9kI<=Zog9dFVT?be zIi}rMlb{?T7>McIeEjm32&(334z?^ap%l>PqWD)6Qkfqd(|mCd}(QEPqL@Q5Fra}aF5i& z;Pp^Kc{#C^iKT#`7J=b0fV)2)%&viXnU3v@n=xuG6duKvZKq>@2)a`_8Uw$)zRRVlJTSdUCS4r6PM9!aY%{SQc3)Qe4`I| zB1`_ijvYU2KRU^>J=#fp9Nk#m^|Ae>K}>7qN_S|Yhe+v2;X7bl$c_o4bRg#H00oZ? z(73U8%Ls*WK}pI2g2gCTKdAhEZz|oDv<+w;L$8x=pqfG`+1N&(Xe`ADk8epN;Q+nF z#l;2FaaSf^!r9vH1IVAR*2&Gr0t*7F>e`@MAQ{@nIrh$k`Pof94r&9lLp?IO z>gvLo0kWaC1Ibv@=ChNSuPBe@&v&x%8MNSiR0gAsXR;Xa=VNfcBSN3z9RLCl(~zKe z0`zls@XkBB)9@3Wpr(3$AnwUWiXGHd#EqNw)X?oPHV*QATQaR8byZyR%+pP79Z)#P zmJSW$#Fya2s^3ZfER){82CAV{t_4Ww>syHJDrRv$TUDYtN?{_ zUr0e9@4HZ1NnSJ>{qzHsfj%qxH(*z%7r~82qU24aYOYWxDu_3OegCoHYy$W7#f#5K zF&y0D_0di-B_yVEcwC1!JVL1w|NjGd@XJRZhRaI+RLYI5uhiBxwqrf2-YeGsn!5{7 zLZtL>C!BhQlG(G1-{2|Yy=P4r-OhO-28~Rn#~~m{0POJ_dJ3#c5{n0XKVxlhVSiUT z9QVFIC2S{o!Sszo@jqH8SbN@ks;5I$Y1e*a`x)t~zzX_5#<{%4{SfiLD%NgiHdyTq zv?<&d$}T*1dzu)9tYJn`Qj<2%rMZYe8YV%ujl+q_NiU#W-Lmx$RhCS>n$*`S=2{gI zQk&gfm8zXDri{agmNox=_5E12c9g(Jdz9D&kL{FxO8&Q zyMMX-4kcZy!8yZ=pRG9-p(TSDP@)f<17ka@TYSn%vX73l0vX}54{T$qp3c#Vb3Dbs z_b_9`k#H>pa3&S3th<7ja_8eD8Hm#vlxbegwttR)R~7gWQ#&B~Sp08;xBBhmmmi`V z_cV?e*usLaR1?RogUM5YTy0bR&dO>BND@$CjDV`5!Afgjx@~Mc&hTrf+eARHWt>n> zjsT4w#hvGQunby`_4GoR3g=XVGXC#O)hf&cbJIEM5Qc7Z&D1RO4MSpq6S~5JLiXnA zN(L+J6Rhg(5O&N8$+6tctAO^Zp28+Zj5OmJ>498<;P+{=2fz3+#Si z{RJtzo-vc=`mj)9MbYZ0s2FFCtnkQ0k}rXg>+JO0q{e2GN`hfE=m(xMVw_-$_s%~eDg06(T$%R7WcP{9mG51DmO=u;NwB(^5T^dD0*Ei%fEt^-sWr&8~MhYYFn{L z;_ydPNk-=(iK$FWrPyzKVzG)V3y@}qhAE{B=Y39w|%d_bazhS z-ZeSg%pVrmFR9^!wip5FG}*o-a$ru*mKQKTS@tb2dHQ?SY&D5g(*BQZ!Su4%T=&0eE$;~4E^WSS;V!yA zy0E|P5J$Ws9J`u+P(xx?H+*!t`S+-Hi|zAw>E@Y&cN+gu0menAMux%7ABBHiH=FhXF~E&c&in9A0W! zx*c!=MQtkb^MlV*O^S|o1|^jxp5FlQ1s_o80bP0gWq(Vr^yeMN9omc9I1RgZ3BA}T zTY!DG7)}6a2fe(+4@J_7f8}LT1-eM|nBulJHg=$#OZ;1l;`Ns5%=@dHGE!1~X4T+; zAbc^YhTgr@I#jpi&olf(l%+9Jpj3`CM~5jo>!v~}1lK(`e z(`6mq`8SU z3Tl#GtsPRp^D-6d9K)l2J~uqe$3&;1d~>~f_{`hqc;MyQ-o@ZvzM06hs0^ll4^)mk zPkD(LA8A$i*s!95ok<20Liw1<%RbeBUeV(kdUtt!GhqGfN@0igqK)2qwG;8VQv>nn z@8xTk3*rhL(NW^%B?L z__(ycfbGzw$mhj$bX+>ji;}5T?tbM`3ytK?Q?=IDPct3aLB6(BybAuy1;f8NeH(9! zx6_0*B^?w`1fCag+@=x~Oj+TA9TUTs^H6Yf5FkLLtC%cH=MH|UYLylb{ZVMHh*^sY`Ep?+HnQg#^bka~WD^FfSwi{R;Pg}_1st}shmmF4Y_8~&yX(=otqG%`UT{qG0uE8Ne z&>8vb4{yI~D?%W_uT%@m9IbBgBg_4JuG^{|6K1~0jJvdW9&RgX=Zti$J|`iPfrsEM zlL_`N->iFBH_c4xMYmBSq{zk{47bMe`WVRGFS=&JTq36suC*`isGnY(lj~r(u)~j* zT;}W)Dsya+t1!hNq-3EgZRTjXz5RVMcU6K{(Q-gjR9xCS=OTrJe4)tU`_p(;;>CLg z8oGDN<~iN4;AWDZ&2ybuH*Nh>?2Y?ih>l#{I<1HPD0|NR4(LeXzpG% zOML47cz)8~WIKU`U`j4hdTOa2A7eR_TcM4|TVJ)!E@YJF5Qv@1$iqQ!)~IZ>lk~Rt zdueAX7&nXZ0Ri(F$$iJtiqc=ND<8br5|>^%Jma77L*HHDPo=lJeHX=h6D}PU58uf_65rp&%<|@xF*I7|7#M1&icSK<4(-$;>It?kl*n6yvyVy((4QoJSt@GZug6R z3X2uqd*+v%w^K(VUbUfwl&*b#<{E}=yxi6w#U;i5{6?a1YvYyLUJLGoQ!|`9zT0W^ zLAgkII9Odau!MuqqD2lVq+FPdzG{D&aNtp39ZIRPv2&HMd~?1O)S|?UA@8}D_R2Bx zV775$iAz<+=X9IBDg*UzdwtYLpFd|udm>(@a(7JvbF2JEUlP)ZrEu8Imj4tir->HN zbkGX-C_>*wX`a%Pojp{~j}kP; zDE@N`I}jBjGdA?@AM-5chS_GmC&d{&UlLDCsnza?&>ID7IXuW@NLp+hCalN&DVM|AGvq8WMh}+a}rZn>+mSwUI-QqUE--pVJx| zRR#|R)NTG#tB0?rO71qersAe@D;`8Ko;DsVaQk>(TKGy88L&K z5i7zq(qI<#A?F-dhn9ujj{T=jLDwCe4A1%XutQ(wM70Eg!YwLbcgN2^*USZrD#D1s z7!INh5nk(D79VFeFJ6cwdhxBCU^&GnV4j685kC(7L^kFqz&!6@+#J-qLWsEP}XwA_ByA^ zu?!;y-)YIA1X{Jv)1H{Abx4AWkFVB_Z) z7B$k!E1mLa%Mi}+kBVU2h$KizXx9-nDy`{x?%a5qZ69&oehs#&l7K;C8}4h497XsX zJwOxse=j91WjUdh4G|V`r#4#LnlOu@7*oPv+5|@52jcK=#$eXo`ho9kv^F!{+lhC9 zNfv}yzklMzlQ-~sVPqa0*e&EIHJ@L$uQntRaKUv-bb8oG{nAB4cenGc}n5?d)>DE7BE)}1kTvu)56p9I(}bfm&(6<*wVRbnJ}dJqE_Mk?@lp%4Fq@Af9o-DTYd?Z^P+ppNdt zGmLs#(S0X`V5!h?aZN5PEHENC9f_$8f;jJXw7$JfKta**`NYI2kp0&OuQ|HGYKd7( z;81d`k{=cNhQ${tCBm}c+m^j$zR;rmmL!C}gpwGvzTEbZ!xRIQ_0F@B)-UJu)Oz|S z1BeeO9OggvyEjfou6LSc0yD^M@Y&py#tA6t;E;R@cx}$4z0U9L?d`$F;p$qe)-(1F z9?GJ?GpG3WZ4#d|HDs~TS<(}w0ga~i+UyL>`dVr8Z0LFiRy;uHy0#Os1&g|je$qvT zm}?LmUO(~zc!8f^=c{!-tJ)jh#u2X_@hZy$4=_W=aO&CN}Yq#;I2#|+>6`0)cqcJ^an z+zX^hb`KN+n=9W`3=AIokN}MNUCx+1bi1nG6Y52D(-zbXQWqw0 znP2EqQiH;*Ds_CM4?j4f1ZT|-GF4Ly-<9EXE8ERsWh+9DeaNV04u){Aa*{Z>o!?4- z%$rq!UTt)2Jsv1=%Hm~fhai0oEvs;Eu+DVPP$Y(=?xI8MbjfgWY4I06A^h*4_%d7u z_=--aBS4!)bNKc)lm_dtgatkxph823-PVzF)^O?63Z)N=jbP=QN$(u399~K=%+?C^ zPMR9m<&$H~BnnoKB1?=&JhPmX)~>Wh@X*4n$B;G{e=J!RrwY!S4P{bIaXj_mcJTqP z+PVpNta&e@aS{G|z2`8IlYcp{e7OoI6RZbDr$>!E4(yl(sRpKj?~(BBbfH#QKzI6% zl%iRXq>F}|V(Xk1ZLnk1NT>f_q+Z}44|tC|73%iSEEX+W+I)n$(Ls?%P;EoQ_*F{t z&_)Um7FTT75HHd%vHwm|Wr4o=PGekUU=BJ{+)d-p9sJb4x-LO>CHi=F^N1^BLV|(| z_7jTw-~tgLU{lsrBkSLeIekaNS>f2w4+gq!F+XRk>X)S2kk~;Xf+!z+NMa!il=(;W zJv9C^$LBm|(cVZ+qw7tEr>|33F?LhB5-8i`u z@5p9xLR#}osCQ+{e@#1ayANKdq6N(R$(w1=FSV+xm9R-t*y=?$GO{LHpDJQ4*W)Go zl6$Mh{GXq|;}3p9-{$F%;`&kZ@F(eBx1By4@Ys-7;2FTxx4{(k;TdOZ=i6{S>#f^z z1J~d)Eau(cqc$NkMaQ|VRvN+3BNkaub%7*r4?fTZ!?M- zuH6<>dy0$tIBcn5@s`9KhH`=7{!vrl5^E0MH#}WnqfzXxRA~7^wNbHPcY2LoEHt6K zP@?Z$p%gx3UTHWVWA~@3rJZv>hsQ2wa_oF7V^r|({HMWsIMr#Fq*mxbNvDcAL(I~V zVPTUkMQQYEeIHnLE8lik6=T$U9WAAU3wg&lYgct0EL(*ON&HT8RFLFf=J-7VXW|1` zF1t#h5xS4oA*Q+^SjIbF1QMj|^ZSEhZilD4af?*oI{h)*2Jxkn>#?}Ha=kmNrcsgs zoK;VZCBdVms%rB27$65glLrFmhr7=>9JnuD{5d)T1Gp@68veLSOPG51*cfN-y5c`w zdoykuXlN7_%~0aeXHAlTA5X{Nc{4n@zDUNyLbYyYBVm6|$2paZt3ZZ!J;1L;QGqSLL3J2AP|itM?FV*!b!PJ=4>xpKW=sB_xT^ z>7K@WY3<$iY;nZ;BfTQ$^J>Dl-va_pA!&ZsLW!0o0?>qWQ0sHoiR76a!Xh9AEejsB1+sTO(Fc(5iIsrB~zz9J7i1M8lt+tG1 zY566Qm1sQK*bBy-etGC_mtnBBqL&K# z^cqG#(UlLYT_4g}WY`^547UW-ZaB3L?g(3K{$J zmz0MB=bCP!Iof-U&ys?z?-J&lC14Z?(2aCOq~!IUaF+qF1Wf@KD1!h^Etg9S8`0K3 z=E#zfjtaU+`tn(czdz`jx@69o^@V? zLRZ7UOs<7b-!V?0R~4}+q+s@pi9@PqN%f^Y5v{~w5@aT8f6dQas_10e*y5OgVhP?U zr>&bTr;eWc02j9+I)lIxUW{5H&2BgAS`kLBKVpBzPb*RGx6Wtz3@)n$_1EIQKDhZ- zL!+}F75Mgt54BQ?WQ){K-{d*ildaI+k7Y?VC#eHhOdFfx*FCD5U^?n8D1!q^t=zDq z-Q!{p_yq8KN|pO&sL1E3ep0pWaEdcql!hsm0jMkw*n;Nfl8ShJ26hYp3v`;6yAH+l z(HKv8X3sb~iGk}H8|Z*}A6ZpR3WRdb~TjFD6)-MY`po(!@RnBvfZtxx-+ih2L=@C#UAfQ;_nJO#`Qz{rdO z^YKW>Udt#g2*NkHCiiPu<>%#XZf{#!Sbz#9CNWoGb8|9qVKPn?7HGk>t8Y}vcTNqn zVAR;*aU&9UGuKEs-^Mg7F1p`mXtJ=Si^rid6K47znEwM7jfnt7Q<#cng2RaXDyUoi3h(*C%V)A!~ zrsD~;UWjMGy*O;$NW5+K_=ezj-Y7U2O_Xl|Vh+C5fUFHigW%(EaoeZS+9)7LL|C7% zxpE}g0bB<3Tj;cTxPcx=fUD`mU!0zXgoTxslz=`bmrIC#oT*25?HPFDpd}9!jX~24 z6dEo^i;jiG!o-yP#xWi*!$wgSK zo6oE{KGh!UQAU`s8O=~`qnQ?jaLR4MTW%1CZ zqy0+zF_Cp#C2d_T=f$O0c6p965$5c~Sr;V1wXV#92kN*hVdBK-;&LJQ| z7#JAFMo{dH=_o*NuXsfO47ZJoGd+t%5p>~@b!h0zK)%*v#wu~{{!5;!s>Uq)r)8f^ zq_DP+DT`rL^g;EN?Sl_u6KOYg^d4frmaPD$yLfjGkq!gYKppODy&NpIQJfdbUZNF^ z!d_b_k%is#^Kt6Lnhx^*4XW|Qgd&7J*@8|t%3>Z3Ik}K*Ey`Un>%;!Zb#61%)5Vtf z*{-nt9Zb%ZFv*!&R8;inm^V^J=)Bvv9B9)bA71gMUDMr?qdzYX4bSKd%0Ku`J|QO-I{&S#cq;hlnRT_`b)}Ev+2tiJ8aP zjEoE)D+AFY-72SB6!&L$+pFC%f6fF~l!Pu%heolNP52|$`EV|7JM?E9-V0USS+8~a zJ=@H9)EN-CF{E?FZZV-5>^I|}%1zR}+xp~@oM1D=)+{vhRqd_&{hMNH>*|CoAx0yU%H=Y3&OWYTfb! z9zJri0W%T=4igK4M~wstX2Mnc3j6iRp1I^cJI6c&@fhkWk$Td#c~=b|K#IH)p3;l| zPWVWR&w4DSn6#?8|#LBa#&wL>zqJ~t8+@bo}46abKhfR!qM`T#XQ zwO~I6gK@I5mKPTf=+L-|-sMg#7^?{ecCMw=Hp_xs5%d882s1rBy%{AmG_*IIqydmV z-~(_?fPVrDr0i^JODxrAKHZfjB2Kw`JdjFUNadOset&1Rq8k1XkwbD(s3T4XxtvTH-F3xb5L(W6U2b>1?pu{Q$i`vMx=aGlfEHH$4&|d0{yx-wQx{kJQPgdj zJb%wc_LfTZ7-8#7hlsvqJbBbJRW)JP8^0iUYxW#UqjQ z@X^F~nP|5+TT8_(nAjEmICXTi?(Q-s|Z9SjZQ8T0T=tjj_b|q{EgE4+TjNSS-H|~-bOD#?6G;i5_ zc^en{-mXIoKI7AdDq{8QqEHUi5Augb3~p><&{;MR_Zl?bfqUx>Fks7P1z+C4UZg2i zGp9Yw?Df8B@r+H8N5MU{>F(Q^?~~eOg%w!11TZl^`x58;Y!EK+`3KAz>Qcj zhJ`X`i}1lXLU+QrGT&Urc_ z=?bsPZtq}91a1HBe$&Tax1CN%UacNUo1uB@XTeUa^N$gr>Ejw*9`8-a1m4Ctwp~mE zJH@W9F3088T~J**cwT2{zi9jtrZ@-;3-Iyq0)v7amzpoi8kVV1sXk8F!n{_ykYJl~ zng{PX3zF1@O739{BEttE3%1l|cp|;(C20T3Bxm$L8z>bQZrPStzud3JqYnHFMba^O z7V?U%sF}r%J=WqhHOAu9RY9IeY0W`I0a8h-X_bA6sIWX_gz<3u#c*n>_=eMm&IWzp zv1sYj?VQLLxoDKhX>KlIN5wBoWXCwspJuZCM__woI5GyW%dJ)$^QD5zS~XC~{JkI< zSJPd)^BkkWlLaE=>}yRl9S>K~8-;YenZA~{nRCApAuE{?PGz|B+DtW%iA+o{W|Y5JF!1PF%BmeiDH$+vI&fh~Z6&;14O@@E?hEUKl^*ZE8^hDlfp$;|X5C#aiYb{q60Lj!cb z8+yLGu&6U!*q0ivKt_jA1newLW>UkgW?Ts!aIvSnoDyKs;*Q+>ia_bq&u^o}PQ?*E ztmVMZb5Qr#Ha1ECA^s*S^mw=ob1A$&_LNFM53y~sVuP#>Ou0|#dmwx6l#6wcklwf{ zkxv}QovM30wl5<>#JVyIq76zKrVJGgOzwXGY+FFGo$BTi zb9;Qteo0`)ir1e&l{eJAkN)qG-f7uRJ)EtVs_d@ZJD=_iPsFt5cwQQY9WHSvS~crz z&%JabyZG}%&#=Aa^S>n9Zr(E&??LVBw5zikim2zLy+4JFN7nRIL*7^iK7$l^48L6jj3EA$`bke>2`G zal(CF7gNM(45E_&0y-mK>!$W;Wjh&h1!{m{g*c6aH8`@Qeq zeLv6Z>A!M`&p6NXIF9!Ua$jqXR?_KpPd2jsk&M}zeQ|E&OpyJv`bNV+ug=!dcV-=w z%-T#e@Ks15%MLA?eNLvAq*17Z$4IEB>{5{|##}uzlT|axZ-BTVv)u2Nbg5S(FVD*xFl5SxM;M;pGN#rp}m+F}HrR zYx0Kv;dSxDh=B#=ix31gRn{XrU!WZzG*v^j9uAnTe?icY%-vAtOV_LZsN*{&E;~9& zHfem`)*4|dl0Rvn)YM+u8W$+daATgC^Js&k><&Y}DB*YXR!d=kb8pxBYUJbN;@=3#o9cqHfa%ZeB$^bM4qFp;te*H4x{+$Fp^8(&V(}-^u;kq@pAx58>+1_X<4LrfSExH`WHSdO;4M z%rpcui?{VeG}mq?D1Ppx;gLh4{e}&JSPbH#V6Hf^y+O`xHmauM#$`3rG%=xh&d}^m zTUtrF_}(?0-llqX-zcrBB*%ue=Gl@cvXvwiz%fjWv^=Ggg8u7Lejw_D*WTTYl9o0# zHZD9;4{6*)GJ&@cNNl(7kT|U;7;2cq?C-Q!4A_dGaj6IU-hco+wIkl)Q~Wq(mXq$B z#vsaI?(X#U*D6MVi;=A)G?(zuk!*PCB@{!_i1MZsvsFroGf5<3q*2fDg!~6$r}4vU zNalW7V-pnt8ft-_uy#_@l zh9{&+fktK+1~%34*AztU>Yl47^Q3k4rq0b7RLCP=u3B5*Uf4V`?xWVxnRb|VDh1h$j-Zdj=JV9fREL7= zyK?NORbK=;A}XHN!N9cr=pzxW=Deu>pj-$Y>^X92GCfvRG-w>~PW=h9aY=iCix?CA zkg4cAZ|8G4Aq86ZJ81Aj# z?+Ms+>R?!H3zG|Inr!wh^CH5+M4F4I?)2Ldj1}Nb+)zf(?cj=0el9pl!SgBTPyDj% ztef+IY>)`?gV~OuZ(6(}`#+AA3^I0fKJDrMt=BSoqE5lamqhmDVO!$}MpS&7J*Lc5 zNT2QpxXHW>ACk2qjmT#jrI9i}k7!k~2ro@(w;{Y4JgeCrKRyLjRF&1N&rlky0wCX; zgZBYUMe^JU4Md@q;-6-r=uc4e!HffV6sj?BBlNfNSrLXY7JNRMzScpW~Un`MKa%JHxtqKSB+k%xTtq8KSIZTFF82l2*p*B`3KJs3Sa5Nj2FB`h*3p|5Z~rF>|ey{*)!=JsdAIsT5Ihe`en!UUf?5m z^ZK4ywEvy!YHwc}$Rc=3$ac_=Tge zd6H1JbBUrH;G3!-h{(yS^qT!Zja#5ydkik3<|m_tj3LQnnK3@L*SL=?!{s0E?Cd0{ zBrlQ;b76A424^jpIgdjF3-R#PL&i=BW2^WBwMp>qeU@xK{2BW?K&}UzD0tu<+L%h9 zwmieUaV2OLM#0RXl6rc2yZ`IT-(?Pz`7SIBKN=9gX1PXv)0$w3N5C19U7q>>b5;2t$c`ZD!e z$g4aY#82Y5ESj4p^zve=zhiB^Dg6zN#l}sUP9E-BMdf!~;>K+D!V>Zx=**mVJ}^&L zTeh7P4+$h~h{fw1jegm1VH^KuDT$5qeNxe#b1n@(m%De_y?RTi*T?K^1Ow?|x<7aI zr_P2ZU!{MiNBRO;CjBBv%q*ts%uRb}=X7D12bl+%#rOUlL%(3f<6Oh)M6$jTYoLEh zNZERHe0-PJ@;AKZ@MJ$LH{W~a_%zsYyedIUU!r(#Ne6{VH(pR1GCC3Ey zoNF>`%~dt~s2_cM-LqnsV9-lq-sdc@wU~F*U0DTn<7alAI!Lm-jA?-!I z>qI{4EA@Jw-33-19UU`KAC@mm1}M#L5D|rf_!eybs;cY0eS*ZH3GiafX>~T%i#syI)H6LN{~+AID~_ zJ|df2E;Y#{G4?6nOcdp`&h4G~%4@tT`JN=UM^U0BAnv5;7_$>Uvu^p__#;{%fRul~ z)s~)_iCd%gp5$S-*){h&4|ED|laLJMzvPjZ?}dQ~C}({?e1M|ri1xN;JgX)!aS432_9sZb8_$NibGD7*dH62<}d~Y`|*#3Qno8 zVZkxfqvbxesENn)1ck8MYUhETqd%l}hkqM)lLjtnp24X*MWmqXqJCy?@)vG>jw zC|-+~DBp#Kp5E-SSfZMp(O;WPW{<#i>+e)W1`OS9-&Asm@DLv*Z(yJp{$SS&4QNXz zY|isLe=V&&mA(YwSHS{abWHYLFv*qbw3vCz16hjaOp)Y)3y^a3rJz8k#4yl8cD3Jx zn4|HBy)axA=fLLDgL^@C98AeK z6VWir4WB;w?akghm>K`$)GZx_Tp|k4GwSSZ*Wv%OfT&!Et@e#$2ozHWrjFK}6A2>z zCS#XDY?Vo-y$mWh4*gzYG&Lv7O3y9o6k1WN-o$Z}?l2v8sY3BfDu}7T+VYe00#HPN z1FZd$T`~-f+6x~K&|`Z^g3CYTw1d~Nzn>rMC+?u1Xw3L4qRr-)rz;g36CXb@#;J5m zCppVy>s{uH@FbaG!MvB-TU*&*zIE~mcfDzsv1@!f-CnBo*^NGkXi(e2^6&?S4nmy2Wd|Jx7aja=;-JuD_@~^#xkM6dP?E93TLZ~VuYam;xp3X z^g9aH)*Ofz35Lu4)rXr{TB*7=%Y)gjQ8q3~fa-nJafeqt5u~$L@wL5QWaQp(kl;IC zyeaimtI)l9g`4Wo6s3YM6>LB}4mm*VFSD$XUV3K+6MP@eX%E|Z>w_ltGVumC@mc-! zvR(hEl;YSZw=sSV&-v)n&hvZSwT;xs>(l+k4pla~TaiqoUx_2U{%(}pmsw-rb%tI+ zv=YJc5Z_2q%>^%{CcSXA)4skwNNKGO?CZ9ice#b{q*Ly^xKsOahnXramdByD`u!<3 z;_FO7K&#;?-%>?)N!9f5l&{C|uOB)(WMw9snO*G(2^T>f8D#%qRZ!sthk637`v2ur zWc)OSxv~LAOrv-PGcaj4leJavf3FBNY@4@^l>YF}km5cALohklG8kHc=0;9R>Ih7? z1Ex^yzWpCo`m{pd56Fu8JmveXY03fW@{H%|T3Tlt9v3c9soEdwB+Hx^(%Zx#bDcCT zgxZpZ4cwXgn>%CA} zuyeCLqS{p;&b6+t<)9ksI#Q`=`jsZU-s@VQY~SqjZlUS$-K!ff@Tq}5JD(mzgoCi9l%EE zGt7hkgKbe{A)51M>~p5tgzMhJ-W^}Hdb%%Tydjuu=f^d67Vzi?!>PA5TRwt4H1V7_ zH4TLRDrUEVXknHuhF&NCDAy6k{`J%S%!<)dZ6BfWSW6}3bGE4y%LOTq{8Vz0J;ITXK&VM$-3`2j+xMYFK?EN z%2ru~Edg<&Pnfi_Px*N1^2^ z{Z&22p7WtGyPrNTRAuza?E?7#LTQl~|#e4@1UJCu#Ph%gir?*+#lt>DUoA~%F zto5*_L>U&>5vzX)Cq;P9^LkP9;xqrNM>ro%w+hixB#w;vMAiB7J@v<1AR!NgDeCWc zSg=ow!?WZrpMRuN$oTy)+E!P345WxbQp@}6QT6IQB-eIV&B4kZ=79xZ3J%925IDfg zZ5Lbw#^=Jdn1ae2pZ+`O0?P9Uj z@3`x$b3INMnzSmRt)lX>Dt_H91uxP+jr{<~+CS;YJpOI8p=s!q2FtwY?}GoK_XvP@ zL7uaymk41K)Oygq<~UHo{z$KcRE^R-=;M?(4tx*CTQ266D=g~8mpMI%%@&Hc;CVi} zko9mPIMRqr5Te$>C}VhN2>QWau4HYd5NFgQjl7OyAkhrwcy*mlfU-BrnLZE{bOZZw z#3mTfK$=DtI2*DCi(gXK*vh3fsCODfq=>H}81gjyEOKPz34DYG%5TUmguZ$vi zM;6Ph?JPdfzv*0}jBgk#`7l~RLwP3A#bRu8Wc~0P+8sd*Nw4phD_H5>0=%b>?ulGp z6%@gNSN}uC(B$l!Lpd5G`@Ss&M&2rJT-?jGqSm`7K;va*VoG#chykVl=*BZJDuF-Z zE~M|N(|q^Eg*3vCszZ4={yoWUh2__Vtt&}K?K!|81A36-lanWBy91Z@21CKKen9md zi6xLC9)H@h#`&_)M9N%ad_Z4y9xH668H%kChjZ<`df6pvt@QE8jpj${e3+H{d*=`BTnN(daOU!^7kP;V{tCe?!- zB^d1SFAN&uas#EJsIxK|8wwR`)pv;{Rq+%5RORkoFtotC=B6JMKOTX}w*a^FT`|1TxQ9SWD}^bZt0s@pvO z!P%DMd&p98+d_WTDFcJ>4m2eMee;6@ zggY|^5>^M#$KBlA)~pP`xeTa;@UtA(%0|u$+MzmCQc?m8a@AoUc5MEP&Pqk_tpVpk zgeUw&Jup>)4j%^_yYO`Ubwj*MdW`Ps0TJigN!Nv{^~@+9Nj46GH=8D_oy(agMjm;S zjQo;GpSxKwHaVve9CDx6AfQ31@iSw6G}nRT4;O)RMz%`Fzbix^sCpfZ#_g`RTA9rk zy$Uq03m5SO}hr!#&|d_(G8W+dETLTNWMS+DHa+oN0ibzW^ZvOn$j-#X4@rxN5IV-vzYVHBc(=o1V)*o1@QeuN*!Y{< zuoU2&Lg;G6!oLM{b#;O5O{tY`{*U4XA)q%#D zu(9?0*x;y%u12e!mU!IYKDw{3M3wlbv{L>(i1pTgRrHD#j};V3)(#>kl(y|@EO5zob#eX{6G zZ8OL!R@d~^b?&-b{z+^-@d-zu;iN6p+W93`Zud$h1>)_Y>%KXAEcU$q@_z!=ry4$` zQgRNWfO-{ zSVS|yI|B=sy88qq^p-GxteRf8mH@B5y~EjHa8=HSP&)6YDTC8(?4Ztoc?j@GhXr+E zgS+c-YL)REjIh2sgf|AIr>9@ybz}AWFjoWuF?@^}Xh>K8azCyX25YA!a8Z16ewdb( zwYax3azu5se>y%ouaSC@Lb#VYYI(b2d~`q7^;f2FY=8rFnKWWVDR&$C1QLpZ8AQHt z@e(~Hyz=fHy{QDCp+2*vDiNpCojqsyyV5TAwEJzn10-er>m7f01*#|XP)$+s?*8Ka zbiUI@`k;c6iepcS$>7RPN8Ld0?)vPnydQmkE|_>cdnpl|NlCIt*{iELLbEhAp0m7P z>;5LC`HFhsAbu3sY+Q+nnB|q@F!+&{gF0c84f@2aXu&6F*x&Y~?s83S%dJ-1O|K^2 zdp1zAJaAUWxiCL_>&;!ji)J=aTk6W%(y=unlPd!2Ur7cw5 z7FJTopm>8W3{iaU?seCvVf8>&#Jr&a1>FTCM6ScByth0AMI$RvRr2%g_LJ9V^y%Gy zc=nJw?#nffBl$l(3gAEk-5n_BoM7l5L=|@3q~J-PD?gerY}@7qB3@uD6$v9QKt&)v z(Fpw6XvG5@!F~~#O9_H(3`j1jD~?Wl86`;z4`Uz2n&CE7W)j+DNj^f+Ui{3tzj=pO z9qVgaUUruf>We%s?N_n3ZbHN<1@cn-)NRRCA(NsMU(l0#{RdAW2C-R>jo@A!}o(RMb7t(xOg~VY& z3@$RMy61+Wd!`?(23(0DMj+B_eS*dh*6VhZTzkyBDUgeddIB%6Bh2i??s*@dOmx%X zysZ}wj_uFk$FB)shy<=}(uEqaFe2n#+El6@I_B{W%3sg?;V_*Vmo&eZh?3T~EUNtA ze6W57os<1i|9wC_;I37Xn2O9=lc=!y`56Vm*eC=XVG|O}8?~><8QAhKX@A(o<(?D; zg%jM;ii!hZ4BrCZH%P4pv#a=c%G&Bm6fJdU<;48!3X#EZJ+$AYPe-Vq7O?@{i$+B2 z*%$d`%G(WnrXrK?!bx6z`xLTPh#(IlLHl(1A{WkelO>=yk1(dtUd@%w_+1TpqE2^i;^(K^WU9ZMS@39d){f>2X$9uxvVX8uR2P7v}uM;JUz>S(1BLCgi70GVyAm zc_t;H5p=mF^dRJ#?hu`uv$tjnlvqTn3K6hAl>p44$y3oCdpuG+{~t*84Z zyTidmE1D&x#Nky3pMi`>mRqBT*ELntt={W=t2a_2dGJ?g3AQ1F!J8N7=Q>g|3k<^R zAD26F*vi(sBNK*G^qn&AySll7u7RA4%yFja6RdhL#1L?KM*2ucalVRg5R6*DklG3E z^&-Bg-PB>QIS$Q?5+B7TMIVMdxATNRIckCg|TnC>~#$eZaG%h;m{Z#P$X5aY*0g z=@&~a94u1Auv<{bcs8gF%TXoagzfUHPLmO3&k0$gkdl z_^QqDzX$W#2Op)a-Oo37;^a>qlmkA}^5eNJG^;309Z_$;H@ez-IHav`da&|CLML#_ z`my;;>N}}BQi$JG%8%o>hNlL4?;l|lMv5J&6-)r9N^*L$P2ugthr-+LE-p%zRogo^ z5xhY=e;*sJUwhNZdV}u2xd2IrdX0@S@-6mVsQQGJTKxDxk0=V(JB_`A75AqgP4|`CPh{1{y4l22 zvu5Ob5h(<B!e^4DrAL=eP?9$aNP`@D(l2X!kTg|G}F{e6Dl1TowIWtfvH z?OFMr5iFs4)~qcIiz@TU(M$mK=I)!j%{qETEl!aX7Y`43?JGmMBfdI!`W)-QxtZgX z>_zbUyqEwL0G61~zvt$w&;{=$2zv9`3NTchHOFG}g>rY>R+^%q?zkKbzE#Q{f_6x+ zsD1YyCueDTdXt5|Xq&S*!y;h*Kyqp?&incHX-naM(Jewz`<2H66vA}SrPvy9<3p21U!6K>MzbV{79Jl2L|qV*sEh_ z)xDmx7IHs5EPtDjUFNtobD60C-6@#haytpP_A!qR-Z%^>*0h#yA2bq*1LPg-8lkTT zBu3(IKo1t$y6vNY6bFA|M2K)vkUX~=pE}8B*;M<0yA2QQ$5!stU9a9j`2h;M91Kj0 zeN3MFX7@#AW{pfIOMEMmu-HCXAd$VGfN~*nI&zwIc4w~qH6VUq#PZg{0<&`@MTz*e zodETk^v)WyYCt?+c)>u;&cU>T&PI4x|Gviu8z_HPeo9ceU7Q{0I4@(g&pDf4E;v?yEF-jp7>w;67~xDX!3|vOXx$=drJS1*HrU+pg~eQ!%}m)DsXp?QD8 z6|_*=ZhI<-7iFeH%mp>iwY1h&iTJ`_;m$rp*C^VD#@mbXrxsHSnVFSN#*=S^793DXDV758VJ;tE#Bnr=xp7>^Gw0;Rg28 zJ$FMDuuF6Y)U|q+h{aO|dxc32Q*Xn@M;T8 z6dwocfjt4|&B{kdwx|VDiqoc7$)7^RfN}suCA^e7&qA;pSolYXRHaeb%cK*ZwZc z!AsP0Z>5jHbgup*vJ5O3Wah(|zCXBG#=xCDa481%{};iq0FS|`T7jp!Hu`kfl&uL6 zbWRfrZrgt+y+MZ=5_3DZ^FBK2NHn(Vj@MuRFOz~w?5P|V>sBYpPiZes2da=$d=4O& zd7YAihQL2Ps}R;h!C42e5p;#Kh)rlgVNTxmi}nWpJ7P2b`+b~d78b$z$g&B6zQG&r z4Vl@Q`#w{Svw<+rqd>SHFJ(a_GRsh@SN_6#mgp6-t}>>M!PFUb*!T`}KiK^}80dP6 z#f^{d$#AzHItnI>^7MzNC2p2+p3&Yc{Xdw<}MZ>GV zswD6qL?Rw;S1#r`a=wh=H0g&T4y=B|0oaO+oNo&KM!868#xK;zscDu74FnOtuT_qvk3{g_oqt% zToMW}Ekpx&9L?Wy3CK?{UUN+jk0BK}eeoydTl$?_a?w>~NKuK$#Tm~~rDSh3v?XF% z`mk)dyPMEuy%C<$258A;Mf6u=|8Xth{DT$yY`%8 zokSei94lTi0#(115b$1c2?q@?)_a@uhA3gr7Uyh|b4n2BSRn_q&nR2U@YRx%y zzeRaHnRTy>M8cjgDtOr7d}_7!(-}G1lJyANV*X5?7iz^6xd#^iYmi_ADKYz7TSe_( zLI$omW?SU31SnB*-pKR@Mf>KG5s%+IqUU89z7|CaD2Yvmwr$2$jqP{w=6+xNs^0iU zzs`gIyZ8QTp%DVJlw%^kEHL1~SWc6m27`vbdA_RRoBZLQTO}I#X~Q}B!&PO&<|^M6 z)rgG()8sTgB_rQProI)=-QMR4^C9w*7`xSCp*J>DYIqRhiVM#M+1vF(qLnz;dbICC>InED!~i*j1F zu#Iy5B9F~!_^e2Q#`s3zjj^c_4rZJ)1oWZQ)qj0veK}>2^OH!1#o%$stBASs^6Axk zbR^QxPez9Me|-$|?|IP8BY}O}t6A7aK{CA}Kl~}`-6dnjJEv$C3mt)AV0b83MjzY?AU_lqy?~Oy@n;hw+j4x5kPOZi z7OkF!!$8l7SIOBOoS4o&^4yDCjxwKFz{4BXua2}duJ)^dcV^cQIey zL~mKh@75SHWRd}6XelX03rb=jeUOk`k~a%wqF^{~aCVI5$t&>k?-CB8_+SbHp}ki9 zYV${9cogf+uyj3tSsFA%Vn1mkNTbx$MxYUds^l_|y}21qOaJCG+N(F2;T(FfsL+LF zr}v@TG@<+K>oc(Ji!wts2!(^U&~lp z7E03byB%}BtQLzcbRfbJ#zdg2 zJe0$!F6DW|BaZeqT{GebN{^$JoJy8E3n8qS-);~(bVG_jXl-2vSwt@t>KdE0>#WQa z=AUEUAbT@~Jkb_8mUU}6pXXr$1@4aBVTO89J7fLC5i8FNO?1r-EiE^JuK2Rl z*a{EXcjH7rdl9|X_Z`!ToHchvi{Kc3V@n$*q3EOQlnrcVFyQ^MA z-WCrWIpPE zchH2Ala?-Bf3`*B?OV?rpC_EGJ>7wV4qwY9vROtA^t$_>BM5csT$%2_o?7VkiFbuE z40xoJl$0#t?QlA6L$<>0Vjg8?XJWJ1V#bjA`it-HFi`cj^xT;J!DGpqE)ALQz!*+7 z9}3@=*{$bFN`P~1E;rzY3gaV=#bP>knMal57{Uf~EBb6@DPlBa6azG4QIZxl+$6PQ zv~i)thzG5)bYg}?>d${Xcq>}Wror}nE!sQezV4$wN^EK59dvg>@@k|K47`xS?RLh^|DO59!8Upr3U9J#9SQjuXX;h%*)TWI<90K0+*nO zcMD*9&w)gup8TT3Kw+5RcKq2RYCcHLsC1sP8yg>wii#TGtOaEQSnoq6`{Rd*XwU6; zuT)|*{%RLy%h=H+EgXa#C}_P1m*3$M3o(%K+Yn<&=-aP~4UG^;stak_ek1Yam0k|m zWOGgvd@|0f6)E}hGswLY zvR>LHiiJ?`P3#~bU0lQvUX4LIQ%Zi0*E|ZX;6Ze0l}T^B2&cw&aXA5e9{Oin;83x# z;b$eqC9+}0iC^c8jEjr2S^}bmdJ6XgtPG+I2dB$76^;;)|6Vc|1bBHNhiX7&V}SZ> zb8_kKow+wR14rfFHxC=cKKu|LOQWc0R9V1NyI(-At#9TkWuNXvW}&so2ViBeL%im0J;%gn!Dpq*b+ zLto>HgQ$rn6SSZI{W}CmPL!0IFJ3?}!yz;ae~WG!P_JReWiDAm03TTGFEPX+L4Hs@ zcy*p&J-(;o-mYZv6nJVtW{Chle`aQ;xVSiI3yT~wuSe|TFXRoleCReLUV6IIOTk?m zYbFM#8xAF)m)dPYXkK<1D=gPfck zFuOgVjRmsfkH$tT^6c9&b@!`MX%#@20bO)aiIdxN{f107$~$*}x8AY1;{c5}P~K~V z$l97okD#`PKL!QRIL%+g`?7-Z-_1rg~EbQ+QJE^VU zxfOFY9{|5j>h1jz)-9D}=YVdu#S}$t?jTJse`spqv|h%M`P#?%)+v)|C^dQnms>1V zP3QL((}l;PoFG1(KDp>EXdVv7xc*dcpd&WAdF-Y!o)Q8J2F3)JAX-{l8i1XCAFK_P zS$$2%N=+Oc525vih|0hSvskNQK8$K05_}gTQs;YS9-arUFBMf1U~drp2;4R3sxZJK z)eA3^E}N9-?d|iHb_(Jpxt$&CB{#bzZI{ZnJ9+HZY>#=8+k3yo%&Yf)6s)JPlCEpt ztToX|>PWg1z#FPqblceH+16UTabJzkKbNF1`JAq}=4c*t1i<$Y^If_*Uwhj)SIIPD*b|kb7mocBMCe);l z-WvgSQ0u%0n_)i;C_FQ~P?-m2asVb$uc!JzEikKSenok9a290D;A2LLu-}*xgcK8i#|IKDYDKRq zA#_blGC2fsxuyK*7&-jgq;onRjdzM!ly2C}(#082!xof@0ba$qJ2-3s3A|1By55>4R=suZq#46!}PjLkWDWk zwetuNePJzpmGKt?BK&d8jlu(x5f}L?CQPFN0Wik1SpZ%x@FxNXy7uUosiPKde5QQO zG*F4s`}jj(=zf7#GnquL%JN8vIYXF^VS$W531Qam?RS6Z zb6D-;(BaL)`Oib)fGc6|%@f}nRy?YEbd+C#5N_+DEReprFjZe5pBEF2jbLrHdp`9= zChzu*8`f}Z@qKq-4rC6MEsT`P1UdEmO`~keI!i>>u5q){bzcD)6y?}}EM{{x3!vPl z5cmxjXB;ahBh%T|_E4KA=Qt2AvyISnt%1MtJZwYpJndUnF+@A_Os8$Gl7b) z>OR@F>Lnk!OL_ULgV-alT_OduE=Wg6woX`oX1cGO?r zUBrFxDH`7=PEtTMD_+9+7q9w%zaFAQ#u{=0)RzZd-p!qEuAf2#cMxIY6>4mw#J7kM z!e*@3R)~u-w~711Zfp%?6~!h3PYkf68r=qT3W_*50_5Yk^Hn9D<$Z(zG(PLOPd6Dr z8uDcyEvLv4es^c*sNOJrnvgw&DNojnuzc-U}y30Kz^9BLE2Kiiv9u{^8 zx^v3O_b4ey!fE$o>uEvyv%Ckrr6o77UTLeT4IdKvkhwIJtLCuOKM$%7fZVQl0^g8q zTRLzNkhWr`E}r};GssK4R5f0*5|_%DuLkR#KFm<*BFy2oi)gQe!*f182GIxmIVkcV zFmV&U5kYwScJ`srU=}NVnoDf^=`-YP7L>b}X@KD>j5+vQ$tBTZvCk(`>iH{}rou z-g?kL@|MUSn-4{Zu(MvnyR6Pr_*1?{88PWw+#!*PekAq?j4u4F$)?~pqQ3blBI*80 zKPJMlHE79^IFqg<{TUvjyj%oP2)E;Ehj8O#+fUE>L7Ra1J65&=%uC2`;sV~zwHWvH zwKYNGzGS1`#F&$30n9u+4)7L_Q8fk-8lFDr$c`q+Au$8i-?b~~{;_740534(oE#ma z;luE4Pp77);O6n{TMiXH9vB|p_XRfUT(~@pn;alfYr#k}X2$x8G^Vp`F_=4cv=QPO z`>*Tw;0|piA5(PH(5dlRM$UF*3HZ;s4Bvj_{fAyl@tkuhBxZVAJ8`?4tXcE%AEDp+ zG1_|hUWMFcF~8o;KY}mmFh+reCj8obVMXwxT`(7krl#SysvZL&L;Dtkgx*AzB)@YQ zVV<7u^bQXXgN@!@SPhN71aDkehCyv2$3iMY7X}nhnpvLv6cq=GXKlWF;R5&V*JCsgcRh1k1JU|2o4~bE%KUwd!bEF+=le{6| zY(l3m*9gBYMJRyw3qC#Tl- zBGV5SHR93EW{#&_ipTLcZlsTk)NaS+iixhv3qGpP75Ha97jnP2RJdfl9HT!0HoJB@ z^~xIh_fQ-;oI08Z&&+T%4wt7TBq$WkH~UwzYj@@D7s8nc;b_@bvn>GKeYTwSgJw7< zkjn7tG3>!Cf07EGK0+mDr-3fuax5MYKtwA(xa?YbW&XPPv(S6Q2+4KszhBz6)kaU} z;ig=gW;pE)xQtQ2RwEbeArJN}E_?x#p~_btyswd1Rsi7b0U#|@PRI{Fbeonoxa|9s#7oMH&vfLsoLgZFWaZ7QI zna%n@){ezw|JegJHl%h<^ew{89Oh&HTQ=tA0!(Ue0OGM<9yEbOI7s`1VALgu+tX21 z%^Z27hjulVU$3P%Gotj}nZyF~V+nSL(%~Z@B-niFCTg1AV<{vtbvO ztFetDX%ps@W%hgp-)ikQ7mItdNV+xWFIqFd@qDvA|G;%E=+NU>C0H0gVsc`?+i)Fg z+TOK%*;j{qqaAPc4iOodfQhtPeSd(G$Jbx6uC;W@v)>OD1z&!P(42hi5Io>pa*X*> zQ9g+6=twWOw=UrN?+&Uvr+*F>-7@z|t8F*GKQZc=?mGAsBttd;J~@i^HscpTRl9gD zr4F6y7rme5vDvFOM>bXnB>m9&2~Ifc#wi{jx7TeIQMADz?%O-AFNgol1;|)iF+!1~ z-<>*a)oFcRnX-X@ZroIjx`T7v-28-8+nk@8+O9V!%^?qyO76}ricJ=$1}~ioI?}K+ zsf)gY%;sv!#GNrBfA%%a603_0P4=hLifLG-JH;*kxUv@8lB%Sr2SaP6xK>v*hSKMd zLig-z#zcH?$H~h_^Q>^GxQq2Xi0kR(<6RI%v@|uH0#XB{D@hrdfmuSIHxu8sp!9_x zRx?Fr5e;(1^v8@Jt|35~2kIgyKyvmyeZoa!6hWPsCLRcfViX9;OX7tU6#4*01S!E~ z==#C(kbk6G&es4m($5CBF*0LfUjQ~DN!J^8LzX|>P`H@!)(5qhQY99z=+kHU!=q}bGx15IMVD_7+h4l|v9*MTavpN(KS34oFmhdEZ z1*^me|9%|zo8#5sP#f)lLyN(u z?qq+KP^mVN#V5dGU`UC&g+K&jA!;DT*!x3wwOh3+Ru1VKre0B4e`lZv0G_gTjpI)c z2oDY_yXjo#zwk5B9f|%j8O{8E*)61bHkVB7inEt)Ej!HqeX5@E31-p%8?h z=A@)1%4wYHBKp{WML3XJ1&`Fypp@&2$c*u?2X2?yq?m{d&@{{+^iZ}f3FUvNRZ_Q& za>;#u7tefHw!0C#)pK(*^J{tYtG8m$90|7v_i_n1FIE-e3yH8auuyeB*LEhOrsIbB zbGlb;c&xE1r|T?hH=5kDdMCR!W-S-{Gf0UBY7)F=>Itx%6fG9gGE)N8wCheDvyI+H z9G+#llS~i!ioQOpbq1vPzZE3+5^ z--!D99cG%@Wbmh!x3Z}a74zP2>&Pcs$fZ+u;_VABDz=#VJWsv z3@4;-i!O{$BsP51F}z*R|8Dj@QSzx+=@>q^d+B?=cSkDhdOo*O%$QF}$E2@*K@HR0 z&_FUYM6vrBLf7y`G%o|g{;tU#f{4T(48+?F14Ad2+DOdTuSkFYW`yO^b2EUfa#V65 z)cZ0f&)ghE==~`xiMc8sp5bIfYrYK>Y%qaa&(Y9gg`+mh$VyOukZsYAMpK2Go0}6g zUG1>(DlZTaG5B^g@|?-`dqDWjrP6vOA~8-k3Vt|7c5B*QJy zrIx5Z3slDoievAQq)2h4d}DaI1^mpbxl_y~pG{;z`L=M340$iBC$$<~Sf3~I+U z3i!#cLz&tJf?Ydr*E&nD(oCGjItxm^2k|*Kl39s+hbIX4Qzv(fiEE)Tmp%o@Kl`&yHv%4Fyx5CiV6C`LO-ipC! z7>jka1L29ogMn_4kuh^m^chU0iN#i}*v;*-B zBAEwe{m$^#TevN-Bok0ZP zq$vF!1I>2Je?n72{+92U93eyeV~qKW1(LqsatHotYKy){fk0%hb=*q_B(s+GBA%(%h#9(+-QD&516#1 z5KF(BcX`Y2+!lEiYeIc3xH9HN39HnH@IexsMN^e0yNEF95yCgmU5}-fl{DQDL;9MC zH(nT=Dem#pBpV)MX;EL?Agf`#{Q5>;n%d%EeeXoY0nV!#T5x;K2942Q>2e1g{i4@C;Rh*uH?L@ zJygLqFAus2s?XhaSDh@5n^_0M*@aGiq@Y%@Hw5Dxw0c9^6SXEQtsKI?eI2U4%19`8 z7X<*1(|xfIV%y6StG4=`Nv#9gq_wVxy~9taYQ}kf1Y=xjC7-kA`)qn?{Vy4JRcKoC z=0c_w#EKf_NVBJL-AG!BDP}#@{qA}oe6&#%A=i}uC5n5Ao^L+rZ z`1!{oV5~Gm)Z7&Nf4F+fsI0oRZFtdwNJw`n-Q6Kz(cRrG-Kn%7C2`RxAl)Ec(hbrj z(k38`QNEfN+`qzBv+EU#Q@7#&U1H;h-Zh!n#T8|XG2|d&EM(7A(y_fSiDN2qp zUn@_ySMg89U4IQ>VHgFm{_Chw@t`CqhQ)D23#e|^r3yX&WD~lg;!}H$fe~@-(pc>H zvw5ff1Ib0oiFa#Smxv@h{HsR4n$^PUWaN&Dp*O9!9EffT_`!9y(}(j_a5SMYtfcvT zJ;j$TePSkv?d{mB3U#`tC!u!S_?AwoO+w~>KC;c-)RH&vuIz@JuP!;Ow?6n-ePMqn z*B^)sDTCqd4!}kG&$|;Jrrh;(QQx&JgR3BxHQ}XCOT9vSPC++p@;TyCi*J+fjmLZ~ zgP6=zV_mVk!{V2?#BLdxRgT3GxIbM_liA_$*+R-%j)7h-0>p5GwE5LZ%lP#4X5%ij zG>1}kpG-8Mv?hMUGW*GP6fw*KL0hy1Scd>82LFO+x$aesFc&*JJ0l|q-?seyLx~II z2XkA-w3zd)0^n%!PiTf{!=^Raxm3l0K14%xE&w{{kYuvW`u%C&b@XUOJ%K=QGi-2RVSN6 z?>U~ba}fmk#@fwZHM*={!ooamFDtas0`c4 zoaI$$2PtZ0XyIADvSNV#6IMWRb_?dZL1WYhaPJ-k2DgCT0diD`{3yREdn>_LA+OIo^yqSTEfD?Z zF&8Y*n2W*9RG^UmTT4}7Bk2C>P46$wXWTT+wrRGgtpDZ16w)zMjeh>}rRP|-xqxM+ z7@y)r>xulH*h4QeI`rc+Pgi|?#pdv~AFf!dDF#Y+G#>4Xw&V4-Tj$)oN(!6W|ED1_ z<*x6}VWj~;63|K1Y-%-KlZtdg>uoX5$q8duUeILlVr$jMD zwCE9`?5Zkb89Ng>$YYbt(Yo++4-TvD6Yq0uiegtB@GZDP!SOAuBQ~1 z8&;`nqH`DJrhruShku=z01Ty%upZ0l0(g|gpZlS%CZtrLdBT0lHY3%``B*!nMxFOC zY(6gELIv>25YrrnGl(~{>D;#<=oKa=1bKV^ae^~ESRXi1R&f>U|Nbtn-dPedTz#!s z|9s6UrtjCwm-!i@Jls>i#8p_pas?m-t4{48VvlmFkfHQf##(r}^}Y?z^Lf0W0XaOJ zAwZykpwo0kYG~*bDb@4|5*S})Ap1o|M5K2|>lk?Y3RX^H={5InPe3#KF)Jzix??Yp zc9@S3S&tayCHQ6M=KxNoX9=$4gs?U@;KhqEcmhZ1=Ap)=K}i7Y_F#>50c zDY8C?`o&8YOFtb~QE_O6{cdNtSM<^;BN8_IXxc%tQz76q7)#^PP*G)rc=$&bDyrou zYnlIWfx+MCRNpi#$2A>n9cT7ANRD~17)R9t57O7iQf>z=)~G$*K-&L?btsA$Es5g{ za7C4D1Pu+Rn|z^2I@^L%oW=9Cx3=zi9c8SL_QUZ}YYw7A|AWI-RW-T@q@>Q17dGT1 zC4|BKIk&rum-}uA$QIgQk|}|r!U_Wp0@P(tS7#(8O#^l^P>%VX?`b(_!YVA^SAO8< zk<|oq3x7}D@_I&a&e94ED5etP<3Todz3$%kN0|Em58$#pWHCGs|E|n{4C~ITWq*I> zrbPQ3?uU!?!;J%rH?Zx<+df!q1e`o)U`qvrCgpWskRcKhC}41~-rk<<;ie3~f)?~b zLeO(REz%KvBT%#}h^Drj!BY!y7qIB(Dk&~DAIZ48+RVfx<^Kn$N`oV~jrrCopOwlP zA`<9w|D<~?end)rQqX0cMbua4T1CrUmYo9db>O|`;Glqo*xn=(1%5Zxceux3^`wLZ z(DmbFXCGzWH0&0SAKARv8bjDjP5sPzG72Ytet!c&>+5Z@?qkwt$Qf$MPV_7w8=g<%>C9^-o zupCRzajQ~r$pH;k&=hBgfbrVR0gj@Un8JXD36+2~KbS2c^%?#BCFq(yB9>5Z|I6>5 zUv(;-P|azUn~#T}4H+Nzx#^Fk=ThsN@0A5i*}H_rEBHP!qcrLb`|hU&ZUDj;V48>s z3m2!fEdhLlRcp&BhDil-Nu=O(-kBq2`|U_Ic{MC5_fTNQC1!Y zu*sV!;@r!2t7I3S9_e`NqFCyuZ;(~`Dc&jzL_7pt0rVAK0D61!q$`EeR3CJ`BqhK3 z*ypxxP*AwkxG)G1trQVPr4vcuTpdK z$N2>=VeMb*DDcbCvtPIifQ364d?p^B$5WR5$npjg!Mdm&85VFd#1bxFvC$R?mBGv9 zF$o^_##%S-%v8{D-3bFY6@VcZhszrGJ6RH(KhU`A7y2uQKw-d(*=+Rw?OS?Tok}+Y zvc@V!vbO;;z#E4G_jIV^kzYH=eF98+Q*J&pr_af#I38G~8QP;tk*$sE1|3RNkr-I# zY)9eX;MyAJg%1XS-}S%XxQZV}!1Q2wfpeQ5Q>5P48^UU+hf^JrT&|+iq6{lxqyyB- zdvMjEkJwpm6$|amw$d)G#;1dR^$dW4TCM?^;wB#V`!E8p?(l02sJNp_dZ4LZNuZm)=4HFoEs*!NcTkJm85S$ zNq51I42s<*%x1v)Kf>EH_R(L*vIF@t?dE31ebvDXEJ%=}J!?Wzk3KL^C&lP#ZwFpo zABNKefCIF8&GzQ!a2zv8QIp<&TF-nwo;cLzD3<;Hs;#CIJdEE_etCoa<{EQ_6afQfss&C#I+QJRjzK z!wDXR)S{$4A2TtGX ze|FGv3gROSVRkkm)gv`DdjF3qJH_25uJYpfyIf^-Zk9||HKo2+RM3+Y-SQ2)W`_S*_A~U zM?qqq6(3(6pxy(%xHnKgh@ASpffl05BAq=S2sL&;d9RSbu_4U;iHezgg z`eV`vxQ^<9X5Pfa2_TNtFwPezA*D8;z<_vWslhY7swhd7@#Q-Z?39!z(0To4te^BL zZ&bvgL_8HPJL-ns)A#H=95U^B^sg`=un0a!0OslYY0Qrcw?7e4{#zJTrZD1I`>ka`FVp^f8 zs|fKq1htCk{-h-5$T8}Ib*I|egOEcrGdyf;4wtP*$PqAe4(1#8k6U}9?`hz&ZZFka zM5`$>&rb@V06K+|jJM&%`M+?ikR(1VZ$G~`zj41lCpiWjfjv-Lfg3phm_bq=TS-K@ zt7;}1uPg8f+}i_4^TFn(`|(;ICh+?M92HujPOsN?lFl{n)J5#2%~WOgjr34C)KW?e zCvZ|#s7#DFMsEw}d%NwU1W0ZE#{`CfJ?gK|NrOz1=ho-@I|CcbjC2-^XCfeV2!#BK zQ-bK4*gVb9ZKs2MGGgo_R%k}Muh~NyYU7%~4BKW&<}#YwGniS-uc~qeiuN4oNLu+c zQ2ihIdh_kgH;&8}R6AV!z3`Hl5dZLdF1{cOi`={|y47fz>gH97-7gg$irq$in{2Pf^1+BoL%bYSEq;VK2}I=<)U zPiL=~vdV^`y5_Bo~U7Zph#(1*+C-JxkHdsP*A8HMy8rtUt9ZO?*kHt zjEszc-RJfQ3Y8l03(1(0_``4n`)}6Kp(OLYE13uN-Gsk2z`rK{|d}dsLf_6EtkM3Ta#@BtZzUF z2G&X$Lhc94{)bn~bt-9|p1zH(TO>~?dUF|BMLV{^_#rZ#T1rO(-}R z#>U2g_jr@*Zfk+c>v|zEty?)IE<25H+HZZKO#j_~mA(Eef1kCt8-cqCAXbkZ%I8M| zo5*b^QGig+R$1U6I-blG=-<6w;dYj^EE`glas7%8*qy)6-mPDAXtd{XC$V=6_WqCn zlRfQpN~m_-1&L7o@yx4~wMN+l=r7>xnkJq|yp06oQfoDlH}@L6w{Za(cyH}2RIm^D zDd{{%V!Vi0_N7Arg!A$mq_|JDb}RS3faHFyx(U8qc$cx9-mn=a1-z=dO$3{spzGgX zO(i;7ej*$3F)<$ilB^DD(~=S(UU^Ks+}pdIoyk@pH_+s7q}MjQj4l###mKuKp`v_S z{&(8W)6)|$F5Dd*8Q9pS9UNSX3{?h*VUNBIz|S<#^(mcfM$wxUM&p=lT!`>Fs!= zn+s5Us-CH`P}m$!FS7f!62Y7}hh0=Gfdreu_|Y=n>^RES+6!f=F?n1)zrAZ;rWnp_ zohmaxJW<;Zq?PPmdy|_Rllm0;8%Y31dER(9<0C@b^VigwfPlclViV8?C~oLH$AT2Z zh~s#(@>jek%{SpRn|Ta3_IT2b8<0^@223jn*z~uW>l&2H3y3WrJ-fes5smorC7-@f zuhH$e<7wP{vglTUI@gemDhrbX<>PftIz-V1lQ6gQjktKg-_^FZHftSKjxS0~EG#8+ zi9mBC_eJSW*)FBUFdppq*|_+&)FS2JqG_|#H{BhGKnmFV#8|MrAz!p7+i0Ooue_4M zCes%OANQhyx2nZBA_KU~CmiB|t{->`yI?r9{~*J|rT%rE^z>|-X`0S0_!|g~k zyt=$XgbaY5TgN+W%IEUu)JV_`ZwDf|lMExcrInnl zqVFs6#NNS))8boEH-Feh1Lo1?uW%+MVT{~2XS){vStiZi7lkFGkMkuS%$LC?JQyen z)qHGE>ourjRT;ZvtEfgR9AmzIo!p+7)~N#!NuhYRXU0=?btXV?2S)*59J>f7?v=Gd zh1!KlUnR7N9D1?T^@ID$)iSnscZCew0)XJpaj?gCFHBNwgu!HW&w8b*%+``*tbh4j zK128l(6B*?z~Pe#i|}t>0Mrw`VG97dgPn4WyBQ?H0Of=4Xrs%%K6B6*PGe1q_2e{Q zE>0?p&uY_cN9-vJ{8E)iRa=!gQ5IF0RG1ha$IaJUorSd+s>Dw3iVo|<{f;Umod{RB ziB}CwV3z~1?UiG^=Fd2qyK>EJ0dDTOk>M2J^<9`$jR?~`3t>i+z|w}71KY;9CD<+p zNi17{Qik?Mg?uxWPrQK}!)r6$9WcuQZ>l2f--q(bASMkc;Nt$KMo`hL-P|bqxLYvR z77Y;|Tv!s~8^70oqPlT(av}yK6%c$eqjGA#>|W;k+#(~F#DCGy^>Q%P`#e3B)2tuJ zYfeiiRC621sWscsQbB?((7c096=XC#?iB!mr-?|UOYfeO6-l8SQdPWZk9?LtTVpZ0BpIMK_P2 zfayj)61EOaK+$X}RxxL5G3}KHZ1?1p4H0Pvj2*}Ij}puyGbLYnbog(+wAMR31V1h$ z;0hme#;v9$-@XB;8IQR&n3#{0U2+kx1fotzJVfcIOP-&U((!jL^WLCc%XZr3j|bQc zNecz_lbG?l4Ef$!xCT>;d&=$+)A}aAtU`i@*wG-Dddun;4A9T)=LW{>}<|lh@BpC21Y5%n4s_OYptE=b`wY^5^vn<)@m4(LO+%BKzQUG7Vz5cfh z(tD$&+&T;S!<|T)T3SSjTVTs*jR0obq@vl&TqhXi&#AI!$_@N?X_plSE>c+^S!wD{ z=Rz2Yj0WQ{wdd&%Nl;3nxuZ1A60s~fKf`c=rizZ1_I>W9sDG!L3F_cxroX7gFeyaO z##D8GWdT8XB?1AL$7WDiv!7lPLURO9isx2vFw{mO`1_AWo2WW%s*aA%$<-~`jW%K#xh3psO?ZT9)g~ z9Hfn8W8m4wQQ*+EnO3)f^Eae6u7gr5zQi7obpxjt+Vyz zZqv(m99*MCFH`SdtScy|JjaOaqn!*{)9t*-9tsC#yp%K5ayKf(#4Yz}SnOVIkn}#U zb5$G1eHwG8zI5`iu{HeY4>Vet;K^~~!+UT;Uz~N!k?BR6HfnZiQ0D8rC^djtMlp_P z;j@K^Ag9;o@UYal`pJZ?Nc1ApdC4fRpj%Fpx^GCo|MJ`%6IyMfbB4YjwbFn{$b=%6Ur8k`K&NdrkN>AnveU-At2 zRN_ZkDy?P@iX2y4Uq0yo=I0(LoW7v%2+Y=jWdRsTF|SklDkQqp-KfKN)5)vJpIM)p zB}dXLV?c#UdDcOwYO|!Y$qhf$fA#z90s~}X9_#PEUU0ioV@}ZM`up*??-^#;v*SBr z{I)=V8mF3_LW~vO&=-%fT7%ohj|cnNR;AVJV0&%loOzDwAXs>#*K@SZdoj3wXer2a zG_Vq`M3Q)BGf4IGob}SgkRF!DLFM&K4uSufj`QD8`wT<~GFn|zjXanGs+X_JYTBMm z0XyodI+tWVWY3^`9QVxIV>@}jxmF>9C?X&4zTv~=vz1Ri<##(Dm`I}SmswzWaA7;k zI;7QSq!S3$+QC6NCOlhb`NHzNZ_r?{K~63av8y$l4WkqJv}BDlTrC%F=m{AaoH#zv zu>B=qGk&;HxCu<|+o%+KP_&d(j(Dq`kkL&dN6!#LNbDVUOj zIlq3Bl@8NlX}D2)N%wEa!h_CpHD02womkz4>Okv-ob(#D_AFs$c2xb2!lFuna$?e!&OJgrSn?e z<)RXk4?kO?^Q`{N2{!y}I9XWm_7iQrv`?aN$H0!ZNpauX?9!O?1*A6c0k*s9(4S`{-5pG0N#c}%{7n>ae_^Z3szHw{C?v$D{cl@L2+hVX$SQq7 zWyV+YcEc`7&}9ptOS(!%zv}-LcB0CrN}6fO1{y6ISD2L)()4pnc=8lJ^9MYo1SSq} z&(>t_=9I-}=#ZnO1YUXodV+(411JX2(QwOg;kbQW4mI%=rdKchQDLYeFx5o0LXXCa zhX<3b)S3tC%I$;KXWmwM;yBQYY5ruZ%19^%!3c@a5{A-sC~ABP;~2nfK2dSdaL$xP z2trkI1#8Mo;ZRq2b44D)l9yOvxvW)8bhnuPjKtUDE9SXZ&4)Rd(ZK#$cPZ51!|oP? z)=3MhFKKSLGp)~|`{ne#A9uj5wsQZ;LsaVQH}>^uHZjdV9)JAP#g%?)oqxFb{u7~O z)34@5*5$3kM9ZIIEv{mQJjsUkmFtG-fk1&4(|k9~xKfK~D+%GRx4vBuT-q7;7kiEt zh&F!2tIW+FD`omMh;iSVX+F&NITE|R&P#FR z+KbmXJ?oN~&mz<;2U{r^RF-N2TgES}OOr*4YS|2HAKJ#0rhpjgQ3^A~vj0XY!IX9+ z;~6)L?HK$Zu?^>X3i4DQxXc&p)^qx)wtfluUg2TSOf2%k_x5KtlmAU*fd?mC6|U{y z@s#TV9J7)Q#u?QNJ#sAY{3|4k*TTYK;*k3o&O;=duu!DIW?^9wkpr9?;lw9yJ`@}J zi9fDa3j8iF7zedyZ35`Ms|d^@rswB4zwl%;nv!bw%*^)_B0r7&F!)b{G~T@X%MZ;) zR2qK#4^J8ra*BWI-rB?7FyvdchD*BpT-|K{U@JZ%Q#6$~mDpt({VQ-+Hn?Bb0*oXLrf*_%>Qm>5{v1CyIS3qzE(O`U(!p-|tbu@v2#a z|K!8%u^85=k>_HoUb7o#k)2slHOo>R<_ zVl+<|pF_9bgUCFa3{9XorD!$xcJ#f547hFrpH`i^d++1Rj(`m24B}Mev%p}c5fHR| zST!O#Uu}icNH$W#?$}P7m*Q1EGbdXkt5yCkM17bQ^T`uJ(c2nhS#*w}NL0QqV-7AB z5kbKQ&j2oRh3Up5(UFO8^u;_!9n3R*a95M*Su2XFuU>^?A*3vy_LQ6F^gD907LwF-!YwVvv#wo?!1zZ2w z9ML3SnKG$|si>GFv6|iRsP!aR5Ldd;Lcr^FFkMK45U=Tj8@3LeIr`I9R+ymK+EKha z&~2DnSZJK!XquJc@y5Ej=J2Ypm=M@TP_Ofm^I-!k(ZH`%w0|m-6GKxHOOxXtu~a}Q zdn{P!>49eB&1=S)goO?E!*uq(jk#vxj||cYL^N?sBY>wMov{5YKi$_#&v@u|LME~E zIajx#>_^J9Kzn`x2-NJ(e?8o;J^q%q7oErON(q4tu`>W{h-%xzHp>LCyrSn6+GEVY z{Q~E!J*ii%wnCS+Bnwxo%io36#*`;%vbp(~hUP|2CW&Ef&Sx$@-V*PRe@;zJehIh! z)OqIm^;^kts`5GI`si8W;qVF77G1>mi8;QV_)JW6&*Vz`DZ2RL^HQsd!-?R^6#thk ztDQp&ciZ=OgYjQs@M^;TFbufG^gz}giTOX^u#IwZke(^^ zbViWvTUhv~U?vJW+Ji^8aZshamywb4$9T;$^XqD(Mmj`^N36G!=$m1@7Ac^)jFLri z?Bdc+EdZnmF#8}wAiM{idC(^X{{==0eB)@Tar30KQ>x$7tQpXFGv9@$mRTerDd&j4 zCtMQhHDw>-#*zaPLIiGP*oNt(=IQL#{#~9$h;fz`BcW_lNFLmeB!vkIkpvD0S1o~? z>qZ8;H{27iKIfT^Wa4{PyVVtW9Bp-AA9XsF^{=BB?Cn12k651~U#u)e38jVHk{%$k z36TDvPa0^?j-ns-`b!}c%yq-(&M=s81*d3yA#c@( z*JGk!ZoDdc(d@~Tak|xAGUDaK@Q-RsmbAKIOw@Q61;}$jZV3;9+C; z-vC=BqwnH-E^>8jMP((7-_iJnFV$YhXly;@^UGy?Uywvx|MUV_T01Op8Pyq9b^DRM zRTCNTf5tZBL)X9|R{kwZFM#FF@_=)YW49bwH*!AggMSHR8-pNH@W`o@qiPehC;~zv zg+YbMzKvsI&MPi(@ei0g$9U!X1Wp|8L%_$tJT2^VmZi+gqv+WDL0{@0a7;4-6(_^} zUlygA?q`WNb2gMnABHo1s@-i(|NQRe0KnDC`3O_1AxVGZ#Yw;v%HfHi59ekbYAh?F z(L8nGvBq;v8<1o6G1-Vdj-Lzi@^m567=%)oSmOv{Vi|$WRYoaL&Tf+ zaJGslBZF*zKNtf8qI7YBhqO*M{sslj^n3v$rEmPV>DMnJ1mwZ_=G1}-+>j7>9GkhB zU&HAG{Wb-RBfrIlzFP@`z#@=}JB;Bu1S@w^?#7!#w=J&hGIj)6?!YF%{M_BE8l7%2 zscqGJoY0Iqgd8aq)OJUm-w+VsqceuF0LsE)n1Ad=1E_)E0j?onmjjNGw6wJJ^iLqr z$1wf;l~sR8(n0>6y%p2ULd8@e(z}`$1$)dnb7-j%XmaMka&9A7TJW%PcnIF|FMuGd zDX6}_UtCxyF6O2M-JuL%72GW-@d-WaKfPdKUS4(2bQ4t_zz54-XrGl>Kh*PdlnDPy zqcHX-f|UvI&Q|v~3>qn}Cr-|0`*Uy*E^4tynMzxAi{Ra~=A#`!2IJt-YF=Z`zZ30w5`*z~BO6XR_Vc+yv@C ztk370iark!QXF;NL=ekcG|1k%m(^xc=n0X6xjC&)W5mc3lFlwlkGS49nskgd`ZEd==~YKmC#)c0HyvEcwgh(?bDB8S9}cpx*Ld>q#j z7{ETmp*B_GCmjYS@gzV?bz_mn!SGJ5igW#+ugELAAi7W1GCe_ZioalPZf)!E!25>8 zg>}XU&jz1>>3%@w?dY9w%JCqeB<-DLlcf@)b-7NbY=g=S_eoe+U!EPc;?uZ7#|)G}PEV_n-mMZX5TxMsOk81eLF zQ4hFI0oQpDA+@u&H>kP^hrIqwrzS}5$BwZ>Q_xV2x3xY`1=2fgh>v}$n*C90)tTdK zmtOLd7r3c<0h2ye4a2PP9ei|dpinMqlD_zZN+q(DoJxm+@|27$yBNK{AD6_lK@Hpp z_b!&<3XSE2gv#p(mK*Sd95T)=IM!1NlKkGk=b#^`s;Ed2a<{i1UOgrdyFHYVJXd8{ zrZ#`6Hsw+;o(M*y*OeR`sWixKL)){9*eNQN9&96>bjCkWx9Q>+9HjB|FCA zYz2?3KJ&;0EQ(J|bay3wlnYe!1=yB;y;ClDGeil)x1X319~&mu0MG=#YO>|iV{@8? zMqSJI8MpK!QZb2Z$ysiQL-aMe-V<;)5MgRnW1bpiJ5En#^W@5WGm?O!C>*Cql-_AV;Q` zdX(E2*qZ>+HxN6i-#mXD%IeSm8A{c3hf<`aX{yyR5k7_U3lt%t>~A#UW*RO_cQ=CM zFFm`_>FKd}ZSrPvNNs>oLO{>ZO!aDxD4RH{+ywM*Z*=~#Tk+Wnok4>(9{z`ve*1DlhBkB<-BvgKy6z*}2Yf6)x~ zBC@p3bSOmyZ~blDHF$_`34*f6@f{tH3L+vrM=~Zo!q!l6AV9rxaYlfSN_3V;ri|Mh%>=uo68O@8$cpX|n0 z9+o^e(}4kw;03a2jp(9B^LWn6DYr(3UPgxg>`z^9qdZ!|1e#zFk(ZT4Y0fB!V-qyS z%4SLk%4;owPv`EG$(kwvbs@ANMrc$SzS~QC@@I$Qzpj94pzLC7DwFK~X7x_0=9|oU zHwgq`U<~FvQ;22ccg~xCt=Q0UfP)lqx$V$qXPx~YM7E7`Sn+hUK`>R^i$@EBq0a|& zZb`(IMZ|Xv$%6uSs@HrIh6qy4FMir z{AK^|3U(D7^!`}RJVTX=CUanff5gh>qcAreUwTv$Mi_e=@+qEW@-jMsvgL2nRQS$Y z_hL7J!!?J^w*hcA|9b-!HiRMVA--wE!`&FAg7b3qW+mD469gzb6a^B0huXUiwR!&& z?~xqbTJ|^BC56Q0F|g{g>0|h;;;1%tm6XN++x3X z@`MlnT)?GRZdroF?O?$Z(1IFxcAL86B%Aa(K#PStKYDU$Dp8RhV4V@coGDSJ^j#O< z&*%q#OC>$UwWdrC8UhCwQ{ptD3BK*I2sm+rjKl>*Mk|gSr0^w;QQ#YVrXPC`kC!x@grsjdD!=Go*)BwV~lBY(hPF z7ZL0$f0ejO(Zo(eV**l2LC=qQZ|sG&n$t{7nZ{WQuZmp)Ds<$_G&S_mEYt%h2Gll>KWz%$=eT}1C7T~lQ?q7`+od&(m$RqxmzlfIro+m01khmVOejP_ zCu$$2hg@EoMc5CzAQADRlGH7E73r64@(91(<9P!YG&S>og30=MvPQ_k=fi$FzQaqO1vuN1)X6+8=m*;@Gs+Ns$H z0bTIoChnf7hM=4Tg^Rln-pQjuP)~OKtj89Xhv?ycod{9Jvhr}NRwzeZjVSpjfleeg z0aJ(lda~1!^t4gfpoT=Tc|#m0c9^?dh+IdAep&0;ln&sB?XNQ|%dv&%PT^=(z2R)N z$PY@8tH2UkZ%TzHMFsxS!2K)ibqp#@yTlF1P4w8ZW~rzw1E_DqLqp`8fjgpM4O;yg zd=S9PzVZkr`Tm{UFV)YPED4_ycFAUH*oYQd_}nih7q~P0cL#Om-ez~A%Yn+jiQhX> zPbDkJaSDk^`sdH52Um=mTtka8DH*1#*BG3(&*8nA{eU?=4-XHid$h&!n~6x?a0U4_ zAzN=(F!pMFX)cTWy_uhx%k5+Ah8uq{Y=RGq`X1Q0;r!>rl1tE9UehlxJd=N>80{w* zv_(peoGd`IT1Ka&1TCfcoPASh8e6%KJZvnhX)=EW53SbPLApe|0?`xJHOqcC`^icK z`^&%A7KM(IXW6no=bFF7j%sU0bj|QqTV^_t1fz>#dQzsL z=2Fa^pJKD#fe(%K$r3Ro%Zi;)mNs4tNe=D}LP8OI7~&YJFnYPV78fHLfqq!`>%BQ7 zaTV>IKAB{(TPz4<&dP9OiY?faWo*Kw343yCrG7Y9u%TOe8(ORxh3bBPcG@`dp+>(t z{f!xYkNh6<6Q*UFGNlLj|ZsbYP(zi9@aIdbet}8FY9v9jZ2Ez(XpbjD94l)Os7!=1t zi{fC0<$F9g?AqS`NZ!h`U7veinOzF1DUwn%`s z!P%kXWvYMsB+lsQ%=PJH{=ZR?oc-HVqSJcroa#L(5Gnbc&GPz9VSJ4d*X52mxF2=a zBruSfu<7x;b4d`d2_!gh#WAAI@<<3 znJA%mQWC1L?mL7bkB&ea#*#2Y>$ zyL$eW0ZJ}R?ziq%WjQ-0Sfc*<8ICaOwSWIY2LTI%8JAwq*M5P0J=M@WQ32}LeLoMJ z^tH8#Nk~YrvD?`{pGI~(&RIlkO^=LC&z6dcBjDW#O!MG~B+JoYyuIb`E^+hWctPxL zD7jZ}?RT}Qy{Tu=pgGi?mzN2Hq3!MnF8CK!T1`9tnBSWn5k48*p6lP3>#(4}TbF~{ zmJkSq@Is?&Mafd4)(^jV=UCpL{F^zE)jjs7re4hiX>%Lq2Cm%CgT*~D*T=WJvMeG$ zS1MgBOc+Ji`{e3qyvO$;RcZ)Kv!^5=7&;UxjDa<+<1PkFxd{ffJ9lEd44`Cpt&QK_ zeqBb2&9^SBMKm1C`9F2?>w3sxfe3OqR&P;7oBL zSGdHzfpC8RI6ijD#}IPXCjOTsZe?qa9OHic{pK#!z_aW8vJsfO&o$rFT%DZIneE?a zj}573oa~Y>c%VdAhYQezte!kjN$+tIZW@qR7_UbQ9sD!_mp{l9g}o3fcX{Kwt~icyei~iTH^SHJ%A+s-`*H--XfVNa`JzeS))!tQ zY4GP%SYMD6j>^5VstP2vSoxc6{l+vC)zD(sE`g32nO5*qiwiurvQ;K0KaL!p-C5+{ ze0Oyn1nX7~>4)&xwacaSr7@gxS81T*KlakrlKFG8H`UrKxs{$_h|f}wYnWC%}8hKT#vEYuR`s&865xId$k%VFp2y1Kf$vXb*A0`0zjjHwq^ z$-eU*rvgbXsv}AgSS*6Ud8H4A-n4wNZ~#@T{W35+xm%>&s4kLk?WaJx+B)6vv3_wq8r^-*Uf64W(eRQI+ z>G*i_;Zr8|Y&H>gKJ+FC_|1bgFA<~}l&4-q#$%np{nXO!3E1wGMxU*n`g;S~>D7Ls zw@0?+!QxHYP)7%38BOkbtqmBrbnuLG7rNu|N@7VYB>b%0zOVa3(V0i_cEZuj z>A-=NvM?(pl@zf@Sy^8D9xZnFf317uK1=ut5-Jq;Mj*bbv3h$yMdQ$}s? zwyc0g`E|#COzzNSc;xs$v>Y}&?iL0=OD8E`MwII;QNkS5ZSlUy0BNL3fA5COK8Za` zMdH&Y@FAkTw!cFl;##Ch<{9U?zE-skjjl8A=N9sZhCp329vZp%Jh@%> znpdNQyk-$UdAQ>zIo|)@*CPgB4{(M}VgLPr857we6W9u@xRLR3(AK0i6c+Iu-x`A) z5sQT6=A!lC4hRG;r<8;&R++X(54J0vZIRP7Lam*e8r+2*W9}m$} zIcqGuEC;0&eQxxPdX41N$XwF#n_mhVE$c9hnh2mMNcn?>g*JvHhxdQ0;#tlUSbMC) z0U8*~40hjZ7lpl)Xb-3C8Aco07m&Elv-d+ss}Sf_-*eajH-;$%!o|MWn*=kalrq1c z=J%;Gk0!IT^>Vo(#d2Z$Skp=`CltCTB2v7jTo_-B59*}e{^pWSZBm)&EoTr6s$?jz zb&|ezMZt|WP{C4++ zsN;lquX8ojySnJ2$VIM!1zsR|w6p1s_-UHFP~qASbFb3g-lIj&VAgmXW1WS6Zafm< znpHfA9Hv#zIc&Y|pFWStGpeeKE_#CIO)G`Z?HosAjQ78r3^uom-stab7wwYTA3xqE z9Q8hVtl_~<4CL6?etn^+Lx^3goU zL7KQPQ7@vQriK?GO+swWV)#???R_+bjGv#Va8WYRg4ITdF24BK>*fBMXq*I19vw;i zZ9?8NFJEnK?NG6oB&IW`WYqa-MLhN}c*n#I{6v(tPr*f<4aA>(Os=NndXy`xl)ojj z9z;B$Ov|kg##9Mq>bk_g;?i02wN~qI%^;uGa6BK0(%D7cauw-pUV0jwi1>$jh=m!4 z9NRvXf#1eC@+|G8y`@0Kga_qD+=5@lDH$?$?Z>xFXkX(CKGxlxUo8_n+#oDmjVH8s zFt_RK*jN*HHoolop&N>{?BcQyA|V>@2V-sw{Q6^vt2d87@r6-aQX?J@=}CkPVdeip z-p#-f_*Y35vk4~n59I=7@6*fuw!oVMBEIj3JKheMKIRuB6rae1-8ygU)KB;4>+t!>E8xv*}PYRPyfu+Qg zPU^Mm=stn%-DA?}UW|qaQgSM%#&TWPHXf#Xxf(?AIU(rWPy8+6FtHzZHEAQ)<@WsB zuawF9aMLy_*o#c?`2Wc+_)fc*Mek5`C`6R$-)wy?yD+HTDV1OmS|;?~Y`JOibJlgh zbQ?@xIG=T&8la1Ms~+%52Ce)?EbYVMQxScGhvBGZT&OMc{;0r)&Y#C>@;o$DK&-Fw z;d%XP5jmmILz8=}mmy)nczdS-3U*+Ef9cHWp4!o-U#HKv{kqKR{jPxn^QHM?%S2+9 zo~T2yyI%uEekGFqFINxz)?%$REchdzwRkO>csiVWtk*aaIW|wkH?>f_LVT%5z%9uL zZimt7IK3HIXs0`qHlRI{ZiBLhCy#(`M-buY=m;k7W2Y+0q^h*l_@??+ymr~sA=`Ly zL@U!@iPL;A8T_eqW%`gL5#Ou&y{43)<4VAn#8@h1kS@HB1Zvq^6aVdoL__2c!2pW^#R zO#kG}#G3Dh0%G}g8aNcsGb>$oUzmAd$=6Fw8&SJnlr0Sw2s@p?rCH5;KkW=z;G`zX z8jVBGpYm@mxD832_zD?RHD4B)L>)}kK0L=`Fxjy0SNYV)@fZ8}#dV^4i|;w?1u{ga zR{afO`k-#vRHrxn(ta4h=DOwlq7&zSYX=>0nMpF2SEtPYgbekOCa ziZt8w^~e0Ia1w>t;kV$|w`q_d3#`NdpWD^dmCQl%lFaBeBlsJqvu#z>-D+*~n5l-E z%F9RZtU--6pN=WYqk^WK7r-tt%cND?7l9F!ZnEjuHGGFAF@;Nhh4BV!lNyc$=EPB!XF7ZFC6Rp$b6W6=B znRaNsTwtOop0|+S%1j|9=`Ih|5V>)BCp*=}U>zb!*htI$ zcF2AzACOVi=VtmD2BjV31;hX6ccp`!%;9dosbPvZGzKy(n7dlnan|=a`{-~n*^`l! zg70~K;W{AZ^|0^h;NMch>o*$n`6oN~{ncVmDh}O(V6l+D%h}U1+i~5(UB|VP9s|vC z^OCj@l|HQk3*M5;OaH^B`;F(T6}|Ta=hL_Kf9vZbryu;vk9(t8=;EtTzOBhoRp$`3 zRNUrEmo@+EAjxznP(2^sn-+N$nAkj!p{otdz#Q8L*ajb*GIKHyZV#--MSlgCE!Eua zsu1rU*(ZHzW|wGJyE`3bYP_6^qx!of ze(Gl1BWH@#>vi-n_sYuWdrJB7$W(ThJ9-0RWqmE)3(|``Kw+Y!gpGDG7We;=^_D?Z zMr|ADrn|dSQUU31L}DWX(%lUb(%mSb(ny!mUD6@B3F&Sr>F%?9-|w9{bI$X_8E5$O ztY@!#t^2yKNc>3LA`q|~To)1lel0r_4|Cyi;mup>h3j^wl$Rb`mzo;)=a;|d*$=Zy zl{9{AsB<>kzm9W8egQ~r9@tT0KOH)ij>;b01LU@XiW_sfeQF}2mwir}lEt-s#&Ti9 z%HxO&I^t_|6|I-LTKxaQ20#`DxPr&XA5Kn9B_=0hFz;h_1LquI^93HX?em0S66GCa zmqJ@hP&ab5M%_Zp0^xwCABCu=GoU$Kff1|E)nT0Y<9*&Ukr`i~>sveRb}Z%9!_+ma zv_9WP=K~;V2k9Z8*Sr^nbm`fzX#hQZQWCNxhq@*(gaZU4kUtGFb||jw$j|Nl5X=_w zG`5An%?|QOB%z(=OFV?uJPiZySt!9K!Q0ZVuEMFj3U6u`Dk+Meu^hE zRgBePhM<9{T%s2ai%6nO+*7yFVczX@W~x2QHb~fFXN%j zUrY(kq;Ag6`;%E7Np9bxzK z63bH^PZtXfGILjHA{7rCO}jPAob&E2Iqt>I+!3;u)aC7!J{s+d;{ty!-%=U8Jc}JA z?PhSz{CU=rQA4fwp7HqE4607<#4Z~l&}~ie4}sHtX$szJwXe< z)d&5Tj(h52aH5HtzdDd9yZ#xTtF`&+5FA{~pm_WITG$>SQgrE4Sm#%Z?=&@;QnJG^ z-JI|WN$9BUFY`vX%+9FAwd*P6b}&SKN=xGMHeU+1 zkm-LV`{;8OLr&alJod@QpZsk63Q0@Zt(ukKv#94z$KhV zhMb7t{X~xek^R_dXPJ@5OEaD6hb9Cye9wpe99REOD$s&UTJFG#h5E&pjOSW^A3bwS z=YI#pP?sWy>!U*YGah|8N-vn%yGAHT>#iFZVgwjP=5liNo=Wi^%7{vmp0b;)9wn;r zb5n!2Igl4r{r+071pRP25>yqim^?mHpB!)HB!9W?`|J_@#pUSwlRwW+){4sbm8S9Q zU!TNg#LjzT(c-X>;@xHl-YjS4narlx-Ej!38jfCl%-g}wIHqH8y58N*!d8x+Z!dH^ zH)wddQjG=Cx|zs*_IV=d%}*wEBuvkpo%w;Rgw4^L^oQhrt%k#{n?ae1u&)Xm>x8?R z04bUb@IH!s0|%KOpm{p}gGB%YDf+GlCwX-bqa|F2Jnv;DG8~9A#Sgay&YM z`mmqjp~Cj_26+YBY)P0K6>>5wJVEOys_Ax_A{%Jb?0A& zapk!w1ot_#=24L$2}|mCW*&12 z?71!e7sr)c$dInCDQnv*$WotuSXJ)^b>31t%Y=&)2ZCl zqx~YV>n*R6k6P-pLz`BsGZTr+Jb=4W+LG(o9)2j0(hHOXV$N>ypA6$dxvNm8@B`^ zgnIZ%oUPb!v>uzeI3I4Nk*b<18egm{;;M}Ay3s8xF6w>nvWz$Bx3ru6D>=tQWkX^N zRP31D|11Pfst>MK1iVHTBt~!Ebiby#Huj&5OdXZQ?jL?|>t#+%Oth^N2F`T0iOt&* z+UebHX&-1J^Hi~Ily&MI|A73g_w9xJQ8QTU!GHAlH>(TTUcFMY6roIf{+c1zTrt}m zDm8IFMtOiPz%9V{<&+gOud@0DTi75>H22fdl+$Wh^25fHKjmH56TjifweLl^){)M<>+KrU+y*LA1;2L_olW*uAF|S#pcZ@`<3fZzU%je zS#zBKWU9bDejlzg|#nTTub(PM5wg}AZ=$XbPj5#a^XvC-wY9!k8>o69X1ag)hIWA( z5;axxG|_y?QR?#5nO5>&>(|Y0!?QI*#1-PI3#tM3XVtwF;VR^FS_6z1BxbH1Bx+x(I>3(WSk1dtS~` z7Fig+u}+c|dz+Wrxx}CHIj?J32iVDq|LuE^DT`hX=l*I2%-?;PG z{a|0XS*RjzZ+%H0`C3JVDZ+9)8$G@Hl|Uf4jRM2L__S;r8PrNZbvju3dDU_@a`(4} zbNZ?ADT^m*>2cL7d4=?DPejly|ErIG?Fa4Nk{*apdwR9M^1g_LGCoTN9Db@Fy@S_X7XSAw3R*ROO{mX_&q=@+C^1sXK zXykr-IY-Zu?%!eg`A}a0_CYla+Mc7qLdNyn>B3kVO~Ppr;fm`Bc6U0O@|ovJM9g*< zMsiN!4Eq{j_^_-*FoF@0`}1)m!n-2n`$UZY?M%=HQxBTn%a=0D%13qP%C;**MoZq) z5A0l34-tm7mqy*c)xLbK+f8j!&wRKwMxgrkOyMD#YzA{`*G)LXu_ylx_A^0@sLD_8 zN81C=cD>9vcKD1pKfR0CBd=vBTAI7JbzFIzdGw*WHKIgR1jj+O|6m&K|+*r6(_HW$&{qljw_IcEKr1%U&Qcqm?C6A4A@d zc|9>CYjR}1d^O{79O)D7eScTxQ?u?Pk}C7p*ff0UVOrg0Wl1FWjqUC64=2BX#-wHj zTrlys{XwNlQk9H`$Q&FW%&b3&!%kS%CM}`yG(Pt4<_lCP0Jg;o8``1RGz)K zup;j^U8i59*7iK(JY#AdcNn1{P$NsK`^MpQP{^FS!YiJ(RjW-;C-yB2u|sdz3V2AQ zO&92&&3W^)@ehgme`DR`6K*jQ$mYWxMP0ysA|=6F*yNtK|US%#7>j zs?TmN%&eXtZ|pzbE;@~GCGXf<(6cy;zpL%!pH3x%+V7tPH>B*Rb(xwzrcr-`(H*Sn z?v3hpnemMn1)`#PU%2SzHJG^xQ$bv;qa*zciy%ZKUzq?YrFvG4qvBBMNJLD zY5Cr-_f(nnB_$^Z)Va)YF0|i0Mr6QXNrnR^th!8cLj~ux@PhvIe;XCv5BJbi)D}+_ zmsI@5YTul%+F$~aA9h=ViU0BoKn$Nwl7pjTru)>pno$wvxTXGT$SLu2)ZsffrFi$K zUHbnFSLSZ2KOHF2cL_W@2HG`HaYPjy6MyPbnY&B0_P+ckiPEX^);YwzbH<;o!FEXO z$n>^};nE$=KGfI%9?vOb`TZji>*o_ntKHCSR$*TlP8`LuQl`LBY);f*_{IXUIR8)I zz0>5=S~p){`PZY;I`Ka)04-{ltMChJa!ll}1G2$|oRv;JbhyFHCu&UpMn~pnu%+%Z zUjS6aQVMa~&sKs!n^t;G2{99#ynYcE)cv%^|p$z}1lA>R?E(b$;b&jL(InrAJQIVdkwjZUJIu8B#p6 zt^!H#T%fvhp8GZpy4r%2ViGC98|Gz~CBpbxZ!^3x1{QNM(nOsSgR{}JRqUVcLvWHv zoP^2`C3vr#2#S_nENHNV?Ef?5Jq}mF_%~O?VBGCMCkImwDK~`13=~3O?UI}UCOb(M zfF%j|99Mtmy5E1(EP( z;+Y}V^XsJq5j26OS z38m#5qyAFT2B=2XY4CLHt{+*fRbayhWxItC1}v%n&UJH#+*HOUZR>!SA-&Xu1h^ll z_0MPSCIAoIBnx01vXWZacW$T)_kr-x4Mr+4Fk8c>FTBfS%Rbl*L`Q@7>#p zUrR1_5@g7@@l8+{g+o2_WW1KgC|xvpu)ypmnvQisjIP8y3iP3XBq4HjCpzp~W<$?t z;rJE__DutdKdR7^^B+7%)*mGfcFQo|KguGI; zj#iTi-|dWT(KpJ7*NCG+}zH4WH?X`Z(M5rf?jplxT_9l2|Us73OXLw5H@D*&c4l|7KxmjMjsI9fgcY zHz&%@UINrUM!qL<*%2Eu!jm~8pZOLRlhgKWuYNkb<0l}1%PvL_{1r#+q{f2~sTB^b zK*US+=CKgAkHQsJOlrKIDB7g~_7QZhAJbhjixtd0Gyjjz5*#{$mZl-evl?&0LyKtC z)De@?+MMZW5Kx?FXsLDeOn&7l=x)`&sz>s7j5;# z(Xuo{z6*SeB6)TS{wRWKH6b}d-Y5UZt${u5XL-)7)_@fTB0*$dy_(;%B9OuvJrf-j z;Nt`F+CVZPQZD%xFHO}LH&#^xH`a}m$UmDPm}x6r376acmQb%vNctC;Y5R2lDeZp^ zsUbp#sFs8geImvPY^kxzIINsChCs?Rvp&N?kfBQ5ZPj?Hxp0Df`U~g!7^yo7LYiC%YF0~BZ-n*1AonBx%?Ey5UTEI<&IG@d3f_9oQmbLnYojf~nVeKg zyb@D=5#Bf|k))IqFxBeuR*>e zhUtDHEs1`qEYAdtdMpMLz(qAf+)r0~{g34*M_d$Y?qX_MR=hcRRCG%XL_~S>@n4c{ zMtuoLg61!*zh1v>vM)|rx&3LnEiTuu2|12?H&G&tFD~7pmKQw5P z{8i2eR_iq7!s~0#W@0R<=fp$6_pVO2Y$J<>O_~fHvkNa8y$es^?HYfCFiMAXyN#(q_R$tR{8W@I#}W* zc%4S#!LSC`U1P`nBXo%rg@RX|+9eea#cE@`2UWZ2$J*<)bS&uyn<@)tCZp?_)=_NM zhM)1tDx4<>`^~wZF*1gRA+6QQHTK!o0VZ&>8c>2s6aRl+3RFWfsc>i&txuu4=$Zh{iDE@^L2$g&jtL(VqKwax09j2+wOq6p zaXMs|D3g?b!KA`za3|vfk_=R)PzFMxP=-@{UU%UP&5{>vY^UR%s78|EuyP*YbwdP% z!JamF=5CAl2Jw6gh|s(#^aigT=XgFo8b99s+>hu14^!QA3hKRQ62FIeJyv*n61!Dy z)sv(~(^Qb6hTd4469SHv1ic(Z;kKv6Y_0r`MgGtxd0J(uVE^c-JAzPFVV087gj;m$ z80(nIA>pUg%)g3)N2i*LgeRqD((QN((az!T(_K_%a&ypF2}9LcxKQO;*ihxonXQA- ztp|y@?Y%#iQK@Qb5^tq@y#7b4mF^Ov&@O}UI$FTiTUuOC$6gR`oNRbe@JI6R7|RED zm2XqU*VNQ-Ql%9~E7!dE?DCTb&3|$^7rM?&QEIi98qNgDwl6bgIzQrj*G=aSE1&CC zQ`oD@Sp2Xi=J|&!o$kJOyksQET~2QD?I&5 zWBKrDQh=q>8g>e6?QJ!w5oCJBN%^-_6M~8%Bd@Rn8E#m?hG1bqvQ=s6;RF9{#ATE# z5B!10ueI_nw?yATeh+YOd;$BxrGNFsvGL2&?N8~$;L-@U9hR$5g@Bq@a$v`KEod#! z)rMRd+Z>)*|9km1pMf(OW(=wG`ZARW%6lk1-1hJ(FMF$xtiSUr98m&T)xyG}Gsni8 zMYaCpv!atf)@#1UohWkTOibpR=Ndm==#wDA^79$1Udddi78kP#1RO+5e@=M)md>oW z*pHZ$*Px#`jRRF)SWN3W2;_4vot?RdbQ*J~z8=GL?5{-oY3{1p)`a8iH2aN++Hm%_ zX>1&dE>=p}i*cBxmWVy4-3N)NuS+@w|MbG)&+su;ZQmvF^;sXpW4stb}wQ-ylKLI5ttCB%$hz9Me;Nhv+5uG-ZnLgdaLJ^k)T`6*UcA4ai`N3G;H81&WNBiO6S42%eM~R>cQKoy z2QEIr@GoJGxTPvT`xOp-_(cDj{mSxvaN@aKEwdmmv;we1)<~VCE2Fe!T%~`Zma&D0 zB_hJ&LqHMyN5eVD-VJt+PC$Zz_Qcz>t$fNBxL?Z!TYg`oiIJ@SH)jXR4tm44xUr1_ z_FYVNy3bbyA+HMXIWW_u?PAyW%Mr4V<_G|t9Ad3mak(WDPyD6Y$~)bLL$R>s$nh89 zqWRKIgtRbCg?cDksw>H7c2!DQUi(!i>Ky~*MPTVd*mo%% zUTRWOmusF`{aU2b-7^JfT>Q?q3PF3XltdIA%! z(#Mv{oiWpcY_Ej>EE-GqICF1S$3SN*GujF@&C6_}O#!ox*a;9UH+aH5)R}$|0c`^v z3MeP+fRr~cH39bUE=C&s;phz5)3~POa9imph(+NfccdcBI7_xfkE2kr{aP`l6N_ZH zv8#P6J^aP$!u&6=*59nP3N1gPPkOmzo5=DgdThQj&W|l-Tk-HTzKQPgJ%_`;jC6OZ zF#c9o9ZlCz7^ut#1MZ6oUzyw+b+tx5%PQlNWxY?;B!Wre2MSL0;-3y=v|SNq%!r{ACttpN0qQ+4 zz^0V&r<4S}Hh7M`P9jH4Xc+513hSUmWn1F^&dJZ0Mdg}R*uH#O$jUmNbV{Q`1UWY` zfeZr;%ctk*GmDFkPSVvkrNhdVfB!x{j8BVvzfQ9QTX9eWhPb+|;n){h{jhLo`H6)p zTDC9SYNGbuCo4>-tV;5lY_xj-OXQ06!=ZX;V<|`!tq0sCR`o(cVq#?P=hSq*yHxa) zMfrjFiq8nj1E0w<{MB!MlRA0y@y3YsQN&%c@v8(o!v+BZT)7aFbWW_wYh^|H_rbK% zL}?t-iCTf~9W#=c5M#b$v`Ru%2=Qur2W2+l4$3fmA-rNXd_VjjI086`CM}95LO-%U z%r20=xqC-KQBe`pOwQ(=Tm%$sw_D!~R7csS?-+voK1_k7rOyWilCjJ4U2A)_ zGsgs3*w6#1aUc0grXal7)s|~*eq}h=)V$l<2xC`&Sw*?1g%g-%^vZpwh9#rI51oE7 zdTdkJ@+(4N-`=NNbn_SRQsvRbvRqvv>P*BBF)^Ryu-c)^u>s@>&{pwxsv=(jN8Id) zv1pslOHB3#QeVnULE# z^;mVM#d%$)r;XHt?Td;D2f;+4MzKUNgM(B_avZ}QfA3!I3OdX;L;eI@cYp`{+Iwfu z6VxpFKH91`{LE77>;JAC&skX!qu;R|w;0dz_Vqxx`1#@cYwGZAWopa^O6g=kq{0hP z2bfIzt!=;5bi(Tld2lmQc;>c1Z+kzBSKNONf)rnGSPm}<=nb*`IEWkG`S)s>Kpugm z168k>QEJ+4in#gnr5Gg*w^#NR8(F5>2$Cn0M>#xy=p5s7Wd^BuCsn>+ycbWtz zNq&rc{AH<2CJ?Ey!*L)?l1LT32M%%wISs0kd~&_g#JR^r-FDwb*u1)65Y8yCuC88^ z*6}$(eWIP9#S^ypoXv_M%4?qs9h(FnEV{cZTWyPvfBvZWxM2l7;I7PlOV3Fzz0{^{ zi`Yy~F4KH3TgbE+{r+IRwwAZm@W|^#WQkTq*tQTWB-7wzYP4e%gnoi2sP(@G$@Nu| z(xE!NXwk>3%V>T!8O;e0>6%UiLNxf#3Ps4b5^9PvkGV!Ss?{Eus_D$xP)PTzLT8QNL z=mj1gWO#i1RT9#e${hHGHWNBj7mg9N3NoWeQ-jprM=uX*`mnv!`pcdms#hdc0?p`A zxze(LLv=G(`2%z-an&ORuhITU1wSBeIS3LtXoOqVWIt0%daXH;U?7ssFSyn|7R`7S zT0s8jwSD^jNt{2P5IvZ7QF=ly@;8+yp(kErtAm25G2GsPaOMmg#B?E(yTjc0WhLC} z%7u5rmAsQUUDTPY<%08Ng;_|}2G9!%no<>P5zmW&}wf{@Vwf%3}W86AOIl1KvUtF;}98A2g77V!F;D|ro>6mPx16y z^=uSr+|bFKU3zmejOWOjbz%o7J@6tycJoR1@cHn&lI{y%v{zrQzFR1h%_Vx%k_tc} zUl@z#FH48YAmWUbH~VIqs8XRjb#BBPgOP`V})6tx;n7Mrs8- zNK7%+9C{m$uP?))-$d*H0WLW)F^b!c?A%@-^T?l37I$^<38P_+F!&uGfa!@j4WBo* zKP#|N5Qcouk|+BrErEo{*JUofF*L;+a11E$;FZ_+5qu{9E_I$fYU{SRCs92?!k zh!_4EF|yb;3kexYavECrv7H4m!J*ZUA3iTg)R;9JB96QaXNYi%;1h@vSQJPR1|YkEzK3ca-sRTv5vX{0^J8MQPGiImWR5 z)0ug3Sl4$Os^X$HlElT6e?k8Ojulln=zy6L|5fORa46gzDZ6F~+|IiIuXRcbD1~$p zt>4ulWNbFFkjV@Rl{_6QSaqG;zkrBp@f2|V`QYaGTE(iYoRt6B^#JZ;=W?Y@H&if8 z7rD7%>6dTJhSLhG=~9N+hrcP?>=JUnr!RO)JRZ6reTxwV!rur}w^@xc<@@3U~N@YmVB! zR`#UTFDbC2Gr`J4$UPQT_>WD4Kh6t$tVMNR&~7(?83$Nz_cEJP6Gfs?o=tH3?{|@F z45mzz6|rtUhNl+9=$S2$MC3FT;$1SXuxxv{T*!2q&5@Zf=1Ng6#J02cj?4!qA}^Y8 z{QohsH6+#7JuSf19mtbji=qsn2Qz6C2mUgB-(0e;!~vK6#=7L{TRcSaY_}+bI(_?f z4#^nMQnx4~C3dA8;EfZ`*#K=BuD~gN5}PIdr6;vYj@e%rFw-cm4LeE^aZeW>Hy)8RQOupcIp|P$uJvH=y|L--$VoZ+@ ztTi~|gI*Nwnz)X1U{@CwT8`(+;fP;ncN-;O=2chwCR3)Z$9z3zH*ccFFua)|0LWXz~a~!i1EXrxiYd9@3tcyA}{utehrR-KE#2>$Gp?ij~eRgp4XL; z2;qpOvDF+Itlv|`A0SIK^Y>g3`jq2M+Uw2Mq@ooxmn^6Mn+8?9U&9csvVu?Hv5M8M zU@4cW@z9`et7d<`iiP)-HZyok9WZqfvU?&sTWPa;j#nSWjVK`!Zf43 zAaYbBEX)BkwHc={8DgLALM$mk&!UgXfE9xXbnNLLS?2VTjN!J#$e5Tm#8AgOLXY z>-m3L9=cd5mx~rJ$f^DlhiK?+I)SsvY%K|PbfTgd@DcYEgfI-j_uDx-He_8^7wTel zXzQe24RIP!niwy|F7v|&_aMR)@=AxMukX&&u^mDq8(-Rk$;Id7%Fc`+>JHPi-z2;u zdoKQRx*C)S@!1Ns^1smK=!}sw5!eEs8&h-PL5z{A0|f%@jb9v-R+4#QdR{ETBH;A` zlNUbFM}8U#3V`gx87!1zc06=w|HKOObA%g#kRT9!2=FFNL1=*t*Xv!2a$&I8>&>Dx z5;daiyg1!ndjZgiW%`ZX;2n7X*Fp_%4Ga$UG=8xjBEdkg3NVa!D;V-({?E(T(~>n= z4E2}kISf(xsQt__u66Ge2!J**S}SI8)FYgt3jp9|VuF&$LhrGq*F~srtIGba6#|Kt z|1^d%;i66efqASD;ZRHqS@5hjEr10<2cH@(GL4nX3`}El*d-(Qr5P6~_%VLzkd$K1 z4=FogTt|mJox#=$vUeZxvsdrG8Gcs4%tM{;r9(zk`P0QiuCNs+v{ACx6KW)M*ViNLq6< zwufnjC4B$jV6Lxg)W(~I&tu7X8732Ld=Z8Dhz`|%>@!iiQx+T*Y)duo47MKbc>>o> zx)HkzZ_?~Siz1^27AiYS-bU$3OzO2v;r$oSW1ATXQsX(eO_|7v!Nuz1dA49)2P{YZ zm`(cm(uz~EYi$7s3v_{=?p6i+f;K3G)YuUdE^7^xEQ?0)EZLi#?4FuzU%90sm7m9B z_(DYYOv3~rlBC&)`1(7UeSt@Ib?e{r$F+tXF;RVD%(#8ba)1yK3Qp|E zsF!cPMb7I&(vI5powKq-F6ZiOQ}BOW02vB8 z`tmNc{#`u>M8)7Y6NF6k;Ho}qng%NHwx||cj;2i6E7zLVQr4{%P7G{gLUgc=5IH>{ zHyzs90ajO)XpQ8g*p(ee9nNtA`f%S63+Gr2&U8Xmu}MP7Ob^D*KTp&C)bAU@ znuz%Mvi!pN8<^(jQBo_~$OA!e-ouGXi&Vu7r(w(N*@cWgjL`dsPm1FkuNP? zJWAs9aB}@$W3l7xfHD|F1K~MFQ$^>6d#c{|KSXC&McqVT7%>nZDIbqlw+%GxEVcaY zMkgX|*Gvl^l%+lb1X2j;E{B9*uTz=w*ta=x7l30NSU`c+BaML`Vm*@C+e8(#*zk)U zUZvw8HMTJ=(%5R2FyUOYt7~{|4Z<4}b9q-~k%pmG_+aLv!?T(JYh}w|&3GjV_m=0V zZLax3Agtko?p=PdWH?ezp)NA4U1;Ah});4#PG7t!vKG54)Y z=vM_+ks9U;7yw=wPf{Dq1SN4{+$_ZCI=YtF(pSTVeF%-k3bK~3dWAqcYX6~K7l0_# zf!z@w-xUMc^OJf}DEPqVzMt`}-G?s@m(tVH2{O84OwQ)(lXiO1ksxA_9H+#P(kT9$ z>ekYMGYBuRIML?g0bqWKu6xjdzBvP}tz{>4`YOp|pkQk@CK}s8wg~Nz=h+kCgqzD@ znHx7l2P64x2EpUOlqve=!9mVQ$kaFZGIKvA9;3_clgI;Q2Uyx7GM28JT5-}bgB8Wxls4nDyu^(h6iB*Xz zi16uXQ!harOfCqsR7ez}6xtSq*3^6URF6gzT+1}|baZwblJ|M(Ol4^83GH}qE4dnp z!zl-9w4JY=L4gbSaG*G4%frS78P;U8Vo#jGrV)1;O7d&<2B3mP{>o%mtI1hvbv1wr zP3y=54Ra**sGGwrtir;G=Idk|lKEoz_{zL?z%_nokT)#i{=N{g1&(c!; z5F#!DmP?lsHDmT;+XZ#xMto1gMjD8-$HFN~hkyMI+$`3jU4uFKF*Rh>Vbvib>@4UB zjs#8sUP&a8gp&rqwy5-hjLghRbD6uZofmK;FKZJS>|yjywtLPW!JCM7jGe6_SnM5H z4SU)yi$eD6og&n{1jQa^XNQKnk7q-if-_}8dIj9o_L)l$Yx-(cw9BnwUps1g9p4sCku9M^{;IB?McRaOM??XE<+0Kyo?yV-e1 zV~X^2xXlb72|aLjt8&u4@S~ekU)~Q5V8&CS9PgDP8U zkq@P=6vEsG_w3$sy)Q?+U-+Ojm2V<-zs^O+#7i4b{*wkaIB~_%UY2l!_MoK+6YjnizdtRCEjs zv6UWYA-!|;z=Kp|vHflIOrAnraUFs`4J7WvRQ0I>1C*>{ra(+}wV>13?mMv)X%E#6VG;FLP)s zIZ*U)0y+UA{xA(U6Qr8;ifh9B8?@_^vvH^ zq4+Ft{rmT<(&?@w;v!p1O-)TXIi$cZU+@90SZI%)p3XquQBD4_SHdZ@vdH+Gd#7T% zrt~>qIc9p7tlJA!HMP^^QlYWi8-6VMKv!sAn0zcDwGcNLB%FR{@w0yp=`6Dm^&<~t z`2i>(hSoHHZR?&B~|l=|a`jUTtGQ$W+TGXu_ks>F<= z#P~(}Xp+$%!*B86!Cm2LT8T`5dXO-a`|6>Fx#F3<6Y|byKVX6T{9ezdNh^0*ly|{kl4Na!<}8q{E)10t^AF?H(F#sZdfEoA-w= zx(05+z6xa*3j*n*sXSJeR#qbIL~r`hb4+Rrn{*~LGmR=VMl?%cFJJbuy{j6GN-j1C zDh4YX)9Z5ZEV)+PN(bU|d(NuK#wvY3oE8)0#JPd-mziEKxRTZmY}vELXo7ULS0_|6pg0xm7x;3^ zd9#l!3*#{2x4iH14Br|W9=Zj8c})HC;zYlcN*LVHc0R2B%CP~yCe*+)xocz6|AC`% z^UEwq6%>^`TJ7XE9_uAfgR9kl|Bk}2@gXNfprzj1Nb~48ZOO>*(yCRC6q~cF(i753 zeZ5{35EofFnO^UAe!M~xb9=ZkK$c0P)!6*7GW_I!jx~ex+s%d%5swkkxp~#DzJgt` ziTC|fGZl{uM;y@t`|f$)NNU@Q7N;pMr@t&iQ1dvar}eWucg;+@b6Z_wc7gVr9NYe~ zxdHQ|1c-FIrk-v%kuhA|5;}1<`Ri(t@>5A3TKymr}Lx6GFYXJ<`0N@Lb4UtaC4bn7&{qO z;>@{NxPCp$Ya}Q|tUpWbuIdc>Wpg3Et1RL?W>@gVEYmasOX+t>y=TzQqW^q|Uf4)K zS5h)U|JgDMW1qRJMEWx;|`Ot#9=XKv)0A&zqtKUtF!;;?*582aA&Ac+?NbuSoyXdJw2vi zpQP>V{kXU}`C;SJCA)XT3=ON!!@HBXXFu7@I8x6$&eJ)SRV(G&{6D-O;!Dobsae&V zN)X6wsV~ZP$5AcLGc()ZRo3s~^U{*%oY$J}D6mT#Oa0grmqB z&#fw&ghP#R?895tPK3k@?USC57W-k*#_ZoUq%khCBWY<-3s_aN3kn<*)6Fd};}oRl zDWMCCUhOmzDay<|P7_wksW-4AuS}fO#iCzXI(O#_B5$%vM*_YJy8rH0a@ujVoOxQ- zZm@}a_2J;)>}Z6VR0R=TI&iINH(26ns6mfsyFKZox68rj^jBo$yXDOtF|YD45GK&LS2Q_K62mbnd!^|N*d-+kEVpsg8?qu1)AO?NKY!6ViX zzxoEs5kN63GEn)SV^M#4t z+#Ct`J#>#`;WS(fwTT=Z+L_Ze9#80v{ymU*=6DqFbd}C4b}|Z;kNcQq;HfISH$vp` z36r5FT;2=}n(}-XU#?MrqWGQHnF@)5P5=rD^ z1m}>sUlj<^-pd7XxI6Ja?UIu5e8BJ>2^zAERc&d_68O{m0v{9)Km8(vY@4Hg++`I? zu{7Dp{bL`#iBRW{b~+s@*B+)eHa|t()T6Xxha8R2I%(}JEzq2ZKw}auABz~@>QNCA zf;XwWqR2m*kz;h#l+J;=Y4eRY=}Lufg7S21q@66!+=HmeCcKtU%IhHU%Mih+o^I$Q zRuE0SJsfQ#XIOOV2Ov3${q#wcmQePC$a9>eB9?1wEa>5RTSfrp&==;H2UnwKft|Sn z)4q4te+B51#oKN<_B!N|a9RiqJR3j|mFg$c!*)lLtCm*h@#Y|-tr+xaji+ni_&_tH zCw}xfD8!Vd`*JuV)4uy?YYV2O0>#`?A$r(PvU0x?zv(HN7oi^!kXspXs0K`GrjV=IYTKqrrXM zrdtEf(I$^kzBgN98NV-mbjre~{@$&&-Lx+q51;Z?xv#VycM#;zwDYnypUlpbNC=;f zP2fnhe0zGx3l_S`ksFQSm6&CSDO=oqBsgk%Jh(?m;uYocISpmU@3MY9{{{nwA~Bbv zkX~)<;t3OY^KiBsT4q=D%zBjO@xH2v?a;8!{H-CT0ZHA_M2KH`)=LXX{g%k{$SZh% zc=RBz1CrAYy$%vE(hpdrt%Tqrxc-}J^Ts3f=-4}uR!*^){+5Ngy=YrrZz+lQk$8F~ z9ytW^o*K~%#>tR7vL0^N{?5e(2Q%uHJ-k3o8V1v08Os7v;6<~l9~y<)asRU%d*7lz zjaR_l@$N!vVi3J`c?_rZVJbF1A5roo5H2|TM`SE=HkpLs)L8t(f>TCp=eBVA&_rXj z#G(eCO6IQ^>XFu)s8RiZ_=pdW(F>ExuD-pMyQQ(){CDZ;KT_){lMDa4eC@GmV`O0H zX3&I&2S={66kB0K<2vogN1UtP;xDAp`qW;>k7V6!m|9z}k={S44<8+iv!7 zS5M;?ByR2sPk*()X?3eir<#=dF=2EoY_UPXS)NjB+UxGco-{g2P3zQPskmITk?ka& zM~p>Ef3wkRZ5dpOBW3l637~phhwX7p5P_5pNrWE#BQc8!Va2T}oC#5B|W~pGGQ1 zZsZG>Npd=y z;kM{tL4r$g3r^7B7Ch+S1PJc#gG&f5!F_Otpuyb1sDhfJ zpnLb;pRR8$pWo2etBRCrT;tSOM~@K@I-d`bqH4S8D!>lxWr=Iwmj~v0#?!e<7$SBs zQ_vb3{PHSW?q0Kh%_lxhaunpIj!5})c}E|!vy|nI-nZdZwRQO;XwV>I^@OKSS>l1c zt<<(``D_)+L#j**Y|SiNdn*S5HP}Fevub_OEZ08NOL;}~c0J>!9dbpZP>hvwI$rV) zD+-x@5RG?2#d<$ryK>fTnW}sDb%^oJPxgB24yY#C%5V5>5^D-{F19gXpGOb;+6rMy?6UU{kq<4 zp6gnrT99m8=-`RC}1D5I3ZUY~(YGkcmruJ$WK<>j3bUCNi;6OWUp?Pvyy_E@In zW~v!G@b#l(&dW}Shr3$e&r6Y&pY#p&XTp;gkds>jWBSDAX_w*s1knOPJwW`ZX%77m9#P+f5&P)(4?K8cmy;dkwDNR%+VOD^ zH%KX4Vzl zzKUGfkV?wYi6g+|2N7ASy#*C6dIt1t6Rf~pAXCsl5MZ|U;o=D`i`%!HFpfLMV-ke8 z^(zY;rU&O`wL_WY)0=G_Va}g!$mG?iZKkQ2EMK%Q_ooHyW8vd_95-F(%h7jVoGW)l z{=vPU(y%;cjDmY%D*x*yKeQN;07p15-{b*Z@BDh=i~f6weasG@QOPjJm-~ZMvmU}u z_J!vAncKUV#Z2Kz$z=sztJBiF7vI|@Id*@38ov!qYSkZp3!84yWRwbUt*;wO(mOdf za;;wpii}CimG{M=hio4PuH+me^DOMzIuAYo4$*SIR!)3 z<@bWG!q%P|c575yxaHG1GNgvgHpuJYTe`2h#{>3^KXZv8Y%7TG@ z@P)A=nJtK%^coi%;{Fa&Qp=`WpfH!5(tyxHOrGwqVq#&NHpNTwmLss{o~Pzs$43VG zVM(Di^W02ZIBljcKZVS|3z!TIp8;mwtuiOIGL1UR$zy{*EkW0c8){Qw>*CYg1LqKB zk)w9Y+=sPhqvH@BBzC)1Ew|&x#RAbz|22KbBbXCDIB53ZDs#8i*0IZOv+dx^hstT| z4CUh`SH*%h6NO7#Az&llz}v!&u{%tG;^|qPo(l`aTb*`B<+# za_nY)kw5MSNjPj5zAIpqTf^TQUh{uB@Rhte##(#+`%OFrB{pKP4Eh_GA&NRPwX{g7 zcrY4_pszgsvl!GxR<*Ny4c2+;KtYUMe-7BO`Lfz-KLzGfBJvs_07||gzJI`9Vi#+V zQnyFxmwC-D+9#Ww1wJS6MXTZ+Wp?Org690>iAsY z2y4m~y$6&hyf;v09?xv0XG6AI`*c4nJGsyNz3fa{>{+egIn=IRt=IONkIJ}t)O78v z@?N`6Si65bs{L?T#FIg?KUsenb3l;arJ~aacGL6NBjV{mi#a6sdcI5#jf##Y6ydb= z6f|g0;5TAAWih(<&W9tPvTKZqi^j3`Re-At=o3T5Hf{WjRs(lS#E2N$?7a*Zz1GBk z!VDnMfx$R7R#qPUcC^~4dtqLV!RyEvCITAL+2 z<9c|z*)FE-u^*LSvV3eAx->G1Rah8@viIt1rX8E|rX8Ki>+fGV2-DwKSXk`8VP_j2 zO5?XlDtl-N+{6zE&5xAMH>o>ENyzcXedb!Lu(-4u-<|HY|B^bxC6ZxRMK;(91`wIb zHpQqH;qTM;6iayDdw4O(ytBes7XdyTMU`i4U@%0yo$Ck)vV2u_ug;>Gar-;}Eo&+WoO(=(`cc%;q_i$@3z&_Oj6IA0d~j ztbccvS9cjsd}rGDV(N6BTsM~;PMZC9-8w2k&v}WaNu$!M;kM9f=rDCvjZFJH(Uhaq zL`g?VdyA7DdPr`bI%S4VgWX|V`N?v(<<>VGmV$c7A-RW54kZIQ_uWd6Ux{#s!+r~4 z5<&tlvO(Kr;+hQ`ZdrhslZf8Yq;69YGYrf&y53{z@NJ>iesUo1#dGV(8TmCm`aa)o z=oX!3^zS6=^3{%pjWs^ZcuW#ok~f1(>p5{rXQFChNV6$omhC?*87iuGZr>B=1jJ z+U(sv%D>pA*cGvn65E*Hic2zx3RnHTu1}hdwXfV*K99yBGeXNn>g4StN0EZxezNdK zO8AOjM;G61+8qVD0$r@_fcv3_JUXcd*{nt1=jCU zZ;`<7tUlx6n=z8uO4T~%04_>XGU$6A9H?;SkFFzYr&G^a9`oRj<1#&K0^}~nl0%f^ z@6&tYBO`zq*1rodTOufhyKeL zTvb_?juC}k$3=H~pYjodHa_*|?uQ}Bbc`m*^zf(-uNigd6)%YU6t3otCn^yl8HfTt z1px-)al$yIi39Bh2z`BlFA{rILokHU$vrn!7=YhhUcLK!`lzKBBkkcAVv@W$P}StL z{yiw%Hi9TOcfp*rXQ$e7bs=qHV&d(6|1+BO$X7V0craoBEfj7PO&^SeQ0(bj3b%Mzf?dxMfswo^63iirQwui}0%2g?E$b zQz&xE2U=?43E?qIxq*F^cByEQ;b^V(X{gclx49W-w`)<@HJ*KtX&iZ$2<#>y7Aa$# zeD~M8>*2CQsi(rAn9V(-D6hi4o)`tvZ+4=R>D6*bAs&Ks9C`7nuhtFPk59Hl%s@>D zJKr34K=`N1>)1|6r~DkVe`rjMI92Q#|6;Ab-#oxy_n_)+D8ST)ulpAZ5b$Fzb6Jw(c33ryXPI zYcNF%K|Q~D>xuRyjjeR(E3BCMy-G|0=#Gb+Ztailsq+^f?#8K` ztpX`_{ygwILW{xXh&x7GjmUBr1L5M~wf*(Bnx7+6LGja)dJ9_oI1OVi_w*+KWls(b zEj0S@1!yz~Cg(?5f2K?HOG}b^+fR0f&1Q5lzPafQNvOLBH#f0n3b1c;hf_Ig7f;1P zgQuFd2{91EE$}Pz><=d=WWz5k1Wln+Vv3zVoRD8{iThYgL_63Z{%w5TGl*Kx!+Sdd zG!w9nP*(a}0^c)jS79>b3B@VWyY?3{eftiZ^{pb01A(1E;}^bEA4;jQQG$=LlXy2H z7=%So0-Ge#dEnoAViXQ|-B1Bj<-MIyR4OK>VgJq+%`tOu$n;gQF%c+X0zCup#JI+O z&`>H{_$Do_pkg@L_R3!Lo(@^lJ2%oS*I4TVoKcreniK$a83NBd%Ut*Hc4`W6)l zPoly!dra&|?RRKgim7RWjTdMp{#C@p&%# z2=^5rbrIn3i<3Nw$M_c;&r#bq8%DJ5eoj+(0SWlUY$oN+)>KD_*B3G@tmxJ;`P_;iIe@Xbl-Jc z#h@i*M`P!rl4;dlvX9poFh{=PA)q5J^8nX5_`Ir6D+36?O%10Yzz|>T zHXt)PdEiAKzAv77VLBMI2Wh323{^>bXgk4eMVPz*s2$MJ(DniT&8%7YQhUxkk*Wh1 zrGM{Ekq}YnRwdPS=Fc)gT*|J2w70ilK(;M(8z06!c0PqfTUm+euV;FsN2xMm5wOIy z@+o-+puz@&kyLban3gjwlamQhicL3NAq1nnV|A$Ov$pr>f^0bG8Sn{D4^a#KfxKx7*JTkMMK&0yS^T>CNdSv*BV#e|e^ET7T_i0~QY+qI6?g2H_ z%m&+e7cwn?*YmR)fM03wx#90#Cwa5a5H7_`rCWVMb!{Dr!PW7}nj1T+?&T5YR^TSN zp)@)7>Iz|Kaop{jM(wni+;q|HVT2s)!Fh#i9Z++;I+$PD$E^1}Gm+t~1;|S%Fbfp; zwWbu&ql~@(Owr!H6Zut%@{ERx9!N*ajFN&a&NT&``1w3V%cv0{RXRNeD<~r-+Q^&@ zM#%etSMQ=DH*2GZ+p~N#^YM>T70I|>Ns*k&B%#f@-EB7lqF5je=Hx9s4S=j$490i7 z%v6~3db*sXVi3+u7axrer~uldoX>p%B_JSY3VqJExX1o`xc&BisHM&Vt(ZkwYt}8X zm{zM=Xa1NiC^4wYsrOVb7^dlxu4qv%6bEE!H^_BdNaMzM36gXmNkp)OOt^%2&HvuK zXKXH0viz2dm#S*K%*Q{kK900>teV+SrM$V>jP!MVunG(US8I|XcTm*iW9X!bAqDKBzeTwG`}CwmD9l)I|x=%nY}&6;R}k}z zoPKX02sFkU;=S;{M)V>)|h{6|0eY@p>?}oqJR$_hsc0zO5ax%M8 zt&9Z>UA3MJR!185>ifwMGQhDOkt?^0qRNQ!iTbN}O|TSF5AF#L_m+!5KqMNwzrjf? zwn9|hZaq1+FtrsLkr}wdAdX%W9ibbiuULG}jy*tWY$$+I4gnaP%oft`awuq1zNhyo z-ioat;oXvK*_nSr1d$=v@h53($WH0`-xcxM+ke)tA_%}6-#%VUW_gB9(Xln~5PowM#uA&+QGkF3K#C4v8aiU)cYdP6 z@Snzm!`iSv^5n9l8O00m#p@&w$ph*?S!qms;zHAm)}LIhZYgM%56%$llO7>xnmk zzOADGRObORFG~C2!)okntKU0l0yh~RW~Qj~e*hP|o$__;-=%0`y+;kG?*L;D*%U}1 z+26lGR)}&#;Zs}f>N>#gtV#c@pCzw~#65ocn3$g4NkDNI>WC7z-=w%Js$M_Pf{H;KT|h+Kkr@fMYI*lLcA5LI+XZ z9aJlMuqtob=si9${&RH@uD^$Knl?wz^;O{!le0OELm!)@Xm>7;s-12<(N68f>wwa2 zMa9^1jrIL}r#zb{m-+kjQ;DfXA!!s<%CH^J$St{4*FdCx7wP}k>5Y(7XHHgva!1tj z-|&VP4d9TC@!e>^jVoEtzsSf=1EXpBVlt*IT!#r*(v*h{csMIM@Rt*E3lP2gW-0d)ejp~@19Y3{ad8d?EP z^>hR`qMhPQhR~0&>$Xf88JVa7HeaaJsS-p`Us5uNH6&0Gt~MU$Gbs?#C@dBf(xfo!va!Q-%IB1h};x>I;7K4=TF{+favc( zQ?#yaMqMi^*b(yrqe9%=7$6CB1m<`YvBoodXL&RbHR?)mOU0gzIBZ_Q(x!m~Brcwy zG=IqoIIT=hdH2-5E6$>pdy=Jy9dY?jOaAH=2^NupqItL6?(~csl}0nd05kD?BLc2d zajw9B#~tfuF~IBdcNpMGN%WZpNtM8W6On$S$swNqHtv6|sgUZ%tMJ@KCcNZB-msH* z%ddXaLz4UZ`!6pqqe=O^y{RybWhDp^<>OKCk&Ng@1>f4f;rf=B+Ny)RACaDZT6>DJ z;Oklx$g0-zKzNcMQl~&u58X>|u+{pCUH)^oVN7x|HtJn?6j!^o4Lp@AAgVIK}cL3X@Iy3n;G}bLq-hqiJ!}*i; z^C+OI1;}{+o|>B4`zW03hzYzltc*CaH$4HhOjgG93djjj{Nt?IO4IR+aHGi65q#4?qHP#yW6up`uLq6T z>3mi<7^>To@@?Ryr|@ggfzm5EIeDcDBcM-h`%;%3Em%^V8LNyQZE^T(%Ff!ltg_Oa zDAXAKc$sXd2GHcP11@dtv@K;h4MdjzaXcoX%*z3CQ)A=fbmU)s356&Sl`)2w(mwdz z4<|DCDNS*!+9mKrcPeP!n1SO_y8AC7p1;oU(`@L;WVhUrCPi+RXNnZa^;*JSsg;L< zfu}8PCE-Y#N1QAVuxl--DNoM|h_uR^3H)AUE@QgMOnS4jB9{FV?)2)T*jE}WD2iC$ zwwQp2>PXI^iH)pD_Hm&!Cs@IU9;BoMBk<35afrg);08FiM@Hly=)t16+;xRL)8h3< zBv3^7|BQTR2$faBo1N#cnphG*GlFvMRv<AR<< zyz(6h2oC+jEVPc&CrFHuH^kDS8k1AtQzQFGTJ!5z#^fz+W@bPEo575lv-6fho5vXo zTz(|Fq2MlG2R@aFECDdjEQD3}o!*4Cvifg8V1n5SS8)TMoIDE(wOK3N>+yBvU&>>` zh{4Ra7ve_!KR4<7T6~I@b)s$1N#LeUYn2%>+*mz*;!Uy;Z6qB%{X`mPpC}?2E~sLd zgQLz~o{Ui|pYtG}O@%3OJaKq^K8At42QWfa<^OD&uB+Wr3tqE^0iGavs7r$6(XXF> zZat-~7(rItps8{~&~Q)C3TbFHA3QFK8KD2UwK)Egy+k+EqQ25vUt=>C06>NZ&l1wHvSETPFCF73t{ClmP^tQ?P;#}_uZb^Ui2#;+C8g0VJy2EeV%ZS4b z2Q_dCBA&nX0;HWB`%w$ntYa4- z{9e)@J$W!|3cY<4TdW}P^m4f#F`qwNfzk?a=#r+a`;Mdp*cq@Qwm=y=luxz-m* zt?6ZL#T_!xJhitEy#YFFw3d_Ztuil+S*Qh2)VEfRgD>bAPg{B-Dr+l$V~OZ=9a%c9 z6{gIR(bfAuvtf||aTGwpuINZ!R)~rfkujktK*`I-$@0@c9l)~xx2|gv*xYhat|eTG z6Gu0-c91Xc?cC+Y5o?Tk0w+aZmLvFHtwsQ%9JJJ?YArOO<0g^tMplA_^9b6V5GK8J zdxrn|xK#-Kv;S5)i>992j%}$$U0>5Y+@Qmtv~IDdrfhF*?eu#KF~@curJ$LmjMvLl zr(3e>&Ed?C16bB3tM3`=9GQokbG`mOAUEnu|RlvxZ44j??D#eI*PvUKB^ zD5=U$egOhaOe!W;_&^}|-(ufl1?KJzvQ9|;)q8CQk!~nK{v&-`WDNV@55pM}k0ky$ zy$W!vRirDct~bNy8Ar(?=DrtbdCz1`H~HY<*$fxEzy$>E|2jpvxqGc*2)x%|QZ-aycu(oE;^Cs?X61+8a~@hS-OdxNvEn7hrPokN-A_|w{p+LGl+c>p)FJ>&`+8t0P=r#*UB}qSPr>~Lf09WCzT4xK8c4+?%(ygpP?Vci72|s<8p05R~rZln(b&ztowp-O(f!@f~ zdWmgDg^p*OLmI?Zs0FRKJzVf$BIWdgc-(Ni*(kWxQ|^wNAEIYVLH{O@)YMG8b+xq@ zHn=UXOolIi@ALX(ryq~8?ex_q^o2|QUvonlpO(g$I$EU0gu}fenUcWz!zXrw$#=A7 zv4{i;a7MDTv)??xLt~8Mc%qTegis`TMa|Fq_pU(94_64M8XrUFL&KUja9TJ3niXfC zVwv}Uj)3PNz!Z$<0ekJjYlVQ~d^c72XxV{7Akx2so{?(#qwl9HtLo!P2GOvmj5+v6 z(tJ9>RADm9{Ng|;8@p^f{W>>z)YtWEJdF%5H@C*8PiT$+Z=}5&j}W24@bGY;CG1na zH{W|$#Q%K;_#S$IQxu2~x~5!P-nM4&AU;mk5L+Q}3l*hpj=jc5TinI1x=64g$vdmx zO+aaQjF)M}r-0iX57uoB^T<`WR*Wr8=NRQ{3JD4Yr(I#bAA;_&hJWj>R9tr9%)II3b^{Na z2eya8D@X}QS&y0wvd^BwDfN-Q9*g}sHsfFlN~ReI>Zq@ zQVX`v`S=A}ZyI_R&Vn~sR`P!A?q=N1H3fC`(+jlx1 zZ?d`8#H!`09UrE!oe=|VsRD~%dR*i~-9N*@v2)uAu41AT1{5O@p_#kyMjqz^b3WL1 z|3E%>e+JyYu>vV1mOel|73tv1`UxY0+#H-eI9~BLifTjO832hR%^vUTxm2wbrKAE? zp85Frcw;6GuS(+!W;&lmv&Ii7`^+|74gTVJF30)9y-ZuGu#k)yP+3Vj03}FFG_^$P zDZI;hc`PC2T)!PqOMMT^+MmjdBO)P?>Z!bgM}+U8t10R7b2(1jv8=p5A66a4`Hd&~ z#(&M|@bZoS!EeW$R<;y)kUSZM99+P2buH_aWLV~E?L$B76Zl@O_c6B1#|#o~pnfqb z6T5m*UE{dgLKkACjHtVd<$F3KqyBt7RqAA$N(5Ou$XRsz%akqDV18D?YAWh&5B*l0 zHpPgmikM21EFS^gQ|4D4M+9gAfy;u84&}vrs%EblD(3{SzqT*jegXi>8cIT5ySUk5 zOsFeE=d3x%L6JVcg_hOdjlnTTBDfs~6_N69c4yHibOk zRnWIii3{Lfi}i9WHZ=5FUi9^%(Y_K_NdzY9XJ_EMM@2FOvo@M(ZHnJvPdETLtn~jb z1FMC{qVT(-aN_KNm@iW7y5&y?%HM-@xy)+Pb9E$DEFWs}9%EbP+3(V~XbL?=Jxxm)*g#ZwvD2G$3OQe2OS*rFE>P#bS(Xs?^4u(bT0SfV?Nal)RhS zHX9uA!>iRR%sR2cnwSF4Y6j9Ja?u}wCvk03G6dtlDNjG=uKE*8;m7bPB%<1#WBZCR&?I74;^1qNCUp$ zTpa$q*Ow?fhR|SE;vf*w?tI6B9VtS2@RJA5=`d}fw)OX9IDTmb?*yw$4h#6-;sa(L z$YdctgxBmTK*0}8DQ=m*Cj#V$Xx!a+Kwy08*8II=ZQg8EpbCgQ zUhr+DBL~t-{LJ{({0I8fCIi>UtJ=-FSLk+MT#QIDA0J)od|garVc8f86pwEH)5Ttr z!+PSopm*cXgY8W_9iM!Ux)?lO6y>Oz1EEk7Wvs93h-Dp7pSF1opiP$uI|??rkU zzyZW>gdfZn9?JutZM{!H0v`6AY)qOywFxuH9E9(7RRrc4l;<^i^(u1j(C&W=ueb{g zrgHcqiO@zxA550dEec&qg?QgO-nTfd%rF6>p2zdmhLaxi9fxlc+c688Tbwp}v#~w~ z?0DvBA>c5fAR30*R%y}Dzx@W^y#FWp9p87Isg9&5EhPn{T#?(OFvnwzSJ;pN{mH^B zjL>7Nz3tzmDVP}1Q!yReyBX$#78qo-@BzOkDZ1>HX+84poxnMJ%AF8(G@5vkdwU&Q z2z)wF6P}uRDq+pM8vfIyX-bG^3i>MM6wEE)G38*Yju*4UwUyZ(cpQIettlU%b+5Dj z3wr-mve9X?kAovI7|pXYz#Lqq_$~*2YPAyebszn@{>Fyda-ebf!j(?EnYMY8UnBiEi|;Z*#EP} z790Wb0{6zF5EBAFr)X^_tLt$XPcp|^H4ek5fEyBcXE!!@V@gmpGLtl6z~8p54jX-M z$K)P+5dVk!rwc9j<7GKmJueBdWvDjj5Sn%A?-Zggy9?bZ1S9iH!AH;?b zP>SkN-MmvPc_Mu3BD+chd!@h_kZ=j6om55TUB}_vk7*w(V}H_W;RvQp!fS^w)9}8( zv{sG{G{QrkRfG&=F9K|GWQj>e{+l~!q6%7E<48b%uDrZFizhTddd6Um+x&dnHS2XvQOn>tTWu$vvn}JOxFIj*EUe;x_`Jgz;P)EaCUuIh>Nf|Lw zfrGG{QDQ4Bg@7%X4U=#5M$y_5!)^79#titNMfwcETJ16z((n3WJyj@(f^{zT9=estt@f7GHlgdPSb$ro3v|)P5GCrx<+> zFi`>ilvsQ9R$ygv27?DrOic~(SGHB7wf$vwc{%-Sy$r?DOUO0pGzY8$gMtE_oqCzkw^e5{ zAR8#AD^Y@DjETfW1OqmK0+Xt(Wsv~k7(ZqFX2>6veD_z)9)wi?hX1oTWo0fLdV=e` z#Si4#1unX8RJI?P7N@B7Oi^KK{X;gT-_f9|wc&pjdzD5Dshj=>3jkrA78EHrYo<=} zjGi2YVs2-=z9>1Zu2Y0=UjqGCbVdqp>3=Dizt~U>u@~R!^=&O5Kt1Jd?khVQA^D|2 z+~Jmb3G&G=zgBwJg)Q=MHuwI1tZ-nYyed2&W$W?8*h z>U$IO?DqYJZ?167|KgM}-yXMuCINiEvqGtC;Nrpoq_YNMzP`dtxqDHHTvRoO9AHV`PG#$Jw|I{GlB#cbs5Fkt~ zcN7N08AYW5#!7oaRV}+=2{nt!B>nB~xs+mrBj0P68pr0n*j=hx z{|jwptKVr4w%?rFdc>^xl@dSASnh~?unusd`}OFx>Xt(~caYq%-Qb*|q~z=ASty=U zxcO0Oi2t!?f~M|oaiwa)I}6sq9*TskQ zx;_{J0Cwn%s{5r#SI%M*$&xB_KJ)Q=hI|tYBV%ORZd!Ropd2XARrTr3;RBs5k`9VD zwZ*<1TFz;2mZ8{EZzV0^gKBlsGttFVcsr!LlL{P-*Vl-fkRv2%CsGgMD|J zQkwfka-WlC!-R5PL@!7J3Z~FeRizjfvrJ1qUSsOP+@3r#`o?$zJtQ-6M6GKIhI2~K zYoS4LthILsC*95t-(tf9vfl__Y-u(}A5aM8- zhWe5k9DE50*Ow`u4FKqnLMrjd+7A~MYct#KsrBtK8lI-9K%DZt5EPHR;Ax_2vi=tD zXYQh=j4;dq%^6VI+cjAU!*MQbuj%F!Ds1|Ig?cQucTmT(2ROt@e3jVu-*SW;7$`V~;P zj-$nIiWB;E8iXVRj+0n|8sZ3X+xwGW`mCa_6+cdJx+pE_n3Lwj@w8b^;_oILt?Z%H zCE}4oZ_r8EUq@Lm{>xJTs~zrEa-bNY0`P6q&ASkCtXjlwY^D3n78U#|s&gwKID`Kr?zB*W7NaR+DCbGZ~}obzu<*&_wlidXhFr{V3tGfGbz|yTgfZV*4t^Ue#ZxJ^f}0* z0;|YBqS#oPWNo>C2&yQwK7C|vdmAslh+n9jf>Z+(^gW9hjUqCT#@QCRTuTn-?IE^_ zx`c~d`e$^yB)mHg3!rruzPSy$z+%x2ywGt*CebT5do!BOFFKDhNaSogAa2scDWoQP zUGch!cUGpo80tm;+wOB|DXEi@lU;KG9v%-=GI?m;VD74(c3 zGC%lvdwB`$q5KsOe%{_zK$qr?{!<*84>DVt_&BeEZv;p^uo$-fdcEY3=F}zPdVRR4 zsi}#H20fxADKy{T$t$0aBME1?VV0mlfm2LLiQD&I;P+phlkm9n;W+>8&Egpf zMbBAan(1YWP>?cL#h^rQ1Ocy{3{|zX>0z@;jFcVM57j=MvT2L=cHd`#KJZch#uYZ7 zR%z0(86ZUJe44WKWMgpyy@o_aNzGttlkn=Z0@Plxt~1m=i|?7FSGgaGiQ85QXEC=g z2}=dJaMWpcq+F^R>dv7tn=^7{K1Ts#XP$E{ToP*F^2^s!zmg?`qvn! z2cYXOb8+~4bbmp}IIVm+$)i!2X)6StC1EE;)KNDSKk&&6JI=SHa0(T{Gl+9LUQTk= zvBLk?X#PK~jxHw{m`_uqnW-{u9fxfG-BrF`{A$!b))2B&p5LJRNmVS+JLexkZ!8_7 zrYl#dr4KNPQLi^tV*-LL+c)hqHG4K>eAq2(*?ajStuKT)P7TJ1fK>@qCgQD2*=1{k z+CD|E)A>8=>eK;>9{{&;FkgL>BnK;F+R;I!o;Hc3`TuM& zg={v*XwT>p8DqQ)cd-=?yM!3AZ0X+_)nx~twGOJb^L8#CnIqp%e&id5QgGXOyMA%K zi5-{zAV06uO4j2R3Vv(#ivEM~0$Juj@mj%-4WqxPKI)?vRB-+SR#yDE{R(UKUVcRW z&fPYA_PC&jL+ZcPu`e0Dn=X*afI|28_cI$50+pxQJWfhWOP`+}e7vcEL)%2n5Z~Ru z$$$g=dCVAX9-WVi)^Ot}2EV0d`5pE2yU)=6y+M|i#H#~dx1CoF<-ocDjTjEwJWNvx z!S>06zmV1>$K&lk+5Q%j_5CfOfT=;m#;0{2IYs#p2CSWD z4V*9pqwWB>6w$Y6(%pZY;{(@q;}T`5Om}DjEK@XzrurtabL9HF=DL-ZfEE!Lt_*rc z;Xq5Zdd2*^-=j&mKlpRZwK(Sx3bOvO>M)zX2Lah##!|b|>hjvM<6-)71<;S1cyEU* z4ih;&f)i^PgdtpF^jWO+EW0UOc6}MB={{w-?xx?qNl@Ub)1KICO$$E0G-(qM5ZJ~d zwVN&j45ORQP8J|FT#+YWr>CZkZeJd1AuT;{d$yU?z!f-owizorvUQI6I+j929tN?o z`OffB%86R^@w5*R85Yz(0%*&Ntf5v=L>VfEc+lX!T)zl#oSdBc^UBPUe_yIET~BfE zAav>rg@R{rhJuEWT?xXn3bF_QE>1zljCa<*V=4q{#t0b5JNoXsfq&gSFR13{LG($X{z<3O38l1@y3aKqx| z9*kVa6%fgzk%@s^c>*w1fe1wYPs(qPsW~~PX&&f2$zl>&EFDQ#sZTamv|>w{l6TiwSg42z)=H(7l~#h zFKHY;h1E!hKpJkS@spW)F9*j6v}|@ZFjv5%FSMomp=l*0J$+BFI*~5}S!8O>xAfwM zQF*i7@PF&8Rg&fw7HDU$Y+>A=DODrNu`*!gT~$ZNvo z`;{94P%0I{z|9t3p|6CYNPyv}REbR~%(7IS$2-!bs>9-MX*nRS<aie;tCEViDm)mh<2RZ!C z63r>Q8>cMsKhOAgFDpNb!+v{b6RNKtjZa8zqA0fK`E&G)L--ev7%c4UD#Ah~Pw|H2 zXgR1EZ~_(LU0px~?rryJzZAbh{2W@W$U#6kSHHpXv)ZRmKY@NX1fs5<=rnKHiU7dl z2q4M~7%4_b){cBxLx^{3aqp27s{vG2#444s)z}-hFUJBZzs~6t)`Q+BD$)x%{|OFy z*QSFEnSSybR;H-3UJw!Fu{&???UTHGO%ytPa0Q@)-)U7X*Y8D@R~=F^35afmzFrcQ zvDxV`MwbdUl_L3AxKUO_7^|iK`2F^Y;N|{Le2T$nj$Xn10j1C355Q?i)8g)3-A^=a zk&IEU0L_uQT`$gncMNqwbqm|WhZ9XwS26kup8I*y8X6iOKmG)~;StIlbMlC^&JNGc zGK6sI*H8Id-fXNNsV+*#(x}0po=2nV%1S>#svC|)r?y`YM*9{iPa!T51*knDH5Mug zi3B3@z;OA9czsGO(14;j8tX*m>Q&jS4S=G?Iq%U^P1n_AP|(4PA>s`=hvFlN1D)H; zg_^y_47IOGN%+Ve633H#v9Yet1K;ot4!jV73eV=?+8c;9P%XwYF$K`#=#+wqpVePWNa*ZfAd^8$Ppu-YA6$3E3gXNK4 zUB<4H^cIu!ue#S24ElL!{=X5|vk_fa8bPh59#8JVJP)clPUGmqBR0p%_ zj~>=Hnw(A)UWgpFaC`12pfSe_e#WP_s%kQ#)ZfC;&~Oaz%WHSAk`6aMDiN)=!J=rN zO=cZ5-Fg=|nT(~tZ<{H^$MN@zKD<0$kaL6Kdz{;)r~Y2CUNwLrih2+yE#=D0#)jyQ z%Xcb@PO@>6W??ue{>r==T4NQQ9Y^(>Ep!eXcFff#QT}^nZ&Q+z>YX<~ZZs5$L=y4p zhbbhE9~sTCEfMqTy!nV!w|O5}vDi5p$Am?$eL1WvhGnMr7tZInQ z!^BTy(nNp;PFAk$aGo8(fJ)+y%;ZNiK&7Wa~Gvr(-vfJpE z?5%H<)i7cUig4gM-q5#?ufRO=A z*jby={EeK~{d|+cjgY+=^AKb<14hG)n_qmIE0Ld{AFKGX-+elW@w=;T=Nn;9JLzzH zc}Zc_Z@v6s8L8ws4<~-gw%{t-)n@c34z7&p=~Z;g(H=V%@9%KJ@{5+^c^(?mF`|}j zEiA)b9F(t!G&@F$9E8tD0WDBeu@Qx~`X}m&TI2%Pr0nwaPdHM+v*lW^=Lr5mg@J$t zFqFuSUr|9u=019NCJ8#pJ|@KBC& zILjQ^aYM`qEb~iV8QI{Qqfgi#V_oO4U5Az#SzY01&9N>9^0HjVAMcp9rl)$H%9juoLaZN(vmE*e{nSZ67~A z4EOy6Nrm_Kg<VY#jCV*mWUmS6P6tcfxhTQ7Qt9QqhCGf&}3(`@u`mQP!Je8c*( zq+Z?df&Mwa;Vu(7?smOoja?240W?Le`b{fM2{kw%pfcB3k>e!JqDrO;C6vWQz1Ryw z6IOIYX>+oB$i5RJuvD{n0T2B*qIUF{1VBIGBq>_sv>f_BQM3;CT6aF5@8pEZYNRIx z>pFZzFergFICRVdgB^h5=t*9&BX^VDe~RKKoFRLG+}C_DPWRT#w$D?- zU(P3atv_~k;&KKhjkRD|qCNb|UcKt#o3sC25D(1PKep8&hi>*NJBp}to^B`gnKqCm;RhTw&AvKDNbqegBAHr&I^K ztfXXa`AXYaCEx!;)LTbI{e9oVBOMX~iqasRN_R?0cY_EF-Q7rsfYROFNVk9z!qDAF zcXvJ4_viOrkBdKGv0O8}=H3(g?6bEJLun+eapTKfAw~q$jRaz==vd3KLE3S#q#-o< zJ2Kg2x;0tj;syMQjzYq#_8Ol77H9h%m93#vo|63Q;%Q48#w2O)$8!ep!Y5ka(`-HO z9$DG>1{L&_Q%V)hag1KPltczgZ1xs%1!BS z6=b-NPlAt1ZfQxiy<`SiNZZeagusVexV~Z@iuj zLe9?x6VqNPg~F^eCeJ19WBKLD4ieaBKrFn;wEaq}okDU*rOl8XfilVi9em9vbb!;j zI{N%;fQl(HHW`#Ugk}+ zti9vnZ)e&)GVkT`(M+jbf%#(c-}cYdWfsW?Uy)Amz0RrC8aO0|5#4O2*Ae;@#e7ZS zJ^GS1>iui~L{7mwuVwYN{^04s!PRQo{3{6W$gP-g-`25mf3766S6Zf_C!aAyS9Kq`{oo>nwKL8 zih6q1zK8=JE@Uq`J!KD#ADZQchB*#7k@8~&DFzL4)un#yo^JRcdZPGOx@B1C`**3yb?YT%zb}}R7KUhMCNau3?%HpN!onv=ByT3&z4(6K5w|PLc=PSW`+K(4= z1>w-Bt(&QU`K2Y246wh%PI64#E?<8#lfcwV$fJLKK;l+GVQ;b2JAt2 zj39;5QK@Z8mv8Gs^kIYs0@m8EpH+w&8jnLAB)&&mXK9zwUA}GiayM8atY|BAnM^K3C5|2#PV6-~-m1S<6GCUhxomO4wI>8WrLbetfB-XHS_EZ^k8 z%*)a&XL^iM(GIom>&*TJMA+;aJgIfIGPOBAJv^4WVwBNW5IU`0`{b-;GN!3W$$9MO ztDPYoYTfqH_?o-xt30gjot-U}629O29u!`~!l>8L5VTd-E2zWnJh?is$=}X;G#7g7 zA!x7IwW=XBt2c1MUs<_uvPz@t&p5cY++LU)y&~kK$fl+H2Up|A$I{|$Y9b9bzIPw{ zUD{)eq>MZ~xGAZq()r!TI^zMqv4CBmvs@ZSsHKxDU%!OcB;xn%=j!kr^_0ORYimSC zowD%_9Vdn%Xp&X1(n)LhmLcOen)U2|yPb-0lgD=A8Fj?}O)<@ybA+OagU=lwugFMu z4+|tnemO|s{EbxYc}GJ*A*#q`s~SbXk+;23xKIK`yWe_qaQvuKAlKvpOW^?9^iiRq zc2BQ~IxRjVQ&(5e`weY;LTt+ob-&~}`AKi___o=QN8o^XdD81_bI40j6fWc@2A4*@ z&-jN;WCiYm9ZvQ$G=AjtUJ`z!e0krUy|_r**2d3c;V-8*$~6UrT9$)Ig)}qWhBxWn z;=bvF4$`(>guq9zBEg?m1t~D6ItRVBzONfN67o_Wwx`;g4q56rdA3pY>G%P9f9+*{ z7l}o1cXi#M)`73fRlm7qjq#^-)i4rdn^~8;kQxar?ChuWWR2x269wx_jvg$#LK(sP zcl#MEhv`YwNJuP#>RxBJ=?&3Dnzb%QPeD3IE#&dff(M>eAwwXlQuoJ7Vz+@rjaHy5 zM2oB^w2c^IS~~kVxhDEJyyV_1skG^P&u8r^&1oGAqs|V*#Mz<36OpF%_d`h-@2>f~ zs#WFZn&rBJs)>15ysahgLqnk{rHaSyG&&N2E%jC)b>F6bc<}7bD8{hHyv2|!^|aNX z-OgnzIoZ^dX1L}odH4#L%Adu1F3n{>-qG}v4`>M0*}d+jF(A16;l9fjJ#-*rU;QRv zSwR1j1ibS_dC~T>Tx3Gyl3%r`xJa(Sq?)b8+gH2oDn^tLh|||>g+;C)wfpT~8LVPP zaNY48Ye&)ECYl}Yfl*GG!%w$Cu2D=6cWYNdQ@#V?$eXsrEyv%HNi=vo&R_cST`B{k!t?FYha8iU z+bmdbrkP>ID2v-|<<(&5Tcv~ORL2||7Sebk1uEI}qMPtg`N_10X-m`1N?&tjp*O+{ zFgDIMkF4tiW5@`z*Jcy4>F=0U!_DpK_BP|c$O+!nJB7szS4%upDSoSBlFuNn-7%J2 z-tH?Wdt1Noh-Pl?2J>^BX41oU>J{yNN6&_HInuQ_IiknI9#*HzvK~h0OHsR*jkdUI zoP5S^PntShcb9A5JcozuK_EYSen7qro$WwMxiQTM2okaWthhrUDHU8+6bKL%Od^P% z07iA%-;LFx+4=9`I^bS@QG7j*#jA<-JShH0fTN$wYtdHsn%}V0C@F5X;81K##-ij1 zC`p^6(u@@$)Nb2;&Y}}+Z`}G4f{}tvBJ@zm5uS^^Kp`hH4|d^M zVAN1bLWjry#a1MkHP0nY70c`6vi@)N9cp!|&idclsGTU+pL8hu}W4ys_(!nFv}YdORzd zNn;V<5){&8me}F6a5Z7k*q8Y^Liq(-6z?thoA3`PHSa9Gd-i$jBmjz(hV zthi~@!|#1@id!h%XOyybC{qbWoPL z{oP!}X;;_@)DY@W4U(WkwM(CWa-92>kMX^I?xyt7#Q@6KPsl3KcH`Y1Mw&5FY|Hj; zk2$$gF&{savo7D$je*5X$&@v7sCOP&MzE%o^tn{|iW#7~pJMww~vl^x$ zjvv>wOkc3!)G}-BHw+F0co{ek$A<4rb_V_`!5&*|)xah>!nJrgz!+SpTFfX`C`0WJZ@6 z0vWCE{{hLeA_~bE#SY03QSwhUg+;Ky3Ac};kYFvi5JDib-y~fYHUP@MZ`$gPJk4dm zAF+5U_w7lw#ej#5l-q_%yxh{8rr_Y1v}p)wJ9OW3I%OOyJ&Fa6e0MXy%zW-OAFqyzOLSS8Vh1pm#8g({ z(RL{zvaj{W$57r%rTMo5C@n}%bZcZEf|5lUm+n{f5)p1`^|)_c+5cN_;iA)#-m=f- zXxNWgrG9(g+r4O(p|4G>TG{lJeW57iN+<|HJ&?&wUJ~&b7=19=j*w6N-;*?3Twfv2 z?!Va9l^ZvpKP6W4!h*^U9tq6_)?OH~Q zL*(2LoO0wBC&e4hPLaTiz&(W1OQLV`0u5JJ}B&3N#++-?q10U6w{FVxnO!{bu&` z*dnYf=ka~y7r{mgqF4~HNR_vlSvcWL=lpinw?ZJ`u-N-p-(C6QXQtbk-=ii1qDq_~ zVjz3UBUaaAtY`2U#=k5Y3)LJOCz7@V$vB;_4woDmT_*Hy z@w#ESoHmcc!vRNxnZnch+-kWU^_f$52|u#iG0lnMc|IK^l;8C-5>qqXl3R9QuzDYU z$cLvH{QOk4OFFTjkvR=Vks|?1ZnJsVOn*z#mff(B;QK>Wz)O)4n-VhcgFiXW=PWMr z$oI5++homok|)zE1`JA!aPyjr8!+82+OW1TZpZsj26o!;DJoOl#QD@Detp}Zig%8Z z@>eX*tHymb=yq5+OfLCQp);fy`=&Pv1OoZkibFO>)D^i@^6VK#-sw;BSl(n znhHi8nGU^`!VGjJXkF5f%thqE|Vgm*R}@I&eq zq77NB;@)j{73!DLVwKWQZmDE9>2ZTEf5YS1DfD>Spdr9!@VWx6BV%Wo(!UcSB!T{^ zHbdAElIUK)5qfcm#%Xmct)a>$&f0goti@UBmGbvTv>`4ej=v*@Or3*WN@=sweKqJ_ zzYQWx8%AOwP6n(K9Fh3zmGyHModz6)DJX9og%3O%4S~;z#dL+9(Bro@qj?5mUBn`1 zecvU4n*#ih=W?LUbpm=OY`JfHVD-DlATs!B3UqC?w>yF{(Mu4_5Q(YJmZ<4)5?AjX3eg-hOwrzbJwJ%M@ev08nr`uzQ*-@Mm38>%5qhtjP@`uf^_-^m|T z_1+!Suy$>|YZyepF%CFdI3LPmD=jFv{Fq)1RmlGBlP?tL@hc|;S17|=N`Bd{FWfKm zwZIlMM@qoe!ME7f;JStoKOY0P(NIsG&oV^{Y4Lg{Pr&uLEXl*UtH~-$MAvzTjr2l2 zla~7{%g(E(`2u}b>nzFz?=D?pAa6O}0lG!~eIT6!+)6YWG@uiihncPidHK->t}8(e zSIPI^v>RnQ_M?{89)vD&<|KE6MFyUNSmMXv4EZ^DLVlCO_nJzME1t!g(b7_x z+l*LLbd4w`@FN^VIXoPE1&2|FB{@I7%txQG(ZZA}vOO#msG*aS z%=@PAkd6?Z14w2Z1h5|b!>84nW;@s3#LV_0ox6px?d|Pqquw#O;P3MCGL8#i^3Ny6 zQF5<)s?4mFEK>scJa*kFGdsh+ybSS4fVWUTA5O!Yx&NoVmytm-LhXaIOJIYb=(0qW z@0L?gP_VNL2EZo9#>ZZLYHaJ(T4}Y~Ocx}JFDx5oq~j%~rpkgeb<%Z8)DccKdU%+e zTSarT_H1vtLw-xp5=I5_bC!bNjYZm^y1VKTGpI0ZQ*(v)>1pg`acI9m^pkCQ;@yiB z1f2Kihd0YEBJkBN5g2hP&|4gKshGi`p$tLq=HWX42WSJvpsVTrRzrFFQ8gE){q$1J zYI|Yc| z-Dxy|rngTk%2EG%f0gfY=ni_8V~peHI;|yu6RAA5sriSG$(c-E&(BIyU+b9twl_*r z;@03hvvDnZnA3Bl0CL9O-%k7*S~rEIRbDrza;cm_Hcv~?S1+t)_I=zE;o+hJsO`5Q zSl-`O0OQ z^tE(Z2kXsuY*FBOEOV6NI-e$RW*XGO1v}|rSv@-{XgisDqN1S*5jfwnFxv^=b?b(X zi@S9<8&*?1RA?992V|q|R;2i>BNl+29VvPXmU--Eox?H2zJkrA45pd5S zBWRH&(z+B>(?t(x>Untd?tY`rd8*~lD$`?G>#nNJf>LZ8%>0#r-WT65+PAME6@Mq% zacNv0_I{p+BwpoN8|1xrMNRArzG1;}{eBc>&HWqi!M_jHc{1_9 znWIi#w3N)^bU2gg%{v$2+L3Rc;s~Cag{24!m{srYI&)1OmS*R!I-m4$x4*t7;1wf% zC-7xza!{68MK-Hg@|HD+u~8DsM&Fk-VX4pN@y8k(^0T3;S$OP$XV3hAW@sr=`TC7B zB`V|u!yoGHA!jHPsEmewbbGxPcj^GqJex84jAAOOPe{yYMj}YEZj_I)pE1iO?wAH>=iu%j zfvWjvS{m<&gRT-Q#&<~E*IyWBOLO1}ovgP$ZZ9s&dS1u3gdnFVr?cESM?3y`8&;0- zrSJRQ(%V#@L7{$TFS4JDM!e7Y!`QKsJ$ zlH_b`(o~B#i}0fvZ_Wi=*IpEtlvn`FatBwL>wc2tu)Ve?xMNm>|1xAzD1E-sK38^X zBjTw(!w^@rGCs3yeHz7%<75+Jcli0|+E>Lr{%z+kf9S)$35MpN=!=?}`CGnUzYiv~ z*(MtGPl^hr>_2M18;btsD9dFCy0S-vka{OW_Moi=Mq~&jQ#L$F_qTZqhmTGK=A~b1 z`1hdhkSsIQNeo{S7w==rvDg#eG89Dab)vTv6X?5R-*=D#35`TFrio_wL`A#)$Xd9lY}=v|U15gno$mm=ENO4<{LR+PG|&Peck|u|NAX zbr5b6ZN=k#yU^^sr^~F-*n%tD6HS^K7q=dp$FZ+{qt=s(j=(#&;4*I=6cqHB_lOc# z5Hu9<+QH{(q@V5-C2(OTJM09}_b90}Fpo0EMQDbaa<`~{K<0Zb!gSW|`igX3uYZTD zZ11>Lx#MbjMJd!@Lp%#povm|VkYef7nb1>};T#NJ2^Lb|W=Rx0oWI3&-3@OOq~mSn@qj1zJ=-OQNpM995-P9aOxsus|E*nLP8`)euq= zo}8svY4GfgtmX^{3*qzkU1GJ%a`X?#|MKfKvLDpY+X}S*LhSBBb#LGZjB<=I4NK z_5PvL$r*f>M&>3sou5P{RXA|96?w!y29iuB1a-XAz(yTlGI%{I`Sx01Asq$z>4w z836@{9sQbmY%5I2$IXxKL{y?=1=Ez$5GgwP(vUWRbudNd}2j1MgnLm^Z9Wx7Nw||F{;G1IAxdvN+Tk z`$A^1QI2II62@gq3fNNj*K5%M84@*gozH<<36D}iK5B`(2rgtOQ^>Yjv-v?S;)I-) zRk?Js-sx>hB9KkcEGaGJYt%@p${pVUm6h;m=CN(D+YO)@ZC zS?2ohZ_coYdGUS``ekA7>IlmA);N*0xVKb>YaETN-*}j)go>G_yx3HSll?q<>y!qP ziYK-F0-Jr#Ox7&lF-eSYjc0Evyx)f$t7diT*f)_qK=u-Fq_oqRW9x=CT;N4rQqyzH zf7zqhBZ#_$=#?uczQlh)L=!u}1a(xhx94-c4AsB?5wX+4p=Ijq%t$4J80;o2aun$e@ zqV8<%r5%8CReu}(Nkpbf21}b z&8kmP!{(%UYXnN1JyhZ3NLgtdv^;gbV$|}a3&*UyboefY4KzuR%hwy7@l4i$oo)<5 z%pe!RS!9pES}!_AD@Os4)-vo4ZhO4lv%V}3Kxe>&2-fz<`R)#lieEw1y53 ztyn@u#nh2Eol<-hPaKXe_9Kd49}3fOwFwm!YjL0vPht0}3-1e2i^!hO)iVc|KvV;H zE+4=f>)bXIMM{+&kGI4PQ397@kS~{ycKhtDmn5xs(hmb`Er#1avkttDjc-inqZYic z76Ho+ZxVxLQyryQz5SMaxTcchOp~_pa!{Cb5QT?bObNfQkVXWLJrSd2h*kq0TXW>s zr+-gvT<)hobx$g@^)Q0p#z3O&TrJ%~n^{1@2ZU{}%c3bQ-qgi=XUT}J^k)EFN$7)W zVVCBhmr(uG4%V7Z`)O#IW=CyMiR_1E)1l|qWV#b~S=^Onw|2PNo9=^$^2U4H_rQ|caJK#l7VzAvom9#^I35WauBF*4KR1mz$ zJ1BVe_sl(j)=co7l|>GtKLrFm<-Y?3Hs>`*_WQx}ga4D4{If7Vkoy3tOkj{SFCUh- z=ntLyBzUDNnTpYpY*@23(kw6@;-RG?^<(zaycH)VajS`310m$p^9soi>lF)~}<<@bPY|7=d524pCsjgK1m!xwO?E+g&txP17XcPC0pO0o_b&~fm}bx8yM(0jvk z`@gnb5)_Str*!h)eCRI7>*JvOLi~RZ105V1C&K4Q-AV6_>aFKr9Y!HY;B#2*<|=AA zW0ilNwt|Ck_Pexvp&TEL&uL@oPa!KV{(AQ?)-{DDIYZTQf@fJ(6{xGI)e#D|o@a?!miIy!{-gjya8a-SgEoNWp8(T(t5$_FgYE6Nw|E}Kiy&s`*yUf{j#jHA0D^`>m(ppi`?(pqnSL?A0bMRSBg4r?OdRO0z5kU{I6B5YJ;uG+9XFabTm?9n z>reLY;qV|4-w^oN-~TVn5>|=fj$6O}|MP4UeRH^BO)qHv*}fDAP0YU|9JAaUaT@Ou zA?r(#mIj?ASs>RBMo5|at$FpA=$;8f>R!dr!o}h29f!$zw)`=PAG%ME5C7=C3k$k{ zS?R>f^eW<5Py`#$ye;bd6G3T31tMnhSHssS1$5y#<|$+-F_fS-={<01(q$Y_#-sW! z<(47oNBQ*^v?0~f@`Wg8OF958b}bSIHtY~|^-S-tPo$-#CD!8U*NERyfYJW+UdO}b zJP%tXPs8w=^M}k1gohqI_cyvB)R4TWSg5zF!(6R-e0)5@s3YkUyG&NFTxNEU89TH7 zg8$@H2QlZsU#DF0ur$6<&4>*7CStm~#IT5jaF(HG@W}ph21~iztOyR>98f zc7*DAs(?BS0pjg6!Wj55xF0&}w2CNQ@YeXu%>e}t(i$&ECG6qg;3D$ns@{^*3gXAX zpe~G?t1@ovNS;${y-P1m*yqZ|QSGJ*(g{Kw8( z6i8PGr8FF*`yEc$2mF`6?bCi+Nuap%X8;e}Vp%j{DN3Be0jk*keHTx#Y~B6t<;#~K z>`G1nIb(vz9xKlIgUbTFm(Nora!1YBU6KrO$@8Z7fZE5}T63N`mxuz0VqjTALsj*Y z$ash_Myh#$HzG{&{EyWEqk&3jj~$vHBt{bD{{rZ{q>8|3W4e-LISpreUVYd;KYQdY zLZwbSc>my^-Gv!zx0x2o@EXJNrt?w;J6aDg8<2wb;&m|%vM}k*sN=c zE0y!Qj zsR2-_sncd)U;tLY-S19LPJo3@wjx+SYGGOWE zT+g9adgKh8)UdEHU@wZ{YQW3lL(SDEuxO@vOyfz7;3HDMX8zH^!67U4S}ZhJ1k;b2 zJBF+(E9~Eq`LBdwevTxj_!rh~Hf;5gAs7ap5!kk<0!wR{=XivAA>`Vud!Pw3X=w2& z*N~x-3y3be=|cZ`Hi8{O!W-F-Od9`e950$iNAuI`qa$qSVAA)*M0{Lau^3}Ly>!>+ z!GcR!TVvKY5FpPU+Ye$1ifCbK-Zkp~aRJ6rOF^g>%?85$#S@?20TT>;C7Xs>KzuDJ z`6ws%l0SoSz=E9sh+E>~<|@*Dlo>Efi3%P0W6Ua4nGp5fiXsqr(t~RzN<M14zAT< z4c98MNH2S`EOo53Tk)t_AQHIom?62KIH;(IGJGAirmUhur5px>)@U-m`2PK4ehe83 zx!=Q_<#?HTsc8PA`LF^EB(e|4gq-gMz9fL%YFv-P!w0Y4FN&_hqya0kkOOoyw7~bA z+XAS+Ap`JV{N6s>`hT?-s94|fni9Z-CkKJVjrDxJ-h(|~b_(6to9C&wv=c@$X~^%t zK=)8OH*>^rV`8(jz?3cC;U*pm8JQ_Zg;-93!iz(J|5>(b+uarB>4OXMwCNE<(}ild zPz={|6RbbE9WFG16(e_kk|S+l5Gbll>;0qK>E_tnGa57*F+&2#P!b2!R8&;d)Pk@} zii=m>^|KX!_4EMwlo-l%%#cN>3Q#)FQluS()_}%h{=nRP8c#wJ9}f@A?5AG({dhys zO)Y{A2+z3^k+;r57%MiO0rC>kJOUODU0@F*NVV|w(@DnWhw@g}jxYvw*#*$nh5m&h z{x#y2@d*&lSMw!%hC;?2C^q!J-16z&VyJu(H28Zhxz}O;kPkY6L^s%SUD&Mj+{RF{ z!!@f9Q>J+K&tQWM5itj2eA5mhj4AynJHAJYM&Lj4jEoO?jIjQtF>H@U_IN7EzsQ5Z z*t!8VG%NA-ZrWfP&-khx-m6yyd3i}N=uYs($doU@F5V}SspuZd}rN#$)-UjUpYJn4-HY2mQx!aA6HLXojJb$UsG0-^6;c9 z!exbnproq{{FfD#r>OoR8sCBK`tRSr8z~f9%%vG@V=sTFimgzefIAIDG!?no#om_V zKoG=Na)e($FJJ;oS*$+yZVmIqBchF-k^c({yd5cYIIp^)(dD+7knAWf+XV1mzYZii z8vn3LM2C#IlR(B$Dbm+~-H5ioX74-5x8xy{bwvo7u{B;C?C9zs0N7A`8V*GDq?Sd= z*)3N?yz$}NrV8#tAE;PwRD+Pk>r1~R`z{57g_5Qw?K-{=E(K0h*y0UZyo6X?0DJ_ku*_psd7|dLR;b2q!-#$Le(x1Xx`g@~> zQvP|CC}u)3i!lpA7C;6e(T9f^m;tXGheGrYwo3wClS%lUklZApB9Bh+-wn&i{qUfY*>~-G=(pY$&Y{9M{ zlBR7pHTzJ=_LiC?_6K)&cTrJMX{|&?G*#t4)RdG!TVO3*m{_*uAQ`~qvKZgV%WZ;SW7# zLiT!7IAM?v71Fp@9h&l#i?f78143tQJPWGI8=K}2Ho?)v7JcyoP>$>!MaI{;E9&bL za%e$HjqU%twq|Kz0Up)L-!kwBDk`Qd>YjI-)xGdjj2ShnnY}$f6fhgf0vBZ(HChYf0bVzJ8 zwk$KCGC&0ap^VPb!KnLRNB1sCUX;OtntDGEW5ZFQmg(>D3v**@?7S_&aQL1OGux?_ zxC8MUwAY>bLSn(ayMmBH0dyt7Vlb=%=eJyH_cPC3Tg@5)5=h^tq+3pX(IgCV$o1oj z2)EnuZMD%d9V1xQ!a>o!7)twvcm?hm-+tO)3dbH$QWFcoyl~^^Of8T9yD34N)%kUuiE(jVl^z_!>MXRpcM@2ciK$eJqAjj#>rOFI7{k zPBE0T00nFJz5^nvn_FAxm?}@^#eU8V!N57eKue3~pm{Yh920}^^~h+~;BV0+7d>qt zt*@)A`)?}UGA?(_wxruwF~V!Ogq#5~uh(GnjJ(yyNYd(%c0qjAGhej$?(6IG> zq{#6|kB12JNXV4m-9&y)<9B*lZF3lCdS;T_9ihR!X#V)PV>Y zqNJn*Qa#w$2RZ0f1XY$|jo5U(hlm7p2I58y=Sf*@wTc3z%*GZ)tis{EKmIq9 zwF)r26F?)t!?Xwi?amw*L^VPP~_k=Y1%=V1@80nZbdwk8q^Y2w?riWR}+I%me0acbr@fz z!l=WOMjCyZuiLK+wx`M}DkM+zOCoTz-8A%$xBiq7B?rIRId25HXvrcrtmm<-508PUxbo?|pgRHO z34G+F#EF3|&lqXzZ$*(rs}g893*ugWBSb&m9|R9jyeYn*rKXlBRs{)XZf>q8bHIo- z*}~E?Hz&s|B|$1*K2fDyoraPUEXr3g-p$)~H0d&v2NY)3+RPyMfu)2dg-k(b&YgTw zNtO=0@?*zGimJ4(Pw$9?e27YuJ4O4_$9Qx48_auN3KcfFs3PD12)ir$P59{tMhZ%V zp?}d9JS%Ep;H&4%y9gHUAFMjS&RlpnTABIhcY1KP9Bhr3vXHDs*$Qbvm@G3}sh%`v zDm}_dgHwFMpRJ6eY%p-;(c)=u?vFoD(SOldAN2$7aB18!uxi)MWrF2WVfEg3mrZAz2Yrt#ELTV_;a){W{u+GPDN*jHU1rDPxMTAUOVCr&W4AF z$NT{t&34cWlk;TF4=EW`2T21Fq|5_xT^mc z2>H2bvgdg;uJDW;j78UDM>H{M%dHBelMx=E#RVApguRr&F#DDxUa{z;Bn#GW;X02sTl# zR=IjAOkD-6BLd8m2{JJ`2@ImZYy#{dem6`4KrdhVP`yGVz8q--0MC8EF0$|AS!Sj; zbl%|5I{K91uiekHRBhe6CErR$LJSQ@qM4KQ%^M8Yf4j8Qv2-I}i;|!(OpB(>c}?rO zfuwQv8FSD#u^N$)vNC$#zbAzc3r-I`Th;$-EoGzgK_khB8R5(wWwW69JskrD^+{YI z)90W>tybeA7*M`IQEBJ&DxkAAQxOjlO?|>$<(|vxvnRAr9CR^Ogx0@4o&CRZ6Xo;E z-txcP`Kl=g4yaK>0P-}O%W^Dt-=Tsu-fgCe^FTiNCtt+Fv+lceX48Gj1$7N)-lp-|d%Se+)LXupG*GD_cY8!8Ts zxDr6Qj9Gv8^z2@Ev@9|=vT#_`ed1(Kg#qxB3?-!iU_fNqX!hHnbw>;Gr<4xqHhlLQ z0xaCihQv~`1y&n%nFx?%4*aTAd+vGnDzIG5*v&#f^DobSie0TxZz zb2OhhHpDMKsK6hNM6k^in1);{eJu7k?HMaL@c-8a18oCvbCQzrI*Cz}_y>j7!cF3saiZl^!iT;i>c1~Q5gtJcNI8jXRc_3;lA|AH`I zWTSVB0e}y{z|iLs%`V84IEd)yCRkpZ%W9?1KRtKw`HH$+DAThdHMGg!j*d2oGZ7uk zH~mMnSS&f^E9s7xe4o%E(+X)b;Y4HzKr00e8}$biQ}hi}p*p{3acbJUI@o;#Wdca3 z4wbzLBa}<6=6?sESJaKvzY}u=V#!dBbgQIKoC@V z?3xPs214UFY5l&|K8oNXG*g)2AXFbEvIX=&V<`I-({zWD2k{0@7<(Owupo>fKG){1 z5&qN~_XoSCr#AP~nZ4pjTNQ{r^uBi(1r6t4BPzLX56piD_CK&AR28UbJ-J`ih~?Wf zI2!AVm8*$<9U<`Aj zj zto}UpGKI)5;EM|@xWIVMU;Hspf1ZX~tdHc;i599+@9H^HmpTzF4te8a5vzb5Ku8sl z0YUpCXQ!Tz)x3|7x>oTHwRW*b6LY5pZoExrMV^Fhp|3+U_dHeQfM{VS&>}wn1yXR|htTp@q*&g<@t^GhW<w2lxHOzBqIM$_dM*fSo^{+>3RoqzJhl^2{N+dq+LE`#R>BMk*JuzUTu9n z_{p+v4xq`=y#d(aU%vvECGcx!_0nE5N|e7d)kZ!(>q$vTg_%Ac-4RbWXYk`#2m7tm zu$ROA%kEFzU^)wC7B#a(hlftc_g}eeGm~b@3{_qvw|^G*5FXbBIi4@-5bHK+MR0#L z=ta9yykiXIhcpC2-Z`{uYM{LPnbA zewTwAZ9Sj({WJId@88cF7=b7{giPho^r?m2u3t_}ZK^e`vg39qPm9lZcY%=RQu%v^ zOv}=f8i!yp`&LWrd#=T7T!r+u^NCLHkm&SgMJ7_aMgJQW4_woZ+v~)lrUr%3LdZ`a zn=Q$X4~tGRUfoE2ad)#*e;#*YRF)3}4d2V^*V?fYEjFEPIcBu8+33A{ue7uf1}9wa z?`>fH^f*0WoTfyBNDu8|YS1lp#3Np~*}&?EAGpmQ&fs$vrmRqj{@3ikv)jNI8g}F) zEGZJ6ukR=IQlyX9Uh*2Zzhul+{?fbVyGjPezEmT7^VhlZYvcEHr(zDtUg$9Y*Pe$M zoL0fq7{CJiA4=0PLu-m6_fU*M7H z*$E;h=@a_{!kh22Q9Cj9^)l^RA^5XR>-DDA=ZJXffbVEH+v4me4&C^xa z9b$jYp_a?MCbQ?7Da~H1piOLD;lk)crF3N6@8<-3CVv72=NNKd8t5n?^q4V)?S>Df z$LWtR(?SKvbMKzB=?m)p>=lpqt+}g3eFkAoUuql2Dc5LWKJ?m&UkEjK6*%uT-xaI$ zvYQEn%nn?3v^pZBG{ie%HhIo5^Ec8l*CzHwcsStl4UwS}g;(&6H+Y*j|#RYM?` z=*S&|(>*&CY1-=*O~-3{sV=IQDeZ3h7AMG-q))x_G97OspxX-fcd^|sy=rLCk{uhY z7Wx%hkBWP3-h6thWAym7O-ZHEymjH+Vz_TTaG0Kc4ce~*I%_^Qj{kCHCo%_FD_K z*1-#v!oy^Cx{mA*!7v;AI9NQ1Lhxcm?YtxQpBIzLF}2^&jZY ztZG0_gL>4Eq4I;uJGP**(GfsbMd@`nHJvTbL_;;`xr2xxQZZm4D~MBg75qG264%r0 z+%^1Z;xlvQd7tceWe8ZNlEw*3$N|XV|EwKBTOh79!j0LMm$$w!Tk|U7H?&4;5SlIV zO*_}VN%uSNBG4<7j3SzCuw9i*r5Nuck!HjYf{^^LM6 zKzR8LHeL^BYMnl2pD#kgW`(W(OoMIa>z_+)1w1%@!bR0t(vYI{n6dCAJ>+2$-ekw~ zuk!id%;S_LFT~3~zRE^Z9ie3JwrO|uxn22%qV|7adW{bXUHsETN#?NTdC9 zOkqR`w=wVK!PRKZmh66Mv>Xwyx$^zvf{X^q346`uj}q6XJgG3w>g5&kfaklxB50H8 zOApou6X%@-a7_p5q3Zo@f@I_x;-ck?xLj7sPevibDcEG=$=x&|k)%W>LN#|X!x(2^ zF9jP{h|K#>mQlyOjRXYJ+~2VH-g9E*5eXLm@GiL6b(zP=IP-O#wk^AA8Z$dNEGtZ9 z&*zq78ROG1pT|4i2ZG#aM`c!r{&e&n3=(dK{h|*(+x|j>!~j%mw0~=2ipC%S%b=~; zzj~-AH}A&D`Fo4eL0vtV%l;wOoo60xYzvAh^EGmh&F4>17knZ8F+A?ST0QVt`?Gb2 zFWn;BPB9azX9aREf%itMt$`w~W-MxT*$m^t!|zY;h(8cyZu+jNPbmB{LCWQW5ufv; zVsO3!+Nc_+_S;=d2BA?T`eU~t*6f$P>Fg$|QiB8^n{;O>QL|th9%}jqyT-&K#^2Vp z{jpW7eL7r^t~{@lkule=_8Lr2*9Br}rfp3cDo@>hqz{3EizNC6#eE>9SVc=@R(IB0 zW_5C6qG-~haGXwqet@A=R$T{-F+g3<=aN5a)>;Y!(2&qp3 zl$%5z!0|O>A9+Q&S`fNe>%#V2P()T&m3?Q)KlJ~j>MMidincWy4Q_$p4#C|$5Zv8@ zySux)JB@pA4HjI3TL=!p-QDNpzWZusx+wlo4OR3$Yp?a$`pp~3%E$=NVZfA|JObob z#flpP%!qP1=Cg{*HyIfU#+I>dH$<`79Qm?&t6fh$vP1{^%IKJrm9nYZxiTOlvAv|I zk^ZOuyI=B1(^2iYTxKo8PPQxb$Nh@j*I@}@$nJi*LS+1aN&lk67A${eIji*3eJl-t zuWZoG+y9icO=Iz*3VV`;_=rrxW3WrppoL7-G%Y2Bz>34e6`Z5`F{Ddjc%!1+z;#fb zmz{p=;t{^V!_+$6G}a+9JSng&xZ;wUNf{n=@{wB#1rv9_Z^t9!i*K+`1moSz?JaN$ z;F&+2`e&iuc5g3{(n2Q4VhO8*ZL`uf0a^?VXUi5U(i_gyOeH4H*N zw6?3nt_Fh2n$O4PsN>$9ej4a1&p**Y0Tj}eR;+|=qfU)LPR#yQMqp>+lC5()I`va* zmbfi%5*J(Gga8_wV`{-jqcxZe0t6S8mgM5AZ5fpqoVp7ZP*T;|V7X$7%PVK604osH z60zz{<+mRt9U(5oGd$G!^gvK&{Xk5cmdOGPS#7?E)FcR1 zinTmG*}R|rS2f2f?db-*o;ZUoj6@Y4#_b|J*L2AbD*gyf0LbAUFE1ZopM2{~A{Cja zbN1&v{ZfY;(+pX0V866B!hX|wb^Q@VqK+QYU@bU)?a>elQ?9z?Qa!edaivX0gpMf& zBpeu}NdpTImsu9PKUB1+qDU4~u6(ZGOr)A}j9-&kCX~+o8<$Pu&xha?R0S18;*kSB zwl+Y?vpu_T>oXJiv3r#P%~-BK_?;)UZKHh*(X})hBa&ityS!<|)T^_9GoKpZq)9{Q z&7x^pm5XMW*#SSV3pb#75DobRsE7dIdDltI;z!GB!@*8uvL`kZprgqn*HBYKCg4UR zZL%0K9?SK6yWNMX%mktfzmY!n>ngw4#35yZ_2y#zl##?YmRO zr|)TDGmr`~?pyKW$9FtXM;QCM(_Xa326aZ=)}@ltj(zv5+k>LKBc?MDK(ay^qgNaM zFST+yUeAX~I3YANor&%V+r0a67FZe$0z21HJfnEuKV@T@uI306zvvi3+Q- zcZQ)f`M15!7gf3aEtYuWW&~3ZRKPvd3Sy!UP|8G8goW8yi!1 zchPW1F8K``9a&ghfhXVR$+7?$g=g3Rl8l9=-uV-ZmC6KC1aOs4+?W~i#43CokQ4kI zTLoYl4b#|&SEYb36aex8)wk}2UoCE*COS3X!edjN#EL2i&bN7ssG&zRoq%ywPT|0h z$|}SB1liMst#^^e0bu|fz|rjyQYp}{gppjOD>gJpVfb6=+O{N;Kdw2R3Hx*3w8k1v zGTF?<;|N9?>4g*0c(WME8rrKwE9Y5}&8HOD@#GvG>+9%Mx6#u&5g~rSi$v7%X(7w_ zwg@oj;CV#iLXgF|xjrrlNZ z%K=gpf93(E0V;1n??tX$wVerR^HkN^gMyXtlLJ9*q5CoSb3Zf9Z;-9+C zUfFHVU=Vo%MsYw|P_|kW9i?184-9;EEi1#rK=w00(@*6Iz5jic*m#-ZLS4o6W7?@a zpHaR&@jmx2bw6LX`mwxy8S+zN4O)ody*G->K9rNq<`X7naaju|qzjQ`5LtjdMT}OJ zYnIR>2J}1{keBM}CZU^SoB;tMp`$~jNUT0fZdp)GN#zAfl5zoM6^Fd7eRWDpdd}mm z2Mzv=k^WYg9AUeu`CYx9bGW$5pDmd`-~GgCq#)}E;=#I=N#$g}z*dcO)ueEd+vEGS zHV-pwW}}a%wHq!Me_JoNu^Ba)kM-?`1_t2D83DWi=+c1~$YAFeI>3_yDjVQCv@o#M z&F}Sg;am0l{n6`ne6a!%myv^$EYoSeYF@l_5`_and_YSk-EJbf^sJiqVT-=MdywKw zxHOKV?s?h9dq7lP3$I|EdGxQP@yM-8`4=CXX*s4<79BAR%zl6tKj*uHebV1}ahV{V zO-`|yA5?B|&%>#*{YQM2ZllA={d5x(!+ALsza0?TH*Da=;D)74}-M}c4(y9WH;90KC9_}ZEZRT?$+uTW_6 zWna&*wl}H{XUn?U9*X*?7FT}`v}q2nnrn#W#I_lbUm+AuVJ9G>l3Jq2D2mv_Xbd|K z((kARQ{+a>6&#koWM8i4>Kuu{yS9Ts9te^spn!IV4B$(KU_b)Dyl7)|*C}_Ou6P#U zHe$t-6A}y>mjEFZ&J{_{quea1@Vp>}G+`|nVeDIu2k?eC!q^a9U+npp>8sI1dg z-Sz)W=Il@9ZPfdY>8EWp9Ea+`l2jTjWFBcMaYkqzI@8Hh?6nf+50$YBj`zSQb5VAf5a zZ6Mi+L(9p4T)&;3m$auG1qCcH5-B+|=1w`I+ssb-yC z!nIRe`0xUPOWhmYs7MZ5J<^?x^9@u0Y|axj?1N@OA!O8vG@SY(nE(r;<%}g#3337j zkg&GDWj|a`0h=Kgbg`qD$U*7DMe6^A!b>&)VJ96r+ur~bKNc32Sy&;PMh`?V5XReg zj=&OFs<1?S?hfWelTActZF>=cKq6sK<_f@9Wj$aBUN2Epp`WNGH8wK%Vn2N1@^oS6 z(jLGz`lv^%x?3ur6`G?sSXRC@Czt~um;lWc(anj2BwyCp+NxPOg8>b|2mmoQR*y7M zM_;L2sTCh?s#Pv~Yf#b&yOtF#OD?r@@s9_qyT=2{q9|84tJP^5x z&4)6P!?t`n;(JkZ@xZR{8~^s7gM7!N-}Uk34oju z0MJ5OD7>;rzCa6;4WKVAErA?v9%|``ysciwz0KB{ONy)7OD5uogzBH87dSibt}YD8 zU-&W3>-jv&m5=hw6P=f`Lv(1$^VmJoCxm~cU{oyq07d+;UwXPNdw=!l4?_k>+Ko={ z`?%BhrF!3R@l!Bgf4u|ejXbPc^i&!MRORYW4k!4G;pRhE+b9J@`Ej|g=cts*dhVub zs8?y$1A(89*ZcZB;Ql?s6elp~Z#E}aNdnt?_whqTc6uH+_fhEZ=fS40#y31lzphri zE1jO+Z@Xr!a<`X`zMc!bx}J9f4^lKFXs3QfD^f&$JH_N5+6oVq&Zw*1;lUz|_NMww z3aFc#fK?iRUJarL5FaeB7O&wTg-xFl1RpY|0slcDQV{@K$*qd2Odox~IUnrt zqa~@jH>{%s@lw@7Pw#}`jK@btEX#$>c+*oq_7Q;J2pCtkA>w52!OKoKuprispmJNm zl?#55j*#Ql{ZF^Z^WCyyxIH;iKJ%h#Neoa3uSkyE(hbnFdR(iYWRjsW=%106Bc@;J zGPWpx)=2nu>a=|7Hb8Ezn<1`!oV3x79B{GIZPSDI!kQ^c=EzL|B6*>65vNU^ z#T<01nlLM)i89qH8{56~01QFMu)%{yhFZ;lcC+aVpcev&>HU&)J?*<5xxdRxmyhh{ z-$)ZH%yB&8++f+$7h5_ju{%dsKrf4TAQ z>z?M1SG$bq$74+0IG(olv9s*%VV?K<30v;)G(Ql+kV6ciHUW_WBNnfliT}k3n?AqY zLbd0aY5Z`b)9&auySCk2@3TxnUtW;#m>TkabP`P`-L7W^V|Kd-0|y6o8dqj{F4fRIky4< zrgV6AM?hKBpkPZL8*SIF9~sVF8dqu^r>Bj!QRp@CA0g;BB}8}#X8%$D1-t4y8Znl< zaHHH-5wGf+^_{8-GZMQ+deDM08rPt*$S7?2l*FGGL8=dDMKx1dw70^tka87_?QNzVU7+~TR)ZaWrbwFtve~iSq>*BFIY0mp znzmpEf_R~YBN|HMomHyrQIHFE1KSB#9QGmE}apTU zlv>fdYjHV)@RWfAOJI;0Vle~vE)AxK2u)zuG$-*g2z3R~SEVtvnFjUZ!c!9gVwpbF z=qpC}fa5Q_VX2PcH2S4wiN>i+=Skmw9~w-3%&1z3%(q-be`IB*zY|8>+b^Yh%*Cucf03+ykZw1 z>NweLk)N2HpHGzr^Ls`3XLR4E?eo{0;SIi5@Z9szJ}k}dLigM4-QC^#`nvD4-m1s$ zsK?E~n)|K>y+GLnYt3A;Q=aV&0fA#fS%+k7Q>q{3p&p$5dzn#duPxYF3jKE-bzjgY%Pqaq{9&=a$ zmaw9s)w$VOR%Ygl#=O_6cKqL}?3|ncGPSq2$AhC8i^nnf0iQ8(zs5{{l-qkxy$h=X zh8^^UerdqF8PXyRAJ)9~#fQZ4F0ZWYh%XH0(bv9UW@(8hR^Vfg4(BxVw2%*&u9r(A zHz~@m;tRaNH`f4pXjJ~U)(ySJ&f{71cbWidee=TT7M4YW>K1jqA-n^~iD?Qp%~M^%|6;kPV)!VE z31Tfc-o8gH2S+LbwYDtpw7-|7Rij6T+(aGPoiuH$KipLOu+105zf@emslx~uK!SP= ze0@9jJpuSCM}F9-UXgl70}PM`qGX$`b|h%i$iWc}ODBK@-c?s0Gk&GbXVTf*%L|;9 z)wpB>yx)ZNA0Lv3-t^X2x&BZ_{PK6t_}uGxDfbuK_Sy5rT3*w}V=A$p-=G=*SvA`J zEH#_ty(ap=?$D0ECJGn_O44s2<3y7L;uH_~dn(?Rvpc$O{BhAK*9v>|~2AU0U_m@tIJax6y zc}#h)Hv$3lp@2@*pkKSqdIPB@B&mvKR9;|G2`dA|AS;DIBRVzy5JWBaaW4ZXnQ&svpG3b3 zu!`{u1_XqOeDK0HoI%ulYwin#3fvAy*ZS%^MUMK}-N{dy8!)}V!v_2M`ew?COXEfl z0+p5o4Tq5MhwV3-UGtMFU@_S>e~Bt*mT9iJIqU0TlkJM~sO)E`FAKM-v_F8+8nCIw z`|YHWhx@ne`tQ~XkPF+G+4v*1_>8*wg9(z2Q0=g~c+rhQ8OB~ZL=VRtV!nor$@H~a2R zqP|Z}2yk`pzMNeO`9<2lw_dB{J)Utathd^&wF^BJ3GsfNasVFnfAzqaj6=9lJoeDi z+WIFDAb#GqpZiGkOUevv&$x}RX(Wy1RMB@G`O2{@&1xjX$LHC^S<(D|9ql;XO?<_Vb{ zcctLip7;6(;8$%h9oveP(Ovu)(~&w4FJC(&nvTsJpdMMcD@B?00$oSV&X1lS5U21{3ch!cUY zU#GM3nffl!EO4J13Az=X60`)yd6v9MFcEg0+JOEY*pPF4{7qZiMR&~fdQD)h+17ay zA0Iyyt=AwS!e)i@i`a^v)qM?+E{|>Ve6iX8<_26dwXIuGKY>j*2Q&RG?-Sm^;u{Ns zdHS6%^a{t^cSHjlK8y#yCK>c!g(V~wBm}P#|MBD=4?fM053hT7EA~RkgUvQePH#hX zn~*%@!p;@mw*z{!Y_AaZpI|0d7~7laRBKZR@|?O79(z&!0HJ=az{bmv`C0dV9?{d| z@AAXOVd8Eq|Cc|;3+q1DKkXh@()GL!*UtUi-QDlK*ROMV7G3{)7Jy2CcRg0h66e4r>{zE5$=@yeN#dItst@TELm;kuOP zioJL_7fP5nsk3IT0)?qUty25jw`;Ls^uo3RQjRo(7zm1Dl0uu$AK{?;5+lwb*yWO) zQAmj5SDJGqDS)fJZ_`0nSJ(9_o>y&_aDT4qAXij%t$0Pu7iMp`r{nIATkEe;t-9&6!lh=t@lTh21g)$4B~t3zZamZ#mB*!c3r#X zmzzsbj*X2KHPKQpP-K>4BZ}X5;?W(Y};{E%k!|c7jK9zE9o`6pXd4rx?Hs3Zxb!Tqcm|o_x)^E}P@#*Wgji*n> zRc7P-{s3#xHWl-G+%jWP#>eCt?%mI8sOh2GXYtC_X-HXO z0(Ke^yDgh_=m|%9*?u#bU_6|hDL@><$1Ze%a_)UUku$&7NbD%&ztCn@W#>!)!uJ)h z5HMtdfJ+@4fv`!wQW_H66+(yn5^z1sK&^fJ=q0zK}4pvL=m~0J&`u-vO9Gy9St?fE`3R@-oAb z!$-tEH;Hj^alrhn-aQWN)avc+ZOaLgA0v2g!h*u2w1AdlP{ z?(mI%5|=JzvmmFt{vnqw<~R58<+J7`PP@X``#j9QB56M+nqT!Y{rp>Efoj4R!OP3r zjzWmnk`q-0PqH7auMGKsF_S*kSgJ+8=YV2m77DbidwXWXj)gPS=JeVc`)!P%p$ui( zyea3{mgXkTmL^G>=)tX?o*o&d&K=KO+Z7SGId)(>*YJF5ytnpi&-vui@-iMAG_CP> z`tByRDvOVa0u~lMv$5Q6FhPbM3S^0Ron*^(#}F>A1GxshV%VbBNyNkgd$!{P;RWGK z=O}}wpOYj@Z9Og5D0v8IO4GQE{gFgS=EEnUmzf6bT~e)w8aOneF&iaO52s#JDBJ0b z5n+P?fGBSY6$PcehOPuDRK%~72iRcgAdX#W^wXlfN>w7Uak6+wGVN+6PcvZeR;&plH5-()ZYS`I$f88hpuXw3*{57BG z`DLRAZ{JXb8p6-~NNt>V#h)@Z(z4Vngx$kQ2J$0(5-)K$!I5?TfKE`R9IiJa-hCN{ zFA^_=(qljE(KSD=W#aIk*HVLNn@zLj4B3Js{aBPJ`Jw7E6Pt!K;jsWGJOA&+>BZ^k zzhnN&(%sc2GBSvt=UC|GcT=@eubhW6)OMqgc^_rSU;{RIyu6b;Y&beTn^06ysK0_} zP+u?mLM!p(LZ)4iC|Be3*s8`9JYl6?~QMurG@wBouAD0`3j?>_m7M z6g>=@-eX%?VJoqQw41=K51JR#wO3y&19zE8a!4xiir)*1V;sBMBXnt&PD*l#2?=d& zY;O8DoZECLFj$}hXJ(XyV7f|5Obhc57YghFO!)q6t!3Tom@-|*X^f%eWn07V_u}IB z*( zTUuJo7PG}B>(*ZYC7!&HzE8S$H3Fghk3>rUZ8@O6^RQcY&|U;L=K5TX z0G+1~hB^bC+A;2*+&sh1$Crj_q%7wtLig3nT_%6eiZ*9L1ooAm&pi|C_h&Pp)lE;3 z;BNLTk!^VCW3MpiEa6I}?32nl$?^d=UqGxMB?o#0Xw~EO*4f$i;ch&02qGtKcPvec zhN<&J`KQ4*2pQ=TOKr}qdPGjZ&@hY>J!mvy!kYf?@q~p8bl}#Jf)GjlI9FC^td3pG z#lbOX#PVKmyP_ffV;9^(7D0+C0p${;QY>Gs6IVkCCv&n98u)d3*`XEw6xT%0TyLX& zYh3~=bbfR2z25mRSwFkeaL9}k^1cw0OAA>NyM{zm+mjlf*lT-pdal3gI`(kB?W3p z3(&Z9cW>ma%+4msmt8-0)P7blq4n0CsPjCNHJiGb>Z2(z1P;RE$?)pb`*oXJPe$(b z{xmQGgiTy4I>o`9PGgGbxUae9?)zTj=hYu@Ap+|@FA|0B?Vg|Y*KV2eye|i_BR{p1 z>HKRg|BF9pIec>bV*cw!ZU5WjpVY01pH1gE@w(}-b<$_N++{T_U_)nNmg6l;32Q0+ z=Y~?XH+AJ1F6qohTmQfW)5iuoN^XlHmcZ$$u7CjO#pVVdFl^Pz&Oh&x zOMtQu&h@+P)|P)*1E%8?Pc|3Gm-rjWw5rVh5s|}s+6r~{s zJ~icg9#^;gTgdeMbp;q9@KIlVYE%MBH}&6p+xBwwb^SMofIbGOF4Y^4lkR)oqW^Dc z|J=R$svfuGC>W>0{7v<(CwJ|CwE$zPGEYFES7w{)%hgh1=`HE=8dG-EGx8k&W=?hbYs zY+q4Poy!2spZof=O*F5K`^~RgjZ*^mC(cv40Pg@W7Q}?O5P^;;J+8X_%qN8cX|f2U z02yJ3BTkJ;MmFq7Fr28&8wdE)71h~ZdF@J4uGIr~FV@T3sa<0Cf3$psyPWd51h27}{q5)f$zE1ob?(1?gi1bWKZy4+mQ59_C^ccVzw z$MPJB9`dxaxG7Y#axa|lvwhp$K~rxgKI9E~fg?2f86HJP$*8(El#eaJp5bArwW81O z9eMe8jGQKb27 zM-zLkNbLgbi^?R@)9)H+s@TnBX6b3aY6Xh6z<5PB)qM5n6zP8apEeA3I$5kp!Eb1i z#z>kyC=k}VTbN=|%EZ^-szrPahLLU)A{jQSpR)IU@TA=X1 z5AVOH*bG^a+1hn=`z0e)FSD@^mvcHhB?`PW``xUicI)OhQr5MkOmg3w*18!j+wPzW z4QFizdnIu=J>39Lg{fR&Y<5vCYP;X|P;6KJ()`*Q%+A##6Yh|GZI{;{Ce)G|*vaU8 zEkgiB<#RvlxEiHnJ9ObEVp?q8=0NRh+gPV#)iR+IaW^V7)-fe#|wsR-xH}f;I?+Ct95aShgdOrr_;|J;e3{)7((O*#c zTC1Hz+i?OT&i#j@h%VHRP$s(W>t6*3Ly~|oFIK{}Oen~6nlr)Kptv$c`+$X_azyVV z!@JK%e`?G9u5dVs`@5n&ShC!)gKxoNi-WLT zepm_}IQ$pnq%~^rS(`Y*-+tT?-#3`Kh@YK>v(?R-xp8g=mXJI=7QImxw*NhFOPh0`+ERjGq&U7a9#fo zVfxv1JEvBuJ`X+de?KzBaJhx(>XrT9-kPzC0}tv;t-^69-~j|Kxe=ZKIiop7Je-Ub zSg>=snYs#_&7^?q<`Nej*2x^x#|C=Uqv^4S(LE`x>)$nr@5lASZkm6vYuYPPum={) z_|H{VTHf8ZhnNnZ+Vt^jj?L?g-F}+O2m7l5mMjD2*5XEI2M0w6AYte{cB)lXF{;QQbazX z4Y@$48(VOZVU$mL9OowHtNel~QmFlj;X$e{ds8ii<-b4JozElpSJ@F=4gTQg?QC=FE~Sn**0h(Eztj2wI}# zfc|GRIOd$tZDBtiEDk=VWEXlo58=vlySMc?k8j>aOHP+P_R_S&+hV5>S+&-Vyy5eO z?I3yr$NDQ?6TjFv3NQ8>i-&3y^pJ9>cv6KgXks4*kqXg~+`n1}H{y@T$7_t zSZq&&<%x)8UYG4O-HYq|)h6vadgzW=Z0$!q)iG;(qUe^c$sYy!HM_wLFxu|$3`{uj z1cp$MqjMeGde?bQ+trMObL7|;UsA^R**fw@avoI%&q8|!^mVMnujZV1z0D#4a_08< zJ-_ANf!6!N2i39^WdaC+$=0Qw&K5R+hGZ5ijdh3ZX361-ifc4kqFrg`(rddS7W90m z7~6NGFWYR1-@e|^yuBd*z`f6KDr4Fv5M>`jb+wU&yTDP3nX=VhfS;BC2_i4e2R)dJ zNEQ@B_He5xTY|-7QdE_t#E}A&qi`U;%c`O&i)@2clfH-oDLDIYu&F6Qj=GX!G0Dma zNrzx%X=y1%5$U0bFQ99U-%ZIY5MN@76W)5*Yt*)OA|z?cQ<9_~qpk3`Tx?xTM7@-S zS&R%yVh`}lv(Z_$c%_jADWEi@;Yo4KOV$!GM3}cgn3%@0w422Ip~_)|iVlP!LZRz%dK!#c(QDrfB-2$diBW% zEk&ZuCO&Q~F)EEJ*{s%F-bQrvNxPkWgI>i{!YKpts8T*=bMJ>Tz~^HOR?#5>Ljobg z{9kC9gOn*CN+WVk9dljWKTdJP=7AVfmHP}sep?7hdAoSD{;;;4x#cg|x>fp_a4HDI z8jsLUC_@{&cziGak!hV40vq)Cs*pKF9(hMi*Vnf)89xlI+=a{pS}H2nSb~5`0yI~h zR%2SeS@0xj?EmC2wl#@nFW6yTMkXPxq>mlVF{E&lL;WdLIZ4v0^e&ya<2D&UhiwR> zG=!EtAG$nXe=AQ~cOY2&f3Q41bEmU&+)|zT*)o?9*hC24nkylPZT zC!qS!!z^OX^{_;S1_uKEVl+^^J@}JHpdkY#DOg!q3oVy>dIHcy)H_Wk+tv%RY`t#4 zb$8l!L&!UD_ZJ7(^#Bg*!i(JVe(X;a=gMP`qkalY9U&n11(l3z>*>SHuwzL7wc?bc z5z+*KB`RL9{$tLJBg=3BVBF~VM1rD0%8hw+cu_T&wr%3X7klUGMvE&%pnWpa8=-YW zCR5K(=;tUkg;?)m2xqkU z%URk&?BJ)hJ7VzC&o*xtqRHM&rPt_ag^4;I0Emm5$l_ASu!(WD_?M;V#MbRG80h~j zeD6s(|KV*BFidA33IKOnEXeI7<8_0_jAi%57+b%E0;j*v#lr8-S$`EEF8p5?Ixi0* zL#xanTkmccoisLT{cfZA-Yqw0vv`8EbO8uXxG$Kt99dbKhLU`U zr&gVg#T3?aeKRGpp3r38j+=Rs(z=rz&X8){_81T6i1EDDk zOVRL}sk=sU7aS?hp~w*T8nx zCmd#L^yoABAJyYrYPNq#mGVpr=OB2{Y6?V!E~+8 zg?BW;DEr!H-7JQCAvGw-Bnl)+%DpWu4Nn7tq&pm!btV|Dqkp%Mq@>f$bcV?S(U=P6 zp@y-SLz4$Ajm-2uHRA-zP(xOJH$ia9zAKi*5Kb(N644XHF6mW(iG9{l({3V@e-tR5 zhYqyF8;Z5fmgO1=Tl65cVKt2TJelDe8UJ#uliDJsE5{s>UM3$c z^tl~ZA)X7_t^jEXzP+Ks<&wd}e1Rkx>HS>eYA4Iuqw)^*`VRTs#meM+_X4vdoPtwn zCIs6r-0e^u!OU?6{kBhkpHWT@4-Tw!e$(rWWbQZ+@bU4xiLyb}4`H4CtvCKa+<2`u z5fcVg-%q6nt;vp))KIq-w7?z5-~Ns}!91LyGvgX+X!YSK;FJIayD1j&f zJt9%`-%#Aq@X%v+?(IHxE%BPB@IA10>aTBcp_zKhM4i=${BbXTIxM&hcbvaGGviO) zW5tQdf>6utoB3I3Hk8lil~s4(XHX9|opZB5O{ZCCY�cK->B839lPc50oj?2{@H* zO7Zq?empdQ_}Tg4!f+#ZX?^`{ML(!FztoaWy$WD4h&doNFuLjWDuIci}>Nm;?si}v89yX zs9hCdAI(OSZ!F=a+mr#5tDvMF=MpOlP8p7}#4e-31`np^#hI3p{A{dO zmUY-MC@?=kWC7WqIrmtSl6yf?8jZx(a6bbJlKV?B1^U<2nj%S7hj(GIbh1H3$2a-k ze@kC%)Du~kxOK--5wfi~WG@VIhXQ$oy9msivb_{koP@Gxek`h8D!c9?<)> zu2hyWpGg{`njjj5NmG&mOAS*}tocRX?_YbqEt}!a@v$eX#plACZG`Sa-O`Fri`zY8 zvvtX$ON4!n-b8jaEEq8@%4d3M>Cj)nPfZ+k$`NYLGo_-e5JO*&F!BsL;~eA$vTvZ* z|FbH*vrw?lj~a$P+vGTZ{ESKfa@a=Z>cE(%TxkXrC9oepFpRZ79aS=n&AR^EJ_B^+ zU0r@QHsg-jsx2&(PH@< z?L7|TLA1?KiW)0XgoA4bV<Jk(fZ+giN6~bYW^!0P z`r5l1eF(FGRn7-}Nsde7+MiHgC89t08@a<~9ZIsWK^ED4SM-+}{z#U5VArl4>r&pn zeRHO_+(^+dHVYf1zD9i5wh@vgxx~bUMdUhxye4rsevivdUivgx^2hKaTRB%PKd0R9 z`9b~nC$76YqO()qN1wQ}d1xq-)a-Xu-tEP^tPPvio7r$;KW;qPDox&vA|5F9+JFM& z^Tqn@s|CHc0k)qmY#>Tf%2B7%ZX9&-UrF4*R7c=wu;5}c-t(LI0}E7*_4LwHXc-ij zZ9Eyt_Y_QHXsE>paPNI{M0YR|!YpY@^D*hhin<`FQ-A-usLmR|DJCIchJR`fdG0<9l0;lF2Hnz+7{pA?JZYjtTY|#^(Hj9D z&}y$uImAH&16Pxb3fm__6M!R)fbo}@S&UMG6tlbmM?>kS*CowQ)(?#q&`%i^)UOP&K-F<|2o_qV;gu6+|1@u=8Z&lj8Vss%K79*$@|m_UJBOT702Hnp%@Z0!a~KAY19tA1zaGP5}I>MhBw zY#heeP+s8kx!N%{9i`ZWA{CMaMgJEC%$HFqtFHeDS4bNTJ6CVFI^ek&Dog`lCq*Z! zGFV0y}Wyy?$R|Lw*$06s&r_-q1@coWoyl`--_H=!=fo&uGKHbZ%K%^*vQDI zRA_eLD*>gX1d$otc9t=p;!uyiAn1`t(PSX^z@;(tG7m4pM{v(-HF-$N{DN)jjyOZd zf!!J-#yyT`Vf;4l{4g^V{ETvFy$UsKvUc>f%6NCvoJh+CndngFq(ys!nVXEUj})H? zI+1&_@V29~=z$fSKKxPMf!hBEkzo6Cz5QY6bsh>^C4kUvb2oC6#8@k6(Weo)xKx20 z1lcFj9#LSxu5f>2SPEgNEbP|qvV@+th1%Y`&Nps`e*47l%C;RMA3mQyzwJ$&`#GKq zYOsn)qkoWw83BPN;kx1uYspG>vNe#x1|(BtBTDX)yPQ6dhTIg>(xk?)kzGYEL^^ID zkK(EXTw#Kw{2*w^OSwstCwH#eBq?mPgbOeOpMRQX3oDjrrba}xZhT2bhhq7HVN4(z z(|i7{9CKe=EEfh79liuq`iLx2^7~&7^@8)ZTr80FuRJ=-II32eZSA*aCUufrGHXMo z+@+={yp88ljA5K+Do&;}%TA^&8skU_v%ShxM>Pb8fFS+oMCCXsEZYNEQI}+wg?`7d zfZFZS;yWlDCOrY;2vQDuvZ5;O#2uwE3JpYwCEfye;EO;*Qfw-^)ReR9T2%)l87y_@ z%Vxhl(kPF+K)Q2{C7v-7w46gpG1=!5z#C9%YL@)9*MeXg1h0&slW0FrZ|N09K_ecO z%GV%Y;4jCMX||KWw-k3h?%E8WHm>qP(Np!-p<}q#>Q7JtePyP@O)25u;w^{y?(vfj zUS&2eku(h$I4ZuTr*9uY+@7*hjH!sQ%<_G|Gk(X|C;Jh4Z)E zY%G%%F3v%ke6A!up`=TdrV+M{S!jR#;K)pu0r&6eR*K|fxf^p5sRdba5n3#J3)wQ2 z+~j?*Fc^iJltP#Vb`z@%$MauTORuQ?X<{EcBam(Ks5~Vz{y3M1ao491%oE?lULJ^R zMxV{s#mW(Dc%4c|JnlH+`42K)S~bu$xqDv_NplU~_tlzvX?NOaZkuof$eCB#+o*3U zbD)sXvFDCLHTz*lgvSo!{paUrZ|`_lHwNo(t4COf1&Vb>i$K(Dvu%;|A602nR@|YC z4SohRI81=qtLNrbJ+Oe||MA`P5GPC!i zsQ!*>q5E!VO@YAXo4w%mO8p&__!_W0m?{3y+EgE}Iy%E(rc&=~v~er{1gbdZ4?Ju= z?mt3cyQzls_na|}FOf&w0Q_s2IgqPmccD#|EaVBruK?a#?KaG@k05!C`WyNQp{dn* z30TYqWBp0!C2yog>KT=uABA|Z^nM_3Wo>PBwd1>OCKW$rXaxqL?8Fv9E*1BJ%N)OF zKSR2R#+F@#qc}y#1>%p;eVTwrLk?*GYZ9IPXfS}IA}vLVvoB2zBNZccD5W4t8X*jy z$+ROdl`5ju8(^5BPI7R*lum=YuZY%1hh@$tNmJ0%`Z<(js2Gh>fts!iLk)UK#XOZr zW>+dcf`1cu&xNR9@}BH=*ktAq_lLjfm55VNJsfh<@Ffw>)Vuo!9&y|7q#?)LaWz>p z?Ox>+=u)IFDDcuWyBg=o$`~=u`YqR$WsxZtA;iI|td+DzG3ord(4_o76+w!>_5lfp z)Z7@SGJu$|s5vb>)uyBGgHloyN1dZYylS??$drtr9}v^Qd0x31yeK4xksUdxVIn1X zE-4Zm~$k{`ILV!np8OulM3udDQD-^1)%qglgV?i?a`*ZJ2F z-0@>XAC*P>|e~aj#CzLGz7^7w zHGj!W(eTCr$$ekG7ZkWkad$1&=k#`UA{BOa7Cry!wPDrWXs}?PnYvCGrIcf<%Ga$k zt`~zO%afz6CHdm&iX3D8D8hmV|2erxul}MQ)&Kh^1a>H^f-is&n4vabG5^ToN~`zY z^(kH>O6~(_2)pTn^W3e`v76u1?j+PUQkEd1mS6@grp1}@?l-*olTU5-%hb(h+}-KD zt-ymDiHiVRX(|UQaQfPI=v?xtL7))~5EDOIT7)hKKKi}1U_~+N*UvU1>JmoF^@H+L z#?72-_9;ihKoZfT%!N%dcjP`{IaYFc~@N|)n{hHY7`!k{CHLbdcO~1%)E=Lzuu7uU09gwp6#aAc7Jx0JU{g)sMT9)*LmE#07pkDdD+&u z$L9#Sf^VmrOn8DFQc%6Bzh~pldWgg(3x-`+Jhvek-H2+&-o-`l8ff=wsxc zfe6G_g8(BE=2DiL2$OmP#Dy88qHK*CRi4NaojV!TiYI7?*_QGY}1J%rQKix~kbaSTRMr`}QJ9*^i@ zFSVrHREDdu^y`<~qGAYov%qDMGtS+AO1%Q9j4EJgPz_R(4P`P7I#HJwhZq&pT&*Rh z{t1*Wm#*RNt*!a6jfb6EmKDatRh~4H&`5hJC7c-KphIr(=&cS-SwMkFBez|%%^WB4 z87uBXi9cAae7vL3K>jn_=irr?b5gU;}7B#C(EJM7+n&0!z zcNF7?#=TSE3T#y`udB;}(B982YBRCa- zq7oY5WmCzv18xl5#)e7~JmEifv*2$k%cjB^u3?J{twCc3+LC#)NACMYQO@qiho+x%a1f_4QpU?+x2?>NOF0`%E^fpBXw;y zS(eq*kj(V|T7b`8H!tRzkaU?-3!A1hfvtmG9G8@K54@`(rK2DqdO8cm+-+R8EEf(CJ&&q8b7AYX`(C0twC zBcR4*A?~;=Zv3d%$+YlunZA_lvPt?tWZFJ)ay5 z{uu6|ho+y1QkWfZib}z<`COi&vx(k%zp&(oUS779{cv%&*j%YCLOny_rZ2ZGmD0po) zAIux_hTY^B-L4;f=}f{oM20o!s2I+w4-Nw7RbacXW4k=?Cx< z#bwAu_mt?|&S8BEN)5s)ofOIve3H-~l?5|hW;laqkO8^-XdNEgBDVivJSi0Ai+o-p z6IR*I%S{Pdgq7|rXPKI@>l^}X?=&r_EH`O}6B&fA`jzdz~;!}(Xkiv|BC4`!0R+^PT6F$NSfOr|V4&)DU-i$AJ65m0g_?a6<=GQ@!D-~N1s zfPh4z5u9j@G@Uyk+cscKpQirBZM*acnh-A3#X{iQH#l zXqnyBovA*a>56YaSp@HNh?p6b&UZg@(9iA8`&F1WTDa-7yB9m$LQh|isooxZZkbka zhmz;){)IWG+83)Tg^PyW>Sv!uR4%}=0kncV$}I!Gbp(C4iaI+tkZ}#bfVf6)@$}@s z4>-ETR#m4@25o?nj6PAGnj=kq^B?V@@1jXixdzHU_uw~v1Rs}M7VYgF%fAOUs4;dm z>$_zk;zc<<^vD-Bruj;6ce#0De0=>2MqA)a#Vytu98Phea0~KF@|l>BpRkFq%i{G2 zLcR zyL55+@t+^MKL7p4$CrQ43q~$=ypRhWxnDF2XI6ypzk-H4KTZHvr)Y0WcXxM1H9cGi zf?+>SO78Ne$lv4U-}}1(jgQwkyo(CU+;4BA4};Amx)6hIi)KjLpoTD_`-FovpxnMK zYA1Oas(v}jd3!X7a_^~Q{Lc#zyX%=vGpgYv*-5GH3|6OplAO(~O~@VOqi`0QT*MUX zAF-9Y#c-% zQ}YwZJowF3#`W~f^{vSGjXtMJh-5W!n0xK3eqK?scSsSL9Iwjs9FY_dkT-6~toYph zFrb#aAeeP~JN99F6a9}!SK+Tk3R+q*$cLYaNO*#VCnGNGX-P@+cnJ8#Wj5)jy!~`I z-;cj#j~<@qGttWDax__}|0sTG`!(K0lT`~H2ZE8M!iLevO_4mepT^84M))YG1REhq z5nl_X<(fIzMm>Qv;YFQ{6x!FM_s9I33Ps4k4J#YH3|*o2S{tur-ceh;3}@Pyb+q83 zavRTFz!!RtXz2)-@h`QOHjFsur>EOfty1Y#C3R^jDcDWB$7=%99z?xVRaz-&Nt8Z4Hn9o{+aL?0xMS=K2SOY#~k@=rDAiOBI8 znrB=HpgAWh{!}^O7|!}}ZfR!+*dwEcc8jeJt{*Kq5dtFs=VacO(zltD>STFpD9Q-M zLJH)9UOVTCQklwpGldv@9L+gQy>eU~+!B-qqsx_}aMU7FMI*}KM!x7U)}-F5Tg^HQ z804CnGPlWjNn}B~AZT_mNAm&IyQtCm(eOUI(>wF02l`JOonbr`8>Dn^_k{iDxQX_dJg%u3e9+hBS6Bx4cEYotw-+bf zR8zv5QWBLGE4l?Xqdk$r+y8Y1I66NqzVqnc6TA$sPPln|7Wg-Hrw4d)fTzUjPgvl3 zvPuP74vg5nv)_mOl-MRwa&)4dy+vCka8QtaTuPtp!UWi|h(A-ezrJM@MG(@W#mA}0 z4)fk)j)gHUV*)GAs|=#2CWS$+M4RGZb;?Dz^WS>3OL>O8DjFX}WuWNaEk!AdZZu3K z>KG@XAcLW&Pi-YEl^Ds+En!KWPBYc=htYI&_=|@ctCU~s0#Dpi z6wBfkmTe#Bwty%;n{jYx(#$3Qu$$77Rh6Jvn~EWtf09}|$AmE|tWW0Ug#o%ff{nq-G8Jq9y|TT~F? z-nTdSV^PGMRt=7FzDlF(c{0*WuET;}zX_uB-O{R0Ia1>l2mgjhJu<6K=&D_3bp!tQ zLC^p_#($r^{hiHZ!E`B58LaqYf$I7yJ{(mqMwhHu!ogxHo)=ejs?PI4BjRJ@*r-BS zMh1?aeAd6a9Y6M~X~dMSi{o9EJ8YJ7rCV2HW!$&Fl30m&IyuIxCo{Ol@{j=7MdurB zsOdyHqyz8w#KH8BxO}|+us^HW9FYXt=h>yg6I^$X-h6$Yi+&1nQ9>g}BaG|iHx94( zPC9fxPS!~G&)}TCX>9xxaq-_o%19&wv1BQ#aSi$6i&_+TzWhs&-~OD5JusV7XRqh$ zu4CPa5Jxp&Lk6D?xM{CdjUj#Y${*hTp>8iZz2uPY=DZoaEa!AHZtgkwh*Y)X7woeZ zlD_%kz>aGYM@ecdx`8rn)M+7MM1+L9(cyh$pLTn15yGJ5s7DgBCCVs46EC86Qigz9 zD!bUKKQ&?IC(3IfHz0s88N0+28fsLSMF{Pc@Rv!-uN#_T5xi%L@0|GKw_c;NRw=i92b+yzsr@|K!M z3I1l3#NUDDH24LFh(RS%MGoA@ z@^*=ZC#{(J*(w(26hf=0bC`>&v;v69VO`Z`D0J{AH|t7 zhMO81v{Ud=!i!Ygh08-NZEg43QYH`T3;2FW^CAwv|A&fbI^{ow?YdljM)L4a%-+bI zzJd(78}lhb$a<+!=!n3DnqQOE*xca2>o>-g73Q^puwdCXq_24zxot;`NBVTM{9lpa zvf$4|NAUJiDe*?@%|17o$~ur-_<0B)p1u0L4hi3PD$gX|Y|JLU_y@>%@LJ^fP4eCU z_6fM>0aMI;JF|ekPlO3W z&tad&whO|w^T(dGHCu*X-uj*THk;m~9jzO0^%e#w!M;hM<1IxJmjoL>di`KNB`OZX83W`>DKl@MXtd=h^^A^i``{91myWw z=x)2(V0Ul-JD9tf(9dy?)uD*O|CIP5BL*>Td{H7naL4|^|AHeYh){|X2uA=iP=KJ; zGUHm$qp3UyI7ww;1-M>^O``^YXi%=fIcu(C-oI-aE83OcB7*8Rbf2T?SKGHHQE&XW zU2j;NTRR{B_4qji{Cn#aFW`QnDGAo&vJ9l__C`inf*wJ=pOt|e-oz$W4&_ZIez*@`|<3tUQq-gLuz^99p33hrJSKoi%!1swOe{Ywx z{gUQwe)AS5FgP?M{f#rQ^$Du++vWrB%cKaDLz~<3uE#nG=_~lCH^fA8*-!$~amr%#Y6}iB@-NbJ{bQnq*hTT_(9Fg&vMf-wpNo1hPI~E( znd&j!ir3KH_dJNnQ6u}=+dkwExQU^K!pnNCNUNpr#bVl|HiVPWtE9jQNRSZDjwiX+ z$(cl}Si>0{oCKyc(zXA}F;mUAx3zo%lY=yEgf=}C?e2e>@mcMi9U>&b{S`t5rH_Ar zK5*s}HI7$=kAWoAdw!w`!wk&QOoUUTVZsvFc#E~tL;Hdj!fM&9J%~4Xox(K;5*^ye zo=Kwnahmy%+t`%#*sc%}alPIir_B?~rB0?LgA0*N4FrRuD1#9Q#((`}q0gd_m2}S< zHz2TKx3c*gQpML{6Q-}CdLcK@0+e4bINik6R&ZtWpDKM_*Q@*|mHEL`57?J&;HZq!@ZSR^-(XQtb;#gQ+?D~>c zE$ZbsIqtN^O+B&qSu9l{q4L`Hj~@P* zU})}nbCBzi+MCa29z$RC-$@f#f&$s)O_bSEW5?NXY*^C5#eR}T=UnCl0idz68h)uZ78o* zuQL{$!^5wW$44p8QWJt6b=uwsCFYl}GuQ9GJ>w?I1K?W49@26?`yU)81UxWYPVa7f zLe)FE_<>EE0|T0B=tt?qY3iZRzO=K&L$KzY$OC0{_Hg zR?ZerA4fwIyvTSmB2rRP68yB(Dm?DM&{9DIx?Xi)+Am*-MTg;dmPOG?8^bn0DT}6j zIxsfEthzj2=UO*T8L5jCv07CygV(KHfK8_oI}Za21E&(qqsMXPL(uZn?9*KiR6xV2yvpX&9#ccgzpb^WUf&lB8&SSu@Gi)0skWh}Cu zZ!Sk9VrnT%sH7jce*XQzl_Qn^<9<0}AojGlx+p`fFsH07+b%ktNxr#RRAu8JWn?V? zQ_9mk`|mGh=i$+yn`9`WM?{o6ed~m3DqgmH&^B|%mxx%gBh(Ue_gq`@$_}WsMe{6dpR`e-T?rURg%&q;Km(tN8Q9S_vs&l zrxc4gGzf6_zG`Is0`ux;j6O9n$t<6hgVNibTB;or1>@J5latdUFLl)#FJ7kM#aPJ) zMYJ5Cge64SY*XENg_?KOVSL#iy3%z?{Y}WwE6Y;v4vpn{G|OGli(7#|1|I^bvug~+Yd7*>hc`PX=ly`ED{b5y=v~c0yuJ^AdwZcd z?(gmZfI4kdo4RZGzkg1%@>h>NC&T9NFn;?xNsk-8cR>{|&2{^74%q>|1}vLG&M%Yn zm|@0BY>x*_;pIF%*`9J;MQomHqr<;v@-3+&ETnwsRA)^jJ;{=?gSVi7^wy6nkN=Qj z@9rcas7Q=UF^#8mqCFb~_l+8E<93_%g2khKm=YT{#hn^EWezQC-4gC%$ z@urwccYMw9dA>W>nKUjx4J2v`wEO)JD;=ab-IOI4L`_2@EiL_DDdZLj+bgrcbr5mH znv;4#CdS_Zps3T+(=NLlE7zd|)HsnK*2KwRG>5&+S+7jwF+eMUM|(ie|W(8wTU=@z%|RB;QFx<$TC@I7^ID?V2+RlQh3a zENJ4E(?de{2$s+xiSP;uxiWrvnS@J-f#f?69MCXyaIHy&I!+RB(^Xf|ET~=mifsH< z$E*gOCve%i)~)&%5<|(~D>a=uy09xOY8g7Gs#QAlH)QlMuEiIND&IN~RfW;v(LnfV zywo)a#xZN9i^+GNHf`nzulJWXR03+%PR>tnL*hViL6toySC76}1NAN(-4%`2(&we? zcjA+a*(wNHk(y$<0(4t5j_t7^NMy|Aac4G^q*P5TQM$XJhzN10|Jcn_>#{q=NRoH2 zcySyU%6eo@_Qp>=ed&$PZ~O~l23IP zPRx>KTa>ki)vawKGd;(_{L1e<^~5F7lA?~AJ3f~1_GzyZ#)F$M5pmv07Hde(v*)OD zXRGJ#!AhZym1iL~u|?~yQGEYd>@B;)!*0!J?Z0Cff@o}OYYX_r7rk*7K|{w6A$L6* zQ2NTK0ZYCQ*H72$*14yMiK?p_i1o;r+)A0tGk>P@f@0o_wZ^JnA6VY6C_sM+yZ-qR zb`CIvG?KPIK=UM6PUJ1y0>Jb7?8E<>R)E%rPecSH%}DG)_XF)}k&0M9upp{l*Ixw#T=B`u@Pf@}ke6>+oo6 z50;AM@N)05%L-NgE9$MZ_m7F@t!flmUW$X~?LGXKXROY*lo`vNu(r~?S?5g_$amhT*6XO0TuN}Gyvj0+W>VvhIJ#ozn1@P z718zGv+%byks?{P15Wb&`TFw%=H>^Dt%7cLfq*VhTd0CK2Goh8UCo?er)fh{0u~gg z5)0HXJ5xEU^(%J|r6Zz>z*n{;`p>W5lFfj~j{Y08h)i_kPU*6>CN~^h=_f-R@)8xw zB9*V^Lw6V2y^&ynU-B4EcP_dr7K~Z`WJjqZ%Xnlea>^EWOHSz&(Di>XMtMr2x~TRT z^JcWY+Lo=s;-&0?Bk-&OlLepO@K|NK6*+EPP?O5*nLqLicqj6lZ$BWo4Oa@`!29?5_ahDy$}Ohh-iWN7QJL4GaNJ&sDZloLWf8>&^43g0Y8A$ zjKe9B(7#bP>k{6DTkgP|CMt|PZYYpku*T-6`o`MXgSgvW3QWl1&;;;>1})knBz#4H zWn_hxDfo(;>#L;HzFx(mcG9$Nt5H|9E#H(n$w2%Qm);H?2euaAb`Lsn^7%*Ewa*1W zH2!d9+;s;DX%}4nTeB_V zzafsavGe9lAeg#6p$%}xo0}i>^oZFokxh(^A)Rm7Wus~>XsphPFc3iB|H#q) z)>DC&_r@M@DJuPN#G*YOVIjb@PTA&$IvPlS&<(*`gX!QyQ8Na(caeM!EdzF(=w$JHJMm0`}M=c!2C81K@FnKyixd}b5)ywdk zg?^|MjABmM`+ZlR!Tb7-YS%41?^9Mr-88320ywi`IzBQKMA;jszGv)spOLLVsYdXB#t$G(y<~n15qv+p&@b%Ds5)bTx0#Eu<^aD(JO2^404~t z6{smEQ7NM;xk3q`-~%JTkyu(yg~JkT@h<;#(9$z}{TyAZ;ZQ~4$z`Wrv88I`%!ql`uE=RbJ&aar4w zqQ_rd$W;)kpOOvwXUQzf;pKGN9_lp^)8Yo!T9ck1D2@VSq!wx0+2GfpEqSUoz)up)tC-v)^L%Cp~ zViI0^suVV(@&x#~$w?)y6Le^5^WRNh{_J^UKUkJo1+Q&wX=e#>&M7K+>uJ;qm5u)|9ECVYl`vC*)SDkB{P2E|C5eML)-0^2fZ~p-W}6vg`GQ z#(f%Y$;;y+%>`qZ`X4M0A#SHCO2p@JkDsiavjTTa!|J)*P={~m281d+U1c=afjoEf zaM!ofi+5uIF0s}haG3c=pm;Uwm z0oT@kyvQo6C7mA<9`;oHUh1-IW=RhX67RN?utYg0@jc$x*mzoKew)Q4fNXTf7vNoZ zO^$rrbYgiKk>2k4$XzjG;w#s6-WgAm{qV6!$kD756jx^pmKnpTfUvs@*r2Iix)150 z#6n>?<%`=eeW%K@rk_IE@FAU->YQctXnMNy;MlE4SxnCy}ug_NsUrvmdu`g?% zd;KmHU4s{FCrS$}v^zQ`tAmE!A{e}mKpT>svA(^z;eX;D$2h-`wMa1#PjG)dAZD}G z1}jzh%fN!5HywB~R<7AwZ9M`o&~+Hd7c?ah>eJLapy=lRKp%ZjLDaO-t&p4avH=U`LGp~u2m(5t=s;+c;LHkJQDB64 zmae$-c3SLC@XbRNj>%5lySkC`x7Od2&*Zk-?|WjZ%lL*v#$C3D9NAE{x7I$$OcPv7OA# zKSW+V{#M6oTxs;KRAaomzr@&1qyO%6*me{7b&QMAqG55ThsjXGy%LQx|3Pdvs&etA zRKX}Ua%F$Go~CX&0cd|malP-G$l>JY?t?|6ur5&mibE@UDU@T$4k(OAXv2T)~d6|CY3BRKxJsR;v8YwohL>9e#^K{Y z-&#dcVaTy*BYd;?^n*o)zwNLPfd0N*5BZ-jHmTJgKaHdRpmX!mO)W^d`;VD&xp6AV>ER@y zj3o)6Y}d-GJGE)Cbg7;M0QnCP%|-V!k+ODyS~g+aynxpDfE5f2iOSy-9PcE$4X6+B zFZK1zjYwNXMHUoEVp?5z6rs7U$nh!P$IKQ+dJ7_2ONpg)|o(_kHKh_LMek z!m<<;6ehcXZm*A>fbEvoBWs#j41?cz%wDWXM=~|9uYj&-Ni%2wf!kvC+r=jkLJD0M ztf}lb^EP#UVY#1>vnnxI5G6T*phSaIMPwzLU6b6YuJC1xxHJ}hkqV~YuS$v0Gqp_O z#AkMune{EjTRxA5w2Nex;;`T;<53_Hsm6pQOe-Q66K0r>P!<%?PdVm<<m8XzdH2d$&-9%frP@ZtJ zo-ooKA2pC);#%1zS_rnv(>5~!;h@SKYR{T+#mAwM<&63SDTSV=h!t*h3LBJr*ON4^ z$WzTl#Fm{&)W{tk1`P<#eD6Rg2{6a?4lD)rN6nqa%TOo6%M>bSAwj3*WDpXpYn;#} z9a{UB3Z6IX%paGzWFsK@y$TiCn&honk1HuETGiOH$wjO0@J|SeRPYdVwBOyG5m+}B zsMja=pFb|ws+%y!p7g4ox2lw@+en+gGf_P1y5~ArcCsIa z!P!vC5%kx5$sWDG(L8V`y1(?NI9OiCJKCm5CcZEM2B}0#+aKrqlNV#FAm=$fmch_aPMAK2r`c8iD**!^${Xvjh0$|VbAt&^((=j6;tdCUe9siA7jb6Q zHXrcE=e?rBX1TkX=+jls-`cOs?@PjBQx6Gm<5s)x_FI0p#<($6hO;C>Bho*5oz1TY zi@A)LdJbkj&o*J$>O(b&=C#6QEEz{cn9Z&J+V=(MYl)bceSLkHIv9no!<)fMZ#XY^ zCEFJ7OrC_bgoD&(uCA`ezPc9PqOkGc9=yH?0=LDd^+uWY)B!V7d}xH42(Cf=qIek_ zQYf_Kz+^S-h=^b1-?0|`DSAP_2s0w&=`tXOm8G$P=y-8BaE8Q#FzAwq@e^OZRc_ih z#xypDMMYAGAO*{-_ebTr-{jOA)x)7pUWYP~gMw`SIS$YD3S5 zrrcThfIjQi!j2e(P3DxD1ttfVn9@_w6{W{Wp*XL6l-R$s_%#AMw9T)m8mS3#lwkGZ zKlEu_fd)lke~^-(3@g=)K4dVrR6A|;MF9`Tze#j&HKZ6*{V~Nz1c5?wUDg@MV z#KNLM^+9GE6hQ9mUraF2Ad<`|STa-#-VnpIK#&u>svVqipctqJ0$Rd@<%5DW?0}8V zw2x(d&nx{i;$0MQjw!@t$bV2^!CRt32&tI`lf#qoF3yE5Yf(Wxf?u; z{QKF|0RsxG=<4wu5Z2mzU>0iM_gFCcDXrDyqT-KEyp9^BC(6KW?FOYBF}7yeC|9J< zJ$*I?n+HwVqt=qq=>?^Q2f{w4wVt=(I;RW!(>t4pX++J471jFIc}zggAm${J0E)7y zH8ALE71gMZgw2(J<&}zV%|d+@w^b-#VRb^}dNA6coNate2TNvp;&t8ad{>^sBM{yS z_b2+1b{E83rI003M%x6kH4Zb>BMG{Wk9L+s<;6iG0eEJ9;0WWCsg> zfK@zcyxPdvXv@~<46%!77kT;d+Cvbo!3(Hnyp zsrpl1D>P3wxdR<{0hZ(M!(yLeK0C|-wdK5@ zR_?T$MKYKQ0I@680rr^L{e^djJ}nMFC&Yu5Fs-!XBsg~$$QYlHR{|!iK$=f~sue9) zEUC|k!;I$c!|LYz;k>c;B9nyAHoL305f!n>^xks6rQPjqNJFNEj zr_xu_zXx~f2AA*5o(HRcZCFzI;JRL3hg~X2;4XJmZ%MrWz&K_WQ*ds_%n>&r!)0h( z@`N)DPi3}jGaf?c$2DotO-)_&L=F!FS?~Xbk(uE}LJbEYQF(Qs>a4KpSEiTC9EF^x zqv~E?IN?V`!kXlN@EidB0%*D4Q^bz&1ZVjPnwI`ae3D}TW3*a3xFd5D1D3SBg%o^# zsp%?i1paYu5Gcax8CiKz`(nfcG(F(jhRnwg4ZGy_{d&a#4_2)ZO*t>0kHtf(saE5g;7r`=la=;1+6Z9gi*eAbSBUDGUeDG+Mzib|)KYmYV3Fy;X zuC9=)FC5sZaMdq2A!p(JiA}g%A%dFaaqC>nRe2+8f{z9j=k4ts-58^tj1`~%c$GOA z8;XhhsC#^YQqm$Zw*S2_64RcWAYzH9W_9t`wC(%}va*mUlH~w=yqM`SLx)V^al))5 z2n5RnVFLr1T3o4#wpB??`^qm1;(Y3^M^kpUC#Jet^7-nc-BsH#9~usW*oxJ79S?4< zN$5mq8#BJL*&>&+{=U6yx0%;!8oxSg*mpOxu3+a%Cd4CH_qfguX`TQ~-WrEM^^wVU zHd9}M)!!-8O-25$ADu0ArxVkLk(yTiK@89QsUb%RBRea5O8c2WkSs&F=Keu_6R8VoKz2N{|*je}6mXr~9wGHFfJv%k0FU^tr1jZaK zA=a<#I2ZimdRkN4ebP`{;|?2ZPY{|(wUbS|xxfr3Z(SWt8zAj1;O*tH{j#%Nzgove z@LbYKmk|qyqy+M_t+|l;C}n|T+o3;1%T6;&wzIZI;X^%iw6OY6obm3c^f^GW+(f9O zIjPP^`D-FB!@p>aC#fu-UmHOxa||v9we7;MOOYNwf5XK6b^vz@A$oZI9TuEq6ZuJ* z6BS%?MzuC{vc%?gmb%Nl*pR=u)IhB(R|Bsz@XH}$lc-5TxYb|d8F=982fW^nXHU)p zLvp;JrshS-V8=8VQZrxi>-5<83XG(-`1G-V)I6O}? zs;yr}pkaf4Qo;wG4r&d~qUE&^ZloVq;87 zhOp5n)wjxi;!ud(x$W9kxMSt#l8 z7UgP~8uG8@W0-j}`gpL&rz#?4F7&z>(4+7QSRX{u;BsM+gNC;DR!vRpn{en|Os29q zDxRLMV%*EQMIv|h5hSnFl>80N&wRa%ij|{!A@b?P>N)7tAajfw-AZOk*^JPFrChVx z_{M2bC8e$D;h))&C;RP6=vHz$!S>F8SdIO~)_<$T#HqC% zmE7?ylqy?!XdN1+q}IFtZnCxYyJM-%qqc%=6wMY8E(cM z{6D)Hi2(o)At5246ebRH5+H*t0TK$)(7(Tb9ewf=1po00{_~tPbjZiTEA7l*v3Tje zb{$rfmmi~dqis1}rI|EiPjflchYFO&75s60iZjW5yiVWx{p`oL7kAQZYkmEco%D4v z2hpAbu1K*ZG_Qk&ty+go&-3E4uWp3s=^)2U!^_!o03 zR1_RK<}w(Sz|g)m!47&3b6xnE5A;V?sN6F_L`7rlfM`Fb9hS067+t%JyiIh3EL8^e z9myxqxbHDPG>uQTAnftHHk=ozqkL`thb?|8pC{ryjuBfcBkHJJ1VTv+l@`N zX}wW7cRi~Bi7CgeH>TmI0E^WgE@%akfHO>>2?dt?2V351mi#ZZZ@U-g4f`)`W*kP( zjhPN$X5+ixau-_wenq=v-&eu+-*;4~?hw=}Wzs!O#rwH=NGu^J(DRIbs1?lY?0vS{ z>>!ZTtji39nto=<@;olWl>R}YkWkpwB_f-^nrOwHaqCTthG`NEkx8J8$_H?oHwB$g zMM>ofsKMRHjpfx{&6KY#z@K{jtZ zcjx$dxxgz(c+OUS4?P$ysdDcYd1l{uZo2p1XE3mmb`t(X-aQtJMlPv$P0P`aNW>8W zM?RnSqkL>CwkR-`GA@Z+<5x&3MsOSge2=r7dXb=k^oo^2^JBqiUZJ_Q#^pBS&QJ34 zhzQw;q=nu<(UJRC_qnFAmFq|xNuBS)Pbey#2{Ng~0f0P~Tv4sX66sRyqLA4c1o|RZ z#54w4if`mcSz_wzCC`^>4;G!9(IB9` zL`6}_`P%?bhur%&YumvYwk8Lovsvh#w*GB$d0}5A-phzVqicf0dgSFZiH?2a$sk^( zTagM>m^OoWawjG_T;aU6mPrh2UCR!m#M$vVc943(w0&b7SSBCXluD05>%$M^LPEry zy{+BiL#T+;np9=$S;;u?0{bbY;_IlbxpAeW?jO^LbZj|STXl1ALsuqKENE87Pv(~R zVvGka2-i78cx)6*V}in3-PKf~Ib2*Ct%V3-Z=axbnD?*7wTW#pJo#lAp=Iy+r6Wqi zzun)VpmLpHtK~NgVQ^+BJ1AW)EuFSYecS10Pegcu`Dkxu6JpE#b3D_}4F`5-3CHK@ z6+&uhy>K`gn}d(PL8zm+(nu_REfwaqC4FH90FW^!^-m)KQQIPN%OUtHcc9}L|2Sy_ zs&EAf$u`CABFB$bA-1)y9@2&;(Rh#bEciq2(wPNWc8#fYoi$?D8SpjKJT-K{_pib;J^>xqxzh;frYQJ+F(D?dANULJ8p9=1{6Dd}_48dYTa7qo4(mdtRiE8EvMtNw)99p>+=aJA?C zh_FS1&zC~HfZr0S3=u6zUKE|E2zK1O>yOvFzGT@ntw8Tv1K->RtMz)XnE`b z*)?PItYSzvK%#wF`wcX+mXtOM!Z{`ftz~o)BM0nhUz&B43pQwP?~rbg(U%fSCc!Yd z1BQ@4w`lZ7uvT07{l2ZgGDV}*cgc*v?JxPd0|_n zNt<%AznnNJY?Ob{y%qGWEL`89orLFfB9YQUB{Sr%q@OgyC4-bP5oZ< zvaFHAe1{eG+Z|dcqV*E!|U^9wAPwhs}UHBWR z!O}Lnhogz%=w2FOuX!&&!Z?)ZSx5_JS?jAKT(H8Tv;RM%=kpMklkI$@7>C|W;{Qf3 z#-G0C=v~avaT336p%Q=`clv8x4&UAo4O)=2M}Wag_ceF9lOyiegLF1m7W{EjQ??iI_f` zHyFk_99;j^bq%ib#Ok2hWk8i?k?nO*yt;7~y&f1$AheHIU%qdIuA4wC8zEy_X=X#* zPLrY~!2p-VenS~MyZU)9SWnDg#17p`!Ui{B>iC-=0tjun%9ojH5D5V~zQ7BsnEGE5 z4UDMcii-T#e3=SZ__!(ABZXd|>yD&g`HT1n{hgN{Su=MQdQV1&`vZET${O;kYn_7h zD2A3fj;vdfVyvv31Rk$FjZnwyekf2DvoDt<~r7Vn!_oUE};%ewW#_aYLT7*?2ibu7Y9@>OXc1!6Wn zb3p3_Qj;g#3C$>D!HI1-i@>$aTjE^7Nk2m{AZ^Ul%_1RFKX&n!Kfys8^ODIF$mku% z1wLdS^3U@LZLB35@60exQ}t9#1Toio($0_A22=&g!RSZ?tLZc!d~D(Bd||}=+g3j) z}#(+Xm7&FSr<~wVU* z{Jm2hE{n^lV6DO@wAbC+o`3A1@vv4?qD#L#C9z-odsM_sI_2hQlD8bb$lu;fGu3MK z1YUb-JCO{w-dR2d=0`x9Z>?{nvYuq)Nx57<7fxhfeKbhjVG zrfj1Rp)*K{psq|9Kr@!(7UF)_cJ1;+nF0Y#ZLGw!)y)nXc1AcAW@>v@n}|aDJg11t zL~udjvURL_3vvvRIOg?-CDeCk9RrJS3{8RpCP;hNk7;GIea{Ybd(RUcPx-RsS?A4C zR!Ug{&*|Z9B})NY-F6mALP}8)u3q+MBNO4ox49{JAl)#!o6+4RAuvipN+B?Re4 zT0od|cisK&>)!nhd$!MWo^##@m-fe=QtgMoT%GiBi1M16&`}Czwv#z^oi4J^-qxQr0iyv{!zeOL115aKwP153}6MMkz zYG|{=pt#aAFl#WV$JRg2?PEpC*1##mw3Ok#T~x(7O`36ze8|~p-P;8r2Vg!P_Xp__lF_7oPv>t_ae0e4i6KH zl}yCKq8d%^KVR0Dogu$h@B{MLHjIL4yzmihx{+^b0luj=Hc~4Uzre3%T5=Xh%DkAG zt^dxNdU*xd$r~z`yyGc;r$_~MQNNSYOG`Ff871Uut-Wn1{IMu1 zJlX=Jl+( z-*@`r{=lt$4~HCk2PGNR{EpynwaCYtKBFw--SQ5O>5vxp1m9@23PC)A7elMp}844|0dEwlDQ+M06hvyG(1kZKd0^95KW3A;~|H+}C{#DXBQx;L=! zZLi$3195}QeCKzR_*_0IK1V|T{4$5m`EEZBWMn9?D-S}fTBfk2%W*c4<}-gHrHsVY zBG-X;63KP^LKnNdLycCk{Q>GEvy=@O@#LUxV~-d9c_{Xcy9)t&dY)S%%^s5(*Bt@` zFKfaMqR$ZHNdISioXM&>>pVtwOJqWh8Ccb)1Mwo%iZ?T1!du#j;DFrs5Tf2=q5K$N zqS~{qF+gVahXEX-id-i>$+EH`TFcL!AE&s*-XkY*<$y5gcoW&nI`H%_;gQ-)OYnb# zRNqG6DRz}Vkt2x?d5%~@D`WgS%(bPp`w~ZdceB&kFrw!eg8wT^Dj-yA3JrbaRh|x z{8UN!=MxG|YFF<6%!7x8LWn?sWs9-trs4GJDGu!Vsq=g*vg`69|6w8j;cwOb#M-0Z zMa+PZ2kzsRI_FnwQ|!B|?(`?T_8V3Gc4{D`n3m=7r`_YJK=7G>neWZ4N+lymDLI)t zni!x{rL%`Sk;_@(1NLz01_Xr)<9iIpo_)VOo1gIwhJXV5fG^As=?eCSzf zCRB$MfYVt7OPL70?mIPHsb(sid9oYO1CB}54a z4b>OI>`a!pxsCG6B{Xx>N88DyT)-a+O+Bq>$aK!=^T;?!?)w~5S@-^k0O0Y#K3vP!?d7Frqb$VO!?5ui-vhw1^ zdbt{45;24n;7=R|HleX$(lY|yQb7bB&nFdE?1U4JPuunezQ=v_S8O&WKiU`?iXBl+ z%NYj%=`y#wDFgM-&rBcjP@2DN-M^Is0d$Qt3was_$Rc=3Lj}zg#;CunqGyXvFfH|( zQgmSMw_N#-+KYiBa$GQogDf@=@iMtS8}8Vk_wN8FtYFr;56P#3JSRrcTzGsVLB~e4 zU2lx-uyg-fEazNZ{qbTjuLG`RNPj0)xlnvFRXvUPRbuIJ`Q@jhx>70}PD8dV>S>r%3h zZ6m-Zj7wvm4gAols`*ABh$bW(Z_}eZr@j;t=acd4CQ~CE3)7A5K>W9(0D{R3QxXoX zm@S50WqmU>%CPui-1x>w9POudXdZg4OfS~wA@suejNB<);O53n{Bm02#x3aNMbINI z!4)N$a63~rH8phy)6&Wh0)8a!u2A&-48i&!@W6|+I z9!;fag|bn znd1T5NyAirq;BjH+yB+1Me-l0G%u^ad+}quW2^IFfu`?3-o6oXaO5{GA#!p$e6{L1 z9elSk-L&krC8IjtGU7EmZgO{E9}N>biXI#DlReSu6Wvf2sA$qsXXN}^IwhdHDnACW`Tv*GZp zY%YP(M60HOqbTJqlSQL533_TqxK#a|8dWRm*mJe`_tKD6{JIejXG0`fVA++KX$oRE zU+v5R7z{^81ASM45+k=kk|i02eXvEI7Db=m-F(8Nk{K)YHQJG@TYR~B#M&P?u&b>u zzBk~0m6k@89lsJ(6g8tHx7|ylhh=6i_$%R{qRM$J$JvqdbXH}FRI@V*UqZ>qT+%>jSyE7IS#aV&WwO=|FfNen`e}D)J|DJXdUM zW}vW2(P8j{JVwUc&wsz)Ib%Ha)_LUOC#nX?Ckv_t%g!|tY{^c(dZ)hy3Q5Bn@Y>_4 zY4wzta5At9J19a$js+Wfd2tcPfdospL?h+V)fKGbW-+15BI(lxwT)K9IHQ1wpUC_IQrwiC9g&&rP0ja*6 zy=hn4*)Zx7mcvr1qbq~-*~9jkS&MC6J1j;NXudma8_y9sOAo$DS8fSoXgWDb-yy#X zW1dZKGFQr$5_jb(T!_G%qoP6wd@mQQy3Uo^Z8DaUC-yD-cTlKf5959~o4yRKSbE@bRiySROU%<#YDcM3W*fQq`l!ml7H5JH~kqA67(Q(ZNWJd#g8QDh8{&4 zRfTdMY#@Tg?)LI;bCKiDYr%B1sQu+d<_o(rIi~ENr($Ry&&7BAVqtQ3mRI?6oDB*&NNcEeMXO2G`9w5FpKOY%2YReG6$;e}o zVPQ+mkEy})@%@?4r}z4d@DvhqV84?*9Yv|6q6YYrVGI`|*ONrDdqt%A=bwjvV~O9O z!v{jX06z#tYsjO~Wk0(#X8FOUjHh2?*|26WJT#Ho|8pEO40j=MqD3c)m{ zlltMX0~zdJ6&T2PDFmJ?$udDQ7e4B+7GxiqI^uJDp26e6HVlzcrIZ@Rkp2|m@_88( z@_Qo0J}lh2{>$RX&!o>h*h5J#acy+V_)^$(h3w>P@wr#MNL#Wd z8lJ%0EWzy`B0Z19j=+6KfzaSYDJOW8y-TeqwN0j+eUp)2UgQi1F}Yb_B^|JO6V!ze zV~52}Dw4DmksWI~CowXi9_4zHYZMot%9#_PFd{o^+QL6nniHEE8JP+NF1P8D&<^0R za-tV=%zwA7_gFnz?YKTiJaG-nYio;?e*I9gfXnpTo^NhmKReFLDRd>=AKKIFHjI*$-U0a{3K(Ea5i)d>;L8kYVf)pS(s+t z#YqD@cJNX18ZI6YYSU$>4z!gcqDCHK+&`|f%^Ypvxgd6Q(S z0@?d97Qx0Bik8yka)C0(wrA_>K*MlJP|Y`m+4b>u z$$?hqNLAn%i|~6SZRbwSwx{cHYlDX*-r4+e!x<{ohCenjwxp|IBoi`3f3@G$!7*GV zP=z=>^(NTpR48#$&Hq!Nt=c{4iNuG#)EKkr` z^9q$IdO`>hQvjKapZ75%ruD#v*gWMk5g&V87DoIIDzR8Wc2J(lpoPFszHFBQz@ba7xs=fixm53!tMnw>FOD0L5thZMR4$*9y#Lob+#s{RU{r*RadWQh;l)$O-cd ziRp=B-rNbQ>FMid*!bHrjSsWL104-EZ7b)mt137|5O#KmVwTfYZqD5J&E^${I&2XS z`mw=2NVahZne1f$cHM2U$YLS=ZB zNV3xv$X@dR6fPBYe!?*uvaIlWDWI6)IcqTkHmg=4TmDQ5H=8qE|E8s@*Vsj5aal{? z#aw%-JK>C+(KbfeyVHB8U(8>JmEl?EDl_qwIeK0n8!uh11DwL_+SaYLOl|YIWv`OY z45+YwkQyA^)}*n-$9gfMDi#wn*LZRr5N1--MG}$BeV3w@pS;Q0SA20xB@HM);b3*v9Xg_ShSay8v zTo%|3RmVAe)l{f#Zv0n|UfdK+=3&|(9n8qh=~_0iRFfoi$6tIOM+7sK50S&!u;FjT z=Ex-*t%kLy&D*9hJ=9{gH(bg%>{XQVwWNhq^*zF*%DpiFxoc7Rj?ULy_nO@sappYJ zo3^Znu00Iaw)*#^ijl$iQgZ6Q`ivedZ%K`g9ioIx9*<1@O0E;}Ir{w}mivBjDsdJ@ z+Q9fW3x#p~bkdw+Kr>j-nLn$|=kS)c^Rm2=I%`~7AYJARbaIGR6?ipe_CRZA8e-+L z2P;cYkvVfYbUB(o>RK)SZOOTx0;?0yGvcFw(pPN)tB;pWYr#(s$fIViC<%wA-Q)X{ zsK>zz%6amC5S>~H^_6SMGmr})v^LMx%cd_l5ca2bLW&lDj5H{_{3@c1^nS{sg$3-cNtK?so_~HV1|W5r}$AQajHbx9y0_)WZqf8N)JlX z1G;~BDE5iF_p@O2x@}pc`U10(gT#yD36+`r#p19Dna*!96q6Lv|6air> zzs4n@Bl(QBhBi)3iAD@CZBNJP4k)n_Nr6}IARU@%uZh@TL@l$S{@QVJFGJ~jrpV{W zQG4PUNS#!RHP^QL&sB^ZRLR&uWYRVpC1WF+IoNj`lr>jKmDeM#pIx;9!oUrmgE&MO zSS*;!v7d6p6iKGZPvhOpQ7?KVyx#a`V(j*o{ zm7p1=V;hJ9llg_jitbWg1z0 zT9h0!t~O2+(TbDy*1spJ9Gi6=UM;70eKvI8bmsHQd2tY-H0JNYM2bX`#KqVE8wnY6 zOh^b3(F8;P-=(aS%)^NZm)E_F4hc_SFRkYsE=3V2zmSLgzLTiS7j5H3R1@qV~Y^Z z%wEW}mH9K`_f(5zDkj$T=9SmkI$OG5R~y+t0a<2Wh9HXjtC{Fxb*^0DR^MSx4#Pzw zno17u`LyArZ1{}{)Xhxj1BkZrW78N8^v&YuPsJ?}{d&cu0!xN@d18Jb&2OnC9iGYq zofF@u@5fd=MGy>OD-Eg07W3CJ#d^@)#-*d*9d_zudnO_X+JKd>Z=W?`ATOUvlB;*C zSDk?Tj~`RN5}uibpt~V3rv;V| z3?N`Y&|QEVZhn1>N?3r5cilY<&<0Zxi{ugjUc$Nk{rylvAK(uLUVA4w;<2`$63-rT zhZFK}yiu455WOu!F@GyY{^Gw6^NG~FUw}XxQ>Dtqaqo}nUs!~vKf*q~|L=cvY_siW zmP!{Xvl{Y*(R01xV7ZFV>yE4lUth3WUShIyE=QRcCi^$K_UCbTQk7>K+4dCt^f+v5 z;1a!hGsao>DPUhe*mG!xtS1he59Lp}=~?R9MOxG2S@6j;@^PLI67oOFo&O-1J}>_W z=wq7Qxwt*%A!(UyBA#s?RQqTE(1YOZN5O^_#aIQ~d{ZJ|WW3(j8LTh+qIf~4IoMU1 zrHnbmvntasGho|stRv|*2T@(5FnLMOZl(8T0>g71W2=KS?62UEfuwAl)kN+UQ;cj# z$7@+F2*0zqoVAw6OWDi3%!Sx!6?;jcorzx{bR=6_PgRSJY-KY8^Aqp$1#@aDPZ?SF zxqiicF^15(o7}5?hJy{+^f93^6q7tVkWLy{D>k;MelDi^jD#8IBMBJ+A_0W@lfrIz z(%yg^3^zs7So{)Qukeo?TWPYnfEM7XXQ+qGLK2Z(ZlY^fq>Nr@lJ$*!yPvy-s_F@H z(TR9uDR}TgSwPaCH_(YX>}2u3DLA~gXw-S*JF@+qT~w}Ughcq0@KMKyF=0Cy6(Tgy z4ohWnJnKmA37nc&XxaUV`zTSC;zgTTDEEL$LZxYXN9xfir3p;GH$A=RCwpaML~&bB z)JYF5d&FTS-{W6Eksm*{V3(LKTxFxrwp))hgxf02R3{@Fpp$%sYo~3N7LJV{|5CBR zC|6Le-E&O%OUSQ&VN6Lz9i?c=wpk@d9{RqTo2g{8YH&O{cwIe5bk4Ey>@8*7CqywqSOqKLm zQDw_Ys^tid*i^>xC?(vAA&*%qIZ*}CyTu$%jZ3S0Wji^@o0NTov3;`zR- zydk?;xs)0;m#G83PqCgSPq5{+sh~IQzH(p+U~9n7BK(& zuYEVsu5&uEbTXY_oG#@z4w&^2P&k^(}n%`5M=!X6Iv$*5b)g$5ITfSt!+RJ^M+TNPc#S5syOsy|l zkt1ikwsS&~j`RoOEZ`gP29Q=W(Te(dCXWIjw1s8C2PR(kD)x!Tg>{%2H#*qIAK{$yK2HP+!O{CPo(UMnK>yoA&mq>)37eO8sd;zH84Y zAG&Dx>6wNx zwXfOn5^;{a;Ww7>J#;H8Fc3{7=|HWLUbvmB@Ycnku-7gFcn=#X+<$i;>$+8^5UY$g8VHRn8I&A zL^L0rjRO~G6_1xabiKN%we|G3Rj~Kp!DO4n&^JZ#q|=VGb_gF|?nbY%8^P#)K5rfU zlCkt`UTnm}#YM*QwApRj#TEm9Q`lo`!9v4b{Ca`@=TBfw{=K;Mf`Rb8hYO>l<}S_r z!ofb=I*#dAa$#H_0k-Em{((XBhempB!?8`vvzd8Ci;MdN!Iyv2+wAnFq)gprKP!&q ziYLYUk0?+;WBW?tV)k4lKYv!`vt6+NKJ7EtifpO62nsG^!A0*!|F+=+{h4lKSmIR9 zte*e)epI8>(9H0*mfmRlW;L*hC1SYTj`HFw=cyd$YLne~Wyf9WoKo2UjhNT@U}8&4 zS%1fp~5##hUp<1ado_p_R4niHxnp1@0sB?O}Go2a94xcG-IZeH9f zBZqQ#>RoI3;{H!ZPgjIobA(<#nbkeK!l$lRZvUp%5kj8>@oKk@PuLGPIU`HP4Q+({ zCl`3RwYt{2g!LDHX3ayEK8?oWXIERWnVJ-0Aeacxd+z5}|7u3N?}es(j^wN{=zQ!@z9l>XI%?E>V6q_V!HAhS?WG9TfRq4sI$t){Pg15J!RsuHdQ z>Ow*XWl=JaFA8LFwqxUza|%L81Pj=}zzKgXiHnZT1klO;d;>x!vz3xXAtq!ZScrlkiSb9xv>GZW0lEgUFLuS3{()$&{+{@Q|Mvpawy!#y+t=bKC^38VfRu`_ zI(G*Zqp%@PjP-LM`Z`i6zVE1sR+odTcd{BFp8S9g> zrPv`ZAac|}3zNA-?e-I=!pEAsy?AtYwPlJgKD=G5*;L1pB<%4pu6jM%yt;qU*3z)0 ztsbpVDmF`tk112B-lStJ%q$!ejZPuAGx$Z&i0bCFxOnv~v{b5Yu(MwTvsmiGfmex_ zo&S8EmVHb$IWfZ0?tpI>hN+s$>*f>qET0b?^SnRHC38jqk-dpbn|5EX$& z)yf%t#=vrWEQc4j*cB-xjXY&AQgwKaP^}Xpl(TU4^QXP?Ua#Mjm)P|UHpS#uQJ)ZL zb8~vP51pDRGwXf7O4r|21-T|$8*xh^*IKVzri!AKxo1emZ5zFB%r@GgZ3QS;Px$=$ znFlw2+0|40rxztydncO%y%Hl*V#cT;rnj-QH$vX9KXlF25gSD5c~5UD!7kU8E!l5< zHgETKTePZIEY4mzP05`V?bF>IewfDOMvQ)c)7FE(Tq1C0=&-)H#Or2?1CT6tOOgUX z4^I!NJ2xhv)2@!2T#4(=r`_}?UB3=_ot-<{nAOucTIi_0m_hmMlqIt#H zs=f(#*a`{rcJD+liDVy?!0WwLf`SFp6bF^#q-NPMdm@pHZBrCc5_XiGrmhJ;2}W;f zj(|Syrx6Mu?fd!e9R0*5%cF!`6RKYI}!KyeEY5fU|?Fn{A)KjhjB5o6Cj&GQ6OTqEzy_LHm zm)~Q`K(FuN_50q+%G19X+=uK`$~Z(HxafG9vl z%RtHz$}>@NHint?2+i`9Hger%bQp|d zE=_-GwbgE15}gBk6^g=kMo$MVr5}&uAFIQt1Sj%nnx^2UR`b0YEzxso%JLvNFg7rs zEB2~}&J##JXLc0af5i#cL(`0T8<^*5YsAeuxg&#R`XiDikcT+V#l@+-UX^!UPDyC3 zoquWs?ds&+#^yjgwUM#0Xwd!j@B<}{HtpK_8gM+|j^XaExqX33Yp@uz(BS^;kCmG{ znkG(PB$&YTNYfd{&ns4mxHd(7d*qjZa!jd`McVt-Zybuc+`ekn{;8G2plfI-d->oa z^ajF=iqf5_$~%o*XCuuxu82`I{`%{NyO`z&T_;~5)hi@n^Q7ykySVH2$J6=cQRidB zao0Jeu>A88{qWnipKQ9~26rr=pUzU+$<`955)+Fu=iM15Gt#q4c>n#RAjQ+K|1& zTSyu#szfrb2@IHDzCHAa4jK83O~*lpT|)M<_+vey`zj>F-1)hzCAuY`6;2WTMi5g{ za?2p<%{ji!k;VQ1dZLE6xP@P#42yo_93CUEDg>WBKgW;pn%4{Oh8iA`KV5VMI1cpS zvksl95K~ySI?0e%vC7Q=+IV>H00TqAm-t$+L0PTx?DcB>@^=7{6e5BKCWGiRT(jpF zQ*K*1yiiIYKu4MxQg*YVKtKot{xk1K2#6%)iy-ZobfPrra~qneDKKM9@t;>10Kz$g zOHO`FM5id~to?Jc0V~5sPwtGuoFQz`-b8s9=-cSgu{i1__QRJnWTPR##h&n&(yHXp z%+LsvoDC&oL7)0ux+O;s7}MB@qs3P=CMr*`nAVQXHZw~9Q+Q+Q@^%JsgSBB3FX%Vv zj9G75zw=c;dp~QSVK+GpRKsuyg6Ssj}K4N*i~oQx)M+IJ1{*nWHrNQZHYHBJzf?Cow5RS-c7=!gbayG5_EV(oRY_K@VH(7WfA~xHa z)zO3Bn{pLb^f)Mc{N1Y!!ptbXR2PUHCXN66A zgDT^kGjR|jv9!zi3NbvE+__a)vHV-88Uxa=jCy3}vrlsDgi!NM+g52?HJ%viV?s5d zjg$M9ZKElA@i#x3^Gs8?$rBTOek>OS7(k_a#qlOF29le`ZjuMXr|N$dJ#A?{$Px!>^o{7>1)^ z!ct`&=;Oa#NHeR*C}n@4!vQnuXu!!_wiy`txZNvPj2!Le69|d`#LP}VjlLliC~I@; z*p~D>L)Pe3BlRCAEIz{J;qmsVuUlvZ(k+u8x5YlJT?BV-(std9x;-AOJ%+j6Y|m3X z3|<8d=$S^@m7CoWJ@hkFJ?5_6AuEn{R3#p*2s`%Um(V8gaScfSg}!6}2|6f8hsZLH zNK@)(I9El5U=#akQBr0>dVb4C>PFPQl1KX`NQ{k=>$$mMz1-|cP9GvzS@WTIa% zc-EG9&)KGiYC7gunGTdF#eDeH2VpW4X${;3t3UR9@%K{Xblu-6ZM(G>>j2##74n2o z`hkFDa^C7i$L3@=?8(S~K2!*X2)hQhTzw@RC}M%vDXy3gJf*B02=k^Ai0NUox!tqT zv{rf!zpS4k4na$kgHKXc_>m)wq4Uy-39`)#_GmFZ3ar|H#}-A)W-$uAFaTV)b`B8T z{>!j49rp1Ygdbcl`#d!KB>D>o-r!leOALy$p2Y)fFPPe+2N=N}UhO<=KcPKFIz4*#-Z?DKt`1G>ST zWA2emRttg-KS^)cGLCE2T{8TVT_Tt|blGW-=XMr6M-X%^$9K;nt(h9Lh6MGxlP=m; zh4fq72T_nzMG|`AciEidmGuM)^jcXjz^17D(PYtaeAQPkQZ6#+RpIdFeEq*Tl=6Yi0tqOM9z z9AZfrh5O}aAYLDoeN|Oe)sGvglTWd6Qx`d^jxM6=rKt<-{xVNFGHiF^gVcb<|6SOY zZezzqp-D2P+OisP4fjBK*lNVNhZCo2-@IF){X2p!EgNGcF6HyK~n!2*Qyu(A>;U^-C7)UqafX}Jy& z8*=&DaM}5fu+3vxHbqcRJ@CX6nZPSZmHX0=s*9rOH7X&#GB*luyQB`>ow(#!oU?rw zjpkp2yl4JKDngm4qs#9rUVa~wNoXXX{Wn=SywN`#8n#3@=N36H7A(Ko83B(>FcZBk z@+(_KU*vZ-{ouj@&Id-1A5;_Gt!LtAR|Ot82?(JjD!ZBcUTW^%pX z{Di9NH7@o+;`X0a@Z&G_$2PO4e-gpt!Ml~Y&rAq3)t=)ksj3H2moMp*_v7uD-2LDNKsUp4sGO`^jD ze>2Kh<7lPof}RhON&$M1#3`FZO1J_sU=ISbeSY@+tgOo5;1X2sYM%`bfN zI;vRM@lXu2(`{aYHQ(f*DpfDx0;~r)7(}3RR7kcYuZ*Y=y<;(sA`x*aKyE_}#*`rw z`go?s`hL#As_6HGU`C_{GQxyQs=!{H!jH5xy|nVmv9~(qP`7l+jobLjQ^WF+$WX?& zvv~XUjaYJh7S9AtDW*%*dgWmSwzPpXLS0r;5_#b<=47#-mi`zW=%?(k?fGJZk%pDe zxtksKIu1oZm)5huJZj2Pnx9KMsJjv{Q!>mG^{eF=8q=|}u(0s=sno0zIl>4};fEx< zJLE=t-(ri^{P})B@RvrBIu2OOxqV7yMFqWO-6UCB^E(D56b6vL5zXVWSru}J z^SpvP4J(&+oeL~{6Jf!`CXxT;_*8MxUv3)c?mAEjDb7r&HNE=#xOAEPJ@}?<+<)&? z+}M6ko}TK}yjtD7BHU)d&u8qWL@q*kSeo^-;;b#=>f5(DT7nN8%fd~FN~6O7aEA~n z_@Zowy5onvZ4hDx30X-wG;V(V{hhv^8gUrAl5MF9S^qPqjam-b5abMgbkmd)k62SM%Wk>R0hH2F}O>9xXEW2q7HSRgbISC$y zzZ_i5?=g7A?R4$@X8xcsS-x`9x6ylZ?_HJOsM*tnnHlocx(BO-c_N;CMUJn0HxtGU z2}O@32Qk>(aR74Lt>b9+scuESND+R4j;8>hiL+nrmCV&!g_7{wcMhXB&fcC&yxg;? zNk)wflV)#B_(kkRNCM9$b>~|nw~^1>;~LeD6;3WLAK~2N?Eud6TBE<&ofrAev#a7K zPP92OB!Dk5pbGdt{J_c=4!BNu{3r2v>lSb>AQAA->gi_3?b`ndHDMjOi~9Eq1pSc- zKAn&u@6#Y=hf_EQIU zOi!#E|84`s(&bmrrt~o`BaURZr;?M4N*-*ME}AaGoT=A@ve-{ z+1(#Ejx!F45XsrMVCXy@fs{>zq(sCP0Z0q{^a#|{z~DG9GcXNiqZw1@kT>t-Z9B8b zXQY_aXE-OIh$btqx$=!gt*C5gduXU7b*o{rx zDjPm~ODu6|~?_lDlR{X0pix?1O1IAp4;d-ain#Q%u-OVStVc#_Yh z&x|5j!j&k)6d*e_`ZYsim8f$AlC_{6S=0bgjELd+6&Y8TU{PdSo2x5V3@PLJ*fV(w~VIR-Tccbs5cyG^S zucCopIhJF%$RI(kxQD>b)|Q;yM_{pmF}gN@kxnTa#O-W~t5CXfSib~l{H|SHr6;SZ z%01aS{=F`*HzuA-C|9Z;(AgBEODVf1aDE8$9k}_a)(3tD82N@b2GAg1!Lqh z#eD9EKeX>Ze;64X8Bgt49Xb^<`W*Gy8^-?j8SangnGF$I-6NF?u6zEYGg-n@<-_Go zYd*AiR1$tFj3&Yl=Z_Cf@*aVLuP*1uzCLUP@F{@AUild2NMnFt!y%j>Lj;dJ!J#ZR zhAd=&B8e5*NBz0lIt$`8Ejq5jE)i)&zq|`Al>)Ym}dE;cejT$Ex4| z-E5F5@Q{B}Ud3qe0=LOiaA1=+gA_3AP&)(BEZh8g!XS zbBDQz(Uv_!kxG{<>LMH5_C(ujs|;kB*fZ-`NILt!vy4dO_8jVHLe~-6^jFO6;e}@U zbHcUL+{VGR`)z@z)2heEz^eO`s++WJJil|Su9lnc^N)YIA5V`ucU0Z9Sk^A6-Nc`$ zKxN+rEWZH9H=SwE5qKJe&vi>kG*LiFQQ4ikPsEF9g1GEBAAMBfL2KlUjo8g-LO8(HobF_yN8L-{xwu!iu?%rOzC zTqK1AJsdk#Z&nyFz`3bSYld}FcwyJApFG*q>=+~}hf`7a-U;>F7Yy#4_)iYPIx+uc z8&H9ixmBp_8#w{WIJr7oORc}rM86qA&uE^f+Wg8>bRxz~Iov&UpFnaP-U;(SmPGCL z7IW3gXQjaoiRm`1-K$HYlwWryT5DsBL)m;-jdR>pqgZ0%yyxn$EQs-E{~|R;M5-30 z{ku<2=+z&gDB3503^7I3mZm5l4@0UPGweyc@LLjT*qWY0mniNDMHWUg;UUvErM z1YL6YHM9!nbvu~?3NA6-kp0XDa3+DaRZ&aJP4Pg!F!b`@W8j^mqNk%j;?3yrRG~)V zmXnim*yB*O0HfC;QJCD6MJP(R@=(vdNttxT3rn*8IJx45idhm~Uf#WShG(dq9A^;D znmOU4X}FcQ|WW;iocQune8mEgWBoLz} zU{2i;D3_-8&-j>(B@;IP28|o?guDP{AGzM-G~CD*yvXfwi+>R*!~5?7i{C=-5WgM3({xLEj}S8i_iI@x9c?Zi8w+koS4`^7Qktk zqUVSt!@yM{3h)apWVc~Kke6MOzm52L*@Vj(m&r=+N1)1@I=3inlmd%afqpMe;TpC~ zg3wHTRB(cOXCeyuj2VBwHe?4Y#a4sBvUv}E(gw`@XG>2*j-S=7HU~s)^pfn+UsGQ@DF4D%&T?PFA}0g_QmR=cz!}l>-iO(!Wwvu?faB* zf1w@8YP}F5<@VQfu779B=9~6>Tfa=LYvQu`oh~9ucj3X)i0kSfX2S0EMd*tgvyYh? zM9}x7c(FU`>`1%`87#+sFbA3P$)!6wz-e zCUM%Jy^kroE?LVJKW$t*l^@%<_Q@*5=x_hXdBqt&Ul1o=URIXs^v31VAyYVrJ(&dp z5$?6TTd~n6FO8=a^W4_4E^_9J;yYXvs;donzthJv7F(s)a!Urhcm>;oR~qb*yLBWh-gczU@~Wp7n;PQ( zPWM1p?4Xxc?BI+7k{G?Y(R*g=v1I#L;)yj9hw#$3TI_O50BHZW@Pj-U~)e||tCXJ+dqH_ON7!3fZvSh+0dFuORK>!Ml3mbcKmI9FYjf}3^jw)>O zzx-yOTrrz(-v8}FF!=gaA$C|8KN;p_BjPJ*YrKuw$$s^rd>p z9al(}s5YC+OWl;Om%En>g=oy^193hUU4U(x<2wcB>n^t@dR4tYQ*f zbhxM}1xZx>jeCg={AwG6_QYJLMYFD%f&?yTL$wqHkxF|DH-6HmbN-icdX!RA9I)nR zlKtkHeGYNG7EhD%5}Osu(cN!nk-LLD!p zj9hu82i@Cyc=WGo>h#*R*0g3HcIs#GoKqWBF+`kk@W$w+r{~>oY%aJ9zKYA?;0;Ng zLoUUFBzwjklkr6rULNAry^q34vr5nWTN?g!WaX|L{4QM}N#9yddFeG@`@`JUR*j-! z6x!k1)in1_VE2Hr@|~?+X%73Vi?jwXd@>_D*UZ$<-{nA|oX2~Oz0=hP(OHaiainf( z7q7d2eK-GRd#9A9!EjzyvGiT;Qtfo!0U?&3_;IBqmW}2c!S8fpbVXDDI$qe4f)9L* zk{udK_4U(GDndTjYFbdg723{7KR!L6$r_hKKCcZO8Abzc zmYZ@_^PA(t7Utp#0KP6SYu^s6S~%iccB*a9nRo;8h-29i^!3U2`lQ<=;2OOKx|F(~ zDb+h%Ggcmk2K>9aOJC59!Sk%$QaQU@`}eq!xcBmLdzl#kPAp(Sd%^^pKPO?+#nU^Y zo9Dmh$d$zIs~?Xech)0!u1}PeC*Axj{8GnFd`5?99}w(f!z2Ii1<>a1ev=h98WeOE zw{{&Dd_NEza3DA3*xl4+g9o(_GGF8)`Xi?<)TMK^9H{@{X5{Ljn~*;XZsxZppFkya zKOwSq>e==FwBt#%WA73!)Q9LoKf1TONP6*v{3WP&TjP{CWsuOaUO3HU4@?SsQ%19@ zApn>C67_xGAtZ(#GdvuXges~eMQ3(JW6LZSFb9&9h_QA2)+`8R4T4*R|^o?O6JHCMz|0Wg`j94OS?y$ zKWi%SL@Iy|a-XH6p$wo%5COFDPw0DwQAb)<7vK{l)> zCbZZ6WTAcyHnoR$aEW==!BLvm`9i=t4?(mZ>bl87q8POP7l%l67> z%sxPhop5h5c@HvqMUsIUt?yp{M4cF=%|EilZW+#F%pA+Zs;6g>BwFu^!8)^j^;f&+1j_ z?QqbM85G<7@V92R5VM`=SiQv*yfeRlL&X%ED|S;~b8@pq@s`iC(ig~4qWS>*J2Z_i zHZ7c|zwGdny$c-OyA$pY7@(K?F7I~7S|(XkNwmua#xCdfF5-D!O^V(AD{LkgK}>P* zLYkJ~|LawO{SQrN9TfE&t?{K%xJ##_uCvwLPpMVK(;bR z_WG~2(~{g)WLvHzweie5XcV@*tDmn^z27*MMD;lL;rYpUa*>|*C&hPK_+8weIggQV zkgX_&SZUDN^^){R;wG_f{c2~Sh~M2g0#V5Oj+&KdR={U%cKr^O@eea-Hl;nlAV@P? zLKUnRM+8wgBK4iqp?nGf9?^)bOMK2XrMb~sfQ-%B$f_aybn0c7uD!1%Oz#&D0{>-r z(7zNT?;9Z#nFTq&lR@|P^M(28+Gz_OCfF55!2W1dG5=^oWhjvM3BPF(7JK{U6Qpy+)NaT5s$5o%--(IJ8eH3hOY)acbx)vMn6A^~iip>gJJ3 z<%iNi@|22(DP7|6R^vgQ@7MR|{E&6}k)eW3H0izm!QtUrk3eC4ZrF^CG(?J>IXI;4 zB>6|2EGjr52)n{R`zO)^6WSTE*LMNhN$`khLH5{%gA13W2(wmWO$~Zm1(4BvK;TD@ zkI`jQPfK;nm)vr2IyooyDns%RoMkNVSdH4b_lAbJ4NwdC*0cnh+w>EQ4;1zY6)wUV z`UoxHevgE_dwL*~I3A4BH}Io>^hJf4rHU)fTs!1-QLP81qG~u-SmX=8(9-(HmrJzk zbQ+X})!xMK;&t&uIlvdPXHSXTmA)N$jL<)C;?7n)!c=PmR1MfWpD$8^*rx6nHGfAr zrh&9pI|qCO8oT#>@^fqhQ{82qJ~S_W_4sqb%UejJhK=a=w?Op2-zeQIKQIfKb0;A7;v7ux` zgTv_g_IFWx_+|wk%}3TI2OZ#4mN~*-z{^i76kSUsWGr@Lnww>$yhbqp)z>ON@zje- z&y#isx+BlLb>G@0JC9;jdxO|w?|rQzNBx%ZhWYH_{kF0paf3+yEbqZ@GB5atVP1-K z-#KHr87ML7Y?o|2m0)uYqA^{(d#uS{k`ed2w&px2q_@Gf{Qw)i;_tbFF_kQy_EY9) zd`@hI&xH8cHg$sEy{2KCoDpmqE?v;V7_)3m?}Md3(e3v^5>vPpL-yyTsOapZp|b0x z%jE`(t-`^mM)_;Z?(c_cRW@U zlu^GG)~lLQbN`)CFK4$pt#S~XHcFYKu!7|M-|eA0Oe~tZJkNJ9{=1e}sS{KRoUVS9>y?BTl+820y)3Hfx7I9jWGEIXsqs0cbDz!Ob;v8vZv_}$9oSY20u=C z0@m+3KJ{jk$exJb{q>8zn-5!=q!SaysmD(EYbRxh?%K-zYRM5I4{P_a;-NOB1iD5vY7pL;6vrYG*l=5j>&b4@iqmaiRSXU8+UCtsR#s z(jZEVczoudY7Q{^Q`3%GxeI@tD9RA>fedlR#_?Ew)(=7$2XTFWPDM1sz_W}Nx6V=F zvC?|nzApYvqIW{rJ>*wYKF&);Fz; z&K=uOk`1Vd+vMi3^~^x<^3o@8&G_bv`pEN z%uGud$+ddCyL;Ggx2<5C^JMoLZoX8496FoYA0TFz_MK{)!k;8O8(W8$vP0-Z%;G>~ z4NADY(T>sPgoFelxHV>Rx36%|EwD+5`WPQoo82AZXOUH;h%nOWMqwjZTKf*!{m_*M zdhIVvE59%KjU2~irk~p#>_S_C5 zy0*{3{ocbV5?~|yY;O?j>l*y8Xp-({Ru}mBuLf#q3S;=PBFGVga0`O-mO~QX1)~EY zeqts=sIke%kpnM0+7tu*urK?IPmNNC53Ur*GDb@;{%F2=G<5leD<5`wWPCp@oV)EP zLpz_#C95KR^*6EV$Mxf$2_r^&~9T)f9W6oG{Os!LC!+yrDj4m{f zhPFD6`K>f!WTR6~%a7vj%OBP{Zo@jR_d1T{fLkOh)5E_%RsI`19rtp#7gwiSfa~Mo zDEGeV0o`#IHKAxeV{ktIxDt6ZUxO7CWpus9?pqy9X0sN=y~GhlZ@?v%gdDr#?U z@4vBs$NhQL!%gY8~z~!!RZi;x7U!PvA04{#*_LA2%2~2zt>Z^lQIb0!Y>D87J~6n3?l1 z|&XSS=$FCX(Y(I3SwNy{-AJq?_;I$@(Qy>m5#6{D;d56 z%`GnKq|p+EIY@bp-ET&cmQ0cG{G+ zV^i&33x)$Iu9*F_p0GjeZte3FQS6}MN0>D#^om7&bL85#7Lje(K{bPqGpTxr3uY4x zDe;|+7Z;M2+NzU_tUTIk>r<_`1n4ZLXQr27TMVFlKWW9{w6#rf8@UHS(e|KpPl8@I zEB@E%vNn4*EZl6XE!D>Xv4&hoo4?J(t2tfV{6hWY+0nlw_U5*J4$kWY83_xAzk|~B3WCJ9 zLfXMD!yB*^Vmv61y}Cv8=^OY5{)RfJEk?vTC%+qYPImT4jr8kUyZUjPI!GUkV1M4P z)fFMyQAY?4ipKPlYDH~enuNpyQ3%$FY@*sPA`^_}zJ#Izks)3=E|KQAQOmbiM22!rjH`s< z@-uy;u30eOXHGi}o;du0W)bhpuz$$(Asyr^m2FUh&5{!IT}Moua#~LBR6S&Aw>cv$ zYC9Tx2dC_wjhx<@l=KN9l+v-bhO_n$s(o12{Uczpwsp`oGF>Ba>H3Ob73 zA!u^?fY9>dqO`|$Q!1vmm-jrusroq`Y%6=|aAmyYVL0)|IO@-!#+{8{tIT#=ir1y@ z4ILb6n9izW)Y>}id%RCus6sQBCsf_})i261bTFU1Q>iznwLDzq<9s;*-bWLDrp|s%eP1tOJjW*|2Zk7%NxJb0Pzg zZIjpXd3-GRSlpYc+}~+mY16lkr%Ypju<*m#iK1OU$algxx-k_>!4!fE*BV2HsYH$m zx&VQ7uH!xv{T24F{9&%@*8AbW_{QXTHS9;3+**$Lr%!i3_Ajx1*K%ATY`Zsq#-5*_ z{|C1L(3OE69e6@LlrvrKa(e*8a$zLz7TDokWCkNw66H&BZz=-srM#1DV1shro5k4* z0La;z!tn0z7L!ENQ6=82%q8sM)^usaB#+C9B#eYfmbUYWOVue+Nz-FIiJ_n{ar4vW z+>4RGy_5De#-UE560*RZ)PS8(8j~jP$3re{-hzr-OrLH`;&eAf`hUK%Vf;l9czz%U zyB`r1eIBsK|1d5Li25u4t9+pBkyxEQQBP^Ge!_MVz}MY00oS9~*Y0wcwT)ZPZnK?l z|Eu>v8aU}ARVW!8{8}wtd>o1e%Etr&u?f&UI82(d&>jc8M*9e-ODZlLx)&c$TS{~x zTdirSO7PC6C8yJDr!(xEi8u% zX=QB9*md*7rIOXIwBE@fYFv)$2vB7->9s4v+vJtR?T@qd-XpKR*#IQIz zR)Z4TqJgtkL{Cl6&Xcx`xmTCLJck$q!W9D<_OmE3qqN>s8FNXqLnas0@D_?IA;|K1 zACtY*NmjG;@>)Hy#m*nam)jJB_X>W~s7Nx8x1+^y+J!V@ub%rw4RR zZkKHozno4N9!d|bMK`F9eOJz<;%{wr=I7HAtfm=uR@Bx_fu*FxF$QiXGu?qg6}iA# z3Ovf1gt%B}$p%{AQ9~&AQOxGz?V9f=FTTpj;U72blwU3m_3ewflLq-24?G)rB1Uj+ zt-Tv%DN0~)BHl-&33;GuYktgdH3%ga1{3)6&q0Hb92pF-jt$F1MqR$$3qvVsYmG%T zwe_$=_{wcJIeZ?~BF~ve36ivi?=LRCFPvXoI%MYFa-i=Wj&t%Z!UlEjncj^A!qjYj zkZ3#_B6<8^aeft;AnVDobZ>2POU`@u zv`|Vrqc~MmOiZj1_`&b!gwdJE5nyNe-wWnxiGU(et3Se3?0a}W^Mcp1tv`M^>s#Zq zW7wG`CAUS~hHSq~(ngDDq>z%0S~3crwS&l_Kv6o-r+m_56UJ7rArP(}yk~B~N%V1A zn6(nNJea^RU3V7U*FdBHP%QF|3yva2`)-9)pvk=1z7U10VJm{C^1A@k~ zLzDD}($ljKUL%+z%3&tFgFyB2IXF1P>$vIwqYO13igf7_;K3F?xw{LkM{%BF#%mER z91x-VcFhMJDl=^Nu0p5|lg*46p?T&|_3hi-JaH2L~u z|2aQdRnCz-Zg=jm!I8YdB9&*CKjY2IgGL3hL?(EoNpcJeaw+7IMa1b;%~aIGOy0Qh zCKcH6ebZmxbSPY=b3i+=6zI=Ou=mvaR!|l-KT~vlCh2wthaxWe2dbE$67vTaH%mWi zYpO*IkWzZ@yf;+k|&{O-fgBUL{$0xH8DP$$uoFuBX-5u8kp#dOBq zdf~SRw_#5&J$yA>qwvo*^w>Ra>Z`_@`0fHoj-Ib5b^j5-sv>tlp$Oa5uzdr+!%}&M zS^P=yR>BfTrNiy&fu=Z4`nr!5-M;G>ti>gS4`vIlv9LPk1%-No@(7G~qbY4E62S%YG^}0>gUESo4E&d!!nN*+ZE9?oW|XAZBp~n#2PIqF^>DlflR8eV6=liE#}x6qD1!*Em(VJqrg-ysPS- z;bWEhB3}eya6xbjMKIY^-$S3K&G#TS4i5M(cuh!Eiq3}XpA4Be2cftys8Mq$`8>N9 zf=ZUQ-*zQOYTHx*yo0PtSoR&zWn3&S*2Gfi{K`=`U{B^|j@QSIF<@EHI?Or7}~QE0@kz?uvU`}$`E&wot%sr@uz3AwJRWwIrA`ypTC;j7FqAcv4(I#PBr#vv(4(o@>s<{FkJeC=7) zJ~KytXbSJsVJ{Ahyhe%Gy)frkQ6*4kU*t0w(r z5)@<&MHXXE5VqJ*FvYJv_qdwJ+eJfJr;PX9rgYmgLT$=S=W#!Oi%Uxud zxY6*?aP?(-KyTWtL}P2~055c6`0#M-mGZa)Gp#KHgQUm)e&}hk9UlYX{DC`jLH#kv zo+r%PyCK@}n=Y2Abr)TE9w1Tl{j5GW6fUrbccny9Sp_NZHbD6FaDQ|K-VAL$sQ_(=9}t!`QV zvcZM9AEpkWESqBOZEaoHe;nCg6kED}x5UCMfDgvX6PV0AHwk107m38ZGEX(2QK_B& z)(+@i;tK2}_bCxE??#41Cn#$c`FIB>GahkEpI$sON&h-7R-)#9hedQ|l5fJ#En_D~~cRYxG7#eukxnmfie5*lLUBlaGjB_7k;ZC3_J5XZU z^7{S|xRi=}?oR&g<@fJ4)f;=ehLC!)?6>;gl-xb{wBy{!TcWd4FLx6qONejq;H>#$ z^-Dy=vOjqC@7odu@6oXAIe*P>$5_KYGH!qS=4!3cYq(WC{cB4dVl~Y9zW;!u8zjzM zqhuwIt=pGBkYNbPy5z;w$WbKQ;T&)Itnwt7N(i5z6GPS&Q$Yc{YfnoAUnLwI6f)?a zY)=cM9I)tWLxQeW)KklT9+T4!b#KpHVgnBUP=ovCrm@>DL8R)gE(Ua6t@sM zWyzMdU<(Zgr1OwS>rxIrDS1367`!njd^4UBsS?sIj*KA>#h*^$ZL6;Sn`P}f7_dH$ z(05nbo0a-LT@Z<{%B7ctQ%kb-n)z0Ui;Z6DV{k8(hNYpBDyeRFb~nrY|7!uZq0Bof zsiC=9-^_k11GzI(qo%Ujgro_2_3j9KsV!`!^pbp6nJiVd$B&RfZ+PBPB0%`H)f|%` zGslRRZ#fGeQ9pn9n_%pTtjh6P6^gZ9IX7vio~gVryU*tEHu}RQFus|PXF-bbh(k_w zO=!T%+Ui?9E{GB)D<@|}9eOzpizs9(WAi(>=`cOZBvc@R5p=lF>@LTs5{+`FCruasba1sy(Qux;z<9{>*gdI(rFRBKQ`5}^&U>XS z1qnp~n`?1oX~sEQIQh)%?gUXcHw&FPNi3m*(o(`5FKDf7l|`(cVfq{?fWU8p$TX19 zWoPf%)W^x^grz|Ok$M2^ti^>oEAAUgB6aIo5VIQnQwXOUZc&$6cqs^yhJg<+6vqsD z$H?E!m5dcM=9c`e|`M5I_Wf zxJ#J+A<{4Oi^C@WKhu9RyQa&%T^g=oqyVS+)7^7uUGcvl*Av5l`(=4cJ`%<&xY>mW3p-7&O zEHn^b8?F;MsdB?E8w-XUO~a={xJN%jpF-k0nao{8W7XZ{;{itUrZzr1_W4@hPc?{I znYO#+=f0*9JoZV8Z4kS)qs?y+zZ8}2qNA6npIox>uGLIrmdHtkJKL-mmWD~6O9aNudO^=i-`p( z?L?~3X7sn8u5u>p3KY#Hgi9tM@@lzQ$Deo`)u+(MRdg zHzRCPY;3mt`v7Zid)AQ#(}11jsREVEqUz9ES=BW#|2uy}N@Thc(!_muXt3_$V%`-2 zwYsWaZg)98VC}VMPe{LZ$V%&DQzr=)eEyV{(vVDBDd~m#+s}8Wi#&j2_FTG1zJNWiNkFd3*x!Do z#CyYR8wNxAQ;N#KJ!hy-2$1GG5D*1)tZ~+tuq((s4f_4pW4a;C@+kiQj^0Q|8|O;&9@( zyK?5*zV|P^xt{3=Fuk}jTl4g7zxRGfJz0|LSjI|U6LsD0d;8z*G~gkCp+6#SQV8rIYpVr(Vk&D%&L?L z29a9va|?jjv9_QOSsUX!)FSjcY`A&V1=OdCAm?zU=O9#2W7%~fPn(l0kHICu-_DMU zegu`=+8;mBk<{>R0Ccl2b1c=>)m;k|+xXnEcf2l6d7~1aBs`((ghS-9e+d(?#_9;w zO4E4REvkitgsaE{@oC7252W9RCGG1)0raB`dG#fzsQx$E1R<1+IozAGfKu@{L~RSU z2`CP6&8?`}b>!JFhg;Yp9JO`1BS2DHQ1_^yNK9o(@MFO3!!=6m%Ex&4 zLi!|d;NR`Oxrs#d?};KRKV5FH;&a4{JO)!5 z&TDFnqu<-0e=ID(tZ%yQ4~C-D@=`Cp0d6s+-)A@NA`IM^g_8@`rp_Wy21gIPGKcib zC8YK*D|jv!+Qm%dmKXR8+|5P#{Fg%mIF`EXYA|y1r8c7y`I!# z$2`Mff8Ho2_Vr8G#r=JRwcJu#`YS|Xk^iPeubAj_CuhfeaW787 zu-NCa7qescdCLydDA;Mmbn(p7L#OlF==CPzwE`8Q2@|+5*9KidDZ9-h!AN^3hvgsb zq&lmNF98Nz@md7z4uld$kv4^;3w!8;1OCdvOyI#$e|hmMN@w!G6Zg&psShmgLJZ?6 zK@rTLPrDQxB_W$Pok^qq0xt1Gw>O9AhwuOoCOqMuo1W#HZi=cOvd={17Jc6FZGlEh zm&V2zB;5WkHoH?OQ2bWS$ZY+$Sl0Uck*}}%=^rZD=E6#LDMmTB^wBJ{?k8D5GBvX& z)w?giBB+DI^IYBZWceDUn{wl_HeAw6=^guJkUcJuhrNy+G}=!26eaOSwugW5kZa?ouq#xMX0*H(u>y?}Nfz*!M4Y_|`7Vbo*En<4~qwr z-X)5)K!MP%{|mPYS=wwn#{j$MmbhqJ6h3)B2FZ;|58duqua$dKL4y&94Cfs!MxwYY zs>BwG)P4Q2I&OMikPnjojkCy|(L-;7iroX7F&l#87Alpa@|IHZ(U|-%u}r<9kL$PW z32)Y#>S9%_ZS|>PIYfZRZ`^ztz(eMmrfDXmrN30k6pwvY!W&sQeD5UwP{|t;o8FEe z!l|)EpFiJLXNa7_5Qx;sv21P4RIOLQzcbMUwWV?j<;b|e0 zz(WGIg=x+Wny00E4PwS-ivEL7IUk(VU|Cl8Rd7MY0yXak(8{NAMV+&_NflIrL&t>S zC&Oesl7&0#*A;T^Feka z^G4fM4nM2^v+thA8Yzh0*sN_&(MxZ!3vcfin0b-hf6S_v(HAvs{wJ&)6@2pt42rWh zx~bHuk5sv^gQQ0Qcxn#Gvj3hQ_W5?9rqx`$r8;(}U;*0052c=Qk&>EPQ$e5wOnA+= zeB9kjmeKEwa6+U+NT=8oU%>TG0sT|HfYJnL-W%ov(B@f-2mb3obX zs_K2K7avdq2_@S>i*8yoh205SoJ9HeJteWo$(<#$P3R56U?lHjAHNH#e3O16_F+H9~^KZx*4K+C`x$;RP)Ew ze$|5PvUOE>(EapXK5@V(Wtybwd()c|itSy}e+2lbEBoi?lyCj}j_^A2n0Dm+4ntE9 zFXfAy^cs`s`yMVf13nGo%eQBz{L!+&gy?O6JB{;Xj%$>QhvZh`%<~Ra z)J8Uh^L~iuEo}2uEU?wV`n>0bhtY|ZQw`g)O~9iNUF}@_a!fcV8R)s!IP^%+7wy82 zDT1S5PWXl@!#fiFaJ2E?8?H;}@^`E_;=3gNDrZ`3FlmVDQ=})e!fz!vM!^q*m<37T z0(dbWr-`+z+}oSk7`Yin_??ZxRam37d3vs40~b7oU?Y6(D#&OTFD-pq_ zvvP9RKIBk+b7&+Ny9R9^&#-^-0hu|Jo}9b^NUzYB4c?;V$pEs|CPq=vgE49l{7v7z zSZ>>3Z;F6snA*~?s_|PrJ2N2K{24}!_0|?I=*OHxJQ%%rG5nRUwu^aTfeuo91*g!I z+=>F{W;<@!7T0?XqtWOM#fI7i)G}K3es&$EJv%N0m{IAAf7&4f&i)-or4H9NMy}Ox zVo(;a>j5$Fo40DZ+0XPCtZvHfnfM$~ntq1*^Ys3!NOhhmY|w7KA<`q`Kv=D?zNyV+ zlKSVHo2;ZtUg1f`_|46f*||p3fbaY0xewbfqg6(uRsM)Uczalr5a0wUDzTU=bXlN_=V zdjBm|s4_?xw}(<&w;H-nO+7n&vzTsGTw)aGDD+n%8!TWD6oJPkJRrdIiIVZ z2{}SZ4SCF_-;03`Ud{S<*yNw0d9=4?0E3k{3v;584Tv8AP&8K=CyVU zGelBezwnIhCEzyh5SJ5P-Y2;(n%rM}pRqA5fwZ+M)_dpdk!9H|2xqRTg=+gbmvGid zYX)a~=TKr0aKBQ+c`6RZ-uYJl44iNFaZNlTS#&M!lcD|Onz-E%A8lfYaF9iI1tuFr z$*bY7wyE^zK28`2pNxg}c&e|CmpN$VJr_7qKJoE40dNciHK&p()Tn~ZHa+*Uqbi!Q z2a^=^p>R4pL5<#^P&`(nDEWD$^c!+&GF(S+Atm@7x^_{|p2$)pk9alKBH-k@4)x2Q zF}(Mv=~;k4n|fttKI}Dg>-(vq9o7e_$AF8}(z_i9S7erl*~ZU63C#u=H6_<3+Kj54ua zAII6_)pi)@>dv@7)0Fkx9Gp{6eO_c(0-X}BB}j&LYlPPc$Sr4Nr)QcD*48Z@62Ao) zx`3ZoO3Elzl%EiH$vkj&@4R)X!CKH&M6Lsv(rj66?GB|+FLnNrlmH423NCuSJZDr3S8;>wrk!HP<@ zq$6}bjYB#$-fZv(UWFQkw`W$TcbqV_PRO+|fIC-L=0h|6{zaL3R4pnHZr?;|EiSfa z3g*3){+Gt?Aj{n3)Ls0rYj9Wg*6nQjOJX%_Z!D!T*1q}NC^tAi_aKKnBX}sJRntbl z7$NVC!GFK9K@<4zL}gC&`6Vu`)F0QZ-^%NfyI3LY(Q`_4e&4a+%G@4-11f8OK;R~o2uS~A^40GZGrNl)=`=;k52Hp`LQ^o2Y|t5qe6;2eu}6Y zo0fnOVm)Q(Q<0}hnlE0=j)S38ugE&Y^x7kZGz4L>V?#?7tA`lm27bOj+e0PeGXxLIiAgfsTD=!+4d;~%{0$WaO9 z;2gbqKYlQj%N`lcIS*ga6#w;gZE&!{ds>Peky!MkSC5gv!kqU_5`38{WKN=_o)|oo z*Py3{v-~2KCz;eWNqa?xoRkYKUP1kBL=l_nyFj=N@>eb2fOxEO2z$_FLA0p0Mv=lh zZm#5FSQcB*-}HL@#~5U70sw@@CP6fjf@#-YDRJ!y3V!6~`?t$BP^S2#MLRQ*$3I=B zLxLDzzG`;BxR~9UAiQ(sQF7jAQu?3_MS*RRP*t*o53an36T^y?1F?X**7oF07=3TU zpfxlmiiZEt+ppIBR7z?AP!<5u47EtB6iZ8O!moxYL~%e{V{=yx{$#tCeYMfQJO6?F zMO52pBsKL@z@BwCjN0ApKRooZx3a2gpKwCYb-&0U!q~mUi}AI$_BINMWBAlIWk-kH z+@jH+F~GYMi7aU2TxT;hF{HDi1NK~Detrk{F4lh5_8m*H>nhlZzb5VVAS$(lTG>7) z6zq1Oe;%_DiQ+sE`?t>U_ zvvi~BH)2^_m2n)o{wGrgrtQmxX=@k%jf}%RGveg9y=e>Q4!lTy+o0%60wEl7{pABS z&7aDpWd7#bPmnmB?P^L7m6!%H4R#Mv!9b&X=b#n2f1e-jjdjdkAG34=M>O-w=I5cC zH})vipiRFurNwKYl{DzMo}w}FS)E4z^#0tcW^->cz=kgloUiWqAS^Aj51(talww*f zm;{(XoM2Eh_gB7AIJh93xe2cPNnTw4B_>D!QvtsT+gu4j+KG2_5llD~k!b{)^)n~V z-VC*EN;BjVfJT;Xr5`PFOB&(|@r`!Erpk6&0YJ8t`< z;&T7>E#9hmZ|yHsb(j!e^!qo}wKVwNt|P6=Yuz`8W=wn!rkG~z>gUq0)M-X)X4PKI zHMx*=g11-mp6;j>4NY%`0-sk^GF-<6>{$P}Y-hUb$py&ECHYpR%j-_oeJJk>zw&bB zq)4D8ZES3$*56yYcM&ywS2b;IwW&Wd-Qd+wH+HUe-naTnQ9FLSi`mi~LtcmG`TKAl zRr+4r46%&!wo(SD^8xyR=E}^{a_2Ub;Aa=`%PL%16Qat>ANJ)<$yi$1j1`Rm@k|Eb zh%yP>Xs!2E4=z`(gI(;;Tg1WL+E-D(H*sq%oH61E<}z(nDWBVESw@(+A4)?zXluy3a6PKIWu|2 zf+#KL_Rg>GoV5Q!_t@TmDZ)6l5R`dytDY!C=0vS zNuHo~pkWrQe%T+=iWzC)(%rqJcHQ|D^-%5t7q+H-- zFF~IPvU58!(#0B3|+9MIjLB#8*?pi#)A}{&caf*>>@}TKJqQ<7Pe${{-(AekXivvK z?I;vNeF4S|DXx39rLJUv>;+N*(l#~t2HrOsP1=vGt@-B=)$%I;Vymp_1%z8&dAT$a z!aisjzsbiqNjln;T%kD(U@pamBopWDY%%SV?eAq9w|8dWMsKTEk=KWtFni#%wB@&M`)^$+Sa)C*$&DIP9svdC6m= zbKJ~)3ImlFSe`J28>l5WV8@GB3Q1894I6D0swlJfN13M(MQGGR%cpjy=cEC88Wq19 zknLct87U76IR#^ZM#z1AMC`Uck=oiJ6@Ni_z@Mu-maRr&-5sMvB_qM|E-1UmkGc{h z6esoo)V5yG($EK8sGThZk~gHLLgHXQ>l5vwUC*Le6>JU{l4S|Tzu3oWE}o+5Xb8s# z52rvynDMztwIR)yIdl<92ZKV?L!U{OtwMI(WmH*Bj4!^-NH-H#^2D~K*Zpm|9(bzC zd+ckJU>|_gs%%9iD-76syWZVtuF-*BhF9w&+i&l@?dtpczeRCRz4Y#Y=9*8c^(x0Q zjAXObr|++A3Nzh2GPqdwzgm_+s~mOzR%&eL5q*I@C|@LPrvFh#p4{N(i&O2GM~1y8P@Pf5|%FM;Zg=RbeM6{Vsd{xfF_!rq|;`t+&$0hFd0G;e^g=%$QyWwMV|e_ht`%vDP$T-Li(xNHMX0j2E>hn<^njmtaO)@1L*Tuf zTeJsaV&~kqy)LN~B_#i|>v=pg)Z83o&iL#hlHw&WYh1u1g>XN{Q$ekV5=hPDX1vun z7Fa9S45WV}S4TM*hX133P}1KkGb3Ys_A=vn~h#8$vF+Yx+StqD>41y z@2e^6_oDT>>)l<)X*Sw_OKMrd|KHK-&#)?<*(~mpdr^yS+czb>cRgR2XQi(w_y5DxSBEtLe_szoT0)R62O`}a64DaVUDASdI7dvn5ednGjM3fQ-637lB_l@X zyYKILzwht;d(Zyav-`RCo^#JR+nw%or~@Ti9ChTx*Vtfe3fw9*&6L(F388ctmD=nC z0fv<%^F{%)lANqSe$MdVFCN=^qIk$cGsls*xMwfXZ-D*}gDt*UB8TV~Y^1RG)>?UJ zem81Mdwg7FptWA8SaP@muZ;QMP4&jKwhFzhunW%a!*79C@WkAf@P71z-B0igXl`GH z%j2P?Nqmw$1@N)}`Skb$dE_)XvSCW8Op%)^89KF^@`i~vnrfen=Q+kVnHG<|&n%5> zpQYQaqAam8d>B|d81Nyh#sFq`riW2s2U`_3@wai*4T>sTyw+BWVy?=YK_n`Vyq4ZAkc}a_l67>gjbKFlMAck@gllV~v9q#zsz1Mi!Nn|*sk2Tl6O!P|+F8}&$u#oh)yJLeYOl*9VKV*XyM0#& z2S1;~4DN4Q_zRE!kU-z;pyad0R-+>WwN*k@jgi(qYV}Rqdew^0mVUCpo*PtP z&Z>6vP@!8t@%+uIvM{I%sChB6h9<%1#A!8LVd*GACXn2pf|jS|Rc!pes)4lLw$dQU zcpF;jch|am-Twe&H!NY(tBf>t@@~OquI6hGKUV08DT#c$hHSH0w&&#Hv;(>AoQrA* z=kVyrJv?@#NZ|X*EjbC<+1hcnp3cthboTYly7EvFB7=ft>X%;fjMVVdZ#hUvEDj?r ziN4-7gS!m2rtAg$xMOqduPmfSM|N&qC5EP~|2U7ca25>3)cTeF7M7X|PuJCj?~AA@ z#5CB%P~z9`e#@M+{}Ihc#KC5)nzf6f?W?QnDcRfK{djx70C{p_0f;#$-B zPTUaR>*39HOF=q16Z5rZe;d~Z!Y=4snz<2W3}GrK>ye_2u5K4|^hQ$BH2SO0=n%aU z$q)xKTaf5K!n2(7&7Jj5AwUM`+;HmaQR|#S7#1q;q&+ox#=e5kLOOim$IH@J*}7%` zbeTO?&e;mU-8+yOq~xsRvrzZMRbThIy}_0tuhd#Zx+T%AuHm*WT}aacK~AXtLd#_I zxBSJ-#`#6yXqB~udX-x-t<>4|hDo_5siDj7>3^YajNk6>1>Pgg1ib7Y1)}O*?p^O^ zH;ymIg@3MG(Qkb7w-r=BMcr<6ue%CRN&c%xk;n< zO+DqGwjkT+(r98dSy?S3$Ez$LQ{WJVP#;Bi-&g1-vMH6D-;D5Z^gzM3VCp}kmhZ$Y z`)Y)Je+^uix;m2B;&sXO^TvC1|9F-jDb1>d!JrWQ#YS3=V;3};o=F%ukqEDSj{X)F zU#{DmB!~&{lgc=}_%WdKCcX||h5|jXmLs_~uZks*fv=AZE=PeQQJSb{qiN(w%ZBj$ z2KY!y`BRo@jquez(+3HS=4>srj)>Nm#Lpp0H~toe8Jvj=_N8BXJtZ1mKvcwA3=Cn3 z3UZFojyEzGsQffGxg&?7a{k{aH$Llm+zLqc59Sxap@wofEPQrUxd`qK^M(ZI{z|XM)a*p;~yME;4O32Fa$w25OgrbJ%zn8z7MIQ<3@7M8OPi~>K z;T|paIfIr!X$%&*6Yi%Qsk<(#xPy+Uv=ziZt%x&dx_cV^o*7m3o7);Gv4)@BPaP2Pl14{COFd zNYGLssXleHAjGPtQkvoK?shS9*=KX)QNN@*wT#!Iy{m5=Gq%1CVRwu%G)l|N{PLY4 zTSwQnae^*Jq0q)%Dz1OiQ({aZsD|ahIj2ehTR>d6+bJgxni@gHd32aPaUp)2yJh}Q+mnO5<91LGX5J`|6w-ak%FoY_heEZ!|9xV2+WAIQO`W%@ z5bf;NZq`%cz)nd1&0Bzg`SsG}nD)`zZX*AiUja9nKC6v)D(B!C)TdjY=&V^M=o-ft(=d>dWysl`ojM6E^N7yw^evKrV3@SbN^YNWFo=lA;Mjn~sn8Jll8_;#uKeJy9Ja&r>4UL5oJ{=cjiXgRNyaHw*vRs~E&DS_bZZUb80qS& z%d4T6wRKLTlb-I9%8G(; zJ^o*3Lsq%$s-l{yv78SiDUJ)k*RP2of_h+RN3O=8`)H>|#d|lLTm~RMfjN8s;Q$p$ z2+Ftb+)tV}nfQlHV8bh6<1sOltT|$21TzIP)cK2TNxN?OZi?aRFy5Z!{!aWYp|R9T zJP$^klAaFsXjj@#R-o9B+kh(g7i{nn60 zk>un%ANb7-G8~0AhfZ!h;wnmidj2`QPzWkn`AkcDBzbvlwSrh4>zrNo-QDLd{pWO5 zJf#DVfE9?7-1!^m`T8N7fEtcZLF|W64dc1F)ZuBnHfg0U6Fr+WYmZjZalD${2qoA8 z#}J=$&yu*fB9?e_y8f+VP{V?#n3#c~s2~j;z#zxM=4M%hdtCBXr+ykiPcu3)N;Par zQEz-C^HjltD;q(r$rxKybuK~A623|4SS0a5@D^jJ>Kb|`QN9p8RAtdQu2a%OrsTygH!$=Ct?nMmTS7b=HAW>tt^*$7d+P4ZG||L1AUkhn_*={Wts zM6RbQXXK#8GGgRGYSm0qRxrk>M857-dO6MoDlp<>iy^Xr6X^!hX>M<+q$UGxpZl!fw6|7Uh49|Cw9{0 zF_tnby#4Ew&7%J=|IMr7N230EKBsq=doQy0J?+wP0OZh?`W$4lP8z}EMQ==8-khJx zAB&qUXR+qIh&{Ura0(dK`1NMluDS7O@b3IIDXbPOFE3B)o; zVI*h}YTrZXBe;WDDjeP@D}-SiF1Io*D?i?NW)A<$G1M*pmy9KaR1BcQx&?P%%#1n0v3q(FpL`pgzx(~^kf=P?*)l9(#kr}GNH zTkU?SprzsSHvITcZW{unelvWu~huI-&4=)*Fz;^yeXR9x8>{~Q4!l2TK z=26vm4JGe)qX=y~zLSww`DG&-!B|kAI<;uDiS@fOnG|H?2$bgS!^MMa$rFcE5&+%j zGNhHR2;cWmYhe3_kFPEsi7fPb?)Hp~|2$#N27SOm?e!LNG;uH2kiW>tu!0`co7KMS z*^`<-{0&-34bhhJKTL89C|{A21>Kbjk3;=(Rk5h`1AM<$B*1$Y#eek$t+ckjKtJiW zuybi9?$6g76WmB$cg?QFvM6E$Z&g-r#=mIsj{gMR=(|mxjX6xen|n9EydtVZ5}Px- zJQ7%mv#-*#BM;4msW-pEl+jIsmO~#l^o>_8mw{trnEu(*o;-6=X{Pi^oWs_ReselD zHmWYaC!yb~^XY}(Y#Hj2MhMb`RZa;|#hytJc4x2A*QAYFOUy4DP!oh^Dj@BB|74hc z-AFAT;Vz+o1eJ~|IKug*s->14g_^LM(-pyU&kc!oe%S*0y8YV+*rXk5bE-zVcm}Fl zI8@jTtW!(1WYva{j9K^D9C*A!AASPIm5U{4Nnx$sD;J%U76D*K$0M699el!A1$i5K zP>Zne+WZP-yu}_koWV)lV}*g>%)LZH?xYXKr!mYkAxG0IL!l^dsccDf(0F4@5$aYl z20iw>8IH@8s;_7f5mt>nt*|Io=&s>VgX-OZyE|QjA*J3t{L@Z7lddBE2YBP^sI(`0 zTmh+kF=hUz+-vj4!pG{ch7{D`jOx}d?GKmTX1zMvD@Man?jN#2!U7}!vCJ`HR4^2| z%lj97Et5KzMGt6*Mg%#B4c6@Wn z>?hN=qLMsHJ8MQ1T=Nl1NWiJ+BP6kFM<_LQ`7l;p_s)N{_{d z_1iJM1ZYuxexLu6*tG%otz0eC(dQ~(;m0Bp#zU})X`F6@1F%~0-{dF|OnnZawn4oWM2|%iDAEYWV4gXl%T+cU<;!6$M1rjM7W1Du!Bo^sI5u_<f`d7Y-S<5CtVZ$Mj*aVV3|V!`OzbznUZMK% z8lRx4*|B9DD6{_cmb&xdcTeE(EK;J!>OChL957ks7Esd#z2v9{y2H0-b^44Pqn|C$ z8uh~u(Y&R#hN^-!txM$ra6vQ%6-_<->?ATs!{lWkMdthKK5vDdrU{3$tz}p9)!yQD zGHDVQc*0s!RQiJe6Fpdl0YfRlI>3edBuE4wB0{jKFaa2xOuJfpu<$?it*>rzyEtg% zx9i_Dl{szk-g|DGp8jhMJWaUKxbVDEv?BHJQcrJ8-c2WwHJlVQc}(9V4G@~W3Tk1A zYQgsln2?g~5>RWdK9XSfqZLf&4WuO?+*H{8`}Z3(4yV-?Rw_XEkCqtZ;Ss|v@o4Y| zdy&7YwoyMxSND}JD>PDhVJKRmJE-+g6p&$L`dNUA!@)4^;ek==Gk)miYS%prB{yf* z`@kU-qW2<}V5xNH@{+k?5}G?m#3SN?;Eg|+TJt@&KQ1CNV2_h}^ypr%AP$AWXaVB< z{3t&e2`c&*vA3TvdTzfLsaU-r2gyeU$JprD6IU)6nHarGPgeMdrr#0z9OcLE;AJ-@ z@d8~cJS~rHEYtL3Bmp4-rw0XAm&ul%T$ull*nXfa)$1l3YtXyXt+7~ z)e`z?UGsBPo3@ayWcD@Wt)idMK=Q3(1m~CLS4W7WpE(HG`i0morTWG7gZ<~@(~4o; zt)-LXS&cl;)2^~vC+;aHq;6th`I}c)Qe5-SMH(e|8tz)&diwgPR+z8PeZO>hmNf3c zO|4GY$qr9=mn>xGOiY$?uh8v)Z+l7_Bg)8V9&dQ(28G*UXI?zU`RHGOmwPcXWy33d7 zEb;`2Fm@1`H~&6>qR)*~FpvQkHZg5xw$*m*SQ?e%x%Eo3Xo%r6lZ>=ggJAVvC~l8c zG54R&M3Ms0LHSZC{}CH4my6flpyJ^{mlY#=lAaslm4iP%U~OU3tFPU-2F4e01ktQW zj?zf$!`sV^siIj}&?w4=p=^XJOZP7tg|YSV({<~@0vrZwnK7lnCmfeLRRwz^D&J-~ z)Gjvi8phYA$q;>YX}|ae%?n!RQU0mGctB5Qq}`bBFG7=Olbmm8xUjxw?_XHm*p>v} zw5^``EWA;{2{241*PYxyry4~Jov9Slg3Y>-RQly+OUv_*UD~wUx-MoC_~$K!1$>Io zxW27Vr;FRPa>k^6$RM7nQEwO}_YP>$q2IqlpUa#JSv8$1DK<|_M;jCBM}(lK1yD;n zj0+}Wat&EG1bCiwrh1qYm4gn>6CS!-gO1o2T*nuC8h@lxVw?pl*RZ}&uM%kKup_qm zUUSU)F*ly2bjnTWbM5Zp%EEdllt*~UBd;j9apr{GF=q$JkmTD?pKi^_9yq(mgFVzm zYWV8bEPi+E2KC4WRl@17QSe`%jw)_&R8>LAb7JaHnfVDPQG8f;>*=JXk@XwnaO%=x z$2qBnCXj22jvi*v)_E#?8%`PDmE!LITYP%Iq}=qF{tdS4<;c`o*UkSOvBx1ND}=EQ zI{}pUglp{V4N(Ivg$T2yyLsn&lr66Rx}wzWWVhL{PS(dbNnn;sHb@FpqbRHX_dO_f zL!3t2*{U&ypL_oPY?N>(eNFq2dm6>MzYevg4mkRC)H}DI;rBaWPAZm8hkHVeD)tm6 zERMp-ys*^j`|ae$DnRa}vF6qbJCKYx4H z;;SN!e0m6ya&U0L6`+TpI`IW+N$%@{aQ)GWuQvZ#wCg3)F`Du0B``{cNlsoVVQ}?Z zM%qb3dQa^pcC}z%la8|1!93l*^TqpRZDI!WxtMjQ1IYW(J_Vaw5XV5IAL)kK#vmN_nxcz+DNXnnj`|waLut zQ)#3T3~Gz>#2rcKYM%rmOyrm&AeEs+>7${uO+_jIKqY%VioO8(yZv5(M%3hGW|{(V zbLR1UjVYxuD>A*cS^4@RA=r0j4EX4^+fzwE;&_zFgrtnMqda8c~ahYn; zE=bo9E&vSqon@!2nIuExaP$m2-hD7##X*13S#|qg#aI(7M{H^nhHA)ONjAz4;I)pk z1U-P1II5yHykjIBFko~y=7R(5(}Ar^CrqgXElB{{=zm-$&O%W0Za7F6_~X(OY6l^D z4#hSm(}GgNgcNMS?18~5*av^n8A^up58TcOe|H%FdrVi_emfTBt(?2ZSESPl3{+))j>P&m*|s;JEj8!`3I)slIa#@q&i%dKr%%7bk{> zr@j~R+0l_>bVvu2k^MT8cxK5x5u>*y?|S>sYW$s_rQI%7j-k;W2P~}-tX%&wSNH0xARTr-Onx*adS5jqY?Ir3hNG0wQxqOhuvto1>FtVg5 zkYFdcoC4NvTH3yN_Cu?vq-fnDV_S$j6)gkac1=?S9^ZB-Bhv~w1da%hoNAtTyQv1jA&l$^gSoa<< zxO}5V!Vdq_7Wu zOe>ugpq-Ia?`A*YbXSK*Th#Q8krr?h_h{c2hvR@NaI8;m-h6&==n^Ty5W*oy<9YqE z&^Cc*oeB6?me!OqO7#=JeDFai0|1K!O*%L+d9hw(5JoD^03iMw0UsN6(a7sG#mr?_ z^hwr`(V`+&4lk|ks}f`war)S(wY&L8#f`^pL%_2m@pAwnD&F}Z(4*q)!z{9}6 zrh&ze0!mXCat2VuYmX?61_O^+XLRffS43r3f_ZAR5F;xoCK~aC%CmS>^2!#74$nAw z-L<9KuOmkRCNMs1osldL_mY+d&KhtH=L~#sT*(#ZvuIxV;w1(376}sVjZ4BO7<(DB^q2x5Dsb+ z{C*kngO}{!tDXYd+O(WK2fJ3RVD)qaNtMXkg4w!LD^zQ zV+X0zeQ7NtX-AY=pC#yC7fp(Y);3LLrmrkXMay#I2DJ=O$26?`vvFu@aThz;Tz6H< z4&s?5O_@R*eGyEjweo~fvR2&;;1edaX0|@c{IvN=9#UI}Le4W&4UG_jX|$ny1l>S( z<1g(q_^aTnAc4V;JxEV8GVG!S`(zsjPMEBAY7qyr1lPBHZS8r*B6(>Cm3H!Sy3`w4 z|9MgHV`X>Hvr-&6j*3f|cfMn!!02swK{&bkXwFXKjUMdPc5k+TJPnp5h9ML`_9ajn zUE?mPRGR6etGo4!5MvGe7!+K@!VW-}K4LurkC^Btp}TIMBa&jURpO8DK7G+m>tqfIT?A= zXzzb397;2a0U5<3hu(wp2_A13yG_S;74p?HQ8Ml69AuW3AHsoo`O1$5AG7@tUhel4 z_xQH?I;+Iw2|n4?-m`>dsIxTR(D7Kc{L&GryIr2tIN~4 zlavY4fRw{zveG|pqP5gtnB~(107S&E`KrNEW=mhg6 z;0@okITd=ag**fH0}kF>pNkw8>_MbN-RzYlx&`KI&-Jo`ipezHMRDdZ!JL+hZH&ee zFYVKS zO)TeDy&|!^wrUCvD;2A4X{rYG>Y?cJuVw&z6);}Zhx~Eqs~&d!GA0KqOv|*q?)4w3 zF}$E;$MHCrUOhkkH%?i83WPp0vc_!9;E<4TI7h7YOevXpbCPE`%rO4)4h({#?dh>Q z_dIsp52@N+?iIMO5p)kM4jD=K?TpB}X!5MBN}%TP7?>@oVpy1>jaibsnNIIPs&?)l zdjb4s97S40@jX`$e1$(xdCI3as58wZ^ChIlUvhmQeUqcCIA{;3qj@3pG`0pZVNL(F z$->M{s-dV!L229KI!GPI z%lIihc&&}*VwC`DS=FVU=hU}(Gr}bZ;e3W0PGJ?9quLLGrdC-4{?Lt`r;U2kpjI_4 zevcRhcG4||b2e?XAy$mv>1_{J*O^*%$M7 zd8yp<Sb+QgN0IFsa4C4)2T5ti1f*o%gn5D!m;pLV246P2d{o^}>%v-Z z{Jc({{B9PGTad-=#;r*GBC550+DG`6L*d)F%=n`REY+;2Gcs*dQ~%$tPiv)iu@TiD zs&;qe(oMTN5%3AQb48kcgEHp5(|9`9I6nKk^rZ_$sO=Dhj>b*RU@f`7qs9Pghwb`2r387$#fQEM)vaP6=a3jm=TRQ7bZ>l(o)D6?LZ>|3)6l zOD$}n9{g{h1Y7hl9{`*s>$>&FCQ{Hu$(eS*9)`&-PR`iXcrP+Bh;h*yrWk!V$w>^Q zUILZI91Q4TsHYxAp{c|~+3z_V)f{dd z`i`)j)kdS*kWQ>l~6y_&9e3I z#6FX%8o{<#A(5|S9MB5OE!s@|27g7Ir+na`7A&nKH^KpoeE>zKEEvIR6mtRctft!` zyEo|B;TRtsIcHgPlvw)gOXagU&KR(3W(7Mj&=ZUJg5!z|32>)|k-IyvVs$HAQ&V7RW%XXgrV7@*Qto?0J|_9?HM`nhMF^mv zC7T4J^c!mRIlX1?Xab20g%9Ge=`a9S1A+>d4DnzKooU4Hw(RUf!Z+0l&@G z(ox5yIbp1Q`;1(pc;4B>83f|OIzz$I4h#+(=o$SA+Ab+%7_a6jDq;)Rj1i`jeCmaV zn6*oZi5(mx&Lz*HSd%@qI1{ilCJ+42Qut4$X z5c1nmg_fo&m04yUgu~_7|Ish) z3f5_Ha*rHuKkcK2mHU1;x*zv(wWk}N96^+731;4U-u&GdB7EW~@4KdcQfmwd-#>Ek z&d7nKa!a@vzxevm8cCqNTmR?(y#d51)V(Fb37YXfERI6xKMw#obf@|J`#ThZ2RP}Y zc3D1TMXXkUJ~Z7*f8U|6_mU1L+#gKU@wC(Ml!%ga`v8>?XUGY!jea|^8!>cFJu6Ngh$AbTUCXSsVG<&$k<6ky&hv%P9t9e563O5R9^us|RdJw|mvNG_TIKw=zAwjw8y zZoZsQU|tyjI7&SRq#l`G9!nu?a0m6wEOUv zxRZ6x+jYCM9{Q~O9yuTLobw;Ia*r$YpwPCT-#i1e! z_K3RwE|)qz|AqfN^KxYA;o@pFV3;tF$0>4qrn=aT=FQ+d6$xf1iH5|@PWmsDG!5ma zQeK~uhXaI)gZ-Voou4eg68{ncnI!pMrKoK1M5irBQ7wtTA9{`dK8GjzlldtEL6>fV zX6sN}+sI4xqPe=1iM5Nx*@r6VQ3k3^(WR{+<^6D*g!-+zJEw*|?J0&&eIBJDSi`Y$ z0iFIkDWD&z1++3LhX%##{fNff-iJM!8R|jvBTKNKwa;Xd6r)`1Uaoe=Q99H$1U7)g(LzOqXaTDgbG^_rH=16h~LF>FiNypuotLeqJ9w? zqt{QULvhgkAY+(T!e$H3Trh(v9W`Y2Y5v8kshDp(y3G7sREQ|>dE7kg&w3gfqJKh` zKAo(WZs%((-4z7Jl=~ey5`tfA`?+&+;w&SV`m*F-Jt3YNT#w=~>#t1xbspMvPM@p0 zcqDmT&aM6lzy>^RNg>hxE^{wfL%=>Q5AD91XdNN>6acQa2Y`Ycx5VHT)x`eSPD1~a zpz?r+!~T>Gzq6?J>!`J-$Ey`I?FXmNO_J}#-BqXW5I)6gcan*>9$LD4E@Vm%iSmbp zFZ1L2y1pleO^~nIGTVzYHoGmJAEwtrnUTg^c$0j ziHbc%D6;it)r4F5=S7THy#Xmv>iKa)(u9#&PL9-;sL*lQk>PnbSw|K2Z(z^l ziG2pXWNCzj1XZ6~aB%4Nl%lD$D$-$w0@B~WBTz0j#t$9c)F}g7vNGyq6L~`8sPHy= zzUtlQ9G{+Bp5+1pYZXw>a$d0`Emwtr@ z^zh$AoD*x?aW=j869ulelr_`oWVK*2`)Cub9AgrFoSJlX0k0&&E69H2j3hWE;@6?> z+EBIe2%j@k?_UbLJAOO3K8Em5B@~(~v)=rj-P#7KojzaCTXgw+Bz4*|jisn)=sw{T z4C3QUlB{i_!qnuWs#(m8iMixf{VYKD#$nOfN2;NU45QOtfTzwL^)jZcyZ$jw z`BHC`iNOE)MX-7BYefUaMO>X?P|K2`h{(Ty{e||K=*=7@6y04FUz;sCGL6cj7ZIWI zv1ryR>E6GIC>|;S&&Eg%s;C z77YQh{TL*k_B>=Pia*tO7Wo{U56#Z%LF2?dWQtcZ3^OF3bn->1Lr1wYM6cek*Hl%J z%FFoVRaVsO6`oi;L0De0%R9$(Do9L2Q!j#SeZ0A%sd6=6>%$qeh>92{bZttKZf+WL z*oKC}U1^o^{+_ghYiAKIA&`z*SVrP(E)hhtvB=BNWIqFBt?96MZ&5x_60V>bcK0B` zy1^5>X&aC75|BrEu;Jzmk01~5e4NDj21e>uN0sD__=@Q zmgqP4%UbnoIK26H*p-lxm^m{uQ@`eaXIXAjq*37FpUK_!2;vfJ4|stYvJ?Ar+lW~#G^6)yP>BydM+np_{1ifu+x4)JB=8)oLPFux^&mj8i(rOcvAgwnF+)7 zQfJQR5$u2RV^PdO_WtGdzrAGG9)a__OZxkbrGV>)tPwuMyFBF5+T$fEt4D+aAAyXn z=XZK{b}hV&Cj7?f-30!q)c&{EKvmkbD|WQR2;-w%uPIS-w2p z*;xPo}!QLx2EPy)i!^#l|o>rnrj8l7VPF zhoi_pBp3aN{Ve4Lby>-4CapFeh8f+9G?)2@9=@m82;||i%AOywm#x}oN;dRE?{i}nVF}LR~6WFYd9>bjV(L8t4n_}XT2{`K% z9lH)%JDZ~y>>g1ccE=^%ZdQJ^pX}{BH6#_cJ{c>jHdrWaz}Ax}*x_k2c0fhVgvqkQ#5r%%?72DPp3t6D@nuU=2_SF-cmu zIC^1Kq6fv!c;|P3y1Ul=7o~HDB_0*UzPU9p|DGxH&8O(o)}6=ovIn=kSHHU+P#DQ% zx=R~$yW6>bup??1neKSkaeY26IU{wzm<;6})ypTY_3`l`xTsUE&m(~kq z`TBzV{h5a!8nsP3eLer|(v-E{t=gC2cH0Y#)cagPeSLYO-^atc{l?BJSvliBdp#g% zUSNgE(_O7IY8w^t+d|zG(rpYXa zm#hyZ%KyA1!~^`JFGJlM(ap!Eqox9`sovG&C(i3~x=XQl$fj!oG^et%vUmSNR4)bv z;i*}58Skr+fwcGAVULXsisUY!`}XVZTh0@g$Jm>-r@wVBVcc!k(if2k8Hf^t7UR%G_;VRryivzV!p(#Q5n(xqBx+m;ABrVfc6@>D8b3 z{yR7O)!aBiCx5E+A0H`7&;|de&->rh{xS!>k`lOzBxzpaEg&XV*hPD$SQ)Mq;mGh> z82JIh64)ghUQi=WMx@MYi3xy{N`Fay#$@*^IAXi{vaV5xZkXgLj|Y!cev7K%aFecIvNy-(CD zUO5=Eb`TO44`S*!p~6y@as9Axb@xL9uJZqV<$Nk@`m3D6apj zQL~9IhPB(Ou?25Oaw2l>Cj)LEgLv_=b#a3jgQiL~u@pX9hfXq45)h*x`c$I4u6ia; zYIKZ~kELE018w5Fb3y-xOVct#TtX2&6NdgKauRlmC>lKN8C{(hsBbE~oe{YCs!uNS zJ+573o*Phc+PQsHD!B0p88mExETZ5X5t7J^;eT&NUD@b=^w}ZBGw8b??Z^msaLjDi z8CwOqjtnV5Tpjh%LTyYfka~Pa?ufET+Z~iqfPq>K{<7rCQ%%bNsWVII%F`eixPc14EGwa#dVhlv- zR|C7xIV`L-vhdySIv+Y!hRt2$e%`dKYqH2;QuDt{ zwOMOgF0HD7lNj^*sNpIvF!j!MvFE88Is|Y0t_U7#N8DvpgaaG4>!V~PP z;JK@EzVr%frJYXvtkyQd8tyWNxD0RW&=V;OBB5~C6^m>O+CLQI5H&ED>6`@vG&?e%X6 zK;~i9R2qOC|JEu6P_~^x6ig?`56&dVi;mflZ_{1bCc2Irslj-&I4rwLK=nEJRsSVS`y#T)-1;1+NXq#>LLd<3S;K zcq}ozmU|K5Q&a$xX|bO`Ce)2BI$K9mpF>p`+Gmd=>kk3g69Hdc)~+$6?w^c*4jCUf zw1)YogK80=QnDzSWDYKGa`bU0P_k-xRh3Bg@U3rVu^H?ckGt zA=So*$FcpeM+>JScV=h$XzpLO`H~)H4&^0Pw$-eEznH99zCy(~B-kXidY#@GAGbdn z;dldtltxM{EG?mh$ox$&0-)T#rv%U-E19P9r1gxYI?Xd55_n(kfT*sa`6#ch?M!i> zwuR3vw?oBgzOn;VuOY$|<)hp}irpL<@Fi#MkHP-eo#1pCidXO!Nnfd9yowKI!qk!9+*mki?uhLY7a-dT~e3wN!yRnR$#1?n$6|GgD z_B(MYR9xlX(%fJj&TO89f>3&dKJ%0hQ@Ae z7k$GWMl%L{1)Claqeqkms+Z$``s?G3vq}D@oq) z;tMPfy!D~N6no&6UPPnGezp}=O!QTDC_I5+qmG)jnYPKlj)+CW;hm`c}I0E3Qq+>3Uf2!e92{1)=i8wStn zA4uak=Q%*R$48Cjd<=A$rSR0(TX2Bi-rwJgi%bqXH+xe_F>j$Fx3`DoWJ$Uz&5`ut zzScVU6k)I&lz;`%S`^tf>7=8wr5Ln&KZVOCC^h}JNx`C&LD|agizX?E7Z=Usw}aD9 zrn)*H1O95W!lHCfY3U1M1t1KYxQc@_%H7{>zbhna$vAxlQRgwXaImloJsm@lIxlX6 zoP9c=!&TughZI5Ysv>m^^%zoeHH#PObbC=gQsEJe+ z7P)(UDX!u`R@KQT=joa{mzcgR{B=n)aeBYAeZiu(;Ym5U1=Fmr)=hdy^`%Ra}8boOUfV=ibNixjTw4E6{Upr^$s(`l#tY{+-%*%dHK9QM$f&uT*|*A3tbc z&3>8eI1no<+Z^1zW|!Js=b~wF$$)`}#M(cstj1#rdzPmkgegAw2iSdMK>4}hFN?)| zE7DLO{&4pAbb00#I=T|SM>tdgI_O6TtDf2eVnG6qo5Q~K`eCFV)fyt32lgZ8RVQVsObamxS zeG{PhfeueBHPs~ToSAp33$&aC>#5A?b~-K0je7GdTQN+?jftTVpRC?>TBHzqSXM%b z3n*T#MqRypQ>dkKsN|@IF=ni#L=`iZ!=kN1Qt-osbf`_90zw?WP<;iY;Tw&>4#v?; z&{EPh#Asvgghyd8;6^B+1zwr4$}6d8>go;^C`+Mft-lMd@EB`aG}ND~og@Ypv1qA0 z_uvA4!x|IU%1yG}1;U8Gqh)$1ks8HDW^1u2SF?PHO((+MAh=l-eCurT1HtC|HW4Fi zydziQtFT|?zZr=mV@CHliqGP<&_NYsy~jLwQUadpcAoMIij+J=fMR-SO15p zvxD{H(gH&bA*~=?0y1=W4vqAF|NC2e zt&g)gNXb_%gYxH7#L%#Hccj^L{d^2B9e-uDYTMje%ot* z=@>p^RF8}2m_GPco^31N%RhH)WiH-P!`$w39c`6WJhIu2)r17tK3dj)2TxzXq@z3R3ic#SXx->8fNDW78STJ z`r~dk^MxuMT|K(R%Gdx}fbn5tqz0m%qr4x=L6ZTdXnRtO_w5}SlsIHgl!#H$M(kXODfRbea@O=&7|H?ovl?XJV=~kQ!?p{5=#pCUKwfU#v(1l7AiN8ej$VcMj*i zWpu6t$=nA2D1X=+kKZ2O3(q^Z<j4InQgNEmYEM>RM9r`diBj z939&M_&dL3RFpk>2=%-C45`O`0Rf9!WILDs^vU^teM>~=oq3B`qw@Wr#?7sLp)a** zn~xio>0xi?nB?ujH@VM%_pJWUzt4t3#IL@pCwwkW(Ku6mT%Cg_(NVSa-aVYJ|Ncfvi|U54{Q-q&CII18qd7UAAbtHDV(cyAN3Y% zfLo>}lusy7j*c{>eq)SFX5967I;`jToLkWvkI2X|i971uezqVLcEdO*zmUaI&=^h@ z!e6JuI?e<`t<7*NRR~ylWG6(kM9sk|Wh#d<0j-(kRsjVM_s5MMrM^KCDY0p7C<1X< zPpL1@N_e9mf1j`_PF)i)&fgc*1;K`X1;Zz)gJHrjV%pEw3Wg(TCSw2*vsJa~l) z_3IF&B9QoP9fvIQh;)=ZeY_PUE(~1_3XxW7sF=MKR@VFtxOPvwgZ@}ajbbxCCh=9?sYIAwDfQ3;mPfC(7r(QMee4YQ8AM`ozx{qEVYzf z@%xI_XvUEY7>&)yY%kXK5`~K^vU@dyuN0^SNCdCS8j_;tH;`?)RIg_{!rnM8{+L3C z6tKX1UsGUYyAOV?V~J8?e-gPgUqEr$vIrT=kVyLenq2o{cI=J?ObOrK-WC*WDfY}c zta6{4SVQMa)jf2yKH-RO2mkGh=XzXeK%{e>$0@%MYe7d(=QM+yx4VeY=wwm1uW~1- z@zTWawID+fhN%KsS__iFmM`g?$Ld)|lVj33<69g%UOd0Ilw_Or2U(L9S{b`X?qQSD zqS_-3_6O_EM;+ufnnH%t~(?X^InL9ELy?$=g~KD`0<` zrS#`ff4&F9g4a4dZ9e80ulG+@PY!Hf$4ic29sOxj|L>uqY2t6qwUWo_Zq^T`DOIjr z*Ps+LzbH-0(ld@U}GQBPkI*B`vMk=LZ;AflN zm`_-tACW`_MTT3IwDCA&qew3r<^=jKj-OpfQK+>S0Q7u8*}$VkYP=uW)og)LR~0|` zRlYv{XN)Z>`z4%k{FVyzHIzg%+q-vX4yjf2+}=6Av2hyk7f{e5-g7rVh;cB@9qeB3 ziNuD<8#t0c#tg-YMfVGYy9lWXWIs;D;zN2XqHNn{KU1cwcYpxOx#=onq5U|9@8?Lmq~r-nL(!YVeXv^5bIJv;kQ zTqT37#*1LysFaI1U1R-2uL{8Rfa{j6Yx9i0;VeW)KTXfg5DyJ4iSS3cgFXV@cD1nU zf`=txIkI*|I|H?aoH_V|tYJU5?qYa#6vTF|1`47RrCbxp5Yatc@~CVUf$ z>aUQ-L=4;IC(K{N62n9Sc-L4?a~r<(L*W@E`R6U6Etg=6diCTY795bY{E|PJB@EEw z9I4SS2=sN0MJpL}8ImO(f3$!xLUclmlInEFQQi$mdCMrZPNDL_If@*ZTe1QYX|1G~ z%4j4#BV!lvk&V&MEt%3-f3&%vQtE1U4CvBJ>=2=iNIk4enVFgfGJek8OVP~F03BaS z{k!XkjBs>J@De957sDTUf`za45!kzJmpj?F1f~W;gC9p?xE4wNh<8bOZX)Bn_YtHu zFo0tS+QePfvwe_84XvQ=6E1Q~Hx`;)&7vRD^3Ixs?5kW>x$fHh*B6-a8~&RNx)gFt ztV9T60$VtTT4?BtvMPkFS?S_0nZ4q4ul}t*KBuL(?bpD3@SpN@R$f3R(DOlCK?8dB zw-?J&Zzw1`ZS_K zCef3Wr%<+{p$aY!0};M5%9`!LH1>C-Wi{XMHH_CG9jX5^SS|5UAk>gFp7zw*uJlR{+u2iJ>qNNlaX|g zEy<}Y%?gmTt{ahfBzRy7xaVXP!h1)q-rn&=vR=prgr-7u7|71PPrZL{`Iu3fOZ;){ z@o#Xw@8%j}?0#o$X;ZE*J}>a<(5g=z?FLYZ&TDdXY2 z&IibjLbprB>@?5!zM`XOEW90L^KnK%Jft%Fs9z$~F<%#S#5?K~{`zQ@7_A zy=qZ98M)Zv2#0Di|5K*pY^IVawb^*WG{Kgt*ZJrtYliX)j=EoLXfo!EP=PgjRE6zV z%EZR|PRY%39vJ!8UZ>zPSh~dOXe& z%fAsCX?my)T-A!-VqiP}(-v@j`tb?YiwlF2%srCnPQUBmf32k*r((-@Bdw2VXlCu} zf^^;AnvHGMCo{~W(N+-Vmsmkdk6DkLEiR#x)r%QS=Me-1wy3|~Q23j|KF1c|Xy5D2 z^zNqw&f;(H<0km^_ZW7Dq>eO}!yP{`)3a<~{;K*%f5!FDWBL?pG5W<)89>r(Kac9E zl(P1xs`LZB;qfrp3D;6AQ;J3^rK%`7qc&FODR^mh?F6cFd0b%DJVD* zr(4&RiQh&k<08p_QI{k$>>CH)f8GUE>eoa2FI-b{GUHwY;xx{Bt+ zp|QB?WX))5ZpWXKA+jhAj23BVQGu|C--aDx+)jXGf3a6@na9<&3fK$-Y{|B1aGxYk z_?6}{X^3YPrRuT8rwA*j2*(s)U{f0wPB~0BzKDxZ$x7R_DK2C2kB8e#knL0Yp z9Y%zZbAj^fkt(%UMg2(0iIUdEtN71>N1i$Gc5VP*6(~pa;@0BHH-xa&<&i5vCMNla(BBvtR(NxE{< zzYzkAABbN9i!IiH(>`dL+)>E}6@a45)@C`&)(qu6JviPNaU;g{xcS+&Q*_3xz0S|~ zelRU=WNKULiXCBY1gL^6wv1rym?)g6b3h!IBkK zRpIySXSgwkgGjg+BErlDOQ~3}#?Ky+VN;gBJP+dnP@tlxzaRLj+XbkeA2xph6Xtst zfUOD<{DN9iRDAQ zeIqcMQZ^#j^dE*joZ7Hk3{`nyB_&L+NwZ&>6e(>@j8?|(xL>!ZPI$j?*Ja1wuNbaP z1f2d0svJP!A)cG3;&jhqT0R`i@{yo12moc1y8F>YZkh2=Gc&xsIu2R{{rTr^Ei?R^ zO^Y1_tYTb^#=WS{HqRFZpr^1TS~T;4&&sv^;aTw6jPjD1JV^@J);Bj-Z!S)r|103p zqG7hrERIunIkd(YwH{foXB7TnXmMcB3Lo$r2BRCC4=(|fe6#+XN{?nQdWPau_8Zm{_nCuZ-nJIT5O@z1UA!mOF!=a7Qz;BoOG z@<|he^bExIv~!!^H5X~njjgq*q_C}QrK$9rNPvsJB^goVnzf~6?V<}pNp~vuc}RR= z7%94MiZ(JjW!MM*iweAf0bU=KNJ?byoXm(ReYrH-vW!9^(bpChv@2%yRM5bDj9SQk zBT#Zt5}f^V^h+ADWxQXFv^Em%oLLgNlT)N@q_3;na&-BArh4`pm?57V<=6DSbk;ob zD*-BD0;jLqFCeoX31t*xRi=}mjAr4d!&B=+dTA#G-3vgVbDvH8={}6ilCZ)B{4bXh zm_fw2FW=1=Ni*@e$1+Q`pr}<5uG*$Si&Q_tT^53_28|C7k<<&Hd>~8K7x3`u8!j+0 zV=bpbdmo)to9)<=m116F;nI8m`<$lH-&972v;2-n^WOOx3OFXF&uy2*4;9EWYY)t4 z-|F6bFZmAn%^K~0nW`y2E!d%va=YuVwX!Gv4`CI#PNAHNKIX+whDCYMoLD z0s59#%Tg6eXe;mkP~-Wn757&Zl!fcs`h)E%{1O>qz&^fkaQ9xASM>YqX+m zgUwN+{c!9wTWM>!N9TN2mif6^d3g=e(4065Y3F!#z&G|9B_RyxToB^y+zunZr7a+7 zMLev;ml)-(rrG|e!L1vMKU^4$@p19>J{aR#q>gaqUEz3JTU#v#df-ikhyk03(hB<1 z-)y!?|K~HsmtDe9^Y=@3f$fMoS9$7ZKXc(%o=7EQcnOuzW13mD{+CxE3KCX%DCt3O z=mQ}U=8O^bgO4ue-?S=reKJtxb4vL+5oQQ-uC8*hjx)xOo5FBg-2F#&2>9MbiVncb zU}RgF7s5X#UD7QGi3!P30sl$5KK{Y1yHAkYs{vkE$M~Jt)Uw)ZE-tA(2DJ-rkIVCa z!8P~GKoICqNz%UkIAvXGEuGWUul{Amo}_2r!q@MgM)RbC7c&Je;GP$7!91t40qUmC zH|^K)(UYmU8)7bA=`Ao*HSp0|IQM6`AC0Ex!(1< zwgK8HG4{^$Vy?hlRrCLqB69_~`5`Vp8wKA_2TSC7;$(#!=vi~;_dE0LPdD}ThV&!4nTESd2ty!+qsPwTS(=4SBKVnP3Y-Mj5)N!o1c z$&AVq{HhZi(Q$gB9wLm|I8lb+G;O1=-tQ-VXJUOzc)_~B8YPeShDW4+2+!742%Pmp zjHoO9h=+OOPxFU^KX{hX>pzI_6~=0*-N}3A4#%K)Vi8f}8m#gzYk%;3d3vFJ@e&y} z%B@KTefr48^75snIS?Au8Vw?^G`9nyL<_m5>YV?kGi}BS%GdEU1@Ju27-{8sAg}DB z8R3_BeAaPKi7%cmW?cVPeS-nD^Wf#jJg``~7Hp*MdqRTnR(#a~% zhS%B|qgW&6l_=!l?D|5DP5$j>l0x$foxx*Eo5ci@!sZ*z+EgIGtTWeACH))O00s!# zWtD^FoRf@jXI=fYiD=DVKd@d&)7wDJWbZ{~|6xg^mtcShA=)YlCuddfjuOdwAZv!y zp(GfUq)D=HkFo`VII(W)L^s)I3`8+dtpX)oPi#=_xYAE_Pt!?GVI?R;xYJvT2#pZJ zu9Fg$x%isHZ920RlHe`J=6c7!xW(E`jm2!@_|WXX2ybS3`ZSIaeDQb|{0NY*hWxLB zt~On(D-R6Y?>Y#1o`lxVjaX`d=#lbfc$}sWKjR{79w&-bQTVsro14s690!0+xjkHh zoi5-#%tqw?IJD`d!%GK!0=PR8nLsC@qbFDVjOcJV*n*#mCx%HvN+@{qbgHE)2Ev^G zLC4_* z$&;140U5>0x!Z=Bf|+ml2N|{O*|*y#lH7CAAaXW_F_BkGbC4n8%N5#?NWs5OuiVJe z<>Sg|TD>YnDDXsc)Jx}a$-j(@=nf%&!+h=CmLCF_#2_?rI7NRN82-&+gW7H30z`JS zeaf<6d6Dvc6;^0$cs7eVm0wV8nziy0*HA$uq&SWYP4*SYh#C@GFe3s~ozP{YV|l=_ z7~r)w?)TYH` zf96m+k2g)j?uthiUH8Xq5^hR*WHx=i_lW}k;XJ6{l=g*Ayjc%9QWg?$x*<0|FI68{ z?QVUR)q3{Zwfb|4>qA_kd?B7O?XkMdJx~3bx zJcG`r%`JLm6T<3iEN>7j@nNA>@dYfOEXpwGi$HW*M8whH2r6s*?~=p0m{8X6$OB5W z_vrj-+VA7=*5Wltq-8O0gl8ix`s7$bB6-#ObLoe3KDWAXtuY#ap%hy7#cfUN-9!xE zqSmbXa-CqaYOTBSoF;9eY-fjXPfHCIwD`B>Pi$W5fUHc&PTw$sW~I@RKq28o-0_pb z(L{gzx3dY<2N-zBk^h$k0H)#B{bJ-*(P40CQ{fs(OL{)YCM* zr;KfA4jC!TH+kgQ>YGb#mCQJz=$mw92>tE^gYisg>9z!pv@vC1`QR?mvjO1IGsn1`-lRy^7sbcK`vutWLZe>Ay(TNJvs|uiUbHAn!38W z`nBT}YSva7oZtIFV1%6Pejr$%K_E!q@*v|?aYGaY4uRKCY=}Q8&<=|nMQT|S{u0Ii zuB(zD_t5}D`Sp>6aIQ2X%XT%}-pB&SwI^ON?0^id0 zW#MGA(*2xj_Rh9?X`E@j>U00B_8_c19O;zkL|;pw9yXz3`b?;)5o+N!*0CMD5#!o% z_OKnaR&h&^?Q^x*gi!F?`D5jNhTE6x^Frji`{>Yvv1^Cmyq$|z!SVm_v3f z8qqw9naz;T4>Elp+)70j4*#r}Ym{m31UEfGfbIE&rtJhWbxlbqi7^ivN?23|yGC9s zj0L-NV%^S+%Qak7kozALm&ep`?6(L9Z1A8KEHt-53+4|~ZSvX$n2f*92k)$$K*p#I zaeoQbDbOe)^^~a)SlbSl7Y9yO%MaoASXaZt{45HzzwEea@Kxa?5T;k%zsja*K?4U} z95KdolS>OTX6DPIiZ(kHJi7vT>#e->Zp3KdQ1>cr1u+zCdn@wKwVzAS$?^K+5(gQ781DfVMBRs$^mBv*F~f+hdD= zzmNa-bh9~zEHuYKV3ANA5BAuvJ}P-@`{%#sKf;i$)8vJxTawcG*UaXRiv7D1ZCm^hc`ebm_A{nh%r|GG!si(nCQ`z#jYIbfxyx#*n{e; z+$Oi>!LPTiP3$F^zJWkpDW%ff$F+;Ex<9<;ctt}CX4c)U^Uq89>G72YA8ljKjXB|o zA4T`LrZNF-WpOKS+@)QIyj%feJrbQ;f zX&GwCL1Y*(q)NCn<30zPL!rD9tHq_#P7kC2iDNCak}|N{3JZQNg%5==G7slI=}uD? z(?YdhRYvwU%KT2`>dGn4xWNL;>1GY}tVduyw`$x;8-KYh!=b=^Ro$fU)C2zw3UB4l;$qI14hbZHVFeOFu9 z$7$YNR^}iuZ)_|_WN5G;CMH$=oxa{Z#(Det?v~o<8~4m0y0k7?OiWBg#l7&9Jyq6M zLkpN!<2Y~oQ4OM<_2(z`T?%OirPkR40#ie>oKd~t8JUn-JyoDP-K;x=U-c?8BQ0D+X>V7?RT3JhU<_`O>|9M>bZU;AawI@-JdBe16?W0m_Ao|!u^qD z>=P8C2?TT;h-7pk%c7L%9bfhC5I#(3S13f2bwDb7M1^l!7 zkN<2mJkj2&fw&;DJ6vOLo^p+N*wK!8kO*3cZSd4XDBb4cL(jYo_QQXhzOe5n4at$t zi(rX5)cQB1@Ly6C{%7m~Zf@m-jJ?lqCwEUy&NYGt9)^~A2)y#Xk>0obr3d+3S0O^t zvmT1}N7BL*Dx`cir-Xzzym3K9i8$XxRP1TxmA{}7M;f3U z_2=U86fD28@sx+ESe=uRu*cB{apka-3L>!_5w?Xb;V+=N76pUvmgzL{Aws% zZw|%&8?A))^dH;mT|#<@7YHC;_qrXX{C*)TA5Dm@q*)*3;5aJ=m7W0G73}PgD5fx~ zua}iqsOnG0Ku|8OQC4WPtZW3&B)wapkPz;KLfc5tt4i#DQQ_?kpJbId=s&4^?}q|1 zqGCj4u@w`ha;BcmG&D-(uatMiO9muJ{dj#>II=;0QazhGF3~kpDU1Z z;R&&JhNoed>V!R4qlo|kk9^mqYFN_r|#D*Px~L1!)ktd`*?Z$2n*f+mO;rdVNn*-3A^7 z1Eq}j>x|LKqnDsG8J=`5Q#kwd;1;zZAD5pJNEW@zLPOl$>Cce=;yALmhBK!I6Z_sh z6wow&Y$vo#F4JoT77oMBu6OkVpNqY7HD5Zw=4Y3x+`X^Y=E}@P_bWZYDk*5IEZT5A zD@R01!r(idsWhu?Ieo)zT7QkmqK1j0=ki*ozf%-%yE*0Wit}zbEOHVYWHaqwhf#Bk zUXO`C-T@yQfgcoq1gPkC3J2bd-v2GRnSXtOdMrRhgMPk0O^?63am)$6FH<}}@jPY4 zpZb32b^G(4u^6O7 z?bbe%uGYTh6F&#k#o{hTltFK+dXQmQ>yWWOoxBv6z4BWu^x|6%zqakwHge=Jigjj` z9M68&GEef4CKr`27OOgT1H-#T3zX#o%6(h9tR9HFm3cUqXbk6hyq+UN)}9s#c^eHXXYA2aedV?Xhq^sgie%%BLbfyp@l&z!4=*8Hh2|0N{*8h{X8}d^ zKIUSm%(%<0g@DpYG-+B#7{L<3Z6Kra8k8ct35r2ez7oh?;I|$2sx4Mn83ay@tOwf{ zr!c;fWqkf2kx;o;{Vfp<`SnW(LpTCfZ%KwSq$Z)@2PJmZaZp0pB}&>YlUX3(&N48! z&atCaZ2Z@cU}g4VQcEz6qPEVI9uVE3hNDqnw_ib_&?R6XYKy%nq`Ggry)8ou3Zd#A z;Q4_E8&Jj;UUAX(v0V&PIg;INMRqGTHM{W5=;{QeP|%0%UwYC0T`+}lT5YlYn)*KR zW8A5P-Jcxs8>*FQbKSY5Z{9AGIynSzljgyZL@D6D<;-M%?Y@Jj-+OdCg}6x`B$(j(bEwxfL+h^FNZa zWIc88wFypUl2=!aVTXHhyc??HPU7GkHEFI-V}kSZ&9@)&yNrw+P@dy}oYew0Pd6(n z^qq7~goAUTV~yL?%I;Rq{(!Z?-u|feB`$rBoq?_{gLZSdY!Rc2Q>8O&{;C~!Qw__C zvAY)OenxXf#_U!PL6e~VZS*h_Rz39Bsl*7AjLf@-{$<|Z|a zkTO#20#Mji7ZyH8jI^#VsJKDY&uR0ImA?@3R^CicepBKl8|0nk<=Sh1tj5bv1*G8{ zJOw9H4ICB468`ZtA}zJGBDwYJM*t{2gfL5qU6vcf&4vRQc%vDzgM&RAMaVOLi+u+s zOjl~m|1Z81`oeVZ`n@m>{^x{^owxUINV@j$NA6O$zM;TiYeAJu2Xp&6d_8vD%Tx-G*(lgrui0{)K8Xqbg+oZnJ_~-q1sgdQC)n zF((i`AA$*Ps=x_tgnqjtL2@8Mx>>L=9jDu{k;UV zh$1=)em!7|g|9>cVcjVeEtZeAFx0FFT~89&u2A{A@`Wf)h$lYAUx87e^2!&AJ{xx8 z1SRPMyzU?ebWAtx-x3ekOeVyx(d6E-IZbtrL8;zmW3OBrM>b4<2>c1lVOaLaXgmDD zx2p+Cx(&rIsI0E8s)k>PR%|Z?KH-^NSTHd8D)%J_eDLmzji`&?Q~haFp8r+e7p}JAzPZ2swk_-=bg!}Q&b+-bcCQc!$*@NNAiSl_$M&%Mx7Z)d5(SRS*yTC;p zkzxAdeaDo8C~EM7@StLz??d0#_7};2D;(S&jkhDPf(8|82Oz^nH&<70#BM3#bG(wq zuHQ4XaNuONFl%Bb{%-dB&)e#68{c{3)6;B240JLodc#HyLV} zsiXTE^fN5djN=a$!@8f*V}g_zLG(K`d}3&l zJ{G~cZz5#+IUp;ufRj(0i%1hHOfk*u9fbcvxTek(Q1#W@^1@nw2v0f)R+*TQb3rpT z5w_cvXSq7(8QY~2{3!W^s?S?{dwT%=$Fq==_F z|82poLiR^xMTl29Bmat$(gZFh2=&n{ghm38_op|eMFmoX7aEfjxDQ=q9p_RRR_vz@ zj}1$0pK=IXeX&Jv8FD1$xbEs7_r`8e0gnu6&P!zgxx0McPE^9B`txq%Ll4rtn8N+d?z{~jl^$Yp^P zKab=Fv0+NnA9U+GSb|w8NNc8k+-}U^msX{jKh5853+2JbYaRwO2r-?1&(0q{d5beCDNl~5r{822~gX=qc!hn zk)+wo8GXvl_s{M2O;X5UsvwAESj_aLC6+;8(JzK*EGRz{j_#$6A!(1&53(;T+M{|o za5Ea4UJFz5oWqgw;pbYqddgp@tO&L2*#_%o9r~2Df%L|1Mg}aHdzi|waGbQvuiaUe z@MQFZB-?&VSvlajlChT%6Pk7q>OAgQS4^NaF)^7rs(K;jBCqlKojaK?@@ycpU1@k91 zYWD6;TJnF_Uz?vlR^9&68VZo6!e1r2^GAKp_?k^%Hd?5X$wm2#nc zQ5PQGz%Cs_!t`|H@?U&k3ANO$kTL3a{X{1>b>~@}gpx$74X8?tFjIDB5t&wU>`A;x zO({I;#?nttHrhjt1gEa@_e?+1Sv8&l(UxHweTYer4uoJ^3}+K@6A#eFZ4)R zKZ*{Wk6Yb-y+;CTou-ls5u4;^1RS^$YrrK!V|28^e?D-(?W%DZe$%e6-u=a8O<6O7MNFtmVSV^Kq<`Pb!zB@^>` z5K&=4VFI0tfKixHB}E#PiHvZ6Z`IB^$K1q3{9&W^|BLnmSrvFy&`qq*+rWu}r7SW2 zv(iVz<9avW<2FzPGIc23ped2retXaTeR`i^t&csi{)dB`zNdgYeS#7}U#{;P-m2A^?{ZimkpK#pGC8S$fA6cO{lRY1 z-gu(^A<}2dLHFLag<&PYnrB{W?!SKS=o(gbL})0fAdOCs9u|qQF6@dy3U+#r*W9}$ zMnfWjeQSy8li=UX#7dE=*H*&d5W{~%7IEUjbc+V=LH#OFR-*BHJ2A7*%yCR)wWU}> zn{e+k-Khq%NMuy6tRRB2LbM~%%kXK0|Nggp97z1Pe6U3P9LNhP(Bx_GjJs8H{5O)>aFR2&t0~k zoRK!sWuW(}K-ipw2Z8wx&d<#)rrm##_z6>+WLH=jt;Z;jabVc#?B1O&Tf(15m8z^D zVCTuaJQTPYm2nI)D$C;e(J&)hI2@m9noQg1rfFGgj#nua(^_$Ihd}0j{plhEGl75x zc3s1iQ35$6q!l1NkKNxs%j zw&TbsQ=ABT_Hk#z-S%!T`=n>l2lT(yZ_1;ZhT5l z%1KK86ot&+XSnWX?tG!+n$lEp_2X(n$fltJquC~5nl!i6zc#FELtT0T)d$A2M^2wY zkeP;LH>q)<&x|UgoK$ z6>SWbua*e&?xBX`?-MK6k{BU>sA!j*)xXHc6 zCv~JPki?@_gM9niZ@pJUopU1L!TjQ03aJs?^U%A@{D_H z1G4Gvw-#NCSnz|;Xx?MqQGxKzleN3CJ0H)z&+{Laa3Ecj->yHNtR--^{hPo%zu3&> zINx%+gp!~qhx|!pJr@ar7S+qju3!_bXJf*EAnMsLE`;}t!T$*e8cn!a7H-0HUYz$5 zeN8n`+Gp*I(cCJ?P9&X`cI7SaYz3E1!Ck7H%L!O$Ln@m7w_7m>uJKmKWVT@{zIsku z^^}ud!JoSMxmndZ5B{CPNUpz^?8k$m^rzWeYJteyD3T2B=B`+<5&$cCuQZqP&JsGJ z7nhh_71{r7iKsNXZJJK|RNv^m-uPF7>s7=_#fZ6D~5&TPuFKM_IP1An> zeQep3G-V1Zb8!u$&sw_Dlve0gP{y$s$LU7DoFoM2kTw4x+AN(s@GSO2d)!E4Z#)eL z{q1+1z)&2BT^Bc4aUJ-YWC%lOzD3`w>@Zbupzl!HSwhgI^S)&;VxzOcnL@EZpgMjn z6?-_59a}ExK1~RTr6rT>kkcnkc3skNu%aaxjN}1DMqf&I#s4yo^7v4-|C-lGf&H|T9|@xPYjcBh16y4x_PPyJ*@4IBYo{uR_S2p1 zybp~O31?2RBbN>pQ-43|iTd1+2$eV75Io$qj)|Z3a0Q$U=iLo>$5fh#AYESn?f$Az zh(?_9Q5|JrTN;D&M%p*m$Z>m{{As9VXCC8vn~^h}aklqxV@RFaJTC4%!1|tK!G|}9 zi5aUOy#Gsk*{WYHdgBHXO+?QGBgj*qESRP&{mzc7 zARiM0_iAMgiBo`U$4t6?iTyy@6SD3$hhly(CLm>i$Qyiza%9_vyT{M6%Bx^P8nv-2 z8uI6N(e{jrWt5bYqa(FbP`K89=4V2>AbNRA3UI%V_~;o;5(Xu9Ww=XIXVWt4U{^~W z%U~Tx3Zp)oPT3%@*wt?mKH0Otl_geweLX!`*cP65RMT~9>6n`fp`(iz z?YOXZX}&xDl_1IK<}`!z>@7v-l)JK7wS;%nDKYgox?%xIpp`v>U5(D->JHi9eS%ZP zprqh)W^WzO_J6#-f@c+DMxdFcYaaBn1bn_QYiFVV%L1^>h~Lm| zC`OC<&L@yz`NGb2Q<%B(#C=cp&989(D3(lC>aVs_e_ZKi;@|$H1U(u#>$Sz+Ih*@A z32;+B(K`h)B$S?p&3<}YNvLdqL4ipDjz5m*IGAU_1dsCM3t_(W$Amz{9A!hx5(92U zKx#OVO6+4F(7}Z0pM<6935h(42tlODrLER$)0_6238nsoOaiPdB)+A=4_F|Ed{#Ms z5}-)5*7kl>T{IK}ErgcvVn-G7O3U0gX_og>AdQ3qlOc(s#Of;?c2;7#2~H z(zT)dwMIRJqQxV23nWC(G3>uYk-%(Czk6E5QeKJ%!XS&8Si1vZJSW zKZ`MD_ zDUP=`KN&8y9it0Jp|`zXRV*E={LA+Ijf3O1MO4;>!})cex^4Ifu@Dtmw~M#c;FtaT6S0Cv!9N&xxH)g8&uY1c&^SL|kM2ioaNeL4@=OsEmQ@ z({v%uFw21D`%?M$-mYU`bhb86Yp+SznJ1dHwk^1nd)x1Wip`8OT`A?mb!BMA#>U7u zeOybWq=N6}rVb0#_B}DbR#w5;-xjUkGk5r)Q#5(CD6a}OiGH-_)=FO z^0(KjFwf12qkvYkFIAJf>{bOV{mE+V(d=5C%LLs!ic$gY7rzJhq6T{#-q0JEIHfoK zVKXoQr+w3M<)?~86L>5iHA^-%LWw7@j zI~h1pk^&)mBF6{_9Epa3Im1IZ_FAutrChJOxf%AV%Ior}SS!|)!&Ecxm|>{;q#6aL z3Z^AV8YG;Z!oG|?*Ykn@F8o`$Q1RsEc?YW( z`_mfP!fvkKun0;?NWIN>YvlYZE#WWzR(c4c}pMb&)j;y)o}9MfYSlFszD8LKz=wT_1I=^5s|0f z)_3glaJ@}H{!eYKq7xSU82tF}M+2QIt)Kd2z&iESV_~qz$*e8Wc-Eg?@cK2w+Cul; zS_R$yVid?glVoY#f6W&C6MYE!&!9|js-DWeaX>3x{34^|nZ)W)rR&2K`OQ*6y7lF| zj+ZfSc3z)2s1-%65E1f#KN-Qv`f9ObkvH4{?%F{?+m65dr{pzDS_Y$F8cYjw)>uru zzrI7pN@*di@V2q5nj3IQMh5+RYoV{630&1eQ(fvS3Sg$2R$WQH_ zrt$_#ZTiZFCWMX;hh3mAaZ|os?*a=A6kSj`O$~>!M;Azc21OQufbc(~a<&xfsHp7_?^TXO zq%5!|Iz9vW8vY{@6!GK!E+eJg8rq97JRHy5mkf1mDdu<}+ZOnl`t01yO=?r*ts@+S z)%%Y{?&}vFhP925Wzvnc)r{shZ+8b=1!&DuNbtZbAR5q1ZZ)$m5FWS;P;dmj zB<5saSHNA*Q0m=cJZ$H37K+PX&V!-78znYmKL_xLVFI{yNe9FnTPYwP=teR}HkThl~u1gcB` ziFl7y=?zw4T$AX!meB46`PTM}fE7uiFB2BCM@P@V9!a3+T-UK_hY>$#v!BBwujy3~ zhC?wlSHcc` zZNfXMN2XzqCp~QUHTJVI9F}-+Iojyns8=zSbx~JeX!#=Z#@N*qW-CAVD?j-9G!0nX zRECgW(p2D!l4fv0_UHGP#^e$0p*`0Q?Ga3%=Nyv9eStgPwDO7V&3g4Zg=^~F|ZMrIfvAY}62{&)-%C+TI@PlP_$IXVV&Q;4ii%oVVF zNl)LNbN?Tj-ZL7`_Ko@;j2I+(5JZ`XE=2DwdN;Js(GaqKnM{8Nvc^&6I_Wo@QbM4HPs(=M07NTM1+q@l8lcS9)nhwk7avx6M7A1@Ev19eNa)l3xQ&dw__F zT8VvTb9wx?ddmB7+oNf8X>RWLBW1y}$L1wrN8hh(mnO2t9zNZ>1T*>FFJ4REvtF5B z4?T}h?z~yeS-l=TDPHYw>n7xBKOS`nI=$L1xR6ilf2$>Vh6HfUgRBL>F_2ZfSxOVx zgVAofnR=`BoG8)1&4mG1%0}!ctMq7Qv7@6S$j=IMgUr5f3%;n4`hI&on=4vE>TdBk~^e4*9nOzP58?5j_wtO9CFX0YaEa zg?tmoQ$8viknBbevA|}_Pw5`cT;}k}B(@&=>6k=qiK2FL^rWs6QFwmbOF75q{=RIV znxjVuK%h@i;v;cF56tg{klL>B3=3%MZ&#jLUsQM2tNA;8zg=``puQ?ZAq$sIrs~?gUm>slefRO2%TaQJ3&*cdw`?u8|q@VR@b%e zp}(8X+l6KY(v7A^Xa2rhbdDr4vX&q?MucmqmI&MN9llBlXQI@J3`)U-cF{z?&wl0k z-qvJLv0L3TpX2aw@V)Ir`$#<(C+PCuPCd%mTi{TiBi;`ssM>1z{(qyE`&|&i4Kt)j z-S>a3U;T|u-u*qdmqW0oS(RTC+w^ww6Lr4zvP)d^Jqy$o++34c2NzHeC7$Xb~SC z9SG4n^3sAxxhDrBF!ZZ?tk7wV2E*Br5H+kk!D`)W!>n;8>LHAXe_(HZm#O=rb z_ps>(q-x+Zv9{L#DBv?VXPbU4@om2Eg^2IThR2vBo)S1GQetbZV2gJ3@^|QHT4LV# zKm3oHHr(3`)Y6x0YSNbz!~4@NQj$sEUNVpHlEz|nTQ)L^{AJ3_@5rg~ABlsC#G~I^ z{+k@I4`JfJDe#-U{Cb}h1(MBVeK!~M49kWEAOp>aL2#-O9{b76gLRc`1k5l+1IKAq zB#i-wEHxW~HDD$+E(c~35|!Sfk4RJ4al&E@1v5tNj@(@cXUB^WD7?3Ikyfb-yL-N^ zYAyggXftFEfvxl^)5Tyd^WV51;5uQl>=ZQ+;y6Lz~X>eQ_cq%#5b9-_iH^=q- zg)72XP?gnwm)1AeLzaTCjcZJyWZ*3)nmR0;1>!g@mPEs9Wmz@5t6)|FIE5Y}tR~kq zqh$U_JLTI{HI&%HBoowW@;<7vAD=9!2&aBTv%`}p7;AWIsNw5u1PxvG8j?_gP<$wP zxT-xoe)1DY%tWkTmc$Mw@=^`Px4Lqp?SG1SNk(&ji0C#-jO%zMf?+Y$2Vg~ zW}OX4U*C&sfMpIC$IVve+Z*by&e2=&16tZN2P92@=ubwor!hWi3oI*4wl{Wp7;QIax>uCmnOPpw2By3PG8tbKPz4XSC#MfRLz(V-zZIXOqf z*ThS~=5%_rqYkFg{>!o@w8WDCAi!eY^`QsAnw|bHHI?dR8DeR8zdv?g$&G|;@|Mr$ zAdMFn+1GqX4F871}B0%O_x z-1z>huEQW|*|ue6pbz+09ak=A7SLRH&z~qAq*?gqNh|8`hp6%|PXW5u{8~6B#fEwu zpC%X5U-85+3doW`>+ow=V(J>k-;=myN3;7TJ)NmzgLP5W&4&QZeRZ`h~9(zpZoZ(r!o-g~o%{$z{ z>>FXz=+4Crz;$IPq4`5jDBS%IIx3CPeI9dQ($Uy?WP7>!aI+jeeDM4hvC7qXai>Lz zz^_N|Jv)r+vTzlVAgP^q>b9*l*tJp{1BWmyqCBE(3j)tgRUJdb`N&vOC*8lWH! zSVA6^3pRdXmXM{^cbTkjZ1e}mS^pr*sclK#aSZGQSgY9w8vP1pAz>23DmoUSi~@=| zj1Zj?pil9G83j6x+$EJv7M};l_sl{G}0vf_1*JiLuGI9cq9FPVD)G3Mf;PrA~)K;ZF9lprqF2DwdO{ zOA1CdM)|h5{A0-NdbgO&Xo&sWYC%t3QoJxrgK&tY0G&Nz?@W=`)Yek3P9^$x@SksuvYk z6kGqL)N9IHU#ge}6XJQQL!DVB==5rUih!FH)?JzEg~kq%lWNJoRGP{vVvZ? zj-L1~t@+4OnN^EHEoEb45dQbes$YFSn)yl_uOYziH3O#WkSI3rcIkxz{oJIpv*};U zZ;drk&`j&A%wAFsc`#G(YcX4laUs%Cz{-k-Mj&H`NY&cYwypDpKR8`&hham?!0XY%(|z%Y_rrLAQ;z?Z{Y9QMs-ju|$d5iO zJ%^~C#=B&`fNES?gpO`1T+Qt+6T3B|vgA&~)+41`k9#uA^%mIREOaCqlaPpcNABL} z5R&nq8B*Nslpsr48CZ;@QJF+NtCWvhGTxs-b;`eM?&Kd?2_V8-=Kw_|39g@;|W~>#X`84dp-^8njU0_3FPZE!tXCK$;B8N8u3d zbTpq9(aX@WdcruJ@F?p3r-=9&%i1n7sT$s<_`JqKA5l29uuU5+!w z3Rr~+p3ci`$I+Y`7|<)p5+XMwuhR==BCQSc^6!9E;MiM-{`JxINltDtMqr1+9)TNX z&J^G7)#$q<`~olqLNrgdb7Aj8c_H13#g@yKj3IW2G&xdTRZ_;HOc~a}W;Rt4S(0r- za6A!siFt@DgyNaCJT)X7>scxkSRQKZ`HVO9IKq{mO%jk0zkNNC!p8_Hd^#a8K^CrZ z6~v)mVn{v5{+tVu&-`=HM-FHr4bV81#FzCFdWB^u^H0){QRE;~4&PVb{jKF-#<;_eIeI5TcHb;=|`Kj_z4nK46-r&yRp{M zEn?)pmgV(6J4w50brj0(n@XvS>%LxeF>{(3Ash>4B`OhZTFTC0@b>bqLP_o(WLyPx z`UkpP@WmV)9hwDTZWN^2-8WSywH)KETsnewCdMRdJ3T&n+vbF1By#T`e7v}5jj|D- zVfuZqU+v9XhZ}2QU+?z<)IcohX`Y^_S()GJ{$cU8xNH2CVMOjrXAyPBY2#84Ug@S( z_~FLx?Yi9Q_1WF>fm`tktna-LY2K8h8*0T)*97G3ajIJC&rA0YIOcsM=&2fIFs-N$ z1~!(u=90CIL4NlBjs~=W*CQ_?kp24Q{aPdODfdG|Zl1Z;?k7`sj;tmbtF50kpR`_m zFDS83wuNuD>%XIUX@$@w`3ZE$kJdpUY-6Gtcr4@n3C~%(P^e|i(%F0yxpDbIb~7V0 zA(qEsfW$D}Ow%6dX7%v9kn1$1RC6jv&sJ?a7xEe#i;GJj+I3tj50_al9hdZ_y|Ig+ zp@jhb>x`HZHZ@X;Ncn}tBgNv{=4J>ZwlnV^oRAqT@z3nE?A;1$t;^`$T?anRQ!erv zOZmJo&1{={n@s@6&&ZXR*3)hR2H$p*7Zk7ytl}N!$&rK5`I6$CVg+kG3ik)m5~pQ6 z!50f>4{MmEe>$CjU-TAkehrs?IF)`7@wNbD5(0|1-d8vQhriK!n7g2dzx@mk>M;V6 zF(2qq$_KW&v|nkNKoZBXx08APV@g)HIS(Co;243#^}Lw&0yHp8tVECHTk!K7V^VEr zIK3+#1)k5_{_m)|X!f8-$Zy*>_iHiENj$*4t4)JhrQ{>F9!~v($9a?Fa!IopD5QOM zx{1yGA_kh)3F=>Dg5?Qf72!z5u^v*N9^^+&ALEzKxR9hrh%Iw5u;~P086Sj;DHtD&ur_9mUi*s)>rob2OdW%hDshEfhbH`K!k)~#4Iv9SnN z{<-w5g)@fAwRE_VvTl1qr4&iVmylLzN8#0=YTZt8qEqoorot%u z1sDy>T2!N|&NS>j8=rTVpqZ-hAmA{W^=^3Oe|LW#zl>U5=1Q{+hD3Gm=dvMoN3)Tz z>bFQ(>VJPu~ihtAn7Vj+3Unw{dVMB>1Tr-{LV zJd-yL)74y1>NT#FndA#Y2+<|@FTds|WoH&Ju14flP8Iv1I@~rtkJ?F$(EILBn7KG1 zUdS;+JT26JJce^CVwl8*J8Lp+pAl*>XGDQy?iF!F)bUs~t1`8p;Jq-w<|QE`6NwyY z1WbEe4H+4fPc4&5_rWB%J~pDk!Oh;`HVAzaBcm+RZ2kawk@x)4O~)7Zp1iI6q^Fi^ zSp^40l~q+lkHXemFLhkJfpdqx9WQ5R;^<-wm_Sa3d4eTwJhZ-;m0VU%q5qm+ zH36E)XrhjP;L*))ioHbVli8|wZGilQbes+F3@P~EzGluU5m8+&OcSs5{G(t`WR&<5 zVlBri1R{{*bH73G=nCBIFP zWxM;qqq{Xzl8LzS+uuHam8x%#yDL&wQdO*wV>0rqFQk0K6_0(hvDX(}Qla47@mMLP z6XmDGnicxtxTr@d^Lv7US3^IQ6L@z*^S^0}Rd3{mPxz9H-6TA(zIbo*P^@AGRaf=# zIZ+%dFN(6;ObcG9hx_JdG&amQz*ITO!F|*pLeElIbIug$6u6vSI>qVYfg1LAM(U^$ zY>+BDmbP)v&(5G<9!I@_AtF~(P>5Y#UL*ZggzIi2UVmjOc8J7qgFfiXw`YYlA(Poa z`RpfrMT}eiHsAm>M%eQYu7;OIY5fFx8q;wLL1nxUPB#tCcs3on-n1CjRf@0muLfZz z??<2^9qCH6DO7L|y3eGcCH6ECmK43&0;EuOdAk&#q8d0l$;az3hW0w86Zh}`!Q9*2=zenPE;x%3) z^?Qt)7=2=&BnZ{ngbc(ai`WTnVZ+)?X7`Y6k8!+yRI$ajPdpBvu!%;71xXu8p2?6H zg5X=j^YT(|LejC1LW|2UDybCYs( z)45?k!u|av5#0z{@f}EdhNf=C8Q{Hm4~A-fiOM->(RYN;9&x=wh(z9*5&tM159LKv z=TWecvJ=D?fj+5|q*^m|8>^+;+8zaK(<0m5E6pkp1*RSewDEqWi)Ff;G5_p%-AANU zsYnyJxtWrYM5NInS+VW=XKkn;X+Es4e0}=|hpEPv`_BK zQqBCs3-J*yzW8o1lL9s$_2UJ^R-v?<43>>0RAC5LM}R)De~>Mv$PWeVu<*i?qCy6! z(4&yii!gsBy9CAJ(t@DtUMln3ziMN=J$OHyPnNHEmj1Y4_z$y`HTNge67Ak7&8vfe z9>RD<%=OtG!^DuG{FSeZYz38!sJfq-+#*}o$~!Nn=YjEeYfUQ+%t>^fIHd6&0Tzae4F_d z6QV5N|L_nuXE?SF<=v$8`wg?e!~D^mr3S5rzzYFsHXstWzUT7p1SOWB;20LOp`1Zf zNVe)Lh13cIF(pl=bTG>64*g0cKfP@DONTnq_}QiLvFB5`f01%R^x??NhP11v(IJ>Z zK3u`^NmMp3MDBx}ynrGnFiuHjq)7TR!78R5kT%pmqf)MO?7ub|dd2WQiwEIS=UUmg zRsokD_M=&S)vKrx0gZXl2zeT%o|1VdeU9m7*ppBhkeUfem&IIt<3L@daoMV;^b319 z;5ZAJ7tFTI1{_B-FLmf_qCW_g{~*a6XUk*3Ctz1_qtjx0BL~F={U}O>sXn!qm1i!D zy6qwb+2-NLkyE-w0_8`Qe2R`wut#1&9s?{5D2M!e5_zZsNLd-3HUu87aOB-wc6qCQ zt&M{%qHCvFkJWzeMpg$Rf0+xKlNf7is^Y26XN05Pd1uRCnu)B_U4&6onFieem*_6p zQmIbp_jBTNVHYQb=~nCc<>g?^*(~tSL||C8#N{d7y})*3`M%#5+s;u`_tjQvYSpGb zA3h%3*U>T1nZ5~mukB>E2zEss@~R+S%N9!+RLn#d8KbTiID>a%Dhzl!uKH+$bsTlC zmo@2htIgX|<4)R@8G>)s!VZ6bswWPc!}M2#pLl59PjhCh*hIR~3FOp@m{8{07@6X0 zl;rAticZ!^|F*N<4JG5^VOU%d`*WBGK}wsYsS0YG-i%3@A<(QU-x}B})l#@(90o;@ z3SW_AB(iZu9Q@Y4`EU#`U*o{`_Tt@rlrrs8VE|BFQ|s0;EB$?Xz00*wgRu%!1Mw4K z8;UFXZd@@9(W_p?p-}k72Im^qv@M7-K`1-2lYPhoTmBd^F%ixc0gD7aEUXW~NMI<9 zgY$Je5lR)MVhIg?5LGxwLK&=IV9+3)s$2PJ|2*>@h2GY7&TO^IiuZ2ZWS>~%K=H)f z0_>UU>E9W2JhMiBaji!c8$oUmR&i9Fgvb8+_im^MBK@_P20s`#4*ho>);3+fn2bcPG8IU+wb)y)T38- z!HkbFk@UVBb0_ZpUuWzDc>tTRtLymAzdH>w(y>vl?IXgADfghmr4|GNVZ<~3m_hJ* z5dxyxSznSKAijSO25nz1ohwz(2VAa2+Wya-rfV4(c(*Z_Qs9-uf=XJ5ebBo~djQ=h z=mh_J)v$%rIg)YTvfz*DC#PH#znsl?qcXc=X0czv2LzjNtwgBH=S0X6H}I2r?@suk z{7$;#ruM$o|H5etpd#LMgp>I+v)b^#^9peXxl|jPvi$ta|ovhC+_ucMz}hO z?-;;Yj>LbvE%QTkd(j=i9T73FVV%740}?WTP3}HP>yM8gophI+GIJ9BX<1{>O-4TV zBd^ZKA^DNPb^i%e@okMF1k^AyBJtHo63&|9sU|13&lOts`qvxBQ70@?6%BkAF!abF zu?PZ^VJ{elfRqbWn4s+C!n^q?U-E1$ebSwc^I!dT8QQ&6fpprT&u;(WQl@mm~16Q6*0=Ea*chd z;i}|giGjj^RUF>Im9L2qG12)KrpKdpA~o>%ZdVDKY{u`i#zKv5FAwSVBQ0|`F}!gK zEWYL6k)S;p+OQk(1gvDI)R#abBf(tu2cTNqI#M-a=9_P}=yv%uheLcwN8rFsD^@M6 zOw19lC+HCTpN_!&$U!6p8qeUJYf%HK4*AoDdJB58Z&>Zxk z>*C(Y-rD!>-@FM&1yN)KV@%Hu)0=es>B9$cI?+(w2 z2|p-a3D%#v=(ntzd3uUr7WprEsiiLeY@c?+jod%%`BCfAC2~#=ogbe2xV{)wI#p9E z#QF03-yJcQVxrVJt~PEl7guiGt6A!)-BH?EXRcQYzV;Pq1XzTofp^mx{XGH<7o0lC zHc5^;&me^5LfZRGB92o;%fgT!#$u1G$ak+h-WZ3$Z{z2Bz+SvThxhH}l8*!p(IomD zLJEqFq!)d?%l`ax@tPNj0@ApbBH7wHcpTrVN*KDm|93iKlv7-FZ_=oUk-)KJs;lcB z@KsFKMi`j4xVpNMD7`KWPpT?o)EH(hkQm!v>F_M`uaTtoJnTHW4+{(I_YzR=3)}x1 ziGK1~QZ6kn*|Ia!aZInmZ?4~xhl+&6GJ~6^>ZN^0J?cq!$a*dtpKm@@M1>;Z4Bsd5 zkE`t;ea?o`St78b8rt2Rb_{!3+Xu2?+D8_S!A<=$l9!j!Hk>P~8eUDU@^wv%wQ!om zDur4ow;NoLdOzEuy;*m4QJNPkLNQeNP0& zT0t#b!(n00M(HLdvltO5{FlH7Arq8ysZMp%;(CV&z!sRdTM@Kn*ev)Czq%|p&)Q5B_U#(s^j(;2rKTMZ4K4_QZ0+6T5ZJT zoP@@acilZMpmF-}VR`Re=2|JC%WbI%h_T^z;i2(SFy@UuUV(p9VxJxMk7#mMsU?jO z-X2!EG0BUi`Y|d0>WlR^GMBc&c_|*fi@{?*7*MCB1vkkzVGq~NiwgG{(lcYX))#rf z=PJVatDhZbt9%t!#ACw(L`O;+p4ogR#yxs10e}Tz+w@zB^@NZWt>+}5r7|Ggzqa@( zLI2V7>v6yWyNr@J?Rmr(A~s1R(1X`4ZzPmNjU6hdYrMw@31$4QTRv?pSfyJmLR36J z{YL8YgG24V-pTLUU%(UIc|PfOtwGH2-!pg)M`qHdpag9>t^mV^~qnEuWE|9!A~?ljnzV zlTwpBx~llDM(;5bY|mLo)MJz#Kgd~iR}PS}51*PZ^Y%T<_F!Uq z51DV{j3_JPcR>>DLaH9kW+!>C#~mZ4@;~txQK)y}CW?fb1i==5KUrx0lL1jM%VevA zKm)0~*$K~a|A=ay$ZdFM&$B9eU|DEoUsGWf)y&nkb+Vc!i{R4P#dH@g9(=YO7}?Ih zOeT6v2Kv3QP{ui1HG<3uA3u8jCHZW+-^)vg=bhi%!i-H5`vuNeS)&s1MPbccV@GuL zs`qZRF}26!uz23+Z1u(+R%nS4{j3Ix)Pp5VHfZNWvtAGoU&_yXQYleEN!I7r$dyA) z-?hyOjGN#1Ghl?FVP#Lk_B@E#swwdF&l}w{*xqso&9azzzW;LG!rs1P!tNu{XDFS* z+I3)sY$byG1d0m6lyj#b5b?sR*K3Z|ovGilx_`{q8BeS5xhF*b`E60Xdh~9wSydId z%d^^(fw9PV>u0V{(wY>D@6XQ#;jV6O>?(>mIg2b&H1Uum05uD*)UzTbWJEe3jU5}Z z56pt2l@NOVfc;yeRW%p@=Uyk@Bq zGuL=IPnxKrn`vrqp|q*7@!aY>mG(#`vpuzff@Rv|O71pH*Jqw{qBU8;%ya4K+fn;JW-lo3Q*&H{mI18 zDdmLgmOEqNF+cF6=Y_QA-Ngs*mOh-A->@>wIJj8xqX78s$Fm;ehsXc3yAEt0{woIV z9u)@F^t+8x2Zg1ps1=mQ!JTA|Fm1uQi;20XlBkF7hu$>lW(IL{0OEa{X=IpHQrEQ{Yam&b%bKqQ&p@4ZAdQusZ=06 zzVen=y^_XZj3|lv5_M~0^s~M>d|>~F8y`I(hm}p|6jHE{t2$2VP&<&@k=s8l6mybH#=jU+9>Px<9p>eWa;RD! ziJdZ5DoN|(Qfu#$7$cOAE1nbG4*Zu=1A;X+81HduqzYM*_!yH$K~x++gvvNtc^1Ys zCM1Ozr3x9dXY(DH>Fww>m`PP4-5Yh~Rqa8BM(^IhAb-YAn9HY$A>pGHzzv*avuQl} z$B(yFzxcPBTZ2>`51!fjc?)@9x1McM>B)~OPTOt%L|qL<04P7H+58G&+_>EB)bo8G3A#_pY6i?`)@nxe-LK+p*Hv-Z(P zytCbQmbY?Qi%uOVvCf+D{0f4e_)$$bOx$b#=MJ7hIZ`z{UOZ2hA_84@c;8IcuVXmh zy22gPE-7qIIaS%ztxb%#9OUvPt{>!cxU`)&8c)=^Y?-vEZ-vgZIKA%cLvo&aAb@Ql zV#?SE=Imt3?H(JYx@MIa$fPoqKttIQ zJ|hyiiWBD$bU){l`}p&nVnyJ|R2HB`wZLMQK7qtd%JlmOzYn~%wf6VtrB8F*+nY8H z*q!pzoyH`^7pbC1O>9pCNaSq}HYTIbFsG-}X&6F}gQ1lmo+u0><0q%!qu>7qf8EJG zj0&$d%;bv#?c&=OUnRBVF@H0aV?!SN6xpq@-y-y@J~$m79!lK~gyAh~QiEsQli|v9 zduJaD7YNgmhnYuD+tpJhS$RQ*l-f+6lY;(y#WM>$J2UGvp`4+vud7=+@(v8g#<`rb z0t=AlOMJYYh-5G_H)*0Y9^EaJKFR*eSW?G!+5iA?NymZL$kK@Wy_BmK_cp*MFspWP z3En`jKC@{iUkN$|jBQ5(5C2+j8G?Tx^MEnrn~uo9oMwyy%|!yWbii%^dLGxnqUqnh3(~cx6(DY zF)ISJfwzm7@%qen*#MWFt;*{iaEqQ(ze)qMUk>U)7dY~6+soQkUhn2(=j7=Hj3d&|k9 z8L^mk-p8el=Ywq&>@FkTZ}qm`zx4UefNS&j14HC}ptPHh49SnNhDNSo7|X~vF^MhZ zrXAZX*6>=bNcntcGEmxUReO214?A4_Zr_nMmLO&gfNDMpv%;pd!20}9fD(>R<8DLu z%ozI@lx>xpc+;=k`n^xlKq^OgF2<0HT6}>3J(#yloLD#_5U@xR2uq0U4at|ESYS4M zY@DPpNcziXpSk;E-hWDRimqEoR&HcV9(5Knzo0z|a2eGr-BtImPGcx7UkQBEaE7Svz>*kKl6QPkFOqN0mHw`O*mtl#Pq`av@s0-sn)Nuvk7mIq z#a0HC7#pMX2ur*8GF=Y)>?p&O_m(0Qq)-_O8AWiGxqORK%AQ^S1jAP#L z2ZZ3&%UlA^*JB3OS?pq`_Fr>dmHv2(ovKMUMZQ39y9V9aTxHi+2vxWww`tLp0=B%a zzw>&L#Fb<9ozo?NkeyXb3gPeBMt_L!(J7;rPvOmvGxxoMKOC9gX>K>byL=MLDPr<| z<*2H))G_~uAFEHI_jSh5xq!$l@XDWAk?ecgt$UYf^VK{46^1hx7W+8BkMTvR99g{zyQ zvVnJBQN1){*c^Bh@{9#Dcs|qX-tsz2J#%xARa%fJ1%>Ky2mAm+ES4K~k=$%>Q-jqO zkLTkhMyWQ>u%A2%!(cFSU8{43R$q#HQl?~zTiT~g`{p^>9``UOTzDPv=1e0ujqBI^ zaS>-|G%g4V>scFr&q5df)ZVgu#sPsYo7(^o+PyqJNX4>6M+Uk>p6V$qev)DepL|>O zZXw{3rs-mcs5EW;_r7ehaymPUv|lgp@VCW-9ogsnV$QV930^5FQ7H+rTzR*^L2pSc z0VB!`&Xrxo)9wflc#Hu;WP9v` zhyF_W#jMHY0XM#zVwLtiToSeN_4RGheU&lX8&<`LT`)OYWK8q~PZK{W*B{eL zpN`*c@gK<_pAC1GKkV@Y(v>I^c5Pw1gyLoNZ%aR1U7cM1?ysM@EtICBL(QIysKWnF zy_If81=(6rwteM0yjs`DqPVe zuQ&1-z%srHVjvN)@pklM-@j^_F}2o@NUgZHxrIQ<^JU}#`sWc)F{s%m497uX~+9(N0ZjT7i|(MO%s6fckOhs^I1Lt#3RFO(*T zAMk>a6yK}wCm5bY=KVs499YbWXNRLSS*4m#_z*nS()?|TFbza|KaZsU-VB47acPQ= z6)KteO~1*m*CTyb``$#d`{9BcV6Z;h;|W+#(Mn8q4qZtB=pzA>u0oD3H zf4015W`){NvdQnYoTc+MlYbJ8xgdzmpZl%+)M=Hji((|PrSxC^rTSI$&zbbu$jh-+ zd2J^~wFE@(AoIdvn|-{3u4we2Cs4Yvvx)X&W*qGg#Z?7eLzE5S! zbcO3_MzY99wXXB4*#7W|Ji@Cf!+M_FfI;mS+vA%wm=69*hg(rds+Th9q5xgI;qiJJYXuU{JlL@P`n~c7 z`^A~#?7G|f-ha|6zt*Wq^fP9Mt$8#wj#B+fxo6K*R57ws9@M1Wf4`ehn{XbS>r{)! zK^y<8Lf!AC4JW3>^agcmrAAiPJ$+l1#)%xVqoyS69Td^|UhF3D`ENmR{R`}lZPwSs z{>v#dwX`C%v}%kE!Q10BSmRl>Hcs^-oavLWGEjI3kW*@|sz3^{Xn_<-dO-QK5;yzX zSw?$PA46+WtR?=&%I?*W`)oFRs50+tL3#uoq3KCO0_dc;xoUo3Cz1s39o_R^D}X`@ zhJa|z?^_p_y$(kW(Tee<)m3vtG}R@wMOuO6*QO-V8^BZ#@D)#wDtFdP$)>> z7N0jgtcZ_bZmtU^>c@_ij7vq8s(MYBon9Slw@;i5%=X=eT+o{PtOQ*}5bNe&&ES4@ zS$2}5^NQ@bK0n{Q%D)M?4U-j?-XFc!re$q^g z5mpi!kKg)JX=S}#p{a|i@?|ltlZe15$*Bv zsAWpx2~Dpl%TNdqG=3V2bgFyL`=_PqO$ku`k=+OVVr^7rnx+2v%vcg2-ocoE{Kroe zlRx7pKh$3DiTOI1vpa}ZhF7O=8Jj`bWH+^-3Yc2y2 z>V`zEBSNs{e|AIIu5Q2N>KF}i>AO<;h`l|~+{`?+{B0WN%kuW$ianVHmX2yIME$HZ zlMi5qeqOu0ELl9rl{(!gPUy$@wG7D+jJl3fzOc-V>mliV($lq|SZ{pwN#vOUr)98D z(X!`9d-mad;fMXEj*EB$`ZjlK`<7=3N>zzj8j)eO)oR5$#^xN}2}<&wcUyb3w2lU^ z%$8P{d9F5{I~llNhF8JH#dbh)ozlkUfV+bL?k=iQH&ODoOn~L<67+5D|Q}9uZ4bJZJ}RsqG9NNyoR$$dbc=JU+MmptgjrithzhgBZy5o43OQJ;Z z?nRvRRf_bWFJ~rc_A%S{3S6mNA6MUiFO?VbM^w_(5;x$^-tR-(1;O{TK?h6`R>Zw4 zD^EZo!}j?K$c4;@9E?<-#|NXTcSnJ{4|lWGxjRIDc5dT0F$$lz+Iqb^{0}w_%)^9P zIBlCb)%`Iz^e{oGRf&3!t>e7wVA4;@?9d^^Uez``0&vWWNBwZma39Tyau?@?kd!YG zX~=_;J!0Q}+8)7Dl^+Rh8F0&1@@-;!BcGm;o{_D#2}_byT=NkiSVWM6hFc5*jQ10M zJ@Noq3@+LqreovRxN3eSfRKt-g@vnRe>3VE38EL>Z83I~8HsJd`jVQyBpK-KXMN7Y z_{A&N{)%ip&I~M1VdJPS@eB(>=9_;c@@gdLqc<9hguU8&YzzeH?sk&-X=ufblMG=i z^5yXl+CVY0Z_MLdmDLHn`T6(#lHC-DmoDLpE``Rr2$AV5AFZS0SZvY2DV_ZL^uhOh z`^15>_34uR(+h%q8}+5iSYO=fU=Zx^)QfvIW*O@EM=66ofq^J(Hj-r6#!UxCWTdhI z&2HuRgp{-e6s7v%!_o1x7%#7RkgS)Bd8hEGfVn!qQT0d_w#HlirZIC^f(Hx7={>cE z<)flC*WaSAG->NVkmtB5I!dC9P70IPlQE-(vpbYwMS>}StF?Qg%keJg=SbByqYOp= z@aU$Au$iL}Z55Ay6Yb$_%EpWMr=*GPxw^3F@mK|AX&twc0@B%W0x zs_I^^`IvI)r;J>hS@LC(bfeL&(EiiVnH@J0ippNOufKg?MS1!k+}#mHl^g6i?y1RJ zJWlADqv;vBlkHsIrED(;#rGs3vx?K8)`+Kyq$~;%a!hLL3_gdyQU)*oY`BuebEK&j z8xx2AFnoj^p-KujYMgT7fFl7zo_9T$wa{Hq=d!~#VJ8eBaew)?*Bz-_#RiX!nDi0w zxw{q|a~sQBB(==3PUmJKEjv4l7tsur`|V2)>eT_B=>Lj3Nbc8=Gllxlu6zhjbZjJI@!`TS`7+7|E zr{RmT_;q&#Aqzj?6x%!Z12uPaN z5Br+>Mm}Z=I9~uaOR|Py@!xn_VaV%IzTqV&u0%zQd+!AfPeL*r{tZe)^ts@A1N!Fl z;CGS@u#EZN_Qlha;`7>zXMNa&?fCy@9|TrK?sovOa0Y&c8i`ZF zvBlu~HkX~mT?xt44=72ZNPulXo2J@x5q5=Eg+oG&IUNsjmYQ_IR)mO|F4sAKyY8)a z+Q9spD|#Ed`$L{P)zLG2x3A*?#K+nnw%%NgHZiUT9EbaSP6+s&dvTUOcK98sc%T`P zKEjVG1<7QyjKDaaE*=mu+8x*$afF1#l*Ye`ic%$o^71DSnFwenF%}jgTM#BpqsC#j zIM&1I&q$3xNy;ixmF)HS1L>!(V@vO(G~8Zl^9Gs^sE9doG5JO75p~ly50S$f2kpT%Lk#4Vi5yebj z-#N@Ye%x=*S$ht^lOvV#(%^cIL=`vgCxDIH0$W@Zr%v>jA-U{@ z%^R&64#Bu6(oLyM5N7EPjfIkD8{}Hvi;|3SMe2<4{p7Q!^;33;I0gBUNpN(>-KdM6 z!?b{kY%T^x&pyH@6?}Mduq-+D_f{qamf}`7Ws2r|%ay8cAj~r1N*3uzJKBRHmw)|e zQb2Fv!^Ogyh*Lp>>8$Tz%l0~(j;c|5mqlhUE-6Kf?APY@x*3LqI)NuKT`Tu%eYe8 zpXQFzu9Up``3?COd9)1D2g)N1xeoSoJ?L09e(~o1{OjuBhyb=Zi>xZ^y((l0ELRTQ z5=9{mM^rHiordKNi-GBe?1EWw7w6}ER=)&1=rqEIIY$N5`Y_tzZOgAh+diHJ*z8Yq z-AjmzXu!tKSS{&@y2HfHn;!e}J>pOt;g~MpYhJxSZ<4-S^61vB7S0~sbe+2hEz~CP zyXz>WQ2sSvWb7Y4BwPN;%s3$!{p;Ul?v`7o zHKMCN4^!EM5&!?pA-;+_|9vmoVcpMIlYnrx7ctSlp!RB?v!qj?(P!eg5d+_oW0lH>$@1l zliOtd_^AsZ=FPxr*ziX<^d4)$+&U%Y1(Nik8xV!lac;|aaj*&qL~Sv`K5xJG@uHdT zuTfSF3Y{V-J(}}PkZugus1|);{q|!AIby}J?R7;lh=s}^ z5Mm1SnW8Gy?MXJwrwStQsr}x3EzfY zSQwPehV|*#!9K!EfN-eg97?Nu$-Kn zD{p?#*YBca4iOQdUi))))K;j9p&auzMg1Q$2n05p(b7_i+Wc%D77!z3x^w1ieqyI{ z-Uv1tF!L8Mq+F`C7eyd8P1_oJpIn%2I957*I9VsTRT_EM9(epP`2w4pJiWPiIXj)d zbvkd!?J+}I4WT0zK8njgIk*xoE4g7zS6CtO^u#v6+qZ$<|t_`=%H&rc17Va}v|?yq0V%fncJ z2!JXT=I4j;Fz9AyuP-vCF+LmdlZK^EbH>4yv=nSvr1u_9UL=51?7ky(T9mW(vm$^2 z?=Q71I@lgo|LwQwS3UpxlHxqmuIu^~k4JYm^V-$J-bnhiQs93Hrb!yE^7FXlhs9E{ zAwe}wnf7td<}WuN{)1cLi%4bew9Fi(d6yME=+9)}GYqbiR~Y$syBHAQzzy7{S69!- zObtz57?Fn29eDLU47acr+9dYNrV^`dv>Fx9nk$hgdg9;IFwO4F*o}>(<>~3!YLxA& z{XFqjI<8x_{h*w0?dE1>XIDJSFEd@RXy8ife>^vK9h;&DElFIh(%Ci&#JNVe*EYNF4yW+OEexwG3v;~Ei9Z#TDC=CcbTqvD*6jr~g6`#z&Q@Z3< zzyHwpn+0iCs($5{mNtp}@reF@8e^=Kn}2hMfgNYo^8SQ2Nvv(*6aWnxD|+f8$M1Og z^3t3a!V#<(@N(aoM15}Wg$35O=C4z+?r`!7DrtKS{DfsLxUPo1kAUSe4|>`7oQ+x? zY9PfkawIW?DnT&#=pjKmpg6684fLkR{4S*W#{|)R+fZnmrvVX2B{U^pmm?*kgwt(9%v_&f(4nX5^+sxIfPyN9|##Pawn? zOA+TSUJpYoP-xfWupZJ7dlFw92QYp<=BV9no+AOlNmUViuq@Z)9U0AL#@CRmwge&l ze!|^JnF#$+U*owSh6CC?`(Dhbu5w0bJ+8fNKcr~4Yc-`Knmzlxll=}SVd}c@W0GW# zqp~Qe@%>kFX@m_K3Dm)^wNuUykr{rEeNHKM0re_bF-jgz?R&g&&>W-I+PXS+0&Gfn z;`nW}W9|2`wj~-J?wi$B^DOx8U1cAuZR+)dJa~Z&Z7W@ZfixBai~$6|7iL|fVdvEm z=;bOfQhtm-Y?%g&88B@&SX*CqVrJ>XYwh&ZD4V~z^=xePWXkHQnm+x)Gv^8Vtyf#! zaCziu98H7H88=-u@AQdB`!VP1kADvrYA_0lxHA8B#Sb@I6Z^SfU-5maIHzH|1u+gqdeT`C^J=(U&)>$}pJOaB z32KNFm(=tnyFt0-4U0;Jo6i(Y7YsHw=dyk!Scv*tY(uG)P!eyz1ue|1cwX0d9r1fC z45rWHh#CHQ{WdKvEj~WJevZd+ZAy=YM>}H1WWF(=*m&t3P$+1AhTc4|wDXV;b>8Fp zUkr$R>%T&-#s+j!8m~OWtp60!zn7zpM#V32yBTgPgeBfBf$$*4Wvo~IC3fqH*zG|^ z0)Rt-6m*IlM~sf-`|6WfbsvELgDT>k0dQe`T9f(7HxPq1;@gOtu&1yW(wHq4(mJ{) z#O;=0NdO+7ra*;!5VpD-LtY#!nI>_`%!~Ant_KB=o_#M9aADq}0vFcRbJO7quHS}; zVfu)Q)o!o9*q*vgbwk> zKnF8p`fL?Gfo1Qp08#M6J;o3uSk^^(ocl5-dmN z=n7HlDc+X2?N2DaVuFWRkim2k;>};KzKA#JQ-5Jee}nVYnPE**FmSU53`PuV#`}Om zB!(2C%7#J{0;N6+f5xHb|}oE-}*E=J2!b`mX*}W!6~;c?!!P% zOf3_a*aoBI`{S$*{e_hUq-vv$+=iA}IsZVW zvCf>1oN2?mKD?-5pMr?YNe7TO#!f#>DUnJ8t}x)3le(q^mFdS>*7{PpE-j zf|?Yg!q_)V5h=(HP-Ym*Xlk=9!^4q7feN67qmDV$0M~J2tUQjD+aYk*kq7Q5ix?G#E{tM~8%6nbe>)(rgU#YxhjjM>y&+C9F z4o4xmtLEZhdHru^#v)^%A6QB|xb_K0M*d;Vo{^o~;9Bj}xO{x`IM=;5rv$A|j_Jvo zH;&(C+jqURA+UR?K$D<=@BSfES4Xrk_Y)NaU`OUFJ7*0VfQvz8lTqaU@kXBtbT@Re z-vN6$4S9zMoji~Z*pdFHX}_I8KN*o8AGR*zY|#6zxW6J`N1=(pDsL~Knq@npS? z@8o*#B2(lsW1?*YXZ)hI^B<$;JgotC<~a%0M^3juHYKNKJ;m`LtDT+I_v5SE_r&AQ z$!=jA*?pmWRDAyEZRbY3BeA0iuY%_CaY5x#Wi|uhKgg$3>*RqDUGDa!+&~(`Sa)D$L~k_i=fUHu+=gak&}0#I}I4~I;*%yzd==X%HEWG@WE88Y%l~O!qEI zHe0EGdx)1bmd3_5ly8DBz1I}`4wRpwPEUv(R;SM}_x;DbkYo^V)D*R@q2U-i)hKLk zvun+vIucwXuATctod6{bhkf|hntR+7m$$&FxV<|IEN|uw*Cc;3Zhx8?zn71F0Nlub z+k(EwROb?ElwO;a7{EB0mh0=Ue{Aq%$%jjaPgV<9cMgc2sJlxzz*ALFT3R6s(y(xNM_Me)q zaocZ}Zflro=X4r8*L{i)vpG{V@OUc_==55(^O^>`SvsF=p}Oxj^?54oq?<8gyT21J zpC)kGI=CfeU@2irIDfI!6wvvUN)WoY{2NNcDPK4h{KsGe8l63c7_=RD_i*Pa1^S!* zyotFg>^quIX#MqE9~~*gD%TsrO0*-D8qeI&Y0-w)cD>|VQu1^Zee@VUJ<7HZyScd` zE2sdO@RADGbbb2!>tf^53%UFjdHoHd)4=8np2!7WYisLyigo)ee`vQQQhV#`EU12b zYcB%Ao)lcbDMFlg_XBS|1^^}6>`|XtwF*i@1NVO7)V=j(xOje>=r{abv*B!4{M-jA zONc6R+eo#N?l52T5POz8PHJr%Gl-(Z2Fpj-H5JCgh9`uMb2i@K619{GThfb-nfy}@SaUx5;T4Dm~GxU zy>v@VQnKvy(SDbj&cFfZ72C#^9Ok!$Y`SPYUA*W(PG=%D38r`<2sED8YEbq`=y}FG zOMj%~@X>LjRV=d~r0}aPc>f)#G<^eZ{IpgX6@_l5giBjvARV|*ty+f;C3?H1FEJ0| z;pxz1@>~HIeM31uAWk;qCs**0^qJA4z}rpJ zMJ4f;&6P?I0E-`l@*fNRMSDogO6;-gJ%G;2Kso`eq0KCk;C2w(?@APBSIEggk5;uTX_^&Wp`}v1;`5QQ#=!n#hit2@t8E-`GkV8Q- zLDEplT1hx;$DG`%A$)oqYbF@TW+v*pYc(|(Fr)*|qSwpHn{~#zWry7ZwPqw489hkl z8yq_Ps3n&vrZ=H#%}f+wzgbeFc3pK5V}?p+<(f6bdzor=Q+F#nc2j2cV2~KN!8el( zC~v{}__Max)Uw^q?pJf4Koq?Jop}O(JUzyDjlVWkEIZcUczBMalx`oWmF)12FW#;` z88R22r_5dZD2hsL7R(=}$)^wm)n)Y8@Ts%BHK*{=mL5F_!6VEhH-ov?2FIF9JC3Rt1eSIU$1T2{o z<^l;+(n3+5(XW1=16~`~eN%U^j8!Itube;64iGg@-Vp|D61vWN$4vyjTp2%Y5q947 zvFsu3yyIFCJ8_99Zg}fNkqkUe+k)d~B3-Kg3Y zGDt3mw)&A4BBG3n&8~G0){tIVvQ)vQvrdT?te&qH6f`8+CW)Em+P`HE%KjoVu5twZWOBZewa9k7Ctv2=&j!ms;iMCJ<33o^I}xW)9X zN@6y0iNevzBOgI>iPpZp?aRl}?{>ZT928MfY-3@v0EcATAg(lGi+66x#Q+(#UM&+p z2p(+8g#U$9**=$tU-Mru*m9A?ylze+Qzjk8MG(qGUkLcTxTh=mAV>496WXqmML`=e zA97s}?~TNQRwhOClY@eLLCth&k=c{h>?HBb#x2w|0&N_N>&upC64?09)@E3kw^`Sk z)qusI5?CH)5x&2h=BaEnh?f)lV~tN-zW)viyqw!pQ^Rzm1E^8XiI@iQ#y*G37397o z4tm&j6~YZ}ehaA5NoT(dqoYFREWTLc!Nh`A^=W5;18O#KZR~x$G(M-)$N|o`g}GkM zjXC4;^E(^lP$wvBlxb$%H!F*Ho?g%6Z>EfBhf@-LR=n3T8#Ym(t zfODJ*5Me$zS6I}O5Lh$#&+;>ND|A- zX(^E1CKpn)&%6i7eI%&x-|IK{0}>_s)HDS;xQK(PWzD8I<&%~houVy7EfCXEQ-N{w zsPPAQaXGG|YpvGZv?vhD5C2Z=0ol%V|A&&|Qw_PX2+&(av!~ym@$pp)f>chD5w(Nj zjr~vl9{l}#@T;cPm=2MVk#TgzvGHm?=lF;>cT_TYE|WLzgZ5*`M0W>yd8LE(?mwRp zR`fitlZ!cHNv zg0DRx(Dqe-?Z-)KS0Se_^>b%+HZTa1(iW3VdaG*>U0n{rwM{T$}fN0wtS=M-wFR6HMfM z9XfAg$*gqhkPvxRU%dUCzW13eUS(x*aVWC%^nYK1;%uH^ks~(dzk`3JP_uk}fh((( zJon$MRo+G;-Gm>&Tz}oa{rUN+OGYuN;C-5Bawcx3EN=VIstBv@zi!tT$BTNx&WnM- zhkD+q{2}UGg)QDFsBEHyEIyzHQ@dmq*(6%f)XrJxLKc-m2z4#wycK6tr-McxH3FmWrF!IRd2EXloJn8hwL#&J#G-+y;D|``d+Asq^)KK#tj{Lh#RC7m@+l zR{!BS8D^7EK{yVPfTOpxU;wA;YA}E8H*qDnp4CucciO^CiA@jA9AUU}+v&J$gV7X! zI~P9BNXmqurdjpy7Rza>@n)GJVoHZ(=ev_O>Qt=7B7xw5 zr}rw{>>S3g7+`QJL9iig3M+uoYF57)CrwGOY!`;2Cs1)*T~)1{S|pdmMjwR!(9Ss~ zI6t9~SkNOijYk7Vq)aonFl3P(ZMztC+!6C%hSq7+h!^lT)f`l9M(3hM1XC2bouIm1m*(~LTWIv-!p7g3h;`J!@Q?AgEDj+vWq z6J#-L&Uf7ptoVlrs_HY_5Xh~!&fY?pBvnNnTp5e@9C;O zZtiyWa>teY$;K_u0b5aBsMN?xvNnSWHM(uq&l|n2?7yh-qSKlu6@7!b2-OjTdTjmu zIb*(UJ9^G=q%ICW=y8yK48X2y8L0R97zeIqCswAph)8zZoSIvbx*xx8*yjUnHRtX> z>K!^Z*0#5Aw~~SN_5wPwP-Jnn%VxK?%~_nKp-pQ#8KFNx0N@QaJ1l2TlzVo1`jAU5 zt(uLF^h_t~P`Ruwnu@WbiVBva7k4LJT3Vq8DusxSb4I3K7w$-LJKTW_Kz*>yhn;?` z(xv}}hxq6j7p6$$@wTwrJYM9?rgED9lMfjMZ|?i1unRhNd)QcS@G(F1B7*Pp_X|2; ze^GIoF3mysK9XEVchv-GfU+kh!akO3$V-p`KdRrtCNniEY;`p&ciYJ^M_U3k$i(0T zuO2n1DkrH*O&3K9rb~NEOFJ-1ir5Df6H2XauCBlg{pgy3gPfG~dp^XCJ`OrWtu$?u zD*jW2*VFOw={|=yDo$Amp);BIy)>{%N0Y=f;wQq(E6C5!FC_sZ9r*Ij3|D$o3rEY2 z3!*gr@5I-nV~258FB38_08o=YCGC?<)MA`<)89{`_CCGN>PGw} zxp4cuH|0}Zx8wbF|3Qy$R<5clyAwmuc7zXP(CoTxe=oyao=e-?N{t{<3I?TSW zFKPD)T%kT1m_m)p5naW`J)b=;BOyB47Ze=S9Cuye=gPd9J%T>LKW$pd^btH%D`4fY zqE7i~$A6l_-j$n!{BMkiWOKM94XAo{X-Wg6b6!jg5 z$Q($P)=?mR4~n9xJ}3MJT>}syFso!E zHYFOaq@TcF$(!P+e#_bQy~X(;t<8`!L~YM`)U)aA?LET!&?lZL86xIX(mZpF)!?Z` zTHM$fNIPiy^ zK5UvXt+K#|23&Fc@A28Al`FSbH`CF)<9h{&2^g`H3BUACcOUpfso?#bbIgRu;vyuri4o4hle+?8 z#4PxkXnsta&+D&!od6O&(D&HssW-+A7qy#Fd=GOpjAU~<(19n{}Q*boys*X`O< zI*k|hs^#-T*~zfF7-nQ~bTS?;%mjK`@7@048-}L9uJ$$UPClU2`$@rsGUkb)mh9$y zCB#lxfdk$eWsWt0Md*OCEZN;YuX#4Kk_-tls^KJx=NsgvJJCtjx@|vc2VGH&*+}gO z3aRhpmby0`_X!Ii3QxCVTH)ugLVxd|2QrMN%21lrF8Un}(UNL&=tJJ$wDuU4E!*(L zZMR@DWacCnQ6XS^QyFcXSQo{gH3@@R-B_V$SIuJrU$EI^)gWacd&g=kF>0|~;oEHV z8gA|Ix64m$1=u=NHdO=`rAhBP-ZN)RRK6=j)#bG+yb^24-S_SY`uMvoFH^VN5@N!Y z6s(jL)jP>QR>QOneg3&EtMZE-O)}bbNrF!LmxdtZL+ClV*mD^aW-#a5n%4MizjtTGV((#p&^kd z<&NcrvQua7<1h!JB+ar}vCe(IK3gHf^6=3Zsu4-Q27o#}}2bOQF8NdhyL; z)F#o*tg7~OJa;_J?({fKu`OYZ%-`M)xxQAEFheqBPLXFEVMKn!0X0=5L6B60UhZgz z>-8X_^dIfTY%C}(sDLff*u};n4&kS79;L>{Zt0#46`j&Oh(gMPR6 z8cxVP#U=Ha@$0p5pz`=l*LGTf*$T->M-cUe0B^xNui+#9s}w3zc@LKnh8 z?oB!XogDm<^ZN>>sI06MhlMHi3^+IG8A>wR{;h?3_2?BK?-a5pNsUW>P1kQr7<3T= zQscf9(aI*$YU^>llOKPWg{#k1V-<|u>s?tDkw;0fkvmwG&TFXH$MU8zZC3b&01R+XhD3P+sRzM;0fAQq|Is*~=a1F}+0I@GE)f1qegs>`y%5 z$9o*-<4JAY@omFknWrET` zxg3aM{>>Z(iI>}=EAi80P&x6K3?lU}*{CTMd*=4@dWhCphEw$Jn%mQMzi)s50a0W>8s+XpaqEW zIMKPfRTS9NzgwN7I`bPpX$-9(6(?2N+t?FYyb0>Y;%&@)uWAM(ts(*Yf*jZ*%DgAYd6BxIeT5;I&B;30^^7M4VQM zY#@^qq@}I>X~8V;@F7+ofOK$k&kgx`{@gy6Ygf)*US5`0yXcUcDyNI`!tW~>z4GHE z0c>6R2jnN`A8ph$Q!*z6?$6E~Jt@~kh^lmoLpDKnWrU9FO;ifjkQE)kCtgYvheSot zSl86nTDzZ(S0td%GqPJ)%8=N54dAC*d6w^M*u)OKSbu%CZd{6f?yIR7$uB?3T)=5P z&1ny4G}O9&$lw?V*`{`QSIBd4wx*QZ*wUVI*cZwSPV-+O*;hlcdD+{iOB0+YtS2Qm^Gv3#k8i~km}?>Dryv<(v*!bbnD-TG79J@lm+ zoqYP22oP98V)*3MKnnP`p9{wMa9qa6v@S{AM%f0IksBRX9~K6LZ<;6k<7kxwwqN~l zg90Zijn?kU^p*WiVPs3BZh|On(~_B>hK95AKvv=BjGYeGqH`vRId=A}Vw&~x%j?1%2X zN5&zVW|D8oYI~f+fUy;G;N2yIU8Igp=rweW}~jgI01Oiq`SSWwQ6E{;a-MG^!AtFQ1-;T(mu^JPa zgONj(ipPEoS?fHi^;&x42IKHLS@tIK#?U|o<&&sUQ`n$2V0m>jviP`uq%>;XRIM*U zxyd<>`K3$c#8kbG1ZBhB!BaEh6%f67rY#AH!O^zL_S@689A49JD7QZTe1{)t!NHlb zF?c9J{h+Z{czqb#bza9giHi2@=BC(aMDL-KWaiKb^#H}$d9u59Iv_KqTzDNEJ3sEt zZA~T8PcdosO>JF{pMBs+ZuONo{qeA!cXu~ZDfqaFMw_G>DUhwZNA$xXTmH%%Dh>+lFmk+;$h$KsxEt6hJUT&#Y!I(vEDbz!~y z0d{Q-@VOE=YBx>NX=Gbh;|8+!nmQ*EY8CT-qPc3B2edoS!E!+(HV0!!d613!~H3)qObbe2NaQFtDlTm+-sZ zl+N`(%A)WJk?Nl4ukf^dRBe)n6u>!-O>jwa3m%!qGDDT4W-eou1Wt*zDNYHticb>;>1wcqIig3WR>~ zQ$UFJQm=S0)g6X~AY^~(o%m9I6DvnH=u-dGwMhOtJvCxO^1-@DmNOj(4>e(&_fH9n zz^@v3+(Qxg_oIA-*DjMSWdvVBNfheQNAZ_Ksa8$C(NN;?k3gv-J-i{QgMl=%u4b-I z!D2Y4=b#A0(Y3nL5%xRLh>wF1l4<%+EobjxS{zPbSI;b;o`f6*x?IKRoJ`tLy8d&E z!udOb;(PUdgMZZxOT4CYgG>uIdl+^`9Q%o^n#EE}uKdY&RQ()3?bJ)xvQ_uKO-AER z==v4&?)OsK5!aP6?ALU;WHg8evbB0&5m34$-nGb0)umWa&iMLzrcW!C36P!|x4FL* zrWqaGrYcTPIwKZ&v>K-DdU>5>7udXYJ@v>ULPieXpD-qim)28G{~#eaNX!(z9g2&intKrr&HH{!V#FUL5a0Bw^c(l$gEeeh5 zZxJa6TpJs=cx_I+o?HQ{8`H_TYw@bAdSh*?+x5|GNXX}4ixL61z0ql9Ax(TqRRw|v zwEc-(-|LjLar<&6W|nr3(}&HjO=L3vJo9GYihMn&YOMM@TNxmvnAH9pQnTdqFX2|A zxc#<+E=sA`&E0**F(D%=B1s~B#I>#2`;+{YMsAc+0sheX_<@RJAh%jJG$rw z)7sxS_x#pa_^eFzR7G8ze#f424`t0o;=5=E$J(e`H5`tdaZAx1Kr-I#)` zh6i%JmqRaCs-{Nf&Jk6k%<((UAWpa@rjT~g6{EWd* zXw~tVO&M4qGK|-6bTn*o-h8^h0$%vc_PZSp^o>TNyWZ{i!zAS^mde)`AkhHLX_aU{ zeftG$%R&BR^~i&ByX-}FJWl>v_44~Bx0CFDR{+&`#bVL~``?z4?NgP=7mD2s9IJWs z-_y!@8qX_DF53rruUA+BJ5+?^Hp747RN6r@oE5j=#htL}GSd&gEU_#zn(wM5MLm-eV_3he3YBO7uh!*jE znfgU00yl($pOghN$?%8CpLj4Jpbn*r5+p-F%u(cka$-LQct8tYd1PQ z*3mj^k1w(_$6nyXR=40@AbDoO;fm^=_FFA6#dG1n-DVn#;k_$hxS4HSI*mgjaIr}Y zDxW@``_kO#n_jdxUBGk@5@T?2ST1hlT-)ZL^r23sg{QoR-`NC-3%UrkKq zj#W5>#^$G|WhEdIqZpC*IWj+Fg1KqamBv<2?94&3N4DpAzBd5bP}Oj@(aDLK>0b@g zdrVdQzV2@E%K0le;X7M)Z(x1?NYAu4IlI#tvOnHIA@Ant3rtO}N5^k&!pVKh>B>4E zhPB7D`P`oSzy5q5oGTI-mvL@?juGC|Qla_9+k5wB{H7_rU@MjIvFzB6$7$VtJo39d zEDz@yxF9S51Ebv5fOvL&!F{!J5>feUcz7!hiAr(C=$Klz%axqPKrk?DydtVe{+pm zJ;+Tz?9n(a=wo`bHZjE=VJ%3~C?FXV7<-WwEkAPFCPYuu=(xsdooE5d(9_fge3$aL zw|_osPq!(K@=E3mJig7$`u=9REd|dd(^5Jdy1Lqq?QZjB?01kinwfY}>CYQ3l>Ywg zUSDmMFnYEt1Hc~N3pgf$(4y=`;N->tzV(i^#$3NlxTmr!k$8ufN5;Iz_S08~N5!|y z+2(PL?*J7u5=b*KZUM561eUxyT>2Z%+A`u*t}oD@EZhRUF5f@Z2J&pYciK8z*Gxy_ z-sc7IKCOchPR3-nvQ_uBdFX*py+T3@Uh-s{e$rG=z^220&N^}d;ao{uVQfGJRR7*1 z`1uMW1iZ>xNN>d;^?Q(n{0kK!7=)eF`aBQ9{upynuY0so*Rb5?GfFZcMj85Rn)3}? zgl^0t4x1_k0W!#*jS$z`3^y#oARmIrYqOw66HPuPH2N{}P3)8smqX&djzUW4r(c;R zNJMS7NLl!J@SZJbwNMn2qtc3FlW%5%sB5)u5+*K_C(OlqT-k0)y`zwmUH1ys9ORra zqnXfvEGK`6XML-~AuSVaQMT*0i?F68l%%cl9W@0Xplj$bA_7-<^&sKsn=s34-@ zpy?~XP?omNekq=yFFL8kqEy8F$O=ulZD@=#^8AeWmP-@fajm7HrOoy1q;M%53Khau zpvTJ)gY5cBR>XN9)2k793M@*9K@4+vOQ3~dG-|f!5FELuqU%1Vd z^>`kN_hsLmXZ;)Y)6$Yp=HIowSWa0dhjpLV$93(rmtAcm99n?t+}_&OriUf8k&b74 z+<84MauvoB@RJD3$nQ)mvE^k;oGrI)e^a{SuCVjOgFjqa`c$cS)fOu*jzz@%Y!CK+ zwV~DLdU*WiEJr|qhA2iV@R`S0)(~E$a{3)r+Moq{i|g*x(NRrhNG5J|W+Vz;u`cAT zIu$JoKNO;U&6t}G6YZ!W44CD8eaNQGXzYh@GtPt3__ zX~-2!n2*LxnO#onH?bmeCUSKfFZ>sT%sW7O`(eJ)IFOKNV*TF@S->UaV(c}&!4V>Ig%~9Af_Fb_ ze9?Kmct7wu-v{^?k&W^+pO{Cs$8hZ(PuHfYVwD3fldz0(?^lzAtP(P@iZD?`KmQ&@ z9pi~x5a)=-vM-QQFSWbr%KVKECwXpWFFaYYl^6k4=5dvWu!5r#Vq+HuO{6A^|~U`C{lcpUEKXbgge6#ja_2PMrMP;#Lm@+hfg8Vkdi*lM4L}N z##UBE`>Pa7(aMu81H?LwEg13RTM5VNN7;gKUD6GLhff$J=)I)RNA~4izq2idmiq5E zFRE_?ex?!j0i2YS*`2$lgHO!&Q)pX#FxD*Zc z6n}P9&=kqp(y;z0^|$9`o5toXJtDa;VL(mjp5L3{;E^cq0t<+oK2zFQBo~L)Ny#BO zHpwBep|e%b{;AqIO8Jdwrj}lMIl4jaX)hrmMRM(@y9adKtb!|FwZEY>!`cO+p93@| z2_#ih-$e|4Zz*7i4hadVVbIdj3QK%$|6qzrHX(Gqvb8le8&3AH#FGc)6JJUP-kCQ# ztqSt5y)48(4UVw171fUvtlHKCrF!S(Cd{#`Gd+vN?acD$P*1*skLYr-a zQcd(N9m3R>L7#$7iuvu4g&d$qIP!$52*~Q`3KOCG$hQNE)=HCi?doY4v{z-`O}p0xmkW?%dfm;Z6KE^l^^VP)*$6 zU2h*wQZAQYCv-FR=q6wMb0kYQ2Yp%MP*v2mAf^gbs1d}71X7}H{;1K!zYeD;M8AQbzg0RrSf3aKL9#j_L2G&eIKH`xz?GKqqrf$F?^EQa^@23Sd4B znv?$uq5mqb0v~b`g z|9)|R$bwIqJZ1B%T1v+NHeT*a2q39p0zt`E6S+Bzocms$+W?#4wq}w1g#($QCPQTN zrM7QqiJa#3>iNSWAgs{|Ui9MSJf0hbJ#$cgJ*92Q!{%3;m)KtrQ49ftPY$AR?l~G%F$^va9&kZCF~_ znuHHKCzBdGl?IyB#kS6Yn@NHnghd7i5=Tk*?kR53py3Y6iAF4D#Y>3jMX&;MD9Fd6 zr#JkO$hDX&=gd-2x0SMiU>B8GRI%OVt=%{xv?}gvnMD-1F}r%LIuc40{VZn)8aA8y zML2r~srPQ+0kad~^S`@c7_D}1S%q$!rxo#Gi_0Wxq>x4@c#|vCGaWg$Qh~e5GPF`e z1j%;L(3nRM5^%Z(b^3^83=&!06zC`@Vqat8yn^B3qIUE?>vFk7Tb2OQ@ zcAQU-^l`l7d>o22NrEG$G`-%r`!+2tEl0SXKu<=5-ajCX);_*iYh@I$J8R@=>J<2T z(%&4?6Y^sAIzH!-YX!#TOgD9NJN_w82$+gSqUAE*UD7*l$nvGT#g$8Th zw+bxhXwlwC7FrB&SC_<3d><1-VX~vk%zQxrLgae;HY8X}OWVVv z@wik_Z~^UShx6vv!;%kv0U8=k$*qKH(}y&hTHbB`ilh8;xmw_xg-jEDA3^*%VP06W zp<>B2r~;;t0g#SnNC~}07L)nt1?GQ+_kR%+TJdIad}maSt1a)!zA6n^2Pi*Y6!>p%O(#GX<|Oj~67Dc%wUHO=Lunge_=He|(*H$=j~5 zQwQIY6@yZt%t0v%NbP1CW|Vz@&Vll6(28qR-yD*C1Ja#l!~4wW0%jFNg&{sc#- z@QWyks2wXIN*2SVT=--oL*f=Vnql-PO1w3CtO)5Dl11ehI2_?NIX-o29BiR%=17s8 z>BM0sr6j(wRtV;1PDUa9*!+;VDGh>tPP>GUu`>#Fg}&z*ys1%~(2r{5!Ne*95gmiv zL<+O%RMkV@Kta0M@}LOb5LD?+J&qZhLf>o!bq;=1w`{c^V~15GzR#f*4jR?!fDbeI z2RDLCZX;;N+p)A-c+EspxAYB7oaHgKpIL3}r+?rbTqK+fUfq-1@E+CTRaaRsb$=0@ zE<=}g*L%DkUPX4=p#rAm(>dUo>Ab%#wq->ZG}N@zEF9-b$V(7P1{bBXKs`$q@EZl_yJicfs}Cyo#Hzwy*JiR7uLo?cv9?Dx|oNk-$5 znop8!Je~{&o;Cg)w3Jt+U@ROFgSbe!o^FM|MXA)qlkL!MfEw34K)yxYt2+^SMx8oZgB_r9)LdH3OmAGv<*rP>#& z;q18!28srACJrG44XPntuXI|E4G`nz&1(j?vb>sR9W^q8Y6u}jp?DCAVGOabEf5pK zK=B@9szd_0Us3&Y%rVCtZyXmcT=-iNngFispKyMu7&gSr$uSKge!=@c9%*5gxvv714CkeN^CLGe# z17TJTWH5tTu;ynC1Pc}oH_um}W{y0loqII2gZ2^~|FA^;6a4JSd&j2Sr`bV^8q0A_(TB}+8zURQ03yhB|ZsIKa`XH|un z4}pk;Im%8oGzV<3qk}^h7D<|Z_bC6Iva&oAXAu!ZPwGcv`}v8*y?J%oz#e&|G|ONC z08!RzVfH!z^?vgxd;lGv<*5F~NkB*m0Ain#$~lq9ZEm5LCNbFQ1DA}PTIpeRe2 zQBiJpbZLqwxqp@HG*!FcE~sf@gv^0AMGzuNW|RA{Wm; z;<}_0)tjA?5EFqIFbx4Q^}wb}FZimgs`HEIieloNy!hhtXU<)?b@RqcFTHkfaFk`q zrOTJMHn-PS&m@Ti4gJN1)z#IqD97W0_j>vA<>URmqtO^fmo8tqefw6Y+wF9_w{G3K zcfPSD zdHeRwb7$AjpS!fXyIWV~bI&|;@#49~{?gHKoVPk_YiIJjU3>q*5B?ilTbtY4JF9DJ zqtRFi28r6~$n!;^u7XTajL13hUdcScojZ5o_U&7nw>Pg{f95RVyZ9*ORK$L7LJb( zBhyc&FjANZg5pmmuhsrNOBIAVZ; zs(}?yGwrlmU=4Hi#V?kvq>>w z$3#@uwK%!Gxj7zBW&yg*{lo$S>dIez_~GT{72`A!N;4M%lC&Kk zY`(kki$C}Mu$eQw5y9rhs@*%A`QXjw_g+=>VA13=&I!#o3N|=x)RsVFAXaz+nXeQS z2ryQoeA$p?oMnki++9816oRjVH#3DIN*7Oj$`m<4j;W`1LYAQsA2qRlmayF`7qjz0T8{6-4;y0n6+?<)& zP#I8-n%N{t+no-W%|caH0Mv(|A%q~}VnPI>FcuIe0jg%wC|)Jq={Dp==}K$Y2FH| z%n1>tY0G;ZO^PJT!5o6ciH@m8q?ly68x4o8R=eL@^=cZtbE%Q!ovwks599GD);Hx@J3bMZEihHpV1&TL#O%G! z;su0>i6O4H&>IYn&0;YQ=k2yCI6eb#9GO|QfY>6|bY6i#WmTeyuxNzPYKkVYGBBB{ z63ADTnwj^NSqOnyOf_h*5JK>%W<)=ksrou-P+xPCaM9egGz1u!tg0rX;Xv56+AU&a zX#%3u2{VVFwGTm+3Br^l3A3bGO3dse0YV5Gf;AZ$C&3Q!?+}n>Syk7}Kp zyZ_?Nx#DKah>xYW0#3kbm3wR^SUKUk<5IhtF}-wfD{-I*#Z z1x=DB5VcN0K&rK`bbJ^JZ(eIAHsUKrmcATgUrbg@5aD1%kanwMs?=g4GL5Ax zFtgwl>O~w>lQbnJYr2LcO>o%PDX7J>+sWdUGk>rT+XM6bU5 zf^!Jo6{Es;gZFmj;zI{VM`cl!RXG?A9=ZBRP<3T>@%(wSK*TOhHCWKlYPagTR?~+c zeq?+54l%Ql5`?&{{ocXRm%j964L+enedX)1k#247q-oY}cYGCs+Tp?B_MQF3{_^5d zXJ>ocl-~2`d-wKtNF0D}w^!BG_RfB{(;19LBAm6_OG_)ljwmtGqAIf_38ogbu6$LO z{eI7aI+4+M98@UFfxw(}y9?bj>*vm%KOPkEe5+SgZLHj|BuSFACF}_9{qO%^r2b(< zB18!#sj6RGTs%75_r4B6nUlqpRbdAb12-Hrlo=!(h1!j7lz1l9R6BM3a3s@7)hnx+ znvx@^ulBcx>;%Erb;06@-An;agh?^k-QE@_aj{VoOaT!&9t@~Sw21K+aN>x#(eJ9p zfCg0qS@R?#(&)_t4ijPXq!1z{;_+yBe013D_Uo$3x*dSLTGHgemU$}!Gsw)e_7x!s z8bATuCXpVO`zKbfpNQ51FXk~jm+q@Ixq6@p`esbh|!K9?kB zR@J2lTeONt%_(W(oQO33c}!W<({j|_?WYq5f~xW~tgs021p z)O88f*Is*Nd1bY?wCW(BKp-=$t*`gG-4|bcflzy2h`8VjVN!VK@~W%|V4>RkZo4}i zPqI7!0%U5$oAulT}WJn>UM^~qqWrXbXH+3mLX_D5OX zKRP@}Qzt?pkeStWnI$dNYISX?C`Nl*hfwvt>MZoU9vvMY=Xn~;7e(3YEyAudb5&Hr za^~#$V7j)x@#<@@CJ6=AvhsPWm3KM|i%a|a`%#HXEW}n#>MYHQa^yqE^Hy1o+wHcQ z0(x{jVrF3uzAn8F?6NF{5#Usnh*eD_&$AW)VP~u`5*F|Mq%4!X?Y(b=pJqS^RR!}* zXti<`x0I{0+VA@3ZMxnP5AVSO#LJcrLlmt}~0a(O= zNQAoG9H8N_U?*9YmPIYZiIcd(G+58$}aSJeSPE6bRXWm!=a03}J%Tzwi~3@E0&cqAUxjG4fGVS%$$#Ce0Is6;%ojK_Or z=?R{Rn5)&bKorbEsH?i)}==;aFEAmcvUf;NJe9!jqh{$F>ctZ2u!#y7`qHINNZaII$I4;VaNs*_mbRq3_+gX|rQD7$TiA0l; zAB}xgVkU;v)4kVr>Q9&%yw|2Iof?5&++g-G-KG+`Q+tTy=JXYszD_4QZ^U$`GjD{l+6B<9bNW)lx;Wz<6#zHX;V0!K&0R*@tjS^NfBa)cr8das@lHffv ziMaTtATlKo_V@RT@$liR7rX7&sF*za{L6J6ScFZ@3hx7;Rw{_b!kGo)GO zLvV=`q5ZwR5Y)M}uItUMt(~2nyp;ohxZQ(ekn;hRx8>!f-Ms@dZ%}q_d1ZwR#kf=z zGvs+b+#a6USSzbhnzkN!b=jiTut*lHw0KPdY&x7#JMEXz%enJlOeRg^=k8Zp&% z$qZ^PbJb88fmmXWF9-@%^<`Nm)P%Y+Wdwo}Gv#?3#RS31@x+N!H8cdNu^|NSIDrO( zdS9CNAgA7#)K@j-3WXC%+Z_u^rlv-yRQ+%`0L=SP6joI=%$P(3Axr}yPI{$~XWZ|% zE?!(9)+qk2J(+suu)5xdr7ykkDnJZPQ%|NuT(hR40i}ose4{j^wSF}QTs&H@QsO(tYj=#(2xEI72&ACEzjydL-;|By!Jn_V* zKJ}@0dOOe`|B3vAU#lNL9r^G5ljH$7+~4(hJw+aX8#ivu1)FbM{K~)YKl}gQ_r?Eu zF$KWKzxc&3UVZd?#}vFJW^=q<<(a@quHyX8^+vJ0ym;m6rRZB`Ye+-VC>As$D5;SG zroqEGs5`Buv}vo))EPRpYeqXZTT~ZDmE=?q7*`cf#hbGx?vuTq`kL;F>ukPDcWp2o z36Yuln3xwrfLVT#{z3b|+GGlkuo5#xY)Snk`64mS<@?8V-S`$%lyA z-31XxfmF3BN>#6je)^fNbb5SfrrLrBKx9O$8qy^9!N&s=#{8$VAOHX$07*naR4ky+ zK*221loClOB^Itjh!%N^(SWl^(D)?-1|c>wf*4GMons$##(~D;^6X*C;9v#@o7Hud ziV)O{ILbjI32oGBwPG|WnADI=N+-^v0?_StopWVbWX`Fng}}lg=(&vx3k&UDZ(-}{ zXT3+3w>d_h3W+0PIC8>LTS$NaM1duMB!QW!sQ0y+8calnqhat0XYITbLS0p*hT06{ zaRFFSRH<|Ac2<>Emo*D_7kXKim1VWqUmA@@-q)(Sw7j~rvs+Z7EAM&a)mLA3E(u=Q zg{rKIqJUw~@3mT;{r&wI&=5IyktEBq!@c8Hd!d!*MKNTdqr;JKnmBppnP*;k<@)7^ z9_}vWSFT*#+1*w3qwxsPhps$)I24YDjPOFtUz zCaEurqSxq zO?NH4_e@5?^1NubDRCGMi&m@6Ohs9Ax~+|sD+l|dXP+K}@H`HpmClTtYCuK?f8OHM7zY%~>AHUuRTDJXW)%!Ei&e5 z7_3kur8NFcVT zPL0GP&=9M-vou}oFKa04D(vm;=XuMyG|3XJD*}qTf+B4tomR(_2a&3JKh?CF5z%-& z%9FepkCHS=)5LLqFdPQ+dAmcPz1_WbyL)(e5Kmd0{Nv+eW>zx4~}*R!-Iu|PTnT4nqgAz4o5{%9Ez*P#a@;r!lB!f9@4#o zwA1N!x|(I`1j|*Pq;;?7mR9mKX_rOexMQ%jGizp46vd=CXfL!xEChYeqw96yN26P- zt1V&Q?=Or;b>h5Q5HfajW}_`Gs0N||{6rOmtSa~Otfvs?G;?U>NnNK5BDSI&93E{Q z9qn&yY$Pd(2$A)ST5R8V!!14|aZZTI%tS<0LkMgLW`MI8-NEd=5vc*Df!G1@5TH7} z!vL{(3j`wbKA54d0|G;g%q$?7uYJvkZDdA7Y%$eBRn-R-VInZc1c$lh{2h#W(fJ&6 zyovau?f+)|qdIz$f9Pla@2~&qe>g8jpW|(a>({SezkdCl-VOxdv%l?r@fZB>{{DUc z%>L=mB>&*=)t~;Sb58Tk!FLgC&WnTICivM;h6l-Jp2pv*SL&_m0s^qL`*!~L)9^rZ zLi3G+2oyi=MlUwNFb)g_sW2r(4#tfS)QrrCNJK)=rjMpkUJ}7*X8FF$SKj=?)XX&a zItmH_fS6f;zO zmPkW{5CEtTW*U`IP>=yUGiPHu;--Iz(5y*_0%CbmPSJxHLnv937PA|INS)8ym>RsY! zkZv~D-nrabNBUUs`1CS$CmCWXD-ZHn$ z-gP!Pm~Czh&YwSZ_3EXQC(32r4F=)%J6`?Kk334u#9cAy&Yay05-(rA(k$z}-3go> z&2qj_?FQp`CXACd`+Iv$YK9&LMT}~r@nA5ZvZ^jVv0x0I`uxQZX*@0t_x4jtqmh(> zmea*#@34qPSqadkMDyunw_ePqvs_Zt*3I_GlK`T~^zg8VW!)^61)n&vJ)7>SRi08c z80;TR_xGI#%A2y8m3Ood~Y|w#SHh{a~@2ov#P8_a5$NeFflA4kP|gq+ofvb z4e#$BR)cCbox5XudwU0MM;O4LKJ>!?PJh?i@zK{`hl8%M##e+Fhw&W1XCA#C1wjBF{=J)2igoMa z%SI@!Y0Vpj8?HUP_f_^R1)FPm=3fT_))|`51ISq{^lX|l04J!Z!}la;}m z3BAnl*ly6fkwKu|vVGKzL)3GntC&b%*_;6|iHPW`I_PMxc{4d`KnD033eBheO^z{u zex!ReRR>r&+cAmA9odskl+{n9s;XvgYP!nbBxPpio=SxE2lHNLX>OWSnBmaX!9-ZK z_lcV+u7zG^c&6d<0L-3Qg49!=$9YX4D^HI|69B^OAy6)gcIt(oeG8CgenmtOBH-+9 zZVa$P9S&n6kwET%tI^Rx2?!x(mn~qXMnoY*tl|a8!NLOR(=9x$ISyZkN$t z{Ka3MKmW4nWPWh4_o`Rja5uq$ML3AmEU>iDM#0I&Bo?X zeMY2i5s>}e>D5bDx;Cq9IYb(5gt`$;E*zhH{GxkgIyql7^LaZvTo$Frz=P2u1RigU zwoeRCoIH8Sg1OOP4Q&P{3M=7!HPT3{x;qsK znshd~SPh1ClNPhq4MaQ`j<>c>Y;0Du>2f}wpFT4Vg=}qCd%MfoY_V*+i%;zjDj8J8 zXk48*u^B~?I#UA)5Zqcr;-GD6k}8w{GfvC_4q~xn{Tv~72Pia6A_@Th@^gQ+eX=-x zX6#7r1SN+PXX#>&`b|yK@v84i0#i=ZO$GvS5Qn8<1gf-T9!Excjg*)%O^ZFn6 zp^v^EK>CKicjvc%e&?6|<6HEtza#Iu{=-;fjW5KD!+3t(3W6T_I6v@aeej{1n!>n6 z@f9iZ)_9@uBM+o^K6oQ}uzO!+k9_*t62+I89<$kOe}Dgm5Sll)JQJDZp|$1wxx)d) zD(;fqdwR=r)TKEHtl$+h_q5vUYrAmstX9feA|uNs;6$#ui-KWxyu`=hA zZG8p$F`M~O8Td6f_cM-;K1mYKaB%kxKYpZ?%!c|LVcGAAU|Ht4$}_~ON5hC1+z+G= z0d;p64DMNbl{w3!&Lfe&lPCAvWHlBMWd*3aV|6Y)nTo7a^rQ2oUJVLArt0+7pg5mM zZewvnrjL&VhXnEZvg}jW>Hsyz%y9{fQ31m+o_K?VAn4D_p=Dr+?%#x0u!;ZgPpwZp7K?y zD->>=b-Yfi)9wXwd;7bY^)^-QQtA>jO{a$;coDaSoJffgW2mawlSJUf;&48jHFZ50 z46Aa;oDTOV1cr60otunD2b8!0f#?H>=@%G?gcYf;Bcx!WGyv=)8=X-k> zPi&9Mf(^r{w#)hk!5>VDouh z4TDmG8$qoTUN&9V47TIJp>Cbn-al9-Ynx`t3{?zA0}vc0BI9wj^VH=chG7Mf;Ld=@ zSXR-_ojK82+TWXo7(if_ot?eGuxy%UUU#Ev5JQL|rqF~SFZsIj2M6=3SLcO?y}jA= z@L(_~2gB;*nG+$(<(-+EQx4iCyZGeJ#^_Fm0ZzhDi?KX?YQRiPnobTE%kJRuoy9U| zxuWaZ`Fu7S`*0{#wV6^2v$jrU$uY!JXU1(aYFbs*{mJrRGTYo3jYcuGP<3HgX1JY+ z*kKSNBQipM_PCllm;xB$1R@JvlR)BNL4+3ov`e5sAQE9=5OQ@AnLA*{#961FDBs&| zATqQLaNIgyj^?@!0$&9aoqWS$pgRLxxhPo0%T8Dlw}E(ruOcg;72umY)R z-B%rAYut+1+1a`G-g_T>@WC5BkTuqLVe#aXPhOuG%`Zgw#4qlA0subvv;PJD@w@(Z z`jKA`@4WuQSYwUjcz%uN4}70K_?{a>_C5F>xjsjK@FBTAYS6DueAN+(YdpXB%;#?K z3_o|q@#$y2_=VGBdwcu7`|f-A;fH_bXMW~7Pmi0n-24bc1|nV)n$HI;(|p#4U9y8* z-OWwSlA9Uhm@(Qcm-_e-<(3t6OyqFQMJL4I{)<0)63Cv)qYd~DUa<4yz-QB6m~CMGz8z{2QjK%Qo+&oO^J|GPRZ zChiN1aG~ZqAyGlLzu>+Vm@0qoXM)e2+R(SF${;r_7;Spj?@_ucU@wEP|x72C5NcC zDR~UUOdI3kHLrci{$BI3y+=)v%*?`H{pFRDCr=V5;b6&PIhfA&>$-t&OeRxR8jUv= zlfzS|Pc7yxNoq?BakLnb{I2vYD7{I8I!>!#$;NzEg8ExkvckfE5eFYH}l!d zBmm|_YHbRoxVsyHsLN{Wxv#(@^{UDBtzj}k z&27TY!nw$sX~jWsrtR|ERwQS(pA$%eAL%r+@Rd2Iksgt=S*l4yLX1`WI%O3f6M;-E zQ^f`%i1)2ae}`?PhkO^ncRZ)a>x8bCW1&NVzZS!XPvScm|za( z05cF^nN8*+mN^sA`64rM^0Xq3u@ZbD)24Y`d1Et8T{oQ^9>o#l16xXFT}qw9m~i#V zmGkHCYU_rCKyb67EW0KV`5m{P|I}wbD{!~Y&XlejhX?a3ms0A4sB;hmQk1jB zbnj}-Y)rCT*#2(U)rVEZBlo&Bq_VTvg@XmFd^L?DkV9Mwc#MIXs-7 z7>CCme}ateIDc+1EV{0lO_$5s0bzo9I(2&UwsV^folWO;U3YDmO(b>U@SqWn2m7;f znPRAlN;b#iq6oA3VzFr2HeJ1Pb$e^$U~jQ8p6~BpEsA0|9I()2G8>Jn`Midcn|6(w zQc~MKQJy??vN%WZGxbvU_NK{w<&K`j1r| zU8~EaQA9+{x$P2>g&3F1#KM{qu`lKgoO8(KVzF!*+u7MK3ZBj8L82zz+#CvV#{!Z#VUKoDYzRUE_BEX5cALRAKO+W(s5 zo5kJDAQCn=hA+AM%y2ZA>>Y#<^K-*eGE3G>L&#@pL5P^xscY)IpQI_Jqz*SfecO4g zacg2{XJ_3Dw8qy0vO@Dlj{*S7fAUic&>z0)uG{{Ht5^Td6F=PklmEB)hc|jqYkZC3 z`7)kA_?{cAUVO(dhwH#;KKNdF;7$7Ad)LPE7aVKB=Jm%7&xO4ARrV|gAR_O6_q#vz zp$}dE>2bra(zAp)MP3t{&mGxZ?r_uje7=}1&8#d!S;nd=t)A&}(yX=>VF?nL)T~V_ zdhYnn`UZ2(ZQwaEvQO0nuu8@Rj%gA5T*{-r^<>;}J!Xcjyy|>x`_;xduyfUC?l4m` z&vth+cQ*hMgpAEsS(rq^k}1=qW^UFKj(INt<;G#j_Rq|TW-ThA=OX)Y+A4&Ut_?ne ziL(L!>6iWJPqexMc@I6=3cnV>*;AX@^_~lJh>rp~&5b~2?&evI+RI2i_X+iT%(mF0 z4rO;|UKIv;eiLV{ZcowX*iuI>E%%%@c*NM!O0?P!o|(VMxf2l+GsuGwk+7jJed^DP zh*L_7)vH%sHH0Eab>|&tiEv{3WL-Dv?P5B=>-;^F>0Z~=8{^Z{ z$r4}&mnAo;D+WV~ZK{b`c6Rntr;B>FT-xTw)_hjOh{wFF7n8}}_V%5QRM*W@7w7Y3 z(=I!A8;!=pLDiH@|#&(za~~ z0id=?W=$&C5bDLeOD&k8)+!v$9)28tt)qGyJP1iKjv$vfd495GDi5a;gN8q+i zdpMa9SVVHgR@ZgI(TT%@dDkhRNeyN@7k6`lYujj3>tddY7%X|aWE7DoE@o*-DHbDf z>6#`bDy!HwttVYJZQJp+`-WIuCWnccRGZ{2vlo>1ZBjRhnAE{S*B%d!5c;(VH6sLu z5VKj5UkrDobH8x6~zt77|6+_1JRAwdIX`OS-$ktXX!=qBiv| zH8BPz4kAwGW?k3iBnh_wLz7x^5EBb?DvECp!oU)_%Mvvr{ho)|Rc(|O;0Tfkv`t%7F5ps7+ zvnhw5oGYgZtB_1Oq67P^H#ax7{GL_IHe>ZusA;C>vQjI5na}JSan=RWDlZd9F_T9O z=+RKGdA^Y?*1ewbh{Ef)>$Qc<(ldY}LPWOW3$iq_uOD}$l)5IVTT1F~>M%Gs_a=** ztxmTm6^VK==h0sBAcf$(N}}vJQ3e2k85uMg;Lac;a(4qUi%5TpIbt-|rRNTuYzpts z-LXxQMSn8;wG*M$fZ3gM20<>e&)q|| zN-L!!epZAToIUs<6zVA!F<&NP63*gKf*of$z5j>E%!#OJn!Vj!z!^?%?n*?~b!65o z>nJft8Y~wzg`#a*RRtX8fAWXg_!toiXDzx~ps zEAIC8w|@@6Ti?oMS^df{?*az^0ckZb{NN8>`t9E~fPp7~_B+2L-t+30Et-j@$>G6l zIF`NH3>04Rny*vLlT8?+_2BB>OcToKvg^<(f9lc4nYZ^2rm1U}O(!g$`P^sSi+bL6 zsc|#1AynH2OhH{|^NtBDgW19s^=wcLHa52Bb4%T9P?c@lnXx%Hbz0U9fq=lou?St~ zW@$EU-Q#4|l~-$~I5}8^z-2YsUCcvho2HAgeEjp1qA1(8OWicaX;oFsLOI=4!hAAk zB2}-Kb4LKoVQPV>Vk#&5HaVCt=CzyTPlpK8i9PjX4&c=yhD^NfT)6Cjna5ZVacWU7 zV3r)NU2Nu28*3HBY+B7`sj8|NhpKvTX%a#x%Mr9e5_V5*TLr0S^PHzjA-aPtAaMu+ zO`a%(aALav;2Wi>v9N#WRfZr%EX;h>$>kwLW>RWXlCH&xt<$q*ec@t5WN-omp5r?#ijyvx!g8{&ZATj5 zw5;bMVX?F+FN>n6s-h4IEU=W+_xBHHv-#?tCBBx-K)J;##IU`+5o6FUm%l6Ag(<|C zGj&1zW6xJ%yXxkS>3lJtEtp{f{!hOm{}lgV^Z)y2lW)J#BUANd5o?Y~Oz__Z}r za9yz$Y`&nl8Q9EcKZY+{fcX;BM9lpReh0GhC==hn|30Kc}86=Cj#k_v)yK zMUW^6WW=0HGDzTzUKP3Wcyo3mA9F`$XL8mpn&j+9?k$=`M93=0Rm>x;A{Vcv#WDB! zZr3!Hz2vEHqd9sh%L%b^Do^KtYs8nNmurQ}?8*>Rp#q zRVWe!eGQHt9mUN#5FBon6Zf*_k(rVEpL-D{!P$HAF6V+~?vjYflLHXqRn0hnzC#DZ z074K`bzccuSF%=LeHyv-10Z+n)sANFPR!)weJ%S+JJ~bExJLUr_t%68=GKq%81iwD zWs&4eP6$Q8Ai$G$4i7E0Is4H~yp|3{_o4=hnng#hGbYQbUdCh#sC2k=nO4z53mIs0-pzh;0}O(@CWqW z?^ZxppTGazzk7b?;srBf;vf70{Pw%;UGD-=|BHX|mY@2mi@;|919AaN`t9Eq;1sY6 zYy;xv&6+NmX%a5rtR&9~pSwR`EwKv^=$3MB{ulWj8395)v+F6Of)`E03kwhneJ>=j)h z%V8NdPgL`zyE@x~nL`kcEaKU4&JYI<52y3x(m+LwK{$jcOdVrcw<%eZlDQT!29a3A z<#MTNli93kIyFnF3n6Z8j+niOk%^nO=^Aw)aB%awZtB!FDW%k1yJ;M7>zamO1TO-D zNLjK(v82pZ*R^Gkx^9;BVlf3tCLg^V4i@dQ!_guHRz+c!Wz`UF>h|DZ0@I{!u0;$i zEI>+{l1^rel&o&r+}=)vATo*p@VaY4j73qL*xvXOzX;a2`SHjjkF0xv*7#b$AN;`| z-0&F9zYg+Ge*?fjn|%A}d+nPq{;wZ;>fbf%gv~Xs7oIQU`3)Co0@&H17n)an$FGHZ zzrh~)#7*4_@?ynWu=%{>ZU0$%$8X+X;_EAAGygh8`4>))yY9N{uDkAfzF6;_E4PS1 z+ua;Yz9uxED}ux_7St}ZPPz;gLCT?*fkA!Cbfy+{MM=6Jec$el$36YkZ|bWk%%h(G zePu@f2gzkI*{R+45m^pKrDH57j@;PDEi@p{-8QRj*pHbsdy!|(^vqf%kbCY1$~sbm z!QmVvv!n*H%t^ZS(U`rwGmBA;Nt~3CE$8U1)gblkiq0PNoZ06q{(*9cDCnBaoRCBG zj*+vglJ3>dd*ri5F80X-1I&!MSFSp8PNvhUdptKy*Y&b2E27XBPm>do_SN$_ax}*W zCWnE9oO~57dQ_>z#~PWKxQInIk{k6s_Nqz*n5|fBCO3f1j3{4fhC0m29Z*3ubC46| z)KDQxXU?2??Q366t9GNwbo$9Z`{e7s>9ti6QnwJ&pZ}KzYB3o&xrP1Ax(IrrHDF40?Lm?)Dsa3;aS(MBS_rP>GIh;*) z0ZM9L|Mf55*xbzbN??FumMIh2laGC_t>=L49?q^@zN8L!W8$uv%@1~j*xfZL3!mC3 zQkMX)7Ym0E2II&6^3NBuLl8SSkX?N8G0{`8FTH050c>g@9*u@aa&I@U%9HNanlw!} zZ}zj~*+K5KJ>D$D%2>3WccxvZ=IYcEft}rr;DLpLB-hTp?GlM3_v!wjyA6gVLAowA zZ9~jaB*A9;a{^UWS(YUWt9siB%!#Nhin1)*wyW#ZG|7P?SS*V1=0>GDTh@+!cXKzu ziN#EdNSmYKuqvFOYKvuCH%nrw25~s3+!d}J`(QAXD1gDul;$L4w0e}LGQgx`yw9p2$;KQR9G(egk1`i&mZ8ZUl4U&iyBL8SS}$N5M8c6y=5uxpD)}DY$kwb&t~3z_uXH1=_P;qPdxENrZV%3&z<$Y;f+aO0VsDNuPx`#8H3Sq z^VG?7HKlnsyZA)6d$k-6HDl zBmQW^K*A*AP-eD7Z2cw5Qq5yKq?K%z0Mew-%rmu2L0=m)2#mlnfDl*+#QzmL?TYa;)_|Ed{)G2SvRSz zFJHa1dvFMNn`R;CD_(Q+TK~z(v)??J@ylO+&%gSYa8HJpYtoaDNhJ;GzS}thTxcL~ni*9(r$f=>NsJv#;M2*cU+e-uLD!RR9VIFa;ic^BXNSgZaFhT2l2p z?!2=-+-=(S#K}9C%Q+Idrc%Q9z2W2vt>eopq^; zfz135|L|i^T=>gx{EoX0W)!%n%JJnZSB8U9m^q20f+@gYW=zGy4?k(}zxjV z+Ae3!<-MJ58i+YCk2l8$J3B>;L4v6=v6;^H4kUz5(}#ceaTbZOOqypAgD40C*cy*x z2r1dc%LmCxSIY*w`_n)Dvqw*#+8R_vvzWsXgv;@ONjlQd>fv|CpYWMSDM*kdH885iefkbK&b`TJrT&wVE{XXaGcg$u|@f>*IIzg!M#6SRdan! zZ#|dZiA^9THqNx^${3Dk%*AKCn44`fYnhMhOk%3n8fR9_=1SMtOA$>C1n!v(Z<=N@ znMer4)OD?DQcGq=OlIC|Em!Z&V^h-{*k@+Q%^S|gn{bZ6*JM@>fSH*YjQn0FWF2Mh zGCqEyOynYNCL-EP4v($`x%Gon=(i-xseb z=?(!U1d;9r=@7x8OQdV)?gkNQkY*?esiCC1q+uAOJCqpd7+@Ik&hNk0UH87g#d|#8 zz0cX7{XDr<<@)r}9&U6p#UUIHPGx9Oq+82ob*|(rEKVXEWK2ME$#T+fU`#!}EJsu0 z);m+8h4Xi+1wD@oWDzWo;%~VCDY6nM<7 zyE`HMyZJPRKMLHS-x^yCn^O8HXB;uGEYvM7?z7H$*BATGkKtgfCG4_s^D(nEfiZAO z(f!-cD-Y~YXKbYL2B7axZtv-!G-3_Dtiq_yv1_BR`|NB_Z1+;-?{-{BoD_Z9J~=FfxF-zIAe4 z=5+pv=9z{Qx<$nJ_%ZN)W~7;Dk0aA+L7OucBX0$I?Pu3%2+S0}_(@d6{+BWIHqAEu zBc8>?kS9M~yM>Wo{Jzw2pmsVTS&~b6<>8kAYp)+@3IJYbIyvBiaLxePL5B|_pX&~+ z0UR@(S14>?$B2K4V%qv6FI*{KxFuL|3oqN$Tj!tvmqXVJK&s-aX)4#RuNq{Hp@+kI z@voS$STb~`#tB4)4?#`SpN>)Gg@^TGg?|!tdw)al~d;8{9eZ z`IN4V4*y_CJm)MhqTj=PS$*|u+mBZK=h5W zk*dr>udSln2mYAaMb8dFce^|0OK_6fBW%1(T$7^9%2d-nWu<~i;{Qc`AqCMUbyTL^ zGW#gu)`N|4cE{4VCJJ-1y^cT1E5!$R1;Eq@34eCx(8^&G%PS;AGXHWA1f4K2{IK~Y zRgG}a))QYqbmk=*$t(-Nx_+U%h+`u zyx5o(1H?lb*8fd4I(>Z_5PHsK+wGQr2|(M@fAKf*DcsEmE2V)wZ#~M^sngq{=g61O z2bEOuV*M5&+$g!X(5lC%vYFv^`cDCaOQNmV!b&*;mO&e_ot-*)8p!fzb#>AfumN&Lm3eDMEZ{`;67oUj2X@8PHBDmbTo*Z#K zgjd3Y1Si(n03if%oxQLSe|YXcX%gDAPg`e+2-!#aP1MkAeN#Or8+XiI$py2?^Wh1q zcwZ)VLxIBoByOG&eGj?R&Rnwzfut1BBfqW%JPqFoajBn%eKgG7$`*Q{2*-ehmvCZ^ zzq{GI>&CEl3%G|9ohab2-ETDM0iEBLX-8BP%17Aq>c)k|rrecB% zlRAhw+MR@Qd3D+116Fx)v8i`yr13K(m$*mRs`|rCaq97Z6;(Z0FjiU@GtY8R8d#-POjVlhz*BGzVBG3dRl5upr$Y%5QbjY9zFX;IkR>LZm3b%W^&7f!ibPCkW9qULc)|x7BWA zC8g58$CFlohh|jJj@p!y`7P=rEm2|BuT=fbin8rJu}kK}1J}wzxRAC+*Mzb(@oVuU zTAKZw26B}Lsq{|2Aluhu0{>zo z@r0jeKAFLEA)x?Gc0dLc3BV=$az~Gd_|DB7MTxdnSoyBZDtt}37L2+Vrjsv&^CZGP zZoQ7GMDTC{%TC@E!8GTO-t&T2V&AtsHR`IZe6rdLT)sAmzw?x!CMLFi-sZC|Ra)yp z?W5Rf$d~$2dnUL=b}b#K?N_Oam!n`br02ER1kUWpBqROI`gEfb-8T_l)j0Mfu(1}n z{j%kAOgllWFCKsk<*p&_BJ`(hqZY@?BAIbPo}B4c7G$w6b`+!I%? zFBUzX5Gyz`G#hu1mt|s)NYqIDq#ahE!Wcq1>MdLo*R}j7RO&~@==!ERV-jolOZ3a0 zXuS7wSiVV_A2jggoAG+L3;%gxg9>3(QB!ZEu=;wbaP_O?+KTKE!)@1__Y^8~ zb<`ZZq}G;*m1(JBL8mvjjo^2bXjbJP^;Kstf4UwfSuisdN_u4A>Ac^6=d$Q<@Z2Rw zx*4lFE>d3qlViu+w-_>YY9Bv-0Yr<7GDhU&w>1*ta)B??g>Bm{X|^#nK0d2ZX5|!` z0IhTZ6b15%*N1~vj*x`u3(b5HurqCW=!4-TYC{-0GnAHFa{kkbfgcBG$s&dsKcF+y zQL8>LQ4uvcX~~UmRhi{uT)u4652+-e8KEg@&+(nGo%JzQ-e2CStzg3E=XX&WDNBgogIa%a-^!zgx z-n<2&)1QNwD&AK>GoJaMAcvU9<70Ky0B0(JGcD#lF4LF3BiGt8N2n4L7TLKJQhmCv zbB){Fbm0d4|61HOq_uD_*54;&eCO6?z(lXK*Rt6y()_8Uo3ZD=(x@B-u$LL(pTuG8 zI9JVicyG2f1NVD0xY_^y?-ALXWF9&zQv3R`16NsUGk>v_edGFjncw|_dcSx6+wGgn ztj(j7&ePC`L-QxPp>35LPORM4Oeu=Rye6lpJ+H6o#5p6ft^84)4hjbrCpk+d!g%i^ zOkhN>W`jdYB*HUJ?`ZcE7hkv~aR`UZTb`UqAd>@S5uB#8(v9ygha}XikGjow=B=f- zj5L)2J6tQ;N-?8J-C0SfSfOi~Yvz5077~P0T%rqobQO!Ht7PpR%>Ld&Amu`+VzXQS zWs;B7|9Z?%39TV^el2EDCyOh#;5u`ozCgW4x` zCi5!l*0hfmaX8?ESQu%FAJMY?To$t>ZZAr*KZX5;&Y{**rn+R>Ty~Dr0{OAsTOo4vSu5CF)T304t zr`P=yg#H^x#{ZZNZ3BV6hUmsFxqEybK{!kj_V3dlatp>A3j@}>mnYluB50&78f~i^ z^N|yQMuQXJk8@XC<`1d8fq$pHV9=IHd3~j3$#+<+eO=|oWAv{C;WV#>Al;zF+--2J z?yPsMdcq5<+@`cq0ian=)XNCt{D`0R?PJD@a403*Xi>S28ooTg&c0iDoMyV%lzBlZ zsG@dIHecx83TC&$wbkaQ*qTKu%x6D)H7m@`6`dhKsl6mT?CB-UZH1+6@fp_eqK~UN zJ=Mnr)@NlTghOsgJ~hUS9i5|?{iT9a0k{8-X4%390HGUK!=9HDDNUc7euH9b5b75? z(uuvxEqiq_*KE2fPWy@}CT8a^{Wmh*Gg3thQUc7{u`E-;#)j(g2FXutWNdC39fNxd zb>F_V3k9g%&go{cl@!Hfg9hM&nC}~FDUyD)eB@pc1x2D0D_3cy@_{w{USsf4PnLc# z#C>Oi)o(AZ^P|OSJw03T6>A(bw&&k6vmdM5)h%4S2r$CN5 z#>LyyP0Z6j(KxVsXQWqF?>-~Xrmgv-i&OPE_Zf=mUNt2RfU`0Qqf6Z|1gs{P`rTg; zTy;PGNv=+WiE;E)FrWIvP}W)tczIaU9jw<=SL+N_8GDL>a2Vp>l+Mq9)2ibX&GVW! zQ-jUE_P-w=AE}W6;JQP1SKE78x2GucN2K{j{j;4Wd9@uZt1^=WOgXvd7>4>{G_AJ( z^j2#zV*}urq&5@(AdMq9(zPbKU<21F3ACXsc%1i=z<;zTFNv@HTZKSUL_L%PI7dorP zo{a!uN0|pZ+SSfN6e%bYjB!!`NzKW1IFPi$m;*%NY$sAM>4mpd8XW>ns|LAM;%4+S zE5I0|)bG*+>cOnK%$CfUuUIU+tgSvd=#1StUL{VSQPuhHjvb#*nB5AZHtIVc++?4w zcN;{-JL#_!w3RBfsPqrW6-U{h50%Rx9WAit?(V|O7O#efZ{GF_g&tWKsJz$~!^Dz$ zwuZBYe$T448D`GB^+1BthlWW*gI565E@ z!GczIhw56FmTue*G-%-yr%m!q`4jB=$q0mj7(&GLvy}t%FoXypbacRgU@m z^LrF|EJj>KuEQaQq2yZ!>-thH*fQ^AYQmF0cS=-Dw6mBdVWb>|>(nkVLvVOWFzXIt1&mb=^>(TJH&wXmJEtx-qhenmj;y!v7 z%3&4PqC^>&$wXw_N+A^r-$&6|d@#PI^c-(2Ditw*%V{0cb7^-5Om4}4iH+mT6!^7X zgvI~td2B@X`*q#bjmN9ai_IrU*c~@xjngYVv7MhN_T&>eDz>z`ah>GXwcSAkM12-0 zQL9g36GQf)M&6ruoB4rT`DtM{c?Tv7A75|(S2Ry7bHqr>@wT4r3N!jg%G^9&jh{>= z*|A>;_LO1e!Zhx}kPrK;mO{P7{{T{AjmXA+AuD`AnfpH^n|F?PhP{{5)R(_i{23OF zp85|@?mDJ3N$c3ps-f8+0I+nQelL z(T7U4<~5!yFDRn>^lex$TVtFk_86zpqK*s`2l!-iTnYr+Nu1&PJ_K+k-gm|pUPPQ6 zl0r3nTqPBvp!HB2gW&R(W`Eaau*K+H9wpZvF#&z^#B*TB zKyRg&(0TsY7lFy-pO*K>V4gA$Q#+M~v-gZKl&Q=n=k=My(-gRp6C8;{Vpbpagd@8Z zp`s~s`|R~00_S1lXLTkzwn6w|#GRdL2sZvJ=nGD`p+B|_e0r|{1KSmA;c>ngDwj>=!2-d~^gosCflM}qg4v^ACLf`_1H*t1xyT%zBzHWak)JX&y_@5Ao zV~JI+vS7Wsv4~Mkv;Oqyg$AnwJeW&6{(hP2=M=Sy~0f$CB4-K3XOtfXQqU!o0v_T?R z<_qw*<>Sr0P$J`qj^_=t*X)0+{2P(DDcV zgtIco9JO((onk;%-XToj7tekN<@M5 zpJkbEANbmDmo~y4noAkY!_pZHKXqkM-!Ay&7UIc~xjOX7J8W-NY zQrxdi=KGbuN!#HsZeI(#cmG`!*%4Ovun}u|o*AsxxTgunnMN^i{R2!C3Xy!z<={H| zul?4LDdtFix_WD0OP>%D+%v$SPwqH)ao9i9NvJfN1@%24*A;A(q8|VpDH!SV`e(mM zS^K@@GIzH5BTeFgiyBj%l&Lg*M3t`H4PqioOV%{eMuF72-D*^9gj-88TL~$*64@-< zW=8BC+-`uy_y_!@Bz-QX_ieCZ-Ayv*-2)OOF-@_(*%kOd$La8{L`ndo0!|4|W7UTM zM%5xeZx}u%6sHECK_x0;@F9jnKRI!BZUtIaS{%V;5OjVKv?I_Sfuhn6r8#Zm z2`ImcO&JdA1T=8F`XeXei)n~&3uyVZ1qxkO%Up9<aY@PveFQ7MZC@zVEQQ{scvTzq`lZf;&T<4WoG#GM7J$2)T+!XJ@0dA}nqjX!Lb`+=Yc_9rg!s?bNB9Wep`R>~nVJ~|93Ps!eUZoz_^(K} zTw`}JOAf#d);D_0lKqH5jA8zabE^u87rOZpEgWQMXh^~!b@N-1er^pOpXtLFQMWZJv$4}iw5&BpdfEN8p?mY9>Fu+l>WZbT(4U_lbp%X^Hqzd7 zcs|5AbeoQ(kliYtAa~QP=-J*Gd>yYB3RmQpD}vCCmaBRn(O3#HES9v?Qc%d=o&jft zt0scFNMKW^{BOzdYUvW$Y`3)98ra2JS#7n&fvOEH9W!%@h)}zZ{V_h0uV7KvoO}-# zerEBq;-fcY%y!^NaJ5=3=O!besMtt}!^0qmsDcn1lZ=+|?&^m|Wldc1;$Z}TenK}w zc|KW{ZJX>ZaY1A`YP8Lc&6#HnTVY4RSOwbcITAtYvk_dp=0*pwcb{NOcNUJzXq%!A z!uc)r4!P-EZ-)RPVy2|Vp|U$4=3_w1?MZ#cXKRxUWcBbh9(oB(ns-VYjU)i2D89UH z(mZ&9C2KKItLt`8j5~Z!_jfH;PBbw+##tXGNpL5zT~SnlNH;wH^d7afo_6|g4!K$L z=PB@Nr8n$qJ57b0Z)2JuBt8()xtVYGxo0=Xf03lTQ>Nv=FTqNAz(4GeEqLcpO2_Zb zD!0ASfwa}GN9asZB>q+ej^EG~a))Fu_2W>lNJ!(vHf;?@TNCjlHE;Odo9XDV2S1sM z!`>1O36<(`Rt~%iPG4e~!8uNMXx_x?LWvC>J>}Klmc+FEo3(vi zb!lzY;k8r5BH!xa(pz8XTbs`Bj(W36mZTPg7JGR((Hx|)L|Ux9U4IQ1rTfPj^h>Q7 z$DE9GQvc<}*U;!1AtMmBZ;BRyWzL@Wl&lgjbVo;{) z`}Q69C-A7rVWok+>kwTL1(Ik@jG>1trGO-0db-115P%j&O-)VD{q7>$1#rT_pu6)xwHm@F_=Q?a1akCbJM{~w$aW(1I zg}@2>hoea+8@dNEVuq?025aj&wK|`6@{~L49&6CGcb@JuToaA-L1b@}A1!f*qEGLC z#tAL~Vj)4YFJqY}s4&B0F|bF_P9AN56~0HJtb4`m*T<`f1HgP=tEoWq?T4ZO7I4S-BjhLglPa#L4I<(<8y40)2^Hb5=SioeOp!`DzcqwaREZ` zUL-ZyB9W6(0X^4e>vyw*CS2Nqn?HmrUmKk~l_IB#n|J>dn(y@(iKL|~un&q4voq`K z6N1M9-E0_D{ZU(Em8=3$+rix;DC0R1g&m@T1EOac4*z0S$Njl3E>${`zeaa_wnU;kUev=&JFH zS=oFTYz*Nh2vIp$N9{zMZ;$lu3Qn44NKV~?o;V&m&4b@Dx5{2w?}sohD_{B+u~ovl zEWHe;0cdX0+?q4&x0kZI0XdT1T0w`=y)GipvKESvzxwfc!uMtuP5nYIYe~Z9baYgo z=lV+4vn(hP7kykE=w{%nsqhjg1xl)>=IrANoxYTV5bwmHgiz?;5(Mqw9KtUjL$nF(&qWqh2&Gz|8du%dK1${vVn7IqJjt0Z$lD7E3|rWxmBvEEUb!yG|rB` zW?{Nv_FTMv+KN|6roX#~$^3^@mofKtT#$z^D=!6T(oZ&=rBBcZDcfHAZKl=H2R&$y z08oE0l%BAAC+&NeonVg5Pqn$IIrw*~XA~(+QvkA*iub8O8owd#YT@0F+2l7Fb%FD@ zD=Sd@OW5~E;Rt1s7M{1FBBW%nXTIp}n-6X522%mPj|;hDkfnC6+BPd6pJp()PWH0- zIRCiA_2h{{)-NB*jLc5_F;-vln@0X`o)8AvywB@m^>x-nFjxVNqjho9{o5Gr%44CV z*WUSLBAlbeZc07(QjuiRX~5&0(S4u|F0^x z>Z2a+`1rdVYLJzV`IoC^CZRm|ag#4Js7^+_%*wjyIMUeE6u)Pa%dl+w1+?Ye%Ohvo zW;T}^Fn}0vWupeM{U;!m&?@GuH2KA%DIj!aPAS%!C9O+K>B~_yA-|)pnv3q2t$aqp zXpW(p$r>h2-E7%Y+80FGmJc5&4ho;656`eiN? zGYX(X6(6Kr_^<5jQ2?!yqZRXFg0Ts*@VkGK*P zKc$gdZ9!YH!H$WuHkgRFctrxEi@T3XhGUV^_?10?r0&h(Bc(dF_y^g~xp6i)-L-rm?O))>B<(9NF+;l|faRY*0ch zUZ1^S4cm5pjaPl*Py3y_hyH^V245(tJRXbfeq1V!G|G`K`tK?hPo}T_tJckyWo4{L z${`}F>kySJ$<<)9HTof30BH3cUe*2!wGT#aJXCQxkvF@JXyygktTb`p1-*tHR315N z#(?+5U0ndufxrWN*PQ2j?^bKzdg*BPP5Bi40be%A25?-Qc;dE9lKnv+r6ly-pAB?&i%CdQ($ZQ)9OfNCSQ(1~fkQ8p-p?3%Xvt_bKU0PnYfwyB{OAmmGoI zZ_A!wP4f00T^!c+ zh6;j$_xNO2OX14!DoI!^sIh7^1TjV1joDFsU(@PMjQW&ilxCD3)&`9>z>{H^NY2 zZ1|z?-<~JdnmVtAup`_`+P6B|z8iW&EW@IriD30r$|usC{x3h{9R&I zL)UB)gX<$Y{^I#KKGBME&3v`%IfjSV~+H^Qmu4e_q0ziQ(dvhV$L`%z0eoA z9je&Xgm+l*jbxRQ7F8~;p^F1g-9zi-0xq0T@uS%A>W>V>7N0H^=J~pXbkoFZurbXq z%hK}GnfoQ#>hK8%pHY0U_HYDZ|IN=ITlO+`NmFueSdXz0YmaPbc@bP6b{dBWl`NpN zmEXxj*u3aUV*xKMZD5b$xY^7)ye$Awt8!{{A%=@_+`N$_qsX zo^0@^L6$matx=Tu3!9L=0!My!^bIe4$}%-M!3i!iz$;%44vX#v_W~Y{Akh-h;Vxo> zub;D1D=KNS<#x7W6G-!d4iQhkG3;fY9jg`MZC$UrJq@zS)K^TK{6iMPf)DOrmL5hg zJRT1dxc2VD0~h~S$4CA-_%0nQq_Gx^$xJGW{hKhW_ItSg1xDtBVX2nzYrh|FAHSP= zbI2gKm-U6=Rw3KF9(a`qX3w6NSN%`$5XRfy4NV!+pwn)7Kq9`Tt$y`sY4K+g&gZ(u zixeLOD@PKbpR(?-{)m71_5m*q4^jxH4^$u~hH+e+2G`L%8F_2p}vu$kV`j- zkLZ%bO6~!=QC|9NZ%^q2B(9+nQDAUIUz^u2vbjNlT-pRZDi&G+z3#rkX=qdI?7qFR zjv$4g=SGShkkDW)!?61L&eFF1Vk4+-5LkO9FGc+VllB=ex;jS#W>D6TXD>lG&tPc0 zfHv8Wmc!J&m#~MP?@8t4L1!(dZnlM^U$ok4j++|iB`IwL-pq?uytpV%Id5`M#4U0s zU0rdtOrobr>cg;P{a`>P4f}u~V#*?q?MU%ASF)%EVtiP;inna{d@lPd28@#05P z2*nT5RZK;NgI55DHItL)Hut4`VaQ0vdj&OS=CTT~7w!Qol4qgW@OV?LyaE7j@adzIvRpkr&pl`(s%osVUo>bXj4$Vy~T1PJ8X3hP`?DV zb-e3P>D}o%o8ZU6KgQ`xxyuuEvi`>(YEi}p^P9ia1>z5b&hLhI@0jIM_a0SzdENRU z?{|kZY$OA*9QV4#wy4B5+8P>WgeM;mn^VNV_Tz};@7bF&jKgb^an`LqQOScgj?80( zs@AJ597Cup)fh|iP;O;^9*ny8-%3Y8?Ww8nM%m=vkL44RxLG^sb6XJ;Pg^SRxWs88 z?}CF}Lz-|@F`Zj-bmXIZ>HE03Pa@y8ET`R00SZP5Dm=nHTRA?7qW|g&B*ZX`)IMph zPHQxVJq6B48kuGcIfl(glplNl6s}g-h!tbMW-BJYp)#%CDqErG*q8IYye0Bo{XP_*vOrk=nsvLd;U=*3l@CST$8VwAW(`W zLQ3a>D?e|g2KCa{SF+d5H4mWjf}nJfOx1*(eWESzv=iw?T*y;Ihow4)le*zHnN@nlfm@SK7YF!M}$s);m$Bz&{ixKMu3W+`dHlU4QB6aVvPu{@4|u zr&4tRaEKlcLi8vwg$hCE-$;fC?Hxb+q62McguI3)Lo&eYT0mkCvr z*I<33`fN6CnwLR#Mgdo1rNin7Dw@2uQk^?YX4q}@l<`4%)7)qGvAH><-a$+Z>TiD3 z>->b$Prb`k9aeWdoU3p&UF728@(~inOncn~g93a-YW< zQZacp&RX)m99`1$b{%8^vJO{EgvTh^IN7m@?C(^jq2BAvLoOG4%N9c3-tg1$(!XsP zRDuh+E;~%*>25ft*25u91iH$0a6OEaL%N)GBH**?Wto6`GmL*%BWELijL)v=q%Z1` z4`>!Yvv*Xc+a{IA04dosGb(7q1*S>1fRMiH$ypB^^9 zYm^tU&p6YY>2-SeHq+f3ip<;el}p0+qB^wuh&M5W2$(831vW1`7VEu|kY3-P?(OaD zgc(poH^dXiWa?2^Nd;5+Tr!;jMr9nBqp6_9QD@O-wMC!>0wsI^vyl&_f*Q78x_0$H z^Od;@+HI4OEjXeqP%al(1~tC)0c0H;!<7mCiniDqeVGx$R4w;`@ORW4f~m7j)vUCa zqBdp(>sL3{7M^2Q-V#?&bnk|`iLWeITIc5AGTZ9!iU!PkFK_&@;14g&b`&}4bT*$q zM3KqJSX=#$Zlr9-Y`>wQ5=UbhT~6nE&)l3mccWjD_{xdl#$Etm@1gcR%>&&uvy(d`!gvN!cYk z4HK-C%Gy}I={hZY0pzQQ0hb`(NY ztfqY1qXek>S_o%KUqA4aFvi9Cpv5Ka7uw@AHY*|t_FV)Cp96qX z=yVP>_XV%(&-~?^ZpA4I7dfM6~%R;%77Tn%?YDdv!Yd$DA1D9l0~$!PY~Oy zeU>M(G0j2#{n7?T%O9A8bf~|O(_fuK8?E9{+R1JVqfpui+A|qkOsuNlOi0~9XC9jn zQ2HSf&kYh>l-@EV4mNSd zqiXvkkG`oX@9$gLtH1}D#;(XUn9N;sbWi33xERc=v?eeaTp14x za}9krcrq9Qr$?+6R7Sfo?I3XY>4+y9f|oy-<6GF-!BEbb-F=&x?mOOZlfgu1)&9>L z(YY#VWD) z!xbOr9SgZ1>kMG^I5CCR%~f5PdDi4rYxN$rus{iJ!Lq*Xu3W0z&xW(Z!-;+zX5NWn z@MpU?7v?Ag6o3|E%P8r&>JD(28T^rBm7`G}zL#tT2HVAz)h;d?#BZTrB~_VC1@T$E ze3=VQojgv}sW$FYU{4ok)o$J`wPeR9t7J>8_@(U*0Ss7f3XM=I52nPADV4ge8YlHQ z{QnicYX;7bs_@{4*f1X>WZlzpknH2>K2E{0wUK?+frHLh7|*PfZ`yt5(+yz#Nnuko z1cz2M?11ryX_O%P(WaB(Q8SxSKC+qw{ZA!j2+)*sV6T+^SqE^sC_we{17jOJOZLnX z4ZDPp$&Qy-5Ji^dVA7N-!OQ_ULKWJQ;SLxopL9gFsa(2>y)L%ti>L$e`)rQI3Vf zp}Ji4C1bFA2vDukwz#4C`eb?YRR6H*PMWI!s{G2{$q9a#{LoC$)M1C**^kaGW3u{c zd{FaTS={R+@7vW~#wR_8Tn8zyK$J{~G$TD>YcvgBdG?PagrHhtu0|@s zt2kwS+~2|+!<51HxjT7PY8o{yy6B`}PeIo-duL0O=s4VwmrN-xR*v7UY$JLCafIwS z4chkM>q&|w*-Tufdgw-PjWC0wdB2+_dem{&TB5*ygfI&MDzKMZ52p`n;$ISaWDmghHPaQ!-r zH>BVO!&Z?r3C~$kB7;EXWaUHOYTN$qQ0=dtk}gWqb2EHF8xm1JXMro%zh3#*@sd?9 zl0ZvhJ-nKZO+T7$7=D%4CuRt`)LU(V6)e#n1M5Tqd-^%u@* z5&&_K5spc~@?SS-rMm!J;s$rJaXu*P>ldsq?0ro8!Qy__j{{S!sd@R?-1vY5ryIUOsTiq88(Qj$U(D#3|h<_y|`{q6Jnb|7ax%TxUQFF z{rI7jB+oA*z>IydPcC5XYuIzti5g*Z*tcS+qoKevcUIK)MX=a{sYkr6_FUsZcG9Ik zB?^uY0BCoJl{A60(2{~OORwpo_Lod`x@rF+N!%~3Xy4g9>`<54#o*;A?f5P6gU#^Ho) zq4qQt0tu*N_HvhiYpqDVP9`u=2Mu)~7jhH(WWJz$!=2_xuwm#qfq56AM{`$%MR12} zR-zmX9*6D{80&Z5E-w2@kaZxLAc1xf6o{4JYuJ*DQ0;i|th!kD&YQ)8;QJla_+_;$ zgLjAc7lc@PyS&lQF_am}^UosN$Mtsk?gQ!(phDc28BdAxwjFHZA9?rG+ zuq*tdu2-K`EdfH)T806U^2wmXPX`_75Nbl;X*c5JVq(GUrkE=d)(F!)K1vW19dRky z=xp$0`sM}L(FNERn$;Z<5kv~t3kaPq^((M%sZk`laHYmnfWZxCKhjeJc(`g~mWug1 ze^K$zusGv?EQXRDEz<&0e@9LEm>`TWE)p`!exSA2+7Ddd=)ZFW16yDRivR1z<0JNp z-+2|mG74a*BV1M*c5Ch@bF*hF(Q%t+H)qTEiG z-%^Kfop5nA*9(w|x0yt_SyG-F@uSGu#k;UwsQGQiTL%r!$?C%u%!>|uLB;xIM8vY3 zSL>evy136VXymb+$gtYpKg^wHY$7jtW7*wOA-!P&&+_5wjqSGS%SfpH67r5FX>zU} zlaR8?(zBbDvf}Xe2$UG=wngJo#d&}-(VJ=109vfo7Mg0{NmBKOB3^^G`j=oifUUN( za}s3*C&@cC4*r1C+o5luoTV?MEXzo^@vDoCH`6VyAPmAHg|LqRl}T@A9|{~UO9ydx z4L$4G3Kl0P5nCE1ih6`Iwwl%0AnZ#^gY|0#$COVx6uhR6g9*YC*|bB;Rg%VEco!Rg`!fQ{0;zvm|eR%&*g!SoTJ>@QnjDhO;_{SM^ zgg~~(Z^~C-0Rci(+5#dJiB(*C@UXoCz)b+C28)Ilj zB}CD>AH$cgP224PZ0*Z@Oey}mLr~;)BW!BU$9U1f*2Q+SM|z-Cp_o!x zK8e0jjT>K#hOn4bNHw*vk`o_;wi&w#)v$4h@l?F_#J)I+eUAR-1k4R4c z??hP}(P&vAhr)LbAnDWP5W?5KNillrx|I6-Wbf0mK`-cLZ5L4q5#4DFd)}tsC%>6} z9{v7ZY`Y;ha_idTpXQzq$P-MWXu$)e^N%6E|1xe91l7@G;c4e5ck8J4Zj%`?$qSUG zD+Q&(yje{UA)(hp)1(-XrU<-nKO0SXt&&8CM1Frl+TDJ8bT$3Ney@i*#-g5&zlPX< zznQ)}z4`s$PZ(S|QjyqOhz#Y?Hr`_zkK|mRY=V2mzIUC1Ja~vQN=z-4bp~X)>o?O@ zvyi1g<#3pNp}PQl zrQXJuLj;@fc3}Eiypp%hKzYnUc($c7YI$xjNb`s_ZK3`{z3tBks}j_5Q(Un-w)F^y za;#064NGDSd;L@aWQj9|Cj~4qawI{`hhdsul&zKI6KQCOsOGK{_34zRwS!x@GsTjU zc75R3T{O{=F;b;Mjd*d_e*tC zo={qd5X`GaD^hhPDRG*cfJ9v7yHseuqA*q@SR@wwg}y%<)wJ!n-Z8w!6XdsxF6l02R(e>u-GMWo5DW z$NI{3n^kNcP3!i8JK53$IFuXlg|)_~+E;Ou%`T~40OH6$sRX>G@08+x8Fv3{X}SI7 zRJ*pcCf*tV6hDe^_uXD|=Wla-nvdMj*`4U9&04^zbj?-mPJ_n2$yh)e32km|HLQ+V z5l%Fwk5^BpEJI5Zq#ezB{nbcGPyh!eI4ovmNdbJVgY(BVTD|`aKE@`9rZKN)timrx znAPo$y86cX3j8+tZyMb-gF3*71LdbwlC^WUr=8Bw>%Gn3)%BC@sp~)7mq&*ZW5Oie zI_OeoAiL*y^d0gDb6~F@qPB6G=hFLfk}e=w>H+R!E*|oL9A^wIiB@o&6wdPu>k0 z<7bju&US{@G!G?w`~x>nU6_D3_x6F1qJ#`ZLn>D-?BO0 z)^P%4-gvzF09FHI^##P$Ck-xH%y0ZnnaEnm6ANtF? z?oc;tYir>byA;nFHUAG!Zyne419gv60wN$O-AGA|9w8_pDIKG8;7I8X>2BO;X+}wR z36dKj4N}rAE&bc)dA`r@kNv;B-n;L6?>Xn56Vz6r&VxcEpGril$mNGOY0vMi8&T5j z)*(JVs8{I%Z}yj1_5iSAGHvP>klj*OjSEd@#>W|c-q1o7bw1XDF6N7sC;6xzLbrC@ z*PM&#YR{Ivqxzn%)-8?O%Z53Ne?dYwp7T_m_}?+8!0p4I0w5{|Dcfxdm95MmiTL8`gA2PY`W<kSC=OoQj>W>r< zm1*|8O7h3;Pd~^5N7YPDN?}I}?Or}UH;pv`M+^0~-Dl}FlDE5sH(&I1!FAc5dFf%` zp{&SdT{#_}tHT9g@Wkf#(#>UPO#s0GyfqLvMj+RlGpqHF7UN%|zZ zy-rMfs@ouWd?xQ{`=ay72o(U9^>6{Ao(WQR^QZUXp64|&Pb#^6b!xDW~!{J7T?*|;Y%M4i9PZi6ynlaR;9gZ zTwe*SEnou(7lI3ulR+tIs^%kDo`yC!TcX&VQtA_{&x<*P4Xw^U2EQ5>&9TB z^ntW`?(wf5i-L9X z6*d)+7CS12S?$=h9Ky^8%GK0T2dwtedwoOzC-Z(~P`QSJ=Zg)KX}V#wnBtUaZ^cwF z@+;xPc0W{meTZQLide3^BFm5buuET?nKugniLXU~SSB%*rba5^5Za+{93AM6snZCF zRS_Qv)9AP;+4WRhIr;Tyx>i=^Vbyr4Qfqt?fbM6L37S?qG{#WiRWOVzgty&c_3Uh9 zb~XbKALXtgRdvv&SAQ@5w2)_0qPh@%y}aru&v6cHf)Pyl<-NG0b>oOx3#gepxW3~b zEm|VB{gSbeU0&(Ec>`ho#P0MpRp*ws~;MT=qZsBu6|VyKlbbJuG;b zaDG)$ctRbbTe|ca<%LdZ`9&G`qq|$~8r|9{9WSEgEX4u$Qu@#`*4|{dV46w&uNzbY_G0epdcN8$Gm-@*ULg{);-9k&uws zIQ_>beGUTwI3{T!<1$TNA9YWFpFeXigLU(;*5(}@z=zo$j;%M2htoPKLTUu_?uHeg zOw_ew#@s&Y_)+Kxm*C{Py7U`8*?AqwnC5gSiBAEA7_;Y+iPTev+b3glH}X zExhRddsFjqu<^OycxRvsuj*ix+wLV-c&z4l&dLx$F(fm()$OK8QPY=5)WbeTqb04N z_x(E?&?ZBW?rKdX{>!d=@uc_>RB`eiKul>iOgNi8c=WjE>%rhZN=GiC-5tNS0_7p0x${|G!)PyBZz(79DJ)wNE8 z?)M5`KKxlcmA+q|%*sQ7%)1NI?W+&R|5KC+aFvSxWt5$#N=A;PQ;z@bRxde&cJ~fY z%t7nze#J`^Qg}+icjGeAzLL_Ua6y|7Yu}tow#@{OUB*WsftOuH$>)W0_eL`Qm(GD^}3d_is=n?N=?`Zp((L*iJKub-jpOqU2 z2BPeIfczYo)65Tq?ko+&#!28h8*PVMUI>+74E27!w!3$81=>4LH(4IWyk zW6EzFa9ZIKA}%(kML@m=%%Pmhf6qU^%}HATkS4D&l{Otm$*L4JuZWCWBT#^-R>qLM zzB9IMn$4b?J5~h+5(q}0$tiOB?Buw8H4F67y+oy=p>F(~*}zvjLAlWxqgf&~K58pU zIK4>q-TN?)&*n+jD>jkkAdqg~`hlQ~f@3n$ra8Uyq}PmBMgy-OkC5y2-Cqsc{PaB>8}b4lrmv1fAG6G8aS|{Y zI>8mba27P%7JO$j3-%2_EF)AgSsAThKSrNiTNBK@O(Za#Hv1`4x(@92Ey440nMT8^ zzui;ZoM5S17|dKku#?^SAiU(Y(s{66Bl$=8jSnJX9X)r3=kE4n(*(LV(ObIuttP8AXx#9S@};AWi{dO12LpA4 z-}P|->LdY~&&=CIw}NtZU8BHbE-<+!R1eBq4~TL((wqNvBH29^`hr&DAfL8KE5(jW zg^$~nuDKM?8|@8a!7qmflqI>(PM!o{ML;p-JrA9@r^{1sC`9gg2(AMY_Maqv#$VwZ zHkw6sj2M7qTTCJ!fns#(^Le}echa@;M7N!R4x5M+;rpWeD}xogfnzy)OIO#+>FN7> z<4N_{PWswQ>=(F-M03VQS}N2dk}ikt5-&P`rs-fS_ah})3|;{fC(#&%sC~Tr5g0rf zZVzYPg|Hgw^B)TJz#xB3wXCX$avs8jF(jR`A+rXepxidw@Kx&)h+MXC_Zp9<*Jd_K zm6O~?IW(*nw4Rq3y!{+8f}L4NiJa^x18<5y5wmpzuTFgA5A^wh9-Jrg2EFq3kyJ=d zD8s<(Hmj^`Q}O;rdxvG%RYy7n(zsHP;sDpai*d&fPefhs^Tf-O?ZC&Ku*_L~Tx5Uw zL|b69`T2jhN5j6SL0)@J=i;OmSVDPszdi48Rvrc!dg@4WmFF8(1NNjnh`=5)+X5eT zk!M|uL8d(66%9{3Dw-RjNlhi7ynT2Zg)hP(Kaw^gLnfP_q*Rz3J(-`U zQ?+2{vi9>4BOibjEQg<;hNTeFGx`3alLVQs7=kXm*KV%%E|ZM$BRpMFv%@QEq=1zO zim#xIR?ZbVov(y02BM~qfjn82f#XYDHl#__sxrAo>*fw%AZ3jCT&cdkU4@{odsn>P zQAZ83pBlQK!1Va#C65X5-0TH<6*G{=Gs)`$w-Y^2iW`?c+SKSzYvy1kY;yED62%}Q z99@t6atQC)9pa;y=zV!s(AnJMGF1<;`Oa*`OP%5!-5=n;bbo?6igdV`B8Z?sRAjYM zZUF{ku{A_aLzoZ{fmVRm34AA7fqx=bvcGi9`brLfCD?9X+MRA1M3=>cHF9>J(cC4k z`(MD(2l_{N%xwx=L{Sk~)m$Tvn4kFN6qXEUIv8)e#rB$hvRuRh(*bw6&BsuRYb|L!*H?C6aX zYbjh6HQ$jMZ|MVc`2O|K&mtf=L%{bZ^9wLAWVi~-jSnd-cdvIk6>@j4_YHLoy)w6*SosSMgxJsaabJLOwbqhs znO+0pQQ3aah$DlOXo!Vr7A|0dL~QsQ5jk$#mskCC&e;KDWhHlYyAj?@0M>v zEY~!OtV_0J{z^o88(zC)O4Egt%L+bnAV z)=iKSD#fhy_{G3g#liOpNRC&=;}Z#cA5}sbMVBb&v=L7w+71|J7F7laZ-8@)1(0;~ zScFx2SX43(rquWy91Hzn&^A&4w%*nPOQ#O5HZBuC3z%E!)!l1SVQPY;mX27M?Do&u z;M&YDVMGm#obd#3wEA)?DjV|%HnPxu1eP9Egk%BaD>{ZERz?P-vbWKdr1Cr7Ew#CW zOdNj2&#WXIdTZ@MYE{8O{qDs?wzCf6_q*4AHZTPL;p<2Mz-O1q?ODq?rB#LvDC4KU zzvYjuz{cs*y$>JKqR3vo$7L!i5YkTgrgh@lX&jaBk`Zvt`=sOFC-VFLHf!}XfpcxQ z$^MBZt+H-rxvr*e0UG0s@Kzvyq`kQ}``U31hK}e&2Vzj#vvA?iU3|{e4>^4?-Q0DFR1Y|t zDxqxZ^!r{_IzgS`zlS!Bl~DDr>tz5RUl8JW9MZWK!3mr1XoZNtUvVJh1_lOE_lIpB z_7w}hf1=sD9{z2hylIPIx(8t(wV8&l@^>qHn>ZVS5|Pg0WRZH#UPpRR7zFNAhXvM2 zT7Ho~U8I^4QVll1v3(HR~HDw;>sNj7Eig#3%gne~6%El5k!diSbcM()LfsqzSu zY9+*Dv8sb0fjK1(11Hy5ILB5kEjuRVoi=GI2p7p_>q8S)4V>hJmPPW?^%6m5N z?WmQfF<;)li@l;L|3?^`0^Kg(#Z4fRUyQhSJ4Ow00sK~XnJz1MDtU{{vuSczI7?3S z-?Z*rtTFRl_E{d*jM!F!dOe)dojh(_3nrHy5zHj%*dKRbTLY(Q3x;j1WE-BF&-)XY zM!bKgYixlOjUH0X{tR5TVABtV$0)*|gKfZH#ZM{lo(&~K+ zpWH-`c9aL#`@+de+O2d9AruAhdt7ZZrpX+>LdG&S0smUP=0y_CgmUzYkLEnf@xmyB zKmu=8ANy5!+jc3Q9AEtF_n14<5AoYrwll6mi-0}bpe&R~FhSUtC@Zh{V3dIvUHjSr zKI(*U1I)GqBak z%AoY+u)6FtS`CvW7)-(ug^^5!o0JA!kR_2Tg5YUABN9_Qqo!q10O{b2Mi&*}H9YG< zNSu6LDMf2CrNaaeD{;whR$d-7tzKk0HQ(Kg2b`{>M2qvaK(>!5V*HXnrx1viuD)Qy zU&f;%gqyk%sg1*{-vgg~1m3#l*;lKsRh_gT%Yz0N- zW*JH&f!%z}@{?w{1>f(_p7r3Su*TNTKyp71zjQ@yxMa_MQJ z1>fS5Gm+S9O@+LzGNANuMjGzO4UU-=GTbfO)kM0QO1)E0%{X z9c&!=`zYl?e?Eq=zf_4|LbnrWwn+2Dg^eWeX8n7|6WQjo zeagoiel1Bixy}tdPp?X}+rG|DHNtZ@wY5z9=0mc*9CZJ<io)hsWXV$3Fpt;q0w`OQ5l14EA z6)RyzmMaz}yP5O6-cDwTDd1266cQ!bFpY-7uXa?l*|cQwKqVw20svB|PHYENy<~lu zD`Tj<1tHv04m*h&plcD#Ye|}BgF$44PmCR&9MZr~%3P)O1O=_n<6@UlDn|0pd3lF_ zs=RH`?N*y14?R7Nu01wrpE~BbAY^!}l_AeF+@FgBZ_o~!t>8O%$_u8}Ch6UZmmvs^ zMj-5eTOl%$5fuQdIQ|z1L@%(!jbjpz?$&aR2vGr!D3J5sWnWX4VH_v}Gyn0{(S>2k zcm)m=((E1_#bPSUAza+vRg_a8{0D6vYM?GEfOC?2y>&b+2!S2vzi$4bKF+f63oIv;iSi*ao;f0 zZ#=0)6rHw7E=$jE$gu3^$*1oNSFsm0`&6Rd-rW}ZTJG|{>T<%HSstA#zHW~nSd6o_8k`u=GU%fD#G6qq zozc3BrROR&x(pN_+Q1n*K5^MQ@u#P?&<~**zXcQG0NhFaKkrF34 z6B?NnOT!|P$S2T=>5G^KNi-lYH&-bwtziL0@ty8-=+Ke@rlYmrk_}Nz(M_IF5`W}HnUpkiPQsL4p7zRXKLj@cV zO7eWD?I@uvgR{5}ODv3%d72eF2Be3Nr+btje5SyS?RsISE>HYE?%P7G;GAmKpYqNR zv8KdgZ$>OR95-d?+m%$!E!ngbF*;bX5ILjF+k1iZHg;eK2f2RMPX>L=jPzX8k^2UM zEW$2PWYqE7RJN6-&Bv9L8;=in*GEg;-@oT;2rjt=ZQZjM^nl_{Q&du7f+vP(;uTm1 zxCJ69E&f)!6hP*L&mv&atWV6NZWW0&@PQ#Y2S}idEUxU@GqjR^+VUT<7=kltDP>@Q zp(BH-_!lO8PNvAedlIR9O{@3FH$f-YBIsE7O(u61lVnhq4`? z`xto9FY^#8GVftvx6X8e4cwghtVjhdS;`Tu?3*bghFeNX^qUP}j~r*Q$+ceTz>Izf zNB` z;Z!o^f0hu4T=Ws9eoD2=>UPZvioPqy^t&$A*TlkE$XLFvf4}2*JO|tIf_B|j?`K65 zkz?gl4GE?M`0s6|Ua?&LoBftdtFzEx|KW-M*_Ws&9g^U?<5HWKHTWC)X5{h}FMcHP z;cQEe*K;p*__$@*OifL_l)nG_&F9Rt*&zJf3XE76v#WEDQ;@D_-AX*t4 zLjEjxVWIG$_X}j-eTm7Sz;q?fey(bdZ{%>YmB@PrUQSv6bLETS_ZaZnUfGr zfBDp>+*&YPb#G`A$TJy7R|ep45t^EhDkxuY0{i5$BIzZ-Z0Cc1=Yz3zil`C=FFJ^} zFOOa9@0IInXEaQ^U(8oVd$yYhDr=RnGP$hSH5gWf-)zY5N9OYx`EB6Z<@Qv1=L7ej zQ6pm=6_}9>Q=3o!j2POkZbe0!^ZqNqL@!fwRkv;O+YVjKfD?iigSlLbQvKpzc(A;u z__LY0{jqLB2H)$E89~Aw96S*(W1hVE#)7ZC&pB!J$&mfZDYk!DF_Dft9_*AX`8V09 zatv5)U-29KyA;DePeSp%?RnXVa%FmetfpzPuiM{u)ecr(bD2y^Hp~o*6JO(wR!q+t zNH$~a_<25ey(VTO-cKR*UDQUX=5rQz4fPPSpp9T?c^K7G$q8ZE3xQ^| z1XA&_Vr+&s5sf*L&X<0^yTdoG8d-ndVQZlg&1He(v5E1yo*S}~dSVKALk~gd#4=y~ zw-n$IerL4LU@P6e_IE_G#*L5}l!5Kkr)Iy{(9)}urJ%nupbYSK{HEU(BR}wa6u|Ve zyvrTG{#|Yz_lc(je0C@cO@}p%$TAMVEA0=8(nS>XqG>V}u>QGQ{X_<6|Hm7~2eiqew=lN51a%=lpBV&K-{$nk8ub z+PEQ6*rD&VFo~>Q7rPhM+6&9#qWtduj0(75C26@%mWf74pkEMVq}6esj~8qMadh># z*TgMP=CL(~CFnwb;95&~>Ha%xtI|}9o;db2y{c3DY9i8?uYUg^eYoT$GfMVemGiaQ zjJ;ltG#LhFdd0HiUM?$|@sgto}FW&QSGT>P%GPF4Nw&GfR@s>v(P2u8M&OgW7DOo~{2+fyPui7#FZZA<45 zc;;ZIb@uHZA;ehc$>Y9z_0y+dlSUw+vqu>uU|+LhITwZF{5cyfEh&xdU3+16|EIb8 zvZ}QeXi4btDFsHN=^>!`tUtgCo{rsa+sw1Yuj7*XM&&UBuhb}jreyIgoKL%~f84ac ze*OeGKHmPGnsGZxOW>rW<}EAch%tprxyPUc>fI^@1WxXGo>9t9zXOW7{3~BrkPRMS z8;m0;U!pS-ZoC~@?>isd!493a6Jlp$7sDH(u9~phVpQZbOberwU2*a_SD`;I?h8c+<5Pozpt}gCoVrR zNYlR!{BK*7uD%ITb+eX~UU!^lLsKv~kIY-W?T&rAuV@Vl=tH`m#yxg-2TDPn_R)*)VCf{S9G`ZO2(^F(yH;{r)s4>5VC!;{|3%9F&?xm$FXK#X@A~4eK6nkBnIbYc zLHjvc$A=CP_?&vVh{i7&>!e==qP1vp+yKZ*T)cwn^B3n2I)r9KWRrFSp6svWxn3My zhf(G{hcuNh4`VED^$<#WNTze9H}cM$g7_`Bi6r5gayrj3)UYpo8K&95aKF5R@iJY8 zM&}k%*vKt1Icly7Bmo50f{!vSHE4nU7pH>^W{21CoKN>Xn3ooU{O7v*HmE%?^x&=| zuyn?5JHBIT@85x7eI_u|-F(xZDlh2D}rsXbbq!M-k4Iag5O0A*MBWDW-t5#!9B`8Zy>}F&$5AS!ANH+ZWS-9R%V znBT21xj8duI67LP0wCNOvw+XJkiRfyRc!;X6Uqei{rPiWyD=zlZ4vl6DTWfpyqI$Z zFIVDBE$*G4H^|ruo3|4&I!fq8-6Ze_`2(;^6n%1S0D00YC)c;f*v%jEg(?!9XjIp0{@tZR)Nj)}BfR!>Y}5KWMomIN<{S(B6BDV) zH(_TQCg_?Y{WA4o!#Tii$$mA>%a&5Yv&p(g z;%vyitRiDtsYeV~$vu4@e-1?EfFFnR?uR$}D!*%szljH17EKt#&ObCSKcYT_gN`U4 z7V&h-{jA^b3C$_fKC#(g{2qqP2u8;Z}pouXe))8bIHRHJ@|Nw^!7hA@JWJ?xeVPt zN?7CCJ)@Ec^#A$>j+oum#|Fv zim+T5H<)HNPY?+Fe6?7Q?|m<^3iRFF)xOK+8cmVqpMSWf(I4>VKTp?>;2u4LdJPUN zRyFlP4b-gS9zW8~%a#AA$<`8Jrc*uMd9jV zWx%Mgl*+~9i>;!HKR0tmE3lLi_MbGJ^rqtrG*F;k*=%BBU^be*J;d!IuJ-n z!@?@bxyI^2JN;l*pFUc|f7t*MG-}^Q94$E?x(_6d(ccV+cAd742biYvle+1s!BxEL zGHl-$>zQVuD;(~ekyz{0!#|gGE!Db5qaD|r6QK?Mwm476Vst^XQyiAcV0IS5I3Go^ zCd0$Sp6#7pCmU{qi9uVVX64l?9^1h+!n%Swdu6=C)(LV&9vnZV+8seXM^n{2Mm1Mw zTopqlRQQJQKeiW}wK-Z$g%)Q0IBG=R{e(jN)Ws%Nxzt`Vu z<~T3<-XrJqjJ4h71Ot1au1CT%jJo9)ep|1ffo#!0h^}yiqAGJ{B$^g!=h~NZef65Q zzhBPfVjpmFZ#Q$Ez8hTVRXGV|BGw-LnV9ullXdz#sLN>6*k%vG@!&WBEl`Nh66t9d zH#zSft8~}-{#H|YADNCy`z!x~<{TYD1(nSgr%g4t-gkP4c>y5B<&TJ2An6ujfeO=9 zl@IIgn7QOKbdK|AL-p4BKp;_a z4sl`hkA=dQosvZ?!RWgp?^$QIx*Zo((0qASu zY4SIXE{(Ud)4%yYsxouRiLhw>4yZw+l4)M?eI(a6e!OaK4sJDCaUJi)#6hP?lUKIc zL}MJ7XTVpDm&Ix@l!WUXX^;>LKa1l;)0i3hrgIujVdWlG4pAU)cEu5wk}8`FxcKOi zGw6e!oC%Edct6f~-5S{gZn398TWBkO?*Mug{a5<&_joiM7PyAVAfz2N7gce<3oC?$ z6OGiV>lP;K7kqI2qQarQN4rp*BCkv3yuB%ZdaN4kT7M%Hj3RSNbhr=h;awUp zsq)3CW+ZjyED=4^4EU1PGV+#j>8 z=52RBT5OE(0Qfl^ADG=OqO3R#KlN6q5JV}eL9#mB_Vy$2TH3DP%b^HXQ(L%9ti{F7 zERXIPCqRGk6SJUhxBk1sQNMq;fzjHHsGc`rq{unr%qzFzP-0x6AthH(S510@U1KQR z2u4!nIN3s6e<}8CKyz=8df0u$ejNi{8@bkC%?rSJ{e?HNnt@BOZ2UK(2c1QbP zy}&$5FA(%-3)wk%TpL-v`?^p@^6*SpI_Xocf;f^+bcp@&4sUUqZpnJ;neR^L`nQ@& zF)QwI^R$s~dHZqoin$+3fE%t5md3U0W0+=nP#)3oU=c4#i%5jF;V-&6+x5 zFk5UodF61t+3^hzx*q8a+e>f zOsolwfk(lVX1;wPDo7CkWH8meuK1_H0>sK}{PzpDNVr9)N~QUY@_UGEcTFJ`+)pRU z+(Rb!1$A_EKEBqBQ?uXfVk4@gOq-WsnYnQQYXH5ttKI4&yVvof(3edf{=#mtU!;b)6vfWzoCKR(&hvYGSmu z_LRqn8kDi+LmyS>Hz2E+0rghoS%@zBfp59(9svU;Da%hxlVLE+nk)TaBCIesRxy~O z6%@oCuF>7-1x1P!Dmh>x52liQ_4J}wDX!} zZn9?cV}HR%y<7E13j~aX=BlEPz$I>~vjuX`Ag^HH${MS0;Wzw5S+c$DR~V{DXObmm5- zZS_C|yR`KOGr^f!XM#V14pNMnAzqnCXbq^nWZBVkaH*dJ<0p1{`F#8Ja9#(pHRU+<)XqXE~wSCcs#+;)sU4d0lJ;&=kx%(nBQ>U z33%hw_i+Z*p?Ti^J2|)Y>A9t%GqbmK`h}VJ7ep-jkaj<178!JV0KpmS&@#IvacurO zLGe!|Pr9NgfG!8*O)sB0u4VK1Kq7LDDqgRXl^xsjjPd8N#t%ZM%{SE^xH=ER?MLBE z#ydI9%co=4ztMXF@*n#ay~fJ8XZYc9wdpSdD0@C!#8DJw(uwU^P7lL$vx{nVX~|p? z-P7km&nUFiWGxt3-j~iSez$n|*WcetGpnv%HF6d)TA@Q40w)l7>%aN;F;v}uJ6E0a zjpB#^5;OFQ>a?W{%|oeS zHgD$giw={%pcV!T%y1^x(OMO&kfFB~r2?+% zFJuO|y`96VMI|919omh5$LdO`uEG^RR6fhkOlp83)b(EOU`Pj=+1kLR^=d}H--7L`-m`h7kWMB;JR97P0*o0M=H zsoU%^{p|FY=ajyPs6I+rwDee_x;^AO_{{ z@2pE~KyX9+uH`|Oa%%}i)@J6pbIU1(1~WLsXZ&#?4-Y^lZbXi?aH z7C+_;_0V1hZM{L^^fl^AH8d=iXG!DYE~ydD+v%r$tP>{Jw}b1{VZ2J(HC=d(Su1P7 zG~}$pGFoRITYfA1f6d2@D9J)u%Q>(g`_uZ3CjGUPgMaQ87+gkhBr7j23{l%w0}H1< zc@4JZd^BRc#EFgVytxTqFa_{sac5;N^#RH1YcbXX(8l^L) z^>{GY`X_tXEuOxcA0PlK?I(jb(2nx2X7+{cPOZ4?d$SxwVjJb<^ieA^Vyb8|jb zOHIw@Sd^-q+$7LgTO!`x*OJ>_Kc*XvN_ZtsXQKV}^STOhTY7%~+2fQD=$5+TEhm2p z{68%~BmI-e!^Yi)tXbLBdeNcSNlLegUx`%SY56!2IItV^{0ov4V!|+qAk9q8{iZ~T zj@*$v={QR8>bfQr&ANN4#td$r(8!7Vgw5QXb5^%IvL1`y?GqtMT86(vZZK&`9S$eK z)#Ya}?ij9~WQ_$Jcp6sdt5+E{Z&xNdB#AEX7OrE4r#`rp&a;+AtG zg+>L5PnUDF{t(%Zw!kbo2-uj(Pa6g;T0-WCfYGHgNbnRQrZ*TCTY&4a-i{xNp&C7m zu#74&WH1f0(cLqoYC|_41$&cy!o4T0`4_Fi+gda^gnqyE;mP&tujY5RH*yJ$irTWc zyzdAAdbsoB+{rR4z)+$uR<(vNXt8ol_YFTXTVk}jze;Zt2`8$;_Ix{&BE00mHv|8r ztgm>9@wxz90YriCmvd&T5aGMf-fy8e(hqy;v38nieOCK%9_5V{uMobkumFJC)x^Il zSY%B7;vv0J%SNVKfAy|;Am3Zg=_OhCybfk`6G@Ht6%W0hHzZuV{;}wBVCp(4zwFeU zY;%5o{@?xA@6(MBiL}_Cx8!TEMn%#b3H8f^{x06tU<(#5UrS-y@dgCUY{$f4Cydtk z^({#!q}h}6Q>m&UlC-!`oINFKa_RCA^w@n)`78zy%#r?F8LX_J_aSjWvN|){u5r<} z8nkR@?ZZ-590)KtWYFi5i)FQ;PCE~kpAi@Zj{Y(5<0jA4+JC9ViSn9-O?Z1b^hGr0 zcv@+UnY3ID{HGbBLPt)$YVle%zN_s3SZDxkBc6*3(GIY+nKVTq!*LCbz4zPGy4MK{GW14dyIxegBu3kQP zC;sCREw(zpi1zzvKHBWC;5r7}L8+oGZeHdw^lm3q*sL<$<_i2e$t715JhjBgq>&&k z%s5A_xBpYCI}ft#!ryfulKr}dS;=4N>k+^Ncy72ozJ-c(rFW{4ZaOEFDjb&*hk{=3 zrPM~8ZjRH=j~Beg&7O{>Gb85;`0sS1%}WRkeo`{lkC^VuyfhSN7ZdWcdkSHv_c>H~ zaQB~3mp4nKGvS{iGEiaF%s+HD0t~EJg78zy!tj0G9JpH*5;IMoj2u_=7AmV3q zqFarXKgE2*CRN#?0>lk*Xh1VFGojh@Cw-*Qh(i(6*)u7+ z8E)EDZD4$eB|kax4B>bPdW9qJ+Ev1w?(@6zsCV>BhAU9*P2gq}X|VL?ooa;A->j8} z+d_s1rQnd>tkrvU)I{F3nWAEP8l#T^MZG*OP)SXjLz-Y}vS$|Mm*w1}+@qD?5>T9t zGM7gRi+KbQ3))w8I3!9_zK$sMlgpk>BL=aR3roEek3%h-@&}2H+o*^{t;vd^cI#ra z7U=lV;dT9QUtu3QNr1Y#+RFXyoM3%);6|;p|Gsvf>)*&W`=M1Y4Z>_joCL_eqNIzE zW^zB1Z*m5vgV|o7tP8~PqTKYkC5}h&&asnbO z-^h(u(Ii`( zTJ5?U`XEGe{XS+4*48FumZ1dkg%5SzzL2^ZNV-?x?ZY2DxV`Irt*sQ?)^P z$#~6g!?$OYdA#-;tYbm9?T~ z?H(&W6xofQCM@F=ueK9uf%ij&X6mSO0`z~6mVyB;iO!tOMn~ZKMikhDODl`t-;W!j z%Tr7y<`zbVA({y!jw#wk@`DuQI!#|%A9=oDEcfr#%3x*&Y@06ht1|J2i*evh(}^Wx znwOKX#z4Yf)W&Iw=UKwJnj#0oIKzet49l;kCI3#F^=cNPhx{1x6a3n5(v382wi>K? z+7?Ia2@qYrD1&wG>(;cPid9Zac`Nemg@szCvZhjT)CNzf2@@7!Z+8MfyrF7JF>=vN zhsL}Ft`rtRX&Em09Q>+24ozE)*}E;x8~68v2ZpxtqbH#j45}m4uhD3zJNCKEcQoFy zb8-0rzmdrM0eH~t(Al=^RGfC)b#Oe`byL-2oKZZeoe3**Wkiz)plRmXbalai1TAZ_i=va&ho|pYlYByU+ZLqn2@+a%Tz|TKm^` zs@dUX;I5@e45hgwar>(r?MvaAYsH8Z7t6yHwb9%izR)){GBfvm-woZBJh0eNVX%5N zrkzg9ZEoYsNj3|IwN_?#`}!#Lil~Gici37PasJxri~Xv%hxcvoR~qfU0(;~)`8Ag| zI*(=s2;WRo^=!X!znMwFBu$^ zh{peSq4Ehs=)-@yBjT|I+q{Rxxh~JJGySn4l_uo9Q|ng7ljVc7pO^o2`ARl9pfp*L zR66R@7)lf$d+IOtMi0Ixc<#E~1TxjJK0kW$yQyBiAs${6+_n+)?IpkM*Wdf*ds3A_ zhq*WhI$vuOB8wz1)1B0c!?e~icsIGK8pDdgjYj(ds z`L1TCTgvm0BiNQ`Tw8+Ob~V1Rlr^y=S>n(`~9jrGQtzIhT30M1eQIjN8OcX zyhVi|`=AFz0Q42CRA1dgJm+i2=8sw@+spkKKm_G`nY~E?GTg7KgTy0#YxI zN`6c$x({c2+3=$S1cD)G2=*4nCjMMMx!bTrGrlYa00L10c>lo1q2#{*ywLvq`9hJU zKZNgXo``c70vi})Z(0?jvchNbHnnyiE3hPQHz$4u!v8ku00kw7MX@T;7utUKLL`gT zrq{(%!9VcTLw_Y_wFvKS{r9Ey2 zU(Ps|!d}`#?Kc9gpVEBB*NgmHCLEWGreRQ9ASu{ksfiYzj0uS3HWqN(L(wq;f=0#$ z|Ax%`(_q@Lj%T^iWE!W=Z~R>8-DC*HDw1tridwahMrw@67%@Lhg4DuhNTDu*yMLFv zhT{eCWp%Cvw+t>iKii+7OdVnLhP!$^VHc}&@|Evo*(5O~L@cWHQ0Ml*r3Kp>XOS!% z!b88qTIawU6|;|=(JeI+XlmiR!L*NkooT}_oAtI2l>Z!= z*@8+6(0U?X3$_dz8$KhdsU-B%ZPslzC*Z?j>ff80+R1IVfIxg95M8cO_B{W6)YDz{ z`6E$3xNVM#QHI9!;`VY4DQZO~-CmZpeF3~w+X`OpE-m#$%b%*KjbdEFq3S^L`}5XuiPiH* zudbbkG9Q~V@|4DVEzOW{YB7@9kf=2Gf0f?|1%1_kECbM=-j4(E6?$sbX5C#gPVP%N zL}eLO;A|W6xAq|Vv5|V;+cZx`- zN=tWlr_#-x=YQ{=7rfvF>}O`q{?7Tc$W5jaMVEnTsHS7PtjW5jypfTBt1^$K!Ep z_;1n{T;@_T>DB}DJ{Vu>5-P#EsALetIVhzsi8)oDPlcn=^{Boxv}^m#mLp4K!B^YK zAO&sdpBPa>P(2e$4r%C^!{! z)e6bVJ+Jev*`pdIS5C)6PwXd`{+GPqiV?O5+nSlX+UJj{9Ytw{uANj=mMDrWx)vJf zfbK>o2VjLotXuu(i%w`sLMg6iK=d2s{6{-kDl_5r)QDMlWI}!dR5bM+9n47}y=@te z&{EcU@d`T5qbUX9F8p!uMhI=mhd2cRvLTky|H0rE(e$T}Ojk#X9@Sfwf*FXBRx^hX*$s~v<#OuZe^6EmAJ7gX7l!ij;{KHOei_8~ zqHG|I%%$?Y>aJ`9hxu)KH68Ef=c2*_F3>Wo-qHqYFiJ~Vf;l+OX}#W#fGQJG-v!?yX5{x3fyv@^g~ zEp~TUt1u9Oi>NLmlm*j zQ_5RCS&Tc{)kvM5?|)a;5f|nvMQfDSKyUp`1t`FAAgFP_gGKh zqajlmqo*!!ycIgH4ar}#QkH$(gRNvQ-B6461{e3sKL6|`|La|8{11rNpjH_cpCXGx zpTq)}DkxK8FWju#q|XsgMw&h;(iWCd>BRS@YLvnn8EJ&mBNDFdUcNm{eU$+58u_GZ z#c+d4Ue*VLL*Ub7*8j2+Erl@E{L(fPGq4NUA-kcPi4~!3T!4;_6;h4?J8S>Nx-L7p zdm!vkjA2g$dOBUrcgk{x@nn4wnZy=&Wd;Li-i~a<(pp}w+zfk0b1(BkA3?Z{qLr^e zX*p!qKSOzqK}pfZ9G3rGlt&&vi~gYP>M%lPznQzofbCGO(>FE*Qj-1LZIDdHB?}*( z%EGN=1z})TJVU@LRanSuMNaTFr()Rc(4-Wto`Lvevf#2-vlWdW{D<^1p02L$pxL+8 z$In+U60Yul?_{N?Fk@jueXVygeB7Z>G)ovAAcKNB>>bP)$A=dWm*9r+(<4DYov8zS zPo{V4iAC4n{v>$C?*A}9(G4kY(SUVEE53!mUVGhD5n0^T*`I$xKM|)hkS$Bi61Sfo zNb;;|Jy3^HQB#Y1{ax)(WWo;p6lH18UixXA3_z&7d={%r3Er@&;k~YEH~~vxd?}JB zqQE+_-#DzZ_8WyNTt2(j$nJQ~p1`TZ$H}mT1$GkDs9I?seVArP^Lj*Jag997_rf|GJ2MGoJ{nCI!Rf~Fxu(+G{O znYFC`jD8p+8GKaou4m?t)ET;68lVQu);lg}1l~@#&UiODmD@QvJ%Yj<%^37szL`%S zC2ozMdIO(U4gy>5Fv6TC!Z{}Tl(g;7wubaEC>L@~9a*qC!D4iam3X z_73Hrj(LvDC;musDtTfL_j{~9uXIqepb^xMd4Ou6&F5w@hPxw&83-!lmk2$34wPYNZFBOr7&a8#YVpPfp!&+QGA<>ch+ z!j;!&!x`O&!Zk^#dbt4#%XQQdd}#bnDZjWjl}W3&`B=axoYYcHTU(psD+*jFre!4K z-{5NEa^PA+Jx0~}Z1S#Pz=mfP#O&mK9?t&V=VIUYxG5Zw^3d7YsqwhRq-|-C z!A5Uk#Y_J}6t(Uf`U<6Gw4Dl42olj>nb8A$e0t$a2!(qUvbmOq29#%>YuMuRzh#u# zy7*5Hz_)2K`wTZbQVMeHFsOZ0x5Z%w!)0bEj$Uj5mrZ$DhFgbUWl7qw0E&|`|TGI6c$}U4D4ihs`H8TlgVzjDL}1|U_1!aNt+YbTaJ8 z%67ExE1%V9#<$r|Evc!gIXa$Yy8Zqw3-0OtvkuGEVWs#ESuGkpV^D_hGiG(Og);E@ z{J3aBE|?RH$h5yz?KVn>tB-|vwqc|Cmvi}|ceeTB_k}IMMiqa}^M3+*j4}qFkQ9lx z5c{!)qWSgh?Z+|iRBVRRhzT+sqXa+6l%--@u2}7JSH55DvDXh%DLvwJpV9l({cNR5dEsd{J z@W$E*6_2AuT!##pp!WHoLqw7dWr(t54~6fKK-yNbc=@7-gsI(SM{G}vng4Nbuvyl% z|Cfbh^(j7uTMiR_+TG#;iIn&1+L?^1iMZ#b7cBJY3ju#TT2-h|0?s$;AC)@JEK!EM zos47KI94`W=Dqhs9{+898ufANC^qM}_6?kSsAZGr@W?k??g_kH9Qt>454mWclb&Ij z_1ix?ZVGH(w!z6ZN^3eQKb|9HXGl(~#3s?P=Amt#oYcyh^S{5Y7FBrMuFn|ZY{*#o za@+B^|8&P0c=052T}Dlo{~GTfJ{`QF$F5nU2wH2qme-B_U;OS+hM{vbcgQch4ovi) zvIvHrw}O38GC*w|sd!vQPBt#GHqK)Kh=wa|yk{;XyM-d5%@O$`aSP0fs;d%Vg?_UB z=-UhXGNi}yozUu?q6n*F4-u-Pmwr%s{r6fz(w5v@m0@q-oP$GEHA7^{hv{=7K-4hBzZNs)CAN;+#f(gKWZcUIW?vep>eY?lZacDzf;|{jw zmK9vS|GqTyh2ieTIaf8yp)g>ItGF#(yh014Z;^9X4zAPFPD+^*wyB&Np^LA(+|tJa z&Syzblcu0D|#X>+7N(J zC?X9-QSL#isPkO%ze;!+WiyiY3|O*h_Vx7z6*?u;XnUGiq!fr#1#|8mJLLoha|y_5 zB3{<$XWX;}l)ctxmexp$e3hjr@;Pm5l1k1euZv1MW|+=XDvfzd6|xu*aeO}5vxplHXExd)!b|)kCalR~En0`Ip4}GG{nkWD zLEF!!&ymu$sz5L@bzEV;vY{90k;>AADVeN?24#9qzfc-ouKJHR*Z zvu&`&puJzkIJrA^KcASivx~cI@oHA&pRhCQKl0=O+^O=61>)okeATHxf;!1ppU2YNhEclI>bPSb^05fyMAg_aLlA4T? zz73Yk>knl)5R_kCvj(|%v0K;xmFP(ZZ918VcUgHyU`}-hDKObb2=EWQ8==7+kou*{ zSbK3+%c~hy!EY69WKIAj?;R#9AL>L`^6gDho}3!8egEEYY57fj>EA=qSgPY=BQcTO z|E~p*@cg&ljfPE9VcH<@JxoqLLnz?K*=(T->BcO%Wkua!(8*$x>(<~LZ)M%G=t*1M zv~c#wPD^uhG`+neRWG>a6Rbfe2M4~MFUp0WXfI3LS0I}fB}hkv)G!JGDpD-AD^gz# zy-FQWw(hX(9R`J3y5+|LJzX^~J~2mH50zm^?f99QWpi75d2NEWq&6^vtkMh#K!U|e zV1bCBzMZ{|*clEW1oxx~JQN3JZ$n2$GQm7~mYou&-6O=J5=}<8@B7uD*q#wH6uHBT8bIw7yX88F3z>^+bDJ8_y;{udhaGy` zy6lG1c9e{3GPr&?Ol@gw-^AfF}UQTnf zt?L6jbWr^VrD+uwxsCc$)*GL=6h=G>$Cc%pKgbX%bU2MK8CG}R)i9ZHw56<7eso}9fY4_y_R=z}o%h62^nUoX& zP--+n8OHv%JIE4@J1W3p$xiTH->}@kKJY?-alEge-_d}nUmOcbsaau}IZ+JBs@HpAMEEP_B6F`2HIzXUG$Tp*Vjq zU5X5-d+WB42p-rl&P|S<(pT+hRQ-7CJnrO_UNaXNx!v^n*|TSkXA7=VQ%(D3Urvmm5X(~UlrEW2D62AVxH2qAAiNrM|fsTh|{fT{m z1BQghi@=al+rpJ$GOr_{BBv(*6U*&uzAf^8NLg>0(PS6v(49 z7ce%|*Kc@l`HtuvB(8!RMu%sp5|&|elGy{7`bBh3CnzXbZQM{VqOWGl$k-zyDhd*S zdhw+u4FO9PhPB`4Sgk!D?{AKeop!|HSxB%=i$~av8vDoydp}e)8^P2wL@=|)@SsWS zv!Z5^*vqwbU<=q@|FI{H|7y#XKV)*k?Rc}lD*uFbLq8KFqB>;IL@CLTZ$y!yK|x4y4B3ibIwEr4Zj^|;M)JNPg}`GSHPzm|jUk?kyf~N{Hfxkh zosn$4PW<_k{=_h~)RRL<7TGF~`CsU{4-06^Pwvu6NI-R=lpD;7o8^tS#wYjCE;YrjKk|?hE0LI!L9bM_XE5{1`l{!(ZktO7PJNRDLtM&?!>nlPihunD>StF~K z2UUJx4mPh4;Vn3BLQ*T{NDSKFf7K&OdwYy>Az&xa6r1J!>!O`dY!M_xXOw@^PrMMe!H23{5<~hnBe1?vr9u}hx1Suh= z>H{oD0KUw}*SlM)OP2|#Ry}lbC~sFgCH!3Ci2gQLL|N)bpILgJJal!1SjU<)x|oB< z!{7MdH#HGjRKZ%n779C}(YJw)0w}4ds3<7`gNf%=ztHog6*@RF9;Ou0Fdg!re?~?~ zJq+G@yY0L(Zm%dS6Nx-bB&h{08D`f zqZ;%C(w7=PXfu{c!KeVZiuN;4@Yp3V6N=IjAid(UP z?cvOWwg!Ryy*+TnL1yiecy${M5)p8?Q@^SYt|%g}<842q2Jqmf*@5>d5Wi#W>~wM8 zdTt1i86FGDf{S%rzh1;LZHy6?9xaHpom&|O1K<3*Bdw}BD-18rw)tP+Bhy>d@3SuE zz#No$J#KqEOt2Db)f0f@f>Pm(MKI}PGXtIScTiAJ`{SeJjhP4XM8^XPK)169M*Q<= zT2=b*#)t18*hiEYM1!p9t|&Ez&IS(f;ZO__mcVwW@tHzT^?oh^=EFdcY1qz zv@X*iiY#pin8Ck12~TN~pDgz3h*u2Nh`yN2jF0&msoAJ-O2OS9>Y>?R=J5eILc{oC zB8hN3`1!IKdYa(tiD$N#7Z)Dxiw3fKO#>I?CE(r--x0|tKf?my&j+b;p6xd$?X%ve z9k9&&zp3466T?c{2em_d3n%ME=&2v6cW25jlNQ?(klwbsp!m5R{BHjk)>{AjJoD+x z@JQ^ab3mofUnNPmDymsICdqo+bG_*ch(NWjhUCLJ2s2i_i@58b4(}l!O5t|f``&Wg zy0iTJ+hl9fscPdM){x1Z?3wlCPucJlad(3{tz>2^RTSlfI2=0yCM6lU1e07a5A16L zOIw0nFJ@_pa>U>l6Kur-*+Z20Nz{}{qUTJhlSvPIL40VmV(MSK65G=H^?mS1%2X(* zsXuRcIk40A;^ME*5@Utd?hJ!>!87~l<1&g&UN;Wp?a7-ERDz+B)PGIAHgfTGJ&{~< z5I}C0fpT1qs!0oqV%!qu(fwPlS1W-}8DYY64kSQxON&Of#M0E%JA`Y~VzbA= zfz6b@6)XN*TU%QO$@$62g1;}bM>;O&?Jq8P1s&(DD)Bl0Q}6ivsIBgx1t9&tw7oTT z^{o1BH$fN_6qMhS4Dt3v{C#?3OuH?(V=Q6p#Mo&8gmUD>|L_M|x4n()9k{1U9L~RX z_<7jcUV}E8>Z&RW61h%omp8Kt$YQt4V-3rGDyYj|e~@6nd8V^qwOPZlnSV8n6o3U} z#!7z7`PdVUL9=M0uV3xjl&`R|&|(wo*_}5jG1MuMCNcZ3mwET z9!5npBvhofGn~VWli8UMhi#VNiO5R{eTxp4$z2r}-L^WkNN7!I-0Y*H_x^W?hE!Rn zSb%svM61#bMH_?8Ge_o?d{G5p`2;h4@^8d^IZJJyYD#mYX+qD6Xvn)JTkPDtMw}C;4&zf2`s(E0tJviq0gXN{GJN5hb zZ&FTEG56iqfo2_cpD#v{;365w0Ddm20xsnH1cMB7rU9l=Xov+CoPNFryVwNzwjJs` z|Lsju`g_t=h_C8RI|KlQvfDhPtwCveQne2GhE)so?T;7LC{l(6H*+P`RlJUbR_$@RN_RSVnJ* z?74lN?9#32)p+28L0+Gc6K%T^pPSvoT6Xg7-QTC1k!%CJQH2uwcNnHo>veT?j?1k# z+A6$At0Epnv<{`-f7anYoJ2<1+4!7gs6`gNcNL43Sy(=NoIrh!gukk!6EVM#(xn{| zM=h6(`ANB5su&jCt%0N^T}njpo0IL+7wfPgX**wxufeb2U(CLLtPQ(hI^p7laJdC| zH5#yX7p8=&6bi*`$mF`*U;q1=`}2%+Sae6sZJ#eZ$YizMzaTS{pTB8f;4nXS(twa2 z87UG%fej2gurQ3^X|lxhqYg3p#_)^{rt%6pEeg49tHP+r8fRBlu7)2UhJ9tNy9bDe z&eA9;Df<)LjyoSwHV8NVBroOeM$SF$>n|7^8Eua^^Y-x6a)IgRY@sqgYZYMpO5nlW zY;z&*w#~=K&yT-0TA2Iz*xq(``8if?ckOg=xO;#9eI*)_z1mT98U~HmTW~r~qjLv8 zzic?}E93e}BT?T=D&Sw1-0VC8@x%VjGk~e5*YjwRpIg)Gg8%s{QXZ$%kkiBZ^gMap z%8jEO>xqN^ddj!J>)i0P?ctX^Ft5k^(4z&<=$$j-B;p~r9f2W7J6l^KU`fxF@nuS$ z`dUK&eGuO(dDH~qq%4~zWZO^m3}*cO)#zz^VH|;}#Q{?I3p!0Uz?Z}y`VXR^eTZx4 z0778(W{3NT5jPO?4uB?%#8OLmU61Al7YgAHY84o;Bf~8hPCZocP`pQIduo9@Wxy$m4yl)B85qZpfStunIe5PxgN)||{ z(8W3of`1H-2BfFchO;TmefXHODgwq$7F(HT3r6W_X{hE_Ub`S@)$;L}g*XaI0G-La zlF)Ngl_Ac^L%2x!5%3J4%B8prJcY-l`rB#5&xSym4A0ER;aCB|k3>k~;n!Z$Qd0f_ zbgQ1neEmy|i*D1^NjbICN}*QK^p=yJod)R?aAYZ>Im23Our+2k{9cgvT_)u0X6$!( zY;?@_-Q8X56{1tZBncvgI7}>Hf@ogsyJLRs{a&sKgbAF%u3{SfF<#1US?!12?Sx$< zs5iO4YzAMzoietstYbfHYfyx~#i7ru!v{omCOyaQM!~Ip)AOK! z_Q#JOlhaesb&%9)_oogH4!-fD0m^E@)n=sNK+8A)`!yce{;^8{o2v z8}&WOz&2D2nUDVr9|ntm;PUda=`77=xJ)7B=g(Y!->a+>Nl6I_bVS0YT={i;v^2mI zmU^(i-+o@msr!yCuH-dyhJ;&DZS7f%=&?bwI}1K?PBR}eylAwOX!&YA>S=Ug!9MOy zAR%x_Dq&Nrt83m9mzTssX)F zav5fQIT?Q!wWEG&@_rj0O-5}bE^@&@*@GsF_~)jW>$<$W()ScECnqL&0|O|bei!9f zNvkK1>R-l+?4^)!8Ti~)HB^a2L@qsOge!{qKh}5&^kBU`w2)!#ehH5YFC66ah(sk} zQdM&PK5S*K-jq_Ls5HJbf&))*e^<+mPoKcu*SSvY)#@e)XYSVv*$1p1j9>+EuDG3IH&TqN@=(j@t2Zf*J=?BRf4*{7 zm!^(^ZPJM5@`0bTmHUso!Bm&&6m8X1^amVHER zCkO{vFxNrQ0bX^P8$R%AM^FoFY?B@N{&+0t2~(7qOq3Mmrxs0PoL8x@ES|C1EofJ5 ztg8L_%`)Sm7s^NcFY$imkF)>G#pOC@H5TsexsEdLgnre_*~8=GH{ag=#1NA6qp(}h zU#u0}oxW{PPHSjfp#sml3f6GsrD&h4)wSU8=P&Rf(g_t6#IIu*95-3Jh?E}_xW4?I zqQJ*dVV7R$Pos}{8_gdlrJkh?AXld}{@#AMjE!C)cMbPb!#LJIUCuX_+d&OdQdVPI{sfGR?_w6D+Vt~(CK=ORG z!VrXeKOD--%LiQ6e#IgzWR9HmC2~1T`c)ECYLi@$2xcYLSU-M3bNuhBJp3tqwLF$@ zTCDLLCj$eHs-P~eL2< z`>Hw1BTB9U-mYqa1F){{OWs6^GJ@Muie@%zqr9QkONVZiuju*AWu^Ulz15Fh#P*Fc z)PCZeZ+5(3IXaP4&sr@=# zAZMJ}Q_U;N0R8@6Sp$oY8?_^f8y%m&+!Xfl_!Ep?ky7yW-@$hP02;(l2{9U-ONzj|6MgxGD< zkEuvdghunE-Z(mf|1(QdG+#vjNZivSQ{>xICz#Sh)tkV8UugZ^XA6rVfcBAxP4#68 z-xl$O(Nuau6&$fVkE?B!uDvk5CV9VB^uM;#Nvd|y;|q zjP1(~#SoYvwMFjS9!f`AHBu!6Bq$Be%%0xd&o2~3^E)@#nGFqj{?!P$F2%<6*>^i` z$~JS;(T50-vKzn=D^HJC&d*lwARe;wgQXsIh1-?UDC5n0QWLL1koHi-YxnQZ-wKRR zm7i2SzNp-F1gE}PH!h`+`p}H}>0^1g^LjI`B}7*wRfN8%t<#pyeSJSX$&v@cP*zOG zvl)j?)f`jFjZ|Yt(QLD08eqluvFbIm(2ls92`h0_H#q!Vm7)mlkWYF(^HbQX42SqC4o7eULv+FPllw8Y$ z!Tw$_0b#{6c1p|!LachaNp%8|rmcZbk3nZBHq9esP#$^MY%Rc+Z9W1Ai;RpQ9t7^$ z&1(GAH>kvsLE(m3z*dr0jgF+-c8?k*Zz=>x=@#xCq%+afG}P67Mdy2Yczh^E@l_eP zzNM5#T;24tmAN%>2JB(lAD!Ie0$%`JvHC3t)M@T}VQDFT#P>O6-9*zdN!)%_ti#*W zTd5fGA}naT=ed`usi{Ym2pDqvJ#pfN;ZU8POE*TOXfwCzPBQEdQ0;0o&V7f^alB;O`o^;F2gS@ zY78tgiGKk&63i#4As0q3REei4%JMT*9_S3D3_{4&UUM7U_mi1}kk`kW?cv^E64snh z+lu1~wj>xsBviIQ9u*2Na2*@%QiBbw1lGxBGUEdR71;9@=F%`F6KWiMg2C*SdY834 z@b>M8k7NihEiHk>euRtQTO=eNtLV=vHP8UygG51IvBnD`i2)+|2DcbU9k&U06$FpI zmM+i2Bq)xE=zGE}z9wVhzvcHZ0@YhefC;WEb$N){z{<665pggR)*p>X#tBAzlO_PN z@}#HJ!|WV*QwLAC{v^L@%P(t=9E~RJiKP|&_;0;%c{xjq1s$NK458jUPubO`vHY|K zA7<<-P4mPW@d&xtBOoZenxz&EcHA!|d_Fk?HkKYUe5h$)b~~);pw*lET4w&MWPc9_V&Ku_*YF5Shv!z_Kc^}@>9|Dw1WSNH@oGK zv9`ye#Cd5`RraI!Rq)ftmr{$jjTrD4l*ySu6>7@{r*lrnr@!{fXz3tS<8ErY1SX$e zbRUf1HYZ)g2Nmhrm3kj+rM`9&esZ5~3CE=sa~G;H!4Bdobu+s+1 z6Dk~&y0yMK+E2*D`Rok^1w~}$#5L|zW8tfE->Wcm4NLGHtgG|5a{e}@JJmyR(i%xO z!T84h6+Y`WfcKpQzs+;l_r#xZpu)7p`eq=h2M->-)%%=U#Qn5ONgVgXA;1-x*DKLb zSW^>k2s9e7JAql-V5_Mdip<*uuBHX7c*s$9Gu#g2A!q=7qyu>D7#kme&(M(w%^>3X z^bcpYu)ki4xTxH#VPVT?BUS=9$VsrW=Hu|bSR*uhwD^5E2QMi-=DdHv{=i*7Epa{i zyUB#(V_{iYSz1~~q}7JSdt2K+;c&>^rN{aCB^?yG?UtgX+2zlRZ}0vjd%rr%@|Hg- z3*~h3|0%2wGC@uc%^+56XrGT&Zo`%NidL1ix^~>#>&Mx3G&ygXn{E&4glrz43f9C> zA^U}ET-smPwE|ib=OUbxW=8lro%*_yJ5uOwX}~ZU3i5D`o0FCM=C9Bo-xFgsvfU&7 z4lEb)iTk(*W%OuL&Nm_-&v#o+Xi(u=CQt^Ff9h_|0MIwu)djQq94ijRN*Ktk6Zb1y z$+JuM@C*0d*~$tx@Po@XQM+q$qkpKwiF#7q=@x9y+O*6ohIorJEo>NF0(VYlqk7gJ;dyFo8xeST}177&;NZ?i-8 zQB4JaV2H1|)MBmik3{i9iLrSPR6HTqbz*5ChmTO^I5kq~Cs~wL1^?N?d|G-sB?Tp< z)POxx$ivRc>v}VS5SkZ|8E1rr${7Ls$r25>k_i#XU1O;gPt{Dr`GWAq{F5sss0TKf zGXE>X50#+Izp1H-eY}<0ZYx{Cy4S4wUgB|7>_I7ZD}RQMe`0cc_sqT<)!%x4q;5cM zccMm5Y%7no@5&+&(e)oe%|+gov$wC zPydcUK0@A2u`dvPtQ9Y)6Mm9h`v0{6uaemId|)uCbU`H4l+1v=OQo5nE7g!+kr5Eh z=pH3(JP5)73P>a4BUuySZ{J^g)#$JiMgCfc&qde>^6>C*x%{);8Ox0~SBI!X@?20p zW{I;L@sQiw+t~>?4Op?&PU$A&?2!gQe0dv~XvC8VUd%*&g|{Y%DHDozfE9L9hyOV?L- zQHM?XDudTXAkX|{Bvah8;0z)vfYAKXOFJ@&e?K~031mK4e42>X~)Oo)}qJ(RpodIiLTa+^H2)vA&k^Y z)LaGtAOkSzr~zh|jDBql5lIw!4eKK-dI}_35>l-%$vV56Q}6Il<5K5*pG(mzXzM<+?aKXP>@&(D+`50JSQ_N4{1BnnGJN$X3V`f&!kfw* zREdmP^%6y03gBxNPx*>0aw5IC>|1H1yQ_3QDC)_DUt#9_Qi+$;Le2EK4LRM9O^_O4 zH!s}<@4f40Up%N$`7vbn+RQ9)#*{7fCPp+F9PK}5itzJ^;Xu))Q4P-Kk>Vg-<%N4h zzt~dx!hh@XrcTKF9N&Z$+cbgbimO`se3RSGRr^(&h7ZwJGqJ~YU?fs|+m+eF&#TJ^ zp|2}f*(-OL-Pt7OGZ*^3=4tJ!|KX%!{|f+K7Y=NObT_XOPs{ zmS@*xjI>(Ehza&1C>Dfg7@C?APPz#>mpXskcT181wr1T-=zrT{{;0Q&4?1@2i7Y>O z3`JhPTjVpYO0<4My#QKgFG2rwk%8Mp5$Jw%yzN3u7woc;%xP}X0067E{p;PdfsWY@ z^iqboHy;jG*M@_`MT=Xd0BGJ(hPF%)Lz|wV=+DoZ?@a)R(#Z>SI{=vl+!N1^^qLD^ zBKEJ%AmHc4gk#2SUu`>pz3zbpDh20lfLzSnPmAorAbfa@-E07|I!zh!VO-e8*e z-LbBxzMdZR)0N-#-+0eUT4rKwAm^9z#ehS{Njq58pzx7WwovB%-NM41&)tSl80`I4 zChv67T{Q5C4!O?5*8AO1gMGBJ$nD(-t(eQI`^;WsB$gCH1sBt1B&+Ur`LaHl8Y_9T z*Bun}H+KW@>;kIY}x>t2%Y@$9R0mZb5FTIe1&+o*{1^6AuAbm zQxqseiQ*Bqa$2Hnk1r^bI=i_~D2(DI$HolOjb{YzuX|7OKLo4KfdvNTBy1Ke<9n(ny=W2AKHgWMbo0b+% z(^ga<3$5!w6%IpECVLEI#7utXE^1&Chua7um6rU^h|}It4!JH3UtClNJ}fr5iFzL2 z7hq^r8SB3~68rmgW$yGm(C2h1c%}0CmPtH=vi$v$SJeela@s=sR@TG0H-12dT}KpH zx7qD>x5F#rF&nP_F0bbI+3X61qM53n>j~7kRk8RTi3GgxbKB7CczBTLxX@ggi51jO zx}V%QZu(k%bvmYiJrfDcH-32GXNQ_DD3|3eS65%Z%;U|ts1v%~(Q=ZDwv~LAu7!b1 z6L2+(ubT5FhaQtmGpc#@Ln+N?xZ?YRDy)_B6D9Rfik*lKDqb}w{NVi~o=(*Dx)1yu zN$Wy1(j+J)~)T~a;&U#%fc~XMCF$E2ch-Z~epn^iF zftEn-n%pm*{Et1;oDM@buiNCIdPGj9WfB zf(Jla8U=L21pI8edV2dD-!}Xto*Dx0UYwXxpk~Wkm-DG^SX8{UKgy34n-}TO3dM|6F-kg20j1nL5r1k>(oTZ-9OF1!`DO8*P0HGNZab_f0AG0I{>$!#4u)lhxUO z8(_?|S>$6~F8h)$(kI%_8K@|U*2k=nc0rA$ zKk{1ZHz7r%tawNw9xF^|w)nfjNh@TwkNIK(+c6v+qXzQF-(IF74i2g1{!%#*Y1D{C z35C|K4-;Q4`qG&Jy?BpJcg|P!y1UAWqQ!N@a8+uGN|8Q^a7vpJSVq zz&-C7i$Ip45ZC~8Pbn$w~(YxSyW*a4knz2ORBC==%y z(6RIH7ANAoinAd!so|ikFU*bt`G4LV<2m`-|EAFVAg7(vKeUgr&&4ipmyMPmrg86n zYxoGw7-v5#@_vOJ&dOq! zy5<5hi&BliiIWcirNNTdqZ;bO4t7fxKewxct(R~A!-JBIhn;025H?D>reA{!Ii|Nw73VqV@{5D^!4l35pKBQT@+JvE)v~xmv!x z5!7U-mi(|jzFPSB7;to{tI;A9)8={WvExq|7Z=w6nLr$(cKXzINCJzI1R(s}G zn{8h>zIl1lHm=H`Q&)6_3qtLN(u;E-X1t_p5+5M;@?nL#e*q=je_ZVv~&eTi_M3Z%Jum9 z2Bo`%VtRWOPH*l9Q$6-Rw7b9mW*MkZL*#pcpHuc-xh_#r+71K2!80@l&oZz6_33F6 zRHAs9n*YertXgrbdO#}0(Q1ExKe^fjf72IgX}OV^nfakK1P0h5gcwW?YAn8g?2b%I zRb@1fk%Mc4I!Dl0%4u2;(`hY2ub2Tj{oDan-*LH|*Ua*oj1Q_Q&)IXkeU&#F+|=ob ze5VgdDarAO%%{e~9N+id@&7GE0O+-|?(RS7+)hLBP`|vbCUVCLK@f*peW4R20jImK z)+xoGr%j=MGqVN2zdS1Bw+~U=A@NSu;$}o1 zq4>&>wefIwxubA;mbUZCtmc^Vptmvi8BP7dj;DwE!xFg}iKj%YFU68+57LDEw^gr7tF#>} z9o;A>KswZD!6=#CI1S`ugOkd`w}os@YO^mzb3KEa40!_zMLr$b4RbYysJ*^1Cr=jzmS9lHq0=C;j zuap9kiPLBsE@_3Xhl7H#*!md+JjlK%E5_OJq9NhWnb+vB6RD7Lm@pGD$}7mHh{HEQ zHSSbXm@uerb$IvgCEZJAUPl&%urAW)fB^vV(lN1H8;xY7QP6cUHZy7pDv;mzTAwT( z^OK0lw3*&AXubORN?pI!*E5GWDJh9Kb?`q{k`f6SO7<;M0P*@r=mU?S{3MNLewbLT zXI9X`!9K{T>Mzx@8mFScYySNMXVSKZ%gfxK^wye|8boyVeWQoMZX}#WjTT#2mh8y5 zxVV>>=g0GP6T&;>A#L39!Ulad`b?Vk;40On@o}&T!U*|5l`Z124~h_e`GLlk;Y`8U zIYJ8S6_2umDSb0SypvCh9^*osbW#BPHuVA=KU=Ssr{?QUEM^uKu0X%F7l{fwUR)p9 zz|>~FgZB@{uP6X4()51dPX`$dO@xXZ#0FD((?-&!j>PYf8&n^9o%UCQiqHGulU-qU zv9rNT5Br&6kTOc8WVr1O(O=iW@;<`)Iq~zv*_Ax?l=s7HoL^G@p(7U=wAAE7Q=8wx z`!t7zDx-C$pyToGyTkXM(IDKPvHad22J{#u(_i=fsr!vLKZ5^S3TXX!?sEdN!a^~I zR?CZwzd~ZhH`iImQ9EfLn8!jsRbk*s6NQ*AQ$5$tn__CH%K3PDijRYidu#q-_;Yl0 zUY4TFWh>arGZO|OuG*`so&Ee|dfqUfiXzB%y7x1z)|59}(Q8;0_1&GweH zoDUZ4NfM;B1RqEVDNB2P26`x#UX9>LwOj#k0yo1JMsEmyOw31frhQXO>&Z!n#=zeh zb8cnjx_{abVL8zWG#xPH#Y282bTcrZ6e{<>Q0>SHS}kq|2ihbmJlClLxCoYGtX! zNzK}Qs0CCL*;OU1L@Z~SCsEg8RiRvUr*sz%7o{p{bre@nHQMl$wdR9>oQ zQNI)*r2!DT@d^S-#Q(|iv~%Z{mzO6eb&f?iXO0Zt#alQ1An|h?&ZvI+b5C2{QNS?O9 zZe<%lfV!lJ2(OEOt`3_wfGw(6H`Eq+n{cI;muHxFU%fYuUb zM>o{X8iv#P3(1FfFnH`j-fslXypcgJrC=afoai(YZIW;B23y~ajjtB$$z}JdD4kg4(&px zk0b~2_Y&ADwVZHhzO=WucLW+($9Z0d7_Zk57WJ%!7SEh;5^N061m+^32Fn9(1BRlE zksRSY%#8rA0Kl#_C(o8&i*p2C*9B-zpg;ZnQ)O>wmu4WDRBOX7$8ndbzD1teZzlj;KH3J)bHY1METz*69*Tm%}<6f~+ieBT^G9y;Fsk>T9!9~t( zrlOKk`P6Nns;c~r=iJJ4Pzga|0gr%wjB;rLy*&DJlo^%9XWLH@NMT9pS8FqhI|S|j z*GWNeGGvdJm-tS{Qh`_}{yUZqoa%g;faG({88}eE=Q8c z8!Ntxc&o$uo_~O)X9foZ%MdJ~{*oJ}p6y_!>puM%m;<~vnHZbv$nNVs1vch@sTc4) zl?$(y+lMSZjE)W1TrJyu_P?8}!}~se?pDr5B~8ifQk2WDlacpFFFYTvr|6LXQSW`O z!?(En*$&2oT6Ja8TO$dhY?C29CUu!q=lkWq3?CAZ*NsbQ0xf?Mo6$J2UQaEVb&blG zlR4!usDima`z=qQfCN-0mPQKvgeIa2{J@~P469Wt>AeGX3Um<>Nnbt3yV@2t^OqpU zmDVN%;sDUF?)&-q5DvnQD?Llcqu&J2wu&=fSC+~C4T}%DDNAu`Lw{4|;l4o= zr%v+8$LEakCMXDJ#M?6O`**g~awj{xO5kXgl`)`!=@(?U*nD)dQFF7pQK37TaqC*< zt=v3CyBwx)I~$H&JjCzn6a-~pR=y0el_v{^1tqcL^-_S5)TM&(* z?)>U9YhQS_rb-qa_=Vm$wju#>zP45iUFXeZT~7Pd;^KB&)H)M=b{6VavwQ`?jQ=1z za@Qs*2fRS9z5+(Zs{1wab<6c3+5w1^wY9Z-<)?wfU!EMMm6gRqzJI%(Mps(;=5>ud zvmFqAhXp2|7zz_Zlqf6+p7(O;)Jg@StjlkxiN-2^N{r@HbePCeJl$29$T@74NZLp` z{2`i@O*twQ8=Ms)wkt-nxa?uUthU(M3l35OQ=jnC$A{#O;pmppUVXTPo%JpF9XZb6cnD_`N}wD`Hc8yg}EcQ8)rl=r>p!`Gl)`>+4b4J-keDy33KVB{I`i+r<>~` zU0ssL!6bpJ+mbn(;n92#SxqvBs3?INa%}kgS-iQ=0$BqU3&y?HW8QoR0_#&i*Iz5r zEJ>Hj!lGfl(L{uZVUg4ELxalD{@0XvQf@D+1BK#yDvE- z=-~)B-;ZLHExjb^!dHAhF;G<4das$XS9vv?N9Ioau*f>y9?6m@n2Ok?Vw(6aZKdM%+3wM3 z-L19uc!%~h&ZzAr9;nr!he%VV*ED{QL7*3JC0AN1p7km$g>P?vf06r#`S5~3d8LtV z`Rsz7h_LVtP@@5v_h-b!CF#SxEzYmqY_lWCSjNx;feJX_X3&(YU_{wCd!g2P5Fo>q zlHg_U-aJzI-}%u!)!;j|o%U?M9?>{Iko>mtG_TB%0AuxAi4b@_aD4W;p$$lI=_GRC z`U#7BO1$4{xqZ4LZoPb8+b)@PL!ZSpzd66pMr*S`&s$t>qrQK+2Z+1Hot&PR*#P|&yHhH3jo*a0z1th$OybWDr@6<L!8}$+T?(C(ohP*n!vn95F==yYZ>H!O9MO{QLSnA7n#kZD{0^P-^Mv2^6|a+Y!w;R;!*;qf|2r0kVH z?+#l4pp%_6I6OwqZI-dc#Cy}lvKXb~z+=I_k)Rre0D*|6_b)tK*Izid9X8w7e^vmw zp2kD~sIK_Kxi&by*iQ64wf4<%nB)(uT`jmnv~)y?ZERmF^V5EFBMS( zlajOn^bKolD&~;T?WoPkyZso0T#ys==jkDL;~$PGtBIfu7QZ;sN*ao4We)v2{~=rN zGyc7ky*>QXr|(*d8t;QXnfNg|_X>8i;C61&_()EN?3C-goj|XFe0s}{?m3nu4eGZQ ztC?ccRh5hkgtAKDN;>_+@(0OGdE@fi7E6^%YB;ibM|D2d@rU6^VG| zG#NqQvx1iHj~m8}5D>&7oFDCr9vzW6Q*d}PlXOVqpYuykV0kE6$wCD+oFx`n^HlWE z;vvrF_||M~s%M;0-Vi|snX#YF&ZZ?C|CjS$?{)f{{cXrRBwmr|4RwP;sk3!_G*_D{ zB5+G@jGsI({3Xv04weCYeK~yrGs=^+q#j)#Z)h1N({jC$3P`#E9I*t#VZ#m*5O#hll}1@I`>mXrYL5XkGUI_5Dk zG)`D<69DwK`CO$))lF@dx$n;``y939T=%eWol7YhN5dK()}Me-87z;7dy@s9ygt_f z`{!G(yU7wq-`^kAIOr+b%^9)!%?jQPNd}lrBmIwKHvB=W_1))t!pMNxvuaSQ>r4E| z@-N;4xsLuheiy>Ged?Y~BaO@OzF2eI>xO0fzS#AZqoI8f;XCfLNqfQWm#y;}=gP0< zjOufr54TkAnkoT5sgHQG&*+G8T$Y$OkTAH_pTPM0b@=zTwu`*H3pBKca(z>Sa$P)T zFi3$uB#^!%cmAp(eTD;vArS?|?oB!|@%oTnMBtT2X9RKI%U+gj-@P=sx_QTXXb*2) zb$B?=F8o-^W|a1dy-jc5fS0@aV#eOt8K0gg5%uMu4634lVl;}4huiKpi3v!k_LT(f z^_Rx?fY0>u_s;2F0>XxLgiVg$;ciKG!%V~Cd$>6qrJ+nfG2aNE5Lj(XiE(ZT>i+@b zga~4D5#jF+MGL+m5`Q**d&<@Au=JYbbAxfMjO6!L>a&lL#74L44|?ha zU_$=F^tIS7b1+Eq7%f)W|Im5LBEk(ceBWOu_={ySq|_p@Q5G9}>+WFfO6Tb8pSZ_| ze)u0A;-;tfPAcli=_?_K=q!n%7uawWaK>|jnlE_-2Q(7|fOC$R( z!5Fo}LYs+deuGHvnn=9Nn#T%6Uk{ACzOX7LE{WCJ0ck}5U!DH7l(X;uu>i@`B7!9b;d#-f?!#&bo@(z+rDM+3*bH)v#5s8|m zJ-UteJ0PG<|0O5ln{_A5t^V~H4i#L2&YemSWmUxi%lOl!%DXw5^o&EAJ>wJ&gU$O2 zcfjzfBpa~Vv{ypB1%9rJPY>VS_3?1etKPNeYaxifBMIIb<+;`Weg+0t*S_e&)=V#+ z)E@R|S$6y>mPpSUhyecU)b{gfGu324Qdq!F`z^X&z-65a3ikme1_42WQV~$W95(qF zAWZfTm?6Z+c-+)b-e;h9TRodymYlj3$iufx)=|)|hM8GWUf$Zjd*w+z+{)?2SSJ3v z{rmDJpLRjulJ|Hy?zSI{tUvWPt*xm>D1h|EEu0_*^cNA!&lEvM-7Zr48iyYgi;|4>-=p?VLVPE zfqxe6dd^0Xxh^G%I`0CFPBoY;!K(Fo%dY#J<@!}hY!O-sWo2bR(Xi})cQ9?=riUm! zA|jCW8C5ZP{=shhV;om71!{f~oP+%yYR{BC8E%m|ve%oe>Az)ytU#_c%fYpDxFiT$; z1(@jDkY{=OGbNpP%1jWe=s*#6jAsKBgm#VE`6LMy7Xne>v@~!;bp3l7&Ji@GMB8>8 zCW3JaH*+c3XONq(xt)fN;R`d(Y_cL0re76J-FLJI_<*t!J=}KIa$_`Btl4k?ep^Wx zg05gB?#W;JYb%Y@wi%BMlotYy&@|^$QCA!Bi&QpNg4Mx?LuqBow8&KeM_*e5s?sSM zk=ru4)3UgG%8q2Z+j-NR$Gbk$+kdIgAOD8ZP8Ge}{FY@P;CY`!`RGJz#GHyYbANrL z-(fR1wXjn}7CM4y{hjtMzopfgX3Jsam+26-;PxmFL#>$PaR-`>@b{bYI;Lj-vBVv2 zeBd$L9yW5}`3dVPl09?0_=7xe6n*?lhjohuFgJj}IXycY7LwaUBVGQfd^d*E5DGzz zPD7et9cYpF;XB7k&%{Nzb`le5rSs zS#jx>vjh{cy!?-=Y`6LNW8Ah{VL?p*rWc3S0c*35M(I&~^QRSlumET_JbZ?t!XNfl zJA;7~oyI_gcaG_(3ikD_cO843oqtukFFwWf0-hEz4|k?w{^x-49Sdx@n7WB)2sa!c zIR7jEj1bdb>v#s)vGB!jHnjU*kPvf;NU>BJ#p}yHTT1! zlHAu0TmCmvC>C4&i;h#ZhJ`n~LHhLaCplx%OI>mZc217xF=*&d)+qRq;7_=$GmE6g z{&K1vyIlBh#-xOJs&l)hq?gn_^f=85Z>8b~>*Ir@26RfR5BJST*M2UKNTj`d82+=f zMnY^W7gp*g;CU#6%qLw$1mXv?K$!K+t*2y5-&Fj(KB*|WpBM^_Ls`8(AwKXBHG(}N zn`Zb!9(zuR)y2=I>PE#ZRl0_NE4#a(d>R|n0OQP(GYtqx)JW8s3c6js|WDxm96KX~v-T_8t(oVm_wI zxK)+JQ>SIYN!oY-q<_YcSGyK0iY6NMe40tIO^-2HupZ&DpJFJO`h1vgEZ^N$hSJ?+ zuU6k~f0T`5OMa@=8SfO9 zKd;{wkBHZnx8$how;SJ&#b1V%zrndyk?j8FlUe$y!u;gWKfYeu1udShjhlh6_e909 zlixj*6@i?5;oR>a!3qpgKeHMPhi8U{RLZm9TF)~wtA;L% z_l9XQzx9ZnBDoD|Utk=El$Vs)>~2xD604y{XvJHc_%5GrH~XQpAJ< z@eI7ZxX#Tt&HI(*dgZGIqFhi#{_kjs!V66NeK92;M_XdniIze&!mAFikMFXE+` zx~))p;xuGl59Pn+mZ{YuoCp4Tgwy-(@F)fOI9f$*94@@ir8e4bt;J=apEQZR@moD_ zdFx>@zIiU@!1f>#hG0@ul}aC;0W3LzN)zDu?_3X1LFp*#11$T~N}s<47QR{Hw$omm zTwJsjOdl>rE@jGR#G}u_a3H7?_Koo3V*UbVudivND%jy>(FQdZ%n+hiQqWXfDamkK zgB(x`&y+g3T?0(f!YGE030gY@&gD+UWdNZxxo&Sf*9lL9z2W|F5v%d-Lg0%8>zJt4 zGIL?9+LlY|jfE0{#s#M#0pWZxS4$1@IKCQIW^aNsxVx3`m&i6dh)ftzDR}ox6? zz9#wQu$ImDBFTq<$6NiQd)ObkhlBN;_Q39+Ur|SOt*^Z+{!-sm8osBD^!MI7=oYIs z@$f%6FENQp1Gz}Vq`5gfQVNDut@F9&aX~nR##EGYy)Qqx0=0O~QkX6J_%<_>LwyLw zPnkBZffsXA+3A_~{8WzfO4y(wsgRk|GHv28eB|wf@*Q9(USaKkD7PF5gm!UstYJTe zLoa^&>|Ma>FSD;WcmSy&IYfbiK>9~3zHN1hbcl{oipaU{ptL*)B!_VDnr?QdUU9v+ zn02nuN!;B{OG~4KuQZ)y06ce$9OL_vFQxPL&)g6*vR{ZS`4g9!21wbfejZ#d-re1X z1AQ#i>*VI)HK6FQhv5Uwa1VH9!5$$3c=iA#neUA&$O=yAv$~mzJh^cG0V``5D6@u3 z|8SIs;xOamz3;yOhTbU zub>*Z<5rG?IntvCb9X3=-12{=8l{u$R(z`N?r=;4Z@dIYb?PvT`b0tWE@Yn%f{J_A zgQ9m(6dY?OjWIxK*1#8Y+8A6*@XZ zRszFW$lw+el|bNciB0=qPm@@?1e$!Qjdi~eFFPu#!q;z1ibS9*%r8cVga53;!>@Pu z!JnPQSLDgbKx6oFPc1&4$GA52$qkM(D)i}V+HT-raO>T&b@CbCxCLgqHPx_Ik^iMl zz@=Nxoe^;1yBFV9(y5!?4Fn+9-bkMNnR;y{P3N@JTh4i;E}yIx$+d`dkD{1ew@?B| zqPtyfTvJirPO9!fuC7>XW>o;!%^;3=JWfTx&HjPpZOm^P(ai1WG@I{0@Y!=bJOBun zSfRkpNaY?539WSXSKS>mA~;yQI&b$=$H~2pH~yeGlso+ib}(~3^)cPGZWf&nJTdOQ2eCaTmQ+YD4*$x;<*?V&^Rqs)IHe6=A6lWion?*xd%4+bEyc$BMi_cVOpdG^;P&Ha z5Jcsr{&v8hk4f{TGRw%atgfEQcMJTPJ~{J9vd1xeT*zQVM8>`Nj0JJ%nloT zhobG3I;p0ONK*?(r5|c`?PZFK`BJOd+#|+|>L0mPDcYDKb%y)nTM#g3`qK{NP9K@Z z7b_*hqHp`;)(*ALvwouEU-S?NzAD__)X60~P0^UXbdQs%f@!;LnJ{h5H<6`4d zt@S~3eYsv05dq1MGQWrZeV|H2`fmV7bg%&i5SPgwEm_5SKOkWY8N85pHPnDu+^1F7Y=^R+qR!i42GPxKL&)rtK};isk=(iB>VbiiyK$Sq*4X|WhCQhmd9BH6C;FkZ%^EzoTrlpQ9LrUgJfB~K#Mjdp^* z!j=}!8CuSbk<}-IPis|lx4$g6I?sSa0CKO&^q5)PfH$Vu62tF;%dM{EFawoeQax~b zP=i{netRVtxZj2Ss}(qH%u!p-e*+&Wp2y7qtjB?Unz2x-Y2k^kFPWx`NZdU1bQ=WA zmH5MfpE^MH7drxF6%3(QH~!I`4Kyubm!_UACM>~I1FW1{_Qk^VZeQBlkq{!jnIlNa zqzM0t7uX_nX*9}oQaBC$x3k*9!KeUt@k++x)fY6hz-q8-J?t%1?JZhk{bS@HR%)^5 ziu)`nyPl3cDdEjTYWvTCrzk43>|#3rObBOsrpvC&YlWbS)=`q06>FVN&PSPJpP70rLGR!F6 zNm^nsU$AGl`H>aC)v!1TLM#4_z)3p|%X}E;x z_6R+MUPP%@nNA`$&aH14cYN9V z@6!}&hiI6#Cn#U8U*b{dl`$113WpFXV_~rk8~peD%_((o(oiSkASxLO2I`$Gf%#_Q zzhk_>YKLz3Jne#^pEhrypfu(X>N<8bW)pJ^q4pH|ZS{ZoBUPwTLyn1>R-SVROFC>H zOs%r}gm4{N6#xx)suBUAKO#BKY6F)kf6UNZ;Ah zBIdEoMxeXk03_UGHr4bZGK~Y%`;+pVyC%~Inf0Szy4YjRLS4@mn&m@A^ z$n?@PMAFDqgEw6(nroS__^cR))M;XyP<>8{NXRY5j;8A zZo5F%vFw{60uq^PGsK1TABn#~r`lW9;!dnCqp>k3WDzK)`c>xU8yLfDEgTan$I-kC z6Pq0xANm(X%s-M4e6T8X+aNfI0JbdkS@4IcKAd^7Xx-FM+tb1vcvS~#PWq$MqI5^e zau==68q^}9V|GTI8nsk+l)JZIRGmzKcJ6T7N*`LsY8f*Y4*J0$sr2vS+6-Q^YZ`$e z^{^M6KWWkx;@mxL+^9k^OeIP#TXZ&44HTiZN+i7^P`u1jN z;gS{yWGR1~nfTvvb*aD8znWm?l?Vb=pCH5}f|OJH>qaN%_7CZLe2}V2+?@qOZg0L1 zLTh-=&?LV;cAIjw?@MwyNMx83i`Zjv%5hf6o~2LZHPJ6L?bn2P9!?0Uf-6OOJX-u# zJMwCP5smM)?ieZ~tuPM`sQHt?VOTR^{J18F48q%cj( z{y0~g8kb^J0P>udir3!SdJyKw^d(|}qhE!*?G)o3XZsHz@4r|)u`nNAZ{?n>+ zlDr&bj>FIW$aksmg@-&4e$MjNm+vDpd`qkOl@kbmRp!Vo9fH$7zvTT-PScHk zj>ke0BT^;TxI{9e>#_Y}Nz%gAI_<0J==8Ud9_xUE$QSFG)u(YWi?_^eOe-Z7NeH z^KwH0CL*)8ssZa@0!(^KDRdNq8dw>}3yRg9eAPrKe-c)B3M*=$M>^!^m@A>VABOev zX-EbZg;ouSA%}%w?QX@#=NbQ~R20qs2$SD+{%cc5ewX?D^j=}HxphCm-C~5Pv4a}zTg~V&~Q#Y%jdsF|s zhZ3Z?{@>gv`R-XB5D7Ml`*8I$&4b*x-$OCd|CjTi_4k^6L+20e?$u7|uA-6fxSvyg zjjU+mtp~-s%3$T}FH`Ct9}&>(6FSS#0AnXS$kvj5L~?4W;qmO2JAD);h4H5WsZNz`;EhlE1qh zUAB>?1HO1Wd;`w?CE26C5ER!z6V*j?*;N{=#H}gU&VImSlY&dlD6(a%2EM{%y+rjE zBOi?au%Z%@pz4IXTJzPv-n%CY2mDfrtdnMiZKzSBzL@(u+M5&xaz})I-ulELyIS2| z|IH5Q*Q1+Bo_2Mf<88kgQQgNL_BhP+v>@}`X%-h@@~nvnpXvY1L0*`>c4$LfQ0i?Q zS&0_z?V0`Z(`OowL&4KZuODtNPA$)zq-9puD0f{eu2Ak?tU&}12?9uZ!|e8yOaqO3 z&{U7NsR%uf;DAolP}XIE0vhdHH`iwq;3d(@g3#v@tGA| z#jC9Ipjh^jFp;NSi{PEw{KAj-7r(+7K0RR_asZ|0P9i8B=z9UW)D2$~m>(hjBahrT z&uacW?W(W14=bxb`W`TDmqsZsmONXohEw|c!^+&;jwGl=U2jd_7(Yk$p?1VprLbpC z;vM7!EQ@)qEoD@ZTBCL>QSycT8FwsJe65+oPgXsvK< z=f2&WrM=&qZTDYY&FikBmGED~Bg1RER8W{Cfwu;yZ4Nj)SSSsqIMmxGGI=gfn<{<} znN#EZPlsYVqqIiJh}GtHizef)J;xZ-#l%D7aT%Xn`(P6&QK_U-H&1|qiNn>;8}=05 zPob2E9ava~;i4#MX-gzWVe^}q5Gupu!o^8&%%R=~fy@Opw_@?}(^~R=@IG{X6F}y0 zfJhB>mi_6uq(GmY_xe&dQTl_M644kOl-i(B1h{mKd&Wzd%_r4tCV_RQlspq5C--u3= z$86^5L4$(KSt0V`Pn-1(qXAHJqW{Nu0gy-WvBO)(}?7Fm!a=J&!U7ZZE z^>o(l8B6KuU5VYNsdkwUD;`_+eDv)Lr|T$!g3QoAtr;d~e`+(SVwmXPx>l2hcG~{< zHmn1Rz)b+z{}2wWPYI2{h1xJtd;hft+j?`Q+VUByB1t;2*f^l*kaS-(6jh7((s@T( zQGXe?6}zeb#{xh#KpLO+E`WLe#1$pI1;S+OE7Qr@u&~dvPpa2}2L10LP{&OB(}QR7 zf11E`5FDUGbY8InmEA~G<<07q|IeGF71!JwXOruWCfg^Xk&-gNzhj}=91TPxjF>MY(gS^)I7Pyj5g!To`zewK*pHl5xC1RtCY>c*-}00OCc&y- z1(-&XUy+TbZ(&nVcjIi7tRFQ}MkU+;RgjHZ|fS{<5-uAix0r1Ooi#4yiW;sIIl z6ocZih*5AN!H~JBz7&ze0ooCCmf}J7uyBN4l0hJe2?kLdnxVUYu9QU|}1w>|p4JUraqEf!K39FgUBuTcg31NDpto)HKXZ)Z7a zypeg~;XiYDJFwK4p!tTqx)OK~#@l2Ap+NiOAaokai1CUXL5tG$LUmGd&FtWRP11pl zU-LcPd)pUXe7+d6__GtF7Kzbq;b! zCFmP3)|auzCogA9*>9kK*zzRv{^Rq<7!{b#tziKMionAB|2EA6ir7p!yIXiF3l& z4HRk*=@#<{@e+VWWuQ+M{j6$<{_b|3>e@iECY4eBYlQ2pVDC_7 zXs*<9tyB7+Z*BNLYJ6oBZ+~)jlQS1)tZumDDtr9?h@@;=abUJ(aG}qe_;m|<2>)OQ zeZgPU1m`zqO5z+UbOrEj4RghUF75W#PqrMGMIRnfQmU2P<)P5tHO0y3hLa8obOOyB z&1|!+n|iPz%1m@pxUGs-*$namVK4Ne@>KWg6})IoST=<~dUOd5a!&PW$d-Hw9vfgz(y>g0Bl&Vyr`lHz)Pzds}h-Z)H4}shwReXDwr&dXic1*^&iVd z>6qed36*ob;mu5e|KCm2GLduL(LstlDW^la9-Rl=JD&F8Ol)m}_;s_!N`Bb43%~jU z%)7jhpl)yczAr2hHU)=Xo`b|xOoW6GZNyYD zym)e|*I#7yWu)4hD-t#N@vKfaz4$E>z2EDF}aU9 zzkQ|sYN@SI3t_hznU)5u#k2Ir(oA;$vfd*Gc6KoNdmR&aSH1=zS^0^4N8}#ZnEIx$ zxznki)4chyBn|q7!_zTTK|Qq*q(c80>ZlE!f-nrBSW`JO>xNi$*3kw9Cf3p>x6MiI zLlia)L0}`^FH(ZEnV+*QocdPNqU&7pfAXg${?cz5@hfox7ZjLrf;zTTMP{ZtNze)B z+6*}WUy`8EO)@?y@{^N)DBYW@HQikwAVW*n;vJ|Tn=r7or=)D1%RheQREyos@-)!; z%uj2+EucYC+qi%MRSqqR#T@;#mSw00t*ia=;A;LmyizD8aHbd&78Z5g@@e)I(*!0`n`wSINn2HhA(lwc$5G9XNkYpp+TV4`v{Fl- z(@ER|(xW3_p9h>Fk&|t&zdH1ZJM>nzl{pARqx$jxZ&0q)|wF96h{)_q2 zQw4eLt`R)XH~acJj;eGL7oEzlfUnC-T1kK3`wb|)#`A<8vT`Zb(@^<$Ous=C_ZAe7=P|58=fjY*or#njEjrk~J(^QcSLl#PS_m$N= zB0*<~<)-{NJ|DGpe-^E@Ir%jErf2Doa0JgfdmfR6=a1Ad4z&t>`y71wBmPbL+nOuk z%K>A85(6c?bFv}hBsX`r^qD0Fu9Lu$&wqv2kuKZ6+Q8#IwMwRS7)(-1D$F5XVcY@J z#j0;duf?Xlzk+P189r9J2mbS)eZyRgL?TV9t}f3*wuw+bk2avd3Z4<7q$A`C#=oVf z|46y$VuV0>dpV4oD@>}0<6*p-bg6q$Z$>__LFg^sv$k^4U3V-46dmqIMIn9^v%AX! z)5p`)|L&mFrvDnVC}{`Un>^3Q-m3QV=_-lE$9Wv_l(z+HOgccHf3fxBbJ(aXhTHVm z*qFTJ?Km3Nb1?wd+s7c3kj?2G$tBVZdwvuC_cfQ>Ts8OboeUWLX>HHS| zYY5Y~H7!cEF{`7m=pZO|8U8w&IGbxuM0i?6xUkpBnC{3kaAI;$G004%X78g8y@F^= zSNYk8$vMp*g=0D^ZOOwD96Bi9Je1a8idlc)Elv2LI?-S8X=a?|KRGo zo9CZid;DF-gksEhFSIad^ztx=9P|Z)<7fyYD%wvh<%yqBK#1d5dehGgF6Up;LWb)Y z+gc{!vJjL^l0)_}};`I}QvRNP94J|&v zYHR;nnU*_(kqH;Iivy|w)U=aDsQiOK5R6jUZWc% zE_q>fLOLDk=`U)drCtlrAy)sgdtH;BZKl;7%a59FbM@Z;XtvH+7VsfxwqI;Hh;?oq zptiXdS-HzP`y1D8%jd`?G{yup{RUBg@zEbkO{(56!w|X-FL}DeczEX3w6Ur)8RI&e z{H35omS8@S+yVY)3DI?mf*E+rbiYVzfl{|jPxcf>K3L(T0r^oj!T2o=0LBbC#Kgtl zhA1Yoj**}^Xu}l~dnmNaboj-ZfETQTKx$^!XAs_7FME5~du6DcOqy9kcq!-5=OEO) z{xFZe-=Pm%9Ffc9BF~GTFXo#~AIfh?T1VXHFMl1h#bIPz>D#lZv56Dy3FVV*ICC_3 zaVEr$n^!>MwJl-1wfY!bH^kGwDSXlPk@+L4xku3K^+on1>b!M`@o3`Nt%qSb;VZ(EMchfr+ua|7kZ0-xQFww77`0jGqndksX-`6UAOQd=C6`z7 z_ZHg0{^OObRMH#Dr`aIkF80i-+91V6U|3M17E@yPUHz9*QM2nNsiGE+tod;DuH1kV zHbhDReDzhBe^enAdyHe!HifO|zZnXb;05w2wf$%n|IcI3_^8g)!wMgNETL~Ov(*$={c+zWcT)er1NTi^fbO19{Cu{bbjL)P_n>=rekVbwMOf(nsU+ zxwbjQ^XBIqVd6_cO`-d@!mCY{x}QLS;@A5X33#zr5#c1Z@FgHjkZH>=zT_lCsggCG z&QYhJb-ly;`&hw-*M|?s#+ZT*Eo)B&zlsPz6!fjINMU0di#V<%Mvqv|Ln^dZ+!wvC zaJIf~Xc2&|0Qs(tvUJr>&oY}`GJtP?X?>JZt>rzri?=k~+j13?&oD1<U>&l^_ zXGY(h%hp;n9V*B|<+DQaUIhjU-5=TBpZhYirg(7}XfC-m^Sf?_3dA_JCa7@CTwCr# zO*kiG0#-4Bt5LXu7J}o&JD4Kd#i#57yJ8#&p*cL~DM%e~trK_01|>2XG;Xn>5WwMb zOs4r@@GDhqCMFr)t;3dv|LBU3W&g!pxBJ}zi7Uv};S{#|9UWi>VH~m`G<2jQanbh2 z{||YI|3g(0GV>`Y71$RMo1p=??)HR1@cG;C7h=9UA6Wy?@Lwl)3bdXWoY8}5zR}$x zKZp5P9p8U_2#R`U-7CU5lZpKD=eJJ|(yYnhHSPbr8=8v)(p~`-LlyEm3i%j?y#5C~ zBPw+~0^)d&EFuiI;6o#tHwho4*LbvDdS77?M?^m!HqM|jil*4%{FMFGPUbe`Db|U8 z9HJomGWd>{rV@+I`J(Kc$r^+LC}U_ zhQn0WSipLOue<_~njnh8^5uGm zlF%5cwCqLBg;1#@aEFX0SKsUI)5!4j&d`2(0HnFl_o`8N-hAPCq~od^od50`*KCjR zt#KRe*lmfPM+sVpBa&!_O((&XQ5tjwDpaa(_MJavDhpSr*J7~Dq@K4KrPs142X#zs z06oATsgPv-3LyH6p+~PJ1_XTudFSx9P!A!ns4A;drgzkQHuE2&$;FT>EGBlp;82yU zxm~36AEZfM_r=M`&-sjfbZ+$F;qj(758vdKrTlB{01Ffc83PX64|@k5i%H)9gnGKy zuNSTjyx9Ib5AS&YTD(oeFqRw|9ZoZMTYT@)*Ik!Cdho>2_H@K`FB%-xS>04Eb+$lc z%M~thh81w$7jSDcIXQVV{OQ+rkc?FadfbcPpjTtusYIHu3P~~9Gfyx=i$Z(Rg2T;~ zjzciH%0AX}7k=CI>L!5=Vw3;i#Jj0-N*{q+?u? z3Vz)5tm~WK(or00_q%{0*ihfB%mK6v)mN&8b6bu|I|+x9EI;G$07`d}(=GY+Et>L- zsxb32D_`gDGDCKl)Afe`8vYMY-x%F^_l29)y4JFZq<@oZmTnKl_32pHa3W$CuxDlfN%ksf+QCTlVf1PL&b)+#~F(qn|j~ zQuBR4u9h>xR_^C?zkmp5!1Hnt7o>)-;XZE#48VDP&3bhBLwh;luKAw+dk;c< z6i$1_#r?hP?;pr$VqBV(Sd^lRBf79=dES8<<;FDoKV@yp!M2p{P4SWA`=<27t^%+` zcN<(_0ov7^%Q+DVydv^ofS#c2h_)le;7L*z@1d}!xPg=)*fi&Cz^Y%*wzV%#evD3S zpChQ}q^>ghgD=6JUYB+^92XY^$mL1Z_wQU|{bG^oWA_)7V2dUmCM%&wEJLtH|kpRHYvTp)H{>sj(Pp~d0Db(Or`HR>iDmAl%f zDuCc&QapvLfCAjjfC+BvbvS5?)`PS^{Fr3aU?%*>7r-_M3SxG;&jsp5PRV#3eXzgAM{~Vz`=Z@hB0H7E z)i)fZV_g?&l_EChJtjfkXdM+xGu@XXvck-@^Cm)G_j6Fc`0@Hcto@X~$?N6%X4||0 z-Q3%c65lVTg8tDUQnjzk!#1Vd{d6MOa>eS8N|s1^)polEA4df+pzYXRhHsMo@T|F6 z$(jT%U7TEk-(8kGhrz+JBUqvo86W;uQ72xHHYDnx9QNuf#MD%jn0B|jUeCN$=#DhU zOf|T&A$3`=E&4VsDq^P8w;P{D?X*56jw9eqaXYR86iKY=;383e(slKxBb4m|75 z-J;J@{@1+O@8CLCqOS4G2Wr9gO_MJ9WxHD%G#94&SB9xl_AONjR37jNW%?-UNP|*M zYlQXsiq>y@sP_h;oYY1PHZe-g#h0vWC)6%DZBVX-D$xEL-q@mKN9a`K?4jXqm|844 zX5a3-HmdFB`mi_nTD;^s_0v0YbEc1ZX#meXFqc0-w_~2nNIslt6$mII`|pvBmZ|c8 z%)JumkaPPwm>jcr-7tE#7u1M3#>^2VT9n2DLtIsO-K_D-#H z&y6^HvIvadk8>3Zt_g~FZXE+>TKm7EV38OIZr0cLE|uRH#<_I1b%Qom#`uJnDe^{O zIM*VhEsbz$ex&j(=oQNhE(8o6c(ULob1^%oDepWC)}v!H^&XsI{jEq4B)@ zT60c5mN}v@1Ot$B@!E~Jk<-nG6}3aSA8YEs~tV1+s5VvfiDttCFc5He&g*@ua+vS zPj#9A;i)n1VA={3q-78osNbZhl^2nV3n#ynfB(qF}58c@IuDn z!AQIb|B6WZBj<+;P=wto?h7RQJ1>uL6d~i5$ZCe|h0-7Gdq5=ZG|%$fkgX;AdI)6L z_MIYHZC~;w!gCz2M*1<7S}Lpc=lwJ*IoELclBVikF~IE&VD)L_b}+6K9yPL=x>BwB zBf`-32bn~6EP2`Dnd?vTzO1Fc+7)#|DR0g52NnM)n6@A?0nWl8sp(P)+}3(&&S8OTH& zg}fjmoH5y>m~+*-aH5QRAU+825;xi#3sLw!TQ-xl4E}Jp(V>QFg{@->jEd(QV}n7W z*KRLjVeVejTRqEflIMHtA2Ru5}(ZIkBg}|id*rd=aahoV+Ix5*grkJ3* z76}>oe`S$yCTQIEYwTk!wZ= ztnwTtbO%fmy1!d}-P$9n643=uGqxO(*$vMlW`j%wP{M$q6_=}}oUmN>p+XUK z>{4zd3&LVDMF!R{Q30n=VAU-wg2n) z9k0+4H$Z4$W}~_h9EeDLDoX}*F6J~P1E2$b@x@%z12nPefrx+!ba8 zvrsmfhDO?GizW;grUD@pIp7*rrEP?0b2i?{nGMOL4 z!>IP7=D#yv=BKs5eTCrb^pisO=Ll7WV1W+95om@awKq+*_3V|Z|Jm*5-Wwz?(+LN{ z*)VYAJagp-(DX4qE1@R z=jD^?BG3U5)NBRq%5F0mZpPq&EEoLW_E`LS0->z~RDwm4X#9@%T}>m&p#rn(YS`(^ zE9q!pSG&4xHgIJB4&25-rYd8%s8S(l7+}~tu$ziY>xs^%zreCuA=)W!CLX5>CaO*9 zg~~*?Z-#RW8fhy<2R7REBJUE>gvcobPEVryC}uwr#PCbIIoFAA$oks1#vyKVRRxd#A7 zsA?>n#amy>&}E%GQWgBjy9REBFXsRP1yz!ZPyPd`d&o$=zyc)wZ>ju)O8vy=Rm$FQ zlR?HOOI-&W&09C~a|*s6-?mT_-P-k-aHMTN#POPrJNBs%c9DtP!QiChh}<@K}~S4f!j zXGq8=W#?NpOZZ{taT3J;r4+nfbu)S1%cQm~H`r~ofi4!G&%502X$TrME3k&0?_1t? zk^at8)u~^`x9-U6E`linKsykJ<@H!XaCM7{k?$$??dyIAf&cfow#JI>9G9C?A~1lZ zv3g!Cj%7Iv7faQ9iCrpp%>)Mz4yc_nlmd^SP6HFN^#lLiq=LrnY852=xBIa( zHv+Kyk@93GE@!gBj2-dll-vJ!ZO#Bg1`tW7-lF5;24~kZ+@-6S1y&xR1qG8_DjNLB z*qis%3OyLHj9~beg)pMvNye1~9?w7IwLStnU<<10LL>_crtO;19Pi91!EefLG3CyV zP_YSlV#gTjZ>1lAWl*yy-@tlSG0{>5zW+52#S@$T*};tDk^n`3jkNZWiDdSO6{nRRM+!_)?~^(V}5NYp-#A3;JaxBqM3aoQc0z&|%>lb_E63%f^>67It!IDHg&^{;~Pp#AfaH z_rKN4q0w|eQeE(eBDB*pNVLcrJnOZHjAHt7RX9oI+G+VDNL0r-5m2l5?SHTg)X7v5 zNJ2}$eU%LQECt!;(;lT~%MZ+Ol=!1B{^OCg;*lSwpO_)jOc*o=d|w_GD0V!~efIZ% z2|ennbtkrT@G85j)L_W!xdXX!gGy0Qa9-~qp&pU7z|cgsa`@r0KKvJ|F6+cc@a;Qt zy;+9AIEHdjCMWV;S2QEZhpZ*#v*P{ozmw-fTZhw~8-xs_dJwz0s^cfdcl(@A#3hB- zE!1xeWS8MBP)fH_0k9TTt~bX3Nf0wf%%hn3r)0HZ9H9M+*smKw-1Fm?o7OQVnMy`D z!X@r$sfK*vCDJ0D#IYH#fqW&Z+{+b9LiW z^{Gn!CU<=oq%CHAN$q%1(AS}M zfHIQN{;=*O4IeC3Jld{aZzAq8{skT(b@3>H|2Kc<#>V7}u?Dpg$$kGB{ zmk~Mp2j3~+zwd=Jj8yBkpL3s7KVUs)P9Xwfeu?<`74ddHz$%0JXHNZax0uZ<7GWB( zuv`|dW{(uW%%yBICh>UxF0bjnTkuOZfFu8A`niPf0mdu*P~bTKc>26z();1GoYV5r ztMv4^B**n~+jS~i@bgq>>$(}JgZ$uttO5#z_T13+-lRC{J}QrA+#LF2BT%^ydDp9~ z=jX65d*`S#`zYq;Oz?|mkD@_sYl6Su;86OZ#Y9KAMx9*UJ68AS=v&^UI`X zjHw|S;fXIM^|A8%`D~`C|C+BS=U^zI6|2zzMq-LGtdSQ>yTlpMqPba6pu8TkwRGdp z7v#M#FYSi?u5dZntouF$MqTH9G^i@~7S9`Ujo@6YpSm#xbMm~lpoNV~3N#HcGZ)Z8 zu`?rOBUhHi@RqN1+sDd4*(EXu6ki~O_q*A(OBBG$e&EW;$Qa*gEt@_S3I_=)V#OT# zyC|A*KMw$OOq$Lc>$gqJbFzl|a@uOLboKUZT!OxVzw9MEita(6ItI5!jX3|gBT)P8 z_v(%U%}SnK%*>wuGK@Y<NfOqU#qL>_r|JarjMJ|j*olpit}}u!U0X& zCC^3!+*~dS)+QXmv7LssHa0B1HT2@zBT^Aoat$UT4kbB+)Jh22K zE&C69<3+Csv)(F}x_4r0{P%Jh*HGuah8A^qU|EB;kgwQ-rAknJ5e=)f8doja-LK@& zUBqpAA$PjunHLa$WKnt?)H!1(3b71nl4ilm97*sLSDI8I3bDWmS!2-pe=+W*pX1j6 zOoEsmIKO;vg-h2y(qNEi6I=KR{EbNM*MIg+^#vu|hxs<%Sn_9;yE$hLPbD$BP3>vz zG`sknc4LiV-AfR8lCPHi35nk*4lK$2Y*A6*Z(O{K!_Y57n6lhnZM0sh)VlE1xI^RN zRxXu{kdzWD#2l~3;1&!$2uMlF2kjO9tkSuAWe5f8ITtz1`XYM7JU%;x3JT=7 z2QyeywAZQ#<>nINlVSiNSE;O%mWX%}_;{>PrL~ zQJ_|F_%R8y03iS6I*@Z;*J+0aqlW$L`GdnW+!WW@#C1B3|NZjRy62z)ioR=UxO2wo zezJn!BP$WV_oSJ9%}O#5M%5eR$m#E7^}-5ahbat>{nnLTHp<_I+|A5OW*X#}$xI-mj?dDKTc< z#a=iQbyV~Ix=*F9ap6uf^0+bO+7(q`0ilAgA~*Kj>f#$lDfAy4^;W~yoPnRpAjep% z_x6d}&Xc^>Ol^4fBzk3#IbbR}p% zzV&rzEa1HKg{$vTI_&g(+M51b&^wIC^&RS}^K|cc^iX&SW4DOcV|)o&F&X&BSO8U9 zu!7S*`Rexq($VQw=gIbhtVZ6;{mhl0!}Zt)pLX-V4cFYnW8bltozmv+yNxTqt2euj zo1qPmFAY6?C<$Q9V6y0XG3hH(Hvt=1X_=MM&<8|U%P;pDK$8GL{q?(o0CH7Y@afkl ze|K_1Ixh9rj`M%KypWvJY78gcw@J#ZDrziwyfK$G6S9Rj6^~{) zd;NBEem{=)Q~2wR&*3M+uUX?rV45#jkXLQYeu!uoWU{mFi75c;keFIx;Pm9hnOOSk~QN5cLMl!OfGbP zVd-OTZ=FzL_M6EK%$;9^AtlZ6TAfQ5C%f%Nu0Fi6bJjG%>Zk)FOWf(AMrgdsaQJu3 z+|bY^o<`f>+K+T^as96n=pZdtzA%Q}hnu0bFOBT9?2-#yATUO=jh0 zgSE@xUQH{<7}pKH`XNltU0M=rZVM)B!}WJ)Ae6;;+eg>7%qP9jR4tCHQ_+AFV1wIjbh>nqQt3EKZEE(5*C zt*)<4Ld~Zf9FM~Xqdz_y6%~JsiDWg>aqN~l+Nsi~K>gXPSA7S`632Pj)A#9ajLDUrDHOyOuLhDby?0V%^*_FX{#nx3h zZ0}CHcg%$_OgSB|$SXpbBkjPFz3ho^v3SSjQ^SiBrT5!&oKAIE`GKMp;1y&ahg5Re zwhmZTO65J1V6SiP5PKIBd}GB>NCbmVMn;>{25h>jxFKdA5Obty%&nsGF4rSAiGg6bZyL~+AdGxY@JbVL|-DuD;$5hY zMiw0%ZQr>YmBZ`)qtXXENn`(6Z%)dN_t48NuS{<4xfe(&$lCJx>Q>HcOL40=lro{Z z5TXgPwpN%yq9c=9bjkC906dqdfMT^u5Hgg};S@Zj4V=0dy^g_w|6PGKaJH)rmY^x1 z?~Z3pcy^rkj?C2SZjr*rfL?bn713!eLD#C2QWn4Y-SA;QD9c+3F}u_Dj%nUy5+#7h zl!z_osq%jGi8y033z@dLkY1DF{pjST+wY&}To;jwO^%bJTnC76hf}WbjlCJUryETXvY#GS6Yhj}?Js^gWR=j)_B; zMrw4muE=qFKb7$_1-YDZ=x@X%{bX@dGN!B6FUCgE&H$ui5CBn9cMMl<(!bid={@^% z6$4U^N`3-j8DFqqCLh}bANNf5muO@s+v76H5ZYCpISN2QzKtP`8_u(BnvbJ`eQae} zRlTC=kH^lknkugz8cN->m4B(AJ@)jHl#0%jeAJK)lrNn2+A` z<2|W^Bv)d$_SP$4JpZw-R>?pb8d*B87W4k*6H!x2D@4-O^51@ z_sXCNc04%Oe2l;F@+hQiikb#e=giu=UM*LKGuQ2emS^iIdoJhtHu{yei5h$JXT8WK zWk?J}C<#n3<?oeJ(Xktwj3S5WiTwkZi*>_p z2RgcEld-T^z%;Pl%Cxu`QaOsIC{n+O{LI^?)4LITBY94q|Dj!3)>^%$bvx+JE3Xyh z|L;IcJ)fJwySuwisrsdUMI3?ezGjbCxi@jFyWJmi?Ph*EiYP}+3+H$|-eHrK0tW~N z+z+6_OyD3z#jDOUV+5G-FuWP>Y4LEZ^)UpI8FDEsL|Z%AIm4sVJmUMN*p1JD!Zn>D zaNzS*RL(q<*^4N~$HNz5m{1VUqb;9=ySH1lC0nLr$$O#rEje7v-9rAX6WwuDK9HuWARdtd+p;pHJ&B9en$+I3k4OJs3xLdPLCB&sXItP`zz(u75s&S!UUMV9IaO zl^{aTZW+z{F_NRb(Xr-a*XgFi@q`yJUsg&3}^ZsG;bm?}zF@@OH!S!7PAoTrL z4!ua07HmGhnRvYIwCt0`#?OVDc%YP$-J4LDO{Kb<$pvpvB4!grLfW+OTBE6JoTeR; zbXB7pW7F?WfrkeR068RS#_f4qI%||_8h+6EW^A#g-!+W?b%t?#CuquJEbUhV9V{GE zW}WN8X>-)DM?AFOK+M_*Y92vF!S$)Ee`m$%IsrDe;e^TEI+E^U;b;(jPL2Hb?W2B! zb;(BWMAsef60!TaBgny1Z%*R!;X1`Ur$(o_`oHT_ja^W1s|4b~%j5JrG3;|s{T6iP zN9xuJ%hy7V!RO(Z`_xOgmtuHMldnGL6_6d6-K?8p_ly|N^9c@M1ex@|1>FZTnvZ=p zavBqV9E3F1{nqmBI&XJrebx!t zd^72S^jvRK_fE|xy~8mV*6;B8tP4K%ZEE}F;LJ%IH(A85@9OM_&N)?b<=MqN9is3b< zt}Jpa;GWZ4&~ECZOn5ar5fP-zx;WvzzwpX|5-hh?>LNprD-g@<8(7jXJweDf+{yQv#pvlI8G5*nG9w`8FW&=NOKZ z`Wnr`*5ZMdM_sgrXc9wFCe?OgL33M`gKw5FqA1`s^=l5$vD<7rtEq810QTNnaf|ph zBqO6C{59xg4w>LmIal-qoS*%zoQx)$25>HnRL0bgPIrD1k};)TkoNfuNhHM5DP^cIM}RpD4#Vq{pq=kk2pgs?R0` zBDR8eR+iM62T8TgyiBT0*qpg$lGyR3L)~NTT4wd)LcANpKY7E0!TR8jq8eIcQ3`5Z zGGQ@GClljA<(m=dF&0WX+~r$Mhyh75>_f8Zo^3(WwNn-S1Y_#dV`>If|H~9iAZ=gJ zzq0|+@X^=rhM!g$6yNg!G=6I5suyoVBqE3Rcc-vvZ3Bk+LojfX(9pwO!l)vE+7FPQ z)N?NibskM79^O0HtvAJnSmrQ+&&dKOEy?#wR1>C*(eIE*pZ?E5BrX52QpYEOSUz@= z_!0$)naV;KB+Zl5S5ba&jRm!sI#ePFs6mp?Ra>uBI`%K(C~Qx{D3*CE8aYp=?DPsS zUj5%T9ZF$lE0&D%T^W6QpJMduK7s9vftvRByCjwVmm_xc@;F$-^++6B)q^O)^CB{-m?jOAxLMyl4B%GB#)nJjqFvW zI9HcTTDmH`7S(xa1`>Z*1TaXJzt0G_q9m|PE| zNP+&JQGv~dRr%|v=Y(y*H&&VuZtj9ik$GwMw(=+dbUrmHreiXRn#u%+ARzx{r}Rf& z-gDNI3|b`g%_gSFMYSO^n;g<&tyy+Nh}IP5|KkD_{@SU8o)RbbNZ)*?6}@^VL01;8 zP;$EVbtG{UxXWnaEk`Ccvf8z&SCkpQLYKypj)^QxEk?FsuJ!zj>x2_+V*o`G0-If& znW@Fj+3aYv<0buKC=N-JTLc^|_gknf>1_iOprK)M=^L@(75kva`gQ~`Gy=n9&_%&L z^cn6(apXW zn;;~LkQf7ViZTEPw0l6dj+e(#DH9a6^i$mx7xY|0P{G!|}P< zg)aiY#GkS?0e8T^!%eFEs}qvJKQDkXn5;M2aDP(BBv#gnG&e>(x+2kkaJ{886mmS$ zi)^6wI8L+CYGLDP9W)G(AatLo#oTl}0-=8A5zOF=Y(R?!NFmWU?!ye!z8v?>vYcaw zZ=4RXUmt>DEbT(&GLV{96PGM}S&sB^ zEt3nLHqoxr@bwCHI*-w(i7vR>Pa*v@Sv1G}X;GjFe4{)BAWFECnN&xR5)eiiv1HnB zWv|lmon`Ar65SB^tS)2g(FrRYtSv32QoF$(m%s-*ij!N@;icx6B#XWiCw4|xGKs{F zpiGHXOw%f{KpU#ZEDra}%rpj?Bo3X%jsr6vk0PQNav5W?rw?2bFOEc5)@Wu8avzM1 zJcb5;6gM>lOz!#+PHI5Xoxn>5jMW&H5`DtzH91pjZsPg(cPZ)b@NyVJQ6%OJgI>HH z%>XeGSbSlUp~R4FE_u<9%WNyyUc`J$K+RUX87A67iVlTI%pVlta{^3i=vmi^P5NOtzOG2A7 zTR&AhedU{(-LtC{tc`!m`6@M4J8Di!VJm_q31MPoO%}Wz{Xo9`m9YjJ>U*jJ>G|;h zZP*{iWRajep>}lss5*jDvBjIq#%cM=r4mKH^)l(+bsQ=ftKZ4iHckwI3YmXI^5> z9VY<8xpyl=_o*Q}O0x;~B?5%h7eF$B7J zn&4Tap{&jD>^eY>BlUuJtXnsPXYN;v z?$z`S4~!K|NbXc#DqKK5I6v!Go$`zIZm&AqPh|;p)O<|@TCf5UxiXjT;*h*i(GGb* zn5*Ymr#}a-pXGTtVF-#i8S8ZtXkYQsD8tbZS@p%Da*`<~3YQ;eU>H5^p=6LV=+I)U zxYT&sJXEe0)Z(m#T;v&S+%d?1{pvcTg8>$>-H-_&*H$L{P}E8Or*#m~?jh_OXyYD% zheimJggx?CbsafoE*HM@K8110LBLWxy*B)Ez&7lMhOk+C5ZQe_YuzCr&E8>>Bd#K- zUu*AQ;;Zx_!Q8Vb!g=)auv%-ft*@^S_rmP-B6K^Q3-o%>R)4&m>Vhi)^Ee;>JWv1n zL`fHL2O3Pi@8%QD8!&F1Nw+^AE3))3cLwI#gveYKA3?a?BFf9q%;5y_m!M(GyNo7$XsQ3$* z#x9Z+`={*I;{8Sh$Y?=jJg<;>h*nnOh|eP!@_diW#_pFLoJASR%4*8u1tzwE`Pe*iN@hJPc+?vQG|PJPwqV&4V< zwAYU~S0{UU z{D33DZvGZmRdbdybqv!}Swnt%+o8N&t;8J$_(eXj}0% zWSr{wvSNW(7Y8dmblxl*8Mv`>DQTIqU~P`rOlX$k0h?fXIaCOX5G|I_qUiv` zSzOV1!i=Q7u-{La<=k#;39t~O0j_Lg#R_OsCGgT}MUeT^zRmD}0;O9xdZ=@0GGqx# z5{P-|*wP@xvCCIT5`HYI`UK65r_u0JRh8kA;&BgIStsU$~><+CJC zFegnjhzq7wZx#y+%&uLeEQQ9MPhHu+vMf zw1($u!CDJc{uqF8HV|Lx>c1|NzT%s~U9>+u!ISfp&+Nt${{zIZuh&v;hyV4_e~?I7 z+aI8-byd^q`|DD-eqvF5M--QWz>7&Utvrc5Un#zXTcT;R-#VukHJ?||3PKByuHKuO z7ti!z!-4T0$!slUzzWrI6C*(fayC_tVf2=Em+WVN*OTL3Y^Cpy1dwzL zQAX3C!lQ=82vXrCN7CPDb zw5|U6m1vH2RFqki(y3p>vcThdFQEN&w6OaqtD4BTqHv+dm`qInUF+ucH6_}IK3)RJ zL|WQ|Sn9#AF|#iduIyBP^ITR%&MtFeWuwvcJGmBo5^XhHDOpHfmT1u3E-HDEDB4^K zeeB@wnFA10Zq5U(HrcB0BA|6>BPT##jUN{gQ9PtBEn#-#DuS^jWv`rs8!?N-*;+lzO58KE(dmi=akGNWa>7WO zk`(r*;aP?(dXVJEJ#U%mnQ2pjHp|oKYguSMZ(-C93nbM?fM4V;5_2!^_qze@5jjRF zI8S3>zxK2(6JXiSEsS;%ZxZQi+I zLc*Id9bE>cjHRfP9Rs77CLl({UPGIHmVESa>$UqHL2xS^{34iWHeaY(0KZhD#@S2`k)<>gFDDzkN_MfYT0iM6%sC*~4l zdTXd!g-hxyQ$@@PL_!718f7Uj?Paogqk!R_Uwv{I9M=2IV>FBL$8)6vXDgaiT&&Y< zSHOn{FA3?>6w9>{*yx29Chqcp7YQq=mXi28p+mcljJqn}B*g<04ISME;Hbvv(v#4f zQdu!+s!${pcp;KmS*XfR-9$<0g#F)=va+Z~rehs!yQq5A$zmfVT9#l-HF!)Bd?_*!jK7CKNO3EFb}u1&*D* zfzjPYl{NHDIT$u45WMThZ)s@8_2LLC$QD=HqeIDA!_5zp2$H4v??tfVGkguxY^2|u zDSqlF3V|Wg&?GI@VW4_#DM=fBkwZYCL$6HyMuZHWp08>*yQB{N`BMfu-%9I%j2e;M za*TZ=9}EsQBC!~dgqSaU8JKW(hXso+q?E;yK^cWBjK>wmR#37B3maxb&9PuJtHusd zlo&=TNwRqr>UHjc;zzHvcJ%6vJJo*m`|N5rOzQ%sfmnaSKkkZ6re;YgNr4vv56V49m2%wBLNM z!phpUOFF4*f=ZQH^wLUGXsfRhw=;c9Y~X`02N5AMHct^9=$O34Qx@@QLYh? zH|z0Uhqwjla3vF=IojfAl#L`WL82zdse5_gA(kvpLQ$v*g%q{n=*g|MQ?@bCD$TPq z!bF{vD>4Nbq$abN7(Qa$865ByWkc1;QgVsZe?=|u9~`{$+m9rn6H|7~CP{Iilm6_^ zhU8hH2Wg+v{g9%GWJ5*quw*N+YlCBl1fLE`5em#;H%j2;OOl@{+WP^d=pk!Nq|MY3 zPm}iU$;JhVILwkSdcadCOA!Z`mmkj93PaxYHLMejKp>*Pi4<@V zD&w?7Fc#_Ce1U7$tx>%5$TZ?WulX~-}R&2^UDDI;APF?gmi&4vDi zQt|j?coBFxh=imt60>sE1Yr{WbH*ev{yas#O^;Fxvv5TR zq^$m!2O-`cd-(51u6L^9W&t2u7&FN7@&0*8Zh#ymmhqgAn z(LbvNSv!ZsoMJP)xYO37sB#865PsA+;bT|bn0k~7QNiGG7HL*PL(jml=`>F7yWm-) zKbMu8+r6J8A9@?{c8wc)<7XwX^%h;B)(2o#ImZr0mJXGk&1v7Iuw;Ux(&nYPVlBu{IA3pr?Rin9#ojpuA<7EI zmzR3T&@2PyJNn{xR%P$Kw55B4JdBO0#Xg6<%n>|z`MFyyw8R?hESG zJd6?5_xg{Qr$wCax!k_lpC+xU9M}T9^oLJdZe($&-Dv>6lIF5*|lu z^D^2{3^fUBBJy3+d}eXh_Q$VRn!e;o^U+`81cQiug{x)Pk@01$!>v?VCi3tm9O1YU zq>!BEQIfNe_B<2nk93k zOwXV4;+ns*8s@|ri0b`RNNZHH$;;FYRC&|9t~q7I8Zz;cl2TBeW^Cc~%ErY<_78e! zq+s>W^rkLh=Z#22nh3GhAzAS1K>}mwi|LH?(k}du$8!elOu6Bb|4M*5$Nzc1rRc_a0m*~_i+zw7_{_egB#_X3mc zPJFt<_sr%UR_(3&d39u)n>@Hi;7;X)**#N12=lQ)GO*}_ae}tw??ya zR32>`)eK+v`Fx4z{cr>+@!n@=r&U46^o#|j@%jB2TLuLqWAi!{MiGv=Y%MOBQcHY> z=MTp^Ht=m|iG_XFE{CgpJVdEv^D=V!Onm*$iqQf|W$8Tk*YA9!)b1B1QBpb?|A(e; z43D#Y;@xvBNG9B{ZkHLd+7KmpIYDQenP9!0kf zm!Fcdx%fapgUK(&nZq_YzUefLq`zpLw8nb zmp1oh@jr1rKl>Vg6ZsAa`ZosB#87hln_`5@J=kAJ3QgOh0FiIbQ6fn?vQD=Srw zNUhso`*r~?!?;yZPp2NBcvP=CrNP?r$M6U8KSnD41|*%tA;d&8k5Y*qh$RyCf+Vz* z$Uu4CsBGV*2j}ge=@#epW8sur#Jc?>=QcemkIKQD#S$WUH*v0i-+4u&k6VvU7Szu}F1cD?ft(mMohr$Pg7V zdFu=BBYIU8DYz4N?~zs**<_L!nvJ4T?2swtBjTatS^AAbc2@Ygndd{$>xn5YBk!_< zqTW((fyq2*_Q_i_O%h0{v=kU9*hgf4qIPJr&#!20W`=IfHhtk*yMedhz2itn z^Wx@0hZEWL zh^luGD8_FfGJ^ZM`iFl;roAKNP@_pb8#e!Z|j(>{9l{1 z<*4WE2W3%}c~K9ViW%^@Q$XU#*pf`G9swCV1r$Pf?lceORKH4tb@XlY4y;J&Y+<;?27vWDkzsFS}`(_No zhCr1^JMbC79Q>RwE&yVKUmC){E|s*&L4PlKq}P2 zonaFjVw1izBc<8M>AX?!@%7LHTB@Cj`YQrg#b>H1&wXNc_rYKX(QlV&; zp#)Esn%6zmzD<^XmjU97t_V=m{4qYA@6gsnlcUYav$ZzYl}d-#t7Lhv9c3xf}qOu#JWUb7hQ?B7?EYD%_T-oEq5vsr(tM~3e(}#&whII-X&GHb9qhe zed+x^=I*(GjAJAnEi@&Owta(a)?>t$YW6JABgEgg37Bg_S)U}@9Kvv$v@>m3J-pda zz21|if@$VHmKr8P2#LnynS=5tagG<0m3tL8G2?+Zvgj-qW?Jy|sbLI>IQd_4I=rVR zF!1bTj!rMWlk!X&dvEgg+^wZ*%*&P0U*Hw8W@rYp;X1yZSITwU3w(HojPOrRez@wH z-)UsIt=??eSa;n~Wh>02s}dI9OaEc-&}vwavUfl3+?^~x{Kp-+mo==j3sKgEAAUW! zF!8!mZry%N^FHhR1uItjYGMRBK-}KHg*87hzD*7qM*l?hs5NwKvSkXX5(`Mg(e)#x z%UWEuF4)VJ-zOG)ehS1QuHw0wBmb81Z_@-$sx_W0VhN%>#mLYlbt4{S0lJ|@DdS=P`)%eg`elcP;sf+U3aRy$i=`353NiZMX3T418o7RI6!HV z2VzjUn1hV)n|2#91@5?D7%>DC$HQP=Nv(=Ay`>Tp#$m_im)_=%8KFMG(pHhOYJC{+ z>BMvO#hM151wz6C;eSPp{I<}zYVql&|2n(&+`2~sUZiH^$r5FNm_{9rTlL6=1n<2G z9KWP(2hJ}sT3TWv2648rJ2dwQx;?)av`f0mxJe2g8z$r;`IeCag34#ik-GVFiT1d4 zRFxX3bPWR+L7Qr73Z3Jbs+>7&a*3kKgX+vRRnEM^*N1lPfmPbh{Y2+|u4_0wI5&H! zUV7K=6c_)c(YYID4oaV#1s6%VQD<5L0TY|c*JDzArefwOOhg34-qM@;OL;)z=rEh9 zOy=XNDaHk|n$2Q^!B%5jEBp3rMQLJ%;aSerRm_lhvW?(s3ogLT{w+28A^oPqcrF7Z zIckPd|Qal={_G*vCp{-`Y zWf}HaAci7d?Du2Sw5YAQIi*-ITo%k{_`A+mUJ=Vhiwc#|*LFGl-*f+;3t$naJkJpq zEIi{IjgoH~+y&6n>mB;`ADi>~KatmeIn_WO_NrTlP~Ks3Gsgcb4G{FFggjtveY*4h zq~|R-ix~@c=?fb0v2N~HH!aoVH7~ieeS>}pyyA0t&IahUE~zkSpFQ}tuW~PXyUVn> zIE$u!YTMVzy=Caw*ZE7Z?S92~&u~*vY<&}uzG!mpWu|R^aJuWU-m^KJESfobFhYB1 zLkH7pnDQ#a7N=(seGTuUsGwT}Nm3_kWq4tI=g1_+__d+}2A{765t^;Zhv-+pEZR)9 z@pX+sNt!Aj_w7~vv!YIac-ww(R&^*+S7L;1jMXL`va>l*-`N5+&2V#*4i%rTvg9g6 z5-VxKqehmu(%|_yx6=9?sx?tq^fJ(DPV&S=?1PUtJUAkLks_eOD{ZxENI>8yED$F> z%&Sbb0rkH(Ed1Ra>{uA*IJ8TQf=Q9IRyODWGq6h#Eh1GI%`A-A8n@7YfT5tdrdhIN zNYMkXwZG5pwxuw3=L1Q_M?A@?@9*B-anZTgGsAP~GPBF7I%xCNTv82(HDcTy%S_7+ zFUs!OWN3M3Hr|avhf^DV5)0b2U*TeN(2QCi;Qx)2@Jc5@Wri$QTF+3DkXkml++sH@ z>^`@%O!a*xXsaWC*i$6SJDb@H_#5z@_5mp~=&7Hc)7yly$LQ_U#su4xsbbw-(N>W& z-ym?(4W&sKKL>Ny%Bv0S#A{0^@3RtVJH`G|uYL%V95T6W8+cN&wX0!McM08r-_s=! zTI+V2w_m+wrwvN<4?&)@gOjl7?`6ThM9IjS&?>?VUvssqEHW3q8omh=-qv<%qR)XbdZ>!|$|vWJ&%c(@m~|T_CM4a=Dm>Vb$*-Q z{FtMw!=uly^XH?o*u$5v_kO@XaDh(j3Wl{G#bJo>WVVQLYoIS=(Dx|a=V=k;J*!`r zMV?!C&;J;A!$R8#<+`zl{W4OZB#@qx1CCE0mXYhVrHb$Bc#uem*1YE|n2k@iS{e3k71#nE4>{_zRnY=NJVh&ghYJ+W<|3jp4KBlE?&v`nH>lkIRVI zH>Msg+oIdU@a@h4yN?Na2d&JeZ4WrST6XK*Zq?XK3WigStlkkL0zZOE0T1nhA1-#@ zgz<4>Ggco*&qr>;s$0y7;I29;4xel=?QI;e9mJ_tK;II<^HFL#btX{1#Y%{F`1|h1 z!A}9ZC);oLtuwxEWw~bG-#FhlxKE0TkTMJjh(zOxkjVLtTKCM9WnYAokue_Dik`s4 z4jwTq1`~wWb&6Ft;P^c8wP(%B zXljIKeRY^8O+gb6lK{dE#Bo%@Q7MEKiYp1m6sgBJsP!@cBRJsXHF-BF6TcCe-!i#z zs<})1NkBp|B0w0(oFf~h0AzmW_{F&xT{DC)k-oAtJkxLYz=LZsE_y4&uZ=!T%_PaX z7O{yEG>M@Ymx6xYRW&ODSK^fm@d=wtBB!Pok7%-%6;D%yV{>^;RPq`lze3fGBs7Qd zxbT9vW5|?xUu$=cex+ffa42agI*+e)9CnHEGzscn>_VB14-`^3L|GVb2n4tHkTkpV zM1QS>W&ho73BEl(Y#f2Un)^pPAvrnCI_UMzY4y!tM)V1H*P(5j?5>&n4j zasxq00~{s?g9v93QTt~&cv9CG`jmeZ2m$y_46nlAU9p;z5_@OlxN)=KXc%Z91DP6g zzwLNFeDk^>3!2{TIefX{=bwzj)e9B}cV=%62wi#Q2N23M-M}T|yZ?3bw%Mr=mLvDM z_2a1gA5Mz(A7iWwa!^1fS7(By9C-Ko`}@C>w%{h8HNxQYQu>!)!JU5|Bc((NOqoK*Nz+0o@VU9CdJ*t`3uDB-Pu{BJ=~yr2ya$)@MSrlO)0f=rR!&~FC8 z4y}}8^~KlBKILc!2hI!~1IaKO{}TRs1UM4yEV`dk7uSqr5cp3}`MJV0mpGeJ71s!! zBmbW>>d4^knqLQlg|h?)obiu$fWus%&&*e1aHZ6Q0_E$# zMhs8pbvxVe$V+6rht8>adq(A9mRGb&!1i5?%KELqVEu^otX^wg{=8D_uma3dyv7>c z=iw0^il3!MLQ`gQapmFv`1w@Vzqi`oXL9S5uay{`JS8&0+~p?l-L9zW?{5;M*`s8g z+0dEynBI z$NEew6Ncr@EsL)B>>7>ZKS*X#s8Kxi^YXxj9FK%Fr&<^}WR(!5$iW&Uc35J#)9t># zST^>qi5eg};hrPbK4bm9t%!dRs&-q2?Q$s@A3aP0zPdV z|KE&)Ol>o0aKCl;njIkaQs`~^Sa9>{aqOgysPnHHR;4a1KB9!TUtnBoDWSO4i#g|i zpMgfnZ)Fe%SmNKN8pV;`#6XrLp`fhJfkONz4!A(TUL2%G5kAz`H^e{w#DF(%WxKiYEK6{^)F z^`R9W&>ZG|XPLxR#H?s6jQgZs=|G)8{k*RsmgfO zet=r~I1>M8REl`Ibs6tcD?{cx*ySGI@6}{ydCmtdY<%Ql&y3!5^3|jiTpHZ(KuM)k z{=0jQGPxnEEOcF}?zY)z`%HG?)5JSh`fy<)D(x15E%*r!dLsFpW$lzDXcLkBVd(m1 zX)q-R?x`s4J0Zg_O!E$zS$q{O_VNxKx8>Dy!AsjNp3M>o^WvHHB{bC3L@JzOI&LbG zubjwSh<)dqWx0P>VC1>Ledd2K!(=b6$Bm`h4wq$QK!gQ>Hd>DTlJ)j}0nzhIZ%7(T zc9$RY_&?WywWiwk<4RFd7$O{A6#P;}{!doil=s<@{OvS4k0fw!z3!##@=Z#l{J*bU z&bRw%YZy<#$wbcVu)N0Fy8EpyB9DSGyo1B;{uTM4nGq=|zvCZ^c?L0Tv%Z10FiI zNiB`i%~TR69X8M@Im)cZhuYe>rv=>cWQ%^gKFrxY%xT2fNjB%OXAtQf&IFWaN$PG-99OO^}HqXXyN?1+W9b6^++kzbf^U$oU zsNdvS>$VFrjG08EO`o#L_>Ks)@@Ng8-qa}v*rG4?_ilHmZY+yETO5bAFex^5Cd{K< zkpJ~D;dH)(Ez3JBfD_ZVt;2t3Rk!ZsfzuQ0u&L19@uH*BiPI)k#y{2JuF$mZpG6)7 zy){@(RvZNlFbZ&8UnPV(K~Q5-(k}OodfKSt9t@mZhz>8ca^Nia?$SNVJ)EJO3t5qy zQ>2i#;?TRRwtXGB8Wyv7n1V?_&*F-j{RNab2dygYQ(2_l&1}D93KyU_*p%W62olQM z98;uhP2p&IaVud^V^tfBb6IJ{{a%JwQ=*CToK;x09SgNXH)K_w8=ZQWDi{PnU&j8m z(Pn~7md=V?CptXF&Ln5><k;i zHYJ4JU6&Q-1j-S>Mpt`wzRq;xI@sKkBq--&SNc}>sRq(3-M;fFZI|lsK=bJlH`SAh z4i(3ku9Rn-Zmn7F*HdfflnL|>%%%*pHwtgnwXGkFxrQ&hqNouhtHwd&zTCt8`SS|@HVk8)gpO4=U8c*45?MOy0ytIVFpnIHTnMeZ-T7)F6HayFX zS)Kx79zx?=Jowh_&%?5!*GUsRn$?8ElCsial}U?!qaZ8TxmLb&eibRcGrAG|1sfIu zT*p~kKO9rS2<3W?K|$UB$;~`3J#WZG9~6G6v%gf#pTEty|C2WLya?|5i4g$%-HHQk zR&*NoOxH^1n~%fV_2L!Jjfl7gz%f|&!WY*&mxjJ3w$-Fd*Ie{#!Lg~$|N2$R%vIdn z%dUT7{-4NfW%c*}<=qH-W^5&^jLhYzAU4+17f@2d!Nc{Hz+vNJ+bkqmFR0V}o&W6p z<@1wZ%s5BLdU<|1H3pq{Tm&#`B>f#}7K@YQJy_4GSC`d=tI()# zk5AlUq6FP{{Vu;dlb66j(fpO%ic}I# zi-A*gwn{P$(!D^b#Br1*BE`MGPekYgz3M_lWqv)&hq z=Hx@b`Fga5r(F)#syu9oO2YdpJ?|#g0SGBQg!@|#QOgd%ocPn&U0_cfK{{3BbS`Id z+LNJD+c+YO z5Y#$w^c*Jj{F$BGPFOp@=>yFA)#)#@Qb+m4+e4nHu1dj2f?FJ*zsaJ@BsvonJUkQl zn7eW1JFz~K|Mo0k%9J=Bj%AG8yQtujx%$_p7Mk(ZJXNdv^jY>Mr-FKdCHsq*(M?!M z7Ih9sr7qz2&twiOq>%GvqM|B+{C>x*S&<$}grAJo;=)0F5^MvIr2lH}}a%9J3L{bU#APz5`zv}wJ6fMAb}d@ z+RL&Ods6ZCLGTa`T5Zhxput^GCMTG7tc!@4FX*8oHAwg zH@=jY>rmq(MFUh4zbUYVF{RrPq1}tHxuxC}9{IX*D}5(ZWF3*4Jqat{D~{d&1^~?4 z)Hl^hyQq0bb?upF)O3r%|1uf6y@-sP^VQcvPqvng(v)48-6R0*iyHzKO>(h zJ`|$e2qe&dX;EF3gWSN{Wi$hNdyH;4m&*?LA6$dL9csIvy*WO!dM*?4*gZ)m9Nz3I7p z`1(>59OSg#a&Mw*U~9V^gr( zN(s0j1g#EZmQ?xcPGK z9>n{vj0*njrzBO`Ou1!sR=A`^%m9*ib_OK1^S2NYEiDuR=*(ww9#(4%|E!0d5U1Ec z=d?jLtL@eMT($T7m>0a&dM}Y9CF_n#<&x$r4sGT2bP*0z;gS^f1jfoyYLaK3GJd+5 z7>oS6XcWy2Zl`A$ibh-m1g&K6slUV<<9c{`;h}p-;{!4a$OCJp=NR!(qd;%XE1%sjNYD7&S0MWnTz z(DB)d4&kL^*a>>b(X+0m5kW#S+5*Hfeomiu4#_rdxS~uM8ES{#*TUZl+|`aIzyrRS zJ5qvWbWiXkC>g*d+H;Ee@HJ|bbhu0qB|o$@jgV}WGUoAdk!i)Ud5BVJQIX~P{h6|| zvUb{kkJJ|o`4SCn?f>2k9CejaqBb-csF2O3Z{`?Zb`HgsrzOx{cS;l+*W26MlTVjt zXJ!BZi#fcAE;U_U`sl+j4xjSw{q>8#+gNEm*Dss7M0`l*YBy}|Ka(|DdByOMFZB;H zN~g(8IkiG@z8;A8_JRk%>D9D~d_Z_d=dA~2Q1hqNesCcEgvExpXURfIhLNC+k}+Ef zG?aIUBb2sL$%>UzGSwfIZ5Ia!U}RD~%2uvr%2S-7(^X8N#8E?cpcDTj@;R7cYB#>Q z@=fvB9BZ0Tsu;HKt(h3mD}sX8f@T`AizPY9!lyo@pn3JBOEWuG(`1(e&CMy{)h#%B zn&}!aG^yK<f&oPbbxq%}mo46J78M1FH^O-)Tj4Rom5sBLcX0T|Z1Ni}NK zSY55;2=gDPnU2QbMjR^EjD9s{|E)J@os%JmCPB0STV#;z!v+kGFgE=+7I>Lfu-s$& zxBSp%Q|M*u8~LZjU{+7HFxTq&D(V@AO0fi$pv%O?iM`z<9ED3~%lrSw^c>D{E% z{vGehQuU@;oOvMy5Z-b`Z+rSVs9WeedceO7?`{0Y?vth6my~lyZsL=_o(#9CI(aVx z^wEqN0>?c;19_$BEJM_;j=mIy%CbUWoI2N$YUUZJp_&Q+&R-P65)P5 zm5j_j`Y_?AA$v~BXRj2At5Y5cRPP>n6#N0DDb7fHY2>eSq>@o;WySQfX>9X2A}bD* zuRJ{#BG71&5JxH1y6ZOAH!Nd;e3z$kj5m#Qmj=K?TohrnwtDFJ`Q?Ag$0xMc>|MoM zIoza$;sK>WtkNtH$-Qv z@{P|mal@<)iA8(PGE$}gOzuRyA|ji1-{p(p2a;D(g@vi@oypFxtuE^yAe8}{VK?=hj!<*P@bp{N1?7|*8KHd z?1x1*PpIo|M?xk()5C4QK~)+Z-NQTZ(Y;Y~hzL0)hqxATQyG8+e>M*BLDKt^?q^&$ zac1;cA~UdzOmRI8*hs8UHV_%#z*?Ip?KzcWq2TB86+7`C=fVR9$%nGJ5l{{?(y6_w zV?T$6tip;a>FB)sp?jM?Ihs8pQ!HvIZmbyGev!nI3lV;!;vl?(R+htJ@&_pSE6}ZvMMQ zk>BG7|LwOGdtHrpR($hcmQ^5)rTD;%XPc9-msR8Max@>S==5{`IknyC_3F@(12Nyj8x#ooi$3-j4bMHKFQQ4deL#F|tI zFb^u2b+#>=K7}Ie3+{0wa&yS!aY>X9$)I7vr<}0CD*<}#lHlOH&Nd{(fo#j~EuBC8 znJGYR9?Cp-@`mlG3z%PB?VCW1BcW748B%-oOgBOYu(@ZWvgnu57is|h(BdRLjw&tb zlYQiBC^#wl5EHGw^by`&qKuku`E5j-@y{Y(6 zrB%AN@ceht=nH=3ePfox8NAk=KCbH0_(B<9sW(GI2e7V&J8kftCR2;tWqT`-gGR-m$QBP=g#(xBi{`xrQug!kfb7tV<{{1ea!*5tqj?mAR+31ZnHdU9gcF$#CzDZf9<3}F%Y-Mb)8zqoP_<8` zl9W0Nr7*#Np%p;K7vXd>qWa=I*Z0(8iTz&lcMeePr5vG9GaRFuhp;wpCZVeDJ~ibh zJw{06>EFj9DtYeQ9ty`wxqMmin$)VNXaMXk&Q$V=jwr)-_y!Xf{rdZ_SOaxh(I;0& zfnH>vmIpwSf?Bg!nO3D+W0H1>v$(hzZRKXSm}teN59>j6(sjl}0#U&;!hm>fiKfz0 z83P2=e$k`>cL}12@{=zn`Gm&ZznoQ}!4C=1YD<0d>`C}p+Nm-}|XZ)Zvj zz~Obe;$AvUK_^B|WXaI%`sFp4wcb;bh+9^EMu}(*Pm13-TRC3c4QALEj2UGSLqjqB zksx*=O|Mwd;#NoE%Hx`hKq)sVF7j8F|3J*)jbbPO+h=V;4-d|alrTOHSym%TQ$M6^ zdO&Y?N7Bf^64ZE8_i{W6C7e{mjiu{i(VY}ww&Gb?Na)Wn1@EsMYdx- zYJGM^=Z6GsGMh{nwAyjNLv~75m1&<^N5^rd37S zruXgOv-hIDZQnIrhAg>3AT}U02``Km7eG~|_ax=Yr-cltf?Cj7Avziz_rz$qfycbg zM?BAWRy2s$BhnP;#y5n{kIl3Y)eMD@CECW}v7Pwu=wT4{3N^R~Mh=w7u z!KL(zc7;JzKN78)*71xuWqM_8tJ{261|V0a0c3(Gv>gdgE0&}@yWyZq$~ikbS4e>( z`r>JF(fiH51VNwWfBcdU891!%db_%-t2KSgZUz%Zw8qR+@!oh;isc-eYD}_M9B`MD z0d%Sk6rB(N!nK4KnzzCqR=y~94x$vSu~V<}n>@UaO^Q{S-Qt#-)ST5J;dU{O)yRQYI!`q!%rXIGVO*OFE>l z{#({tNW-2++$a}<-Z&pmKXzygxH)QTbTFg<5c+wnP4mLYg2C|Jw}f)yq-aUo;uySG zxlbM~V6*+T8b>6+O!I=W^t=sK80Mx~RK(JmATZ2`58-re`SNC(8(`J`Sga}7WSrwN z=tQGKRd3<;j+1^r>!c!c zAS<7;UozG^7C3=KybSHaI)i|dm`DWG;6|*ehT9IGxp*v+vZ4Xig>M`aduZ>H4MpRv zl;3@y;^tQWMB3!4CB39-`xC?ROMl+Ew4Npoh{}4JR0T_)yYj<~Kf8!-{miyM7T!71 zp$>~f6d5w^wk(mTf!@8ave0@BAK(Xy)Sn};8N3Y@Qj~auGENdzkq6Czv;o~<6MPe+ zNy(*6!_c(XP#?oS7u0vWUBwluf{iagSi&7yNP95Trxe#4kxqoI8Lh>X#!|;n#lUQf z46ae59j~f}Dj_N`f+H2^=i?MYy=dh_;d-e^;I+(!CX9@cTS2m|MG; zwMe=&{&>u;Aio3d!GSkdAfb%HbxG`*MA*A_JKQR>I^y|w@F^DJY6DK{`t=4y8cyQW zda9w;Vg*oZwcN!eha!!14GEu&?k(AL%vC_lA@t??X&Yr#vS6xOD#G}E4o;#s4#Ref&0h*W2 z?b+F+QL8YDKT}ri9UX#R-qprEE{9V&q@<*vmUGPg=JuE zW(9=Ayr+|$^c1+SBcQ{eg*K^y$FO@2=GQKQ^HYDmz9Jg#^XiRoAc=tQY%NQSdqkq2ImPCkf&NfeTr%!zIP{(<7tRDJkvU7O|)fxx;O|vyxUE5F7CjeN&`3 ztlQ#qetsqW%2bfb1zRp+u8$04;dbr60m%8ccT^cVVn$h8Td&Pqt%43;^Q)^j^elY}Ry05w#>=b>wP)G5QYx(ld#m($myDb}S`Ml9Y5^h)ij6eyBwv zs*4Np#N1xh&>+M0blY6tmZBnVh!SQ630J_MEC04RM9Lv3a&q;55r1=& z_Ostx7{zsi+~sBB-?Q@MU#RJErtxt;;_vdpjO9kmb-+5ntkYR<-85|?xg5foS}WGk zQQGFQFGL&ygyKltByuk8xwUoXVZo=2+pMpxd7W;ouC0;0=Y}p#RI4fHxE;vT=cTHY zAZ+VVIXb5r*8=(%EL^{7MzMr4XAWZwfC(~3D7 z`*qGiqd^KE5onnQW;XFZ{*qiTx*5esrvd`RU0{0hf%Hwc#z>9=0WYMXrwf&5)JS;@ z6xRd-k%G&wR?2(YEMrsWl-<&dkDp&ds3Z*wnY7%j4#>D{RWl3fvh)MsZdpvYdZ@WXfb`C)JoL_X|jEPcok;4 z$3aC@D$(rlI=gP>udd`8xwubtC&Zz^U{pnxNRLikLc_+!w-AJkczJ&;pgi*ZridAG zb#s5()OW)}^+-p-weEe&6M8h|5k8MC{<(b1Z2r2Q`DS$<0K#(ws3|24;U4fxu~>2Z zaG^;e7%T)BVP7jp6EB^aS&2t;jTaMU`@)NybqsqkLqmI_+&h3-!4GwwNaR7ElzMO} zl)z|nVnm=Km5OGcq&>tYBMT#GF7~`$z+|XvzRZY@iQZc9*}R$K98upAFl$|*iKndv z(ul-f=|}yxI5ARdNMp?fmL@`venOf)4T}06n2_-7gtrv&O=Nr)pv{96&Nk!n(+Oj z5u4_pDNhblmkcZw{P&Nvyleee>I+t#wh+_5nMcxbNR7`cZRAWcP|&H+3tR9F!P_F3 z5+f-vBG!uo$0B63rNI>*?LyySGu$Bq@NFlo$g-VYFkv#*sRg(X=_yudq0LG~^7(E3 z(qUWhHty2k11f~JfCs91DHu+gW)%vkuqc5V(TG$eSi;J=I!hc3ax@-ec3>FY*71zd z>Q{s1aNs5R@Tc{bJJr}XAct>WMmB}OKrtimIr_iq9s6sK8t>1+NdW%8fIHec=gc4N zXSSQ%3Z$tNADnMllb)7zCpK_f8qJM$8ULl7xP8Wtk-AAlg`Zzte6n#oi9cHxneNz$ zVICVFBNVO&Nd6yLI0#M9Jr;Q-aj+EwNBSr{Hg-zG z-dy%5695qbL)^E~Y}9}Xa61EOVSvbSxQb@LCV|q@Z72kzjhv|L)(rJ@YCyU?c?NMl zxnle>4KjEd91}AowhV-j>uWC9QX=|nwH+MGnpp*XKt_~;`M76>b8YiIRR=w;J5`dJ z!E?|%Y_E$gQp6w-qB%7g{ogweePuBruE7Syu6;Stoi_~q2F39^ez*a-@|X!n^V-0q zvxd6Q_<-b5nj|4qC2^&5ET%Q-gf7WovW6J}o#Ic)B_k??k;523^X>1VK@w~p*U`e*S)l$>mM&>A#6PwlAC&99Sv*+3Sa#Cs(O641>nK$0BxePt z$t~jn3lZ2oI*##!oFJRQ^}}PQ=D>4z{rW#{S)!!xGup|i3-E~msXBB(Jjb}o`1YH? z5bTR@-HyvA{qYJl?I&2Vx?EfnlAy;5tA4CrqHrKAPm(xd<8wIHY#z;%NCpy6Bq`}B zhWtT+vjX7Tz_yxF)y%B*>N$!`-`sQ``c`<1J;E_fJaw0el;Bh3Ym64#)<{G|DEx51 zC{N`rPF&6M7#lz2&h=^+V~lb^8K-lE&RM}*AvbqJC+vvhcopD66iUW{5|jpNO4TAY zp71Q@c57N81fK9A#MMaRnBANTjC3IpvS7q=ymr}l2Dsc@)c#Ruuf547zken;`aD>l z&qh(4V!@h9Shf8h0`V$=GmZ2cSn{0vO#bz`b$K31_w_1!I|q8T|7r8$wHgMm_Nz-` zE~g4ch!iST+6WrO7Xq`sDmXfx%#|ok=lGuE>l%IDxcoho>BRTE;jV~!S^8ZR28CE- zq6~r7dx>mXz92MOedK@xaO+#faoWJ#0;VERdj~ol4{Kq=y_uLOXj$@T1TS62w0~}f z3LQWn8)=B(3j9=aX^zg|ni+S)htdkOF?Z1Q7(O9uR zGgJve`E^ucBkO-S2a5Tw4*H&sd2&)ohg8m#m4kS`aDxR;-}0$+9j_V)UvdZ6J{Kr4 z17rvmB-;h=vkHGXeM_jlIQQQhzu>*=CX94L@VEK5I3!6XSV_!%=RU2WiL3N|h;4o& zjnnhk!^1Ale7yQ~Q{sZ(?^fhkb~55m;XC}B9~B}9oP)MvxB3W7C84W0o}QkxIH+_o zT2QEECNb-KOO}ufIiFnH>Z?Fg`+a*X?C@R+CQBBs{Qw0z&GP!DCMim~WO-+N4*y)j z%#e`zie~ahqVz~4#M|cko6xyTg_0;1*$3!79)Jj!A@bZjj+Zax3R;G10*@W-%tz=0 zJJ$TUEGL;1<`@V36so}q3ENgEA2|^$YucB1*n&V;m*zjKdAoVh@R^+Bu9`F06ftYa zaz_uM8Pb%j@c_SO3Z(G;hBSv@fbBFoXhso+$Stkic(8q9u1pyBY`M6oz(WjKTGHXP zN9%v1fZ=Jb;2Vpku!9Ftq~5&l7gL=cQS-a>;q_0(g@oyXY!U)tjM~$A)JTZ+5xEwy ztx&AwoOf+ANZFH9PyawZ$$pR+~BGTj^1>h*Pi~xd|%C}Qt$V)zj)-K z&jlHK4$}9HUJ`_umMMi@R<{rEv}+4=K_@H74v>{SBxA z-21N~QJr9cExjs`W(6Miejqu(NRUsTZ^U1yYaO^MxMR_tQf#PHaH5u@@Yr`svL9L^kI9uP}8cD=*6L% z{+TbhI*rPUxNGIMlY8$9W|%Lhom9oy{9SsHdl%8!cEW?S3~tsF%-HOv~s9lXcS^Z2$NvIT2p7VN}!hmPgCABKQAXh_4`5A z6T{h2?=%8~Ryowmux%}AcCny$Gm)~A;b&m5+n)!3>{X=i>+b@5Qkx%R;3Zac{gY0} zs1;WllVaIeWmOfzHUNO&SOWu-ycSvT=sc1k8y6rdNi~Ini~$N@+$S89u^VBr8TYgiFv_`XSB3K-zY#iZZsk{V$jxnbt+vWkPLz0 zTlXg-3dn6HXVR?^>8`PmPIbo)m3s4uQ{Sxt+>`Fdr)kntdBOY3IoefcV`F3a z`}K^htSp!+`LwoUkGv?X-gE-y-SGDE^dCeh3pX5m^``j7A#yX;@1Jt>Ke)yBR+&#s zkf^t3r-vu-{_)zu9*qY?0gyB_e9ukf*wPGTbvF9DGnNKEJ$zOE&JVYn2pjEJRgN*u zDbZzMc3Q0=J_YcNE2X934^1C7u4?sLTKue5Z_@}z2g4DS))I71{6OGLN`c>Mq>x@ee218mqUSn!cdISQQIOf$KJ zkD}bn;xh`&6z`d$Lob+1aq|E4Qn@dAFqNx%IB*l z>z=m1sh)UQPDeg_p9>tdmX8%Y&m^-tG~tqJ1?R|SAFN);`cpa~4gkzGX~hvsU%mO? zF-YgmlbvihYW2AvPednSr|oo0J`=ox{Ox?72Ur(^D#y+%Pj2|6J~-rE1u`X`lS`9W z=e^$YH-b!l%h?9? z8mzG6u08shxP}1ra|ZU-tZn`2>FZCu-MgX`4q68kUN)qpRKmKxhXxckH3$WMy^)^1QDzG z=OT+ofVracqm*>{9N|xBadMYJRI)Y1zx0v-99aRdUCezGBY$X#df_=7Y8aA~kh@{o zPJyum&tcgZ5dw)y8O75_|8vVbh@nt)RWoTwA7)pg*0IY}+?h;UBdj&jyOe1?F2{(4 zeR87DZ2f<@dJC{9pQvqokrt5<1ZfFrknS!K>68@dmhKRcl#uT3E@@b$yF*%OmhRl$ z?^%Do-~avob9s3QJ~8vmnKS3y_dPS=I+MWq)U(@nqS;)1n(NbK$$==A){pCpyh~G$ z@?2Q`YGQ{+0>0+lSC;%Tai*95vigpJTM8+lghoYQd16li2y%{kTCx<5mN`OGyK8Y~ z6n}4wk{-*54ql4An z2T`K2(q3#*KGa=Mrot5ct(icKuOhvpc~&`M^3^r*IwA+Eb8*9akXMl`m@zP>m*ijnl%#O6?=Ut3wB4!Lud ztTJC7g@pm~lLjp>`l4Z`p`oE=SKF_S=E}f?9d2BnFem+EM3-4%4#gIPA5QS-UIJvw z0|`#Xc=&Os%3Sz8uf(V3d%~zG;Kz{f=bG;oIe-uXMD?-qyPD;T2CXFiZ|_<|u@BJ#P*~>o1gnE3!CpJb;08qH%br-L#PzLq_A!p9ags>@R>d0KB-ZkfM zVEa9f;XqGjE9*xfofeWJMWLF?y7wUdno2Y>`f5OvV$vT?9_m1kdQ66VnhOc3C2q~; z;sD{L{1EGbKK8a)rYmzCz-bpv5^iZKokH>w06QpJttMpMRCl=JoV zRaA^ZfGJ|7!1=EL7|7q6dZKL91}Tj>>)WPWEJwI>3}j`(S@)}C9Ih;`D^(`{^Q6v)3&k#Y2d?-V|j#trW7P4n)&407#Z?P-P$c+0Ua9#$v_?RXa*TMKe;Z2+fAx*}S1(sxJ-z+?{c8~=Toe#Ur{=@YuP?aJ z(wB5`gFhEScdUnfcc9I_Q$?iXu;l{9<9843Gk6FwW`+srYS`xRhHW>1AUpyEs8w}; zrNRgV{(SPVw70J+EoF2i2>e9*M=%Saa=~4FdVUS z0rYm?(3U>o>aj*XHq%mtUUeIB*AuY>7X5u(*B=^tYz>Gw%Ac^mS&UA;*`HQaG0&Zy z#;@L6KWm#Ze%;mPUMC1rOYny@|6H!Q!QC7XAsiK6&cR4SREG*9G;w>|d{B@m7+DgL z2mLZ#T3++>H8`v`_xEt?u4A9+yz2ZNUl{!c7fr}yFBbOgz4E2Ir#t!36FOC{@Xzm2 z6#sT%aJRgko*v*Of$sYg5R2$L^HZYr_{i~=@0XkX_6BZah3x)JP+LTkB;+bg>_t&T zYO^5e3NPg-fKQP22=i}!$lMBeVyVa&5EHuOj&^#Ih}&Z1afTyg=jgt8dS0tY6wzsa zUaKiw9*uKo;DG3tLev3){2Uw zh@F(@4MGzpX)yY!&H;W!%)j#)AF2d@U+PIEj^RzR!|%uy_rnx5hz?3_&)32`sTuCI zkKWrLm?ms%uby7x>1^2g1i@cp<8S{**~|gZ-+xseNvnn)9f999+w>=ti(Z18vfEFs zVIGK9$2smk9i`!3AOjHxVEo?(x1+wXp_1Uo_`403?)FHkI?$aG#L~hZJHTcuhj!P% zf+g)SUnsatd!ABPoj`(r=nZ9vP@eVc6*G(+f*?dc9>fe*%FGxFmj}Ge7t8tFlT%`j) zU3?0&-u}@A>Os^F(G7oC3;q&kjWeqMw=QB<_f70#E$w~_7XJK~$o}^a6SF1;i{wWE@4P?T?PZv#b^4ln+{Kmol!5ETmofuMPQ*O$OW zBTQxYb(pM^UlN0z6wb4@L3%W^o_7~fku6YxkU;_3>p-sq&EbEvP-mvVmTcqTu(mUx znlB5a^-&}|5Y{kASWZjJdxTm;V*1xFe)ps0B?oW^@cjWlayq5_yaOc?^x=jben{yD z>%bm|+kJyt0(xDPKOa6>zj_pz!-!~a*XLTZ;iNy^p+;^CX7>WHKd(do2>*{3Ae7SH z!GTC|dU9?K4aCF4bM%D@16^7{A#zy6sOEzNph8FaGhosmwf2DLQ-3ssiESaudw3MS z=ILzsp^&ciQ}E;m(#4ue&(}No!XDR`7xq*6H+)L7ZXyzzjh-C znE`|h`aG23Z>4_ICJ*y)bD#K4PfWy)nk$fBQsn{RR%d7D-!6?P&-MIDv`L8aN5%4e zv-v3>8+5zqS%}|xLbdYZ1MDRZ!oU48BC+lM*m0Ah$@S97QnEV1nOYZkF#xDXt{vy>W@cX9 zyxE9hm#GQ*1|-*bfNN7hOad7K&OpZkBlhonB=;Iv7`@N>$p)Hw@!6fd;ufqC>bm8ly!lxt8LdljdP8&igjJY?` zm7(i6OBO3PtJ6%MsJ5RWoWP@zC!km9zI*gy@|A`LV)hw(kVod3N)ARXPM4YPS$@-s zO4HH_;1Dm|roa3fzhyxR@JWzm&Lhiid&@yNcQ!^3UC8OYw%&W4tjBDC$dc*;2Z_NH zg#{yxS*zj~ppbBNy&UCR6SiM&zJX#sd-X2mwJ{)-a9?(m^Y*?UN@N}vJ|7Vowc!(W z8s0fl@;v~9ucA4;zimE@4pS^~->o~xurHmbeD3Rng~s^aY1@HHHAaKa+5F}SlZ|}t z!Zs<;)bAq|4B5o|ujHlfZqc5PYxI=ZfUoOYu1>SzI6en+q>%e1>op{ML#JVjBg-*R zL0R9|Y|itk>&|0xb=f1vE@bzLLo+ zD*nh2hF<(31=_kEzFk#i)wHYzd4tY4Me+vsDc)ay6i^SG(bPfMi3K{oUzV~E_UNmg z_c6;ysFY8P-_U88&H^@uIID#E8-o^CB$QyIFRBe#m@G1`2mDe_uAgGNfwesAkpDE8 zFWb9x^vG;}xx;f0c~sA5bvUKFD@Q*%yOvbzGa9Q_cz;7;rpWN5TDftBqT(>XXmp!3BOH*Ga9^b69AA#X~ zV(>AGRn6PwN-@7YGl${7V~vicDy9Wm+aL1G%*SXnHU4HmZm1gEc_u|UL?1sJc8EpP z*Zr3KIOl)j3XG!K+S>qHe!my@Xo6VTMH_d= z73Od9$J=)!hR1|*r~Eg*8Hv63yLBaso^7by>%2D-a2!Loh}N39J8*#g@`QzsDRkT& za4D7>8qN#YLfWeQjy+9=sdTP?tqe1dd+Y71`x}ZljqR+8G2TxZJ!kXVzFgj|Uv-?_ z+L=jw2?}_dq^X51uZ=Bm4T-r;7xP|QW6L^QJ*}}BJ+sKNF@!>7!B-i>)t&8~K8NdT zEIN(8-OSeyyIaQU)vc#pwQkjl4$-pE2S6aI5gNo}|py@9^GzK?J@Y zdQYzP*ZA5)ZcuC#(%BBJIUJ0$9y3odG(i}+tAX^Sc|1(V&0s^k>`w3 z_Vf0eU(@WzRRVB`&6@9!3hIwkMFmR3n;R^>DSCrXz25AiW+@FdM8G(CN`#sk2he=Z z-a_m;Dp!NbMQWwd*$=e$kn-@Mw-}GUab5=^BE1R6SBifJ$e*08D{nvSYtRqE?9TfP zbhh@&t!VPAMg;HKFIaoZ?qX@bP=^W{6WGbJ!#jgMyS1Ml#IGcF=h&G|M^8?#Ij@L; zk9#h`H@ETWPe2xnSnYE&@n?xgKHF3V|b%gdiC>5P~{ns6fN7 z_ANTjej1M_3TDs*+zrlrDy__JFD}pl5-EZJ*$|zH5%YRb&A2~$Gt$b+3e?wc>TPg8Akh_VTKX!5z5$b_yv(|9_B*)UG4%e6isxi#HQ0K4 zulSvadta&0+;_KF@OCLGDVv8wcS3ExtTO*`-X1A1l^FQBBVwpftcc$}6m{>(M1=*c zrjC{z9N=T_L$8#A&z$N_&`F=+FuS$~5m>piVT49A7cl}10Tr43-0CgZUCbA9?3Sf> z4yDw0UW{-C7H$gW{S2GtNY^gyjoI7Q464>^__P@WO2Uh1%aEF>YUppy<4n7+(M}m< z&i2b+8UuHj;hE~zSKI2}ZVN%mu3m(LO@?1N9F$nQXBJ17mk#sT?FUT1%GA8S*XBJa z^K+e*zvNTK_B$C087l)r}nM2Z@@CTj~_n7S`Z*t5b0 z1sGE23RmKS#Jw3$kb#rP`Hpn`;Ph2@s{D<2>+uE>s+xZKb_Of47mSzn)fDi?4KNOAO*&oB z?wq?R1$Q<*txiDOCnp-W)V}b@)}Wo({b+_pHer6gjbm!dN12>fPSfJo*!JV!pT)(l7<9n4!PYdGr?vq;cHrE^$ zvS7sSlWqJ8Lur)WnlPSOOf@Es05!Imw2|-@kX@d{k5%2Bmq*Pq+bDbAFZH?4ik`gP zh@I7e=W+;ML%JxJ)1fE+%U)Nnzh63td0Z{5s(-wlNHb3M-)vMKtzf%@%}leCG*tQd z9b!(4x{p`=U<&9NRTYJsJ)r({_Y`S7EaXHj!D{zoI~f zhgMu{{O&sKH1(&oLPx(Ys^AY}U-F+Bus=LFfY&w>%o1nKiebYsVE5S@>Zrvk(wr~^ zIFn27NPWA>?su9fbj%$itX6A=^@P+syryj_nry*!uW-8a!HiE{yOeTeN;-`Fu>ob-gG28NHGq;)lhHi?XDdlgaL;%J=h&3*Qg7=pwUz z?e%@Ujm4|6>p$`ljSq6P0NeO%(8Pe-S=0A_os7iw->y3=mr1|*DzbHO&Uws^-s zM#|$D;dRsG?{QwCzLvC^<2_#$VJtNryK;4Rw*B32jfPZYYkiPi^kE=^^}P+$fYfk_ zfUu+B;0Oqk8mshfe^nnp7+e$1XBia>%(rmyHF#M@aN4o68ZB6ZK(7tnSGw7+Wu9}r zZ|h%pN>U+u`Eb5S;o0oyoLnnmF>JGcJ!7BQ>h8cws%4OS);8Bs^KjfEGX9>|aa*W^ z&fm*v#eOYqBney%JWZStr-JU51d&iadF|-kJnX<9M$eB58L^m6Z_&&8`_$8{`A zt0r*BX`0Q-<#$VQ49c z2_>AMhX4&r@C+0ZxQ$7l5fG*V8|A+Zf*3J75*N)G<+90~{tOqb1^Y6w!yC>YWz(ykhbMC2 zPlwCOKF91WlkrnfvX$L)vAaSnx3&9Qo1KxCD=snL^{7MR$zeMj-~D*L)rap(ln>sQ zTTMQDkm)kqnSuIM=P&SkWqse#V*fMY==1~t8jOf%_k$0J`5TYTX5T@FTSP|PPCi_| zr+iq~45u@K7q>XC!cQrMAJn|v;cFLh&)DuxUasC2aU2j|Q<~A7H=*3yR znw-lCKk9jiKldeYGEdlT^WQ!j`EBcc1DqS*+ytPo^Hm0V1_r)>pNb*ntC~k6<+E?! zh!z48e-Y!ZU@jm#3~-b6dlh45hIs(B@1tcJ>TVJkFlE%tS_C^`+19;?uXuCp+c4_B zQ&U0RGQJcY_%2C}P{e)g)pX)D)B5POcOx|P;fSU1+LO4&-YEIn5G?XT;+09$;Py@nBCVG0#2J1@9PudBJ~j2 zXtV(U)iE(MBlZP_?p<|{C<~uTySq1)JJ1B0gSmmi$EQH2C_#)1;DQ^=X^7gPAeH%x z9QQ4W*8l14hyS1iY6SxEy{ewn%+`m-V-42q6xVF+k)x?~D;D z0;r>e+If)k1jG_Bw)UcNFubVqZDt9xFEm0{s>`e=EAWpbA)CNgdgx(NCI zpxJ~#2#bjbUVo@*Yx4nJfQt1zK@b`fHVEFaV-N15Ud@6aXL$ zLtvF3OhzR;(6(2w&qwCR+e`-2wyN82mZDom%dbn6B0e!gHa&=j|J!g zeUcX9mOwzX#IZ$)Pz)%|7BAZfKtruQ6|n39M#>dhK1;w z?w|i*nb8+z1VC+t9xQ(r!+mENe`0GJy7dm#_rr`zyYYf0P&i(Lf(kMaz6O{ZULk~k zp+P{9)8f1nf%sH-((6@UaM;u8e9qC!#4cykl`LVQzq$Uh3#cUTY5t*}G0Wyi~ zDFCr;k7u+0jaI`CTF>E7OJAru{3=MLXVBkplRuJ-!5BVU4_^AAr|LvZ^ zwF9>}W<$=?X#;_>7Yth43MG(KpY*Uj(RhN}hKEPmMhciGvg$#fq_l*DjHIO3ph2U_ z_B|3qZO*E4FaLOUdD}CK5ce_HrxvTHW&7f|lDpsm9jUd`=H8AlQ1LfXSFaF(w>xvL z(ipQyj{?vLev_qPybQ*b1e4lMN$=8!hlTw}dnLK6e0{b1HPGfTUZ~w+?RT-ktngo3xt)0pOl~e;>Mo#hmXgzOvDVoDK6fp1q%4 z$?+t?D5xkZHv-FS-rhJbYoe z8&(ycz@UnVh=2&jWm9u-d>b`~SIUJ>R2LK$7Ut#}o0zE2e|}&|VZ*&sg$Nrwm>sk8 za&x;lI<`1&$QqyrPOJ?M50^LS)mI@)VB}H`4&+y74&Hcw+aY#%I_t`Uk$C$V-juo4 z-cgw*m`Oz}W*rGm?CFsf%#6mdetD5!P*6ZiM+Z&hQG7>)0oCz$Y`wV@<+DnHA-%jX zk&%}6@b)%p_rSAB!^j28Uq!{*V&t~$#&R8dWe2;b*5g}Fx{?z}iao&=e~ZWc2sRc7 zEYvyz=p6&O&l77>dV2S(9p0|wy~>~W9_3Q*vnvs~=DEC5MD&5hz{p6u$7vpbHUN$e zBKSNQ_wJ|VBr5KqALfs|)bZEfk>#ku@Sf|>OT4_G!4;=xcoYV9eyZr>LXb;&bVV;IK?oMZg|_Rv~vDk>zHWxsWJUSWySV>@S#6H+xQ%r}drN2PO}X?y~ z28$&%;yuvS8u@3r*{symT|GT0h|lSdE-(l;^x4;l$y;4jrezJCcjd?MWhPODg$iOL zBa9Wp7nRqF`T`3D9oa4Tt4+Dpmrukg zr2ZWCFttm>UDH(71UHx;dB3`pa7tHPu4X0iv*ix_H?w-#5*k3-20hLNaLgm&*3? z)JUorHG*NrzY4-9*m3djCi7&lo;{0ieTwoj*pKIDA7-f2;-?)sFO=mt!NZFEPq<~+ zQ8^`PI}^0MlApz?a4~}MUo<5a)TE^LSNV0zhYO&#XkzIW@=a-C(9!lP$28vyXKE|d zo}g1X8)dC<%okgU#2`DG(IGi*L#e7|*$#CVc&}IP%fug3g)b~<$+bKx56@ko?Y$=! zt`G86pAW%q=My&8VjmpT6;FX}ZWfhhDQV@i7Yw(*Ox_k-6D-M%x2eCgE6P&*tp*Y& z?7&`Wa*?*-3Uy@O@2)j#+jcuF&h#6va(ZMYBXb%rxqangwLe*Ftgt4+ z9?4Wq?bnh!xzo*eDVju^=();t5J>KAtELyKWk3#RlJa8mn4}Mji@#{nW-+-9t&(gEcpXpa40zS$dJk|FQxK%KYPWZ+mtro#_ zdvjyxQnkB7fu)J>?`V81+c>5O(R0mkIy1mT1yK#Px8+&*TFe(=x3adTvY~*ij4vjw z49E^hdF!kvoc%28Kmknh?TucskupKR=+3-nY0l`WcKgkF9!?A2@)K+Fnp0|g#U|Ax zY@)@gI`o$4;MYdHP@Bt%<;E|oq15IfZOy3L(2*97CCy^5kkTX{hSh1pOXgQnD|eBU zi5kB!d*$1`O-Gx@v@Um6nMY}-@_spEc?qQPSuZvl*8j9QG7DoS5B%z2R)i)0@KU*Z z+}o~|j>I1;P{r)8@x-R4dY-P!I5;@`9pZ{sHpF~x?)l)%l4Bw7B|2pFdZt{PLCj(vOOg)|w;hD2~b2 zdTWh+h3@-SUfH&#>l&8Q)>kVz^OlV`j@)WE_H{>b&9B89T-`hNP){_}a2F)QGe=rl zm`*Y+2JUfAk8xU-DcT_R6f*879p8okJ;*!rqtNqbnXRM5YYT7EJj~}fVGZ=BgU3Na zBB{+seiDiJUv&B&5isIUUskX*>}qZ>$Pj+9%kXIH4ga;-vx8;1UzGho^(cpyx-{ZT zVue5NppIdjk1cfsMhb6wCQd=?^23FN{*O#r zJPdyF91F(xk+y)w(zK79(o#Ozag~XU(%EC1Z8TBUk#e0<`8Qjp7mLyx;HWyI4Q#K$BHYTnyf48*xp&)Z3)mg2-^Cl$ET-%GBxE=j~bd!uV8-j0NWg4 zg+yk_$aH#&DjP%NekVK@Dr1Dlj|ozRTO$vqHcuH$~eS)Y&dr0lrGBO#qc z)tIpKO~nUWP37BRCVZ{%h0SuxX-@Su^cNIab$sm~-^QJ?GBO*0dRfQn^!>yl0TF0w zsqsdp^_x5l=rCe(FaiP7!b=p;NYMUV|8-8x)bk2~X({H0s&0whNQYD@b(0g=K*EfB z?RAVI2TnGL$5{vNz_Jjt?|gy#uTRHzz!pNgaUs76e`T?pTixG( z9wYiTplH6}ctT<&L$lNDw&38Goa(4hODY5I6X+Z=T4`1@EKNa`F5I1cRf!?jR940* zqK;TLWbsK(sUAz4p1*MV_s@{`u_eNqF9v=4e~n>#=fXNqHEgU zEE}dG7-@Y9$@X0zLk~|=_|drKOKLedO`w?8Xq`crt}i|$taIUB>tZ|Rf6gKISp4)^ zepf__@#G*ih^ihxKc}T*@7iG1g*h8pH9S0=(w@b}O4#H0Jh-Q)hh71|SexIqUis)5 zO=ku6I;msmHn8Pn>5V zKm(jPiI00wK{Al;y2#b*;)i6HTQ1inH>BSL^vA zQ<)$yIdn%!MYt1gFNmq3>J~RKF*PMFV<@rGJ{x8gl&LZ7Ah$P^CJ0CdTNkY(Ts$@H z$N>>DIV&MrDruw1AfV@@eWPAo_2ltWf47fjKS1o@#Gl9KTv-(FkHkLwPO!V4R`AAT zgcXOPKaajVebILEBmW5!s<>kuWyq@Xy3dZuNN`46niF0m4HAgT%Ej}~enQ4s1W5B{ z^Ty8(p3BOO5s{oqV4*WE{sja|i>@WSW#ei3I6kXQ6#HdF(U-k}W3CVxlw06no|cyI zehF_t*RZSr4VA@kk7fnM;LH6>))@Rw@at~AlXoo1%*;$72G^K&RaN?)qGu)thZ7AF z6k|*pZohc_;iK1F@;S{1fpOa2#aH`#TWu%5^Id*wD>3Gl6~=(yT0Z$+(epLp zyP>g?bzsEz@aLDA=#emKw8p5*RlheIYE+88=M{#^IA>P2tpp``3D%ojvsio z+UFg8{M!~yt=0j?n;XHOeF~LySV6-`IJjs&0dv=@Cdhc~fUKy{j;t7#O8MI!jcIAHmp~*yfPj zoT$Ei3_cZ%ytcy$d7R=<)%*Gj=*O^E1N)~{fzL}NFS-@8M@gof-!gO@{`%oJ^wRlC zn6V&Wq@&(vW~@CaUaLB5nc90}rn}bXEiq-?r>Vf-?rVkx43RCW*`RKk@_Dj07yEI2 z@Oz?&-l_3;*p?{fQ@h0`I}t%pSg?y5OnsXPrL5?D@*hc9jLYAH-K@7?qSgN*4#_VsVQ^Te3~&W*sKaK%vbtk%95B zCEVX;BArPpv`AD6YSmSl?Pr~J_ct$m3D{6PJlVXeHt=2-KC_sA*ihAf+*3+q5hbeZ zF=7awniuqfwMR1IN07T(Ulrt}Gk$NcEXG$oOOzraiN3O=q9;64&`2O427$yG7;N5p zbdAf2JDRYOVH|T7#0vnV)`(|=9qj85x|h1-OG_nqAR~FAM{La5zV4%a6Ca;hpx>U{ z`Vy^;(SXy~Fg#c8qDIcM4#*Z8&IJ=;28RjOcBTapSqD02Gc=YT6)M?>eU*s5S1>8I z_}|G~8?w4$f=Xi9taXJi`_2})imD?k))q!9bl>p!-P0N12B*c(M|?Sd?y%fq{&nG8 zK4?yqsVnZ4BPXR>t7O=86qnQd=Ifu8nTIHTO;E?L5Uc?v);AkC-XzRSK+zrVRIkX%liE1}HX!+; z|GcD>LBnWAp(bKBSzE(B-Sg@F!o}#51gp9(t-!$ha^x&; zvJRii$$dG}uQAbj=QXj9LPEkzi^xE@5Nu&NkM9jlHMYM--EGGUoMXi13~zGx+zmWE zgWA*#Kl{}0?LT*)n3!jC=qIE#(h-EO{3y)VPr!WtbKb3HS6RB`J+I5V7=__+_z88b zW`3WNq5-v0AJGnNf1Lqo%HT7msQ!wKz3HOPZy{BQ9SdzG!Fh0higzm<=i4~;Ywemi zF>XwdAoI~HtLX|?oR~S(TE^Q1s;jdj9N+#JTN4}eqk{#o&BNu+ivsh|mZmIn%E^FJ zR=r~W+RzhRgSG~1Y0`S9aE%Aicp4s&&&|MA*dsTM-P2)*h>|lGRW44rfycY98@yVH{wKdq)5?ixR~f+Pp0d~beSMJGMSUcA4c8;5~*)Y&fs{~xtLDhJgQ<(rvxQYhaQ^f8=J1M?0!WfqOR zSk;M_EwLhzG&kVgXcj?RtPJNQoX4z(&uG z{zQ-*gb|V6s{p-P@ zWC57>lQToP+?(l*tjP4GG)@o*Lq=U_XL*x_7Zs#t?j_v4F!ZM0WCEQcrhj8=nRp*K z<_AgY#pJ}H>=)A$4`B*+M@0*AWCgj~<_3L6kV?iuf{VA%^kQp){xS|GIhB8Z^12})SN}OSrkDTOnhToAfcHtvnQyGvEJKnR1BG$WT z%oEaI@-dg9`QIZG@sU7zBSI1;$xg+GDU-U9B^(|X?zyB(ysEy5u>|mKGcF=M9vXDM z>5~*3#&C}3N=dpXDs-6hyyzE~X?3^D`N8-ca#Rm@ufQQ%Ni4)pXFp=|r$GU+@#>%~ z6&5oydJ8Zn#NPe`qRfdfbcFSz=adqs?D`C6d?jGtTYsp%ztFOKvGnE(DCfmeL%@y8 zD@>57VV_*xmr4$D5QE!6u9b-c_fn@@j;mE-R^Hola;ferSE10R7!xN=a2(s$OBS*y zXDorjEfG{RS3zZQKRSaH3=;}byQ!8I(V!yR#YJ}?c!RUD^*uC5qXkxzxS{`DzEp#n zPM%6We1vFRn?}j|T4QWsaW@^`_O|w!lVH?RUfY%J3|<)?A4k&tu#H)SCOK{|$^ zv7w(?T)5~BDYuE5%*4OJ&I)6LAmsN z>`!;CuBU}uFbNe!X1B{JxQ3l%RCP-nf*im$oN9$W9IV? z;nj?%e&708J$!Fnq<2>B(YUStl#4t=uUNljCAaQ{CuC&AX=eEO9_?xZt@4nhI3Mj0 znkh+}D#O_qvP>mYMJ~mzQyutQrbLBg@)L^kYJ# zncaA2XCKEXg{t`q;`66)D9ACOGJgRHOavgIA#@8>cv|e{b$>$(;-)^$X4oyxpJph5 z7K#J05Z8gQU&QQ}DEfSUg6`Ix;Gd{^Nk`34Q7$ntk!?ty*?r<8AE6gh1uwLBE=Zbg zy^gpx+i1pqR>a@yS&&=w*7GvR zc(2~C{;&|1gcemqe|L~R*$9bbGi4FqUd@^v=^3$`O8lzuOn;QDJ(^zQD2sYVPjQKh z+TwHhXUCWgS(|yBI^zItHwSdRXXTxw(^GTTjoenXEETb3W}a^cj5~GKy4BWdX7iMx z(Up64?~rjVWU>|%zzLA_+Gat*%Vyy?q~HP?1TD zTOf@TWSQjsxwd?ecE=FFLo%%IcO@KvA&DnldZ zO!r8-;z1Z&#DFj&ozNHlXKCu{U7##_?At;DTyDWPv{Mc?BoEJnBb={aI?>~xgPC#P z_8urt)}~T}ai3nd~%-eBu6X3Bm|j!0xcGwRaG&XIdGk zI}4W#!V}UW%|2_G;M#MV@_-iobW5a!BstzP^IolVh;K-g4)(`0W|6RIoz3|U4b67~~~`Kk7JGe$1^U$bZ7 z;^LyF&Xb9J?n;gUP&Y@b6M6fBC>PhvzE5Hqn3&>D3%OyR{IiL{ZKU42(*f(U$Hc-c zQ}m|rPkNpbi$T!zMzXd$&UpLDy5p48&osIugUGQ5JwpB0gh&r+WU%v z6FGlk8O>U^LcaB@lW<8d{OO-#TktqyRTymV-lZ$IaOZpXOU!a0k*$AR*|I=~=b_F0 z`098K+?Y>~YRi^eR&+9(#!R>ESP)?y!NYbli)wn@8LX_W`R#s=^a?Vp;9>hYBMp+Q z%tYOISZ#Zn+J3G==q0L zGn(kl6?HrWO|Q?$v-r*5R6 zKC4R2O}TA=3QYX2Q&@%pth2GLd=Ql~E&2IlD63Wd$nNH0K*$p&_%_S6R1{kVg}u~9 z;p!4)gU`-)+UPQa7)<8Cq6Ss3+Rn9R;xz@iP@Q4oH6vvrkeXq*ilJi5RfI6zpW0v4 zsIJ(BB-M{o_awVau(oEbJ0(r^CDf4Gq$_e@*e@zV_?ZeL9aI?&1|F-8m?geRzGYo^ZV>y>_61o+dDCF0*Iv$mIaS}&Z?V|k^=C1 z^R83~s+sZ?7uUI*opr8_w*sN70Ew!U#JNpDAiijBp6=mx0>1OYqmV`a&e1A^#7cGQ zTpc9|!@j8FCJhE$$+a!876Subv2=w_%N6TZeM@jeD>XT-{_~jJtM8KY?ldwP__gh= zZ{Pb-$w-!F1Rlh_EW!%*<7csikpOCp7C)$$l9CdFP!>bblP@nQ-$3r~+szCGx_SzpQkG-5$b5&)z5`KhYH<6h@zmeVVS1*{z5}T8;8<cv3?Z9wEv zfDC#K{J#g!Gmzz383~io8M0z$h&2#DL0di{kiw3zu&|MlckJxde>puE?N=Occ8)Rr zF{8uEv%IDTcZ1L%7#jZG{LX~*f7B~^27r?be&zwF+dGHV$~5nW=4X;yZX z`=2JVqo`_f!U5{^<%LBT@D2zHBKh4F^KO$ln)t@X9$BR1z_--2=4yBMqcs`>S_)9s zMM+6o2B85HYuo>uRUSs<&aS9`KZXC|h2_dm1(CDGgo;LQmc99E0Q&LACqX)Cdd>~3 zj{=Ui(wtYNy14eZJu3_eku{JzRsYZ`zT1BnIo*4V2`B-|n02P5F>>LQA_sTv!Hr)P zk_XuInt0oF=l|r0A1%I4mwMPKRY~&C3M?`WBE_kdTn@^76Wp4~z#Q`18WC z>0YtRr1NoMVd1>|{8QH*j9E;dV?b~K74H$ZA^n!hAA&0B9SU|~Tp!OW$e}eY^_q)&>*j&?pkNkHjj0srAEAc_%|GD)(e+U-&U(NqrHbIGu z^`DUAuRUPou8~WqfW%dG{u#)BzlB~gM1V5>-)hKFVdUTueE!#ve~#`wiUDoE(*b{^Ld1S2 zbDBsEhzh8N)|{e&Vg0Ygzyn}BQ|s3+nbBK$Y^QS#x}!Vwy6SpB;*Rm%N_JUu#g6BN zIFaQV#|%g1&(6m!zpl2wtm#NyW{(1PMauDI`%ek+@4Lcyf)flruKV)}UP04$BA+OY ziI5HEf(oc>1HXMKt@}z?vVIU_%Zx5Zs(^)Tww@gFR)sq-kKrbYQlL1vLiiO|4Bdm* zv*On@w)Zz|(Qcz1jhzg)koAJt#LSG8r1AJiAeD+8p$EB`OxM$V0_nk@(;^+_==6`x zD(Stvxj!@<2gf^3RijDE%LJ;`-8uR5zU>*a;7q-x%NxH>`h*40uoMd7NSef*o^N7Q zm%7fGUGWsuCAXu=55XG(%}GA6UW<|FD#WycxRA@TDJcxM;q_NikX>r^C|{m`>2R*ccOGeEv9ieOwig zMTnnlRh!POU@sk6oJkvXv8;F})+qFI0X!_{d1MRW+<0ew&#-gXWD1Gwk-zXE2$WDl z3v5M0mrRoj8bUkS4WOybt3GJBu;BJnrrp^mikD_6sem}bY4M+Ov2t**X6t#`683BM z_Ac~ zUtjGlN>@Xs2;heciu6W=y&3vE-YbX7gWB3v{C?2I)m|7f+E+cFP0uO}P=IL%xWRAe zx2PyA@@o0r2WX8N5_SMpK%RAmlseP;xu-Bi3_Gs;en}3aPe)s1hi@{JW4)T}NvgNQ z#^x+vPbJ#5m6=6OtcUSxLn^w_VATwPbauvcu{?5UQB_nXsT&3OUOwr~(4Yst(~dzd zE(0br4Gg;Eo~`roJ+r!xxyL}%fbdUk8%zRb;8aDLzXeMu8KBTD^3P~_SXmVPT`oSl z7)O!PrGB$e{^GC96ZuY%tDwbqqY>*kVfGQD(q^M!)ZwAfaoD;#ftc75D@~(}jduF47!X z02xVFm%G`0DPtTb;?jYQgt+Rtn8Av2^-OYfN`)ITVll7KP~Yh-;|faEt6UVy=qGlZ zccvfr=u+J+jM0x*9EOa2I;HyQU26-DLne@pjv)4gnXE9JK50W91C%J+uK zHDis5+Z0Jg(BPo_*GSKM4kL3ya%<5;)4Ng4&(lr8gDf|32hFit$SVi?ZOy!nj)z;M*y7!#3_x|l| znvr$7*%65x)1i#d_z6zSQ_nJ+_pFJ-Z}!Pl<0%4er8ZmQsRR$TAUno zf@C;wa|%g9NV9sJWPG1EDrFeVp9=e#!aR4Knm7!U!WS}r{!lNRf_2q7#Iig%hS*K@ zLV%Qp^$de6C=L*C*)KKtpQ8p7K*z+q-n!l8da(~!o`(-6+$6hdE%mFK<5`i(JMG>^ zx$NHmd=7nVRfIME$YxLEge5EA3(URiKjE}J^2SOwWFX+SI9sQovrYC%jPX}XEdb;3 zA+)A>C9EEia zF*XZc?D5*?C^wX;h_66}l)|lMJYBQbM2L9h=T-{vT#Lh!RKmonjB>Yg=^iN{A6u|! zd%oRFmJi*;BUYt50WINLhZml^#NW3$`f*F|9zu1_6$~$(B%D9Y(SY|F8|S&L48H)f z<>rTRwOzhJ9CC|SH=z}C6C z4p{Ly1`FN#8tOfWf`X_fDy-~L@X-mw9+jxTzPR=0xhaawe5D{pR)%Da(p151!TA;! z$J5b$Illtggj^}N=_Mf4Q29_p{h^UqhS1g~s55}uwwk2Eu|4@u<zXi&81JXi;9jUv2LsBpr3`72rU0D#B*Fhald;VTo9GtWy_*-3YF_y-q# zYEAl`6XHUV1csmRa9ZA$Q69(i9I#X~9$wWOzJ@<~R3>&BZ|GZTiMs9A7%z~j%5@6Q z4?urm9OqVZnrqeT=>AMBm45BF5TZWhQO|X2o#lP)?KYO1qEq85P*vkF?Rd1r5>pl( z<@!2yU~^^~(dIwye>@DgF}P)o-)ivK^J1|hZ}c4=s|tSfEwy21duyv41OAeiJj3f% zZ>;ZZfG3zh(%wKQjBhj#?QHDOw`Afp)U|1J>90O?XJ+n8Lcnr~JrirG0?&;7pD_af zk;m(3y@$-n!;*$tPOBx^y}{Q6(CYP1x|uJEm%rW~f2k-+OsZzlU+whXak5d$`QxT) zTSrB*>En6b1neauq#sS$oRV(8aWs;zq%ZLNTsL7a;hcWjy+XuWko%ij(e(52aczPL zLdRo!Rs6%jLEyun;Ln$K=O}BX0+(>y+D{0NC8P}gZ{a1}!c*t!nol1r935>i32=UP zhQRE%drO&H5M%0TVRt;S-8&@1PCOoEl-JILzA+Yd;A_1hNR9;H8@Ong6GEP@dYHbX4jy5R6=L(eSn}J z^i|-n`&JzuvTG8`|EVTKRAw3o!`=_2BBxZ^u7tQv^tCSpEmuy=O>wZ3XuVTevoU-o zq|s`rwZwnAuWe z^%ZjYjrPlrxjCHXrs-LM-I@#Q=Eh$yR3QeST$a@-XR?6dMr?rH_GBWAOB~{7c{rWJ zj^iB*94j^xkpJq|<-sv?%98v55Sc~iVHY|tlKy{N%n`FM=(o#@1ub!LxS)`0?$-Fb z(;0Gh1{H8Wo*pNTkC8;0uFL6yu+GlWv>@_N1(CPe&5Dz(om3pD79z)x@Q!+--|gZ=4TIiAVFfN1As0kF zEf?BeZ=fM54Bywq=Ij0L6Lx!iDc(IXhOn>P3*q+`^*;$yd!n`3@~OZ1`J3S+4dmsI z0_{q*ohy~>{H1My<{~xtA4lpPz+YkCm=k)$?`#>Zh~@6~#_rV}k9~wpWo=7DMX6Ew z>bt|^qYG`~zyTr<&}SlYr&fJ@ij&H=(!oC8w4Q^h*S8+BzU)xT6@_@vXfLb2I`i5_ zo#t^gYdpkq`3A_HOIaZp#;1BCs=BrITIT|sWP+c0mKgsx_)@}w>%Q*!^K zO0-5b3}`p{?g~TPMmD}ZLRclKw&>4h5o!1JuP7_yGqQF*@kf_<7Mh zbP;SoG;GH`95;JTJN`!(3jmnjcWPY}pcZN@?+dSi5sGtKZt~l1*mL2!3ZlFIMB7^! zl^8*3-1#CZN1JSRstuw?f9UCznr^L$J}hOl-@m{bA0ic?Zm{fqK>;DL7(7Bt#^0_l z&Knltr{Y#*%*<$F%+`mu+!Tq#lwnB-7Ss7Hy_O$^!)NvSfbTp*Oj0fjboeh^Vzy}- z{W`OKDk%uePG818c=mQ7Jxu@tF6_$QTA^ktf3e1Mq?FS?Qqr|84*GegUs%Q-SvXZJ z>&y2Q$#35=p|(NCe7Ks}P6Jw6aj0CKBch&uceUNo$ERhyef$Dva+dgEULowl_YYYb zHb%!WE9$oHq94T*gp*FXKo8~Td?eiqGSmigz9t;4d zKBmY3csI_*a{3nxi9n5h+P<9;<_R$Y&orfy@=Z;4+Bd0csRZ1NgBw(nP3~B3z02?Z ze=fdzv^E$PlJ3!!QJ}30Z%)owbt|&C9M8wZb!}?)-2q?Ug zhX8lr(77s^;;|836WI~J`TBenP8Pk;l{WnL!0vA7soiZWJ9EX8G#|BelyW)Cr5b+} zHika`tKX8Z`PX1&zJT|58NI~W{17Ek*ix0(wz*eg!rjc}zqnT@ADA~f z@mD>qqUhuR{IRm=0EH;9Qgx#Od^4PRfdLo>blH7tOtkQJ&BarNU$7Ua3fj+%1#x|y zZN8RWnB1A2X2X7Qvfu2sar~5C^$AoXi}z{EsZ(mrTHgwVkxS096G`(}Jbi(Isod3J zXNjm`Dc$uK^2-$2R+-;>l=N7E13o@mu3wC6>e!QF-7GCPnNZ)nG`-~`@85i0kj=4> z+8-hqv@4`F)+i^4R>J!^uJV-|a+N$%ijlc8V>6LB)`7hR_2a!90+izID{(*uzG;c& zQmz1iT*(w-s5KxF4R`Ni#1QF$D~m{GH68c)RG9u94{_3-4`{HFo(~c4du?~^wDXw| zJ%|P1y&gSGP_Y<}cCX~d{Qwj{JzE?f4y$k&&D+WCT4I&`R3=^FH8lU6nc_AQ3Xs41q_|LL;Cn3J$< zxu+~m_5OH7-`D=yO|s4MOG!X7S2-=ma+#p`r2X<}uMy9&0Km4vq}Hv61vHeAJ2F>f zF?OWe>=nD^zJJl3{z&|`&==|~(X9{=j}7>{HS^vz^62tq5iIA3;B^L@kH0^dvGLu) zPpdG8nK!2W@%LFjKjiq(5PHk|v)SU@=c{g9`Sldw};Su>D zaB(lObmhh~k z=%*&XztM6w6K9i#{!c8=cvleDtLlFThml& zjtI?nh^6l-qR<}fpUQ>0m-1-Y5=%k*TO-@uj0Lu^0ezgz!x_`#kK$^Va|7B$%`z%i*A>|0Pp|(f85IcF6lf5 zZk!U*Ow51Pdf|R=t{$AZzWwqe-;<_Xza-5*&Vj++xYF&-(%xQF;7cA6k%Fc)LiXi} zUJ9pR^7q7-!^5GYAa^&ODu?Ayolm$g&B1fof!WUi0u=mMfxhgva#`>P%bG339!Fi zpG&-5(?T=`{?Sj3Y<)Bcs-Iw5l%(KiHTAcqO3U*9ATxzyMGwW37pP~!X1a0qksBu1 z0%T9!cigJ|5m8a`6Ri0v8?-*fCT=OM&w)!yTNVwI5Ki}8I}rxB(`NJZUE6UQomUsv zKWsK1?q$c_7Mpu}m)^C@YO=%ny=jIu^bJA3h&Udn1v|W~)|jvW#IqV7vV$wQ-_%|2 zQnUKwD{Ig*sY6xGvfb5PU{7-zZXzTbWgWbGzJ*cG)Eaqt?Zk*T^Gimdo9YV8{~}5^ z6m?TFem#;`wJ@RTNdCiLEd-3i=|dFy=;0ffAuM^uqb_%e(iA*Ux>pg}I6+Fko`NO= ze$~kU-kLe@G$#a!9Z0T`D+Ai}$MY||DeXQnMPDU_=}~Y#ZFi=V>U}3;F@lHD_7<8b zYKT%&=TJ8seQI1mi?gfiCb!iHX!jAm+1GhG?Y)&u7nv?CF8a9lZ@AN7%lZ3SNinOR zrt86=dboz+*n6OZc!MQ6I8RXz_o;chn9p313q6SlKy%(x!?fNbOG_XAqsEzjLYQTA z0v7Ew*rhrLnP=Si6@|-X*~0l=vve4YyqjGQ=__bh6e_R>Ukf&1q>h@%*#A%0`Q+_la9Vx( zoKR2a-ny|P<|#%-z9I-@sFcEGHRCAE4zmR55g73JEi~o=0ITm#__qL3>qX3~3k!%p zmijYECs#nutlgTVNtnR4sYR;=;B+kE$FXg-*BAsM;Xi?enPgh~=O2E?UrIVhJo?0Tc3C5};~ zfw|+^+3pzx{<>ukG#>z@r8wPe+3H?YeK^IxuV-^bkFUqtmMJT_jiXjGDUq5Q7?TT7 z!%_+#2VrcP@B=%?SwdsKWhR|>N7XtKjQc0m6Bu7V1i~$iE^~NIRfRo8K)vd+ zT$LWb^5xz#oi3nx9q!#NYf=>nMCrh@NNzI!r}A zhv8fT4-3HJw4HX5O1HwyfBGp=>RDFm>qmf>1zE{DyvOM+&iRKsd(w)zD$FsAO;Gw} zHyHfdSb2E9Lb{(p2S=C4kwEE@tSo#)uWS zwnj$e;H4R8ZOLQo7F5(*VBh&LE?% zHYY{<+whVDKk!v=^%zx7sa5HN+;3v!cmPsE2`+lGQvnqog5!M&J zWdZMf+A3o_c%AJh^@+x0W$5{s002hzL$&H%!{|xJC ztZSU$V_=C`@6&_&U>gTFpS_KwkBW42#FGwVU%YjE;V8cYJBEhdmgyd-%4tgaXgZN$VA&(EarVunqC71{ z!Da+2pY)+r1Fe_XtAF2KuPHaXaKAMjV%wWY)~Uyh6_6cbShWuo(7nSWfcqT1e5caO zl`#>|*l(ddhJMy4)WLIXIa2Y{j~KwBwbaw7tG`AN5ig5yT)g0ZvHYGKw(C-nTjBV4 z=Hc#Gr<^N3R8vC{UKr_J&LX`%e!U+hg`BV3{{giysk^*XhA!NXm2pSp@-xo-`$3jA z(&ZF77OyvninRMFG3}lU7C?@-$*4}T`gG(%%h_!=x8nwKtMOErcE5Z|ZA-EzSShfF z-B&_X|4%*TEKufrnD^OjR*j2b?WIRa&Pxs=Wg-C0dw-+oqa;*?jH^;i> z4mZ2#O2Iu}V=1hh3Ja&VXPL#5B&6S2X2~cv~`;r;mexSxwigqk|-AG2M?T^>(1m zg=h9E^06}N>B106)xn9fA30%SIpfv?pEPc7R>pB-Gi!Wqk1%l386DYYQAKHaS!v~T zvP;JLUyc&UvfGy$)OQJWH58vDTLbhu8j+&~i8xGM&l8H&2+~JEr)%|k%qV9T-kt6A ziVTr6Q`$GMLKzky4XKcj!_H6|Wj;ogvvifLZv1UKh&(8Q05cG#ovrZ{vjcfV4~u;4I<2#LkT;VaV{m8Dcay7%eDSjih{!btHh% zFqUXnh@RcT14m|Z205pNEHi7c<^^eQAU+5=5Z$NV zP!hw7%%A(+QD54NdxLw)Y1H5`DwKtS-!_C&1Xnj_Vn1G{gDYK+Idj-dS;^tbBGwA{ zl6HlwZF*CBixT>LW=@)8viPmGcL5t;j$wieeeo(J8kg?&linj}Thlt6LOX$dlc&%&!jqyVcmtxcEJ-%NW1DTZCntZ3~^0%e20m%Hc`v*XU zlO;8qkL+Ah>+)fbiYP@qwsM9g{ZDx0#a)%S9sJ>?x6Yzv07uQuJk%l*(IwZb8bf$PAje|{#7 zkaqrsko{>w^^TOoVt%hq;UL||bZ4*0%%V`z`_s&z3?p|sU*1F22vE9*)$Miz8V3a1 zC@8>~q+n`IOP%*mQ+y`OCM%wgxq^xGPzX9aobEMksfh~%r^IA$9~3r%3E$E34CHMr zb|g{*If-V^zf?|@S-j5McN8v5VL`t+a%hQcw=ve64TjlNPFN^9y&;Rr|CJkCiQ+3* z_}TpLwl$?+#n)?l^+^NP9>*4$PRN0qm+M(Zm?%=j<4m4B+~9)Y>epvFEF3XuOfgBFOTkt5H&oJ@Os6Y#!l|SYmpn@#Q3n(Na1^8 z!thF!aPGdtu%)8$d<`bz&7{SHwmIQV?U`Y~$CZ}_*RaCa%-U6%q(G2vT|wl?CjtAd zw?*@dOngZ+{!qh`7R^rUj^=USbx#9`ul4nMu!bCGQDw@+kY^UfG3!^#)M2Er)iN{L+Hzi)RU}_u4Cf^rO3hu;S79F z)xBqpYUu)E91xA4ucW-gO~>cLqCZ#L^W1Yybq8#W`FP?O8Kpvj)K$l(uFsVZB|@`M zp2C7=`jsWxuNM+DD&M&$+%EFutcrbHNm7o+muV;yJL#-eBsv}w=jDLwV@M5CAJ6k@ z&Lyf0pOzmIM=G2A$5fNj3`@%qHc*wJHqlt_{h^jx%lXY-hkeo`)%SV}jq1gMM|0jD z2>}jAmz|R!jc&Hn_qBeyd}_^hX$%sBjNHSI6nWZ1IKX_)w-I$+gC7Zpo*4T_ln*W* zs|Ni1EG#UNgYx@5kb^PZ3$906uu;#x--J%5*!J~q3QyXKZwv{W6-7$oHA6QdArkT+ zp9x^ef&(si6BUY##;6~P`CZRfC2kjI$IDOl?bTozb7P!JHBS4eUOK+E7FOCo^L3ul zta{I#L{jx%$KeEX{68S}tR7>*7K;0mZzH&JR#*AFQ(oU+*6$gNx1|G9V=Vf~@t=z_ z6C9kKZO_3RK*00fjXw64Nmc=>M&~bSCuiHrZa_&D*yk(CKgeV{$$CsAqt9lAo+y}X z`noc8%{<3)uDj9(G8CORwZhi=BXh)wx-nq?BxatP+J!BKSTTYg zXjKUhR7-t(-7ZC^fkd2MI51~f=)+dClm@((y+yxbn!W_(d6+{Gyw`57lc=XoYKUKF z(!Ib}!Ir({kpd5Bo$t+w<{01rsfkg=X~{skwp&y3{444SL^##a&CJDFOgL=$U!%EI zB*3OQcZ<=!vu#;ZokM@D{yr=>^ewDI#NW2#RVf)Aeaz4x!MzTH45x9Vjm-oWyZilX zi180bzo1fJYQwFVaewl7y}@C!baF$I&sGZXY-2cU9|adx*5?XWULo@K?)lczUQ#4M zz~VG<7Sv_>^s%teuhiqK-LP&LVf$Z9KLpR`(b`+{J*s(kQ~txum_vJFOtY+Bn)NvH<+c2jtKa~`rgEVhg!&+h8O6bQ~6u2q| zryW{%kLR`{WN+gt3ljPkfl~=>xW4YIl>q}SKr^VYkk}m`AM5*KyU;CH)I*j6nONhlM#AtJh#{hyZab*%L<*;X zHX+-t0S{8Bu~P{1>;+M~*Y((NqOWK2@K=xHQH`v&fYYU4w`T2a2RDoRrLQZ=*@!c63JIXRZfYS#c@8&3>Fm?b&EBa^Uk4X zPOCdOYwitUD~p98GUwU&Q@BF&bxMpF_t1>KS%(}eCKOswTZ$y57O~I1kMv(hBq!SR zB$;+kAS&VRF79W+?8&C$1@~8b*PsQ7QorNHnt~05r`1dO_F$x;(cMbkX&QLwo1^dZ ze9IL$mIXV#U!q(9IG=FSSsK#SkAhn+t-Nzfy`?U#x!lqVUwjRLW*Vr{~a1=!PGR? zs`E@ii9uVtuz&67?CcB^hf%ICdiAEcVn;~5$ynm56hn*rQ#81}>Fd2;w6&G(LcWtk vSYZG6az`fIgm*=VPPT(q_AHMttwk7*3 literal 0 HcmV?d00001 From 8b03061fbc12cf127951fd75d457da7831b7fa0f Mon Sep 17 00:00:00 2001 From: Mingyu1991 <115005477+Mingyu1991@users.noreply.github.com> Date: Fri, 30 Jun 2023 10:04:45 +0900 Subject: [PATCH 057/118] feat(traffic_light): improved traffic_light_map_based_detector and new traffic_light_fine_detector package (#4084) * update traffic_light_map_based_detector traffic_light_classifier traffic_light_fine_detector traffic_light_multi_camera_fusion Signed-off-by: Mingyu Li * replace autoware_auto_perception_msgs with tier4_perception_msgs Signed-off-by: Mingyu Li --------- Signed-off-by: Mingyu Li --- .../traffic_light.launch.xml | 74 ++- .../traffic_light_node_container.launch.py | 73 ++- .../README.md | 16 +- .../node.hpp | 12 +- .../package.xml | 2 +- .../src/node.cpp | 48 +- .../traffic_light_classifier/CMakeLists.txt | 37 +- perception/traffic_light_classifier/README.md | 55 +- .../classifier_interface.hpp | 7 +- .../cnn_classifier.hpp | 85 +-- .../color_classifier.hpp | 6 +- .../traffic_light_classifier/nodelet.hpp | 21 +- .../traffic_light_classifier.launch.xml | 19 +- .../traffic_light_classifier/package.xml | 7 +- .../src/cnn_classifier.cpp | 137 ++--- .../src/color_classifier.cpp | 36 +- .../traffic_light_classifier/src/nodelet.cpp | 12 +- .../src/single_image_debug_inference_node.cpp | 38 +- .../utils/trt_common.cpp | 170 ------ .../utils/trt_common.hpp | 142 ----- .../traffic_light_fine_detector/.gitignore | 1 + .../CMakeLists.txt | 156 ++++++ .../traffic_light_fine_detector/README.md | 66 +++ .../traffic_light_fine_detector/nodelet.hpp | 172 ++++++ .../traffic_light_fine_detector.launch.xml | 26 + .../traffic_light_fine_detector/package.xml | 29 + .../src/nodelet.cpp | 310 +++++++++++ .../README.md | 27 +- ...raffic_light_map_based_detector.param.yaml | 11 +- .../traffic_light_map_based_detector/node.hpp | 133 +++-- ...raffic_light_map_based_detector.launch.xml | 12 + .../package.xml | 6 +- .../src/node.cpp | 501 ++++++++++-------- .../CMakeLists.txt | 23 + .../README.md | 34 ++ ...affic_light_multi_camera_fusion.param.yaml | 6 + .../node.hpp | 131 +++++ ...affic_light_multi_camera_fusion.launch.xml | 12 + .../package.xml | 28 + .../src/node.cpp | 322 +++++++++++ perception/traffic_light_selector/README.md | 6 +- perception/traffic_light_selector/package.xml | 2 +- .../src/traffic_light_converter.cpp | 10 +- .../src/traffic_light_converter.hpp | 4 +- .../traffic_light_ssd_fine_detector/README.md | 16 +- .../nodelet.hpp | 17 +- .../package.xml | 2 +- .../src/nodelet.cpp | 17 +- .../traffic_light_visualization/README.md | 20 +- .../traffic_light_map_visualizer/node.hpp | 7 +- .../traffic_light_roi_visualizer/nodelet.hpp | 75 ++- .../traffic_light_visualization/package.xml | 3 +- .../src/traffic_light_map_visualizer/node.cpp | 26 +- .../traffic_light_roi_visualizer/nodelet.cpp | 48 +- 54 files changed, 2205 insertions(+), 1051 deletions(-) delete mode 100644 perception/traffic_light_classifier/utils/trt_common.cpp delete mode 100644 perception/traffic_light_classifier/utils/trt_common.hpp create mode 100644 perception/traffic_light_fine_detector/.gitignore create mode 100644 perception/traffic_light_fine_detector/CMakeLists.txt create mode 100644 perception/traffic_light_fine_detector/README.md create mode 100644 perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp create mode 100644 perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml create mode 100644 perception/traffic_light_fine_detector/package.xml create mode 100644 perception/traffic_light_fine_detector/src/nodelet.cpp create mode 100644 perception/traffic_light_multi_camera_fusion/CMakeLists.txt create mode 100644 perception/traffic_light_multi_camera_fusion/README.md create mode 100644 perception/traffic_light_multi_camera_fusion/config/traffic_light_multi_camera_fusion.param.yaml create mode 100644 perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp create mode 100644 perception/traffic_light_multi_camera_fusion/launch/traffic_light_multi_camera_fusion.launch.xml create mode 100644 perception/traffic_light_multi_camera_fusion/package.xml create mode 100644 perception/traffic_light_multi_camera_fusion/src/node.cpp diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml index 9e63832f5e522..ea50101719d65 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -2,30 +2,62 @@ - - - - + + - + + + + + + + + + + + + - + - + + + + + + + + + + + + + + + + + + + + + + + + - + - + + + + - - - @@ -33,13 +65,21 @@ - - - - + + + + - + + + + + + + + + diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py index a3fd412577e1f..964008dafa5cd 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py @@ -35,38 +35,39 @@ def add_launch_arg(name: str, default_value=None, description=None): DeclareLaunchArgument(name, default_value=default_value, description=description) ) - ssd_fine_detector_share_dir = get_package_share_directory("traffic_light_ssd_fine_detector") + fine_detector_share_dir = get_package_share_directory("traffic_light_fine_detector") classifier_share_dir = get_package_share_directory("traffic_light_classifier") add_launch_arg("enable_image_decompressor", "True") add_launch_arg("enable_fine_detection", "True") add_launch_arg("input/image", "/sensing/camera/traffic_light/image_raw") - # traffic_light_ssd_fine_detector + # traffic_light_fine_detector add_launch_arg( - "onnx_file", os.path.join(ssd_fine_detector_share_dir, "data", "mb2-ssd-lite-tlr.onnx") + "fine_detector_model_path", + os.path.join(fine_detector_share_dir, "data", "tlr_yolox_s.onnx"), ) add_launch_arg( - "label_file", os.path.join(ssd_fine_detector_share_dir, "data", "voc_labels_tl.txt") + "fine_detector_label_path", + os.path.join(fine_detector_share_dir, "data", "tlr_labels.txt"), ) - add_launch_arg("dnn_header_type", "pytorch") - add_launch_arg("fine_detector_precision", "FP32") - add_launch_arg("score_thresh", "0.7") - add_launch_arg("max_batch_size", "8") + add_launch_arg("fine_detector_precision", "fp16") + add_launch_arg("fine_detector_score_thresh", "0.3") + add_launch_arg("fine_detector_nms_thresh", "0.65") + add_launch_arg("approximate_sync", "False") - add_launch_arg("mean", "[0.5, 0.5, 0.5]") - add_launch_arg("std", "[0.5, 0.5, 0.5]") # traffic_light_classifier add_launch_arg("classifier_type", "1") add_launch_arg( - "model_file_path", - os.path.join(classifier_share_dir, "data", "traffic_light_classifier_mobilenetv2.onnx"), + "classifier_model_path", + os.path.join(classifier_share_dir, "data", "traffic_light_classifier_efficientNet_b1.onnx"), + ) + add_launch_arg( + "classifier_label_path", os.path.join(classifier_share_dir, "data", "lamp_labels.txt") ) - add_launch_arg("label_file_path", os.path.join(classifier_share_dir, "data", "lamp_labels.txt")) - add_launch_arg("precision", "fp16") - add_launch_arg("input_c", "3") - add_launch_arg("input_h", "224") - add_launch_arg("input_w", "224") + add_launch_arg("classifier_precision", "fp16") + add_launch_arg("classifier_mean", "[123.675, 116.28, 103.53]") + add_launch_arg("classifier_std", "[58.395, 57.12, 57.375]") add_launch_arg("use_crosswalk_traffic_light_estimator", "True") add_launch_arg("use_intra_process", "False") @@ -80,7 +81,7 @@ def create_parameter_dict(*args): container = ComposableNodeContainer( name="traffic_light_node_container", - namespace="/perception/traffic_light_recognition", + namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ @@ -92,12 +93,11 @@ def create_parameter_dict(*args): create_parameter_dict( "approximate_sync", "classifier_type", - "model_file_path", - "label_file_path", - "precision", - "input_c", - "input_h", - "input_w", + "classifier_model_path", + "classifier_label_path", + "classifier_precision", + "classifier_mean", + "classifier_std", ) ], remappings=[ @@ -195,28 +195,25 @@ def create_parameter_dict(*args): condition=IfCondition(LaunchConfiguration("enable_image_decompressor")), ) - ssd_fine_detector_param = create_parameter_dict( - "onnx_file", - "label_file", - "dnn_header_type", - "score_thresh", - "max_batch_size", - "approximate_sync", - "mean", - "std", + fine_detector_param = create_parameter_dict( + "fine_detector_model_path", + "fine_detector_label_path", + "fine_detector_precision", + "fine_detector_score_thresh", + "fine_detector_nms_thresh", ) - ssd_fine_detector_param["mode"] = LaunchConfiguration("fine_detector_precision") fine_detector_loader = LoadComposableNodes( composable_node_descriptions=[ ComposableNode( - package="traffic_light_ssd_fine_detector", - plugin="traffic_light::TrafficLightSSDFineDetectorNodelet", - name="traffic_light_ssd_fine_detector", - parameters=[ssd_fine_detector_param], + package="traffic_light_fine_detector", + plugin="traffic_light::TrafficLightFineDetectorNodelet", + name="traffic_light_fine_detector", + parameters=[fine_detector_param], remappings=[ ("~/input/image", LaunchConfiguration("input/image")), ("~/input/rois", "rough/rois"), + ("~/expect/rois", "expect/rois"), ("~/output/rois", "rois"), ], extra_arguments=[ diff --git a/perception/crosswalk_traffic_light_estimator/README.md b/perception/crosswalk_traffic_light_estimator/README.md index 54d7c561e05c2..e23b454905081 100644 --- a/perception/crosswalk_traffic_light_estimator/README.md +++ b/perception/crosswalk_traffic_light_estimator/README.md @@ -8,17 +8,17 @@ ### Input -| Name | Type | Description | -| ------------------------------------ | -------------------------------------------------------- | ------------------ | -| `~/input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | -| `~/input/route` | `autoware_planning_msgs::msg::LaneletRoute` | route | -| `~/input/classified/traffic_signals` | `autoware_auto_perception_msgs::msg::TrafficSignalArray` | classified signals | +| Name | Type | Description | +| ------------------------------------ | ------------------------------------------------ | ------------------ | +| `~/input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | +| `~/input/route` | `autoware_planning_msgs::msg::LaneletRoute` | route | +| `~/input/classified/traffic_signals` | `tier4_perception_msgs::msg::TrafficSignalArray` | classified signals | ### Output -| Name | Type | Description | -| -------------------------- | -------------------------------------------------------- | --------------------------------------------------------- | -| `~/output/traffic_signals` | `autoware_auto_perception_msgs::msg::TrafficSignalArray` | output that contains estimated pedestrian traffic signals | +| Name | Type | Description | +| -------------------------- | ------------------------------------------------ | --------------------------------------------------------- | +| `~/output/traffic_signals` | `tier4_perception_msgs::msg::TrafficSignalArray` | output that contains estimated pedestrian traffic signals | ## Parameters diff --git a/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp b/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp index 852e99ff7ba54..0850436851e6a 100644 --- a/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp +++ b/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp @@ -22,11 +22,11 @@ #include #include -#include -#include -#include #include #include +#include +#include +#include #include #include @@ -43,13 +43,13 @@ namespace traffic_light { using autoware_auto_mapping_msgs::msg::HADMapBin; -using autoware_auto_perception_msgs::msg::TrafficLight; -using autoware_auto_perception_msgs::msg::TrafficSignal; -using autoware_auto_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; using tier4_autoware_utils::DebugPublisher; using tier4_autoware_utils::StopWatch; using tier4_debug_msgs::msg::Float64Stamped; +using tier4_perception_msgs::msg::TrafficLightElement; +using tier4_perception_msgs::msg::TrafficSignal; +using tier4_perception_msgs::msg::TrafficSignalArray; using TrafficSignalAndTime = std::pair; using TrafficLightIdMap = std::unordered_map; diff --git a/perception/crosswalk_traffic_light_estimator/package.xml b/perception/crosswalk_traffic_light_estimator/package.xml index 1a3b90f617f4e..435ecf6e6fa3d 100644 --- a/perception/crosswalk_traffic_light_estimator/package.xml +++ b/perception/crosswalk_traffic_light_estimator/package.xml @@ -11,13 +11,13 @@ autoware_cmake autoware_auto_mapping_msgs - autoware_auto_perception_msgs autoware_auto_planning_msgs autoware_planning_msgs lanelet2_extension rclcpp rclcpp_components tier4_autoware_utils + tier4_perception_msgs ament_lint_auto autoware_lint_common diff --git a/perception/crosswalk_traffic_light_estimator/src/node.cpp b/perception/crosswalk_traffic_light_estimator/src/node.cpp index 8400a1708e6af..55d272cb71cfe 100644 --- a/perception/crosswalk_traffic_light_estimator/src/node.cpp +++ b/perception/crosswalk_traffic_light_estimator/src/node.cpp @@ -160,7 +160,7 @@ void CrosswalkTrafficLightEstimatorNode::onTrafficLightArray( TrafficLightIdMap traffic_light_id_map; for (const auto & traffic_signal : msg->signals) { - traffic_light_id_map[traffic_signal.map_primitive_id] = + traffic_light_id_map[traffic_signal.traffic_light_id] = std::pair(traffic_signal, get_clock()->now()); } @@ -185,17 +185,17 @@ void CrosswalkTrafficLightEstimatorNode::updateLastDetectedSignal( const TrafficLightIdMap & traffic_light_id_map) { for (const auto & input_traffic_signal : traffic_light_id_map) { - const auto & lights = input_traffic_signal.second.first.lights; + const auto & elements = input_traffic_signal.second.first.elements; - if (lights.empty()) { + if (elements.empty()) { continue; } - if (lights.front().color == TrafficLight::UNKNOWN) { + if (elements.front().color == TrafficLightElement::UNKNOWN) { continue; } - const auto & id = input_traffic_signal.second.first.map_primitive_id; + const auto & id = input_traffic_signal.second.first.traffic_light_id; if (last_detect_color_.count(id) == 0) { last_detect_color_.insert(std::make_pair(id, input_traffic_signal.second)); @@ -207,7 +207,7 @@ void CrosswalkTrafficLightEstimatorNode::updateLastDetectedSignal( std::vector erase_id_list; for (auto & last_traffic_signal : last_detect_color_) { - const auto & id = last_traffic_signal.second.first.map_primitive_id; + const auto & id = last_traffic_signal.second.first.traffic_light_id; if (traffic_light_id_map.count(id) == 0) { // hold signal recognition results for [last_detect_color_hold_time_] seconds. @@ -233,11 +233,11 @@ void CrosswalkTrafficLightEstimatorNode::setCrosswalkTrafficSignal( const auto ll_traffic_light = static_cast(traffic_light); TrafficSignal output_traffic_signal; - TrafficLight output_traffic_light; + TrafficLightElement output_traffic_light; output_traffic_light.color = color; output_traffic_light.confidence = 1.0; - output_traffic_signal.lights.push_back(output_traffic_light); - output_traffic_signal.map_primitive_id = ll_traffic_light.id(); + output_traffic_signal.elements.push_back(output_traffic_light); + output_traffic_signal.traffic_light_id = ll_traffic_light.id(); msg.signals.push_back(output_traffic_signal); } } @@ -265,13 +265,14 @@ lanelet::ConstLanelets CrosswalkTrafficLightEstimatorNode::getNonRedLanelets( continue; } - const auto current_is_not_red = current_detected_signal - ? current_detected_signal.get() == TrafficLight::GREEN || - current_detected_signal.get() == TrafficLight::AMBER - : true; + const auto current_is_not_red = + current_detected_signal ? current_detected_signal.get() == TrafficLightElement::GREEN || + current_detected_signal.get() == TrafficLightElement::AMBER + : true; const auto current_is_unknown_or_none = - current_detected_signal ? current_detected_signal.get() == TrafficLight::UNKNOWN : true; + current_detected_signal ? current_detected_signal.get() == TrafficLightElement::UNKNOWN + : true; const auto last_detected_signal = getHighestConfidenceTrafficSignal(traffic_lights_for_vehicle, last_detect_color_); @@ -281,8 +282,8 @@ lanelet::ConstLanelets CrosswalkTrafficLightEstimatorNode::getNonRedLanelets( } const auto was_not_red = current_is_unknown_or_none && - (last_detected_signal.get() == TrafficLight::GREEN || - last_detected_signal.get() == TrafficLight::AMBER) && + (last_detected_signal.get() == TrafficLightElement::GREEN || + last_detected_signal.get() == TrafficLightElement::AMBER) && use_last_detect_color_; if (!current_is_not_red && !was_not_red) { @@ -323,12 +324,13 @@ uint8_t CrosswalkTrafficLightEstimatorNode::estimateCrosswalkTrafficSignal( } if (has_straight_non_red_lane || has_related_non_red_tl) { - return TrafficLight::RED; + return TrafficLightElement::RED; } const auto has_merge_lane = hasMergeLane(non_red_lanelets, routing_graph_ptr_); - return !has_merge_lane && has_left_non_red_lane && has_right_non_red_lane ? TrafficLight::RED - : TrafficLight::UNKNOWN; + return !has_merge_lane && has_left_non_red_lane && has_right_non_red_lane + ? TrafficLightElement::RED + : TrafficLightElement::UNKNOWN; } boost::optional CrosswalkTrafficLightEstimatorNode::getHighestConfidenceTrafficSignal( @@ -348,13 +350,13 @@ boost::optional CrosswalkTrafficLightEstimatorNode::getHighestConfidenc continue; } - const auto & lights = traffic_light_id_map.at(id).first.lights; - if (lights.empty()) { + const auto & elements = traffic_light_id_map.at(id).first.elements; + if (elements.empty()) { continue; } - const auto & color = lights.front().color; - const auto & confidence = lights.front().confidence; + const auto & color = elements.front().color; + const auto & confidence = elements.front().confidence; if (confidence < highest_confidence) { continue; } diff --git a/perception/traffic_light_classifier/CMakeLists.txt b/perception/traffic_light_classifier/CMakeLists.txt index e125abc7b435a..aeea36ecde047 100644 --- a/perception/traffic_light_classifier/CMakeLists.txt +++ b/perception/traffic_light_classifier/CMakeLists.txt @@ -84,14 +84,14 @@ function(download FILE_NAME FILE_HASH) else() message(STATUS "diff ${FILE_NAME}") message(STATUS "File hash changes. Downloading now ...") - file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) + file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/traffic_light_classifier/v1/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) list(GET DOWNLOAD_STATUS 0 STATUS_CODE) list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) endif() else() message(STATUS "not found ${FILE_NAME}") message(STATUS "File doesn't exists. Downloading now ...") - file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) + file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/traffic_light_classifier/v1/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) list(GET DOWNLOAD_STATUS 0 STATUS_CODE) list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) endif() @@ -101,8 +101,9 @@ function(download FILE_NAME FILE_HASH) message(FATAL_ERROR "Error occurred during download: ${ERROR_MESSAGE}") endif() endfunction() -download(traffic_light_classifier_mobilenetv2.onnx 7dc31c696b0400ddfc2cc5521586fa51) -download(lamp_labels.txt 20167c8e9a1f9d2ec7b0b0088c4100f0) +download(traffic_light_classifier_mobilenetv2.onnx caa51f2080aa2df943e4f884c41898eb) +download(traffic_light_classifier_efficientNet_b1.onnx 82baba4fcf1abe0c040cd55005e34510) +download(lamp_labels.txt 4b2cf910d97d05d464e7c26901af3d4c) find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() @@ -113,15 +114,16 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) add_definitions(-DENABLE_GPU) include_directories( - utils ${OpenCV_INCLUDE_DIRS} ${CUDA_INCLUDE_DIRS} ) - ament_auto_add_library(libutils SHARED - utils/trt_common.cpp + ament_auto_add_library(traffic_light_classifier_nodelet SHARED + src/color_classifier.cpp + src/cnn_classifier.cpp + src/nodelet.cpp ) - target_link_libraries(libutils + target_link_libraries(traffic_light_classifier_nodelet ${OpenCV_LIBRARIES} ${NVINFER} ${NVONNXPARSER} @@ -131,16 +133,6 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) ${CUDNN_LIBRARY} stdc++fs ) - - ament_auto_add_library(traffic_light_classifier_nodelet SHARED - src/color_classifier.cpp - src/cnn_classifier.cpp - src/nodelet.cpp - ) - target_link_libraries(traffic_light_classifier_nodelet - libutils - ${OpenCV_LIBRARIES} - ) rclcpp_components_register_node(traffic_light_classifier_nodelet PLUGIN "traffic_light::TrafficLightClassifierNodelet" EXECUTABLE traffic_light_classifier_node @@ -153,7 +145,14 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) src/single_image_debug_inference_node.cpp ) target_link_libraries(single_image_debug_inference_node - libutils + ${OpenCV_LIBRARIES} + ${NVINFER} + ${NVONNXPARSER} + ${NVINFER_PLUGIN} + ${CUDA_LIBRARIES} + ${CUBLAS_LIBRARIES} + ${CUDNN_LIBRARY} + stdc++fs opencv_core opencv_highgui ) diff --git a/perception/traffic_light_classifier/README.md b/perception/traffic_light_classifier/README.md index 0935a451862e1..e2faf1633d331 100644 --- a/perception/traffic_light_classifier/README.md +++ b/perception/traffic_light_classifier/README.md @@ -8,8 +8,14 @@ traffic_light_classifier is a package for classifying traffic light labels using ### cnn_classifier -Traffic light labels are classified by MobileNetV2. -Totally 37600 (26300 for training, 6800 for evaluation and 4500 for test) TIER IV internal images of Japanese traffic lights were used for fine-tuning. +Traffic light labels are classified by EfficientNet-b1 or MobiletNet-v2. +Totally 83400 (58600 for training, 14800 for evaluation and 10000 for test) TIER IV internal images of Japanese traffic lights were used for fine-tuning. +The information of the models is listed here: + +| Name | Input Size | Test Accuracy | +| --------------- | ---------- | ------------- | +| EfficientNet-b1 | 128 x 128 | 99.76% | +| MobileNet-v2 | 224 x 224 | 99.81% | ### hsv_classifier @@ -30,17 +36,17 @@ These colors and shapes are assigned to the message as follows: ### Input -| Name | Type | Description | -| --------------- | ---------------------------------------------------------- | ---------------------- | -| `~/input/image` | `sensor_msgs::msg::Image` | input image | -| `~/input/rois` | `autoware_auto_perception_msgs::msg::TrafficLightRoiArray` | rois of traffic lights | +| Name | Type | Description | +| --------------- | -------------------------------------------------- | ---------------------- | +| `~/input/image` | `sensor_msgs::msg::Image` | input image | +| `~/input/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | rois of traffic lights | ### Output -| Name | Type | Description | -| -------------------------- | -------------------------------------------------------- | ------------------- | -| `~/output/traffic_signals` | `autoware_auto_perception_msgs::msg::TrafficSignalArray` | classified signals | -| `~/output/debug/image` | `sensor_msgs::msg::Image` | image for debugging | +| Name | Type | Description | +| -------------------------- | ------------------------------------------------ | ------------------- | +| `~/output/traffic_signals` | `tier4_perception_msgs::msg::TrafficSignalArray` | classified signals | +| `~/output/debug/image` | `sensor_msgs::msg::Image` | image for debugging | ## Parameters @@ -54,19 +60,14 @@ These colors and shapes are assigned to the message as follows: #### cnn_classifier -| Name | Type | Description | -| ----------------- | ------ | ------------------------------------------------- | -| `model_file_path` | str | path to the model file | -| `label_file_path` | str | path to the label file | -| `precision` | str | TensorRT precision, `fp16` or `int8` | -| `input_c` | str | the channel size of an input image | -| `input_h` | str | the height of an input image | -| `input_w` | str | the width of an input image | -| `input_name` | str | the name of neural network's input layer | -| `output_name` | str | the name of neural network's output name | -| `mean` | double | mean values for image normalization | -| `std` | double | std values for image normalization | -| `build_only` | bool | shutdown node after TensorRT engine file is built | +| Name | Type | Description | +| ----------------------- | --------------- | ------------------------------------ | +| `classifier_label_path` | str | path to the model file | +| `classifier_model_path` | str | path to the label file | +| `classifier_precision` | str | TensorRT precision, `fp16` or `int8` | +| `classifier_mean` | vector\ | 3-channel input image mean | +| `classifier_std` | vector\ | 3-channel input image std | +| `apply_softmax` | bool | whether or not apply softmax | #### hsv_classifier @@ -93,10 +94,10 @@ These colors and shapes are assigned to the message as follows: ## Customization of CNN model -Currently, in Autoware, [MobileNetV2](https://arxiv.org/abs/1801.04381v3) is used as CNN classifier by default. The corresponding onnx file is `data/traffic_light_classifier_mobilenetv2.onnx`(This file will be downloaded during the build process). +Currently, in Autoware, [MobileNetV2](https://arxiv.org/abs/1801.04381v3) and [EfficientNet-b1](https://arxiv.org/abs/1905.11946v5) are provided. +The corresponding onnx files are `data/traffic_light_classifier_mobilenetv2.onnx` and `data/traffic_light_classifier_efficientNet_b1.onnx` (These files will be downloaded during the build process). Also, you can apply the following models shown as below, for example. -- [EfficientNet](https://arxiv.org/abs/1905.11946v5) - [ResNet](https://openaccess.thecvf.com/content_cvpr_2016/html/He_Deep_Residual_Learning_CVPR_2016_paper.html) - [MobileNetV3](https://arxiv.org/abs/1905.02244) ... @@ -153,7 +154,7 @@ python3 pytorch2onnx.py YOUR_CONFIG.py ... ``` After obtaining your onnx model, update parameters defined in the launch file (e.g. `model_file_path`, `label_file_path`, `input_h`, `input_w`...). -Note that, we only support labels defined in [autoware_auto_perception_msgs::msg::TrafficLight](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_perception_msgs/msg/TrafficLight.idl). +Note that, we only support labels defined in [tier4_perception_msgs::msg::TrafficLightElement](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_perception_msgs/msg/traffic_light/TrafficLightElement.msg). ## Assumptions / Known limits @@ -191,6 +192,8 @@ Example: [1] M. Sandler, A. Howard, M. Zhu, A. Zhmoginov and L. Chen, "MobileNetV2: Inverted Residuals and Linear Bottlenecks," 2018 IEEE/CVF Conference on Computer Vision and Pattern Recognition, Salt Lake City, UT, 2018, pp. 4510-4520, doi: 10.1109/CVPR.2018.00474. +[2] Tan, Mingxing, and Quoc Le. "Efficientnet: Rethinking model scaling for convolutional neural networks." International conference on machine learning. PMLR, 2019. + ## (Optional) Future extensions / Unimplemented parts @@ -17,17 +16,9 @@ - - - - - - - - - - - + + + diff --git a/perception/traffic_light_classifier/package.xml b/perception/traffic_light_classifier/package.xml index 2f7b07962a23b..89129cf0fe9d4 100644 --- a/perception/traffic_light_classifier/package.xml +++ b/perception/traffic_light_classifier/package.xml @@ -9,10 +9,11 @@ Apache License 2.0 ament_cmake_auto - autoware_cmake wget - autoware_auto_perception_msgs + autoware_cmake + + cuda_utils cv_bridge image_transport libboost-filesystem-dev @@ -20,6 +21,8 @@ rclcpp rclcpp_components sensor_msgs + tensorrt_common + tier4_perception_msgs ament_cmake diff --git a/perception/traffic_light_classifier/src/cnn_classifier.cpp b/perception/traffic_light_classifier/src/cnn_classifier.cpp index 621466206ac01..45ef5f94af146 100644 --- a/perception/traffic_light_classifier/src/cnn_classifier.cpp +++ b/perception/traffic_light_classifier/src/cnn_classifier.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// 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. @@ -33,23 +33,41 @@ CNNClassifier::CNNClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr) std::string precision; std::string label_file_path; std::string model_file_path; - precision = node_ptr_->declare_parameter("precision", "fp16"); - label_file_path = node_ptr_->declare_parameter("label_file_path", "labels.txt"); - model_file_path = node_ptr_->declare_parameter("model_file_path", "model.onnx"); - input_c_ = node_ptr_->declare_parameter("input_c", 3); - input_h_ = node_ptr_->declare_parameter("input_h", 224); - input_w_ = node_ptr_->declare_parameter("input_w", 224); - mean_ = node_ptr_->declare_parameter("mean", std::vector({0.242, 0.193, 0.201})); - std_ = node_ptr_->declare_parameter("std", std::vector({1.0, 1.0, 1.0})); - std::string input_name = node_ptr_->declare_parameter("input_name", std::string("input_0")); - std::string output_name = node_ptr_->declare_parameter("output_name", std::string("output_0")); - apply_softmax_ = node_ptr_->declare_parameter("apply_softmax", true); + precision = node_ptr_->declare_parameter("classifier_precision", "fp16"); + label_file_path = node_ptr_->declare_parameter("classifier_label_path", "labels.txt"); + model_file_path = node_ptr_->declare_parameter("classifier_model_path", "model.onnx"); + apply_softmax_ = node_ptr_->declare_parameter("apply_softmax", false); + mean_ = + node_ptr->declare_parameter("classifier_mean", std::vector{123.675, 116.28, 103.53}); + std_ = node_ptr->declare_parameter("classifier_std", std::vector{58.395, 57.12, 57.375}); + if (mean_.size() != 3 || std_.size() != 3) { + RCLCPP_ERROR(node_ptr->get_logger(), "classifier_mean and classifier_std must be of size 3"); + return; + } readLabelfile(label_file_path, labels_); - trt_ = std::make_shared(model_file_path, precision, input_name, output_name); - trt_->setup(); + tensorrt_common::BatchConfig batch_config{1, 1, 1}; + size_t max_workspace_size = 1 << 30; + trt_common_ = std::make_unique( + model_file_path, precision, nullptr, batch_config, max_workspace_size); + trt_common_->setup(); + if (!trt_common_->isInitialized()) { + return; + } + const auto input_dims = trt_common_->getBindingDimensions(0); + if (input_dims.nbDims != 4) { + RCLCPP_ERROR(node_ptr_->get_logger(), "Model input dimension must be 4!"); + } + batch_size_ = input_dims.d[0]; + input_c_ = input_dims.d[1]; + input_h_ = input_dims.d[2]; + input_w_ = input_dims.d[3]; + num_input_ = batch_size_ * input_c_ * input_h_ * input_w_; + const auto output_dims = trt_common_->getBindingDimensions(1); + num_output_ = + std::accumulate(output_dims.d, output_dims.d + output_dims.nbDims, 1, std::multiplies()); if (node_ptr_->declare_parameter("build_only", false)) { RCLCPP_INFO(node_ptr_->get_logger(), "TensorRT engine is built and shutdown node."); rclcpp::shutdown(); @@ -57,36 +75,33 @@ CNNClassifier::CNNClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr) } bool CNNClassifier::getTrafficSignal( - const cv::Mat & input_image, autoware_auto_perception_msgs::msg::TrafficSignal & traffic_signal) + const cv::Mat & input_image, tier4_perception_msgs::msg::TrafficSignal & traffic_signal) { - if (!trt_->isInitialized()) { + if (!trt_common_->isInitialized()) { RCLCPP_WARN(node_ptr_->get_logger(), "failed to init tensorrt"); return false; } - int num_input = trt_->getNumInput(); - int num_output = trt_->getNumOutput(); - - std::vector input_data_host(num_input); + std::vector input_data_host(num_input_); cv::Mat image = input_image.clone(); preProcess(image, input_data_host, true); - auto input_data_device = Tn::make_unique(num_input); + auto input_data_device = cuda_utils::make_unique(num_input_); cudaMemcpy( - input_data_device.get(), input_data_host.data(), num_input * sizeof(float), + input_data_device.get(), input_data_host.data(), num_input_ * sizeof(float), cudaMemcpyHostToDevice); - auto output_data_device = Tn::make_unique(num_output); + auto output_data_device = cuda_utils::make_unique(num_output_); // do inference std::vector bindings = {input_data_device.get(), output_data_device.get()}; - trt_->context_->executeV2(bindings.data()); + trt_common_->enqueueV2(bindings.data(), *stream_, nullptr); - std::vector output_data_host(num_output); + std::vector output_data_host(num_output_); cudaMemcpy( - output_data_host.data(), output_data_device.get(), num_output * sizeof(float), + output_data_host.data(), output_data_device.get(), num_output_ * sizeof(float), cudaMemcpyDeviceToHost); postProcess(output_data_host, traffic_signal, apply_softmax_); @@ -101,17 +116,17 @@ bool CNNClassifier::getTrafficSignal( } void CNNClassifier::outputDebugImage( - cv::Mat & debug_image, const autoware_auto_perception_msgs::msg::TrafficSignal & traffic_signal) + cv::Mat & debug_image, const tier4_perception_msgs::msg::TrafficSignal & traffic_signal) { float probability; std::string label; - for (std::size_t i = 0; i < traffic_signal.lights.size(); i++) { - auto light = traffic_signal.lights.at(i); + for (std::size_t i = 0; i < traffic_signal.elements.size(); i++) { + auto light = traffic_signal.elements.at(i); const auto light_label = state2label_[light.color] + "-" + state2label_[light.shape]; label += light_label; // all lamp confidence are the same probability = light.confidence; - if (i < traffic_signal.lights.size() - 1) { + if (i < traffic_signal.elements.size() - 1) { label += ","; } } @@ -134,11 +149,13 @@ void CNNClassifier::outputDebugImage( void CNNClassifier::preProcess(cv::Mat & image, std::vector & input_tensor, bool normalize) { - /* normalize */ - /* ((channel[0] / 255) - mean[0]) / std[0] */ - - // cv::cvtColor(image, image, cv::COLOR_BGR2RGB, 3); - cv::resize(image, image, cv::Size(input_w_, input_h_)); + const float scale = + std::min(static_cast(input_w_) / image.cols, static_cast(input_h_) / image.rows); + const auto scale_size = cv::Size(image.cols * scale, image.rows * scale); + cv::resize(image, image, scale_size, 0, 0, cv::INTER_CUBIC); + const auto bottom = input_h_ - image.rows; + const auto right = input_w_ - image.cols; + copyMakeBorder(image, image, 0, bottom, 0, right, cv::BORDER_CONSTANT, {0, 0, 0}); const size_t strides_cv[3] = { static_cast(input_w_ * input_c_), static_cast(input_c_), 1}; @@ -151,8 +168,7 @@ void CNNClassifier::preProcess(cv::Mat & image, std::vector & input_tenso const size_t offset_cv = i * strides_cv[0] + j * strides_cv[1] + k * strides_cv[2]; const size_t offset = k * strides[0] + i * strides[1] + j * strides[2]; if (normalize) { - input_tensor[offset] = - ((static_cast(image.data[offset_cv]) / 255) - mean_[k]) / std_[k]; + input_tensor[offset] = (static_cast(image.data[offset_cv]) - mean_[k]) / std_[k]; } else { input_tensor[offset] = static_cast(image.data[offset_cv]); } @@ -162,19 +178,14 @@ void CNNClassifier::preProcess(cv::Mat & image, std::vector & input_tenso } bool CNNClassifier::postProcess( - std::vector & output_tensor, - autoware_auto_perception_msgs::msg::TrafficSignal & traffic_signal, bool apply_softmax) + std::vector & output_tensor, tier4_perception_msgs::msg::TrafficSignal & traffic_signal, + bool apply_softmax) { std::vector probs; - int num_output = trt_->getNumOutput(); if (apply_softmax) { - calcSoftmax(output_tensor, probs, num_output); + calcSoftmax(output_tensor, probs, num_output_); } - std::vector sorted_indices = argsort(output_tensor, num_output); - - // ROS_INFO("label: %s, score: %.2f\%", - // labels_[sorted_indices[0]].c_str(), - // probs[sorted_indices[0]] * 100); + std::vector sorted_indices = argsort(output_tensor, num_output_); size_t max_indice = sorted_indices.front(); std::string match_label = labels_[max_indice]; @@ -194,27 +205,27 @@ bool CNNClassifier::postProcess( node_ptr_->get_logger(), "cnn_classifier does not have a key [%s]", label.c_str()); continue; } - autoware_auto_perception_msgs::msg::TrafficLight light; + tier4_perception_msgs::msg::TrafficLightElement element; if (label.find("-") != std::string::npos) { // found "-" delimiter in label string std::vector color_and_shape; boost::algorithm::split(color_and_shape, label, boost::is_any_of("-")); - light.color = label2state_[color_and_shape.at(0)]; - light.shape = label2state_[color_and_shape.at(1)]; + element.color = label2state_[color_and_shape.at(0)]; + element.shape = label2state_[color_and_shape.at(1)]; } else { - if (label == state2label_[autoware_auto_perception_msgs::msg::TrafficLight::UNKNOWN]) { - light.color = autoware_auto_perception_msgs::msg::TrafficLight::UNKNOWN; - light.shape = autoware_auto_perception_msgs::msg::TrafficLight::UNKNOWN; + if (label == state2label_[tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN]) { + element.color = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + element.shape = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; } else if (isColorLabel(label)) { - light.color = label2state_[label]; - light.shape = autoware_auto_perception_msgs::msg::TrafficLight::CIRCLE; + element.color = label2state_[label]; + element.shape = tier4_perception_msgs::msg::TrafficLightElement::CIRCLE; } else { - light.color = autoware_auto_perception_msgs::msg::TrafficLight::GREEN; - light.shape = label2state_[label]; + element.color = tier4_perception_msgs::msg::TrafficLightElement::GREEN; + element.shape = label2state_[label]; } } - light.confidence = probability; - traffic_signal.lights.push_back(light); + element.confidence = probability; + traffic_signal.elements.push_back(element); } return true; @@ -262,12 +273,12 @@ std::vector CNNClassifier::argsort(std::vector & tensor, int num_ bool CNNClassifier::isColorLabel(const std::string label) { - using autoware_auto_perception_msgs::msg::TrafficSignal; + using tier4_perception_msgs::msg::TrafficSignal; if ( - label == state2label_[autoware_auto_perception_msgs::msg::TrafficLight::GREEN] || - label == state2label_[autoware_auto_perception_msgs::msg::TrafficLight::AMBER] || - label == state2label_[autoware_auto_perception_msgs::msg::TrafficLight::RED] || - label == state2label_[autoware_auto_perception_msgs::msg::TrafficLight::WHITE]) { + label == state2label_[tier4_perception_msgs::msg::TrafficLightElement::GREEN] || + label == state2label_[tier4_perception_msgs::msg::TrafficLightElement::AMBER] || + label == state2label_[tier4_perception_msgs::msg::TrafficLightElement::RED] || + label == state2label_[tier4_perception_msgs::msg::TrafficLightElement::WHITE]) { return true; } return false; diff --git a/perception/traffic_light_classifier/src/color_classifier.cpp b/perception/traffic_light_classifier/src/color_classifier.cpp index 0267b3cd3c3ac..4b7fb37096021 100644 --- a/perception/traffic_light_classifier/src/color_classifier.cpp +++ b/perception/traffic_light_classifier/src/color_classifier.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// 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. @@ -52,7 +52,7 @@ ColorClassifier::ColorClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr) } bool ColorClassifier::getTrafficSignal( - const cv::Mat & input_image, autoware_auto_perception_msgs::msg::TrafficSignal & traffic_signal) + const cv::Mat & input_image, tier4_perception_msgs::msg::TrafficSignal & traffic_signal) { cv::Mat green_image; cv::Mat yellow_image; @@ -157,25 +157,25 @@ bool ColorClassifier::getTrafficSignal( static_cast(red_filtered_bin_image.rows * red_filtered_bin_image.cols); if (yellow_ratio < green_ratio && red_ratio < green_ratio) { - autoware_auto_perception_msgs::msg::TrafficLight light; - light.color = autoware_auto_perception_msgs::msg::TrafficLight::GREEN; - light.confidence = std::min(1.0, static_cast(green_pixel_num) / (20.0 * 20.0)); - traffic_signal.lights.push_back(light); + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = tier4_perception_msgs::msg::TrafficLightElement::GREEN; + element.confidence = std::min(1.0, static_cast(green_pixel_num) / (20.0 * 20.0)); + traffic_signal.elements.push_back(element); } else if (green_ratio < yellow_ratio && red_ratio < yellow_ratio) { - autoware_auto_perception_msgs::msg::TrafficLight light; - light.color = autoware_auto_perception_msgs::msg::TrafficLight::AMBER; - light.confidence = std::min(1.0, static_cast(yellow_pixel_num) / (20.0 * 20.0)); - traffic_signal.lights.push_back(light); + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = tier4_perception_msgs::msg::TrafficLightElement::AMBER; + element.confidence = std::min(1.0, static_cast(yellow_pixel_num) / (20.0 * 20.0)); + traffic_signal.elements.push_back(element); } else if (green_ratio < red_ratio && yellow_ratio < red_ratio) { - autoware_auto_perception_msgs::msg::TrafficLight light; - light.color = ::autoware_auto_perception_msgs::msg::TrafficLight::RED; - light.confidence = std::min(1.0, static_cast(red_pixel_num) / (20.0 * 20.0)); - traffic_signal.lights.push_back(light); + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = ::tier4_perception_msgs::msg::TrafficLightElement::RED; + element.confidence = std::min(1.0, static_cast(red_pixel_num) / (20.0 * 20.0)); + traffic_signal.elements.push_back(element); } else { - autoware_auto_perception_msgs::msg::TrafficLight light; - light.color = ::autoware_auto_perception_msgs::msg::TrafficLight::UNKNOWN; - light.confidence = 0.0; - traffic_signal.lights.push_back(light); + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = ::tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + element.confidence = 0.0; + traffic_signal.elements.push_back(element); } return true; } diff --git a/perception/traffic_light_classifier/src/nodelet.cpp b/perception/traffic_light_classifier/src/nodelet.cpp index a593f34fd8273..5332f5d3baacc 100644 --- a/perception/traffic_light_classifier/src/nodelet.cpp +++ b/perception/traffic_light_classifier/src/nodelet.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// 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. @@ -37,7 +37,7 @@ TrafficLightClassifierNodelet::TrafficLightClassifierNodelet(const rclcpp::NodeO } traffic_signal_array_pub_ = - this->create_publisher( + this->create_publisher( "~/output/traffic_signals", rclcpp::QoS{1}); using std::chrono_literals::operator""ms; @@ -74,7 +74,7 @@ void TrafficLightClassifierNodelet::connectCb() void TrafficLightClassifierNodelet::imageRoiCallback( const sensor_msgs::msg::Image::ConstSharedPtr & input_image_msg, - const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_rois_msg) + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_rois_msg) { if (classifier_ptr_.use_count() == 0) { return; @@ -89,15 +89,15 @@ void TrafficLightClassifierNodelet::imageRoiCallback( input_image_msg->encoding.c_str()); } - autoware_auto_perception_msgs::msg::TrafficSignalArray output_msg; + tier4_perception_msgs::msg::TrafficSignalArray output_msg; for (size_t i = 0; i < input_rois_msg->rois.size(); ++i) { const sensor_msgs::msg::RegionOfInterest & roi = input_rois_msg->rois.at(i).roi; cv::Mat clipped_image( cv_ptr->image, cv::Rect(roi.x_offset, roi.y_offset, roi.width, roi.height)); - autoware_auto_perception_msgs::msg::TrafficSignal traffic_signal; - traffic_signal.map_primitive_id = input_rois_msg->rois.at(i).id; + tier4_perception_msgs::msg::TrafficSignal traffic_signal; + traffic_signal.traffic_light_id = input_rois_msg->rois.at(i).traffic_light_id; if (!classifier_ptr_->getTrafficSignal(clipped_image, traffic_signal)) { RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback"); return; diff --git a/perception/traffic_light_classifier/src/single_image_debug_inference_node.cpp b/perception/traffic_light_classifier/src/single_image_debug_inference_node.cpp index f324b04f1628c..10d36978224ab 100644 --- a/perception/traffic_light_classifier/src/single_image_debug_inference_node.cpp +++ b/perception/traffic_light_classifier/src/single_image_debug_inference_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// 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. @@ -28,31 +28,31 @@ namespace { std::string toString(const uint8_t state) { - if (state == autoware_auto_perception_msgs::msg::TrafficLight::RED) { + if (state == tier4_perception_msgs::msg::TrafficLightElement::RED) { return "red"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::AMBER) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::AMBER) { return "yellow"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::GREEN) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::GREEN) { return "green"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::WHITE) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::WHITE) { return "white"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::CIRCLE) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::CIRCLE) { return "circle"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::LEFT_ARROW) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::LEFT_ARROW) { return "left"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::RIGHT_ARROW) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::RIGHT_ARROW) { return "right"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::UP_ARROW) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::UP_ARROW) { return "straight"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::DOWN_ARROW) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::DOWN_ARROW) { return "down"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::DOWN_LEFT_ARROW) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::DOWN_LEFT_ARROW) { return "down_left"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::DOWN_RIGHT_ARROW) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::DOWN_RIGHT_ARROW) { return "down_right"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::CROSS) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::CROSS) { return "cross"; - } else if (state == autoware_auto_perception_msgs::msg::TrafficLight::UNKNOWN) { + } else if (state == tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN) { return "unknown"; } else { return ""; @@ -122,17 +122,17 @@ class SingleImageDebugInferenceNode : public rclcpp::Node return; } cv::cvtColor(crop, crop, cv::COLOR_BGR2RGB); - autoware_auto_perception_msgs::msg::TrafficSignal traffic_signal; + tier4_perception_msgs::msg::TrafficSignal traffic_signal; if (!classifier_ptr_->getTrafficSignal(crop, traffic_signal)) { RCLCPP_ERROR(get_logger(), "failed to classify image"); return; } cv::Scalar color; cv::Scalar text_color; - for (const auto & light : traffic_signal.lights) { - auto color_str = toString(light.color); - auto shape_str = toString(light.shape); - auto confidence_str = std::to_string(light.confidence); + for (const auto & element : traffic_signal.elements) { + auto color_str = toString(element.color); + auto shape_str = toString(element.shape); + auto confidence_str = std::to_string(element.confidence); if (shape_str == "circle") { if (color_str == "red") { color = cv::Scalar(0, 0, 255); diff --git a/perception/traffic_light_classifier/utils/trt_common.cpp b/perception/traffic_light_classifier/utils/trt_common.cpp deleted file mode 100644 index f12be16879321..0000000000000 --- a/perception/traffic_light_classifier/utils/trt_common.cpp +++ /dev/null @@ -1,170 +0,0 @@ -// 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. - -#include - -#if (defined(_MSC_VER) or (defined(__GNUC__) and (7 <= __GNUC_MAJOR__))) -#include -namespace fs = ::std::filesystem; -#else -#include -namespace fs = ::std::experimental::filesystem; -#endif - -#include -#include - -namespace Tn -{ -void check_error(const ::cudaError_t e, decltype(__FILE__) f, decltype(__LINE__) n) -{ - if (e != ::cudaSuccess) { - std::stringstream s; - s << ::cudaGetErrorName(e) << " (" << e << ")@" << f << "#L" << n << ": " - << ::cudaGetErrorString(e); - throw std::runtime_error{s.str()}; - } -} - -TrtCommon::TrtCommon( - std::string model_path, std::string precision, std::string input_name, std::string output_name) -: model_file_path_(model_path), - precision_(precision), - input_name_(input_name), - output_name_(output_name), - is_initialized_(false) -{ - runtime_ = UniquePtr(nvinfer1::createInferRuntime(logger_)); -} - -void TrtCommon::setup() -{ - const fs::path path(model_file_path_); - std::string extension = path.extension().string(); - - if (fs::exists(path)) { - if (extension == ".engine") { - loadEngine(model_file_path_); - } else if (extension == ".onnx") { - fs::path cache_engine_path{model_file_path_}; - cache_engine_path.replace_extension("engine"); - if (fs::exists(cache_engine_path)) { - loadEngine(cache_engine_path.string()); - } else { - logger_.log(nvinfer1::ILogger::Severity::kINFO, "start build engine"); - buildEngineFromOnnx(model_file_path_, cache_engine_path.string()); - logger_.log(nvinfer1::ILogger::Severity::kINFO, "end build engine"); - } - } else { - is_initialized_ = false; - return; - } - } else { - is_initialized_ = false; - return; - } - - context_ = UniquePtr(engine_->createExecutionContext()); - -#if (NV_TENSORRT_MAJOR * 10000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 80500 - input_dims_ = engine_->getTensorShape(input_name_.c_str()); - output_dims_ = engine_->getTensorShape(output_name_.c_str()); -#else - // Deprecated since 8.5 - input_dims_ = engine_->getBindingDimensions(engine_->getBindingIndex(input_name_.c_str())); - output_dims_ = engine_->getBindingDimensions(engine_->getBindingIndex(output_name_.c_str())); -#endif - - is_initialized_ = true; -} - -bool TrtCommon::loadEngine(std::string engine_file_path) -{ - std::ifstream engine_file(engine_file_path); - std::stringstream engine_buffer; - engine_buffer << engine_file.rdbuf(); - std::string engine_str = engine_buffer.str(); - engine_ = UniquePtr(runtime_->deserializeCudaEngine( - reinterpret_cast(engine_str.data()), engine_str.size())); - return true; -} - -bool TrtCommon::buildEngineFromOnnx(std::string onnx_file_path, std::string output_engine_file_path) -{ - auto builder = UniquePtr(nvinfer1::createInferBuilder(logger_)); - const auto explicitBatch = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); - auto network = UniquePtr(builder->createNetworkV2(explicitBatch)); - auto config = UniquePtr(builder->createBuilderConfig()); - - auto parser = UniquePtr(nvonnxparser::createParser(*network, logger_)); - if (!parser->parseFromFile( - onnx_file_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR))) { - return false; - } - -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 - config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, 16 << 20); -#else - config->setMaxWorkspaceSize(16 << 20); -#endif - - if (precision_ == "fp16") { - config->setFlag(nvinfer1::BuilderFlag::kFP16); - } else if (precision_ == "int8") { - config->setFlag(nvinfer1::BuilderFlag::kINT8); - } else { - return false; - } - - auto plan = UniquePtr(builder->buildSerializedNetwork(*network, *config)); - if (!plan) { - return false; - } - engine_ = - UniquePtr(runtime_->deserializeCudaEngine(plan->data(), plan->size())); - if (!engine_) { - return false; - } - - // save engine - std::ofstream file; - file.open(output_engine_file_path, std::ios::binary | std::ios::out); - if (!file.is_open()) { - return false; - } - file.write((const char *)plan->data(), plan->size()); - file.close(); - - return true; -} - -bool TrtCommon::isInitialized() -{ - return is_initialized_; -} - -int TrtCommon::getNumInput() -{ - return std::accumulate( - input_dims_.d, input_dims_.d + input_dims_.nbDims, 1, std::multiplies()); -} - -int TrtCommon::getNumOutput() -{ - return std::accumulate( - output_dims_.d, output_dims_.d + output_dims_.nbDims, 1, std::multiplies()); -} - -} // namespace Tn diff --git a/perception/traffic_light_classifier/utils/trt_common.hpp b/perception/traffic_light_classifier/utils/trt_common.hpp deleted file mode 100644 index d7e314a3b4705..0000000000000 --- a/perception/traffic_light_classifier/utils/trt_common.hpp +++ /dev/null @@ -1,142 +0,0 @@ -// 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 PERCEPTION__TRAFFIC_LIGHT_CLASSIFIER__UTILS__TRT_COMMON_HPP_ -#define PERCEPTION__TRAFFIC_LIGHT_CLASSIFIER__UTILS__TRT_COMMON_HPP_ - -#include -#include - -#include <./cudnn.h> -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#define CHECK_CUDA_ERROR(e) (Tn::check_error(e, __FILE__, __LINE__)) - -namespace Tn -{ -class Logger : public nvinfer1::ILogger -{ -public: - Logger() : Logger(Severity::kINFO) {} - - explicit Logger(Severity severity) : reportableSeverity(severity) {} - - void log(Severity severity, const char * msg) noexcept override - { - // suppress messages with severity enum value greater than the reportable - if (severity > reportableSeverity) { - return; - } - - switch (severity) { - case Severity::kINTERNAL_ERROR: - std::cerr << "[TRT_COMMON][INTERNAL_ERROR]: "; - break; - case Severity::kERROR: - std::cerr << "[TRT_COMMON][ERROR]: "; - break; - case Severity::kWARNING: - std::cerr << "[TRT_COMMON][WARNING]: "; - break; - case Severity::kINFO: - std::cerr << "[TRT_COMMON][INFO]: "; - break; - default: - std::cerr << "[TRT_COMMON][UNKNOWN]: "; - break; - } - std::cerr << msg << std::endl; - } - - Severity reportableSeverity{Severity::kWARNING}; -}; - -void check_error(const ::cudaError_t e, decltype(__FILE__) f, decltype(__LINE__) n); - -struct InferDeleter -{ - void operator()(void * p) const { ::cudaFree(p); } -}; - -template -using UniquePtr = std::unique_ptr; - -// auto array = Tn::make_unique(n); -// ::cudaMemcpy(array.get(), src_array, sizeof(float)*n, ::cudaMemcpyHostToDevice); -template -typename std::enable_if::value, Tn::UniquePtr>::type make_unique( - const std::size_t n) -{ - using U = typename std::remove_extent::type; - U * p; - ::cudaMalloc(reinterpret_cast(&p), sizeof(U) * n); - return Tn::UniquePtr{p}; -} - -// auto value = Tn::make_unique(); -// ::cudaMemcpy(value.get(), src_value, sizeof(my_class), ::cudaMemcpyHostToDevice); -template -Tn::UniquePtr make_unique() -{ - T * p; - ::cudaMalloc(reinterpret_cast(&p), sizeof(T)); - return Tn::UniquePtr{p}; -} - -class TrtCommon -{ -public: - TrtCommon( - std::string model_path, std::string precision, std::string input_name, std::string output_name); - ~TrtCommon() {} - - bool loadEngine(std::string engine_file_path); - bool buildEngineFromOnnx(std::string onnx_file_path, std::string output_engine_file_path); - void setup(); - - bool isInitialized(); - int getNumInput(); - int getNumOutput(); - - UniquePtr context_; - -private: - Logger logger_; - std::string model_file_path_; - UniquePtr runtime_; - UniquePtr engine_; - - nvinfer1::Dims input_dims_; - nvinfer1::Dims output_dims_; - std::string cache_dir_; - std::string precision_; - std::string input_name_; - std::string output_name_; - bool is_initialized_; -}; - -} // namespace Tn - -#endif // PERCEPTION__TRAFFIC_LIGHT_CLASSIFIER__UTILS__TRT_COMMON_HPP_ diff --git a/perception/traffic_light_fine_detector/.gitignore b/perception/traffic_light_fine_detector/.gitignore new file mode 100644 index 0000000000000..8fce603003c1e --- /dev/null +++ b/perception/traffic_light_fine_detector/.gitignore @@ -0,0 +1 @@ +data/ diff --git a/perception/traffic_light_fine_detector/CMakeLists.txt b/perception/traffic_light_fine_detector/CMakeLists.txt new file mode 100644 index 0000000000000..a26cafff1ee4d --- /dev/null +++ b/perception/traffic_light_fine_detector/CMakeLists.txt @@ -0,0 +1,156 @@ +cmake_minimum_required(VERSION 3.14) +project(traffic_light_fine_detector) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +add_compile_options(-Wno-deprecated-declarations) + +option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) + +find_package(OpenCV REQUIRED) + +# set flags for CUDA availability +option(CUDA_AVAIL "CUDA available" OFF) +find_package(CUDA) +if(CUDA_FOUND) + find_library(CUBLAS_LIBRARIES cublas HINTS + ${CUDA_TOOLKIT_ROOT_DIR}/lib64 + ${CUDA_TOOLKIT_ROOT_DIR}/lib + ) + if(CUDA_VERBOSE) + message(STATUS "CUDA is available!") + message(STATUS "CUDA Libs: ${CUDA_LIBRARIES}") + message(STATUS "CUDA Headers: ${CUDA_INCLUDE_DIRS}") + endif() + set(CUDA_AVAIL ON) +else() + message(STATUS "CUDA NOT FOUND") + set(CUDA_AVAIL OFF) +endif() + +# set flags for TensorRT availability +option(TRT_AVAIL "TensorRT available" OFF) +# try to find the tensorRT modules +find_library(NVINFER NAMES nvinfer) +find_library(NVONNXPARSER nvonnxparser) +find_library(NVINFER_PLUGIN NAMES nvinfer_plugin) +if(NVINFER AND NVONNXPARSER AND NVINFER_PLUGIN) + if(CUDA_VERBOSE) + message(STATUS "TensorRT is available!") + message(STATUS "NVINFER: ${NVINFER}") + message(STATUS "NVPARSERS: ${NVPARSERS}") + message(STATUS "NVINFER_PLUGIN: ${NVINFER_PLUGIN}") + message(STATUS "NVONNXPARSER: ${NVONNXPARSER}") + endif() + set(TRT_AVAIL ON) +else() + message(STATUS "TensorRT is NOT Available") + set(TRT_AVAIL OFF) +endif() + +# set flags for CUDNN availability +option(CUDNN_AVAIL "CUDNN available" OFF) +# try to find the CUDNN module +find_library(CUDNN_LIBRARY + NAMES libcudnn.so${__cudnn_ver_suffix} libcudnn${__cudnn_ver_suffix}.dylib ${__cudnn_lib_win_name} + PATHS $ENV{LD_LIBRARY_PATH} ${__libpath_cudart} ${CUDNN_ROOT_DIR} ${PC_CUDNN_LIBRARY_DIRS} ${CMAKE_INSTALL_PREFIX} + PATH_SUFFIXES lib lib64 bin + DOC "CUDNN library." +) +if(CUDNN_LIBRARY) + if(CUDA_VERBOSE) + message(STATUS "CUDNN is available!") + message(STATUS "CUDNN_LIBRARY: ${CUDNN_LIBRARY}") + endif() + set(CUDNN_AVAIL ON) +else() + message(STATUS "CUDNN is NOT Available") + set(CUDNN_AVAIL OFF) +endif() + +# Download caffemodel and prototxt +set(PRETRAINED_MODEL_HASH f3af5bd588c6c99ccf9ca236a07ad41e) +set(LAMP_LABEL_HASH e9f45efb02f2a9aa8ac27b3d5c164905) +set(DATA_DIR https://awf.ml.dev.web.auto/perception/models/tlr_yolox_s/v2) + +set(DATA_PATH "${CMAKE_CURRENT_SOURCE_DIR}/data") +if(NOT EXISTS "${DATA_PATH}") + execute_process(COMMAND mkdir -p ${DATA_PATH}) +endif() +function(download FILE_NAME FILE_HASH) + message(STATUS "Checking and downloading ${FILE_NAME}") + set(FILE_PATH ${DATA_PATH}/${FILE_NAME}) + set(STATUS_CODE 0) + message(STATUS "start ${FILE_NAME}") + if(EXISTS ${FILE_PATH}) + message(STATUS "found ${FILE_NAME}") + file(MD5 ${FILE_PATH} EXISTING_FILE_HASH) + if(${FILE_HASH} STREQUAL ${EXISTING_FILE_HASH}) + message(STATUS "same ${FILE_NAME}") + message(STATUS "File already exists.") + else() + message(STATUS "diff ${FILE_NAME}") + message(STATUS "File hash changes. Downloading now ...") + file(DOWNLOAD ${DATA_DIR}/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) + list(GET DOWNLOAD_STATUS 0 STATUS_CODE) + list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) + endif() + else() + message(STATUS "not found ${FILE_NAME}") + message(STATUS "File doesn't exists. Downloading now ...") + file(DOWNLOAD ${DATA_DIR}/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) + list(GET DOWNLOAD_STATUS 0 STATUS_CODE) + list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) + endif() + if(${STATUS_CODE} EQUAL 0) + message(STATUS "Download completed successfully!") + else() + message(FATAL_ERROR "Error occurred during download: ${ERROR_MESSAGE}") + endif() +endfunction() +download(tlr_yolox_s.onnx ${PRETRAINED_MODEL_HASH}) +download(tlr_labels.txt ${LAMP_LABEL_HASH}) + +if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) + include_directories( + ${OpenCV_INCLUDE_DIRS} + ${CUDA_INCLUDE_DIRS} + ) + + ament_auto_add_library(traffic_light_fine_detector_nodelet SHARED + src/nodelet.cpp + ) + + target_include_directories(traffic_light_fine_detector_nodelet PUBLIC + lib/include + ) + + target_link_libraries(traffic_light_fine_detector_nodelet + ${NVINFER} + ${NVONNXPARSER} + ${NVINFER_PLUGIN} + ${CUDA_LIBRARIES} + ${CUBLAS_LIBRARIES} + ${CUDNN_LIBRARY} + ${OpenCV_LIB} + stdc++fs + ) + + rclcpp_components_register_node(traffic_light_fine_detector_nodelet + PLUGIN "traffic_light::TrafficLightFineDetectorNodelet" + EXECUTABLE traffic_light_fine_detector_node + ) + + ament_auto_package(INSTALL_TO_SHARE + data + launch + ) + +else() + message(STATUS "TrafficLightFineDetector won't be built, CUDA and/or TensorRT were not found.") + # to avoid launch file missing without a gpu + ament_auto_package(INSTALL_TO_SHARE + launch + ) +endif() diff --git a/perception/traffic_light_fine_detector/README.md b/perception/traffic_light_fine_detector/README.md new file mode 100644 index 0000000000000..1ed6debfeae91 --- /dev/null +++ b/perception/traffic_light_fine_detector/README.md @@ -0,0 +1,66 @@ +# traffic_light_fine_detector + +## Purpose + +It is a package for traffic light detection using YoloX-s. + +## Training Information + +### Pretrained Model + +The model is based on [YOLOX](https://github.com/Megvii-BaseDetection/YOLOX) and the pretrained model could be downloaded from [here](https://github.com/Megvii-BaseDetection/YOLOX/releases/download/0.1.1rc0/yolox_s.pth). + +### Training Data + +The model was fine-tuned on around 17,000 TIER IV internal images of Japanese traffic lights. + +### Trained Onnx model + +- + +## Inner-workings / Algorithms + +Based on the camera image and the global ROI array detected by `map_based_detection` node, a CNN-based detection method enables highly accurate traffic light detection. + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| --------------- | -------------------------------------------------- | ------------------------------------------------------------------- | +| `~/input/image` | `sensor_msgs/Image` | The full size camera image | +| `~/input/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The array of ROIs detected by map_based_detector | +| `~/expect/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The array of ROIs detected by map_based_detector without any offset | + +### Output + +| Name | Type | Description | +| --------------------- | -------------------------------------------------- | ---------------------------- | +| `~/output/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The detected accurate rois | +| `~/debug/exe_time_ms` | `tier4_debug_msgs::msg::Float32Stamped` | The time taken for inference | + +## Parameters + +### Core Parameters + +| Name | Type | Default Value | Description | +| ---------------------------- | ------ | ------------- | ---------------------------------------------------------------------- | +| `fine_detector_score_thresh` | double | 0.3 | If the objectness score is less than this value, the object is ignored | +| `fine_detector_nms_thresh` | double | 0.65 | IoU threshold to perform Non-Maximum Suppression | + +### Node Parameters + +| Name | Type | Default Value | Description | +| -------------------------- | ------ | ------------- | ------------------------------------------------------------------ | +| `fine_detector_model_path` | string | "" | The onnx file name for yolo model | +| `fine_detector_label_path` | string | "" | The label file with label names for detected objects written on it | +| `fine_detector_precision` | string | "fp32" | The inference mode: "fp32", "fp16" | +| `approximate_sync` | bool | false | Flag for whether to ues approximate sync policy | + +## Assumptions / Known limits + +## Reference repositories + +YOLOX github repository + +- diff --git a/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp b/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp new file mode 100644 index 0000000000000..f115596453835 --- /dev/null +++ b/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp @@ -0,0 +1,172 @@ +// 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 TRAFFIC_LIGHT_FINE_DETECTOR__NODELET_HPP_ +#define TRAFFIC_LIGHT_FINE_DETECTOR__NODELET_HPP_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#if __has_include() +#include +#else +#include +#endif +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +typedef struct Detection +{ + float x, y, w, h, prob; +} Detection; + +namespace traffic_light +{ +class TrafficLightFineDetectorNodelet : public rclcpp::Node +{ + using TrafficLightRoi = tier4_perception_msgs::msg::TrafficLightRoi; + using TrafficLightRoiArray = tier4_perception_msgs::msg::TrafficLightRoiArray; + +public: + explicit TrafficLightFineDetectorNodelet(const rclcpp::NodeOptions & options); + void connectCb(); + /** + * @brief main process function. + * + * @param image_msg ros image message + * @param rough_roi_msg rough rois message + * @param expect_roi_msg expect rois message + */ + void callback( + const sensor_msgs::msg::Image::ConstSharedPtr image_msg, + const TrafficLightRoiArray::ConstSharedPtr rough_roi_msg, + const TrafficLightRoiArray::ConstSharedPtr expect_roi_msg); + +private: + /** + * @brief convert the images into data stream ready for gpu process + * + * @param in_imgs cv::Mat images + * @param num_rois number of rois + * @param data output data stream + * @return true succeed + * @return false failed + */ + bool cvMat2CnnInput( + const std::vector & in_imgs, const int num_rois, std::vector & data); + /** + * @brief Calculate the match score. Details will be explained in docs of evalMatchScore + * + * @param id2expectRoi + * @param id2detections + * @param id2bestDetection + * @return float + */ + float evalMatchScore( + std::map & id2expectRoi, + std::map & id2detections, + std::map & id2bestDetection); + /** + * @brief Every traffic light roi might have several possible detections. This function + * is designed to select the best detection for every traffic light by making use of + * the relative positions between the traffic lights projected on the image (expect/rois). + * To be specified, for every detection, all the expect rois will be transfered so that + * this detection will match the corresponding expect roi. Note that the expect rois + * of other traffic lights will also be transfered equally. Then, for every expect roi, + * it will calculate the match score (which is IoU_detection_roi * detection_confidence) + * with every detection. + * The combination of detections that will get highest match score sum will be the selected + * detections + * + * @param id2expectRoi id to expect/roi map + * @param id2detections id to detections map + * @param out_rois output rois converted from the selected detections + */ + void detectionMatch( + std::map & id2expectRoi, + std::map & id2detections, TrafficLightRoiArray & out_rois); + /** + * @brief convert image message to cv::Mat + * + * @param image_msg input image message + * @param image output cv::Mat image + * @param encode image encode + * @return true succeed + * @return false failed + */ + bool rosMsg2CvMat( + const sensor_msgs::msg::Image::ConstSharedPtr image_msg, cv::Mat & image, + std::string encode = "rgb8"); + bool fitInFrame(cv::Point & lt, cv::Point & rb, const cv::Size & size); + /** + * @brief Read the label file to get class number and traffic_light class index of the model + * + * @param filepath path to the label file + * @param tlr_id output traffic light class index + * @param num_class output class number + * @return true succeed + * @return false failed + */ + bool readLabelFile(const std::string & filepath, int & tlr_id, int & num_class); + + // variables + image_transport::SubscriberFilter image_sub_; + message_filters::Subscriber rough_roi_sub_; + message_filters::Subscriber expect_roi_sub_; + std::mutex connect_mutex_; + rclcpp::Publisher::SharedPtr output_roi_pub_; + rclcpp::Publisher::SharedPtr exe_time_pub_; + rclcpp::TimerBase::SharedPtr timer_; + + typedef message_filters::sync_policies::ExactTime< + sensor_msgs::msg::Image, TrafficLightRoiArray, TrafficLightRoiArray> + SyncPolicy; + typedef message_filters::Synchronizer Sync; + std::shared_ptr sync_; + + typedef message_filters::sync_policies::ApproximateTime< + sensor_msgs::msg::Image, TrafficLightRoiArray, TrafficLightRoiArray> + ApproximateSyncPolicy; + typedef message_filters::Synchronizer ApproximateSync; + std::shared_ptr approximate_sync_; + + bool is_approximate_sync_; + double score_thresh_; + int tlr_id_; + + std::unique_ptr trt_yolox_; +}; // TrafficLightFineDetectorNodelet + +} // namespace traffic_light + +#endif // TRAFFIC_LIGHT_FINE_DETECTOR__NODELET_HPP_ diff --git a/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml b/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml new file mode 100644 index 0000000000000..442aa3f45ea88 --- /dev/null +++ b/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/traffic_light_fine_detector/package.xml b/perception/traffic_light_fine_detector/package.xml new file mode 100644 index 0000000000000..960a90379279a --- /dev/null +++ b/perception/traffic_light_fine_detector/package.xml @@ -0,0 +1,29 @@ + + + + traffic_light_fine_detector + 0.1.0 + The traffic_light_fine_detector package + Mingyu Li + Apache License 2.0 + + ament_cmake_auto + + autoware_cmake + + cv_bridge + image_transport + message_filters + rclcpp + rclcpp_components + sensor_msgs + tensorrt_yolox + tier4_debug_msgs + tier4_perception_msgs + + autoware_lint_common + + + ament_cmake + + diff --git a/perception/traffic_light_fine_detector/src/nodelet.cpp b/perception/traffic_light_fine_detector/src/nodelet.cpp new file mode 100644 index 0000000000000..75812a072f4c6 --- /dev/null +++ b/perception/traffic_light_fine_detector/src/nodelet.cpp @@ -0,0 +1,310 @@ +// 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 "traffic_light_fine_detector/nodelet.hpp" + +#if (defined(_MSC_VER) or (defined(__GNUC__) and (7 <= __GNUC_MAJOR__))) +#include +namespace fs = ::std::filesystem; +#else +#include +namespace fs = ::std::experimental::filesystem; +#endif + +#include +#include +#include +#include + +namespace +{ +float calWeightedIou( + const sensor_msgs::msg::RegionOfInterest & bbox1, const tensorrt_yolox::Object & bbox2) +{ + int x1 = std::max(static_cast(bbox1.x_offset), bbox2.x_offset); + int x2 = std::min(static_cast(bbox1.x_offset + bbox1.width), bbox2.x_offset + bbox2.width); + int y1 = std::max(static_cast(bbox1.y_offset), bbox2.y_offset); + int y2 = std::min(static_cast(bbox1.y_offset + bbox1.height), bbox2.y_offset + bbox2.height); + int area1 = std::max(x2 - x1, 0) * std::max(y2 - y1, 0); + int area2 = bbox1.width * bbox1.height + bbox2.width * bbox2.height - area1; + if (area2 == 0) { + return 0.0; + } + return bbox2.score * area1 / area2; +} + +} // namespace + +namespace traffic_light +{ +inline std::vector toFloatVector(const std::vector double_vector) +{ + return std::vector(double_vector.begin(), double_vector.end()); +} + +TrafficLightFineDetectorNodelet::TrafficLightFineDetectorNodelet( + const rclcpp::NodeOptions & options) +: Node("traffic_light_fine_detector_node", options) +{ + int num_class = 2; + using std::placeholders::_1; + using std::placeholders::_2; + using std::placeholders::_3; + + std::string model_path = declare_parameter("fine_detector_model_path", ""); + std::string label_path = declare_parameter("fine_detector_label_path", ""); + std::string precision = declare_parameter("fine_detector_precision", "fp32"); + // Objects with a score lower than this value will be ignored. + // This threshold will be ignored if specified model contains EfficientNMS_TRT module in it + score_thresh_ = declare_parameter("fine_detector_score_thresh", 0.3); + // Detection results will be ignored if IoU over this value. + // This threshold will be ignored if specified model contains EfficientNMS_TRT module in it + float nms_threshold = declare_parameter("fine_detector_nms_thresh", 0.65); + is_approximate_sync_ = this->declare_parameter("approximate_sync", false); + + if (!readLabelFile(label_path, tlr_id_, num_class)) { + RCLCPP_ERROR(this->get_logger(), "Could not find tlr id"); + } + trt_yolox_ = std::make_unique( + model_path, precision, num_class, score_thresh_, nms_threshold); + + using std::chrono_literals::operator""ms; + timer_ = rclcpp::create_timer( + this, get_clock(), 100ms, std::bind(&TrafficLightFineDetectorNodelet::connectCb, this)); + + std::lock_guard lock(connect_mutex_); + output_roi_pub_ = this->create_publisher("~/output/rois", 1); + exe_time_pub_ = + this->create_publisher("~/debug/exe_time_ms", 1); + if (is_approximate_sync_) { + approximate_sync_.reset( + new ApproximateSync(ApproximateSyncPolicy(10), image_sub_, rough_roi_sub_, expect_roi_sub_)); + approximate_sync_->registerCallback( + std::bind(&TrafficLightFineDetectorNodelet::callback, this, _1, _2, _3)); + } else { + sync_.reset(new Sync(SyncPolicy(10), image_sub_, rough_roi_sub_, expect_roi_sub_)); + sync_->registerCallback( + std::bind(&TrafficLightFineDetectorNodelet::callback, this, _1, _2, _3)); + } + + if (declare_parameter("build_only", false)) { + RCLCPP_INFO(get_logger(), "TensorRT engine is built and shutdown node."); + rclcpp::shutdown(); + } +} + +void TrafficLightFineDetectorNodelet::connectCb() +{ + std::lock_guard lock(connect_mutex_); + if (output_roi_pub_->get_subscription_count() == 0) { + image_sub_.unsubscribe(); + rough_roi_sub_.unsubscribe(); + expect_roi_sub_.unsubscribe(); + } else if (!image_sub_.getSubscriber()) { + image_sub_.subscribe(this, "~/input/image", "raw", rmw_qos_profile_sensor_data); + rough_roi_sub_.subscribe(this, "~/input/rois", rclcpp::QoS{1}.get_rmw_qos_profile()); + expect_roi_sub_.subscribe(this, "~/expect/rois", rclcpp::QoS{1}.get_rmw_qos_profile()); + } +} + +void TrafficLightFineDetectorNodelet::callback( + const sensor_msgs::msg::Image::ConstSharedPtr in_image_msg, + const TrafficLightRoiArray::ConstSharedPtr rough_roi_msg, + const TrafficLightRoiArray::ConstSharedPtr expect_roi_msg) +{ + if (in_image_msg->width < 2 || in_image_msg->height < 2) { + return; + } + + using std::chrono::high_resolution_clock; + using std::chrono::milliseconds; + const auto exe_start_time = high_resolution_clock::now(); + cv::Mat original_image; + TrafficLightRoiArray out_rois; + std::map id2expectRoi; + std::map id2detections; + for (const auto & expect_roi : expect_roi_msg->rois) { + id2expectRoi[expect_roi.traffic_light_id] = expect_roi; + } + + rosMsg2CvMat(in_image_msg, original_image, "bgr8"); + for (const auto & rough_roi : rough_roi_msg->rois) { + cv::Point lt(rough_roi.roi.x_offset, rough_roi.roi.y_offset); + cv::Point rb( + rough_roi.roi.x_offset + rough_roi.roi.width, rough_roi.roi.y_offset + rough_roi.roi.height); + fitInFrame(lt, rb, cv::Size(original_image.size())); + cv::Mat cropped_img = cv::Mat(original_image, cv::Rect(lt, rb)); + tensorrt_yolox::ObjectArrays inference_results; + if (!trt_yolox_->doInference({cropped_img}, inference_results)) { + RCLCPP_WARN(this->get_logger(), "Fail to inference"); + return; + } + for (tensorrt_yolox::Object & detection : inference_results[0]) { + if (detection.score < score_thresh_ || detection.type != tlr_id_) { + continue; + } + cv::Point lt_roi(lt.x + detection.x_offset, lt.y + detection.y_offset); + cv::Point rb_roi(lt_roi.x + detection.width, lt_roi.y + detection.height); + fitInFrame(lt_roi, rb_roi, cv::Size(original_image.size())); + tensorrt_yolox::Object det = detection; + det.x_offset = lt_roi.x; + det.y_offset = lt_roi.y; + det.width = rb_roi.x - lt_roi.x; + det.height = rb_roi.y - lt_roi.y; + id2detections[rough_roi.traffic_light_id].push_back(det); + } + } + detectionMatch(id2expectRoi, id2detections, out_rois); + out_rois.header = rough_roi_msg->header; + output_roi_pub_->publish(out_rois); + const auto exe_end_time = high_resolution_clock::now(); + const double exe_time = + std::chrono::duration_cast(exe_end_time - exe_start_time).count(); + tier4_debug_msgs::msg::Float32Stamped exe_time_msg; + exe_time_msg.data = exe_time; + exe_time_msg.stamp = this->now(); + exe_time_pub_->publish(exe_time_msg); +} + +float TrafficLightFineDetectorNodelet::evalMatchScore( + std::map & id2expectRoi, + std::map & id2detections, + std::map & id2bestDetection) +{ + float score_sum = 0.0f; + id2bestDetection.clear(); + for (const auto & roi_p : id2expectRoi) { + int tlr_id = roi_p.first; + float max_score = 0.0f; + const sensor_msgs::msg::RegionOfInterest & expected_roi = roi_p.second.roi; + for (const tensorrt_yolox::Object & detection : id2detections[tlr_id]) { + float score = ::calWeightedIou(expected_roi, detection); + if (score >= max_score) { + max_score = score; + id2bestDetection[tlr_id] = detection; + } + } + score_sum += max_score; + } + return score_sum; +} + +void TrafficLightFineDetectorNodelet::detectionMatch( + std::map & id2expectRoi, + std::map & id2detections, TrafficLightRoiArray & out_rois) +{ + float max_score = 0.0f; + std::map bestDetections; + for (const auto & roi_pair : id2expectRoi) { + int tlr_id = roi_pair.first; + // the expected roi calculated from tf information + const sensor_msgs::msg::RegionOfInterest & expect_roi = roi_pair.second.roi; + int expect_cx = expect_roi.x_offset + expect_roi.width / 2; + int expect_cy = expect_roi.y_offset + expect_roi.height / 2; + for (const tensorrt_yolox::Object & det : id2detections[tlr_id]) { + // for every detection, calculate the center offset between the detection and the + // corresponding expected roi + int det_cx = det.x_offset + det.width / 2; + int det_cy = det.y_offset + det.height / 2; + int dx = det_cx - expect_cx; + int dy = det_cy - expect_cy; + // transfer all the rough rois by the offset + std::map id2expectRoi_copy = id2expectRoi; + for (auto & p : id2expectRoi_copy) { + p.second.roi.x_offset += dx; + p.second.roi.y_offset += dy; + } + // calculate the "match score" between expected rois and id2detections_copy + std::map id2bestDetection; + float score = evalMatchScore(id2expectRoi_copy, id2detections, id2bestDetection); + if (score > max_score) { + max_score = score; + bestDetections = id2bestDetection; + } + } + } + + out_rois.rois.clear(); + for (const auto & p : bestDetections) { + TrafficLightRoi tlr; + tlr.traffic_light_id = p.first; + tlr.roi.x_offset = p.second.x_offset; + tlr.roi.y_offset = p.second.y_offset; + tlr.roi.width = p.second.width; + tlr.roi.height = p.second.height; + out_rois.rois.push_back(tlr); + } +} + +bool TrafficLightFineDetectorNodelet::rosMsg2CvMat( + const sensor_msgs::msg::Image::ConstSharedPtr image_msg, cv::Mat & image, std::string encode) +{ + try { + cv_bridge::CvImagePtr cv_image = cv_bridge::toCvCopy(image_msg, encode); + image = cv_image->image; + } catch (cv_bridge::Exception & e) { + RCLCPP_ERROR( + this->get_logger(), "Failed to convert sensor_msgs::msg::Image to cv::Mat \n%s", e.what()); + return false; + } + + return true; +} + +bool TrafficLightFineDetectorNodelet::fitInFrame( + cv::Point & lt, cv::Point & rb, const cv::Size & size) +{ + const int width = static_cast(size.width); + const int height = static_cast(size.height); + { + const int x_min = 0, x_max = width - 2; + const int y_min = 0, y_max = height - 2; + lt.x = std::min(std::max(lt.x, x_min), x_max); + lt.y = std::min(std::max(lt.y, y_min), y_max); + } + { + const int x_min = lt.x + 1, x_max = width - 1; + const int y_min = lt.y + 1, y_max = height - 1; + rb.x = std::min(std::max(rb.x, x_min), x_max); + rb.y = std::min(std::max(rb.y, y_min), y_max); + } + + return true; +} + +bool TrafficLightFineDetectorNodelet::readLabelFile( + const std::string & filepath, int & tlr_id, int & num_class) +{ + tlr_id = -1; + std::ifstream labelsFile(filepath); + if (!labelsFile.is_open()) { + RCLCPP_ERROR(this->get_logger(), "Could not open label file. [%s]", filepath.c_str()); + return false; + } + std::string label; + int idx = 0; + while (getline(labelsFile, label)) { + if (label == "traffic_light") { + tlr_id = idx; + } + idx++; + } + num_class = idx; + return tlr_id != -1; +} + +} // namespace traffic_light + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(traffic_light::TrafficLightFineDetectorNodelet) diff --git a/perception/traffic_light_map_based_detector/README.md b/perception/traffic_light_map_based_detector/README.md index 435969e6e98a1..e03a4c6dd8f69 100644 --- a/perception/traffic_light_map_based_detector/README.md +++ b/perception/traffic_light_map_based_detector/README.md @@ -21,17 +21,22 @@ If the node receives no route information, it looks at a radius of 200 meters an ## Output topics -| Name | Type | Description | -| ---------------- | --------------------------------------------------- | -------------------------------------------------------------------- | -| `~output/rois` | autoware_auto_perception_msgs::TrafficLightRoiArray | location of traffic lights in image corresponding to the camera info | -| `~debug/markers` | visualization_msgs::MarkerArray | visualization to debug | +| Name | Type | Description | +| ---------------- | ------------------------------------------- | -------------------------------------------------------------------- | +| `~output/rois` | tier4_perception_msgs::TrafficLightRoiArray | location of traffic lights in image corresponding to the camera info | +| `~expect/rois` | tier4_perception_msgs::TrafficLightRoiArray | location of traffic lights in image without any offset | +| `~debug/markers` | visualization_msgs::MarkerArray | visualization to debug | ## Node parameters -| Parameter | Type | Description | -| ---------------------- | ------ | ----------------------------------------------------------- | -| `max_vibration_pitch` | double | Maximum error in pitch direction. If -5~+5, it will be 10. | -| `max_vibration_yaw` | double | Maximum error in yaw direction. If -5~+5, it will be 10. | -| `max_vibration_height` | double | Maximum error in height direction. If -5~+5, it will be 10. | -| `max_vibration_width` | double | Maximum error in width direction. If -5~+5, it will be 10. | -| `max_vibration_depth` | double | Maximum error in depth direction. If -5~+5, it will be 10. | +| Parameter | Type | Description | +| ---------------------- | ------ | --------------------------------------------------------------------- | +| `max_vibration_pitch` | double | Maximum error in pitch direction. If -5~+5, it will be 10. | +| `max_vibration_yaw` | double | Maximum error in yaw direction. If -5~+5, it will be 10. | +| `max_vibration_height` | double | Maximum error in height direction. If -5~+5, it will be 10. | +| `max_vibration_width` | double | Maximum error in width direction. If -5~+5, it will be 10. | +| `max_vibration_depth` | double | Maximum error in depth direction. If -5~+5, it will be 10. | +| `max_detection_range` | double | Maximum detection range in meters. Must be positive | +| `min_timestamp_offset` | double | Minimum timestamp offset when searching for corresponding tf | +| `max_timestamp_offset` | double | Maximum timestamp offset when searching for corresponding tf | +| `timestamp_sample_len` | double | sampling length between min_timestamp_offset and max_timestamp_offset | diff --git a/perception/traffic_light_map_based_detector/config/traffic_light_map_based_detector.param.yaml b/perception/traffic_light_map_based_detector/config/traffic_light_map_based_detector.param.yaml index 6acb255a79aa2..2b8ff4aa737b7 100644 --- a/perception/traffic_light_map_based_detector/config/traffic_light_map_based_detector.param.yaml +++ b/perception/traffic_light_map_based_detector/config/traffic_light_map_based_detector.param.yaml @@ -1,7 +1,8 @@ /**: ros__parameters: - max_vibration_pitch: 0.00436332312 # -0.5 ~ 0.5 deg - max_vibration_yaw: 0.00436332312 # -0.5 ~ 0.5 deg - max_vibration_height: 0.01 # -0.05 ~ 0.05 m - max_vibration_width: 0.01 # -0.05 ~ 0.05 m - max_vibration_depth: 0.01 # -0.05 ~ 0.05 m + max_vibration_pitch: 0.01745329251 # -0.5 ~ 0.5 deg + max_vibration_yaw: 0.01745329251 # -0.5 ~ 0.5 deg + max_vibration_height: 0.5 # -0.25 ~ 0.25 m + max_vibration_width: 0.5 # -0.25 ~ 0.25 m + max_vibration_depth: 0.5 # -0.25 ~ 0.25 m + max_detection_range: 200.0 diff --git a/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp b/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp index 941e0596bf061..9db8d7242c64d 100644 --- a/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp +++ b/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// 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. @@ -11,24 +11,6 @@ // 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 2019 Autoware Foundation. 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. - * - * Authors: Yukihiro Saito - * - */ #ifndef TRAFFIC_LIGHT_MAP_BASED_DETECTOR__NODE_HPP_ #define TRAFFIC_LIGHT_MAP_BASED_DETECTOR__NODE_HPP_ @@ -38,25 +20,24 @@ #include #include -#include #include #include #include +#include #include -#if __has_include() -#include -#else #include -#endif #include #include #include #include #include +#include +#include #include #include +#include #include namespace traffic_light @@ -74,6 +55,10 @@ class MapBasedDetector : public rclcpp::Node double max_vibration_height; double max_vibration_width; double max_vibration_depth; + double min_timestamp_offset; + double max_timestamp_offset; + double timestamp_sample_len; + double max_detection_range; }; struct IdLessThan @@ -89,8 +74,16 @@ class MapBasedDetector : public rclcpp::Node rclcpp::Subscription::SharedPtr map_sub_; rclcpp::Subscription::SharedPtr camera_info_sub_; rclcpp::Subscription::SharedPtr route_sub_; - - rclcpp::Publisher::SharedPtr roi_pub_; + /** + * @brief publish the rois of traffic lights with angular and distance offset + * + */ + rclcpp::Publisher::SharedPtr roi_pub_; + /** + * @brief publish the rois of traffic lights with zero angular and distance offset + * + */ + rclcpp::Publisher::SharedPtr expect_roi_pub_; rclcpp::Publisher::SharedPtr viz_pub_; tf2_ros::Buffer tf_buffer_; @@ -104,30 +97,92 @@ class MapBasedDetector : public rclcpp::Node lanelet::LaneletMapPtr lanelet_map_ptr_; lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_; lanelet::routing::RoutingGraphPtr routing_graph_ptr_; - Config config_; + Config config_; + /** + * @brief Calculated the transform from map to frame_id at timestamp t + * + * @param t specified timestamp + * @param frame_id specified target frame id + * @param tf calculated transform + * @return true calculation succeed + * @return false calculation failed + */ + bool getTransform( + const rclcpp::Time & t, const std::string & frame_id, tf2::Transform & tf) const; + /** + * @brief callback function for the map message + * + * @param input_msg + */ void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg); + /** + * @brief callback function for the camera info message. The main process function of the node + * + * @param input_msg + */ void cameraInfoCallback(const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_msg); + /** + * @brief callback function for the route message + * + * @param input_msg + */ void routeCallback(const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr input_msg); + /** + * @brief Get the Visible Traffic Lights object + * + * @param all_traffic_lights all the traffic lights in the route or in the map + * @param tf_map2camera_vec the transformation sequences from map to camera + * @param pinhole_camera_model pinhole model calculated from camera_info + * @param visible_traffic_lights the visible traffic lights object + */ void getVisibleTrafficLights( - const TrafficLightSet & all_traffic_lights, const geometry_msgs::msg::Pose & camera_pose, + const TrafficLightSet & all_traffic_lights, + const std::vector & tf_map2camera_vec, const image_geometry::PinholeCameraModel & pinhole_camera_model, - std::vector & visible_traffic_lights); - bool isInDistanceRange( - const geometry_msgs::msg::Point & tl_point, const geometry_msgs::msg::Point & camera_point, - const double max_distance_range) const; - bool isInAngleRange( - const double & tl_yaw, const double & camera_yaw, const double max_angle_range) const; - bool isInImageFrame( + std::vector & visible_traffic_lights) const; + /** + * @brief Get the Traffic Light Roi from one tf + * + * @param tf_map2camera the transformation from map to camera + * @param pinhole_camera_model pinhole model calculated from camera_info + * @param traffic_light lanelet traffic light object + * @param config offset configuration + * @param roi computed result result + * @return true the computation succeed + * @return false the computation failed + */ + bool getTrafficLightRoi( + const tf2::Transform & tf_map2camera, const image_geometry::PinholeCameraModel & pinhole_camera_model, - const geometry_msgs::msg::Point & point) const; + const lanelet::ConstLineString3d traffic_light, const Config & config, + tier4_perception_msgs::msg::TrafficLightRoi & roi) const; + /** + * @brief Calculate one traffic light roi for every tf and return the roi containing all of them + * + * @param tf_map2camera_vec the transformation vector + * @param pinhole_camera_model pinhole model calculated from camera_info + * @param traffic_light lanelet traffic light object + * @param config offset configuration + * @param roi computed result result + * @return true the computation succeed + * @return false the computation failed + */ bool getTrafficLightRoi( - const geometry_msgs::msg::Pose & camera_pose, + const std::vector & tf_map2camera_vec, const image_geometry::PinholeCameraModel & pinhole_camera_model, const lanelet::ConstLineString3d traffic_light, const Config & config, - autoware_auto_perception_msgs::msg::TrafficLightRoi & tl_roi); + tier4_perception_msgs::msg::TrafficLightRoi & roi) const; + /** + * @brief Publish the traffic lights for visualization + * + * @param tf_map2camera the transformation from map to camera + * @param cam_info_header header of the camera_info message + * @param visible_traffic_lights the visible traffic light object vector + * @param pub publisher + */ void publishVisibleTrafficLights( - const geometry_msgs::msg::PoseStamped camera_pose_stamped, + const tf2::Transform & tf_map2camera, const std_msgs::msg::Header & cam_info_header, const std::vector & visible_traffic_lights, const rclcpp::Publisher::SharedPtr pub); }; diff --git a/perception/traffic_light_map_based_detector/launch/traffic_light_map_based_detector.launch.xml b/perception/traffic_light_map_based_detector/launch/traffic_light_map_based_detector.launch.xml index 465fd4171b9ec..2dc6afa4fa4d5 100644 --- a/perception/traffic_light_map_based_detector/launch/traffic_light_map_based_detector.launch.xml +++ b/perception/traffic_light_map_based_detector/launch/traffic_light_map_based_detector.launch.xml @@ -3,14 +3,26 @@ + + + + + + + + + + + + diff --git a/perception/traffic_light_map_based_detector/package.xml b/perception/traffic_light_map_based_detector/package.xml index 3b19413e5ecd6..1021757e99a07 100644 --- a/perception/traffic_light_map_based_detector/package.xml +++ b/perception/traffic_light_map_based_detector/package.xml @@ -8,10 +8,10 @@ Apache License 2.0 ament_cmake_auto - autoware_cmake + + autoware_cmake autoware_auto_mapping_msgs - autoware_auto_perception_msgs autoware_auto_planning_msgs autoware_planning_msgs geometry_msgs @@ -21,8 +21,10 @@ rclcpp_components sensor_msgs tf2 + tf2_eigen tf2_ros tier4_autoware_utils + tier4_perception_msgs ament_lint_auto autoware_lint_common diff --git a/perception/traffic_light_map_based_detector/src/node.cpp b/perception/traffic_light_map_based_detector/src/node.cpp index d2d54098859c9..99ec2ddb607ad 100644 --- a/perception/traffic_light_map_based_detector/src/node.cpp +++ b/perception/traffic_light_map_based_detector/src/node.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// 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. @@ -11,49 +11,21 @@ // 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 2019 Autoware Foundation. 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. - * - * Authors: Yukihiro Saito - * - */ #include "traffic_light_map_based_detector/node.hpp" #include #include #include -#include #include -#include - #include -#include #include #include #include -#include #include #include -#include -#include -#include -#include - #define EIGEN_MPL2_ONLY #include #include @@ -68,11 +40,10 @@ cv::Point2d calcRawImagePointFromPoint3D( } cv::Point2d calcRawImagePointFromPoint3D( - const image_geometry::PinholeCameraModel & pinhole_camera_model, - const geometry_msgs::msg::Point & point3d) + const image_geometry::PinholeCameraModel & pinhole_camera_model, const tf2::Vector3 & point3d) { return calcRawImagePointFromPoint3D( - pinhole_camera_model, cv::Point3d(point3d.x, point3d.y, point3d.z)); + pinhole_camera_model, cv::Point3d(point3d.x(), point3d.y(), point3d.z())); } void roundInImageFrame( @@ -84,6 +55,60 @@ void roundInImageFrame( point.y = std::max(std::min(point.y, static_cast(static_cast(camera_info.height) - 1)), 0.0); } + +bool isInDistanceRange( + const tf2::Vector3 & p1, const tf2::Vector3 & p2, const double max_distance_range) +{ + const double sq_dist = + (p1.x() - p2.x()) * (p1.x() - p2.x()) + (p1.y() - p2.y()) * (p1.y() - p2.y()); + return sq_dist < (max_distance_range * max_distance_range); +} + +bool isInAngleRange(const double & tl_yaw, const double & camera_yaw, const double max_angle_range) +{ + Eigen::Vector2d vec1, vec2; + vec1 << std::cos(tl_yaw), std::sin(tl_yaw); + vec2 << std::cos(camera_yaw), std::sin(camera_yaw); + const double diff_angle = std::acos(vec1.dot(vec2)); + return std::fabs(diff_angle) < max_angle_range; +} + +bool isInImageFrame( + const image_geometry::PinholeCameraModel & pinhole_camera_model, const tf2::Vector3 & point) +{ + if (point.z() <= 0.0) { + return false; + } + + cv::Point2d point2d = calcRawImagePointFromPoint3D(pinhole_camera_model, point); + if (0 <= point2d.x && point2d.x < pinhole_camera_model.cameraInfo().width) { + if (0 <= point2d.y && point2d.y < pinhole_camera_model.cameraInfo().height) { + return true; + } + } + return false; +} + +tf2::Vector3 getTrafficLightTopLeft(const lanelet::ConstLineString3d & traffic_light) +{ + const auto & tl_bl = traffic_light.front(); + const double tl_height = traffic_light.attributeOr("height", 0.0); + return tf2::Vector3(tl_bl.x(), tl_bl.y(), tl_bl.z() + tl_height); +} + +tf2::Vector3 getTrafficLightBottomRight(const lanelet::ConstLineString3d & traffic_light) +{ + const auto & tl_bl = traffic_light.back(); + return tf2::Vector3(tl_bl.x(), tl_bl.y(), tl_bl.z()); +} + +tf2::Vector3 getTrafficLightCenter(const lanelet::ConstLineString3d & traffic_light) +{ + tf2::Vector3 top_left = getTrafficLightTopLeft(traffic_light); + tf2::Vector3 bottom_right = getTrafficLightBottomRight(traffic_light); + return (top_left + bottom_right) / 2; +} + } // namespace namespace traffic_light @@ -95,6 +120,36 @@ MapBasedDetector::MapBasedDetector(const rclcpp::NodeOptions & node_options) { using std::placeholders::_1; + // parameter declaration needs default values: are 0.0 goof defaults for this? + config_.max_vibration_pitch = declare_parameter("max_vibration_pitch", 0.0); + config_.max_vibration_yaw = declare_parameter("max_vibration_yaw", 0.0); + config_.max_vibration_height = declare_parameter("max_vibration_height", 0.0); + config_.max_vibration_width = declare_parameter("max_vibration_width", 0.0); + config_.max_vibration_depth = declare_parameter("max_vibration_depth", 0.0); + config_.min_timestamp_offset = declare_parameter("min_timestamp_offset", 0.0); + config_.max_timestamp_offset = declare_parameter("max_timestamp_offset", 0.0); + config_.timestamp_sample_len = declare_parameter("timestamp_sample_len", 0.01); + config_.max_detection_range = declare_parameter("max_detection_range", 200.0); + + if (config_.max_detection_range <= 0) { + RCLCPP_ERROR_STREAM( + get_logger(), "Invalid param max_detection_range = " << config_.max_detection_range + << ", set to default value = 200"); + config_.max_detection_range = 200.0; + } + if (config_.timestamp_sample_len <= 0) { + RCLCPP_ERROR_STREAM( + get_logger(), "Invalid param timestamp_sample_len = " << config_.timestamp_sample_len + << ", set to default value = 0.01"); + config_.timestamp_sample_len = 200.0; + } + if (config_.max_timestamp_offset <= config_.min_timestamp_offset) { + RCLCPP_ERROR_STREAM( + get_logger(), "max_timestamp_offset <= min_timestamp_offset. Set both to 0"); + config_.max_timestamp_offset = 0.0; + config_.min_timestamp_offset = 0.0; + } + // subscribers map_sub_ = create_subscription( "~/input/vector_map", rclcpp::QoS{1}.transient_local(), @@ -107,16 +162,24 @@ MapBasedDetector::MapBasedDetector(const rclcpp::NodeOptions & node_options) std::bind(&MapBasedDetector::routeCallback, this, _1)); // publishers - roi_pub_ = this->create_publisher( - "~/output/rois", 1); + roi_pub_ = + this->create_publisher("~/output/rois", 1); + expect_roi_pub_ = + this->create_publisher("~/expect/rois", 1); viz_pub_ = this->create_publisher("~/debug/markers", 1); +} - // parameter declaration needs default values: are 0.0 goof defaults for this? - config_.max_vibration_pitch = declare_parameter("max_vibration_pitch", 0.0); - config_.max_vibration_yaw = declare_parameter("max_vibration_yaw", 0.0); - config_.max_vibration_height = declare_parameter("max_vibration_height", 0.0); - config_.max_vibration_width = declare_parameter("max_vibration_width", 0.0); - config_.max_vibration_depth = declare_parameter("max_vibration_depth", 0.0); +bool MapBasedDetector::getTransform( + const rclcpp::Time & t, const std::string & frame_id, tf2::Transform & tf) const +{ + try { + geometry_msgs::msg::TransformStamped transform = + tf_buffer_.lookupTransform("map", frame_id, t, rclcpp::Duration::from_seconds(0.2)); + tf2::fromMsg(transform.transform, tf); + } catch (tf2::TransformException & ex) { + return false; + } + return true; } void MapBasedDetector::cameraInfoCallback( @@ -129,23 +192,35 @@ void MapBasedDetector::cameraInfoCallback( image_geometry::PinholeCameraModel pinhole_camera_model; pinhole_camera_model.fromCameraInfo(*input_msg); - autoware_auto_perception_msgs::msg::TrafficLightRoiArray output_msg; + tier4_perception_msgs::msg::TrafficLightRoiArray output_msg; output_msg.header = input_msg->header; - - /* Camera pose */ - geometry_msgs::msg::PoseStamped camera_pose_stamped; - try { - geometry_msgs::msg::TransformStamped transform; - transform = tf_buffer_.lookupTransform( - "map", input_msg->header.frame_id, input_msg->header.stamp, - rclcpp::Duration::from_seconds(0.2)); - camera_pose_stamped.header = input_msg->header; - camera_pose_stamped.pose = tier4_autoware_utils::transform2pose(transform.transform); - } catch (tf2::TransformException & ex) { + tier4_perception_msgs::msg::TrafficLightRoiArray expect_roi_msg; + expect_roi_msg = output_msg; + + /* Camera pose in the period*/ + std::vector tf_map2camera_vec; + rclcpp::Time t1 = rclcpp::Time(input_msg->header.stamp) + + rclcpp::Duration::from_seconds(config_.min_timestamp_offset); + rclcpp::Time t2 = rclcpp::Time(input_msg->header.stamp) + + rclcpp::Duration::from_seconds(config_.max_timestamp_offset); + rclcpp::Duration interval = rclcpp::Duration::from_seconds(0.01); + for (auto t = t1; t <= t2; t += interval) { + tf2::Transform tf; + if (getTransform(t, input_msg->header.frame_id, tf)) { + tf_map2camera_vec.push_back(tf); + } + } + /* camera pose at the exact moment*/ + tf2::Transform tf_map2camera; + if (!getTransform( + rclcpp::Time(input_msg->header.stamp), input_msg->header.frame_id, tf_map2camera)) { RCLCPP_WARN_THROTTLE( get_logger(), *get_clock(), 5000, "cannot get transform from map frame to camera frame"); return; } + if (tf_map2camera_vec.empty()) { + tf_map2camera_vec.push_back(tf_map2camera); + } /* * visible_traffic_lights : for each traffic light in map check if in range and in view angle of @@ -155,13 +230,11 @@ void MapBasedDetector::cameraInfoCallback( // If get a route, use only traffic lights on the route. if (route_traffic_lights_ptr_ != nullptr) { getVisibleTrafficLights( - *route_traffic_lights_ptr_, camera_pose_stamped.pose, pinhole_camera_model, - visible_traffic_lights); + *route_traffic_lights_ptr_, tf_map2camera_vec, pinhole_camera_model, visible_traffic_lights); // If don't get a route, use the traffic lights around ego vehicle. } else if (all_traffic_lights_ptr_ != nullptr) { getVisibleTrafficLights( - *all_traffic_lights_ptr_, camera_pose_stamped.pose, pinhole_camera_model, - visible_traffic_lights); + *all_traffic_lights_ptr_, tf_map2camera_vec, pinhole_camera_model, visible_traffic_lights); // This shouldn't run. } else { return; @@ -171,100 +244,134 @@ void MapBasedDetector::cameraInfoCallback( * Get the ROI from the lanelet and the intrinsic matrix of camera to determine where it appears * in image. */ + /** + * set all offset to zero when calculating the expect roi + */ + Config expect_roi_cfg = config_; + expect_roi_cfg.max_vibration_depth = 0; + expect_roi_cfg.max_vibration_height = 0; + expect_roi_cfg.max_vibration_width = 0; + expect_roi_cfg.max_vibration_yaw = 0; + expect_roi_cfg.max_vibration_pitch = 0; for (const auto & traffic_light : visible_traffic_lights) { - autoware_auto_perception_msgs::msg::TrafficLightRoi tl_roi; + tier4_perception_msgs::msg::TrafficLightRoi rough_roi, expect_roi; + if (!getTrafficLightRoi( + tf_map2camera, pinhole_camera_model, traffic_light, expect_roi_cfg, expect_roi)) { + continue; + } if (!getTrafficLightRoi( - camera_pose_stamped.pose, pinhole_camera_model, traffic_light, config_, tl_roi)) { + tf_map2camera_vec, pinhole_camera_model, traffic_light, config_, rough_roi)) { continue; } - output_msg.rois.push_back(tl_roi); + output_msg.rois.push_back(rough_roi); + expect_roi_msg.rois.push_back(expect_roi); } + roi_pub_->publish(output_msg); - publishVisibleTrafficLights(camera_pose_stamped, visible_traffic_lights, viz_pub_); + expect_roi_pub_->publish(expect_roi_msg); + publishVisibleTrafficLights( + tf_map2camera_vec[0], input_msg->header, visible_traffic_lights, viz_pub_); } bool MapBasedDetector::getTrafficLightRoi( - const geometry_msgs::msg::Pose & camera_pose, + const tf2::Transform & tf_map2camera, const image_geometry::PinholeCameraModel & pinhole_camera_model, const lanelet::ConstLineString3d traffic_light, const Config & config, - autoware_auto_perception_msgs::msg::TrafficLightRoi & tl_roi) + tier4_perception_msgs::msg::TrafficLightRoi & roi) const { - const double tl_height = traffic_light.attributeOr("height", 0.0); - const auto & tl_left_down_point = traffic_light.front(); - const auto & tl_right_down_point = traffic_light.back(); - - tf2::Transform tf_map2camera( - tf2::Quaternion( - camera_pose.orientation.x, camera_pose.orientation.y, camera_pose.orientation.z, - camera_pose.orientation.w), - tf2::Vector3(camera_pose.position.x, camera_pose.position.y, camera_pose.position.z)); - // id - tl_roi.id = traffic_light.id(); + roi.traffic_light_id = traffic_light.id(); // for roi.x_offset and roi.y_offset { - tf2::Transform tf_map2tl( - tf2::Quaternion(0, 0, 0, 1), - tf2::Vector3( - tl_left_down_point.x(), tl_left_down_point.y(), tl_left_down_point.z() + tl_height)); - tf2::Transform tf_camera2tl; - tf_camera2tl = tf_map2camera.inverse() * tf_map2tl; + tf2::Vector3 map2tl = getTrafficLightTopLeft(traffic_light); + tf2::Vector3 camera2tl = tf_map2camera.inverse() * map2tl; // max vibration const double max_vibration_x = - std::sin(config.max_vibration_yaw * 0.5) * tf_camera2tl.getOrigin().z() + - config.max_vibration_width * 0.5; - const double max_vibration_y = - std::sin(config.max_vibration_pitch * 0.5) * tf_camera2tl.getOrigin().z() + - config.max_vibration_height * 0.5; + std::sin(config.max_vibration_yaw * 0.5) * camera2tl.z() + config.max_vibration_width * 0.5; + const double max_vibration_y = std::sin(config.max_vibration_pitch * 0.5) * camera2tl.z() + + config.max_vibration_height * 0.5; const double max_vibration_z = config.max_vibration_depth * 0.5; - // target position in camera coordinate - geometry_msgs::msg::Point point3d; - point3d.x = tf_camera2tl.getOrigin().x() - max_vibration_x; - point3d.y = tf_camera2tl.getOrigin().y() - max_vibration_y; - point3d.z = tf_camera2tl.getOrigin().z() - max_vibration_z; - if (point3d.z <= 0.0) { - return false; + // enlarged target position in camera coordinate + { + tf2::Vector3 point3d = + camera2tl - tf2::Vector3(max_vibration_x, max_vibration_y, max_vibration_z); + if (point3d.z() <= 0.0) { + return false; + } + cv::Point2d point2d = calcRawImagePointFromPoint3D(pinhole_camera_model, point3d); + roundInImageFrame(pinhole_camera_model, point2d); + roi.roi.x_offset = point2d.x; + roi.roi.y_offset = point2d.y; } - cv::Point2d point2d = calcRawImagePointFromPoint3D(pinhole_camera_model, point3d); - roundInImageFrame(pinhole_camera_model, point2d); - tl_roi.roi.x_offset = point2d.x; - tl_roi.roi.y_offset = point2d.y; } // for roi.width and roi.height { - tf2::Transform tf_map2tl( - tf2::Quaternion(0, 0, 0, 1), - tf2::Vector3(tl_right_down_point.x(), tl_right_down_point.y(), tl_right_down_point.z())); - tf2::Transform tf_camera2tl; - tf_camera2tl = tf_map2camera.inverse() * tf_map2tl; + tf2::Vector3 map2tl = getTrafficLightBottomRight(traffic_light); + tf2::Vector3 camera2tl = tf_map2camera.inverse() * map2tl; // max vibration const double max_vibration_x = - std::sin(config.max_vibration_yaw * 0.5) * tf_camera2tl.getOrigin().z() + - config.max_vibration_width * 0.5; - const double max_vibration_y = - std::sin(config.max_vibration_pitch * 0.5) * tf_camera2tl.getOrigin().z() + - config.max_vibration_height * 0.5; + std::sin(config.max_vibration_yaw * 0.5) * camera2tl.z() + config.max_vibration_width * 0.5; + const double max_vibration_y = std::sin(config.max_vibration_pitch * 0.5) * camera2tl.z() + + config.max_vibration_height * 0.5; const double max_vibration_z = config.max_vibration_depth * 0.5; - // target position in camera coordinate - geometry_msgs::msg::Point point3d; - point3d.x = tf_camera2tl.getOrigin().x() + max_vibration_x; - point3d.y = tf_camera2tl.getOrigin().y() + max_vibration_y; - point3d.z = tf_camera2tl.getOrigin().z() - max_vibration_z; - if (point3d.z <= 0.0) { - return false; + // enlarged target position in camera coordinate + { + tf2::Vector3 point3d = + camera2tl + tf2::Vector3(max_vibration_x, max_vibration_y, -max_vibration_z); + if (point3d.z() <= 0.0) { + return false; + } + cv::Point2d point2d = calcRawImagePointFromPoint3D(pinhole_camera_model, point3d); + roundInImageFrame(pinhole_camera_model, point2d); + roi.roi.width = point2d.x - roi.roi.x_offset; + roi.roi.height = point2d.y - roi.roi.y_offset; } - cv::Point2d point2d = calcRawImagePointFromPoint3D(pinhole_camera_model, point3d); - roundInImageFrame(pinhole_camera_model, point2d); - tl_roi.roi.width = point2d.x - tl_roi.roi.x_offset; - tl_roi.roi.height = point2d.y - tl_roi.roi.y_offset; - if (tl_roi.roi.width < 1 || tl_roi.roi.height < 1) { + + if (roi.roi.width < 1 || roi.roi.height < 1) { return false; } } return true; } +bool MapBasedDetector::getTrafficLightRoi( + const std::vector & tf_map2camera_vec, + const image_geometry::PinholeCameraModel & pinhole_camera_model, + const lanelet::ConstLineString3d traffic_light, const Config & config, + tier4_perception_msgs::msg::TrafficLightRoi & out_roi) const +{ + std::vector rois; + for (const auto & tf_map2camera : tf_map2camera_vec) { + tier4_perception_msgs::msg::TrafficLightRoi roi; + if (getTrafficLightRoi(tf_map2camera, pinhole_camera_model, traffic_light, config, roi)) { + rois.push_back(roi); + } + } + if (rois.empty()) { + return false; + } + out_roi = rois.front(); + /** + * get the maximum possible rough roi among all the tf + */ + uint32_t x1 = pinhole_camera_model.cameraInfo().width - 1; + uint32_t x2 = 0; + uint32_t y1 = pinhole_camera_model.cameraInfo().height - 1; + uint32_t y2 = 0; + for (const auto & roi : rois) { + x1 = std::min(x1, roi.roi.x_offset); + x2 = std::max(x2, roi.roi.x_offset + roi.roi.width); + y1 = std::min(y1, roi.roi.y_offset); + y2 = std::max(y2, roi.roi.y_offset + roi.roi.height); + } + out_roi.roi.x_offset = x1; + out_roi.roi.y_offset = y1; + out_roi.roi.width = x2 - x1; + out_roi.roi.height = y2 - y1; + return true; +} + void MapBasedDetector::mapCallback( const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg) { @@ -326,9 +433,9 @@ void MapBasedDetector::routeCallback( void MapBasedDetector::getVisibleTrafficLights( const MapBasedDetector::TrafficLightSet & all_traffic_lights, - const geometry_msgs::msg::Pose & camera_pose, + const std::vector & tf_map2camera_vec, const image_geometry::PinholeCameraModel & pinhole_camera_model, - std::vector & visible_traffic_lights) + std::vector & visible_traffic_lights) const { for (const auto & traffic_light : all_traffic_lights) { // some "Traffic Light" are actually not traffic lights @@ -337,132 +444,62 @@ void MapBasedDetector::getVisibleTrafficLights( traffic_light.attribute("subtype").value() == "solid") { continue; } - const auto & tl_left_down_point = traffic_light.front(); - const auto & tl_right_down_point = traffic_light.back(); - const double tl_height = traffic_light.attributeOr("height", 0.0); - + // traffic light bottom left + const auto & tl_bl = traffic_light.front(); + // traffic light bottom right + const auto & tl_br = traffic_light.back(); // check distance range - geometry_msgs::msg::Point tl_central_point; - tl_central_point.x = (tl_right_down_point.x() + tl_left_down_point.x()) / 2.0; - tl_central_point.y = (tl_right_down_point.y() + tl_left_down_point.y()) / 2.0; - tl_central_point.z = (tl_right_down_point.z() + tl_left_down_point.z() + tl_height) / 2.0; - constexpr double max_distance_range = 200.0; - if (!isInDistanceRange(tl_central_point, camera_pose.position, max_distance_range)) { - continue; - } - - // check angle range - const double tl_yaw = tier4_autoware_utils::normalizeRadian( - std::atan2( - tl_right_down_point.y() - tl_left_down_point.y(), - tl_right_down_point.x() - tl_left_down_point.x()) + - M_PI_2); - constexpr double max_angle_range = tier4_autoware_utils::deg2rad(40.0); - - // get direction of z axis - tf2::Vector3 camera_z_dir(0, 0, 1); - tf2::Matrix3x3 camera_rotation_matrix(tf2::Quaternion( - camera_pose.orientation.x, camera_pose.orientation.y, camera_pose.orientation.z, - camera_pose.orientation.w)); - camera_z_dir = camera_rotation_matrix * camera_z_dir; - double camera_yaw = std::atan2(camera_z_dir.y(), camera_z_dir.x()); - camera_yaw = tier4_autoware_utils::normalizeRadian(camera_yaw); - if (!isInAngleRange(tl_yaw, camera_yaw, max_angle_range)) { - continue; - } - - // check within image frame - tf2::Transform tf_map2camera( - tf2::Quaternion( - camera_pose.orientation.x, camera_pose.orientation.y, camera_pose.orientation.z, - camera_pose.orientation.w), - tf2::Vector3(camera_pose.position.x, camera_pose.position.y, camera_pose.position.z)); - tf2::Transform tf_map2tl( - tf2::Quaternion(0, 0, 0, 1), - tf2::Vector3(tl_central_point.x, tl_central_point.y, tl_central_point.z)); - tf2::Transform tf_camera2tl; - tf_camera2tl = tf_map2camera.inverse() * tf_map2tl; - - geometry_msgs::msg::Point camera2tl_point; - camera2tl_point.x = tf_camera2tl.getOrigin().x(); - camera2tl_point.y = tf_camera2tl.getOrigin().y(); - camera2tl_point.z = tf_camera2tl.getOrigin().z(); - if (!isInImageFrame(pinhole_camera_model, camera2tl_point)) { - continue; - } - visible_traffic_lights.push_back(traffic_light); - } -} - -bool MapBasedDetector::isInDistanceRange( - const geometry_msgs::msg::Point & tl_point, const geometry_msgs::msg::Point & camera_point, - const double max_distance_range) const -{ - const double sq_dist = (tl_point.x - camera_point.x) * (tl_point.x - camera_point.x) + - (tl_point.y - camera_point.y) * (tl_point.y - camera_point.y); - return sq_dist < (max_distance_range * max_distance_range); -} - -bool MapBasedDetector::isInAngleRange( - const double & tl_yaw, const double & camera_yaw, const double max_angle_range) const -{ - Eigen::Vector2d vec1, vec2; - vec1 << std::cos(tl_yaw), std::sin(tl_yaw); - vec2 << std::cos(camera_yaw), std::sin(camera_yaw); - const double diff_angle = std::acos(vec1.dot(vec2)); - return std::fabs(diff_angle) < max_angle_range; -} + tf2::Vector3 tl_center = getTrafficLightCenter(traffic_light); + // for every possible transformation, check if the tl is visible. + // If under any tf the tl is visible, keep it + for (const auto & tf_map2camera : tf_map2camera_vec) { + if (!isInDistanceRange(tl_center, tf_map2camera.getOrigin(), config_.max_detection_range)) { + continue; + } -bool MapBasedDetector::isInImageFrame( - const image_geometry::PinholeCameraModel & pinhole_camera_model, - const geometry_msgs::msg::Point & point) const -{ - if (point.z <= 0.0) { - return false; - } + // check angle range + const double tl_yaw = tier4_autoware_utils::normalizeRadian( + std::atan2(tl_br.y() - tl_bl.y(), tl_br.x() - tl_bl.x()) + M_PI_2); + constexpr double max_angle_range = tier4_autoware_utils::deg2rad(40.0); + + // get direction of z axis + tf2::Vector3 camera_z_dir(0, 0, 1); + tf2::Matrix3x3 camera_rotation_matrix(tf_map2camera.getRotation()); + camera_z_dir = camera_rotation_matrix * camera_z_dir; + double camera_yaw = std::atan2(camera_z_dir.y(), camera_z_dir.x()); + camera_yaw = tier4_autoware_utils::normalizeRadian(camera_yaw); + if (!isInAngleRange(tl_yaw, camera_yaw, max_angle_range)) { + continue; + } - cv::Point2d point2d = calcRawImagePointFromPoint3D(pinhole_camera_model, point); - if (0 <= point2d.x && point2d.x < pinhole_camera_model.cameraInfo().width) { - if (0 <= point2d.y && point2d.y < pinhole_camera_model.cameraInfo().height) { - return true; + // check within image frame + tf2::Vector3 tf_camera2tltl = tf_map2camera.inverse() * getTrafficLightTopLeft(traffic_light); + tf2::Vector3 tf_camera2tlbr = + tf_map2camera.inverse() * getTrafficLightBottomRight(traffic_light); + if ( + !isInImageFrame(pinhole_camera_model, tf_camera2tltl) && + !isInImageFrame(pinhole_camera_model, tf_camera2tlbr)) { + continue; + } + visible_traffic_lights.push_back(traffic_light); + break; } } - return false; } void MapBasedDetector::publishVisibleTrafficLights( - const geometry_msgs::msg::PoseStamped camera_pose_stamped, + const tf2::Transform & tf_map2camera, const std_msgs::msg::Header & cam_info_header, const std::vector & visible_traffic_lights, const rclcpp::Publisher::SharedPtr pub) { visualization_msgs::msg::MarkerArray output_msg; for (const auto & traffic_light : visible_traffic_lights) { - const auto & tl_left_down_point = traffic_light.front(); - const auto & tl_right_down_point = traffic_light.back(); - const double tl_height = traffic_light.attributeOr("height", 0.0); const int id = traffic_light.id(); - - geometry_msgs::msg::Point tl_central_point; - tl_central_point.x = (tl_right_down_point.x() + tl_left_down_point.x()) / 2.0; - tl_central_point.y = (tl_right_down_point.y() + tl_left_down_point.y()) / 2.0; - tl_central_point.z = (tl_right_down_point.z() + tl_left_down_point.z() + tl_height) / 2.0; + tf2::Vector3 tl_central_point = getTrafficLightCenter(traffic_light); + tf2::Vector3 camera2tl = tf_map2camera.inverse() * tl_central_point; visualization_msgs::msg::Marker marker; - - tf2::Transform tf_map2camera( - tf2::Quaternion( - camera_pose_stamped.pose.orientation.x, camera_pose_stamped.pose.orientation.y, - camera_pose_stamped.pose.orientation.z, camera_pose_stamped.pose.orientation.w), - tf2::Vector3( - camera_pose_stamped.pose.position.x, camera_pose_stamped.pose.position.y, - camera_pose_stamped.pose.position.z)); - tf2::Transform tf_map2tl( - tf2::Quaternion(0, 0, 0, 1), - tf2::Vector3(tl_central_point.x, tl_central_point.y, tl_central_point.z)); - tf2::Transform tf_camera2tl; - tf_camera2tl = tf_map2camera.inverse() * tf_map2tl; - - marker.header = camera_pose_stamped.header; + marker.header = cam_info_header; marker.id = id; marker.type = visualization_msgs::msg::Marker::LINE_LIST; marker.ns = std::string("beam"); @@ -480,9 +517,9 @@ void MapBasedDetector::publishVisibleTrafficLights( point.y = 0.0; point.z = 0.0; marker.points.push_back(point); - point.x = tf_camera2tl.getOrigin().x(); - point.y = tf_camera2tl.getOrigin().y(); - point.z = tf_camera2tl.getOrigin().z(); + point.x = camera2tl.x(); + point.y = camera2tl.y(); + point.z = camera2tl.z(); marker.points.push_back(point); marker.lifetime = rclcpp::Duration::from_seconds(0.2); diff --git a/perception/traffic_light_multi_camera_fusion/CMakeLists.txt b/perception/traffic_light_multi_camera_fusion/CMakeLists.txt new file mode 100644 index 0000000000000..5765ebf58fd45 --- /dev/null +++ b/perception/traffic_light_multi_camera_fusion/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.14) +project(traffic_light_multi_camera_fusion) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +include_directories( + SYSTEM +) + +ament_auto_add_library(traffic_light_multi_camera_fusion SHARED + src/node.cpp +) + +rclcpp_components_register_node(traffic_light_multi_camera_fusion + PLUGIN "traffic_light::MultiCameraFusion" + EXECUTABLE traffic_light_multi_camera_fusion_node +) + +ament_auto_package(INSTALL_TO_SHARE + launch + config +) diff --git a/perception/traffic_light_multi_camera_fusion/README.md b/perception/traffic_light_multi_camera_fusion/README.md new file mode 100644 index 0000000000000..ded0613a202ad --- /dev/null +++ b/perception/traffic_light_multi_camera_fusion/README.md @@ -0,0 +1,34 @@ +# The `traffic_light_multi_camera_fusion` Package + +## Overview + +`traffic_light_multi_camera_fusion` performs traffic light signal fusion which can be summarized as the following two tasks: + +1. Multi-Camera-Fusion: performed on single traffic light signal detected by different cameras. +2. Group-Fusion: performed on traffic light signals within the same group, which means traffic lights sharing the same regulatory element id defined in lanetlet2 map. + +## Input topics + +For every camera, the following three topics are subscribed: +| Name | Type | | +| ---------------------------------------| -------------------------------------------------------|----------------------------------------------------| +| `~//camera_info` | sensor_msgs::CameraInfo |camera info from traffic_light_map_based_detector | +| `~//rois` | tier4_perception_msgs::TrafficLightRoiArray |detection roi from traffic_light_fine_detector | +| `~//traffic_signals` | tier4_perception_msgs::TrafficLightSignalArray |classification result from traffic_light_classifier | + +You don't need to configure these topics manually. Just provide the `camera_namespaces` parameter and the node will automatically extract the `` and create the subscribers. + +## Output topics + +| Name | Type | Description | +| -------------------------- | ---------------------------------------------- | ---------------------------------- | +| `~/output/traffic_signals` | tier4_perception_msgs::TrafficLightSignalArray | traffic light signal fusion result | + +## Node parameters + +| Parameter | Type | Description | +| ---------------------- | --------------- | ------------------------------------------------ | +| `camera_namespaces` | vector\ | Camera Namespaces to be fused | +| `message_lifespan` | double | The maximum timestamp span to be fused | +| `approximate_sync` | bool | Whether work in Approximate Synchronization Mode | +| `perform_group_fusion` | bool | Whether perform Group Fusion | diff --git a/perception/traffic_light_multi_camera_fusion/config/traffic_light_multi_camera_fusion.param.yaml b/perception/traffic_light_multi_camera_fusion/config/traffic_light_multi_camera_fusion.param.yaml new file mode 100644 index 0000000000000..4e9459ce4a71c --- /dev/null +++ b/perception/traffic_light_multi_camera_fusion/config/traffic_light_multi_camera_fusion.param.yaml @@ -0,0 +1,6 @@ +/**: + ros__parameters: + camera_namespaces: ["camera6", "camera7"] + message_lifespan: 0.09 + approximate_sync: false + perform_group_fusion: true diff --git a/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp b/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp new file mode 100644 index 0000000000000..bc63f34b191e7 --- /dev/null +++ b/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp @@ -0,0 +1,131 @@ +// 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 TRAFFIC_LIGHT_MULTI_CAMERA_FUSION__NODE_HPP_ +#define TRAFFIC_LIGHT_MULTI_CAMERA_FUSION__NODE_HPP_ + +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace traffic_light +{ + +namespace mf = message_filters; + +struct FusionRecord +{ + std_msgs::msg::Header header; + sensor_msgs::msg::CameraInfo cam_info; + tier4_perception_msgs::msg::TrafficLightRoi roi; + tier4_perception_msgs::msg::TrafficSignal signal; +}; + +struct FusionRecordArr +{ + std_msgs::msg::Header header; + sensor_msgs::msg::CameraInfo cam_info; + tier4_perception_msgs::msg::TrafficLightRoiArray rois; + tier4_perception_msgs::msg::TrafficSignalArray signals; +}; + +bool operator<(const FusionRecordArr & r1, const FusionRecordArr & r2) +{ + return rclcpp::Time(r1.header.stamp) < rclcpp::Time(r2.header.stamp); +} + +class MultiCameraFusion : public rclcpp::Node +{ +public: + typedef sensor_msgs::msg::CameraInfo CamInfoType; + typedef tier4_perception_msgs::msg::TrafficLightRoi RoiType; + typedef tier4_perception_msgs::msg::TrafficSignal SignalType; + typedef tier4_perception_msgs::msg::TrafficSignalArray SignalArrayType; + typedef tier4_perception_msgs::msg::TrafficLightRoiArray RoiArrayType; + typedef tier4_perception_msgs::msg::TrafficLightRoi::_traffic_light_id_type IdType; + typedef autoware_perception_msgs::msg::TrafficSignal NewSignalType; + typedef autoware_perception_msgs::msg::TrafficSignalArray NewSignalArrayType; + + typedef std::pair RecordArrayType; + + explicit MultiCameraFusion(const rclcpp::NodeOptions & node_options); + +private: + void trafficSignalRoiCallback( + const CamInfoType::ConstSharedPtr cam_info_msg, const RoiArrayType::ConstSharedPtr roi_msg, + const SignalArrayType::ConstSharedPtr signal_msg); + + void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg); + + void multiCameraFusion(std::map & fusioned_record_map); + + void convertOutputMsg( + const std::map & grouped_record_map, NewSignalArrayType & msg_out); + + void groupFusion( + std::map & fusioned_record_map, + std::map & grouped_record_map); + + typedef mf::sync_policies::ExactTime ExactSyncPolicy; + typedef mf::Synchronizer ExactSync; + typedef mf::sync_policies::ApproximateTime + ApproSyncPolicy; + typedef mf::Synchronizer ApproSync; + + std::vector>> signal_subs_; + std::vector>> roi_subs_; + std::vector>> cam_info_subs_; + std::vector> exact_sync_subs_; + std::vector> appro_sync_subs_; + rclcpp::Subscription::SharedPtr map_sub_; + + rclcpp::Publisher::SharedPtr signal_pub_; + /* + the mappping from traffic light id (instance id) to regulatory element id (group id) + */ + std::map traffic_light_id_to_regulatory_ele_id_; + /* + save record arrays by increasing timestamp order. + use multiset in case there are multiple cameras publishing images at exactly the same time + */ + std::multiset record_arr_set_; + bool is_approximate_sync_; + /* + for every input message input_m, if the timestamp difference between input_m and the latest + message is smaller than message_lifespan_, then input_m would be used for the fusion. Otherwise, + it would be discarded + */ + double message_lifespan_; +}; +} // namespace traffic_light +#endif // TRAFFIC_LIGHT_MULTI_CAMERA_FUSION__NODE_HPP_ diff --git a/perception/traffic_light_multi_camera_fusion/launch/traffic_light_multi_camera_fusion.launch.xml b/perception/traffic_light_multi_camera_fusion/launch/traffic_light_multi_camera_fusion.launch.xml new file mode 100644 index 0000000000000..9aa4958378c1c --- /dev/null +++ b/perception/traffic_light_multi_camera_fusion/launch/traffic_light_multi_camera_fusion.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/perception/traffic_light_multi_camera_fusion/package.xml b/perception/traffic_light_multi_camera_fusion/package.xml new file mode 100644 index 0000000000000..6dd0bf89bd716 --- /dev/null +++ b/perception/traffic_light_multi_camera_fusion/package.xml @@ -0,0 +1,28 @@ + + + + traffic_light_multi_camera_fusion + 0.1.0 + The traffic_light_multi_camera_fusion package + Mingyu Li + Apache License 2.0 + + ament_cmake_auto + + autoware_cmake + + autoware_auto_mapping_msgs + autoware_perception_msgs + lanelet2_extension + rclcpp + rclcpp_components + sensor_msgs + tier4_perception_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/perception/traffic_light_multi_camera_fusion/src/node.cpp b/perception/traffic_light_multi_camera_fusion/src/node.cpp new file mode 100644 index 0000000000000..7500193a3b643 --- /dev/null +++ b/perception/traffic_light_multi_camera_fusion/src/node.cpp @@ -0,0 +1,322 @@ +// 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 "traffic_light_multi_camera_fusion/node.hpp" + +#include +#include +#include +#include + +namespace +{ + +bool isUnknown(const tier4_perception_msgs::msg::TrafficSignal & signal) +{ + return signal.elements.size() == 1 && + signal.elements[0].color == tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN && + signal.elements[0].shape == tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; +} + +/** + * @brief Currently the visible score only considers the truncation. + * If the detection roi is very close to the image boundary, it would be considered as truncated. + * + * @param record fusion record + * @return 0 if traffic light is truncated, otherwise 1 + */ +int calVisibleScore(const traffic_light::FusionRecord & record) +{ + const uint32_t boundary = 5; + uint32_t x1 = record.roi.roi.x_offset; + uint32_t x2 = record.roi.roi.x_offset + record.roi.roi.width; + uint32_t y1 = record.roi.roi.y_offset; + uint32_t y2 = record.roi.roi.y_offset + record.roi.roi.height; + if ( + x1 <= boundary || (record.cam_info.width - x2) <= boundary || y1 <= boundary || + (record.cam_info.height - y2) <= boundary) { + return 0; + } else { + return 1; + } +} + +int compareRecord(const traffic_light::FusionRecord & r1, const traffic_light::FusionRecord & r2) +{ + /* + if both records are from the same sensor but different stamp, trust the latest one + */ + double t1 = rclcpp::Time(r1.header.stamp).seconds(); + double t2 = rclcpp::Time(r2.header.stamp).seconds(); + const double dt_thres = 1e-3; + if (r1.header.frame_id == r2.header.frame_id && std::abs(t1 - t2) >= dt_thres) { + return t1 < t2 ? -1 : 1; + } + bool r1_is_unknown = isUnknown(r1.signal); + bool r2_is_unknown = isUnknown(r2.signal); + /* + if both are unknown, they are of the same priority + */ + if (r1_is_unknown && r2_is_unknown) { + return 0; + } else if (r1_is_unknown ^ r2_is_unknown) { + /* + if either is unknown, the unknown is of lower priority + */ + return r1_is_unknown ? -1 : 1; + } + int visible_score_1 = calVisibleScore(r1); + int visible_score_2 = calVisibleScore(r2); + if (visible_score_1 == visible_score_2) { + int area_1 = r1.roi.roi.width * r1.roi.roi.height; + int area_2 = r2.roi.roi.width * r2.roi.roi.height; + if (area_1 < area_2) { + return -1; + } else { + return static_cast(area_1 > area_2); + } + } else { + return visible_score_1 < visible_score_2 ? -1 : 1; + } +} + +template +V at_or(const std::unordered_map & map, const K & key, const V & value) +{ + return map.count(key) ? map.at(key) : value; +} + +autoware_perception_msgs::msg::TrafficLightElement convert( + const tier4_perception_msgs::msg::TrafficLightElement & input) +{ + typedef tier4_perception_msgs::msg::TrafficLightElement OldElem; + typedef autoware_perception_msgs::msg::TrafficLightElement NewElem; + static const std::unordered_map color_map( + {{OldElem::RED, NewElem::RED}, + {OldElem::AMBER, NewElem::AMBER}, + {OldElem::GREEN, NewElem::GREEN}, + {OldElem::WHITE, NewElem::WHITE}}); + static const std::unordered_map shape_map( + {{OldElem::CIRCLE, NewElem::CIRCLE}, + {OldElem::LEFT_ARROW, NewElem::LEFT_ARROW}, + {OldElem::RIGHT_ARROW, NewElem::RIGHT_ARROW}, + {OldElem::UP_ARROW, NewElem::UP_ARROW}, + {OldElem::UP_LEFT_ARROW, NewElem::UP_LEFT_ARROW}, + {OldElem::UP_RIGHT_ARROW, NewElem::UP_RIGHT_ARROW}, + {OldElem::DOWN_ARROW, NewElem::DOWN_ARROW}, + {OldElem::DOWN_LEFT_ARROW, NewElem::DOWN_LEFT_ARROW}, + {OldElem::DOWN_RIGHT_ARROW, NewElem::DOWN_RIGHT_ARROW}, + {OldElem::CROSS, NewElem::CROSS}}); + static const std::unordered_map status_map( + {{OldElem::SOLID_OFF, NewElem::SOLID_OFF}, + {OldElem::SOLID_ON, NewElem::SOLID_ON}, + {OldElem::FLASHING, NewElem::FLASHING}}); + // clang-format on + + NewElem output; + output.color = at_or(color_map, input.color, NewElem::UNKNOWN); + output.shape = at_or(shape_map, input.shape, NewElem::UNKNOWN); + output.status = at_or(status_map, input.status, NewElem::UNKNOWN); + output.confidence = input.confidence; + return output; +} + +} // namespace + +namespace traffic_light +{ + +MultiCameraFusion::MultiCameraFusion(const rclcpp::NodeOptions & node_options) +: Node("traffic_light_multi_camera_fusion", node_options) +{ + using std::placeholders::_1; + using std::placeholders::_2; + using std::placeholders::_3; + + std::vector camera_namespaces = + this->declare_parameter("camera_namespaces", std::vector{}); + is_approximate_sync_ = this->declare_parameter("approximate_sync", false); + message_lifespan_ = this->declare_parameter("message_lifespan", 0.09); + for (const std::string & camera_ns : camera_namespaces) { + std::string signal_topic = camera_ns + "/traffic_signals"; + std::string roi_topic = camera_ns + "/rois"; + std::string cam_info_topic = camera_ns + "/camera_info"; + roi_subs_.emplace_back( + new mf::Subscriber(this, roi_topic, rclcpp::QoS{1}.get_rmw_qos_profile())); + signal_subs_.emplace_back(new mf::Subscriber( + this, signal_topic, rclcpp::QoS{1}.get_rmw_qos_profile())); + cam_info_subs_.emplace_back(new mf::Subscriber( + this, cam_info_topic, rclcpp::SensorDataQoS().get_rmw_qos_profile())); + if (is_approximate_sync_ == false) { + exact_sync_subs_.emplace_back(new ExactSync( + ExactSyncPolicy(10), *(cam_info_subs_.back()), *(roi_subs_.back()), + *(signal_subs_.back()))); + exact_sync_subs_.back()->registerCallback( + std::bind(&MultiCameraFusion::trafficSignalRoiCallback, this, _1, _2, _3)); + } else { + appro_sync_subs_.emplace_back(new ApproSync( + ApproSyncPolicy(10), *(cam_info_subs_.back()), *(roi_subs_.back()), + *(signal_subs_.back()))); + appro_sync_subs_.back()->registerCallback( + std::bind(&MultiCameraFusion::trafficSignalRoiCallback, this, _1, _2, _3)); + } + } + + map_sub_ = create_subscription( + "~/input/vector_map", rclcpp::QoS{1}.transient_local(), + std::bind(&MultiCameraFusion::mapCallback, this, _1)); + signal_pub_ = create_publisher("~/output/traffic_signals", rclcpp::QoS{1}); +} + +void MultiCameraFusion::trafficSignalRoiCallback( + const CamInfoType::ConstSharedPtr cam_info_msg, const RoiArrayType::ConstSharedPtr roi_msg, + const SignalArrayType::ConstSharedPtr signal_msg) +{ + rclcpp::Time stamp(roi_msg->header.stamp); + /* + Insert the received record array to the table. + Attention should be paied that this record array might not have the newest timestamp + */ + record_arr_set_.insert( + FusionRecordArr{cam_info_msg->header, *cam_info_msg, *roi_msg, *signal_msg}); + + std::map fusioned_record_map, grouped_record_map; + multiCameraFusion(fusioned_record_map); + groupFusion(fusioned_record_map, grouped_record_map); + + NewSignalArrayType msg_out; + convertOutputMsg(grouped_record_map, msg_out); + msg_out.stamp = cam_info_msg->header.stamp; + signal_pub_->publish(msg_out); +} + +void MultiCameraFusion::mapCallback( + const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg) +{ + lanelet::LaneletMapPtr lanelet_map_ptr = std::make_shared(); + + lanelet::utils::conversion::fromBinMsg(*input_msg, lanelet_map_ptr); + lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr); + std::vector all_lanelet_traffic_lights = + lanelet::utils::query::autowareTrafficLights(all_lanelets); + for (auto tl_itr = all_lanelet_traffic_lights.begin(); tl_itr != all_lanelet_traffic_lights.end(); + ++tl_itr) { + lanelet::AutowareTrafficLightConstPtr tl = *tl_itr; + + auto lights = tl->trafficLights(); + for (const auto & light : lights) { + traffic_light_id_to_regulatory_ele_id_[light.id()] = tl->id(); + } + } +} + +void MultiCameraFusion::convertOutputMsg( + const std::map & grouped_record_map, NewSignalArrayType & msg_out) +{ + msg_out.signals.clear(); + for (const auto & p : grouped_record_map) { + IdType reg_ele_id = p.first; + const SignalType & signal = p.second.signal; + NewSignalType signal_out; + signal_out.traffic_signal_id = reg_ele_id; + for (const auto & ele : signal.elements) { + signal_out.elements.push_back(convert(ele)); + } + msg_out.signals.push_back(signal_out); + } +} + +void MultiCameraFusion::multiCameraFusion(std::map & fusioned_record_map) +{ + fusioned_record_map.clear(); + /* + this should not happen. Just in case + */ + if (record_arr_set_.empty()) { + RCLCPP_ERROR(get_logger(), "record_arr_set_ is empty! This should not happen"); + return; + } + const rclcpp::Time & newest_stamp(record_arr_set_.rbegin()->header.stamp); + for (auto it = record_arr_set_.begin(); it != record_arr_set_.end();) { + /* + remove all old record arrays whose timestamp difference with newest record is larger than + threshold + */ + if ( + (newest_stamp - rclcpp::Time(it->header.stamp)) > + rclcpp::Duration::from_seconds(message_lifespan_)) { + it = record_arr_set_.erase(it); + } else { + /* + generate fusioned record result with the saved records + */ + const FusionRecordArr & record_arr = *it; + for (size_t i = 0; i < record_arr.rois.rois.size(); i++) { + const RoiType & roi = record_arr.rois.rois[i]; + auto signal_it = std::find_if( + record_arr.signals.signals.begin(), record_arr.signals.signals.end(), + [roi](const SignalType & s1) { return roi.traffic_light_id == s1.traffic_light_id; }); + /* + failed to find corresponding signal. skip it + */ + if (signal_it == record_arr.signals.signals.end()) { + continue; + } + FusionRecord record{record_arr.header, record_arr.cam_info, roi, *signal_it}; + /* + if this traffic light is not detected yet or can be updated by higher priority record, + update it + */ + if ( + fusioned_record_map.find(roi.traffic_light_id) == fusioned_record_map.end() || + ::compareRecord(record, fusioned_record_map[roi.traffic_light_id]) >= 0) { + fusioned_record_map[roi.traffic_light_id] = record; + } + } + it++; + } + } +} + +void MultiCameraFusion::groupFusion( + std::map & fusioned_record_map, + std::map & grouped_record_map) +{ + grouped_record_map.clear(); + for (auto & p : fusioned_record_map) { + IdType roi_id = p.second.roi.traffic_light_id; + /* + this should not happen + */ + if (traffic_light_id_to_regulatory_ele_id_.count(roi_id) == 0) { + RCLCPP_WARN_STREAM( + get_logger(), "Found Traffic Light Id = " << roi_id << " which is not defined in Map"); + } else { + /* + keep the best record for every regulatory element id + */ + IdType reg_ele_id = traffic_light_id_to_regulatory_ele_id_[p.second.roi.traffic_light_id]; + if ( + grouped_record_map.count(reg_ele_id) == 0 || + ::compareRecord(p.second, grouped_record_map[reg_ele_id]) >= 0) { + grouped_record_map[reg_ele_id] = p.second; + } + } + } +} + +} // namespace traffic_light + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(traffic_light::MultiCameraFusion) diff --git a/perception/traffic_light_selector/README.md b/perception/traffic_light_selector/README.md index 9e38333c0e345..d20d5dc790e3a 100644 --- a/perception/traffic_light_selector/README.md +++ b/perception/traffic_light_selector/README.md @@ -32,9 +32,9 @@ A temporary node that converts old message type to new message type. #### Input -| Name | Type | Description | -| -------------------- | ---------------------------------------------------- | ------------------------------ | -| ~/sub/traffic_lights | autoware_auto_perception_msgs/msg/TrafficSignalArray | The state in old message type. | +| Name | Type | Description | +| -------------------- | -------------------------------------------- | ------------------------------ | +| ~/sub/traffic_lights | tier4_perception_msgs/msg/TrafficSignalArray | The state in old message type. | #### Output diff --git a/perception/traffic_light_selector/package.xml b/perception/traffic_light_selector/package.xml index 75796ac3cd710..fb696dd54dddd 100644 --- a/perception/traffic_light_selector/package.xml +++ b/perception/traffic_light_selector/package.xml @@ -11,12 +11,12 @@ autoware_cmake autoware_auto_mapping_msgs - autoware_auto_perception_msgs autoware_perception_msgs lanelet2_core lanelet2_extension rclcpp rclcpp_components + tier4_perception_msgs ament_lint_auto autoware_lint_common diff --git a/perception/traffic_light_selector/src/traffic_light_converter.cpp b/perception/traffic_light_selector/src/traffic_light_converter.cpp index d67cfaa53de79..afc8dab72e788 100644 --- a/perception/traffic_light_selector/src/traffic_light_converter.cpp +++ b/perception/traffic_light_selector/src/traffic_light_converter.cpp @@ -20,9 +20,9 @@ namespace converter { -using OldList = autoware_auto_perception_msgs::msg::TrafficSignalArray; -using OldData = autoware_auto_perception_msgs::msg::TrafficSignal; -using OldElem = autoware_auto_perception_msgs::msg::TrafficLight; +using OldList = tier4_perception_msgs::msg::TrafficSignalArray; +using OldData = tier4_perception_msgs::msg::TrafficSignal; +using OldElem = tier4_perception_msgs::msg::TrafficLightElement; using NewList = autoware_perception_msgs::msg::TrafficLightArray; using NewData = autoware_perception_msgs::msg::TrafficLight; using NewElem = autoware_perception_msgs::msg::TrafficLightElement; @@ -53,8 +53,8 @@ NewList convert(const OldList & input) NewData convert(const OldData & input) { NewData output; - output.traffic_light_id = input.map_primitive_id; - output.elements = convert_vector(input.lights); + output.traffic_light_id = input.traffic_light_id; + output.elements = convert_vector(input.elements); return output; } diff --git a/perception/traffic_light_selector/src/traffic_light_converter.hpp b/perception/traffic_light_selector/src/traffic_light_converter.hpp index db6d0a76c9c52..8c6c6545d9dc2 100644 --- a/perception/traffic_light_selector/src/traffic_light_converter.hpp +++ b/perception/traffic_light_selector/src/traffic_light_converter.hpp @@ -17,8 +17,8 @@ #include -#include #include +#include class TrafficLightConverter : public rclcpp::Node { @@ -26,7 +26,7 @@ class TrafficLightConverter : public rclcpp::Node explicit TrafficLightConverter(const rclcpp::NodeOptions & options); private: - using OldMessage = autoware_auto_perception_msgs::msg::TrafficSignalArray; + using OldMessage = tier4_perception_msgs::msg::TrafficSignalArray; using NewMessage = autoware_perception_msgs::msg::TrafficLightArray; rclcpp::Subscription::SharedPtr sub_; rclcpp::Publisher::SharedPtr pub_; diff --git a/perception/traffic_light_ssd_fine_detector/README.md b/perception/traffic_light_ssd_fine_detector/README.md index 01a30fac88fe4..1dd05665709f5 100644 --- a/perception/traffic_light_ssd_fine_detector/README.md +++ b/perception/traffic_light_ssd_fine_detector/README.md @@ -98,17 +98,17 @@ Based on the camera image and the global ROI array detected by `map_based_detect ### Input -| Name | Type | Description | -| --------------- | ---------------------------------------------------------- | ------------------------------------------------ | -| `~/input/image` | `sensor_msgs/Image` | The full size camera image | -| `~/input/rois` | `autoware_auto_perception_msgs::msg::TrafficLightRoiArray` | The array of ROIs detected by map_based_detector | +| Name | Type | Description | +| --------------- | -------------------------------------------------- | ------------------------------------------------ | +| `~/input/image` | `sensor_msgs/Image` | The full size camera image | +| `~/input/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The array of ROIs detected by map_based_detector | ### Output -| Name | Type | Description | -| --------------------- | ---------------------------------------------------------- | ---------------------------- | -| `~/output/rois` | `autoware_auto_perception_msgs::msg::TrafficLightRoiArray` | The detected accurate rois | -| `~/debug/exe_time_ms` | `tier4_debug_msgs::msg::Float32Stamped` | The time taken for inference | +| Name | Type | Description | +| --------------------- | -------------------------------------------------- | ---------------------------- | +| `~/output/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The detected accurate rois | +| `~/debug/exe_time_ms` | `tier4_debug_msgs::msg::Float32Stamped` | The time taken for inference | ## Parameters diff --git a/perception/traffic_light_ssd_fine_detector/include/traffic_light_ssd_fine_detector/nodelet.hpp b/perception/traffic_light_ssd_fine_detector/include/traffic_light_ssd_fine_detector/nodelet.hpp index a2fa16de01a25..14aa7fcbd94fe 100644 --- a/perception/traffic_light_ssd_fine_detector/include/traffic_light_ssd_fine_detector/nodelet.hpp +++ b/perception/traffic_light_ssd_fine_detector/include/traffic_light_ssd_fine_detector/nodelet.hpp @@ -22,10 +22,10 @@ #include #include -#include #include #include #include +#include #if __has_include() #include @@ -58,8 +58,7 @@ class TrafficLightSSDFineDetectorNodelet : public rclcpp::Node void connectCb(); void callback( const sensor_msgs::msg::Image::ConstSharedPtr image_msg, - const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr - traffic_light_roi_msg); + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr traffic_light_roi_msg); private: bool cvMat2CnnInput( @@ -70,29 +69,27 @@ class TrafficLightSSDFineDetectorNodelet : public rclcpp::Node bool rosMsg2CvMat(const sensor_msgs::msg::Image::ConstSharedPtr image_msg, cv::Mat & image); bool fitInFrame(cv::Point & lt, cv::Point & rb, const cv::Size & size); void cvRect2TlRoiMsg( - const cv::Rect & rect, const int32_t id, - autoware_auto_perception_msgs::msg::TrafficLightRoi & tl_roi); + const cv::Rect & rect, const int32_t id, tier4_perception_msgs::msg::TrafficLightRoi & tl_roi); bool readLabelFile(std::string filepath, std::vector & labels); bool getTlrIdFromLabel(const std::vector & labels, int & tlr_id); // variables std::shared_ptr image_transport_; image_transport::SubscriberFilter image_sub_; - message_filters::Subscriber roi_sub_; + message_filters::Subscriber roi_sub_; std::mutex connect_mutex_; - rclcpp::Publisher::SharedPtr - output_roi_pub_; + rclcpp::Publisher::SharedPtr output_roi_pub_; rclcpp::Publisher::SharedPtr exe_time_pub_; rclcpp::TimerBase::SharedPtr timer_; typedef message_filters::sync_policies::ExactTime< - sensor_msgs::msg::Image, autoware_auto_perception_msgs::msg::TrafficLightRoiArray> + sensor_msgs::msg::Image, tier4_perception_msgs::msg::TrafficLightRoiArray> SyncPolicy; typedef message_filters::Synchronizer Sync; std::shared_ptr sync_; typedef message_filters::sync_policies::ApproximateTime< - sensor_msgs::msg::Image, autoware_auto_perception_msgs::msg::TrafficLightRoiArray> + sensor_msgs::msg::Image, tier4_perception_msgs::msg::TrafficLightRoiArray> ApproximateSyncPolicy; typedef message_filters::Synchronizer ApproximateSync; std::shared_ptr approximate_sync_; diff --git a/perception/traffic_light_ssd_fine_detector/package.xml b/perception/traffic_light_ssd_fine_detector/package.xml index 49f67d171295a..994f84bacdae4 100644 --- a/perception/traffic_light_ssd_fine_detector/package.xml +++ b/perception/traffic_light_ssd_fine_detector/package.xml @@ -10,7 +10,6 @@ ament_cmake_auto autoware_cmake - autoware_auto_perception_msgs cv_bridge image_transport message_filters @@ -18,6 +17,7 @@ rclcpp_components sensor_msgs tier4_debug_msgs + tier4_perception_msgs autoware_lint_common diff --git a/perception/traffic_light_ssd_fine_detector/src/nodelet.cpp b/perception/traffic_light_ssd_fine_detector/src/nodelet.cpp index 96014800ce842..ffdca742dc918 100644 --- a/perception/traffic_light_ssd_fine_detector/src/nodelet.cpp +++ b/perception/traffic_light_ssd_fine_detector/src/nodelet.cpp @@ -103,8 +103,7 @@ TrafficLightSSDFineDetectorNodelet::TrafficLightSSDFineDetectorNodelet( std::lock_guard lock(connect_mutex_); output_roi_pub_ = - this->create_publisher( - "~/output/rois", 1); + this->create_publisher("~/output/rois", 1); exe_time_pub_ = this->create_publisher("~/debug/exe_time_ms", 1); if (is_approximate_sync_) { @@ -136,7 +135,7 @@ void TrafficLightSSDFineDetectorNodelet::connectCb() void TrafficLightSSDFineDetectorNodelet::callback( const sensor_msgs::msg::Image::ConstSharedPtr in_image_msg, - const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr in_roi_msg) + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr in_roi_msg) { if (in_image_msg->width < 2 || in_image_msg->height < 2) { return; @@ -146,7 +145,7 @@ void TrafficLightSSDFineDetectorNodelet::callback( using std::chrono::milliseconds; const auto exe_start_time = high_resolution_clock::now(); cv::Mat original_image; - autoware_auto_perception_msgs::msg::TrafficLightRoiArray out_rois; + tier4_perception_msgs::msg::TrafficLightRoiArray out_rois; rosMsg2CvMat(in_image_msg, original_image); int num_rois = in_roi_msg->rois.size(); @@ -216,9 +215,10 @@ void TrafficLightSSDFineDetectorNodelet::callback( lts.at(i).x + detections.at(i).x + detections.at(i).w, lts.at(i).y + detections.at(i).y + detections.at(i).h); fitInFrame(lt_roi, rb_roi, cv::Size(original_image.size())); - autoware_auto_perception_msgs::msg::TrafficLightRoi tl_roi; + tier4_perception_msgs::msg::TrafficLightRoi tl_roi; cvRect2TlRoiMsg( - cv::Rect(lt_roi, rb_roi), in_roi_msg->rois.at(i + batch_count * batch_size).id, tl_roi); + cv::Rect(lt_roi, rb_roi), + in_roi_msg->rois.at(i + batch_count * batch_size).traffic_light_id, tl_roi); out_rois.rois.push_back(tl_roi); } } @@ -345,10 +345,9 @@ bool TrafficLightSSDFineDetectorNodelet::fitInFrame( } void TrafficLightSSDFineDetectorNodelet::cvRect2TlRoiMsg( - const cv::Rect & rect, const int32_t id, - autoware_auto_perception_msgs::msg::TrafficLightRoi & tl_roi) + const cv::Rect & rect, const int32_t id, tier4_perception_msgs::msg::TrafficLightRoi & tl_roi) { - tl_roi.id = id; + tl_roi.traffic_light_id = id; tl_roi.roi.x_offset = rect.x; tl_roi.roi.y_offset = rect.y; tl_roi.roi.width = rect.width; diff --git a/perception/traffic_light_visualization/README.md b/perception/traffic_light_visualization/README.md index f675d42aaf089..5d99d6614a1ae 100644 --- a/perception/traffic_light_visualization/README.md +++ b/perception/traffic_light_visualization/README.md @@ -17,10 +17,10 @@ The `traffic_light_visualization` is a package that includes two visualizing nod #### Input -| Name | Type | Description | -| -------------------- | -------------------------------------------------------- | ------------------------ | -| `~/input/tl_state` | `autoware_auto_perception_msgs::msg::TrafficSignalArray` | status of traffic lights | -| `~/input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | +| Name | Type | Description | +| -------------------- | ------------------------------------------------ | ------------------------ | +| `~/input/tl_state` | `tier4_perception_msgs::msg::TrafficSignalArray` | status of traffic lights | +| `~/input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | #### Output @@ -32,12 +32,12 @@ The `traffic_light_visualization` is a package that includes two visualizing nod #### Input -| Name | Type | Description | -| ----------------------------- | ---------------------------------------------------------- | ------------------------------------------------------- | -| `~/input/tl_state` | `autoware_auto_perception_msgs::msg::TrafficSignalArray` | status of traffic lights | -| `~/input/image` | `sensor_msgs::msg::Image` | the image captured by perception cameras | -| `~/input/rois` | `autoware_auto_perception_msgs::msg::TrafficLightRoiArray` | the ROIs detected by `traffic_light_ssd_fine_detector` | -| `~/input/rough/rois` (option) | `autoware_auto_perception_msgs::msg::TrafficLightRoiArray` | the ROIs detected by `traffic_light_map_based_detector` | +| Name | Type | Description | +| ----------------------------- | -------------------------------------------------- | ------------------------------------------------------- | +| `~/input/tl_state` | `tier4_perception_msgs::msg::TrafficSignalArray` | status of traffic lights | +| `~/input/image` | `sensor_msgs::msg::Image` | the image captured by perception cameras | +| `~/input/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | the ROIs detected by `traffic_light_ssd_fine_detector` | +| `~/input/rough/rois` (option) | `tier4_perception_msgs::msg::TrafficLightRoiArray` | the ROIs detected by `traffic_light_map_based_detector` | #### Output diff --git a/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp b/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp index 3f82712538a76..07cb21e60b137 100644 --- a/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp +++ b/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp @@ -20,7 +20,7 @@ #include #include -#include +#include #include #include @@ -35,15 +35,14 @@ class TrafficLightMapVisualizerNode : public rclcpp::Node TrafficLightMapVisualizerNode(const std::string & node_name, const rclcpp::NodeOptions & options); ~TrafficLightMapVisualizerNode() = default; void trafficSignalsCallback( - const autoware_auto_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr + const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr input_traffic_signals_msg); void binMapCallback( const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_map_msg); private: rclcpp::Publisher::SharedPtr light_marker_pub_; - rclcpp::Subscription::SharedPtr - tl_state_sub_; + rclcpp::Subscription::SharedPtr tl_state_sub_; rclcpp::Subscription::SharedPtr vector_map_sub_; std::vector aw_tl_reg_elems_; diff --git a/perception/traffic_light_visualization/include/traffic_light_roi_visualizer/nodelet.hpp b/perception/traffic_light_visualization/include/traffic_light_roi_visualizer/nodelet.hpp index dfffde9018108..1c64eb2f9e82b 100644 --- a/perception/traffic_light_visualization/include/traffic_light_roi_visualizer/nodelet.hpp +++ b/perception/traffic_light_visualization/include/traffic_light_roi_visualizer/nodelet.hpp @@ -19,15 +19,11 @@ #include #include -#include -#include #include +#include +#include -#if __has_include() -#include -#else #include -#endif #include #include #include @@ -54,75 +50,70 @@ class TrafficLightRoiVisualizerNodelet : public rclcpp::Node void imageRoiCallback( const sensor_msgs::msg::Image::ConstSharedPtr & input_image_msg, - const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & - input_tl_roi_msg, - const autoware_auto_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_roi_msg, + const tier4_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & input_traffic_signals_msg); void imageRoughRoiCallback( const sensor_msgs::msg::Image::ConstSharedPtr & input_image_msg, - const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & - input_tl_roi_msg, - const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & - input_tl_rough_roi_msg, - const autoware_auto_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_roi_msg, + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_rough_roi_msg, + const tier4_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & input_traffic_signals_msg); private: std::map state2label_{ // color - {autoware_auto_perception_msgs::msg::TrafficLight::RED, "red"}, - {autoware_auto_perception_msgs::msg::TrafficLight::AMBER, "yellow"}, - {autoware_auto_perception_msgs::msg::TrafficLight::GREEN, "green"}, - {autoware_auto_perception_msgs::msg::TrafficLight::WHITE, "white"}, + {tier4_perception_msgs::msg::TrafficLightElement::RED, "red"}, + {tier4_perception_msgs::msg::TrafficLightElement::AMBER, "yellow"}, + {tier4_perception_msgs::msg::TrafficLightElement::GREEN, "green"}, + {tier4_perception_msgs::msg::TrafficLightElement::WHITE, "white"}, // shape - {autoware_auto_perception_msgs::msg::TrafficLight::CIRCLE, "circle"}, - {autoware_auto_perception_msgs::msg::TrafficLight::LEFT_ARROW, "left"}, - {autoware_auto_perception_msgs::msg::TrafficLight::RIGHT_ARROW, "right"}, - {autoware_auto_perception_msgs::msg::TrafficLight::UP_ARROW, "straight"}, - {autoware_auto_perception_msgs::msg::TrafficLight::DOWN_ARROW, "down"}, - {autoware_auto_perception_msgs::msg::TrafficLight::DOWN_LEFT_ARROW, "down_left"}, - {autoware_auto_perception_msgs::msg::TrafficLight::DOWN_RIGHT_ARROW, "down_right"}, - {autoware_auto_perception_msgs::msg::TrafficLight::CROSS, "cross"}, + {tier4_perception_msgs::msg::TrafficLightElement::CIRCLE, "circle"}, + {tier4_perception_msgs::msg::TrafficLightElement::LEFT_ARROW, "left"}, + {tier4_perception_msgs::msg::TrafficLightElement::RIGHT_ARROW, "right"}, + {tier4_perception_msgs::msg::TrafficLightElement::UP_ARROW, "straight"}, + {tier4_perception_msgs::msg::TrafficLightElement::DOWN_ARROW, "down"}, + {tier4_perception_msgs::msg::TrafficLightElement::DOWN_LEFT_ARROW, "down_left"}, + {tier4_perception_msgs::msg::TrafficLightElement::DOWN_RIGHT_ARROW, "down_right"}, + {tier4_perception_msgs::msg::TrafficLightElement::CROSS, "cross"}, // other - {autoware_auto_perception_msgs::msg::TrafficLight::UNKNOWN, "unknown"}, + {tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN, "unknown"}, }; bool createRect( - cv::Mat & image, const autoware_auto_perception_msgs::msg::TrafficLightRoi & tl_roi, + cv::Mat & image, const tier4_perception_msgs::msg::TrafficLightRoi & tl_roi, const cv::Scalar & color); bool createRect( - cv::Mat & image, const autoware_auto_perception_msgs::msg::TrafficLightRoi & tl_roi, + cv::Mat & image, const tier4_perception_msgs::msg::TrafficLightRoi & tl_roi, const ClassificationResult & result); bool getClassificationResult( - int id, const autoware_auto_perception_msgs::msg::TrafficSignalArray & traffic_signals, + int id, const tier4_perception_msgs::msg::TrafficSignalArray & traffic_signals, ClassificationResult & result); bool getRoiFromId( - int id, const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & rois, - autoware_auto_perception_msgs::msg::TrafficLightRoi & correspond_roi); + int id, const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & rois, + tier4_perception_msgs::msg::TrafficLightRoi & correspond_roi); rclcpp::TimerBase::SharedPtr timer_; image_transport::SubscriberFilter image_sub_; - message_filters::Subscriber roi_sub_; - message_filters::Subscriber - rough_roi_sub_; - message_filters::Subscriber - traffic_signals_sub_; + message_filters::Subscriber roi_sub_; + message_filters::Subscriber rough_roi_sub_; + message_filters::Subscriber traffic_signals_sub_; image_transport::Publisher image_pub_; typedef message_filters::sync_policies::ApproximateTime< - sensor_msgs::msg::Image, autoware_auto_perception_msgs::msg::TrafficLightRoiArray, - autoware_auto_perception_msgs::msg::TrafficSignalArray> + sensor_msgs::msg::Image, tier4_perception_msgs::msg::TrafficLightRoiArray, + tier4_perception_msgs::msg::TrafficSignalArray> SyncPolicy; typedef message_filters::Synchronizer Sync; std::shared_ptr sync_; typedef message_filters::sync_policies::ApproximateTime< - sensor_msgs::msg::Image, autoware_auto_perception_msgs::msg::TrafficLightRoiArray, - autoware_auto_perception_msgs::msg::TrafficLightRoiArray, - autoware_auto_perception_msgs::msg::TrafficSignalArray> + sensor_msgs::msg::Image, tier4_perception_msgs::msg::TrafficLightRoiArray, + tier4_perception_msgs::msg::TrafficLightRoiArray, + tier4_perception_msgs::msg::TrafficSignalArray> SyncPolicyWithRoughRoi; typedef message_filters::Synchronizer SyncWithRoughRoi; std::shared_ptr sync_with_rough_roi_; diff --git a/perception/traffic_light_visualization/package.xml b/perception/traffic_light_visualization/package.xml index d90cf992b96be..276f04762cdea 100644 --- a/perception/traffic_light_visualization/package.xml +++ b/perception/traffic_light_visualization/package.xml @@ -10,7 +10,7 @@ ament_cmake_auto autoware_cmake - autoware_auto_perception_msgs + autoware_perception_msgs cv_bridge image_transport lanelet2_extension @@ -18,6 +18,7 @@ rclcpp rclcpp_components sensor_msgs + tier4_perception_msgs ament_lint_auto autoware_lint_common diff --git a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp index 31f7e88a02c7f..ced36476e00ef 100644 --- a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp +++ b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp @@ -47,16 +47,6 @@ bool isAttributeValue( return false; } -bool isAttributeValue( - const lanelet::ConstLineString3d l, const std::string attr_str, const int value) -{ - lanelet::Attribute attr = l.attribute(attr_str); - if (std::stoi(attr.value()) == value) { - return true; - } - return false; -} - void lightAsMarker( const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & node_logging, lanelet::ConstPoint3d p, visualization_msgs::msg::Marker * marker, const std::string ns, @@ -121,7 +111,7 @@ TrafficLightMapVisualizerNode::TrafficLightMapVisualizerNode( { light_marker_pub_ = create_publisher("~/output/traffic_light", 1); - tl_state_sub_ = create_subscription( + tl_state_sub_ = create_subscription( "~/input/tl_state", 1, std::bind(&TrafficLightMapVisualizerNode::trafficSignalsCallback, this, _1)); vector_map_sub_ = create_subscription( @@ -129,8 +119,7 @@ TrafficLightMapVisualizerNode::TrafficLightMapVisualizerNode( std::bind(&TrafficLightMapVisualizerNode::binMapCallback, this, _1)); } void TrafficLightMapVisualizerNode::trafficSignalsCallback( - const autoware_auto_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr - input_traffic_signals) + const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr input_traffic_signals) { visualization_msgs::msg::MarkerArray output_msg; const auto current_time = now(); @@ -167,28 +156,29 @@ void TrafficLightMapVisualizerNode::trafficSignalsCallback( continue; } for (const auto & input_traffic_signal : input_traffic_signals->signals) { - if (isAttributeValue(ls, "traffic_light_id", input_traffic_signal.map_primitive_id)) { + if ((*tli)->id() == input_traffic_signal.traffic_signal_id) { + // if (isAttributeValue(ls, "traffic_light_id", input_traffic_signal.map_primitive_id)) { for (auto pt : ls) { if (!pt.hasAttribute("color")) { continue; } - for (const auto & light : input_traffic_signal.lights) { + for (const auto & elem : input_traffic_signal.elements) { visualization_msgs::msg::Marker marker; if ( isAttributeValue(pt, "color", "red") && - light.color == autoware_auto_perception_msgs::msg::TrafficLight::RED) { + elem.color == autoware_perception_msgs::msg::TrafficLightElement::RED) { lightAsMarker( get_node_logging_interface(), pt, &marker, "traffic_light", current_time); } else if ( // NOLINT isAttributeValue(pt, "color", "green") && - light.color == autoware_auto_perception_msgs::msg::TrafficLight::GREEN) { + elem.color == autoware_perception_msgs::msg::TrafficLightElement::GREEN) { lightAsMarker( get_node_logging_interface(), pt, &marker, "traffic_light", current_time); } else if ( // NOLINT isAttributeValue(pt, "color", "yellow") && - light.color == autoware_auto_perception_msgs::msg::TrafficLight::AMBER) { + elem.color == autoware_perception_msgs::msg::TrafficLightElement::AMBER) { lightAsMarker( get_node_logging_interface(), pt, &marker, "traffic_light", current_time); } else { diff --git a/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp b/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp index 5ebf4f9a61c50..a3b1a2b16a743 100644 --- a/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp +++ b/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp @@ -72,7 +72,7 @@ void TrafficLightRoiVisualizerNodelet::connectCb() } bool TrafficLightRoiVisualizerNodelet::createRect( - cv::Mat & image, const autoware_auto_perception_msgs::msg::TrafficLightRoi & tl_roi, + cv::Mat & image, const tier4_perception_msgs::msg::TrafficLightRoi & tl_roi, const cv::Scalar & color) { cv::rectangle( @@ -80,13 +80,14 @@ bool TrafficLightRoiVisualizerNodelet::createRect( cv::Point(tl_roi.roi.x_offset + tl_roi.roi.width, tl_roi.roi.y_offset + tl_roi.roi.height), color, 3); cv::putText( - image, std::to_string(tl_roi.id), cv::Point(tl_roi.roi.x_offset, tl_roi.roi.y_offset), - cv::FONT_HERSHEY_COMPLEX, 1.0, color, 1, CV_AA); + image, std::to_string(tl_roi.traffic_light_id), + cv::Point(tl_roi.roi.x_offset, tl_roi.roi.y_offset), cv::FONT_HERSHEY_COMPLEX, 1.0, color, 1, + CV_AA); return true; } bool TrafficLightRoiVisualizerNodelet::createRect( - cv::Mat & image, const autoware_auto_perception_msgs::msg::TrafficLightRoi & tl_roi, + cv::Mat & image, const tier4_perception_msgs::msg::TrafficLightRoi & tl_roi, const ClassificationResult & result) { cv::Scalar color; @@ -120,8 +121,8 @@ bool TrafficLightRoiVisualizerNodelet::createRect( void TrafficLightRoiVisualizerNodelet::imageRoiCallback( const sensor_msgs::msg::Image::ConstSharedPtr & input_image_msg, - const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_roi_msg, - [[maybe_unused]] const autoware_auto_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_roi_msg, + [[maybe_unused]] const tier4_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & input_traffic_signals_msg) { cv_bridge::CvImagePtr cv_ptr; @@ -138,21 +139,21 @@ void TrafficLightRoiVisualizerNodelet::imageRoiCallback( } bool TrafficLightRoiVisualizerNodelet::getClassificationResult( - int id, const autoware_auto_perception_msgs::msg::TrafficSignalArray & traffic_signals, + int id, const tier4_perception_msgs::msg::TrafficSignalArray & traffic_signals, ClassificationResult & result) { bool has_correspond_traffic_signal = false; for (const auto & traffic_signal : traffic_signals.signals) { - if (id != traffic_signal.map_primitive_id) { + if (id != traffic_signal.traffic_light_id) { continue; } has_correspond_traffic_signal = true; - for (size_t i = 0; i < traffic_signal.lights.size(); i++) { - auto light = traffic_signal.lights.at(i); + for (size_t i = 0; i < traffic_signal.elements.size(); i++) { + auto element = traffic_signal.elements.at(i); // all lamp confidence are the same - result.prob = light.confidence; - result.label += (state2label_[light.color] + "-" + state2label_[light.shape]); - if (i < traffic_signal.lights.size() - 1) { + result.prob = element.confidence; + result.label += (state2label_[element.color] + "-" + state2label_[element.shape]); + if (i < traffic_signal.elements.size() - 1) { result.label += ","; } } @@ -161,11 +162,11 @@ bool TrafficLightRoiVisualizerNodelet::getClassificationResult( } bool TrafficLightRoiVisualizerNodelet::getRoiFromId( - int id, const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & rois, - autoware_auto_perception_msgs::msg::TrafficLightRoi & correspond_roi) + int id, const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & rois, + tier4_perception_msgs::msg::TrafficLightRoi & correspond_roi) { for (const auto roi : rois->rois) { - if (roi.id == id) { + if (roi.traffic_light_id == id) { correspond_roi = roi; return true; } @@ -175,11 +176,9 @@ bool TrafficLightRoiVisualizerNodelet::getRoiFromId( void TrafficLightRoiVisualizerNodelet::imageRoughRoiCallback( const sensor_msgs::msg::Image::ConstSharedPtr & input_image_msg, - const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_roi_msg, - const autoware_auto_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & - input_tl_rough_roi_msg, - const autoware_auto_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & - input_traffic_signals_msg) + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_roi_msg, + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & input_tl_rough_roi_msg, + const tier4_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & input_traffic_signals_msg) { cv_bridge::CvImagePtr cv_ptr; try { @@ -190,9 +189,10 @@ void TrafficLightRoiVisualizerNodelet::imageRoughRoiCallback( ClassificationResult result; bool has_correspond_traffic_signal = - getClassificationResult(tl_rough_roi.id, *input_traffic_signals_msg, result); - autoware_auto_perception_msgs::msg::TrafficLightRoi tl_roi; - bool has_correspond_roi = getRoiFromId(tl_rough_roi.id, input_tl_roi_msg, tl_roi); + getClassificationResult(tl_rough_roi.traffic_light_id, *input_traffic_signals_msg, result); + tier4_perception_msgs::msg::TrafficLightRoi tl_roi; + bool has_correspond_roi = + getRoiFromId(tl_rough_roi.traffic_light_id, input_tl_roi_msg, tl_roi); if (has_correspond_roi && has_correspond_traffic_signal) { // has fine detection and classification results From f5b40539ed153f98c71ae8e25f4a51240589edc0 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 30 Jun 2023 10:32:12 +0900 Subject: [PATCH 058/118] fix(velocity_smoother): add acc limit on manual driving (#4113) Signed-off-by: Takamasa Horibe --- .../src/motion_velocity_smoother_node.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) 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 057308e4329d1..b77af629ad7c3 100644 --- a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp +++ b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp @@ -786,8 +786,10 @@ MotionVelocitySmootherNode::calcInitialMotion( // We should plan from the current vehicle speed, but if the initial value is greater than the // velocity limit, the current planning algorithm decelerates with a very high deceleration. // To avoid this, we set the initial value of the vehicle speed to be below the speed limit. + const auto p = smoother_->getBaseParam(); const auto v0 = std::min(target_vel, vehicle_speed); - const Motion initial_motion = {v0, vehicle_acceleration}; + const auto a0 = std::clamp(vehicle_acceleration, p.min_decel, p.max_accel); + const Motion initial_motion = {v0, a0}; return {initial_motion, InitializeType::EGO_VELOCITY}; } } From 8381f8e8463abd3d72e1d4851ce41261eb075c7f Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 30 Jun 2023 13:21:43 +0900 Subject: [PATCH 059/118] feat(start_planner): add offset to not finish before engage (#4121) Signed-off-by: kosuke55 --- .../src/scene_module/start_planner/start_planner_module.cpp | 4 +++- 1 file changed, 3 insertions(+), 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 e9e28b8e62f9b..3540b616aa78f 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 @@ -682,7 +682,9 @@ bool StartPlannerModule::hasFinishedPullOut() const const auto arclength_pull_out_end = lanelet::utils::getArcCoordinates(status_.current_lanes, status_.pull_out_path.end_pose); - const bool has_finished = arclength_current.length - arclength_pull_out_end.length > 0.0; + // offset to not finish the module before engage + constexpr double offset = 0.1; + const bool has_finished = arclength_current.length - arclength_pull_out_end.length > offset; return has_finished; } From 00dfda5229a006041f084c7b9bbb40b96c2387b3 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 30 Jun 2023 14:01:06 +0900 Subject: [PATCH 060/118] refactor(behavior_path_planner): move parameter declaration from node.cpp to manager (#4124) * refactor(behavior_path_planner): move parameter declare Signed-off-by: satoshi-ota * refactor(start_planner): move parameter declare Signed-off-by: satoshi-ota * refactor(side_shift): move parameter declare Signed-off-by: satoshi-ota * refactor(goal_planner): move parameter declare Signed-off-by: satoshi-ota * refactor(dynamic_avoidance): move parameter declare Signed-off-by: satoshi-ota * refactor(lane_change): move parameter declare Signed-off-by: satoshi-ota * refactor(avoidance): move parameter declare Signed-off-by: satoshi-ota * refactor(avoidance_by_lane_change): move parameter declare Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_path_planner_node.hpp | 24 - .../scene_module/avoidance/manager.hpp | 3 +- .../dynamic_avoidance/manager.hpp | 3 +- .../scene_module/goal_planner/manager.hpp | 3 +- .../lane_change/avoidance_by_lane_change.hpp | 4 +- .../scene_module/lane_change/interface.hpp | 1 - .../scene_module/lane_change/manager.hpp | 11 +- .../scene_module/side_shift/manager.hpp | 3 +- .../scene_module/start_planner/manager.hpp | 3 +- .../lane_change/lane_change_module_data.hpp | 5 +- .../src/behavior_path_planner_node.cpp | 688 +----------------- .../src/scene_module/avoidance/manager.cpp | 204 +++++- .../dynamic_avoidance/manager.cpp | 45 +- .../src/scene_module/goal_planner/manager.cpp | 213 +++++- .../lane_change/avoidance_by_lane_change.cpp | 45 +- .../scene_module/lane_change/interface.cpp | 4 +- .../src/scene_module/lane_change/manager.cpp | 219 +++++- .../src/scene_module/side_shift/manager.cpp | 17 +- .../scene_module/start_planner/manager.cpp | 63 +- 19 files changed, 784 insertions(+), 774 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 454106e4e6811..0ec1fe0ca493a 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 @@ -25,12 +25,6 @@ #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 "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.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/side_shift/side_shift_parameters.hpp" -#include "behavior_path_planner/utils/start_planner/start_planner_parameters.hpp" #include "tier4_planning_msgs/msg/detail/lane_change_debug_msg_array__struct.hpp" #include @@ -134,26 +128,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node bool isDataReady(); // parameters - std::shared_ptr avoidance_param_ptr_; - std::shared_ptr avoidance_by_lc_param_ptr_; - std::shared_ptr dynamic_avoidance_param_ptr_; - std::shared_ptr side_shift_param_ptr_; - std::shared_ptr lane_change_param_ptr_; - std::shared_ptr start_planner_param_ptr_; - std::shared_ptr goal_planner_param_ptr_; - BehaviorPathPlannerParameters getCommonParam(); - AvoidanceParameters getAvoidanceParam(); - DynamicAvoidanceParameters getDynamicAvoidanceParam(); - LaneChangeParameters getLaneChangeParam(); - SideShiftParameters getSideShiftParam(); - GoalPlannerParameters getGoalPlannerParam(); - StartPlannerParameters getStartPlannerParam(); - AvoidanceByLCParameters getAvoidanceByLCParam( - const std::shared_ptr & avoidance_param, - const std::shared_ptr & lane_change_param); - // callback void onOdometry(const Odometry::ConstSharedPtr msg); void onAcceleration(const AccelWithCovarianceStamped::ConstSharedPtr msg); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp index 517057f8d6ac8..e4421459e61fd 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp @@ -33,8 +33,7 @@ class AvoidanceModuleManager : public SceneModuleManagerInterface { public: AvoidanceModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - const std::shared_ptr & parameters); + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); std::shared_ptr createNewSceneModuleInstance() override { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp index 51fe30c8dc7ee..d2b1deb36bd30 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp @@ -32,8 +32,7 @@ class DynamicAvoidanceModuleManager : public SceneModuleManagerInterface { public: DynamicAvoidanceModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - const std::shared_ptr & parameters); + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); std::shared_ptr createNewSceneModuleInstance() override { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp index 31920ecd640f0..d836f73df22bc 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp @@ -31,8 +31,7 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface { public: GoalPlannerModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - const std::shared_ptr & parameters); + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); std::shared_ptr createNewSceneModuleInstance() override { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp index e58a8c07850cf..9af413d48b5c2 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp @@ -34,7 +34,6 @@ class AvoidanceByLaneChange : public NormalLaneChange public: AvoidanceByLaneChange( const std::shared_ptr & parameters, - std::shared_ptr avoidance_parameters, std::shared_ptr avoidance_by_lane_change_parameters); void updateSpecialData() override; @@ -42,8 +41,7 @@ class AvoidanceByLaneChange : public NormalLaneChange std::pair getSafePath(LaneChangePath & safe_path) const override; private: - std::shared_ptr avoidance_parameters_; - std::shared_ptr avoidance_by_lane_change_parameters_; + std::shared_ptr avoidance_parameters_; AvoidancePlanningData calcAvoidancePlanningData(AvoidanceDebugData & debug) const; AvoidancePlanningData avoidance_data_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp index fa7011bcdce27..1171b92343e30 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp @@ -130,7 +130,6 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface AvoidanceByLaneChangeInterface( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::shared_ptr & avoidance_parameters, const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map > & rtc_interface_ptr_map); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp index ebee8f3d3a07a..9dabd3d0004fb 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp @@ -35,8 +35,7 @@ class LaneChangeModuleManager : public SceneModuleManagerInterface public: LaneChangeModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - std::shared_ptr parameters, const Direction direction, - const LaneChangeModuleType type); + const Direction direction, const LaneChangeModuleType type); std::shared_ptr createNewSceneModuleInstance() override; @@ -56,18 +55,14 @@ class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager { public: AvoidanceByLaneChangeModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - std::shared_ptr parameters, - std::shared_ptr avoidance_parameters, - std::shared_ptr avoidance_by_lane_change_parameters); + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); std::shared_ptr createNewSceneModuleInstance() override; // void updateModuleParams(const std::vector & parameters) override; private: - std::shared_ptr avoidance_parameters_; - std::shared_ptr avoidance_by_lane_change_parameters_; + std::shared_ptr avoidance_parameters_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp index 71a3691b88748..f35f497df0e4a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp @@ -32,8 +32,7 @@ class SideShiftModuleManager : public SceneModuleManagerInterface { public: SideShiftModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - const std::shared_ptr & parameters); + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); std::shared_ptr createNewSceneModuleInstance() override { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp index 09c201b0b38ce..103e7dc375233 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp @@ -31,8 +31,7 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface { public: StartPlannerModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - const std::shared_ptr & parameters); + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config); std::shared_ptr createNewSceneModuleInstance() override { 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 006040d8eaa4a..106263cc66ebd 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 @@ -114,11 +114,8 @@ enum class LaneChangeModuleType { AVOIDANCE_BY_LANE_CHANGE, }; -struct AvoidanceByLCParameters +struct AvoidanceByLCParameters : public AvoidanceParameters { - std::shared_ptr avoidance{}; - std::shared_ptr lane_change{}; - // execute if the target object number is larger than this param. size_t execute_object_num{1}; 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 410c443b94ed9..7857c2962d001 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -121,22 +121,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod "~/input/route", qos_transient_local, std::bind(&BehaviorPathPlannerNode::onRoute, this, _1), createSubscriptionOptions(this)); - // set parameters - { - avoidance_param_ptr_ = std::make_shared(getAvoidanceParam()); - dynamic_avoidance_param_ptr_ = - std::make_shared(getDynamicAvoidanceParam()); - lane_change_param_ptr_ = std::make_shared(getLaneChangeParam()); - start_planner_param_ptr_ = std::make_shared(getStartPlannerParam()); - goal_planner_param_ptr_ = std::make_shared(getGoalPlannerParam()); - side_shift_param_ptr_ = std::make_shared(getSideShiftParam()); - avoidance_by_lc_param_ptr_ = std::make_shared( - getAvoidanceByLCParam(avoidance_param_ptr_, lane_change_param_ptr_)); - } - - m_set_param_res = this->add_on_set_parameters_callback( - std::bind(&BehaviorPathPlannerNode::onSetParam, this, std::placeholders::_1)); - { RCLCPP_INFO(get_logger(), "not use behavior tree."); @@ -158,8 +142,8 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod }; if (p.config_start_planner.enable_module) { - auto manager = std::make_shared( - this, "start_planner", p.config_start_planner, start_planner_param_ptr_); + auto manager = + std::make_shared(this, "start_planner", p.config_start_planner); planner_manager_->registerSceneModuleManager(manager); path_candidate_publishers_.emplace( "start_planner", create_publisher(path_candidate_name_space + "start_planner", 1)); @@ -168,8 +152,8 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod } if (p.config_goal_planner.enable_module) { - auto manager = std::make_shared( - this, "goal_planner", p.config_goal_planner, goal_planner_param_ptr_); + auto manager = + std::make_shared(this, "goal_planner", p.config_goal_planner); planner_manager_->registerSceneModuleManager(manager); path_candidate_publishers_.emplace( "goal_planner", create_publisher(path_candidate_name_space + "goal_planner", 1)); @@ -178,8 +162,8 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod } if (p.config_side_shift.enable_module) { - auto manager = std::make_shared( - this, "side_shift", p.config_side_shift, side_shift_param_ptr_); + auto manager = + std::make_shared(this, "side_shift", p.config_side_shift); planner_manager_->registerSceneModuleManager(manager); path_candidate_publishers_.emplace( "side_shift", create_publisher(path_candidate_name_space + "side_shift", 1)); @@ -190,38 +174,38 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod if (p.config_lane_change_left.enable_module) { const std::string module_topic = "lane_change_left"; auto manager = std::make_shared( - this, module_topic, p.config_lane_change_left, lane_change_param_ptr_, - route_handler::Direction::LEFT, LaneChangeModuleType::NORMAL); + this, module_topic, p.config_lane_change_left, route_handler::Direction::LEFT, + LaneChangeModuleType::NORMAL); register_and_create_publisher(manager); } if (p.config_lane_change_right.enable_module) { const std::string module_topic = "lane_change_right"; auto manager = std::make_shared( - this, module_topic, p.config_lane_change_right, lane_change_param_ptr_, - route_handler::Direction::RIGHT, LaneChangeModuleType::NORMAL); + this, module_topic, p.config_lane_change_right, route_handler::Direction::RIGHT, + LaneChangeModuleType::NORMAL); register_and_create_publisher(manager); } if (p.config_ext_request_lane_change_right.enable_module) { const std::string module_topic = "external_request_lane_change_right"; auto manager = std::make_shared( - this, module_topic, p.config_ext_request_lane_change_right, lane_change_param_ptr_, - route_handler::Direction::RIGHT, LaneChangeModuleType::EXTERNAL_REQUEST); + this, module_topic, p.config_ext_request_lane_change_right, route_handler::Direction::RIGHT, + LaneChangeModuleType::EXTERNAL_REQUEST); register_and_create_publisher(manager); } if (p.config_ext_request_lane_change_left.enable_module) { const std::string module_topic = "external_request_lane_change_left"; auto manager = std::make_shared( - this, module_topic, p.config_ext_request_lane_change_left, lane_change_param_ptr_, - route_handler::Direction::LEFT, LaneChangeModuleType::EXTERNAL_REQUEST); + this, module_topic, p.config_ext_request_lane_change_left, route_handler::Direction::LEFT, + LaneChangeModuleType::EXTERNAL_REQUEST); register_and_create_publisher(manager); } if (p.config_avoidance.enable_module) { - auto manager = std::make_shared( - this, "avoidance", p.config_avoidance, avoidance_param_ptr_); + auto manager = + std::make_shared(this, "avoidance", p.config_avoidance); planner_manager_->registerSceneModuleManager(manager); path_candidate_publishers_.emplace( "avoidance", create_publisher(path_candidate_name_space + "avoidance", 1)); @@ -231,8 +215,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod if (p.config_avoidance_by_lc.enable_module) { auto manager = std::make_shared( - this, "avoidance_by_lane_change", p.config_avoidance_by_lc, lane_change_param_ptr_, - avoidance_param_ptr_, avoidance_by_lc_param_ptr_); + this, "avoidance_by_lane_change", p.config_avoidance_by_lc); planner_manager_->registerSceneModuleManager(manager); path_candidate_publishers_.emplace( "avoidance_by_lane_change", @@ -244,11 +227,14 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod if (p.config_dynamic_avoidance.enable_module) { auto manager = std::make_shared( - this, "dynamic_avoidance", p.config_dynamic_avoidance, dynamic_avoidance_param_ptr_); + this, "dynamic_avoidance", p.config_dynamic_avoidance); planner_manager_->registerSceneModuleManager(manager); } } + m_set_param_res = this->add_on_set_parameters_callback( + std::bind(&BehaviorPathPlannerNode::onSetParam, this, std::placeholders::_1)); + // turn signal decider { const double turn_signal_intersection_search_distance = @@ -433,630 +419,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() return p; } -SideShiftParameters BehaviorPathPlannerNode::getSideShiftParam() -{ - SideShiftParameters p{}; - - std::string ns = "side_shift."; - - p.min_distance_to_start_shifting = - declare_parameter(ns + "min_distance_to_start_shifting"); - p.time_to_start_shifting = declare_parameter(ns + "time_to_start_shifting"); - p.shifting_lateral_jerk = declare_parameter(ns + "shifting_lateral_jerk"); - p.min_shifting_distance = declare_parameter(ns + "min_shifting_distance"); - p.min_shifting_speed = declare_parameter(ns + "min_shifting_speed"); - p.shift_request_time_limit = declare_parameter(ns + "shift_request_time_limit"); - p.publish_debug_marker = declare_parameter(ns + "publish_debug_marker"); - - return p; -} - -AvoidanceByLCParameters BehaviorPathPlannerNode::getAvoidanceByLCParam( - const std::shared_ptr & avoidance_param, - const std::shared_ptr & lane_change_param) -{ - AvoidanceByLCParameters p{}; - p.avoidance = avoidance_param; - p.lane_change = lane_change_param; - - { - std::string ns = "avoidance_by_lane_change."; - p.execute_object_num = declare_parameter(ns + "execute_object_num"); - p.execute_object_longitudinal_margin = - declare_parameter(ns + "execute_object_longitudinal_margin"); - p.execute_only_when_lane_change_finish_before_object = - declare_parameter(ns + "execute_only_when_lane_change_finish_before_object"); - } - - if (p.execute_object_num < 1) { - RCLCPP_WARN_STREAM(get_logger(), "execute_object_num cannot be lesser than 1."); - } - return p; -} - -AvoidanceParameters BehaviorPathPlannerNode::getAvoidanceParam() -{ - using autoware_auto_perception_msgs::msg::ObjectClassification; - - AvoidanceParameters p{}; - // general params - { - std::string ns = "avoidance."; - p.resample_interval_for_planning = - declare_parameter(ns + "resample_interval_for_planning"); - p.resample_interval_for_output = declare_parameter(ns + "resample_interval_for_output"); - p.detection_area_right_expand_dist = - declare_parameter(ns + "detection_area_right_expand_dist"); - p.detection_area_left_expand_dist = - declare_parameter(ns + "detection_area_left_expand_dist"); - p.enable_bound_clipping = declare_parameter(ns + "enable_bound_clipping"); - p.enable_avoidance_over_same_direction = - declare_parameter(ns + "enable_avoidance_over_same_direction"); - p.enable_avoidance_over_opposite_direction = - declare_parameter(ns + "enable_avoidance_over_opposite_direction"); - p.enable_update_path_when_object_is_gone = - declare_parameter(ns + "enable_update_path_when_object_is_gone"); - p.enable_force_avoidance_for_stopped_vehicle = - declare_parameter(ns + "enable_force_avoidance_for_stopped_vehicle"); - p.enable_safety_check = declare_parameter(ns + "enable_safety_check"); - p.enable_yield_maneuver = declare_parameter(ns + "enable_yield_maneuver"); - p.enable_yield_maneuver_during_shifting = - declare_parameter(ns + "enable_yield_maneuver_during_shifting"); - p.disable_path_update = declare_parameter(ns + "disable_path_update"); - p.use_hatched_road_markings = declare_parameter(ns + "use_hatched_road_markings"); - p.publish_debug_marker = declare_parameter(ns + "publish_debug_marker"); - p.print_debug_info = declare_parameter(ns + "print_debug_info"); - } - - // target object - { - const auto get_object_param = [&](std::string && ns) { - ObjectParameter param{}; - param.is_target = declare_parameter(ns + "is_target"); - param.moving_speed_threshold = declare_parameter(ns + "moving_speed_threshold"); - param.moving_time_threshold = declare_parameter(ns + "moving_time_threshold"); - param.max_expand_ratio = declare_parameter(ns + "max_expand_ratio"); - param.envelope_buffer_margin = declare_parameter(ns + "envelope_buffer_margin"); - param.avoid_margin_lateral = declare_parameter(ns + "avoid_margin_lateral"); - param.safety_buffer_lateral = declare_parameter(ns + "safety_buffer_lateral"); - param.safety_buffer_longitudinal = - declare_parameter(ns + "safety_buffer_longitudinal"); - return param; - }; - - const std::string ns = "avoidance.target_object."; - p.object_parameters.emplace( - ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); - p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); - p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); - p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); - p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); - p.object_parameters.emplace( - ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); - p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); - p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); - - p.lower_distance_for_polygon_expansion = - declare_parameter(ns + "lower_distance_for_polygon_expansion"); - p.upper_distance_for_polygon_expansion = - declare_parameter(ns + "upper_distance_for_polygon_expansion"); - } - - // target filtering - { - std::string ns = "avoidance.target_filtering."; - p.threshold_time_force_avoidance_for_stopped_vehicle = - declare_parameter(ns + "threshold_time_force_avoidance_for_stopped_vehicle"); - p.object_ignore_section_traffic_light_in_front_distance = - declare_parameter(ns + "object_ignore_section_traffic_light_in_front_distance"); - p.object_ignore_section_crosswalk_in_front_distance = - declare_parameter(ns + "object_ignore_section_crosswalk_in_front_distance"); - p.object_ignore_section_crosswalk_behind_distance = - declare_parameter(ns + "object_ignore_section_crosswalk_behind_distance"); - p.object_check_forward_distance = - declare_parameter(ns + "object_check_forward_distance"); - p.object_check_backward_distance = - declare_parameter(ns + "object_check_backward_distance"); - p.object_check_goal_distance = declare_parameter(ns + "object_check_goal_distance"); - p.threshold_distance_object_is_on_center = - declare_parameter(ns + "threshold_distance_object_is_on_center"); - p.object_check_shiftable_ratio = declare_parameter(ns + "object_check_shiftable_ratio"); - p.object_check_min_road_shoulder_width = - declare_parameter(ns + "object_check_min_road_shoulder_width"); - p.object_last_seen_threshold = declare_parameter(ns + "object_last_seen_threshold"); - } - - // safety check - { - std::string ns = "avoidance.safety_check."; - p.safety_check_backward_distance = - declare_parameter(ns + "safety_check_backward_distance"); - p.safety_check_time_horizon = declare_parameter(ns + "safety_check_time_horizon"); - p.safety_check_idling_time = declare_parameter(ns + "safety_check_idling_time"); - p.safety_check_accel_for_rss = declare_parameter(ns + "safety_check_accel_for_rss"); - p.safety_check_hysteresis_factor = - declare_parameter(ns + "safety_check_hysteresis_factor"); - } - - // avoidance maneuver (lateral) - { - std::string ns = "avoidance.avoidance.lateral."; - p.road_shoulder_safety_margin = declare_parameter(ns + "road_shoulder_safety_margin"); - p.lateral_execution_threshold = declare_parameter(ns + "lateral_execution_threshold"); - p.lateral_small_shift_threshold = - declare_parameter(ns + "lateral_small_shift_threshold"); - p.max_right_shift_length = declare_parameter(ns + "max_right_shift_length"); - p.max_left_shift_length = declare_parameter(ns + "max_left_shift_length"); - } - - // avoidance maneuver (longitudinal) - { - std::string ns = "avoidance.avoidance.longitudinal."; - p.prepare_time = declare_parameter(ns + "prepare_time"); - p.min_prepare_distance = declare_parameter(ns + "min_prepare_distance"); - p.min_avoidance_distance = declare_parameter(ns + "min_avoidance_distance"); - p.min_nominal_avoidance_speed = declare_parameter(ns + "min_nominal_avoidance_speed"); - p.min_sharp_avoidance_speed = declare_parameter(ns + "min_sharp_avoidance_speed"); - } - - // yield - { - std::string ns = "avoidance.yield."; - p.yield_velocity = declare_parameter(ns + "yield_velocity"); - } - - // stop - { - std::string ns = "avoidance.stop."; - p.stop_min_distance = declare_parameter(ns + "min_distance"); - p.stop_max_distance = declare_parameter(ns + "max_distance"); - } - - // constraints - { - std::string ns = "avoidance.constraints."; - p.use_constraints_for_decel = declare_parameter(ns + "use_constraints_for_decel"); - } - - // constraints (longitudinal) - { - std::string ns = "avoidance.constraints.longitudinal."; - p.nominal_deceleration = declare_parameter(ns + "nominal_deceleration"); - p.nominal_jerk = declare_parameter(ns + "nominal_jerk"); - p.max_deceleration = declare_parameter(ns + "max_deceleration"); - p.max_jerk = declare_parameter(ns + "max_jerk"); - p.min_avoidance_speed_for_acc_prevention = - declare_parameter(ns + "min_avoidance_speed_for_acc_prevention"); - p.max_avoidance_acceleration = declare_parameter(ns + "max_avoidance_acceleration"); - } - - // constraints (lateral) - { - std::string ns = "avoidance.constraints.lateral."; - p.nominal_lateral_jerk = declare_parameter(ns + "nominal_lateral_jerk"); - p.max_lateral_jerk = declare_parameter(ns + "max_lateral_jerk"); - } - - // velocity matrix - { - std::string ns = "avoidance.target_velocity_matrix."; - p.col_size = declare_parameter(ns + "col_size"); - p.target_velocity_matrix = declare_parameter>(ns + "matrix"); - } - - // shift line pipeline - { - std::string ns = "avoidance.shift_line_pipeline."; - p.quantize_filter_threshold = declare_parameter(ns + "trim.quantize_filter_threshold"); - p.same_grad_filter_1_threshold = - declare_parameter(ns + "trim.same_grad_filter_1_threshold"); - p.same_grad_filter_2_threshold = - declare_parameter(ns + "trim.same_grad_filter_2_threshold"); - p.same_grad_filter_3_threshold = - declare_parameter(ns + "trim.same_grad_filter_3_threshold"); - p.sharp_shift_filter_threshold = - declare_parameter(ns + "trim.sharp_shift_filter_threshold"); - } - - return p; -} - -DynamicAvoidanceParameters BehaviorPathPlannerNode::getDynamicAvoidanceParam() -{ - DynamicAvoidanceParameters p{}; - - { // target object - std::string ns = "dynamic_avoidance.target_object."; - p.avoid_car = declare_parameter(ns + "car"); - p.avoid_truck = declare_parameter(ns + "truck"); - p.avoid_bus = declare_parameter(ns + "bus"); - p.avoid_trailer = declare_parameter(ns + "trailer"); - p.avoid_unknown = declare_parameter(ns + "unknown"); - p.avoid_bicycle = declare_parameter(ns + "bicycle"); - p.avoid_motorcycle = declare_parameter(ns + "motorcycle"); - p.avoid_pedestrian = declare_parameter(ns + "pedestrian"); - p.min_obstacle_vel = declare_parameter(ns + "min_obstacle_vel"); - p.successive_num_to_entry_dynamic_avoidance_condition = - declare_parameter(ns + "successive_num_to_entry_dynamic_avoidance_condition"); - } - - { // drivable_area_generation - std::string ns = "dynamic_avoidance.drivable_area_generation."; - p.lat_offset_from_obstacle = declare_parameter(ns + "lat_offset_from_obstacle"); - p.max_lat_offset_to_avoid = declare_parameter(ns + "max_lat_offset_to_avoid"); - - p.max_time_to_collision_overtaking_object = - declare_parameter(ns + "overtaking_object.max_time_to_collision"); - p.start_duration_to_avoid_overtaking_object = - declare_parameter(ns + "overtaking_object.start_duration_to_avoid"); - p.end_duration_to_avoid_overtaking_object = - declare_parameter(ns + "overtaking_object.end_duration_to_avoid"); - p.duration_to_hold_avoidance_overtaking_object = - declare_parameter(ns + "overtaking_object.duration_to_hold_avoidance"); - - p.max_time_to_collision_oncoming_object = - declare_parameter(ns + "oncoming_object.max_time_to_collision"); - p.start_duration_to_avoid_oncoming_object = - declare_parameter(ns + "oncoming_object.start_duration_to_avoid"); - p.end_duration_to_avoid_oncoming_object = - declare_parameter(ns + "oncoming_object.end_duration_to_avoid"); - } - - return p; -} - -LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam() -{ - LaneChangeParameters p{}; - const auto parameter = [](std::string && name) { return "lane_change." + name; }; - - // trajectory generation - p.backward_lane_length = declare_parameter(parameter("backward_lane_length")); - p.prediction_time_resolution = declare_parameter(parameter("prediction_time_resolution")); - p.longitudinal_acc_sampling_num = - declare_parameter(parameter("longitudinal_acceleration_sampling_num")); - p.lateral_acc_sampling_num = - declare_parameter(parameter("lateral_acceleration_sampling_num")); - - // parked vehicle detection - p.object_check_min_road_shoulder_width = - declare_parameter(parameter("object_check_min_road_shoulder_width")); - p.object_shiftable_ratio_threshold = - declare_parameter(parameter("object_shiftable_ratio_threshold")); - - // turn signal - p.min_length_for_turn_signal_activation = - declare_parameter(parameter("min_length_for_turn_signal_activation")); - p.length_ratio_for_turn_signal_deactivation = - declare_parameter(parameter("length_ratio_for_turn_signal_deactivation")); - - // acceleration - p.min_longitudinal_acc = declare_parameter(parameter("min_longitudinal_acc")); - p.max_longitudinal_acc = declare_parameter(parameter("max_longitudinal_acc")); - - // collision check - p.enable_prepare_segment_collision_check = - declare_parameter(parameter("enable_prepare_segment_collision_check")); - p.prepare_segment_ignore_object_velocity_thresh = - declare_parameter(parameter("prepare_segment_ignore_object_velocity_thresh")); - p.use_predicted_path_outside_lanelet = - declare_parameter(parameter("use_predicted_path_outside_lanelet")); - p.use_all_predicted_path = declare_parameter(parameter("use_all_predicted_path")); - - // target object - { - std::string ns = "lane_change.target_object."; - p.check_car = declare_parameter(ns + "car"); - p.check_truck = declare_parameter(ns + "truck"); - p.check_bus = declare_parameter(ns + "bus"); - p.check_trailer = declare_parameter(ns + "trailer"); - p.check_unknown = declare_parameter(ns + "unknown"); - p.check_bicycle = declare_parameter(ns + "bicycle"); - p.check_motorcycle = declare_parameter(ns + "motorcycle"); - p.check_pedestrian = declare_parameter(ns + "pedestrian"); - } - - // lane change cancel - p.cancel.enable_on_prepare_phase = - declare_parameter(parameter("cancel.enable_on_prepare_phase")); - p.cancel.enable_on_lane_changing_phase = - declare_parameter(parameter("cancel.enable_on_lane_changing_phase")); - p.cancel.delta_time = declare_parameter(parameter("cancel.delta_time")); - p.cancel.duration = declare_parameter(parameter("cancel.duration")); - p.cancel.max_lateral_jerk = declare_parameter(parameter("cancel.max_lateral_jerk")); - p.cancel.overhang_tolerance = declare_parameter(parameter("cancel.overhang_tolerance")); - - p.finish_judge_lateral_threshold = - declare_parameter("lane_change.finish_judge_lateral_threshold"); - - // debug marker - p.publish_debug_marker = declare_parameter(parameter("publish_debug_marker")); - - // validation of parameters - if (p.longitudinal_acc_sampling_num < 1 || p.lateral_acc_sampling_num < 1) { - RCLCPP_FATAL_STREAM( - get_logger(), - "lane_change_sampling_num must be positive integer. Given longitudinal parameter: " - << p.longitudinal_acc_sampling_num - << "Given lateral parameter: " << p.lateral_acc_sampling_num << std::endl - << "Terminating the program..."); - exit(EXIT_FAILURE); - } - - if (p.cancel.delta_time < 1.0) { - RCLCPP_WARN_STREAM( - get_logger(), "cancel.delta_time: " << p.cancel.delta_time - << ", is too short. This could cause a danger behavior."); - } - - return p; -} - -GoalPlannerParameters BehaviorPathPlannerNode::getGoalPlannerParam() -{ - GoalPlannerParameters p; - - // general params - { - std::string ns = "goal_planner."; - p.minimum_request_length = declare_parameter(ns + "minimum_request_length"); - p.th_stopped_velocity = declare_parameter(ns + "th_stopped_velocity"); - p.th_arrived_distance = declare_parameter(ns + "th_arrived_distance"); - p.th_stopped_time = declare_parameter(ns + "th_stopped_time"); - } - - // goal search - { - std::string ns = "goal_planner.goal_search."; - p.search_priority = declare_parameter(ns + "search_priority"); - p.forward_goal_search_length = declare_parameter(ns + "forward_goal_search_length"); - p.backward_goal_search_length = declare_parameter(ns + "backward_goal_search_length"); - p.goal_search_interval = declare_parameter(ns + "goal_search_interval"); - p.longitudinal_margin = declare_parameter(ns + "longitudinal_margin"); - p.max_lateral_offset = declare_parameter(ns + "max_lateral_offset"); - p.lateral_offset_interval = declare_parameter(ns + "lateral_offset_interval"); - p.ignore_distance_from_lane_start = - declare_parameter(ns + "ignore_distance_from_lane_start"); - p.margin_from_boundary = declare_parameter(ns + "margin_from_boundary"); - - const std::string parking_policy_name = declare_parameter(ns + "parking_policy"); - if (parking_policy_name == "left_side") { - p.parking_policy = ParkingPolicy::LEFT_SIDE; - } else if (parking_policy_name == "right_side") { - p.parking_policy = ParkingPolicy::RIGHT_SIDE; - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "[goal_planner] invalid parking_policy: " << parking_policy_name << std::endl); - exit(EXIT_FAILURE); - } - } - - // occupancy grid map - { - std::string ns = "goal_planner.occupancy_grid."; - p.use_occupancy_grid = declare_parameter(ns + "use_occupancy_grid"); - p.use_occupancy_grid_for_longitudinal_margin = - declare_parameter(ns + "use_occupancy_grid_for_longitudinal_margin"); - p.occupancy_grid_collision_check_margin = - declare_parameter(ns + "occupancy_grid_collision_check_margin"); - p.theta_size = declare_parameter(ns + "theta_size"); - p.obstacle_threshold = declare_parameter(ns + "obstacle_threshold"); - } - - // object recognition - { - std::string ns = "goal_planner.object_recognition."; - p.use_object_recognition = declare_parameter(ns + "use_object_recognition"); - p.object_recognition_collision_check_margin = - declare_parameter(ns + "object_recognition_collision_check_margin"); - } - - // pull over general params - { - std::string ns = "goal_planner.pull_over."; - p.pull_over_velocity = declare_parameter(ns + "pull_over_velocity"); - p.pull_over_minimum_velocity = declare_parameter(ns + "pull_over_minimum_velocity"); - p.decide_path_distance = declare_parameter(ns + "decide_path_distance"); - p.maximum_deceleration = declare_parameter(ns + "maximum_deceleration"); - p.maximum_jerk = declare_parameter(ns + "maximum_jerk"); - } - - // shift parking - { - std::string ns = "goal_planner.pull_over.shift_parking."; - p.enable_shift_parking = declare_parameter(ns + "enable_shift_parking"); - p.shift_sampling_num = declare_parameter(ns + "shift_sampling_num"); - p.maximum_lateral_jerk = declare_parameter(ns + "maximum_lateral_jerk"); - p.minimum_lateral_jerk = declare_parameter(ns + "minimum_lateral_jerk"); - p.deceleration_interval = declare_parameter(ns + "deceleration_interval"); - p.after_shift_straight_distance = - declare_parameter(ns + "after_shift_straight_distance"); - } - - // forward parallel parking forward - { - std::string ns = "goal_planner.pull_over.parallel_parking.forward."; - p.enable_arc_forward_parking = declare_parameter(ns + "enable_arc_forward_parking"); - p.parallel_parking_parameters.after_forward_parking_straight_distance = - declare_parameter(ns + "after_forward_parking_straight_distance"); - p.parallel_parking_parameters.forward_parking_velocity = - declare_parameter(ns + "forward_parking_velocity"); - p.parallel_parking_parameters.forward_parking_lane_departure_margin = - declare_parameter(ns + "forward_parking_lane_departure_margin"); - p.parallel_parking_parameters.forward_parking_path_interval = - declare_parameter(ns + "forward_parking_path_interval"); - p.parallel_parking_parameters.forward_parking_max_steer_angle = - declare_parameter(ns + "forward_parking_max_steer_angle"); // 20deg - } - - // forward parallel parking backward - { - std::string ns = "goal_planner.pull_over.parallel_parking.backward."; - p.enable_arc_backward_parking = declare_parameter(ns + "enable_arc_backward_parking"); - p.parallel_parking_parameters.after_backward_parking_straight_distance = - declare_parameter(ns + "after_backward_parking_straight_distance"); - p.parallel_parking_parameters.backward_parking_velocity = - declare_parameter(ns + "backward_parking_velocity"); - p.parallel_parking_parameters.backward_parking_lane_departure_margin = - declare_parameter(ns + "backward_parking_lane_departure_margin"); - p.parallel_parking_parameters.backward_parking_path_interval = - declare_parameter(ns + "backward_parking_path_interval"); - p.parallel_parking_parameters.backward_parking_max_steer_angle = - declare_parameter(ns + "backward_parking_max_steer_angle"); // 20deg - } - - // freespace parking general params - { - std::string ns = "goal_planner.pull_over.freespace_parking."; - p.enable_freespace_parking = declare_parameter(ns + "enable_freespace_parking"); - p.freespace_parking_algorithm = - declare_parameter(ns + "freespace_parking_algorithm"); - p.freespace_parking_velocity = declare_parameter(ns + "velocity"); - p.vehicle_shape_margin = declare_parameter(ns + "vehicle_shape_margin"); - p.freespace_parking_common_parameters.time_limit = declare_parameter(ns + "time_limit"); - p.freespace_parking_common_parameters.minimum_turning_radius = - declare_parameter(ns + "minimum_turning_radius"); - p.freespace_parking_common_parameters.maximum_turning_radius = - declare_parameter(ns + "maximum_turning_radius"); - p.freespace_parking_common_parameters.turning_radius_size = - declare_parameter(ns + "turning_radius_size"); - p.freespace_parking_common_parameters.maximum_turning_radius = std::max( - p.freespace_parking_common_parameters.maximum_turning_radius, - p.freespace_parking_common_parameters.minimum_turning_radius); - p.freespace_parking_common_parameters.turning_radius_size = - std::max(p.freespace_parking_common_parameters.turning_radius_size, 1); - } - - // freespace parking search config - { - std::string ns = "goal_planner.pull_over.freespace_parking.search_configs."; - p.freespace_parking_common_parameters.theta_size = declare_parameter(ns + "theta_size"); - p.freespace_parking_common_parameters.angle_goal_range = - declare_parameter(ns + "angle_goal_range"); - p.freespace_parking_common_parameters.curve_weight = - declare_parameter(ns + "curve_weight"); - p.freespace_parking_common_parameters.reverse_weight = - declare_parameter(ns + "reverse_weight"); - p.freespace_parking_common_parameters.lateral_goal_range = - declare_parameter(ns + "lateral_goal_range"); - p.freespace_parking_common_parameters.longitudinal_goal_range = - declare_parameter(ns + "longitudinal_goal_range"); - } - - // freespace parking costmap configs - { - std::string ns = "goal_planner.pull_over.freespace_parking.costmap_configs."; - p.freespace_parking_common_parameters.obstacle_threshold = - declare_parameter(ns + "obstacle_threshold"); - } - - // freespace parking astar - { - std::string ns = "goal_planner.pull_over.freespace_parking.astar."; - p.astar_parameters.only_behind_solutions = - declare_parameter(ns + "only_behind_solutions"); - p.astar_parameters.use_back = declare_parameter(ns + "use_back"); - p.astar_parameters.distance_heuristic_weight = - declare_parameter(ns + "distance_heuristic_weight"); - } - - // freespace parking rrtstar - { - std::string ns = "goal_planner.pull_over.freespace_parking.rrtstar."; - p.rrt_star_parameters.enable_update = declare_parameter(ns + "enable_update"); - p.rrt_star_parameters.use_informed_sampling = - declare_parameter(ns + "use_informed_sampling"); - p.rrt_star_parameters.max_planning_time = declare_parameter(ns + "max_planning_time"); - p.rrt_star_parameters.neighbor_radius = declare_parameter(ns + "neighbor_radius"); - p.rrt_star_parameters.margin = declare_parameter(ns + "margin"); - } - - // debug - { - std::string ns = "goal_planner.debug."; - p.print_debug_info = declare_parameter(ns + "print_debug_info"); - } - - // validation of parameters - if (p.shift_sampling_num < 1) { - RCLCPP_FATAL_STREAM( - get_logger(), "shift_sampling_num must be positive integer. Given parameter: " - << p.shift_sampling_num << std::endl - << "Terminating the program..."); - exit(EXIT_FAILURE); - } - if (p.maximum_deceleration < 0.0) { - RCLCPP_FATAL_STREAM( - get_logger(), "maximum_deceleration cannot be negative value. Given parameter: " - << p.maximum_deceleration << std::endl - << "Terminating the program..."); - exit(EXIT_FAILURE); - } - - return p; -} - -StartPlannerParameters BehaviorPathPlannerNode::getStartPlannerParam() -{ - StartPlannerParameters p; - - std::string ns = "start_planner."; - - p.th_arrived_distance = declare_parameter(ns + "th_arrived_distance"); - p.th_stopped_velocity = declare_parameter(ns + "th_stopped_velocity"); - p.th_stopped_time = declare_parameter(ns + "th_stopped_time"); - p.th_turn_signal_on_lateral_offset = - declare_parameter(ns + "th_turn_signal_on_lateral_offset"); - p.intersection_search_length = declare_parameter(ns + "intersection_search_length"); - p.length_ratio_for_turn_signal_deactivation_near_intersection = - declare_parameter(ns + "length_ratio_for_turn_signal_deactivation_near_intersection"); - p.collision_check_margin = declare_parameter(ns + "collision_check_margin"); - p.collision_check_distance_from_end = - declare_parameter(ns + "collision_check_distance_from_end"); - // shift pull out - p.enable_shift_pull_out = declare_parameter(ns + "enable_shift_pull_out"); - p.minimum_shift_pull_out_distance = - declare_parameter(ns + "minimum_shift_pull_out_distance"); - p.lateral_acceleration_sampling_num = - declare_parameter(ns + "lateral_acceleration_sampling_num"); - p.lateral_jerk = declare_parameter(ns + "lateral_jerk"); - p.maximum_lateral_acc = declare_parameter(ns + "maximum_lateral_acc"); - p.minimum_lateral_acc = declare_parameter(ns + "minimum_lateral_acc"); - p.deceleration_interval = declare_parameter(ns + "deceleration_interval"); - // geometric pull out - p.enable_geometric_pull_out = declare_parameter(ns + "enable_geometric_pull_out"); - p.divide_pull_out_path = declare_parameter(ns + "divide_pull_out_path"); - p.parallel_parking_parameters.pull_out_velocity = - declare_parameter(ns + "geometric_pull_out_velocity"); - p.parallel_parking_parameters.pull_out_path_interval = - declare_parameter(ns + "arc_path_interval"); - p.parallel_parking_parameters.pull_out_lane_departure_margin = - declare_parameter(ns + "lane_departure_margin"); - p.parallel_parking_parameters.pull_out_max_steer_angle = - declare_parameter(ns + "pull_out_max_steer_angle"); // 15deg - // search start pose backward - p.search_priority = declare_parameter( - ns + "search_priority"); // "efficient_path" or "short_back_distance" - p.enable_back = declare_parameter(ns + "enable_back"); - p.backward_velocity = declare_parameter(ns + "backward_velocity"); - p.max_back_distance = declare_parameter(ns + "max_back_distance"); - p.backward_search_resolution = declare_parameter(ns + "backward_search_resolution"); - p.backward_path_update_duration = declare_parameter(ns + "backward_path_update_duration"); - p.ignore_distance_from_lane_end = declare_parameter(ns + "ignore_distance_from_lane_end"); - - // validation of parameters - if (p.lateral_acceleration_sampling_num < 1) { - RCLCPP_FATAL_STREAM( - get_logger(), "lateral_acceleration_sampling_num must be positive integer. Given parameter: " - << p.lateral_acceleration_sampling_num << std::endl - << "Terminating the program..."); - exit(EXIT_FAILURE); - } - - return p; -} - // wait until mandatory data is ready bool BehaviorPathPlannerNode::isDataReady() { @@ -1603,12 +965,6 @@ SetParametersResult BehaviorPathPlannerNode::onSetParam( rcl_interfaces::msg::SetParametersResult result; - if (!lane_change_param_ptr_ && !avoidance_param_ptr_) { - result.successful = false; - result.reason = "param not initialized"; - return result; - } - { const std::lock_guard lock(mutex_manager_); // for planner_manager_ planner_manager_->updateModuleParams(parameters); @@ -1618,8 +974,6 @@ SetParametersResult BehaviorPathPlannerNode::onSetParam( result.reason = "success"; try { - updateParam( - parameters, "lane_change.publish_debug_marker", lane_change_param_ptr_->publish_debug_marker); // Drivable area expansion parameters using drivable_area_expansion::DrivableAreaExpansionParameters; const std::lock_guard lock(mutex_pd_); // for planner_data_ 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 816ed94e5b822..f9a652a4cec27 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -23,11 +23,209 @@ namespace behavior_path_planner { +namespace +{ +template +T get_parameter(rclcpp::Node * node, const std::string & ns) +{ + if (node->has_parameter(ns)) { + return node->get_parameter(ns).get_value(); + } + + return node->declare_parameter(ns); +} +} // namespace + AvoidanceModuleManager::AvoidanceModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - const std::shared_ptr & parameters) -: SceneModuleManagerInterface(node, name, config, {"left", "right"}), parameters_{parameters} + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config) +: SceneModuleManagerInterface(node, name, config, {"left", "right"}) { + using autoware_auto_perception_msgs::msg::ObjectClassification; + + AvoidanceParameters p{}; + // general params + { + std::string ns = "avoidance."; + p.resample_interval_for_planning = + get_parameter(node, ns + "resample_interval_for_planning"); + p.resample_interval_for_output = + get_parameter(node, ns + "resample_interval_for_output"); + p.detection_area_right_expand_dist = + get_parameter(node, ns + "detection_area_right_expand_dist"); + p.detection_area_left_expand_dist = + get_parameter(node, ns + "detection_area_left_expand_dist"); + p.enable_bound_clipping = get_parameter(node, ns + "enable_bound_clipping"); + p.enable_avoidance_over_same_direction = + get_parameter(node, ns + "enable_avoidance_over_same_direction"); + p.enable_avoidance_over_opposite_direction = + get_parameter(node, ns + "enable_avoidance_over_opposite_direction"); + p.enable_update_path_when_object_is_gone = + get_parameter(node, ns + "enable_update_path_when_object_is_gone"); + p.enable_force_avoidance_for_stopped_vehicle = + get_parameter(node, ns + "enable_force_avoidance_for_stopped_vehicle"); + p.enable_safety_check = get_parameter(node, ns + "enable_safety_check"); + p.enable_yield_maneuver = get_parameter(node, ns + "enable_yield_maneuver"); + p.enable_yield_maneuver_during_shifting = + get_parameter(node, ns + "enable_yield_maneuver_during_shifting"); + p.disable_path_update = get_parameter(node, ns + "disable_path_update"); + p.use_hatched_road_markings = get_parameter(node, ns + "use_hatched_road_markings"); + p.publish_debug_marker = get_parameter(node, ns + "publish_debug_marker"); + p.print_debug_info = get_parameter(node, ns + "print_debug_info"); + } + + // target object + { + const auto get_object_param = [&](std::string && ns) { + ObjectParameter param{}; + param.is_target = get_parameter(node, ns + "is_target"); + param.moving_speed_threshold = get_parameter(node, ns + "moving_speed_threshold"); + param.moving_time_threshold = get_parameter(node, ns + "moving_time_threshold"); + param.max_expand_ratio = get_parameter(node, ns + "max_expand_ratio"); + param.envelope_buffer_margin = get_parameter(node, ns + "envelope_buffer_margin"); + param.avoid_margin_lateral = get_parameter(node, ns + "avoid_margin_lateral"); + param.safety_buffer_lateral = get_parameter(node, ns + "safety_buffer_lateral"); + param.safety_buffer_longitudinal = + get_parameter(node, ns + "safety_buffer_longitudinal"); + return param; + }; + + const std::string ns = "avoidance.target_object."; + p.object_parameters.emplace( + ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); + p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); + p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); + p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); + p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); + p.object_parameters.emplace( + ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); + p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); + p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); + + p.lower_distance_for_polygon_expansion = + get_parameter(node, ns + "lower_distance_for_polygon_expansion"); + p.upper_distance_for_polygon_expansion = + get_parameter(node, ns + "upper_distance_for_polygon_expansion"); + } + + // target filtering + { + std::string ns = "avoidance.target_filtering."; + p.threshold_time_force_avoidance_for_stopped_vehicle = + get_parameter(node, ns + "threshold_time_force_avoidance_for_stopped_vehicle"); + p.object_ignore_section_traffic_light_in_front_distance = + get_parameter(node, ns + "object_ignore_section_traffic_light_in_front_distance"); + p.object_ignore_section_crosswalk_in_front_distance = + get_parameter(node, ns + "object_ignore_section_crosswalk_in_front_distance"); + p.object_ignore_section_crosswalk_behind_distance = + get_parameter(node, ns + "object_ignore_section_crosswalk_behind_distance"); + p.object_check_forward_distance = + get_parameter(node, ns + "object_check_forward_distance"); + p.object_check_backward_distance = + get_parameter(node, ns + "object_check_backward_distance"); + p.object_check_goal_distance = get_parameter(node, ns + "object_check_goal_distance"); + p.threshold_distance_object_is_on_center = + get_parameter(node, ns + "threshold_distance_object_is_on_center"); + p.object_check_shiftable_ratio = + get_parameter(node, ns + "object_check_shiftable_ratio"); + p.object_check_min_road_shoulder_width = + get_parameter(node, ns + "object_check_min_road_shoulder_width"); + p.object_last_seen_threshold = get_parameter(node, ns + "object_last_seen_threshold"); + } + + // safety check + { + std::string ns = "avoidance.safety_check."; + p.safety_check_backward_distance = + get_parameter(node, ns + "safety_check_backward_distance"); + p.safety_check_time_horizon = get_parameter(node, ns + "safety_check_time_horizon"); + p.safety_check_idling_time = get_parameter(node, ns + "safety_check_idling_time"); + p.safety_check_accel_for_rss = get_parameter(node, ns + "safety_check_accel_for_rss"); + p.safety_check_hysteresis_factor = + get_parameter(node, ns + "safety_check_hysteresis_factor"); + } + + // avoidance maneuver (lateral) + { + std::string ns = "avoidance.avoidance.lateral."; + p.road_shoulder_safety_margin = get_parameter(node, ns + "road_shoulder_safety_margin"); + p.lateral_execution_threshold = get_parameter(node, ns + "lateral_execution_threshold"); + p.lateral_small_shift_threshold = + get_parameter(node, ns + "lateral_small_shift_threshold"); + p.max_right_shift_length = get_parameter(node, ns + "max_right_shift_length"); + p.max_left_shift_length = get_parameter(node, ns + "max_left_shift_length"); + } + + // avoidance maneuver (longitudinal) + { + std::string ns = "avoidance.avoidance.longitudinal."; + p.prepare_time = get_parameter(node, ns + "prepare_time"); + p.min_prepare_distance = get_parameter(node, ns + "min_prepare_distance"); + p.min_avoidance_distance = get_parameter(node, ns + "min_avoidance_distance"); + p.min_nominal_avoidance_speed = get_parameter(node, ns + "min_nominal_avoidance_speed"); + p.min_sharp_avoidance_speed = get_parameter(node, ns + "min_sharp_avoidance_speed"); + } + + // yield + { + std::string ns = "avoidance.yield."; + p.yield_velocity = get_parameter(node, ns + "yield_velocity"); + } + + // stop + { + std::string ns = "avoidance.stop."; + p.stop_min_distance = get_parameter(node, ns + "min_distance"); + p.stop_max_distance = get_parameter(node, ns + "max_distance"); + } + + // constraints + { + std::string ns = "avoidance.constraints."; + p.use_constraints_for_decel = get_parameter(node, ns + "use_constraints_for_decel"); + } + + // constraints (longitudinal) + { + std::string ns = "avoidance.constraints.longitudinal."; + p.nominal_deceleration = get_parameter(node, ns + "nominal_deceleration"); + p.nominal_jerk = get_parameter(node, ns + "nominal_jerk"); + p.max_deceleration = get_parameter(node, ns + "max_deceleration"); + p.max_jerk = get_parameter(node, ns + "max_jerk"); + p.min_avoidance_speed_for_acc_prevention = + get_parameter(node, ns + "min_avoidance_speed_for_acc_prevention"); + p.max_avoidance_acceleration = get_parameter(node, ns + "max_avoidance_acceleration"); + } + + // constraints (lateral) + { + std::string ns = "avoidance.constraints.lateral."; + p.nominal_lateral_jerk = get_parameter(node, ns + "nominal_lateral_jerk"); + p.max_lateral_jerk = get_parameter(node, ns + "max_lateral_jerk"); + } + + // velocity matrix + { + std::string ns = "avoidance.target_velocity_matrix."; + p.col_size = get_parameter(node, ns + "col_size"); + p.target_velocity_matrix = get_parameter>(node, ns + "matrix"); + } + + // shift line pipeline + { + std::string ns = "avoidance.shift_line_pipeline."; + p.quantize_filter_threshold = + get_parameter(node, ns + "trim.quantize_filter_threshold"); + p.same_grad_filter_1_threshold = + get_parameter(node, ns + "trim.same_grad_filter_1_threshold"); + p.same_grad_filter_2_threshold = + get_parameter(node, ns + "trim.same_grad_filter_2_threshold"); + p.same_grad_filter_3_threshold = + get_parameter(node, ns + "trim.same_grad_filter_3_threshold"); + p.sharp_shift_filter_threshold = + get_parameter(node, ns + "trim.sharp_shift_filter_threshold"); + } + + parameters_ = std::make_shared(p); } void AvoidanceModuleManager::updateModuleParams(const std::vector & parameters) diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index b9ca4ffa964f7..08188343f1d64 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -24,10 +24,49 @@ namespace behavior_path_planner { DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - const std::shared_ptr & parameters) -: SceneModuleManagerInterface(node, name, config, {""}), parameters_{parameters} + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config) +: SceneModuleManagerInterface(node, name, config, {""}) { + DynamicAvoidanceParameters p{}; + + { // target object + std::string ns = "dynamic_avoidance.target_object."; + p.avoid_car = node->declare_parameter(ns + "car"); + p.avoid_truck = node->declare_parameter(ns + "truck"); + p.avoid_bus = node->declare_parameter(ns + "bus"); + p.avoid_trailer = node->declare_parameter(ns + "trailer"); + p.avoid_unknown = node->declare_parameter(ns + "unknown"); + p.avoid_bicycle = node->declare_parameter(ns + "bicycle"); + p.avoid_motorcycle = node->declare_parameter(ns + "motorcycle"); + p.avoid_pedestrian = node->declare_parameter(ns + "pedestrian"); + p.min_obstacle_vel = node->declare_parameter(ns + "min_obstacle_vel"); + p.successive_num_to_entry_dynamic_avoidance_condition = + node->declare_parameter(ns + "successive_num_to_entry_dynamic_avoidance_condition"); + } + + { // drivable_area_generation + std::string ns = "dynamic_avoidance.drivable_area_generation."; + p.lat_offset_from_obstacle = node->declare_parameter(ns + "lat_offset_from_obstacle"); + p.max_lat_offset_to_avoid = node->declare_parameter(ns + "max_lat_offset_to_avoid"); + + p.max_time_to_collision_overtaking_object = + node->declare_parameter(ns + "overtaking_object.max_time_to_collision"); + p.start_duration_to_avoid_overtaking_object = + node->declare_parameter(ns + "overtaking_object.start_duration_to_avoid"); + p.end_duration_to_avoid_overtaking_object = + node->declare_parameter(ns + "overtaking_object.end_duration_to_avoid"); + p.duration_to_hold_avoidance_overtaking_object = + node->declare_parameter(ns + "overtaking_object.duration_to_hold_avoidance"); + + p.max_time_to_collision_oncoming_object = + node->declare_parameter(ns + "oncoming_object.max_time_to_collision"); + p.start_duration_to_avoid_oncoming_object = + node->declare_parameter(ns + "oncoming_object.start_duration_to_avoid"); + p.end_duration_to_avoid_oncoming_object = + node->declare_parameter(ns + "oncoming_object.end_duration_to_avoid"); + } + + parameters_ = std::make_shared(p); } void DynamicAvoidanceModuleManager::updateModuleParams( diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp index af96313aa0c19..caa75927f4062 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp @@ -24,10 +24,217 @@ namespace behavior_path_planner { GoalPlannerModuleManager::GoalPlannerModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - const std::shared_ptr & parameters) -: SceneModuleManagerInterface(node, name, config, {""}), parameters_{parameters} + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config) +: SceneModuleManagerInterface(node, name, config, {""}) { + GoalPlannerParameters p; + + // general params + { + std::string ns = "goal_planner."; + p.minimum_request_length = node->declare_parameter(ns + "minimum_request_length"); + p.th_stopped_velocity = node->declare_parameter(ns + "th_stopped_velocity"); + p.th_arrived_distance = node->declare_parameter(ns + "th_arrived_distance"); + p.th_stopped_time = node->declare_parameter(ns + "th_stopped_time"); + } + + // goal search + { + std::string ns = "goal_planner.goal_search."; + p.search_priority = node->declare_parameter(ns + "search_priority"); + p.forward_goal_search_length = + node->declare_parameter(ns + "forward_goal_search_length"); + p.backward_goal_search_length = + node->declare_parameter(ns + "backward_goal_search_length"); + p.goal_search_interval = node->declare_parameter(ns + "goal_search_interval"); + p.longitudinal_margin = node->declare_parameter(ns + "longitudinal_margin"); + p.max_lateral_offset = node->declare_parameter(ns + "max_lateral_offset"); + p.lateral_offset_interval = node->declare_parameter(ns + "lateral_offset_interval"); + p.ignore_distance_from_lane_start = + node->declare_parameter(ns + "ignore_distance_from_lane_start"); + p.margin_from_boundary = node->declare_parameter(ns + "margin_from_boundary"); + + const std::string parking_policy_name = + node->declare_parameter(ns + "parking_policy"); + if (parking_policy_name == "left_side") { + p.parking_policy = ParkingPolicy::LEFT_SIDE; + } else if (parking_policy_name == "right_side") { + p.parking_policy = ParkingPolicy::RIGHT_SIDE; + } else { + RCLCPP_ERROR_STREAM( + logger_, "[goal_planner] invalid parking_policy: " << parking_policy_name << std::endl); + exit(EXIT_FAILURE); + } + } + + // occupancy grid map + { + std::string ns = "goal_planner.occupancy_grid."; + p.use_occupancy_grid = node->declare_parameter(ns + "use_occupancy_grid"); + p.use_occupancy_grid_for_longitudinal_margin = + node->declare_parameter(ns + "use_occupancy_grid_for_longitudinal_margin"); + p.occupancy_grid_collision_check_margin = + node->declare_parameter(ns + "occupancy_grid_collision_check_margin"); + p.theta_size = node->declare_parameter(ns + "theta_size"); + p.obstacle_threshold = node->declare_parameter(ns + "obstacle_threshold"); + } + + // object recognition + { + std::string ns = "goal_planner.object_recognition."; + p.use_object_recognition = node->declare_parameter(ns + "use_object_recognition"); + p.object_recognition_collision_check_margin = + node->declare_parameter(ns + "object_recognition_collision_check_margin"); + } + + // pull over general params + { + std::string ns = "goal_planner.pull_over."; + p.pull_over_velocity = node->declare_parameter(ns + "pull_over_velocity"); + p.pull_over_minimum_velocity = + node->declare_parameter(ns + "pull_over_minimum_velocity"); + p.decide_path_distance = node->declare_parameter(ns + "decide_path_distance"); + p.maximum_deceleration = node->declare_parameter(ns + "maximum_deceleration"); + p.maximum_jerk = node->declare_parameter(ns + "maximum_jerk"); + } + + // shift parking + { + std::string ns = "goal_planner.pull_over.shift_parking."; + p.enable_shift_parking = node->declare_parameter(ns + "enable_shift_parking"); + p.shift_sampling_num = node->declare_parameter(ns + "shift_sampling_num"); + p.maximum_lateral_jerk = node->declare_parameter(ns + "maximum_lateral_jerk"); + p.minimum_lateral_jerk = node->declare_parameter(ns + "minimum_lateral_jerk"); + p.deceleration_interval = node->declare_parameter(ns + "deceleration_interval"); + p.after_shift_straight_distance = + node->declare_parameter(ns + "after_shift_straight_distance"); + } + + // forward parallel parking forward + { + std::string ns = "goal_planner.pull_over.parallel_parking.forward."; + p.enable_arc_forward_parking = node->declare_parameter(ns + "enable_arc_forward_parking"); + p.parallel_parking_parameters.after_forward_parking_straight_distance = + node->declare_parameter(ns + "after_forward_parking_straight_distance"); + p.parallel_parking_parameters.forward_parking_velocity = + node->declare_parameter(ns + "forward_parking_velocity"); + p.parallel_parking_parameters.forward_parking_lane_departure_margin = + node->declare_parameter(ns + "forward_parking_lane_departure_margin"); + p.parallel_parking_parameters.forward_parking_path_interval = + node->declare_parameter(ns + "forward_parking_path_interval"); + p.parallel_parking_parameters.forward_parking_max_steer_angle = + node->declare_parameter(ns + "forward_parking_max_steer_angle"); // 20deg + } + + // forward parallel parking backward + { + std::string ns = "goal_planner.pull_over.parallel_parking.backward."; + p.enable_arc_backward_parking = + node->declare_parameter(ns + "enable_arc_backward_parking"); + p.parallel_parking_parameters.after_backward_parking_straight_distance = + node->declare_parameter(ns + "after_backward_parking_straight_distance"); + p.parallel_parking_parameters.backward_parking_velocity = + node->declare_parameter(ns + "backward_parking_velocity"); + p.parallel_parking_parameters.backward_parking_lane_departure_margin = + node->declare_parameter(ns + "backward_parking_lane_departure_margin"); + p.parallel_parking_parameters.backward_parking_path_interval = + node->declare_parameter(ns + "backward_parking_path_interval"); + p.parallel_parking_parameters.backward_parking_max_steer_angle = + node->declare_parameter(ns + "backward_parking_max_steer_angle"); // 20deg + } + + // freespace parking general params + { + std::string ns = "goal_planner.pull_over.freespace_parking."; + p.enable_freespace_parking = node->declare_parameter(ns + "enable_freespace_parking"); + p.freespace_parking_algorithm = + node->declare_parameter(ns + "freespace_parking_algorithm"); + p.freespace_parking_velocity = node->declare_parameter(ns + "velocity"); + p.vehicle_shape_margin = node->declare_parameter(ns + "vehicle_shape_margin"); + p.freespace_parking_common_parameters.time_limit = + node->declare_parameter(ns + "time_limit"); + p.freespace_parking_common_parameters.minimum_turning_radius = + node->declare_parameter(ns + "minimum_turning_radius"); + p.freespace_parking_common_parameters.maximum_turning_radius = + node->declare_parameter(ns + "maximum_turning_radius"); + p.freespace_parking_common_parameters.turning_radius_size = + node->declare_parameter(ns + "turning_radius_size"); + p.freespace_parking_common_parameters.maximum_turning_radius = std::max( + p.freespace_parking_common_parameters.maximum_turning_radius, + p.freespace_parking_common_parameters.minimum_turning_radius); + p.freespace_parking_common_parameters.turning_radius_size = + std::max(p.freespace_parking_common_parameters.turning_radius_size, 1); + } + + // freespace parking search config + { + std::string ns = "goal_planner.pull_over.freespace_parking.search_configs."; + p.freespace_parking_common_parameters.theta_size = + node->declare_parameter(ns + "theta_size"); + p.freespace_parking_common_parameters.angle_goal_range = + node->declare_parameter(ns + "angle_goal_range"); + p.freespace_parking_common_parameters.curve_weight = + node->declare_parameter(ns + "curve_weight"); + p.freespace_parking_common_parameters.reverse_weight = + node->declare_parameter(ns + "reverse_weight"); + p.freespace_parking_common_parameters.lateral_goal_range = + node->declare_parameter(ns + "lateral_goal_range"); + p.freespace_parking_common_parameters.longitudinal_goal_range = + node->declare_parameter(ns + "longitudinal_goal_range"); + } + + // freespace parking costmap configs + { + std::string ns = "goal_planner.pull_over.freespace_parking.costmap_configs."; + p.freespace_parking_common_parameters.obstacle_threshold = + node->declare_parameter(ns + "obstacle_threshold"); + } + + // freespace parking astar + { + std::string ns = "goal_planner.pull_over.freespace_parking.astar."; + p.astar_parameters.only_behind_solutions = + node->declare_parameter(ns + "only_behind_solutions"); + p.astar_parameters.use_back = node->declare_parameter(ns + "use_back"); + p.astar_parameters.distance_heuristic_weight = + node->declare_parameter(ns + "distance_heuristic_weight"); + } + + // freespace parking rrtstar + { + std::string ns = "goal_planner.pull_over.freespace_parking.rrtstar."; + p.rrt_star_parameters.enable_update = node->declare_parameter(ns + "enable_update"); + p.rrt_star_parameters.use_informed_sampling = + node->declare_parameter(ns + "use_informed_sampling"); + p.rrt_star_parameters.max_planning_time = + node->declare_parameter(ns + "max_planning_time"); + p.rrt_star_parameters.neighbor_radius = node->declare_parameter(ns + "neighbor_radius"); + p.rrt_star_parameters.margin = node->declare_parameter(ns + "margin"); + } + + // debug + { + std::string ns = "goal_planner.debug."; + p.print_debug_info = node->declare_parameter(ns + "print_debug_info"); + } + + // validation of parameters + if (p.shift_sampling_num < 1) { + RCLCPP_FATAL_STREAM( + logger_, "shift_sampling_num must be positive integer. Given parameter: " + << p.shift_sampling_num << std::endl + << "Terminating the program..."); + exit(EXIT_FAILURE); + } + if (p.maximum_deceleration < 0.0) { + RCLCPP_FATAL_STREAM( + logger_, "maximum_deceleration cannot be negative value. Given parameter: " + << p.maximum_deceleration << std::endl + << "Terminating the program..."); + exit(EXIT_FAILURE); + } + + parameters_ = std::make_shared(p); } void GoalPlannerModuleManager::updateModuleParams( 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 1a1d680a99805..c808703b8f961 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 @@ -25,18 +25,16 @@ namespace behavior_path_planner { AvoidanceByLaneChange::AvoidanceByLaneChange( const std::shared_ptr & parameters, - std::shared_ptr avoidance_parameters, - std::shared_ptr avoidance_by_lane_change_parameters) + std::shared_ptr avoidance_parameters) : NormalLaneChange(parameters, LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE, Direction::NONE), - avoidance_parameters_(std::move(avoidance_parameters)), - avoidance_by_lane_change_parameters_(std::move(avoidance_by_lane_change_parameters)) + avoidance_parameters_(std::move(avoidance_parameters)) { } std::pair AvoidanceByLaneChange::getSafePath(LaneChangePath & safe_path) const { const auto & avoidance_objects = avoidance_data_.target_objects; - const auto execute_object_num = avoidance_by_lane_change_parameters_->execute_object_num; + const auto execute_object_num = avoidance_parameters_->execute_object_num; if (avoidance_objects.size() < execute_object_num) { return {false, false}; @@ -52,7 +50,7 @@ std::pair AvoidanceByLaneChange::getSafePath(LaneChangePath & safe_p // check distance from ego to o_front vs acceptable longitudinal margin const auto execute_object_longitudinal_margin = - avoidance_by_lane_change_parameters_->execute_object_longitudinal_margin; + avoidance_parameters_->execute_object_longitudinal_margin; if (execute_object_longitudinal_margin > o_front.longitudinal) { return {false, false}; } @@ -84,7 +82,7 @@ std::pair AvoidanceByLaneChange::getSafePath(LaneChangePath & safe_p safe_path.path.points, getEgoPose().position, safe_path.shift_line.end.position); const auto lane_change_finish_before_object = o_front.longitudinal > to_lane_change_end_distance; const auto execute_only_when_lane_change_finish_before_object = - avoidance_by_lane_change_parameters_->execute_only_when_lane_change_finish_before_object; + avoidance_parameters_->execute_only_when_lane_change_finish_before_object; if (!lane_change_finish_before_object && execute_only_when_lane_change_finish_before_object) { return {false, found_safe_path}; } @@ -93,12 +91,12 @@ std::pair AvoidanceByLaneChange::getSafePath(LaneChangePath & safe_p void AvoidanceByLaneChange::updateSpecialData() { + const auto p = std::dynamic_pointer_cast(avoidance_parameters_); + avoidance_debug_data_ = DebugData(); avoidance_data_ = calcAvoidancePlanningData(avoidance_debug_data_); - utils::avoidance::updateRegisteredObject( - registered_objects_, avoidance_data_.target_objects, - avoidance_by_lane_change_parameters_->avoidance); + utils::avoidance::updateRegisteredObject(registered_objects_, avoidance_data_.target_objects, p); utils::avoidance::compensateDetectionLost( registered_objects_, avoidance_data_.target_objects, avoidance_data_.other_objects); @@ -117,8 +115,7 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData( data.reference_path_rough = prev_module_path_; - const auto resample_interval = - avoidance_by_lane_change_parameters_->avoidance->resample_interval_for_planning; + const auto resample_interval = avoidance_parameters_->resample_interval_for_planning; data.reference_path = utils::resamplePathWithSpline(data.reference_path_rough, resample_interval); data.current_lanelets = getCurrentLanes(); @@ -133,8 +130,10 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData( void AvoidanceByLaneChange::fillAvoidanceTargetObjects( AvoidancePlanningData & data, DebugData & debug) const { - const auto left_expand_dist = avoidance_parameters_->detection_area_left_expand_dist; - const auto right_expand_dist = avoidance_parameters_->detection_area_right_expand_dist; + const auto p = std::dynamic_pointer_cast(avoidance_parameters_); + + const auto left_expand_dist = p->detection_area_left_expand_dist; + const auto right_expand_dist = p->detection_area_right_expand_dist; const auto expanded_lanelets = lanelet::utils::getExpandedLanelets( data.current_lanelets, left_expand_dist, right_expand_dist * (-1.0)); @@ -173,8 +172,7 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects( [&](const auto & object) { return createObjectData(data, object); }); } - utils::avoidance::filterTargetObjects( - target_lane_objects, data, debug, planner_data_, avoidance_parameters_); + utils::avoidance::filterTargetObjects(target_lane_objects, data, debug, planner_data_, p); } ObjectData AvoidanceByLaneChange::createObjectData( @@ -184,32 +182,34 @@ ObjectData AvoidanceByLaneChange::createObjectData( using motion_utils::findNearestIndex; using tier4_autoware_utils::calcDistance2d; + const auto p = std::dynamic_pointer_cast(avoidance_parameters_); + const auto & path_points = data.reference_path.points; const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; const auto object_closest_index = findNearestIndex(path_points, object_pose.position); const auto object_closest_pose = path_points.at(object_closest_index).point.pose; const auto t = utils::getHighestProbLabel(object.classification); - const auto object_parameter = avoidance_parameters_->object_parameters.at(t); + const auto object_parameter = p->object_parameters.at(t); ObjectData object_data{}; object_data.object = object; - const auto lower = avoidance_parameters_->lower_distance_for_polygon_expansion; - const auto upper = avoidance_parameters_->upper_distance_for_polygon_expansion; + const auto lower = p->lower_distance_for_polygon_expansion; + const auto upper = p->upper_distance_for_polygon_expansion; const auto clamp = std::clamp(calcDistance2d(getEgoPose(), object_pose) - lower, 0.0, upper) / upper; object_data.distance_factor = object_parameter.max_expand_ratio * clamp + 1.0; // Calc envelop polygon. utils::avoidance::fillObjectEnvelopePolygon( - object_data, registered_objects_, object_closest_pose, avoidance_parameters_); + object_data, registered_objects_, object_closest_pose, p); // calc object centroid. object_data.centroid = return_centroid(object_data.envelope_poly); // Calc moving time. - utils::avoidance::fillObjectMovingTime(object_data, stopped_objects_, avoidance_parameters_); + utils::avoidance::fillObjectMovingTime(object_data, stopped_objects_, p); // Calc lateral deviation from path to target object. object_data.lateral = @@ -221,8 +221,7 @@ ObjectData AvoidanceByLaneChange::createObjectData( // Check whether the the ego should avoid the object. const auto & vehicle_width = planner_data_->parameters.vehicle_width; - utils::avoidance::fillAvoidanceNecessity( - object_data, registered_objects_, vehicle_width, avoidance_parameters_); + utils::avoidance::fillAvoidanceNecessity(object_data, registered_objects_, vehicle_width, p); return object_data; } 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 713188afb7f0b..721c7fa6fd390 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 @@ -487,13 +487,11 @@ void SceneModuleVisitor::visitLaneChangeInterface(const LaneChangeInterface * in AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::shared_ptr & avoidance_parameters, const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map > & rtc_interface_ptr_map) : LaneChangeInterface{ name, node, parameters, rtc_interface_ptr_map, - std::make_unique( - parameters, avoidance_parameters, avoidance_by_lane_change_parameters)} + std::make_unique(parameters, avoidance_by_lane_change_parameters)} { } 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 b410d4d75840b..f336d1325b688 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 @@ -23,17 +23,112 @@ namespace behavior_path_planner { + using route_handler::Direction; using utils::convertToSnakeCase; + +namespace +{ +template +T get_parameter(rclcpp::Node * node, const std::string & ns) +{ + if (node->has_parameter(ns)) { + return node->get_parameter(ns).get_value(); + } + + return node->declare_parameter(ns); +} +} // namespace + LaneChangeModuleManager::LaneChangeModuleManager( rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - std::shared_ptr parameters, const Direction direction, - const LaneChangeModuleType type) -: SceneModuleManagerInterface(node, name, config, {""}), - parameters_{std::move(parameters)}, - direction_{direction}, - type_{type} + const Direction direction, const LaneChangeModuleType type) +: SceneModuleManagerInterface(node, name, config, {""}), direction_{direction}, type_{type} { + LaneChangeParameters p{}; + + const auto parameter = [](std::string && name) { return "lane_change." + name; }; + + // trajectory generation + p.backward_lane_length = get_parameter(node, parameter("backward_lane_length")); + p.prediction_time_resolution = + get_parameter(node, parameter("prediction_time_resolution")); + p.longitudinal_acc_sampling_num = + get_parameter(node, parameter("longitudinal_acceleration_sampling_num")); + p.lateral_acc_sampling_num = + get_parameter(node, parameter("lateral_acceleration_sampling_num")); + + // parked vehicle detection + p.object_check_min_road_shoulder_width = + get_parameter(node, parameter("object_check_min_road_shoulder_width")); + p.object_shiftable_ratio_threshold = + get_parameter(node, parameter("object_shiftable_ratio_threshold")); + + // turn signal + p.min_length_for_turn_signal_activation = + get_parameter(node, parameter("min_length_for_turn_signal_activation")); + p.length_ratio_for_turn_signal_deactivation = + get_parameter(node, parameter("length_ratio_for_turn_signal_deactivation")); + + // acceleration + p.min_longitudinal_acc = get_parameter(node, parameter("min_longitudinal_acc")); + p.max_longitudinal_acc = get_parameter(node, parameter("max_longitudinal_acc")); + + // collision check + p.enable_prepare_segment_collision_check = + get_parameter(node, parameter("enable_prepare_segment_collision_check")); + p.prepare_segment_ignore_object_velocity_thresh = + get_parameter(node, parameter("prepare_segment_ignore_object_velocity_thresh")); + p.use_predicted_path_outside_lanelet = + get_parameter(node, parameter("use_predicted_path_outside_lanelet")); + p.use_all_predicted_path = get_parameter(node, parameter("use_all_predicted_path")); + + // target object + { + std::string ns = "lane_change.target_object."; + p.check_car = get_parameter(node, ns + "car"); + p.check_truck = get_parameter(node, ns + "truck"); + p.check_bus = get_parameter(node, ns + "bus"); + p.check_trailer = get_parameter(node, ns + "trailer"); + p.check_unknown = get_parameter(node, ns + "unknown"); + p.check_bicycle = get_parameter(node, ns + "bicycle"); + p.check_motorcycle = get_parameter(node, ns + "motorcycle"); + p.check_pedestrian = get_parameter(node, ns + "pedestrian"); + } + + // lane change cancel + p.cancel.enable_on_prepare_phase = + get_parameter(node, parameter("cancel.enable_on_prepare_phase")); + p.cancel.enable_on_lane_changing_phase = + get_parameter(node, parameter("cancel.enable_on_lane_changing_phase")); + p.cancel.delta_time = get_parameter(node, parameter("cancel.delta_time")); + p.cancel.duration = get_parameter(node, parameter("cancel.duration")); + p.cancel.max_lateral_jerk = get_parameter(node, parameter("cancel.max_lateral_jerk")); + p.cancel.overhang_tolerance = get_parameter(node, parameter("cancel.overhang_tolerance")); + + p.finish_judge_lateral_threshold = + get_parameter(node, parameter("finish_judge_lateral_threshold")); + + // debug marker + p.publish_debug_marker = get_parameter(node, parameter("publish_debug_marker")); + + // validation of parameters + if (p.longitudinal_acc_sampling_num < 1 || p.lateral_acc_sampling_num < 1) { + RCLCPP_FATAL_STREAM( + logger_, "lane_change_sampling_num must be positive integer. Given longitudinal parameter: " + << p.longitudinal_acc_sampling_num + << "Given lateral parameter: " << p.lateral_acc_sampling_num << std::endl + << "Terminating the program..."); + exit(EXIT_FAILURE); + } + + if (p.cancel.delta_time < 1.0) { + RCLCPP_WARN_STREAM( + logger_, "cancel.delta_time: " << p.cancel.delta_time + << ", is too short. This could cause a danger behavior."); + } + + parameters_ = std::make_shared(p); } std::shared_ptr LaneChangeModuleManager::createNewSceneModuleInstance() @@ -64,16 +159,12 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector parameters, - std::shared_ptr avoidance_parameters, - std::shared_ptr avoidance_by_lane_change_parameters) + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config) : LaneChangeModuleManager( - node, name, config, std::move(parameters), Direction::NONE, - LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE), - avoidance_parameters_(std::move(avoidance_parameters)), - avoidance_by_lane_change_parameters_(std::move(avoidance_by_lane_change_parameters)) + node, name, config, Direction::NONE, LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) { + using autoware_auto_perception_msgs::msg::ObjectClassification; + rtc_interface_ptr_map_.clear(); const std::vector rtc_types = {"left", "right"}; for (const auto & rtc_type : rtc_types) { @@ -82,14 +173,110 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( rtc_interface_ptr_map_.emplace( rtc_type, std::make_shared(node, rtc_interface_name)); } + + AvoidanceByLCParameters p{}; + // unique parameters + { + std::string ns = "avoidance_by_lane_change."; + p.execute_object_num = get_parameter(node, ns + "execute_object_num"); + p.execute_object_longitudinal_margin = + get_parameter(node, ns + "execute_object_longitudinal_margin"); + p.execute_only_when_lane_change_finish_before_object = + get_parameter(node, ns + "execute_only_when_lane_change_finish_before_object"); + } + + if (p.execute_object_num < 1) { + RCLCPP_WARN_STREAM(logger_, "execute_object_num cannot be lesser than 1."); + } + + // general params + { + std::string ns = "avoidance."; + p.resample_interval_for_planning = + get_parameter(node, ns + "resample_interval_for_planning"); + p.resample_interval_for_output = + get_parameter(node, ns + "resample_interval_for_output"); + p.detection_area_right_expand_dist = + get_parameter(node, ns + "detection_area_right_expand_dist"); + p.detection_area_left_expand_dist = + get_parameter(node, ns + "detection_area_left_expand_dist"); + p.enable_avoidance_over_same_direction = + get_parameter(node, ns + "enable_avoidance_over_same_direction"); + p.enable_avoidance_over_opposite_direction = + get_parameter(node, ns + "enable_avoidance_over_opposite_direction"); + p.enable_update_path_when_object_is_gone = + get_parameter(node, ns + "enable_update_path_when_object_is_gone"); + p.enable_force_avoidance_for_stopped_vehicle = + get_parameter(node, ns + "enable_force_avoidance_for_stopped_vehicle"); + } + + // target object + { + const auto get_object_param = [&](std::string && ns) { + ObjectParameter param{}; + param.is_target = get_parameter(node, ns + "is_target"); + param.moving_speed_threshold = get_parameter(node, ns + "moving_speed_threshold"); + param.moving_time_threshold = get_parameter(node, ns + "moving_time_threshold"); + param.max_expand_ratio = get_parameter(node, ns + "max_expand_ratio"); + param.envelope_buffer_margin = get_parameter(node, ns + "envelope_buffer_margin"); + param.avoid_margin_lateral = get_parameter(node, ns + "avoid_margin_lateral"); + param.safety_buffer_lateral = get_parameter(node, ns + "safety_buffer_lateral"); + param.safety_buffer_longitudinal = + get_parameter(node, ns + "safety_buffer_longitudinal"); + return param; + }; + + const std::string ns = "avoidance.target_object."; + p.object_parameters.emplace( + ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); + p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); + p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); + p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); + p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); + p.object_parameters.emplace( + ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); + p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); + p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); + + p.lower_distance_for_polygon_expansion = + get_parameter(node, ns + "lower_distance_for_polygon_expansion"); + p.upper_distance_for_polygon_expansion = + get_parameter(node, ns + "upper_distance_for_polygon_expansion"); + } + + // target filtering + { + std::string ns = "avoidance.target_filtering."; + p.threshold_time_force_avoidance_for_stopped_vehicle = + get_parameter(node, ns + "threshold_time_force_avoidance_for_stopped_vehicle"); + p.object_ignore_section_traffic_light_in_front_distance = + get_parameter(node, ns + "object_ignore_section_traffic_light_in_front_distance"); + p.object_ignore_section_crosswalk_in_front_distance = + get_parameter(node, ns + "object_ignore_section_crosswalk_in_front_distance"); + p.object_ignore_section_crosswalk_behind_distance = + get_parameter(node, ns + "object_ignore_section_crosswalk_behind_distance"); + p.object_check_forward_distance = + get_parameter(node, ns + "object_check_forward_distance"); + p.object_check_backward_distance = + get_parameter(node, ns + "object_check_backward_distance"); + p.object_check_goal_distance = get_parameter(node, ns + "object_check_goal_distance"); + p.threshold_distance_object_is_on_center = + get_parameter(node, ns + "threshold_distance_object_is_on_center"); + p.object_check_shiftable_ratio = + get_parameter(node, ns + "object_check_shiftable_ratio"); + p.object_check_min_road_shoulder_width = + get_parameter(node, ns + "object_check_min_road_shoulder_width"); + p.object_last_seen_threshold = get_parameter(node, ns + "object_last_seen_threshold"); + } + + avoidance_parameters_ = std::make_shared(p); } std::shared_ptr AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() { return std::make_shared( - name_, *node_, parameters_, avoidance_parameters_, avoidance_by_lane_change_parameters_, - rtc_interface_ptr_map_); + name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_); } } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp b/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp index 91ae50e196b0a..5c92d7ced6036 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp @@ -24,10 +24,21 @@ namespace behavior_path_planner { SideShiftModuleManager::SideShiftModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - const std::shared_ptr & parameters) -: SceneModuleManagerInterface(node, name, config, {}), parameters_{parameters} + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config) +: SceneModuleManagerInterface(node, name, config, {}) { + SideShiftParameters p{}; + + p.min_distance_to_start_shifting = + node->declare_parameter(name + ".min_distance_to_start_shifting"); + p.time_to_start_shifting = node->declare_parameter(name + ".time_to_start_shifting"); + p.shifting_lateral_jerk = node->declare_parameter(name + ".shifting_lateral_jerk"); + p.min_shifting_distance = node->declare_parameter(name + ".min_shifting_distance"); + p.min_shifting_speed = node->declare_parameter(name + ".min_shifting_speed"); + p.shift_request_time_limit = node->declare_parameter(name + ".shift_request_time_limit"); + p.publish_debug_marker = node->declare_parameter(name + ".publish_debug_marker"); + + parameters_ = std::make_shared(p); } void SideShiftModuleManager::updateModuleParams( 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 3b2917c94c8e1..bba6f2b7b0da3 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 @@ -24,10 +24,67 @@ namespace behavior_path_planner { StartPlannerModuleManager::StartPlannerModuleManager( - rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config, - const std::shared_ptr & parameters) -: SceneModuleManagerInterface(node, name, config, {""}), parameters_{parameters} + rclcpp::Node * node, const std::string & name, const ModuleConfigParameters & config) +: SceneModuleManagerInterface(node, name, config, {""}) { + StartPlannerParameters p; + + std::string ns = "start_planner."; + + p.th_arrived_distance = node->declare_parameter(ns + "th_arrived_distance"); + p.th_stopped_velocity = node->declare_parameter(ns + "th_stopped_velocity"); + p.th_stopped_time = node->declare_parameter(ns + "th_stopped_time"); + p.th_turn_signal_on_lateral_offset = + node->declare_parameter(ns + "th_turn_signal_on_lateral_offset"); + p.intersection_search_length = node->declare_parameter(ns + "intersection_search_length"); + p.length_ratio_for_turn_signal_deactivation_near_intersection = node->declare_parameter( + ns + "length_ratio_for_turn_signal_deactivation_near_intersection"); + p.collision_check_margin = node->declare_parameter(ns + "collision_check_margin"); + p.collision_check_distance_from_end = + node->declare_parameter(ns + "collision_check_distance_from_end"); + // shift pull out + p.enable_shift_pull_out = node->declare_parameter(ns + "enable_shift_pull_out"); + p.minimum_shift_pull_out_distance = + node->declare_parameter(ns + "minimum_shift_pull_out_distance"); + p.lateral_acceleration_sampling_num = + node->declare_parameter(ns + "lateral_acceleration_sampling_num"); + p.lateral_jerk = node->declare_parameter(ns + "lateral_jerk"); + p.maximum_lateral_acc = node->declare_parameter(ns + "maximum_lateral_acc"); + p.minimum_lateral_acc = node->declare_parameter(ns + "minimum_lateral_acc"); + p.deceleration_interval = node->declare_parameter(ns + "deceleration_interval"); + // geometric pull out + p.enable_geometric_pull_out = node->declare_parameter(ns + "enable_geometric_pull_out"); + p.divide_pull_out_path = node->declare_parameter(ns + "divide_pull_out_path"); + p.parallel_parking_parameters.pull_out_velocity = + node->declare_parameter(ns + "geometric_pull_out_velocity"); + p.parallel_parking_parameters.pull_out_path_interval = + node->declare_parameter(ns + "arc_path_interval"); + p.parallel_parking_parameters.pull_out_lane_departure_margin = + node->declare_parameter(ns + "lane_departure_margin"); + p.parallel_parking_parameters.pull_out_max_steer_angle = + node->declare_parameter(ns + "pull_out_max_steer_angle"); // 15deg + // search start pose backward + p.search_priority = node->declare_parameter( + ns + "search_priority"); // "efficient_path" or "short_back_distance" + p.enable_back = node->declare_parameter(ns + "enable_back"); + p.backward_velocity = node->declare_parameter(ns + "backward_velocity"); + p.max_back_distance = node->declare_parameter(ns + "max_back_distance"); + p.backward_search_resolution = node->declare_parameter(ns + "backward_search_resolution"); + p.backward_path_update_duration = + node->declare_parameter(ns + "backward_path_update_duration"); + p.ignore_distance_from_lane_end = + node->declare_parameter(ns + "ignore_distance_from_lane_end"); + + // validation of parameters + if (p.lateral_acceleration_sampling_num < 1) { + RCLCPP_FATAL_STREAM( + logger_, "lateral_acceleration_sampling_num must be positive integer. Given parameter: " + << p.lateral_acceleration_sampling_num << std::endl + << "Terminating the program..."); + exit(EXIT_FAILURE); + } + + parameters_ = std::make_shared(p); } void StartPlannerModuleManager::updateModuleParams( From 6744206515d4db4f92352c494353de5d65b9d3e4 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 30 Jun 2023 18:00:23 +0900 Subject: [PATCH 061/118] fix(behavior_path_planner): copy z in dynamic drivable area expansion (#4120) Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.cpp | 35 +++++++++++++++++-- 1 file changed, 32 insertions(+), 3 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 a27010e4f8d15..819265b70abbe 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 @@ -19,6 +19,7 @@ #include "behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp" #include "behavior_path_planner/utils/drivable_area_expansion/parameters.hpp" #include "behavior_path_planner/utils/drivable_area_expansion/types.hpp" +#include "interpolation/linear_interpolation.hpp" #include @@ -68,9 +69,7 @@ polygon_t createExpandedDrivableAreaPolygon( for (const auto & p : expansion_polygons) { unions.clear(); boost::geometry::union_(expanded_da_poly, p, unions); - if (unions.size() != 1) // union of overlapping polygons should produce a single polygon - continue; - else + if (unions.size() == 1) // union of overlapping polygons should produce a single polygon expanded_da_poly = unions[0]; } return expanded_da_poly; @@ -129,8 +128,36 @@ std::array findLeftRightRanges( return {left_start, left_end, right_start, right_end}; } +void copy_z_over_arc_length( + const std::vector & from, std::vector & to) +{ + if (from.empty() || to.empty()) return; + to.front().z = from.front().z; + if (from.size() < 2 || to.size() < 2) return; + to.back().z = from.back().z; + auto i_from = 1lu; + auto s_from = tier4_autoware_utils::calcDistance2d(from[0], from[1]); + auto s_to = 0.0; + auto s_from_prev = 0.0; + for (auto i_to = 1lu; i_to + 1 < to.size(); ++i_to) { + s_to += tier4_autoware_utils::calcDistance2d(to[i_to - 1], to[i_to]); + for (; s_from < s_to && i_from + 1 < from.size(); ++i_from) { + s_from_prev = s_from; + s_from += tier4_autoware_utils::calcDistance2d(from[i_from], from[i_from + 1]); + } + if (s_from - s_from_prev != 0.0) { + const auto ratio = (s_to - s_from_prev) / (s_from - s_from_prev); + to[i_to].z = interpolation::lerp(from[i_from - 1].z, from[i_from].z, ratio); + } else { + to[i_to].z = to[i_to - 1].z; + } + } +} + void updateDrivableAreaBounds(PathWithLaneId & path, const polygon_t & expanded_drivable_area) { + const auto original_left_bound = path.left_bound; + const auto original_right_bound = path.right_bound; path.left_bound.clear(); path.right_bound.clear(); const auto begin = expanded_drivable_area.outer().begin(); @@ -155,6 +182,8 @@ void updateDrivableAreaBounds(PathWithLaneId & path, const polygon_t & expanded_ for (auto it = right_start; it >= begin; --it) path.right_bound.push_back(convert_point(*it)); for (auto it = end - 1; it >= right_end; --it) path.right_bound.push_back(convert_point(*it)); } + copy_z_over_arc_length(original_left_bound, path.left_bound); + copy_z_over_arc_length(original_right_bound, path.right_bound); } } // namespace drivable_area_expansion From 27c5a106f29702d0e55cff744ca004800b1495e7 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 30 Jun 2023 18:08:16 +0900 Subject: [PATCH 062/118] ci: remove global codeowners (#4131) Signed-off-by: Takagi, Isamu --- .github/workflows/update-codeowners-from-packages.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/.github/workflows/update-codeowners-from-packages.yaml b/.github/workflows/update-codeowners-from-packages.yaml index 7c4132ef0c746..055d2b02a799a 100644 --- a/.github/workflows/update-codeowners-from-packages.yaml +++ b/.github/workflows/update-codeowners-from-packages.yaml @@ -27,7 +27,6 @@ jobs: uses: autowarefoundation/autoware-github-actions/update-codeowners-from-packages@v1 with: token: ${{ steps.generate-token.outputs.token }} - global-codeowners: "@autowarefoundation/autoware-global-codeowners" pr-labels: | bot update-codeowners-from-packages From 1e6449502bca25dcaf6a84f5728766312c28d7c0 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 30 Jun 2023 09:27:23 +0000 Subject: [PATCH 063/118] chore: update CODEOWNERS (#4052) Signed-off-by: GitHub Co-authored-by: isamu-takagi --- .github/CODEOWNERS | 407 +++++++++++++++++++++++---------------------- 1 file changed, 207 insertions(+), 200 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index dcf9c92f50442..98dc5c47506d2 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -1,203 +1,210 @@ ### Copied from .github/CODEOWNERS-manual ### ### Automatically generated from package.xml ### -common/autoware_ad_api_specs/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp @autowarefoundation/autoware-global-codeowners -common/autoware_auto_common/** opensource@apex.ai @autowarefoundation/autoware-global-codeowners -common/autoware_auto_geometry/** satoshi.ota@tier4.jp @autowarefoundation/autoware-global-codeowners -common/autoware_auto_perception_rviz_plugin/** opensource@apex.ai satoshi.tanaka@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp @autowarefoundation/autoware-global-codeowners -common/autoware_auto_tf2/** jit.ray.c@gmail.com @autowarefoundation/autoware-global-codeowners -common/autoware_point_types/** taichi.higashide@tier4.jp @autowarefoundation/autoware-global-codeowners -common/autoware_testing/** adam.dabrowski@robotec.ai @autowarefoundation/autoware-global-codeowners -common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners -common/component_interface_specs/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -common/component_interface_tools/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp @autowarefoundation/autoware-global-codeowners -common/component_interface_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -common/cuda_utils/** daisuke.nishimatsu@tier4.jp manato.hirabayashi@tier4.jp @autowarefoundation/autoware-global-codeowners -common/fake_test_node/** opensource@apex.ai @autowarefoundation/autoware-global-codeowners -common/global_parameter_loader/** kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners -common/goal_distance_calculator/** taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners -common/grid_map_utils/** maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners -common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -common/kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -common/motion_utils/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -common/osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -common/path_distance_calculator/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp @autowarefoundation/autoware-global-codeowners -common/perception_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yusuke.muramatsu@tier4.jp @autowarefoundation/autoware-global-codeowners -common/polar_grid/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -common/qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -common/rtc_manager_rviz_plugin/** taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -common/signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tensorrt_common/** daisuke.nishimatsu@tier4.jp dan.umeda@tier4.jp manato.hirabayashi@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_api_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_automatic_goal_rviz_plugin/** dawid.moszynski@robotec.ai shumpei.wakabayashi@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_autoware_utils/** kenji.miyake@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_calibration_rviz_plugin/** tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_control_rviz_plugin/** taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_debug_rviz_plugin/** takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_debug_tools/** kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_perception_rviz_plugin/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_screen_capture_rviz_plugin/** taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_simulated_clock_rviz_plugin/** maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_traffic_light_rviz_plugin/** satoshi.ota@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -common/time_utils/** christopherj.ho@gmail.com @autowarefoundation/autoware-global-codeowners -common/trtexec_vendor/** daisuke.nishimatsu@tier4.jp yusuke.muramatsu@tier4.jp @autowarefoundation/autoware-global-codeowners -common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp @autowarefoundation/autoware-global-codeowners -control/autonomous_emergency_braking/** takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -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 @autowarefoundation/autoware-global-codeowners -control/external_cmd_selector/** fumiya.watanabe@tier4.jp kenji.miyake@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 @autowarefoundation/autoware-global-codeowners -control/joy_controller/** fumiya.watanabe@tier4.jp kenji.miyake@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 @autowarefoundation/autoware-global-codeowners -control/lane_departure_checker/** kyoichi.sugahara@tier4.jp @autowarefoundation/autoware-global-codeowners -control/mpc_lateral_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -control/obstacle_collision_checker/** fumiya.watanabe@tier4.jp kenji.miyake@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 @autowarefoundation/autoware-global-codeowners -control/operation_mode_transition_manager/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -control/pid_longitudinal_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -control/pure_pursuit/** takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners -control/shift_decider/** takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners -control/trajectory_follower_base/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -control/trajectory_follower_node/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -control/vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -evaluator/diagnostic_converter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners -evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai @autowarefoundation/autoware-global-codeowners -evaluator/localization_evaluator/** dominik.jargot@robotec.ai @autowarefoundation/autoware-global-codeowners -evaluator/planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/map4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryohei.sasaki@map.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_map_launch/** koji.minoda@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_perception_launch/** shunsuke.miura@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_planning_launch/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_system_launch/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners -launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -localization/ekf_localizer/** koji.minoda@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -localization/gyro_odometer/** yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -localization/initial_pose_button_panel/** yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -localization/localization_error_monitor/** yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -localization/ndt_scan_matcher/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -localization/pose2twist/** yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -localization/pose_initializer/** isamu.takagi@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -localization/stop_filter/** koji.minoda@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -localization/twist2accel/** koji.minoda@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -map/map_height_fitter/** isamu.takagi@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -map/map_loader/** koji.minoda@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp @autowarefoundation/autoware-global-codeowners -map/map_tf_generator/** azumi.suzuki@tier4.jp @autowarefoundation/autoware-global-codeowners -map/util/lanelet2_map_preprocessor/** ryohsuke.mitsudome@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/bytetrack/** manato.hirabayashi@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/compare_map_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/crosswalk_traffic_light_estimator/** satoshi.ota@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/detected_object_feature_remover/** tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/detected_object_validation/** shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/detection_by_tracker/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/elevation_map_loader/** kosuke.takeuchi@tier4.jp taichi.higashide@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/euclidean_cluster/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/front_vehicle_velocity_estimator/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/ground_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/heatmap_visualizer/** kotaro.uetake@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/image_projection_based_fusion/** yukihiro.saito@tier4.jp yusuke.muramatsu@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/lidar_apollo_instance_segmentation/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/lidar_apollo_segmentation_tvm/** ambroise.vincent@arm.com xinyu.wang@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/lidar_apollo_segmentation_tvm_nodes/** ambroise.vincent@arm.com xinyu.wang@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/lidar_centerpoint/** kenzo.lobos@tier4.jp yusuke.muramatsu@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/lidar_centerpoint_tvm/** carl.liu@autocore.ai xinyu.wang@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/map_based_prediction/** shunsuke.miura@tier4.jp tomoya.kimura@tier4.jp yoshi.ri@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/multi_object_tracker/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/object_merger/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/object_range_splitter/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/occupancy_grid_map_outlier_filter/** abrahammonrroy@yahoo.com yoshi.ri@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/probabilistic_occupancy_grid_map/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/radar_fusion_to_detected_object/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/radar_tracks_msgs_converter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/shape_estimation/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/tensorrt_yolo/** daisuke.nishimatsu@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/tensorrt_yolox/** daisuke.nishimatsu@tier4.jp dan.umeda@tier4.jp manato.hirabayashi@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/traffic_light_arbiter/** kenzo.lobos@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/traffic_light_classifier/** shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/traffic_light_map_based_detector/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/traffic_light_selector/** isamu.takagi@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp @autowarefoundation/autoware-global-codeowners -perception/traffic_light_visualization/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -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 @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_crosswalk_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_detection_area_module/** kyoichi.sugahara@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_intersection_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_planner_common/** isamu.takagi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_run_out_module/** makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_stop_line_module/** shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_traffic_light_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/external_velocity_limit_selector/** satoshi.ota@tier4.jp shinnosuke.hirakawa@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/mission_planner/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/motion_velocity_smoother/** fumiya.watanabe@tier4.jp makoto.kurihara@tier4.jp takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/obstacle_avoidance_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/obstacle_cruise_planner/** takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/obstacle_stop_planner/** berkay@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/planning_debug_tools/** taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/planning_test_utils/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/planning_validator/** takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/route_handler/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/rtc_auto_mode_manager/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/rtc_interface/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/rtc_replayer/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/sampling_based_planner/bezier_sampler/** maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/sampling_based_planner/frenet_planner/** maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/sampling_based_planner/path_sampler/** maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/scenario_selector/** fumiya.watanabe@tier4.jp kenji.miyake@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 @autowarefoundation/autoware-global-codeowners -planning/static_centerline_optimizer/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp @autowarefoundation/autoware-global-codeowners -planning/surround_obstacle_checker/** satoshi.ota@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/geo_pos_conv/** yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/gnss_poser/** yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/image_diagnostics/** dai.nguyen@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/image_transport_decompressor/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/imu_corrector/** yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/livox/livox_tag_filter/** kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/tier4_pcl_extensions/** ryu.yamamoto@tier4.jp @autowarefoundation/autoware-global-codeowners -sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp @autowarefoundation/autoware-global-codeowners -simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -simulator/fault_injection/** keisuke.shima@tier4.jp @autowarefoundation/autoware-global-codeowners -simulator/simple_planning_simulator/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -system/autoware_auto_msgs_adapter/** isamu.takagi@tier4.jp mfc@leodrive.ai @autowarefoundation/autoware-global-codeowners -system/bluetooth_monitor/** fumihito.ito@tier4.jp @autowarefoundation/autoware-global-codeowners -system/component_state_monitor/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp @autowarefoundation/autoware-global-codeowners -system/default_ad_api/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -system/default_ad_api_helpers/ad_api_adaptors/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners -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 @autowarefoundation/autoware-global-codeowners -system/dummy_diag_publisher/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners -system/dummy_infrastructure/** kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners -system/emergency_handler/** kenji.miyake@tier4.jp makoto.kurihara@tier4.jp @autowarefoundation/autoware-global-codeowners -system/mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp @autowarefoundation/autoware-global-codeowners -system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp @autowarefoundation/autoware-global-codeowners -system/system_error_monitor/** fumihito.ito@tier4.jp kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners -system/system_monitor/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp @autowarefoundation/autoware-global-codeowners -system/topic_state_monitor/** kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners -system/velodyne_monitor/** fumihito.ito@tier4.jp @autowarefoundation/autoware-global-codeowners -tools/simulator_test/simulator_compatibility_test/** shpark@morai.ai @autowarefoundation/autoware-global-codeowners -vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp @autowarefoundation/autoware-global-codeowners -vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners -vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners -vehicle/steer_offset_estimator/** taiki.tanaka@tier4.jp @autowarefoundation/autoware-global-codeowners -vehicle/vehicle_info_util/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp yamato.ando@tier4.jp @autowarefoundation/autoware-global-codeowners +common/autoware_ad_api_specs/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp +common/autoware_auto_common/** opensource@apex.ai +common/autoware_auto_geometry/** satoshi.ota@tier4.jp +common/autoware_auto_perception_rviz_plugin/** opensource@apex.ai satoshi.tanaka@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp +common/autoware_auto_tf2/** jit.ray.c@gmail.com +common/autoware_point_types/** taichi.higashide@tier4.jp +common/autoware_testing/** adam.dabrowski@robotec.ai +common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp +common/component_interface_specs/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp +common/component_interface_tools/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp +common/component_interface_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp +common/cuda_utils/** daisuke.nishimatsu@tier4.jp manato.hirabayashi@tier4.jp +common/fake_test_node/** opensource@apex.ai +common/global_parameter_loader/** kenji.miyake@tier4.jp +common/goal_distance_calculator/** taiki.tanaka@tier4.jp +common/grid_map_utils/** maxime.clement@tier4.jp +common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +common/kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.saito@tier4.jp +common/motion_utils/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp +common/osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp +common/path_distance_calculator/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp +common/perception_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yusuke.muramatsu@tier4.jp +common/polar_grid/** yukihiro.saito@tier4.jp +common/qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp +common/rtc_manager_rviz_plugin/** taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp +common/signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +common/tensorrt_common/** daisuke.nishimatsu@tier4.jp dan.umeda@tier4.jp manato.hirabayashi@tier4.jp +common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp +common/tier4_api_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp +common/tier4_automatic_goal_rviz_plugin/** dawid.moszynski@robotec.ai shumpei.wakabayashi@tier4.jp +common/tier4_autoware_utils/** kenji.miyake@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +common/tier4_calibration_rviz_plugin/** tomoya.kimura@tier4.jp +common/tier4_control_rviz_plugin/** taiki.tanaka@tier4.jp +common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp +common/tier4_debug_rviz_plugin/** takayuki.murooka@tier4.jp +common/tier4_debug_tools/** kenji.miyake@tier4.jp +common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp takamasa.horibe@tier4.jp +common/tier4_perception_rviz_plugin/** yukihiro.saito@tier4.jp +common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp yutaka.shimizu@tier4.jp +common/tier4_screen_capture_rviz_plugin/** taiki.tanaka@tier4.jp +common/tier4_simulated_clock_rviz_plugin/** maxime.clement@tier4.jp +common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp +common/tier4_traffic_light_rviz_plugin/** satoshi.ota@tier4.jp +common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp +common/time_utils/** christopherj.ho@gmail.com +common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@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/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/external_cmd_selector/** fumiya.watanabe@tier4.jp kenji.miyake@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/joy_controller/** fumiya.watanabe@tier4.jp kenji.miyake@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/lane_departure_checker/** kyoichi.sugahara@tier4.jp +control/mpc_lateral_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +control/obstacle_collision_checker/** fumiya.watanabe@tier4.jp kenji.miyake@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/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 +control/trajectory_follower_node/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +control/vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp +evaluator/diagnostic_converter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp +evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai +evaluator/localization_evaluator/** dominik.jargot@robotec.ai +evaluator/planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp +launch/map4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryohei.sasaki@map.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp +launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp +launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +launch/tier4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp +launch/tier4_map_launch/** koji.minoda@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp +launch/tier4_perception_launch/** shunsuke.miura@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +launch/tier4_planning_launch/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp +launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp +launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +launch/tier4_system_launch/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp kenji.miyake@tier4.jp +launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp +localization/ekf_localizer/** koji.minoda@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp +localization/gyro_odometer/** yamato.ando@tier4.jp +localization/initial_pose_button_panel/** yamato.ando@tier4.jp +localization/localization_error_monitor/** yamato.ando@tier4.jp +localization/ndt_scan_matcher/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp yamato.ando@tier4.jp +localization/pose2twist/** yamato.ando@tier4.jp +localization/pose_initializer/** isamu.takagi@tier4.jp yamato.ando@tier4.jp +localization/stop_filter/** koji.minoda@tier4.jp yamato.ando@tier4.jp +localization/twist2accel/** koji.minoda@tier4.jp yamato.ando@tier4.jp +localization/yabloc/yabloc_common/** kento.yabuuchi.2@tier4.jp +localization/yabloc/yabloc_image_processing/** kento.yabuuchi.2@tier4.jp +localization/yabloc/yabloc_particle_filter/** kento.yabuuchi.2@tier4.jp +localization/yabloc/yabloc_pose_initializer/** kento.yabuuchi.2@tier4.jp +map/map_height_fitter/** isamu.takagi@tier4.jp yamato.ando@tier4.jp +map/map_loader/** koji.minoda@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp +map/map_tf_generator/** azumi.suzuki@tier4.jp +map/util/lanelet2_map_preprocessor/** ryohsuke.mitsudome@tier4.jp +perception/bytetrack/** manato.hirabayashi@tier4.jp +perception/compare_map_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp yukihiro.saito@tier4.jp +perception/crosswalk_traffic_light_estimator/** satoshi.ota@tier4.jp +perception/detected_object_feature_remover/** tomoya.kimura@tier4.jp +perception/detected_object_validation/** shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp +perception/detection_by_tracker/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +perception/elevation_map_loader/** kosuke.takeuchi@tier4.jp taichi.higashide@tier4.jp +perception/euclidean_cluster/** yukihiro.saito@tier4.jp +perception/front_vehicle_velocity_estimator/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp +perception/ground_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp +perception/heatmap_visualizer/** kotaro.uetake@tier4.jp +perception/image_projection_based_fusion/** yukihiro.saito@tier4.jp yusuke.muramatsu@tier4.jp +perception/lidar_apollo_instance_segmentation/** yukihiro.saito@tier4.jp +perception/lidar_apollo_segmentation_tvm/** ambroise.vincent@arm.com xinyu.wang@tier4.jp +perception/lidar_apollo_segmentation_tvm_nodes/** ambroise.vincent@arm.com xinyu.wang@tier4.jp +perception/lidar_centerpoint/** kenzo.lobos@tier4.jp yusuke.muramatsu@tier4.jp +perception/lidar_centerpoint_tvm/** carl.liu@autocore.ai xinyu.wang@tier4.jp +perception/map_based_prediction/** shunsuke.miura@tier4.jp tomoya.kimura@tier4.jp yoshi.ri@tier4.jp yutaka.shimizu@tier4.jp +perception/multi_object_tracker/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +perception/object_merger/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +perception/object_range_splitter/** yukihiro.saito@tier4.jp +perception/occupancy_grid_map_outlier_filter/** abrahammonrroy@yahoo.com yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +perception/probabilistic_occupancy_grid_map/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +perception/radar_fusion_to_detected_object/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp +perception/radar_tracks_msgs_converter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp +perception/shape_estimation/** yoshi.ri@tier4.jp yukihiro.saito@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/traffic_light_arbiter/** kenzo.lobos@tier4.jp +perception/traffic_light_classifier/** shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp +perception/traffic_light_fine_detector/** mingyu.li@tier4.jp +perception/traffic_light_map_based_detector/** yukihiro.saito@tier4.jp +perception/traffic_light_multi_camera_fusion/** mingyu.li@tier4.jp +perception/traffic_light_selector/** isamu.takagi@tier4.jp +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 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/** 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 +planning/behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp +planning/behavior_velocity_planner_common/** isamu.takagi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_run_out_module/** makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_stop_line_module/** shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp +planning/behavior_velocity_traffic_light_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +planning/external_velocity_limit_selector/** satoshi.ota@tier4.jp shinnosuke.hirakawa@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +planning/freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +planning/mission_planner/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +planning/motion_velocity_smoother/** fumiya.watanabe@tier4.jp makoto.kurihara@tier4.jp takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp +planning/obstacle_avoidance_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +planning/obstacle_cruise_planner/** takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +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/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/** takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp +planning/route_handler/** fumiya.watanabe@tier4.jp kosuke.takeuchi@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 +planning/sampling_based_planner/frenet_planner/** maxime.clement@tier4.jp +planning/sampling_based_planner/path_sampler/** maxime.clement@tier4.jp +planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp +planning/scenario_selector/** fumiya.watanabe@tier4.jp kenji.miyake@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 +planning/static_centerline_optimizer/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp +planning/surround_obstacle_checker/** satoshi.ota@tier4.jp +sensing/geo_pos_conv/** yamato.ando@tier4.jp +sensing/gnss_poser/** yamato.ando@tier4.jp +sensing/image_diagnostics/** dai.nguyen@tier4.jp +sensing/image_transport_decompressor/** yukihiro.saito@tier4.jp +sensing/imu_corrector/** yamato.ando@tier4.jp +sensing/livox/livox_tag_filter/** kenji.miyake@tier4.jp +sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp +sensing/radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp +sensing/radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp +sensing/radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp +sensing/tier4_pcl_extensions/** ryu.yamamoto@tier4.jp +sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp +simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp +simulator/fault_injection/** keisuke.shima@tier4.jp +simulator/simple_planning_simulator/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp +system/autoware_auto_msgs_adapter/** isamu.takagi@tier4.jp mfc@leodrive.ai +system/bluetooth_monitor/** fumihito.ito@tier4.jp +system/component_state_monitor/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp +system/default_ad_api/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/default_ad_api_helpers/ad_api_adaptors/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +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 kenji.miyake@tier4.jp +system/dummy_infrastructure/** kenji.miyake@tier4.jp +system/emergency_handler/** kenji.miyake@tier4.jp makoto.kurihara@tier4.jp +system/mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp +system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp +system/system_error_monitor/** fumihito.ito@tier4.jp kenji.miyake@tier4.jp +system/system_monitor/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp +system/topic_state_monitor/** kenji.miyake@tier4.jp +system/velodyne_monitor/** fumihito.ito@tier4.jp +tools/simulator_test/simulator_compatibility_test/** shpark@morai.ai +vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp +vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp +vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp +vehicle/steer_offset_estimator/** taiki.tanaka@tier4.jp +vehicle/vehicle_info_util/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp yamato.ando@tier4.jp From e88ccad6e05e51471bf365c99c381f3a9c913c28 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 30 Jun 2023 18:40:35 +0900 Subject: [PATCH 064/118] feat(traffic_light_selector): remove traffic light selector (#4130) Signed-off-by: Takagi, Isamu --- .../traffic_light_selector/CMakeLists.txt | 17 --- perception/traffic_light_selector/README.md | 43 ------ .../launch/traffic_light_selector.launch.xml | 14 -- perception/traffic_light_selector/package.xml | 27 ---- .../src/traffic_light_converter.cpp | 117 ---------------- .../src/traffic_light_converter.hpp | 36 ----- .../src/traffic_light_selector.cpp | 129 ------------------ .../src/traffic_light_selector.hpp | 47 ------- 8 files changed, 430 deletions(-) delete mode 100644 perception/traffic_light_selector/CMakeLists.txt delete mode 100644 perception/traffic_light_selector/README.md delete mode 100644 perception/traffic_light_selector/launch/traffic_light_selector.launch.xml delete mode 100644 perception/traffic_light_selector/package.xml delete mode 100644 perception/traffic_light_selector/src/traffic_light_converter.cpp delete mode 100644 perception/traffic_light_selector/src/traffic_light_converter.hpp delete mode 100644 perception/traffic_light_selector/src/traffic_light_selector.cpp delete mode 100644 perception/traffic_light_selector/src/traffic_light_selector.hpp diff --git a/perception/traffic_light_selector/CMakeLists.txt b/perception/traffic_light_selector/CMakeLists.txt deleted file mode 100644 index 9a8555690beed..0000000000000 --- a/perception/traffic_light_selector/CMakeLists.txt +++ /dev/null @@ -1,17 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(traffic_light_selector) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/traffic_light_converter.cpp - src/traffic_light_selector.cpp -) - -rclcpp_components_register_nodes(${PROJECT_NAME} - TrafficLightConverter - TrafficLightSelector -) - -ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/perception/traffic_light_selector/README.md b/perception/traffic_light_selector/README.md deleted file mode 100644 index d20d5dc790e3a..0000000000000 --- a/perception/traffic_light_selector/README.md +++ /dev/null @@ -1,43 +0,0 @@ -# traffic_light_selector - -## Purpose - -This package receives multiple traffic light/signal states and outputs a single traffic signal state for use by the planning component. - -## TrafficLightSelector - -A node that merges traffic light/signal state from image recognition and V2X to provide a planning component. -It's currently a provisional implementation. - -### Inputs / Outputs - -#### Input - -| Name | Type | Description | -| -------------------- | ---------------------------------------------- | ------------------------------------------------- | -| ~/sub/vector_map | autoware_auto_mapping_msgs/msg/HADMapBin | The vector map to get traffic light id relations. | -| ~/sub/traffic_lights | autoware_perception_msgs/msg/TrafficLightArray | The traffic light state from image recognition. | - -#### Output - -| Name | Type | Description | -| --------------------- | ----------------------------------------------- | -------------------------------- | -| ~/pub/traffic_signals | autoware_perception_msgs/msg/TrafficSignalArray | The merged traffic signal state. | - -## TrafficLightConverter - -A temporary node that converts old message type to new message type. - -### Inputs / Outputs - -#### Input - -| Name | Type | Description | -| -------------------- | -------------------------------------------- | ------------------------------ | -| ~/sub/traffic_lights | tier4_perception_msgs/msg/TrafficSignalArray | The state in old message type. | - -#### Output - -| Name | Type | Description | -| -------------------- | ---------------------------------------------- | ------------------------------ | -| ~/pub/traffic_lights | autoware_perception_msgs/msg/TrafficLightArray | The state in new message type. | diff --git a/perception/traffic_light_selector/launch/traffic_light_selector.launch.xml b/perception/traffic_light_selector/launch/traffic_light_selector.launch.xml deleted file mode 100644 index 44eec5284c03c..0000000000000 --- a/perception/traffic_light_selector/launch/traffic_light_selector.launch.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/perception/traffic_light_selector/package.xml b/perception/traffic_light_selector/package.xml deleted file mode 100644 index fb696dd54dddd..0000000000000 --- a/perception/traffic_light_selector/package.xml +++ /dev/null @@ -1,27 +0,0 @@ - - - - traffic_light_selector - 0.1.0 - The traffic_light_selector package - Takagi, Isamu - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - autoware_auto_mapping_msgs - autoware_perception_msgs - lanelet2_core - lanelet2_extension - rclcpp - rclcpp_components - tier4_perception_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/perception/traffic_light_selector/src/traffic_light_converter.cpp b/perception/traffic_light_selector/src/traffic_light_converter.cpp deleted file mode 100644 index afc8dab72e788..0000000000000 --- a/perception/traffic_light_selector/src/traffic_light_converter.cpp +++ /dev/null @@ -1,117 +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 "traffic_light_converter.hpp" - -#include -#include - -namespace converter -{ - -using OldList = tier4_perception_msgs::msg::TrafficSignalArray; -using OldData = tier4_perception_msgs::msg::TrafficSignal; -using OldElem = tier4_perception_msgs::msg::TrafficLightElement; -using NewList = autoware_perception_msgs::msg::TrafficLightArray; -using NewData = autoware_perception_msgs::msg::TrafficLight; -using NewElem = autoware_perception_msgs::msg::TrafficLightElement; - -NewList convert(const OldList & input); -NewData convert(const OldData & input); -NewElem convert(const OldElem & input); - -template -std::vector convert_vector(const L & input) -{ - std::vector output; - output.reserve(input.size()); - for (const auto & value : input) { - output.push_back(convert(value)); - } - return output; -} - -NewList convert(const OldList & input) -{ - NewList output; - output.stamp = input.header.stamp; - output.lights = convert_vector(input.signals); - return output; -} - -NewData convert(const OldData & input) -{ - NewData output; - output.traffic_light_id = input.traffic_light_id; - output.elements = convert_vector(input.elements); - return output; -} - -template -V at_or(const std::unordered_map & map, const K & key, const V & value) -{ - return map.count(key) ? map.at(key) : value; -} - -NewElem convert(const OldElem & input) -{ - // clang-format off - static const std::unordered_map color_map({ - {OldElem::RED, NewElem::RED}, - {OldElem::AMBER, NewElem::AMBER}, - {OldElem::GREEN, NewElem::GREEN}, - {OldElem::WHITE, NewElem::WHITE} - }); - static const std::unordered_map shape_map({ - {OldElem::CIRCLE, NewElem::CIRCLE}, - {OldElem::LEFT_ARROW, NewElem::LEFT_ARROW}, - {OldElem::RIGHT_ARROW, NewElem::RIGHT_ARROW}, - {OldElem::UP_ARROW, NewElem::UP_ARROW}, - {OldElem::DOWN_ARROW, NewElem::DOWN_ARROW}, - {OldElem::DOWN_LEFT_ARROW, NewElem::DOWN_LEFT_ARROW}, - {OldElem::DOWN_RIGHT_ARROW, NewElem::DOWN_RIGHT_ARROW}, - {OldElem::CROSS, NewElem::CROSS} - }); - static const std::unordered_map status_map({ - {OldElem::SOLID_OFF, NewElem::SOLID_OFF}, - {OldElem::SOLID_ON, NewElem::SOLID_ON}, - {OldElem::FLASHING, NewElem::FLASHING} - }); - // clang-format on - - NewElem output; - output.color = at_or(color_map, input.color, NewElem::UNKNOWN); - output.shape = at_or(shape_map, input.shape, NewElem::UNKNOWN); - output.status = at_or(status_map, input.status, NewElem::UNKNOWN); - output.confidence = input.confidence; - return output; -} - -} // namespace converter - -TrafficLightConverter::TrafficLightConverter(const rclcpp::NodeOptions & options) -: Node("traffic_light_converter", options) -{ - const auto callback = std::bind(&TrafficLightConverter::on_msg, this, std::placeholders::_1); - sub_ = create_subscription("~/sub/traffic_lights", rclcpp::QoS(1), callback); - pub_ = create_publisher("~/pub/traffic_lights", rclcpp::QoS(1)); -} - -void TrafficLightConverter::on_msg(const OldMessage::ConstSharedPtr msg) -{ - pub_->publish(converter::convert(*msg)); -} - -#include -RCLCPP_COMPONENTS_REGISTER_NODE(TrafficLightConverter) diff --git a/perception/traffic_light_selector/src/traffic_light_converter.hpp b/perception/traffic_light_selector/src/traffic_light_converter.hpp deleted file mode 100644 index 8c6c6545d9dc2..0000000000000 --- a/perception/traffic_light_selector/src/traffic_light_converter.hpp +++ /dev/null @@ -1,36 +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 TRAFFIC_LIGHT_CONVERTER_HPP_ -#define TRAFFIC_LIGHT_CONVERTER_HPP_ - -#include - -#include -#include - -class TrafficLightConverter : public rclcpp::Node -{ -public: - explicit TrafficLightConverter(const rclcpp::NodeOptions & options); - -private: - using OldMessage = tier4_perception_msgs::msg::TrafficSignalArray; - using NewMessage = autoware_perception_msgs::msg::TrafficLightArray; - rclcpp::Subscription::SharedPtr sub_; - rclcpp::Publisher::SharedPtr pub_; - void on_msg(const OldMessage::ConstSharedPtr msg); -}; - -#endif // TRAFFIC_LIGHT_CONVERTER_HPP_ diff --git a/perception/traffic_light_selector/src/traffic_light_selector.cpp b/perception/traffic_light_selector/src/traffic_light_selector.cpp deleted file mode 100644 index 599bcc0f389f1..0000000000000 --- a/perception/traffic_light_selector/src/traffic_light_selector.cpp +++ /dev/null @@ -1,129 +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 "traffic_light_selector.hpp" - -#include - -#include - -#include -#include -#include -#include - -namespace lanelet -{ - -using TrafficLightConstPtr = std::shared_ptr; - -std::vector filter_traffic_signals(const LaneletMapConstPtr map) -{ - std::vector signals; - for (const auto & element : map->regulatoryElementLayer) { - const auto signal = std::dynamic_pointer_cast(element); - if (signal) { - signals.push_back(signal); - } - } - return signals; -} - -} // namespace lanelet - -TrafficLightSelector::TrafficLightSelector(const rclcpp::NodeOptions & options) -: Node("traffic_light_selector", options) -{ - sub_map_ = create_subscription( - "~/sub/vector_map", rclcpp::QoS(1).transient_local(), - std::bind(&TrafficLightSelector::on_map, this, std::placeholders::_1)); - - sub_tlr_ = create_subscription( - "~/sub/traffic_lights", rclcpp::QoS(1), - std::bind(&TrafficLightSelector::on_msg, this, std::placeholders::_1)); - - pub_ = create_publisher("~/pub/traffic_signals", rclcpp::QoS(1)); -} - -void TrafficLightSelector::on_map(const LaneletMapBin::ConstSharedPtr msg) -{ - const auto map = std::make_shared(); - lanelet::utils::conversion::fromBinMsg(*msg, map); - - const auto signals = lanelet::filter_traffic_signals(map); - mapping_.clear(); - for (const auto & signal : signals) { - for (const auto & light : signal->trafficLights()) { - mapping_[light.id()] = signal->id(); - } - } -} - -void TrafficLightSelector::on_msg(const TrafficLightArray::ConstSharedPtr msg) -{ - using TrafficSignal = autoware_perception_msgs::msg::TrafficSignal; - using Element = autoware_perception_msgs::msg::TrafficLightElement; - std::unordered_map> intersections; - - // Use the most confident traffic light element in the same state. - const auto get_highest_confidence_elements = [](const std::vector & elements) { - using Key = std::tuple; - std::map highest_; - - for (const auto & element : elements) { - const auto key = std::make_tuple(element.color, element.shape, element.status); - auto [iter, success] = highest_.try_emplace(key, element); - if (!success && iter->second.confidence < element.confidence) { - iter->second = element; - } - } - - std::vector result; - result.reserve(highest_.size()); - for (const auto & [k, v] : highest_) { - result.push_back(v); - } - return result; - }; - - // Wait for vector map to create id mapping. - if (mapping_.empty()) { - return; - } - - // Merge traffic lights in the same group. - for (const auto & light : msg->lights) { - const auto id = light.traffic_light_id; - if (!mapping_.count(id)) { - continue; - } - auto & elements = intersections[mapping_[id]]; - for (const auto & element : light.elements) { - elements.push_back(element); - } - } - - TrafficSignalArray array; - array.stamp = msg->stamp; - for (const auto & [id, elements] : intersections) { - TrafficSignal signal; - signal.traffic_signal_id = id; - signal.elements = get_highest_confidence_elements(elements); - array.signals.push_back(signal); - } - pub_->publish(array); -} - -#include -RCLCPP_COMPONENTS_REGISTER_NODE(TrafficLightSelector) diff --git a/perception/traffic_light_selector/src/traffic_light_selector.hpp b/perception/traffic_light_selector/src/traffic_light_selector.hpp deleted file mode 100644 index b21efaa2ec2e3..0000000000000 --- a/perception/traffic_light_selector/src/traffic_light_selector.hpp +++ /dev/null @@ -1,47 +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 TRAFFIC_LIGHT_SELECTOR_HPP_ -#define TRAFFIC_LIGHT_SELECTOR_HPP_ - -#include - -#include -#include -#include - -#include - -#include - -class TrafficLightSelector : public rclcpp::Node -{ -public: - explicit TrafficLightSelector(const rclcpp::NodeOptions & options); - -private: - using LaneletMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; - using TrafficLightArray = autoware_perception_msgs::msg::TrafficLightArray; - using TrafficSignalArray = autoware_perception_msgs::msg::TrafficSignalArray; - rclcpp::Subscription::SharedPtr sub_map_; - rclcpp::Subscription::SharedPtr sub_tlr_; - rclcpp::Publisher::SharedPtr pub_; - - void on_map(const LaneletMapBin::ConstSharedPtr msg); - void on_msg(const TrafficLightArray::ConstSharedPtr msg); - - std::unordered_map mapping_; -}; - -#endif // TRAFFIC_LIGHT_SELECTOR_HPP_ From da9c9c58a73cef13295f1744282f5ca32ec5b906 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Fri, 30 Jun 2023 13:23:39 +0200 Subject: [PATCH 065/118] fix(yabloc_pose_initializer): disable downloading artifacts by default (#4110) Signed-off-by: Esteve Fernandez Co-authored-by: Esteve Fernandez --- .../yabloc_pose_initializer/download.cmake | 25 +++++++++++-------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/localization/yabloc/yabloc_pose_initializer/download.cmake b/localization/yabloc/yabloc_pose_initializer/download.cmake index a17910156b574..6ce997b3978d5 100644 --- a/localization/yabloc/yabloc_pose_initializer/download.cmake +++ b/localization/yabloc/yabloc_pose_initializer/download.cmake @@ -12,12 +12,14 @@ # See the License for the specific language governing permissions and # limitations under the License. +set(DOWNLOAD_ARTIFACTS OFF CACHE BOOL "enable artifacts download") + set(DATA_URL "https://s3.ap-northeast-2.wasabisys.com/pinto-model-zoo/136_road-segmentation-adas-0001/resources.tar.gz") set(DATA_PATH "${CMAKE_CURRENT_SOURCE_DIR}/data") set(FILE_HASH 146ed8af689a30b898dc5369870c40fb) set(FILE_NAME "resources.tar.gz") -function(download) +function(download_and_extract) message(STATUS "Checking and downloading ${FILE_NAME}") set(FILE_PATH ${DATA_PATH}/${FILE_NAME}) set(STATUS_CODE 0) @@ -38,11 +40,17 @@ function(download) list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) endif() else() - message(STATUS "not found ${FILE_NAME}") - message(STATUS "File doesn't exists. Downloading now ...") - file(DOWNLOAD ${DATA_URL} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 3600) - list(GET DOWNLOAD_STATUS 0 STATUS_CODE) - list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) + if(DOWNLOAD_ARTIFACTS) + message(STATUS "not found ${FILE_NAME}") + message(STATUS "File doesn't exists. Downloading now ...") + file(DOWNLOAD ${DATA_URL} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 3600) + list(GET DOWNLOAD_STATUS 0 STATUS_CODE) + list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) + else() + message(WARNING "Skipped download for ${FILE_NAME} (enable by setting DOWNLOAD_ARTIFACTS)") + file(MAKE_DIRECTORY "${DATA_PATH}") + return() + endif() endif() if(${STATUS_CODE} EQUAL 0) @@ -50,13 +58,10 @@ function(download) else() message(FATAL_ERROR "Error occurred during download: ${ERROR_MESSAGE}") endif() -endfunction() -function(extract) execute_process(COMMAND ${CMAKE_COMMAND} -E tar xzf "${DATA_PATH}/${FILE_NAME}" WORKING_DIRECTORY "${DATA_PATH}") endfunction() -download() -extract() +download_and_extract() From 879a837e7524762d0c4fe700b9a0138e2a18d4bd Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 30 Jun 2023 21:14:17 +0900 Subject: [PATCH 066/118] fix(lane_change): fix visualization when path is invalid (#4132) Signed-off-by: Zulfaqar Azmi --- .../src/scene_module/lane_change/interface.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 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 721c7fa6fd390..2c1ba45c3ef84 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 @@ -232,6 +232,7 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() module_type_->setPreviousModulePaths( getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path); module_type_->updateLaneChangeStatus(); + setObjectDebugVisualization(); // change turn signal when the vehicle reaches at the end of the path for waiting lane change out.turn_signal_info = getCurrentTurnSignalInfo(*out.path, out.turn_signal_info); @@ -249,8 +250,6 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change); is_abort_path_approved_ = false; - setObjectDebugVisualization(); - return out; } From a9346851684d6c9884398fa86a533c7106c5fd53 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Sat, 1 Jul 2023 19:27:36 +0900 Subject: [PATCH 067/118] docs(planning_validator): add unit (#4126) Signed-off-by: Takamasa Horibe --- planning/planning_validator/README.md | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/planning/planning_validator/README.md b/planning/planning_validator/README.md index 08ddee246317f..da1e572bb383a 100644 --- a/planning/planning_validator/README.md +++ b/planning/planning_validator/README.md @@ -63,15 +63,15 @@ The following parameters can be set for the `planning_validator`: The input trajectory is detected as invalid if the index exceeds the following thresholds. -| Name | Type | Description | Default value | -| :-------------------------------- | :----- | :------------------------------------------------------------------------------------------------------------ | :------------ | -| `thresholds.interval` | double | invalid threshold of the distance of two neighboring trajectory points | 100.0 | -| `thresholds.relative_angle` | double | invalid threshold of the relative angle of two neighboring trajectory points | 2.0 | -| `thresholds.curvature` | double | invalid threshold of the curvature in each trajectory point | 1.0 | -| `thresholds.lateral_acc` | double | invalid threshold of the lateral acceleration in each trajectory point | 9.8 | -| `thresholds.longitudinal_max_acc` | double | invalid threshold of the maximum longitudinal acceleration in each trajectory point | 9.8 | -| `thresholds.longitudinal_min_acc` | double | invalid threshold of the minimum longitudinal deceleration in each trajectory point | -9.8 | -| `thresholds.steering` | double | invalid threshold of the steering angle in each trajectory point | 1.414 | -| `thresholds.steering_rate` | double | invalid threshold of the steering angle rate in each trajectory point | 10.0 | -| `thresholds.velocity_deviation` | double | invalid threshold of the velocity deviation between the ego velocity and the trajectory point closest to ego. | 100.0 | -| `thresholds.distance_deviation` | double | invalid threshold of the distance deviation between the ego position and the trajectory point closest to ego. | 100.0 | +| Name | Type | Description | Default value | +| :-------------------------------- | :----- | :----------------------------------------------------------------------------------------------------------------- | :------------ | +| `thresholds.interval` | double | invalid threshold of the distance of two neighboring trajectory points [m] | 100.0 | +| `thresholds.relative_angle` | double | invalid threshold of the relative angle of two neighboring trajectory points [rad] | 2.0 | +| `thresholds.curvature` | double | invalid threshold of the curvature in each trajectory point [1/m] | 1.0 | +| `thresholds.lateral_acc` | double | invalid threshold of the lateral acceleration in each trajectory point [m/ss] | 9.8 | +| `thresholds.longitudinal_max_acc` | double | invalid threshold of the maximum longitudinal acceleration in each trajectory point [m/ss] | 9.8 | +| `thresholds.longitudinal_min_acc` | double | invalid threshold of the minimum longitudinal deceleration in each trajectory point [m/ss] | -9.8 | +| `thresholds.steering` | double | invalid threshold of the steering angle in each trajectory point [rad] | 1.414 | +| `thresholds.steering_rate` | double | invalid threshold of the steering angle rate in each trajectory point [rad/s] | 10.0 | +| `thresholds.velocity_deviation` | double | invalid threshold of the velocity deviation between the ego velocity and the trajectory point closest to ego [m/s] | 100.0 | +| `thresholds.distance_deviation` | double | invalid threshold of the distance deviation between the ego position and the trajectory point closest to ego [m] | 100.0 | From 06184cff9f804b3a700206c066729ab4207bd4e7 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Sat, 1 Jul 2023 20:41:23 +0900 Subject: [PATCH 068/118] docs(mpc): add mpc document (#4011) * docs(mpc): add mpc document Signed-off-by: Takamasa Horibe * fix format Signed-off-by: Takamasa Horibe * Update control/mpc_lateral_controller/docs/mpc-algorithm-document.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * update Signed-off-by: Takamasa Horibe * update! Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe * update Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --- .../image/vehicle_error_kinematics.png | Bin 0 -> 53288 bytes .../image/vehicle_kinematics.png | Bin 0 -> 36676 bytes .../model_predictive_control_algorithm.md | 389 ++++++++++++++++++ 3 files changed, 389 insertions(+) create mode 100644 control/mpc_lateral_controller/image/vehicle_error_kinematics.png create mode 100644 control/mpc_lateral_controller/image/vehicle_kinematics.png create mode 100644 control/mpc_lateral_controller/model_predictive_control_algorithm.md diff --git a/control/mpc_lateral_controller/image/vehicle_error_kinematics.png b/control/mpc_lateral_controller/image/vehicle_error_kinematics.png new file mode 100644 index 0000000000000000000000000000000000000000..73c82d8ce128520d3ba64bbc90f87630439b4fc8 GIT binary patch literal 53288 zcmeFZ_dnNdA2;r7s3g0xB9fL(c9cl&MMbscxSGl-DylWA_;2e* zYWzvZc$g&qXPvXs@zWde%X_0mFn-VGqN?wrYj5e|X6kg2%F53E%0)qEbEk_J?VPRc zUB=cHE8vI3FP+wRQFgj$>T=26Zs+MsS1#fYsi?$6#KimZ-ib)|KL{3;>5qM~Q&gfq z{`x_gzTiL+v4Qm4Z^gqtQBm!rI<9i$wEKgzkDR@i98HKj3QFt}|_A12O|%MU`f(f&Rh4 z!Bw=UA9r~!B_*Ye^z@ZxnHsaZL#oz&(})gMyA~bI7#JAnAe$KDvyWG-R3OllHO7aL z7r$aoimUR9^{j8_U=Qq~Fh$3!V&5(K#HZ)I6{t6CxOC}K>4@uElT7{7>U?5r_pyXj z-LeSeimX)D)n&FXUXeU_@Zj{^+~s>}7J;YsGDWjh(<&S~bcj>IJI<}cCwB98ArX1` zzm%kp(N(o6f(v*j)L_$axmo7duU|`|cO6qZaU$jM;~Vqy?l1L*pMKyKd=gSidw(BZ zshn0$@5SAsA_ck~vMTE8n==Y$*^eJT-fSyb#}HDhO+!9*+@pc2=w0vLy^BgnsHq6& z*tB^w$H4=SuV2RZsIlS|Gmpzsv21qCZ?m{~F*-W>h=IX<%U~5tX_R=pC~aBEz?3N~ zwQGK2L4o}3n3#~r$g?|{7_YwD79C&uV7F7AA?=nej9a(fY?S?Qy;D#9qJaW)ybMl> z#nFv_Pmj!aX10#FZFR>VSki4Z2&>v9{3hb*ix*)&OS4^0dCL^7^^Lr1$mdjcFEn~> zRQS0xV8cQ^Wm!vBPHw_oes%2fcS9BY>)vQfq4>NuJIzGd^3k?@8NXF|Wo6}g?;@Q@ z9TBGZmUl}UDqJ24$&tfN8P2^`jO-j79$h!LtEsE++Pin7c3V{N?}yraypa-FMt_Z4p8DUvGo9u8;5x$I*x1Nn4&KozWI}PQcZ+*ZCLqrQ&#VVzF6r*&7ZH%AJf#NbItepHNq?I z$Hf>gjSZMod!sLag8q=7KR7hRD<_w5=7ruuy;Oo7ORx%m626Q4DNec#mz!Si77~gm zC@82d;$)0J+EAdQ!o?Q({dSBg>#bY2L_|ccnX>Zj-hC1$OMddSwIJ`0`z;C9vKvw| z=h6aAJEstuYehL>hKbD7A-O`G!i=F)BS#mXKu z+RRYe2Bx}PWG~s<5A0D~*c2WfZrl9E^z$k$ZzK~cbitr0!#F)JFMjO?y05=~*WNvF z7AF`x5qkd!=i=8Wpuv)dJyyXZqgL+?k;`7-3( zZ=3Wiq@}0-@$Fk_q~Egn;?h#fyGzVk3JZ^wqN_-QkCtQS#xmZdjy=xtj=A`>=CpG-@m3iBTtG)gGnv-WjYiY3+PRFiXx#B%py=Qr`shD3; zG5M^K$Ib3;Gc3QLpy25+G$L!4fg;*ikoCuc+ndD2k3i)!WxcmJ^dsaiLnv+Sk3ysO_8pq% z&vW2QcV$*`!lf8I345zC(*D;mi=%00*cXHf%Ej*+O=zQ z4TU~@_^^CcWLwz!7mX*>)HZ4znqg5@Rjo}{^!wn^Xb5k$!PL}Les#VF)k(=- z?|bs1W_rvHIai0l@4G3b**TkC{pCh#g&EltNl$Ejt1p21V`OGVe^@K$`qyNtzpi&+ zV5y!ttHoADRdwQ+-}JHR+1cB7?nv<5{AsyTH`!NHT~~K;b$LNofoi=NZNU5Yl11~~ zo8Mn)t-xv0&#~K4U0uD}b3(SJ?J%SJ2^EKfAI3pcN_j#cDa`K$4yIYNraP=lYXAlZfxh@j^bqF)yde$j~_EIF)8Wk{S=IS z%AZ1AVUvA3E>6wNto!L)A{|fH$D5l;>5#LoFR-m>WyD@rPw%Lq;e+C{-(2(;nLQfz zVnAJq=SeLncyQqCYwfdVkKs5_#_1{7%DOt2Iw%V0N&2t!D7PaQIJ2zX3$Vw2Wo3h` z>}Y{l&(5rRgC-S(OT4#2X5yzS7C6Tp^hcOpNMn+IpqF5DM$yQ~rjG&7nzp@1k-Ua{pV?8-J ziPe10!xX>fG#YG9@6-Y-E2~M<>kG@1vBkZpd2DcWV&X}Ad*N7N%2*BU>@+d*UAXw~UTJHie;O9JN7uv(>+0&3p;>$M$6Eoe z%q7c6wy&?ZOsy#Nn*09i*9l)=g}%PNb?euMw|d=@O0GZV=cgD%x1+n^nJyn6pNQM2 zp|=9JWWq^*H4B>ii#g|b#Y}O+Ki@szy}B^4ypT+hxp3ivZOhx6W8MRDEG#VZ+&Qiz z2BBeL6P|_B)6;LvE9qoqWx0O67RPHF8*|^idlzq(>AT{Yl9H14S0mb#mGnLg+tnt@ zqOtdUR}d{Ntwzi6)@Y9DOLbs2 z0HqsT(?{0(T~3bTyUXlcT>Ur`>G}ByA3rML@XczsUoJ4rcMV5_AGh+GwIV0Dg2R41 z+}?Zb{FS=KrmJa1XRJmCu}~HtzG05cH#Rjn|M|*uKOte$mMwjE&l;Jw7kI3Wbn^$5 z9Z^zRgI!Aj0KsGslaP=YrKlyC@<>a^;rM<0__3=cXf5?P&y-}^4l~qdeKdqM`ris(O&#AkCS#iAOHu% zJNnL_WK&I(#BoB&iOS2@W|~(@yNz;w`}R%1FgNP)V?N3~w-=4F&n@@L%6c|LbI~iC zD63tos;UZF^zGph6T4j=ww;-c?YN`k#8b2JXRQ4yy*XquV`H1BzjIDtTX%PN+VZG0V;+x#e8T)I(MHksBEUvkZ*@AFn6qXIQ;ZHAhAg1dNlObs)z$RRisP8bM!uM7^p&RE%5 z+fiCowGkz2+xFq^hYzy-UlMDU7pCkz9|UXc@K09HX+3FfzDv$+lyBd@5Fj0b+Qa=n z8txC^P*>7SpSl-$kTw7t{^R#=4U8-7pZr2^4Ej!ZO?I5P2wvDQ*TEl+B>KSv`HNqq z#pQgt<=vy|6_#%O{HdpxVRRDvjJXx#+d0|SHR9D8oMpn$8x zKcjEo7Q1L^1QY@I=RID!0f#8dwneOnvNFcJefvQ2Iq{4$SVG+}Q&!NP&I+rRfvE-c zHHYzMYd{jdfB#1h`L5j9QC3bQ|YM^#q+DkHfE zxG59d9+Z{2kcf!>NXmR90c0&LEkJ3cFADokY<3;_rK+d5jgX#m6gog+*&R!64)a08zv?(q5Pf- zx@fM*AWVO(DEX=K@`cUcE1jhi_lukJ{y1Z@nQ?0Q(~GkilYXo9l&FAQb6q(J1gEcj*pA%(R^T18L@*?)@37rjlMqXkt0X2+Ex}de_6ew{lH~!)E>(@8Z(ed-~-FW(RFIKz^ zQ|Y*t7I*AniCI=UXRCM_xr<-4!{@Z0Yx7N-tl@ZmU%U;2@!w_3bLd)w)uAa~$}d*; z_Aa2vfT7`oDt<&w-??`WFi6GJlqXi`LP|zPB+foirlX@Hu#C>BQ%VK~?2jHj>haxy zf>-ZW8+S>({d2T9auuGb+i1yEksAB>660`s=!s>k>KZS?J>Gddk>X z>%<9~n>TM#r5bGATM(>q0Z=dfM>Up6A-TTT;%8%{s*cXLldn|B{B^U?luI~2v!{Dy zjg`A*vO=BWYLDXN7rC*oO-)kIkDGPUp48BwRgV?w8_DV57ZqhpsFQsD<&RxQt9QZw z=JwoZ+i5+$w-`}HGq3F1W<7dNnyUAfddPEu4+3v}>~eSm`erN1VVA>!abRuz=V{`r z=d>)*a)6EK$wBPFwO2+hnX^kuVq#*-=>6uEaY&9{C~Lm>>g7v;cK4nwX6EKAH9m9f z0;pewWcrLIb)es|Vv2&_#CAXbnm*or`v%i|HQi+Uj8ynz>j%uOt%KbEla2H+ttF3r9)26 z&h|92+rn<5Vf5E0*Mr7$TW^0*XIVBpbL#y0n&Oq#;t8zO8;>c=RUo-2Of$;N{&gW5 zJ|MK?;|@?UmIaTYjz-9w+W6(jNK>(~9y(v!N&w;NlG{?5A*6tt8vpr;rRtdUg0 zu@#LKaB{n_(c|3QxNr`s+lh(c827t&^+bf5T(K`&=ucpFDCFgp0?P27X*|2!y}j53 z90|Z!`_w6?nyH`oJgjVNT|njU-oIaTyHlGW71@$yC5}mm|2Ymu&%;yNaY5GM{Agla zq_~%8`KM3gwc_>K`ug+QG@pwjuHUO#!DgFbE_*KyrmGx1dOJ4u7~oQTd_3Soo8#I* zfNP8I;KH+G9a=!6yLa!t6C2y%=(Ut~GC>;J0$6xjMh1OQSt+xY{1ME5AaDYk3RY%Y zi5O^Pq^Y9v>Cl*xc%B>nPjW3XIQ4aRB*= zb=5v3)4Y<~ul8?C*12q(t>@02bED0 zOyrf4n!6Wtz9ZsZJ-%(6&$Z7rHRs-0Gm46e8hZ&G!(l=Z1O`%*aj{f?AuK%n$F?=Ro z7_Wq)&Y%!g*VOc&JW^i1{F@Zfr331`X{+>-S+>D(4Gq3Mdn)}5sej9t@6g{4$f<%a zg%UI^3*1thbO!T86`@^inP=^HxKRQT_en~_68g?bzZ$NJIStajwcKbyA+`BTU9%vi#u|Md|7Fdcd?6(l>SFPo@sJl(rsFpMlpqX2ZHcud^ z7_SVS<&<;1#l76Q0p;o4Ae7ZA*w$7*6H-;yHQ_$LR7~+g2ZSE<5EHfJPyIyO>^^Y< z-FB?!D)G!%tFiMx8kFxkVurT6^?;uI9R{3ox&hQjfLfvFjE}uvF$ccS>C>kjW`@p0a2-0~(cTo2&WM3T2PX}EO+kSjV2Up)jjZbiQrsYTN{|D1G@Y@fpba_ z#ISBOD!e~#)%0~k6(&l-jT<+jl9ImM-mSj8v@GdTvV;KRQ4{tdVC3Fpi(|&y3AS z-7cg*ZL{JPKilcZfv(y&wmLc{?Yk^(lo1;j$GS~G|1h8umI!0wJ5DN&5UQ~c9pd7` zWMAr#v)$QwTcP9~hdl2Prg`VijW##p9yx%M9XmkN$qmmoDYStA@173E;;qpo5x z38VlVEQ2=z#1%aMo`HkIt7eyX=c-lmR!G>ntE;{?Ha7DUk$$z$bko(ew5%q&%dsYq zn*!=A%`wL?xP=UJ4}GS8^f4-#_%y)-bSXqgSiCqUt5ELA_ zm-w7pg5}a3hIrG8_6^wp{#S?f_8&N~Pe8z8WpM_|3;~N2y{kA8pd#qyyC8&u34KYF ztDGHay<}_q82keL^{qpf(kWeCdr#r8@^1T=tn;f}kyeIfp?MN|`0PNrcu78#=5Hfo z75>21k+dgIZoWF7Lv&QYL$oDq+){*;F8v423~d-7@uj_sGsEE4%%g>_7VK%z6Ybzc0%8v~0WF{`_njevJy z{`)s=2_!X-m6;|F%zv4yLo8&nf->3rP9@NDs#Q>Pl!-Xx8J2`Uk71%iKs&6o4nC%pG9bWXS0$gasc{( zsHf8X7SpjN?Wb>f=kr@bA)Ih$WoQ35=yK}9g_9RA?ml_)BpOIea&kS0Etoms9;ndy zvY#t-mi}dT>jzR(Qv>|wgZw%{r(d4WiP&!Be#BJG;yyb&dpE{OKf%*`_wVm6UXGh8b@1R_^lYc@ zPn&QAfY3})#=yk)@85@N!Y3^~UljYcwvrwyI>=1D->S1_lKgR1)%6Pt3p9$nKjJET zh&cJ+kk`F8Z$x14poQ`9@|t~oedH0GG11rugwH_~fY$cXFzmSGjG}`oG^8fvn9fm&q`SWK|R)T`zt1i^XAvJuqpiXnQ8y3Fupz8%xj0iS4V2757_RK5u7V zxV`_aKH5rN9znS=_wR?|13(|_PIPPU>MRYApZLTK$>#dURY7M*Vd-%#WK!a4Twp!POs{;}k9!U*qB70XW(| zW5Vrb*TkTj*s z(QG&hH?Y%_i^CZ|nwlyBiQQ*gtO#2f6JgBV{0WZCjHjb);`Gc6^lo)+?I_CFz?Z}x z3=~)#f#{K7^X@n;Ed?Ip*nQYBK390&w~koig^9YPv+Mb8rg&f4vWIDDfyE06#a*95 zn1M4CJI{A4ZUZlkaqUh~|NpZ9C*MnTKy^Rv<;ED#VA*-;^5q_^(E!m2VT)FBdEJ6s zx#9i=QMWq_-U{HTk_lT9>W*4i@cql9M>~uXqM{Caddh}`gg_IACQX{(`}g-Sv;Vrv z0nV|Z?mpj?l+Vwr8_+a7({XradRqJZd3ASpX*hk4)6;b^ z1ku-mBO{X=vNmOV^NT6d($P5$HS8lGo_E(S0<`hUL`c7OHDgV3kBe-k!7C}ji|c)1 zabRAQ!9KzONkDkY# z!zK*G2!V-*qeYopldqRhkA*S)mZAzpKGURh4LLzLhsNF$>oHwXOepR$g2B4OgmYm* zLU6f{VV<3n^F zHLv*m`2>6{{d`wJqNG3-EY46k!7H`^S#SPtRz20;y?Z<1eVLbDUk`qHGOwkh`h_KU z4~%mNh5z%Kf4;sz^q1nFraBO;OhYNgVjz6SD$;OM;v~(eatN- zB6NF$s^43nWBHFjb9Hrf#L^fYwS#zc%+$0i_XaIQ2fP6BFK`&%y^{cd4Y_p-=X=4* ze@$8Rg1qxr3Cd*!NlZJ`8WZ>$`X@RAKUCKSb5)B)k;t_)oXoX5Ug$<+gm9Sx^8Eds zhepW`i(s#y;BJ2Yet(;g+Uu9ZSrQffxFD7QgW?rt6~Bnk78qstrB!imTwC0Ev=II= z3{fZ)Py)8$+`>g_9r;O%GBfiv^78cjGdx_@<)E#tU2-|2FtBO(32LOdS-&&q!gxBI z;OJv&ojYNl10)k66vcLPX1FQKq3h#@BK6JQKF-w#_U;V^4unNMRLmifvD=|yuLvjl z1y&YzDq!UW(D-|19tVm-_kOKmNSI{rwl zm(e^h3bqfae&|&v@zvI^U%$#cQu%Y{x1e})oN5EOq=5b#GA7{-+0z{1pDL_n77)NL z*4;md$xWqeKD;slJ5T<4ZPAfr@5xPAe_|2*{%uJ4wYswLueilqgIC~EDD5`}uTqDo zD-@avgn*2|P{G$EJI%GVj_hLe!c?aT5tkFm~ybcsHlBG=K&)8Txd_d+sn&4BuKkOnm z#P3FLB32qc7s(t!!xa)5eQlLYTecH66%Aw-(oTxm*0=-?!q-d-k;8yIS?W9@Z_&R}d=ozO9sVP7G(DKnBx?WzTH^&9Zww~Dt`Y&Kzat|T@g~HwM3tX7aRT8JsMsq0 z<&7XV59Hh;oyHi?~z>uB2y_L0fmGPe|tkj^CsiR!OLqpa!Hc(E9 znjRe&7k5eKVW|A)HA@kgyAIQTbl%&weFpM7_uiHb8-<>D``$gtD>N@E?s)I&7ODuZ&DfvHZ+V|BZGHYY-Kn#W(f!E%NgicFk4+C2$`2;)t;YnI9?< z7HfWUR-M5O9A%I{QQ81(%qf`W+S*^&QWR8ry9TkdKq`?6iyO;Csy=__1(U*utS)-D zA?3Vi^s#GbM_`j6Mc-Rmjssa^!mq~1PjtG-;-6Yo-`$<2 z2_K(B&=QH11asV~;pJUexpZ`Iz2@vdw)EdxYyx!kF`!iBD$v*-n7`p_{7tz0J^fXdp)&5HH{U{abe@h`9K@uq^tCCd(E}Pg<%St8%Q1? zXw|=7{{60T84zA#8WTg(-n)l`W&3uRk~iusr;5|s?1%*{T)cc67>#&L0LG0*gStRZoUgp`%=7DT8{C-qz%>EN(4xtadHeP@=38iJ zD6(`P21+me&Aa4(Rnan6Y^_dbPwlWM_vM_{<0np-LC;=2-0L8Hv@q7AzXf?7#APnx zK(TDwX49f!5sG#SSLj<~BZd<{f@KMHvsE)px_Gk+pjn`HqN(H9kYE|w6ez)t*rVa7 zILtgIE-p^6u$031))-(AF z8xE9Jv^=SfWC`rGqDvK(!!zAZdB{jXH8ja;K`;s$dl z_Lg5B$Ve5w57v0y-fl#o6*^;8b#>Q7CHH_=#}XGjAxOTR!?87KtxmcBB0^Sb^hpwv zdi`4HXNIwstE(ii9~rK8QTYd5kK2L)5R0LqLB-50#V@4R&_I0ilh$9q{)~*wBxhKD zp;`ZvBfiF7GJ!ZC2>YpedCB2Gn;{)Sni@q|O@&Jhis)F;k`M{^pf-q{OZu6{bW@|i z{hk{O10@vAGib^`nz3q6pFK0h552sQe-BBW4f|h9TDbuZ0caygh1^J8fya~sOz?Bu z=-{KH{U9;69Yu*LDZGG;!QtVBeVyC&Gfu-~LFEUBh4nm%HR4rJ@clKW&*;H&H#U}7 zD3~GpfOf>iV^HLsqe@>+(;v=B0TkboXD9?XU4hn&!Y6iHQqpMhqfG_M`R6Tpvj63! zFmS?9?~p_hpwqdKSr5Pu+zgHa`RFEgPN&8-=Y^bD>=I&W9)B|{NgxTx@Q2eliwDb9 zS68Ryc}EyL`fp7BL1K*$7=&1wTelvx5&x7rpLd2F1p-xprHL?31oy%3Par0M_i|Z3 z6ifC3XT@GCWALKD0AUv*nHGj#WHjfy2@@S&K_LlB6o$sK&V{FyvoeTCK~%B1e3^h} zjB5GWW^*C}MRV$_rg2P}GyzAndkzai>|JP|E2@P23bH>TT&+07wUVse%Lp0kBSH!b zAQZqi3sVCz2?=5K1NmduL|t901>#;meM)wgkf)!^C?$jQ=Se~WHUZAe^!rMuxQu}b z_gtqwntZo0!YaRiKXp&oSYgELez1m{KL-!e1H_8~HpVW0`}ONHG?QzJ42Oo2&(*Pn zXfXGi0Bckb$Q+3VL;2?xs+3+rKU^@d76l%;`X>@pU{x4eJ`Ce0Po4lnLBKs?Y1w~L zT*<%o;X$-zbXX!3lIraHe781HZZ4YJL^VwonhDaoJrfLwV89x;FPNYXG$oFaxA(Gz zarX_BFjjiD)xaSv@|s%{P?X3lmk87SeqX(?i3cLf6?e!nO|AbJ%kmY@Vi2si|CH$-@d zSM*bWO;7Jq$m>L@J={Ctjnl4)W|ndbd**d$lleSGJ3Awv^%Pqb`w zT;H0*PQn?R5x08=+Y*PHWXvFpqM}+5Kt)DywQWyY=7r~#fjqf7FWV3xz&R&i1T#K8 z$@8<{gUaR|HoTJ#@yR(LPmt}A`6S^!0tVBwv+tq|V&davs?W;gf%T?^bS(Ev5z2St z#yaGe`jfNslFy}-R9r@P1&}8i7gW=I`}P^)OU|`>kv}X#92Sy^lD>ZPQxTUJb6aR- z@Y7g+awt)N2p`?17)mn6%VWQx?RQWB$onf5S4H9W#C=n@^nbV8*di364f3L7YT}b( z*g+nfb-Pz++%L*mSXlVCH7634M09fiNkp#7EVCxs#(ZN*TxiFRa0q=(LOvIEUguDE zA^{ADb>w@-8vCBBvE*g`qbL3Wu_!1UUy>EI;76b{eCnCd=su$H%Z;Wr6D~5 zr=9Q+{Bqp)+BMG*F-h%n=STpS1gw&Ewn0z;9wo61;j7^zcXqJes1T|=C?VmnIDH9f z1JR@)ams#Cwpat24pZ*G;6OJ$@b9(pS>fCS?SM$)p$9bn1jv|^};TzBiQ(&=PlIG=-XvS`l;P5S~{;k9KfMg<_J&U$o zj^w$1f%}Bdg%`oU6`l9AV1HU*rD4Z*Nl4s5{tIe-qx{S^gd@dNk@tme#O*!)56%+_ zmLw)_k#GL;s^nZ^QW6)q6Yx0x84Il9MjHUig@6dQz}n)-LzJrD?U(7^0E7N*&I~}o zkkFE&VC zB`5o36t7|Qpn~j;NDQDcIA|&+qT+IyVlVJU`pcKM2~pr09>+L_~o|f)tP<&$216kLsJt;6i5{> zoJ8IfqEm5>@wMRJF`0?aGYs>TAh=Uj$0$Tt1rka_mH`R?k_ncdF3ruU1Mh}zq!k8$ zCDtE6lQ`0r0Lb=oac$2TJpazsHM!-t85VlpZOeCaMr?wHhUV$hr@0x6*E0_uCAQx;;g0ilMAgKQ(MP@vf*@;nk*hEq`$<~+B>FZlMGzQb3BB|}n; zNq(yyC)Cxgdi`(nG7CDGQxh8vbl{~yb|{$7mwBN^LaHr7MU+EedLmOJaqyrhz91_wMqJfGWG39@qRa&-Z&B0;?>uU=&Nk+=2Fl zem!1i?;8Wa*mgHmg8^i#*y5!d{cY!v`fi1%66-*{)BFYm;W_ns)< zzWmopu?Mm#X&aOUMamw~_thPiPHv=aY)r1N#3B+yAFdB^%>c*cs8cd;{_IbNN{2oS zr~|+37~T_k4ajQXJ$7EdR+=_>KWGtzIP8S5DPnnh_w6G&hMWg2Owkh%?2&Il!@I`;v(5awAwuYSnv?w0~AZXS@)$q4(I>@Y51lNfOe9$ z&7EV85?pTK{az8bZhdWU{{q<_y^|!kp-^u5#7iF!TMoG**)+T6VC2bEQ=ht`tGW=KoR?2!u z2c`JMHm!-xhnPxc8pPoew6dJegh=t6g2*i#IUktcwb+tyeMZq@=*60QuynL;EeVNC z3B4;UOhk_%my#fvp38OM0cQgP?Xj>eda$yw`Mf9RN=-o5v$p|?^?>T@ypNd}@{s@N2`m-yuv4>5RONN8Zl zsS3k1Ds#the3{~{qKNkmr;N+%uPE>Z^e3(}dsvzS{tQPy|ewqDdi(ltrLPKqW6-`h@X5XD6iBnWV64lfoQ z8fr$|a>HB(gm9pupb7nI7WqO>i*_fKWndVnF9|h$`7*m9GPA-i^Qvqj(Ss3xWnyFV zsBAyn!+58*Pa0kacwVmi1TVB7;tNvAUOjK|09Oj?2N2RjKB0^<&rJ#F@3%}sOw!0} z z`mHMG8%^0tIOkK^3%wwR!WzgjD-R8tE#eiA&WkTyc1CO&_6@9Mq_H6|LS1hQmggg9 zvFhb^kqvSgO>#p^{%-z&R=BH(5F`B0Juq3`z7^XhWT*zOLQy(gDl2#jN1J5WG3K%? zs+sNyT{vN5Gn8ALT%{o?EnNi#7p)F(Dih&D;0-_*QE(-y)n5v1et0+LT3T7iSD4;_ zKe!n|uHFDI4~h0CS4v(1~ zA!%TDvG^gZFbx#&m5vRKjE6MHm$UeLxZgoqA7&qVC%MYg4PTi2w2X5<_*A#CkaM2l zzm`*C>sGCfvD&)krp?~;Wg;Ze56K(np2&1j@$t{@Q%5^mvQl>}{>*_`4;v6jUF12> zP}{qqs13x|I}U3TLkyl*>P+1T_Ocm1`rN= ze%lu$RjZK>;N$CU_tR!%D<7D0oc(*Q-H+k}Mtd0PZL;P@1+1*euIx_sWD{E;9qJ>% z2yg{FOm1>O`VOfdz&*|?V~rgwEWKl=u5dAM=(~8lFmVyC9Z1MN-XD<#?Uw)_bZIU5 ziFG)}_jfaS9PS^;K_~)D%G1;HX-38#T&8PoZf;f3N-hi{DDHY(mXv?_?fc1DoAot6c8r!pv=g8{5Khc;KM@*QQUA65g*Q?%^IJPBF4*D<0n~E{CYhFX>=+X1 z`Dddym;~}= z28R?C$IK$H(_C%686vz0)sO-v*&*1kw*i9@9@et8eObIAdSRh);EEaCL5*vfSlWKiKTBb{DLZj_)4k{laQF$NP6Y=QbQ=QVV6qW${!I>4@68Qskq zpWjABt~wynj%7iFJQJQQ1S|=)u-|)}Eps91f?Xk`1TkkP#4-f#;D5UQ7!~vRNv@by ztwRc%T=sz>J~?bmxo=EaY?_|^&D@an|2-FA_I6ZM2^5L>*_`4!V!)$Hfis=*5Nt^S z>%zTSP_;6&3!?uF)F-Fo58+7R28-P<8CONQuUI$ahQN*RIr89U11Y`r`wAZ=PZ8Y- z+YHqTCHolX1OLu1)@EkseRkV_gUjSTxVS2)FLb2>%Iebc@_=G`aWV3nL-Z;ne}U84 zY)j$x8rZR;(W9SIZ!NLw(qo-5vj#>crS&RXRj-MpG)tK4+E%*$eP`~a>zY-qczpIj zZ%)2ucg#$6MP`$$;UH^*Q0Sk+<7>8R|8ub6=Hjh1%IbKYl(^D0hLrd@XS!o*_r1pC z){c1<&v_&dEbZ0V%d+?GiGspH=x{tRP(TjxpsWR@>sEMA+8dDz~UI7MLE{s5MNw_&ANrYq-cqW^u**a1K5Qzt8R-D(a zr{Bi7k7*+p)hV++a#b7lH;Mdt7IK|EdsbdvK2F+^7w$^orG%3oEwe~G#L$ovDn;kl zN6I8^_(0Jw3Fw04A0WK4D*DO;uRT4zKhM_qxxO=J&Ed@%r>phOoGHgi92_1tM=Al$ zqiSURx;3S3rXsBK2&E8?58=8K4qYE+$35ri&i?lb*Mou>RM(XHd~|&A3|1z&V7V>9P3! z;o-34WbV`CIRk?npZ^KzI|OY-PvZVL;ht*38zk#th@AaUwi&rK3utPEi4YA7M z)DVXaq+EM13tSY$9uEvK4!X#;@GRP?{{fNOL{Gm5BnDHQiHV7XrOsv;J%QPafC^p_ zd01XPzIDRF!g;6abULN=%7Im|`87~}zgbI6UcRxDX(RP9#Ijm*><8d?Ls0=%CS#^g z{zz$R7}+_IU1uE6oIRTbvy?bKNNcc%2SV*Q8p&06XP+*yrTqQVIa0~D?B-#LD>F}|B|Nh-u71?4-GBw~taO=Yp5;!nL zt*|+haW zMR^mU07{+n_|%j$lalhK>Ti@^r}|oukBw9Ck%j3@SSX3>;Z_E@*Mi|0kG}x=#g|Dr zz5mjcD;FuNDH^ z^=|$jg(St+U-vr7!~n?_;nDHY{4pntao}qQH#aNPFu5_ycj(XsNkbR;pV3_mJ0TkU zhXIKEA|(|I-{{BJuh(K@V>ut)e(>V_`Sb9Ox=4r?qPE5ZX-1S3DV5Ef-0ZiG?!rAG za$A!ioZeoGyql3I)}*8)Ef5$HE9ruhNpf<(a~;aCCx=xNwNs)7-ZX1=gu8R{s7^#LEzBc!CHez&zvOik_L=MTJfix%Ed1qwoh zl{PmokCB1lF!E%`)lBjVCEZF zmQCyCu7Oyg;!tN(xGh6s0JWClXm~_t0B(kEyh&dEk!Tb{ew#k$E|u8k4f&8ZxF^&|A6gp93#iO@H!!q-}A@i&j+(Ot1G?cvZ*9uW5&^O~cwcpCHF_Hc4a$@e?tHAsv;)aC8bQ<-m zfO9*!Kk-Uyhtcx{ue)Aqio-HE_y__yBns5ygZ{--vHJCHk>oV(_+#&6ovDwRZHB8d z-msO?Fa8nnn6yapnLS59ike!mVPI=Vz#kpjFQM(~Yf2NJy?8-ddHB(?I8k$VT*BY9 zaia+;yzK26e)oB@*PW8mLQa@VL@$M&gECEh`gG$fy&62#;2fUIKr+z#_kSL2&Q}$9 zx~4SsCUyswEv}W|zF-;dD#yz>^MkEhXB*)87TV8FyX_ABB=0A|7>$D{DSgxp^$)3$ z=tzhLqe}5G6ne+MM<#riRK2o0ayRG$tG(0 zh6gkGNHL_S?abYBJ3Xq}q8s#Tc~HyGtfR;W9J;Hgr|iZiW^#*#?VwG=$<~W&{5vNq zz6mM-8KV74ux~-*U=2T-H*GZDcEmP$)4H5e%PjH@Fv>k}IRz;4G3Gab01#X;#N>RQOpqj3%CXd`N5jpa zmJq`RAO7_Itqzw(`I4yDU$3OUB$QBRIqi7}Eu!0WVAGLc-cp}RyBu@L1X1>IT%aMz z6~t<)>+1*VkR9z+(E%EUYDL)5T!&vWMu1GZ2^t(ZhbMv*d2{iX(i7_x#Xj2XyKqL;q&Y4HCj z<4TEn3d#-sl7%bvtGF)kwV?sm56B3WYIhHSD<&%#q5MpmG3EG9_i2%Yx_{lE4nJ<7 zDB_%^X~Zj8TBgM`#dYR~GpJr)y3Vo#^rQ#Pl=yvka>r}qV$x-WgoM^nQ+N0G&wi~O z%>9ZPk$JIZ8@W`2EQU??{n}a$y_fo>V8LIlCER?r@LXSa{TOp)5Ia6Pt~NpZvzB1T zQzqbam*WCebv26WD3Ua57lx5u+Ss@?^;_^a>rX#^Fk`A3Uf^!` zD_z}cM*0(y&cqIYZ+GVeo-iUq(hVtgBl~zbc>QTCa}-xQ93mM2JkP=; zloXJR`$#tF@KEHcJOZxo*}xOJPWk9B-pls(B!Z1)Cglw8l%x+^TN9AM!AmPcm;|JK zSX9K7P*;Jc5ji?Ld+klB(qTaJ0QC6eHC9*&+=hqN5FrBZMDC4NL~>(Tc3i96OhK7V zd=wo*xcV4wx{;m=2++4dah~MffcxZob!fQwl~^{7hG1MF5cUy|Ybi%~@z3DkKPEVR z@>8|q7{S|(jg1xNJJ%w9fM?sFC$P}0Cq}klx|-*y0uXb*j?FF`l6%>y3_3h@eOEUQsD$FW|e@TQ<3_^0d z9y^N>C~*G$Ef6dO`l|8g^JA1%dt}ffU@tW_#R9?LQ?Q30b@lg+0*r!TT7`$JKx6|p zTN6-P0uPqhdyuMezwd8aW(ax*8k}7Y=9dcS$3Or4Lk1Eq3?aLO9$!*Zqt16)v1_9a zAFJ4jC*Xe!Aah7!kP8XGAV|F6lEowRS^x`2=;fe4=#aShO-mgh5X$AkhexD*Z*Hza zpKZx=-h*O!t3HDpS0zN`2oJwH3yrJ}{#6-ja!Uke^CsD&Fe~n~?M9_ESd6h$0 zz=mPz)Zkd2EA}PPE8qr#RiLGP2K(Q@qOz7}nj04Wyb5V30&B^$yaon{;z6>z2Cwd+Xkmzqsz3hYnn#6+ zNy1>Ty6Fpz=t}^_{=G~ynm1q}>LT1~Vdl7X<7jO_ZHp)?EwQL^Ckuk*0>Ub|B766T z{<<~C$d~7cNFnzhkXgr+LX6>d;=?Cg)@3{PITg54)=S|g1&qWuZevEURmP{MEpP>l zXnCkpxe(cqQh{Ge>#)Z{XxcH=DtNFFE}ikiO$7)f_c~%@n=Z8a2QREzpc!>0MSTix zv#YepHj_-ydC^!KCmMij8kj&hB~MQ6I~M(T^6V=;Iop&f$I{#DBEDJoqA!y#3Bp05 zO`vuprHc^4tsQcDvpbo#T)@=gxYW);ON|bM=RM5N&x>6A%mOrsu?|uRe)7q1`)?*v zU=^aWz-J_xjhjY5rZ@NLrbWTk?d+wwoT)DoukrNsbJO~Lw-=d_7YDF_(nxFUyRaKg zn1D?jbj$iA!gs3xlmJa9msme%gFdI;G|Cvjg;8|r?O83gxYnnRi_QPB5SlU3(jANx zxpm4PMU{HHyOkgwqt*7|ZYVRB2N>Y z6!(>B;Lo8!;)xaAGfl>O1O>OCSw|Y%-o^4O(%f8AXhfbXmF&B?4?qByT%da){^n^d zcynFkcGB}U9T&hY#!NqoFL}-f9LA%mxa#k!8~3ZMEC8n;{{R<$SZ8m3HW48kPC6iw z2$de~L{Oc`!{m8ckS}Z{6Rbz~GW_1~SjI2kzpm!iG6gj%Qr4vrBvQ=pPucSlGZ< zT`6^zp}{CxXFSpes0D%2f3LJ7A&oOrb;i;y-+J=|AH(nX4I|WoGa{`}7`KI~ z3T0)ydZqg06h4UT-37tQOJQ19fOD>r%v5wP`b{;gSvn1z@mcPMr(cp?;e&p6iic~B#fla zt}f9|-PGxs3KxV4LTVK=mJ8%Jsh)57l_b=?Tg@L+$y}& zWG%w_;Qc6M0NSmnaW_@JmU=# zEu&dBKR@g+MjN~H_Ltp#jCb$dOKG%u29^%aQthW!d!bYtC|bn&@s)I_sKlcMawXaa zaqFP{V1w%{^9SR)9s|1IX^jeaz7#SE$O$o zltm7NSyY6fq2c)CB+0-+FT(RtBJrz=2d$T!%1|h#|_}ndUBNr^4hUyr^Rd<_9A;#0qeAq9M!=@nswLZM4SJ7HQ99nVk^i1iSt99 z;K75;&_6|-de!nCD(_^~B%_ArKLG-yHRRh+9P`sI&UW>Eun+s`mC7hKok}`j|j_L`0%6z{rzGK#jmQ-3)3u z4-``Gy2a@gy^nL*umnac-kW`SMoU^$>VzX|h^0(5CV7x7fr< z0t0;G3zBh9U%l!>O@r=|M97*oYaFg#y;~m6=Q?`&`PlpvstBl^v<5UVT(R2*P|1Jt z{wKh#!?5)+>{5EN503{sN|}Ai6j7Fajfe}Pwxm?A2Lw#a&RTxHvv1wHbyXR|#j1PO zMVaI>xUrNz1Q$mTgxukR6#{c04XF@tIDB8?HGnY??&a96f-ZDG*ev4xGE>g^Pq-9M zZWbpEf|fkR4d3=gaWUmu(vh`- zPOkYEUfV4p6bC4l!5eL7~X2+Yhz@B;_McI9f+@4i@fVm(})}di&-vSS$X-~*H@eY*X!~AZ>@FB z$;k-;Tt=#N2Z;UU&Gp6z=~CzPD!Uv~yPNlUiFAVw>Mn?$Yqw|7QBeeu4&n?&uoveL z&NTqnB4P!Y{Qay2mGLikri|C|h_zWc?aah^7pE3@S}=H=n`M4zHT$CXYfRLN>1avYbTn51*@kZP32v*Csv-_!VaZ?80;mrYTs+Z6lyxf-(>EiZvmL&0M-mPUkY@LBWNsv+qt3(7DQ%}E|5Vpr zMeIo%9vy8Y_G@o%91*hsu*u0$oq<1Oz~|U8O(3bQZ~_T>e8NG8PV?Q#Vi}mNnVBh| z>P#kh-s<)&>#A}~?~%RUD35awS$^y>2o4uL6u{M~pU1j&?~00cQZjTqU~6YmQu_O~ z*SpG!iqOeXg^newJojwd*`Y%R@z248=n2Y9nAUVE6eq<0H&;Jg%Tu4kdO0$O#Qf zqy$$-aGLh{!8yeMv$7K&|Fg_+d)uqjy48dt&nI!{jD^i2oltHJtWcU@(3s51j*B8@?Qa;a)DZ~`p}scoAG5DD@ORx-Hs?p(~vg)IF_p$H*SPB2q0Iy%ggIHB&yqi`*XFUw?svC2l(EtVJw%4(z0Ng z{sG(04l`6oKDl=EO3JD6XUZxoKVU!l`@)Z3`-YAE<2)d86!5YJG`>{*f?%yO1ONul zl?s=#Q4a{4(His*W-ta2_FNE#dJ)ITFz#P5N7G2<0A5)QOeqkF;AZ2-wFHPtrVMM_ zRzLA>dFU0deFF)_3jmvB&=P+I&_^lhgjeYLW%lR)(*l$#bAB2Bk_q&L z-#?d#?hE0|ee}}^q=xBP?N)nyZ_!$9sFRnyA(%Suy9Q$@%o!?M&cMzel`1gvj2=8C!$#DQPt*cJw z?F8zrnm4?)vX&RAgA(=wF?<21yC$)&vd(~1)T@_Du$^(P&%wjLysfvU_8H$AVIXbJ zIO?Lv$o%4BKTsFfdmO(@292RbXbuGbB%Oc^Z<~JZZgzI?g$oxNE>_j|OXIfwu30M+ z#e}=^%E~UN2B@v$>dmV=+iT>7wH_W#m%I%GD|ld(SO8ZkTqq?RCXRhifBm)D?O`+F zZ78XP2tisy70P#gzqQ@$IZQfwtX-S!evJEO!ih)spZoc*$9~)RV(llq8Q2g=Jr{p=kR2Z55 zUX&U9P`Na9{%515Bt+5Oq4ho$AFocqL2e;DY?2MY4EvZG&6LS>ZjiCk zqfmYHBz`nwpgkmI00y7H6D4Q6t49Pu}GygDBSYl`XK-B!>D5k)L>fQ&_-N@ZY24`{NUabh}H|o zs~&KlrGxu)+Cq-{*l|+v+t}qkxZzxydt0e`xDf||8M$9aFLzaGYV03ju;LEQm4icR zCtsqN>+5;@k}s29uv=0^*I{L~ZRS7AP5%i11%YlN3h%=c9b8eQ0v$Vwb18_~1jLEo~8iI`GSbBbRkMGz>^q0IKG!}A0g$qZ#Qd3(C zBAzGC?-J~FbZ!-WiwpXEc(mxbK7RSa;cvJrrM~Ac*OJmwLD!f46Gp?OMeS@A7J!mz z?WmlrERA5hF42q3n>Nz2)>=PqKD?umk%%zpIS~PnuM~_AobTScF<`3lEm(W1!33kY z9<{CZH&bdbBgUl=$eI`@U)t8Tv5Sk#rFH@Ptvhun9k|fCMQGlI7La5s+Wj0ds1Va}lUA4GH+6x4lvt4GI&W}Wf7>o(YN)VzoD`;411C6$7mgolc% zH+N-KexCr&024!9vot}!E`Ts2Ww0DQdUxQct9P z9cqNI%a;Sun7lf4Z%(hrWOC@u2m|#mRp81p4~fiJ=RfyzewW<+~3sw7T(iM0k34lTEs0-Z$yh5HD4b9wdCjLTOcDLY2M!6f=S3x z$Ra_SLDep*HBr2616)COs(=^*HKjGpD2|cHx5DfVT+U8!v(mmSw*2KTUAh63+x&-= z3-3xxjq2>a<}#Ejc|>f1@epBr+&=2r?N3dM4P^c;4uXg_OFRepawOuB_{!0t+huf2 zJvRUh1R?{W8!~iwRYA2V(oszV7f{exXkCW7hCva?9t~5kjWr&l^#f~uC0Xsr%}T!s z0tOxTN0xv#6=;^&A`KIMHMp&9vW-x`r1J@V0E0E+nf%`@%zs+<38ryeAjI#ZQ4C>Z ztFNcmz`-G>;Pvu_AfQbg> zYSN)a{CP7SH}Yr(j(}K!kOTDD93V7jt5*5@&+Djow)6O68PI7&kG2oS{F^}*smZCU z)yBzhA^57e&uXnsY?`VpbU2S8uzNI~=W50-$0kgg=%uY&6gB_jR0iD`B>;MLB%5=s z$}1D=g3)jwIuh93-l^&S@SYo@?G2bx*MoLpr~|%6^c8e)mQl}|Pgfa9=X3!YdLwf| z4<5~m9DO8NUHp z9U!*C()j`dX!cZJI;!c&FEkN!OCFWkYk*egAzUY*rz!dR_^D7^LxlcI5dq|I;GYZu z#F@lG{*#)SIbp!Y8<}dZYqIfC{!x-W3Y_oD%Kdxy=I-C#e{V*_?C8|_eRj@N+MKJ^ zOWjZUR-XC0{QM&WmZ_UoCAFA}B$^b;= zLP&;*7JcU?D>7zdiCw{$5BcxkTM@zt#LP_JUr=0|^6=cz+pm`nAR?k7I&t%6Fh)GU z0U(-dx&&U z%8OZXzttzNW@+s#k?rVCR2$Y<(ISk$06gd-3Dn9@-IBCOWxsd*p`D-XlGYsH5YRXP z4N@GQBypl^AQAwM{TVBOt+#7_|Mn5g8&w^aJ_+#Wp<7-m||l^!qb}r)-1z;jG0Cr4b-3b=b4ziaUSxp z{2SFGw+Cwm2@PF!4OEm%c7HGHRM81S>QIO8^?e}c(%B|mX;R!s4jVYLiRW{kho3-468{e zap>jDBs+rpo&6pI1&O{psAfrdHLjfzREvWG^*GNfEAG_yD zli{7J48H}dSfT_pA)EBL)pN$2H=if_y5DGBD9%a%{h|+`B1J5KGAZ8qmyNB$!M6Kp zscGT68XDe3+`+WBtxIy_oW|`_H4+_5K>jrNc;X;U#gK`92ZK*8m5h0@Zp6bQwq_8m z@$a(jrV1CxuC(Jge*3IVB;`m_l(dHN7!)!+v^Wmd6m&7|*ts+8>FTk|tbfAsGM{}4 zlpyGl{;yC{@cj_Kr^$@y&h2xACWyYdc~pwGSy?AGi-EF7a9r^GFXs-y&7^0!CWv}_%;}ua>g31a;!P{-GEhv@bHhA^WfsXridb^_sZtmq2geRx z04z_If?VP&ICAyAurJw$(jXH4tP-H^5zYJfVlYl zx`KTvhj>!Qqya?#m&t@oY&))=v)ZYBR|Mh@%S)ZEnU`{XlapRJhMiaQ1K8^#7S#c7Tj^r*_;jimElx%&xbijmZ z)4Il}mQ_@A?%%%+P1viY2cwJB?na+I%bGhy1z-RwFEkvjcU>`a(-8YFXq-BVm-$it zzf&|-YySy2Jj1)Rk9q5Cr8B?QV`ju2j{@3Ys)cDP&i&K}^^P|kZ@!A63Ar*nV&8S& zow%Myh#eiG&%OAJPhl>z#hvij;Ejk{fR30hzHya*$lN^dn56(3Gon-$3dW!Z@8HZ-szV&TaB86R}5a-RH;GPvK3Ww zR~Z>7P+XDPdq$78GW~>@FXM9sx-(+mrs?Ojo?rZ}#WZj1(*4NG1lkAObv#O9~h#az*#S!ESID9?6y&W)Trj{2aPjnj+bg zHUKdlfIA&yL3qw@W9K3h8Ac+PfHfkEr3;x4>qJ*J=t$${?%zt7eMmn(RCGC1V4_#1 z8GD3KrQw3zhq**#Oli2OYdrBPrMqg|bNZG@;M-pZbVtarF#ox<{vRvWk)uVqF70@r z{+ReP-ztLD&KjWq2F-t*k+C^3F){Ga6SEIJx_8en~Po|l_+$>h~PL=(XgG|#OJ@VVX zzcnfdzd# zzV%2gTgphfqqK-$RHLy*3xm;oqwuwkej)28sVWHGb7>9)B5bK=#SSn->$xchkC^2? zY}M0OGi4`Y9MTGnZy7Qvpcc{EFiHgM*F4t4X00`F000&}t0?tx(xH$?gWx?m>Sj^w z??(R;;5&1HF`=o8fQaIOArr7*=mo^>S}6isabd>qp85x0`9NwPpue3Vb zHnsUiGaVI^G$v{dXSu7((SDw8%wL&R)Sw;7a@-%v|C! zufEQjyjy6zfRGS>hDjbh8gpI;Iqc}8{Td;2L;fw|kiw7Y%wK^Q!8L-AQBs ztpqQGb#6e)!N$BjGexVEXU(VrW-p12M=#OOsl_1@i z19IL+2M=cb(UyAtt8SbDOI!(iCdM?PNkoed7{rADzj7FK=I7*-Hm|SsRhQwht>6HF zNom+g4jMGAM5R=1)?Z;LB84O_qeucGA}sCff6!RPywO^CC4~^$zVE^d3}c|{qW%hH zB9M(hlzU9eOJUBmiAb4b@29lym>XGWTsA8cW4nVdPLNyyany#c>xbzNnca80;^sL! z4C?a57+&j#j#j6AFGb6VMuxm5&XKqS_USXer07}BWoBm(Ni+AHZ-(EC5{C!>3 z>LES3RIJ?sg5lzl#*mhGwZ5yRkK7v_Cn=EOA40SS1vRM{6m1@fU39EWn3K2egCEgb zG#D}HVs09Cq@vtA^%Ov+MoXsKgn><_mxO3QCZJ#aCKam)y2iny6KNS zzI$>M^IDdMrHPrx6G#G#EWm03nxL-Tt=@m}tz|>3=Tcs|tz4<6tLy!rl#awJL%TTV zpC6-M+79Inf7JwLU)dKywfj2>6iaqoLXpTAw_F$svuTRH$47g2*(qbIT@#T=?JMRLzb6!<0I*xYyLw;r!r0musrz7A^&sjT0x% z4Qzn0+M~G>74)*;Q_BWu0Cx%tBQtZD(A-N+y?gh*VdnTll|v?NY~NH#wk9FOf}JHS zLjO%a_k5(n$oflk0&NgigF=I&VqoWwa7i2r0uCJ5>hGU!(M}DhiI$rhK$twnwu$;y zVM(c}4YjpHwtosmCF}Y#Yqbc84jpQE3&zohcT!_7D9gQ!*&Qb;dauvl>DzkbK$kAg zSEqA(C=yOEg~~6bv?)A2ibjRwnGZEeJtxr=hDn4QkdoK#KV%XYzC$oFAUc^Q;SNcD zMr}1Hbh>J($6ycXHsZwioSzXyqIYvE@7aK7?53-fuNR!XJ<-JE8 zX<3)ATD9SHvd!WwnGys$#r;CgFir*EUG-Evr!4oJ+#g7fR;;c%q%IU&D+(coPaqY$ za5$+Jg9c}zj|?rp(|LM}r|Xweu%RfUupExqg7l2(Q2m^P@er6OMv|BgL)555L`-n} zyi0KH2M=B$sS>~T0YQE|bVlwA@;eVNcxk-sM0s+Iz8`ZbBuJWLkv<}2i)mxjp#R26 ze@4e8WsM%aKV5t*;olj6bR=Y1)VR}i+XuXl3~Rp>$AB6g_*d}Xz1nO$s2LG$x_Qpw zweLo>9N0v!>bXI$p+h_PB$?5PA^Evwntd|+&6~quVuXOsOn~jt8iCfE^eCe&thw7p z<-v+5vDl*li7Y-hlP)e^iH?|EC2QLn};GXLoKSO7~jpPmUg9#sBL|UyWqj+TN8|R>>&rcUv@oBlA8+y2L>4McX-#A+F)zW#c3zL3Jqy`9un3zc zj+cmTV15k`?P)O}boyBxG(F;sKz&Si2B@w{tFUj3Zr;D!mei&MJRQc+R3Jqh8gW@q z1pLm__{LvZIY21uf3={TXnN##i#|_Y04&HbHk1K6FKa}1Z&s$u(($!JRpv1@XlfEL z$WpboogRt<4kG<03pZs#3bYyDg8khYU{e`c+y$*cqO6BNS1G&3nA<^jnpXe);NRx= zC@wLfBB%<+Ni3l$qqwBo6tM|qUNNY@Xm0q#ZslcVIs*r)LC=e; z0F*;uUHUn)jcm#mMLNzx?t?qX;0)p+!rXq_!V@P4)g~UAdCX{5{Fd3#U06xZ@4nyD z#%0x);NDT_q+WbFmLhieXiKqR| zH=NO89v6)jnC<4tQI?UJ<#n&Fm*$=>9a5K{UVI(t#F(3-HpPET)-l`hw&^Ly)SaJa zc`nyqrut#UkvB$1(hBvj86Drn*jes$%q*XbW>*LuOt6Xl<@>zni3g!VWwFJYIr&YSkS zt+O{pH+ua7angI4-lobb5WVlhg_qVckNwm6QpxZqD$~XAM`+ zPp0MtO{{*e8VMLKQ(|0sC^2#3qtEHYobWa62`XERFvUffuohg5{5&6ml49iRJw1PN zFjiM>d2sV4OdcLPs-(K8ua{5E54D=QZH@KBEy0WXB4Q5_oWLESGnjj8bw}f0^*$uN zjzav3{qi?l9~}D}k%x^2dRwYT)Np6Fq}bBZgtE58XN;u(`WEwDT#A1GGdy-SF;M^{ zR^;IGr?%C+W5rN>(b0c?iMQ1Gop5&9b{*xMV`^Q$ew);+MQvRPCQaz;n6H)}5np_Y zM{z}Bo8&UryB}A?g>QHyViFRKIrhbHs1%UkJiX>*?bYazf37T1+o6n}Lrm&5HHkSe z9JSX{HX zEqz_Q>x^SqT=IXeZof(s{imOMpYW^1k)Hz$*$|dm-p0|3Mnfb>w3K8X0L}weJ4+@m z^RJtDbo?1)9w$-Pl$4yhdUe%H?XfC%)pHh&0J5-)oG^X)bS4@J+A@buPePS(*}Z5y zcnghYe8&9VtMrxE_$yn+oPhL3)b-z4f4unWn>9Hbq!lE;MQi>@Xul%v82l+V8>7f- zI5|k>ZPZF%MNLilO|`3k!s7*(U$IEZptWz7R<-Ju^|JIx#yv5&CR9;oP`zV`IOVAK ztPas0c!XRtN z`Hs**b;zlH{bFub<(inRM~KX*N_6S8`M^WI#(MWUT0P*v>cPS2pZK;i4Mn3ax{<)N zJE%lnf^v$Tu8xiZM!gSq87dC1`mw{_y%iSp(uM$w4HdBfKr%DUY&!o^ulvJ?T|JcSujT54&YZ%s)K3C7byK>k8*C<&N32;my zEsNk`$k82v1wl?vTD*I3Y@2Or9aOgjjNEcE8ZqrdacBvttJZej`iksu#AI!s#aGw8 z)B;<;O64%q?kG7auz4DA6l=aTc$zpipmZ!}R=xnzaE{M%&fLhL{Knp8osW#RqPFvb z)TNL9V=hr>FAepJGmlg30SKp8{@@awzk(?rn? zG76yNlc(Wzq1wfj`7zvfse?ua>IWbVpp>4|OCjdk|LRunNm`>x0WM@HYJXglXxZm5 zH}bLK=a8>2y?d!wz4d}(lTFNw+YE4dV}p|=%88gPxPkq@k5G4x*1vw{ZnU?~?jA%o zx%|9`Jg{G}_aU2z=K;N8#K{k?wmg)WEE~>m8Uq zf-`;^h_9wtb;+nH7YVnkEm!uxC|r?U-eL;NS9y7iUKEg$SjZ>pwXqw&wxUVfw#wID z#i~zT%U2wKXbQF{L8r+WI9Z5>Os(7zR0%(r-W~Ln9q$a)_EkzRWy*TCN8Udo zk7T6;#0gWMjeL@jb?i+T+I&@(2GUym%D{KT9g?ZVlMIFVr~24MTIdJj&BUNTVq17p zjN)?ckFNp{lrJp9s~lgxaPE;s$A?G1Xz}qvPi4no*KV(H)uar3yYbgDp`iq~ZP3ER z49Nq6DjvTufX)sUb;-^x_bASFzaD83Q0J?{w?`EsX@Zx`l#%>boHjpV=b4GNVHQ4X zj@HGuF!xUtrvyRw zX`Au{?&s&@%`Fq$U;qb_8fAAdq!#pl0OJ!^oHI#X)`o{1rhM_dti3d$C>Dzru@5*s1~*%IewYF3FLptU#L!pDM7&VJ+S*3-1Kh@zZMaxo zp|hTxi>N{7$3aM?dnK+SJEmU=n;g~fO0G)OJ;k|S;&`B``Jw+2@0cUW$w#Cq5IaEg z_z6~ZKSP6FX+H|dEFunVVNBy)xd&~8$YT#4Z0qd%(0D6$oztW~-k^}P^V`)|OJ%B` zdQ|Mc*tCGaM1&gPge`Y$>HXkEzl-RupjN;D;AxbQzQALQ(mO??1^8qoduhB|H%1@b?SL;S)p;kIUNnEKjNuu#X;Y4!;A3Jx0l!+tLE+!_vhCBtLG3cK zNa@UB?dW)Ea|dB|gvds6B7^kkU8*uees7s+c<61Nj+KvM-t3j>TXgHn-gWP_u_)q@ z5KdyDLcz}1ZdVk($LsNYyp#kFmV{QVO&C^ zI>(!c{Q%bsrP|`nS!-|D&){}15<~C7opw7*6N}+MH?#u_5orlJxjg@FIc9L`SZsn! zQBPYL9%?bjQeQdwX5sNhmctO-Et27#zutB7=!p}cMS(~A{H!0~I^X%Uz5C^6ZJ0Iy zVUh2O;GQeWez@>{L!Yxa6m$f#n70H9ziokOe}}mqY?z?(&tuR)L6#fH_6V@b<^~_z zT81S%71Ry;La_w;#=#RgGW;1C8Tzqc#UKvs_sU9s)nQ{-EovT+_cQ-&(@{62$qQ$tvLe=IFcUI6jSTJR-)NerDF$UB14|+NBh^t5PCT-tepd-g)_; zL8RqoqlU`a2jQe~VlI-)RxuJ5? zrXwQ8H~ToP-^|U*2}|Fw2{MhsibXdfuSY5Y2&GeD{iMj9XehfysbIp3u4fgx4aChu z=9Out+U`n8rjt%jta*?qLl~zXZW+gxyDM46PkvqG85?m72750L-?jsLkv$UFJ! zHLu&OoEL7Rc7|#MrwEF2u*#8u`@F^zuy(TLU7{;U-b&z5+G3GI>*$!p-z?p=%`2z( z#fP(16ule=w_a=aoqFkNCnC1@$vD8hpaJ_k*hhq(DWb>#a=+;{Mj1^Di2m=H%h+g zINC0x`lkZw2!9ItLsDZi4^y?%M+x|>gyyex8O${WBzj1i?uCfN}@B`6FTqCq48XSIz`;p)t%1{DqA$#uMEA%HavbiQ{?7&5P|I2Tk=cp4z&nx< ziR$B5rev*+Zl3UHsz>vGhN}&8G;EFTu$hoO`0R@V8RC@&4Od*f?xH z{nz4LcK6~9gEBh>d?F3U-TRbG;UR5G&J&E;B#;gnP|aEkc{0f}TyLfzgb)*Gx+Lmw zYPj3voDuZ=q7(ze5X*|N4CUR~@twBcPU2-%=WEy5@VaFK5-l{bzb(ah+I(GJh}lss z4MWHB>eh;RLG4?G-t+1_m6(dY)=EFHH>==@P|PaF&OHCw#rSpo0RNeWay(cjv4sz( zP{z3E1%~Yedhjp|E7DB$rWEFg%Zwp#M(WZ5BL8MQjV!^NqV7Or_h(r(k5Fs|^}BRw z7&r4@ZqePRt6Nc;($5RfXFql7J(44PL^j^$afk~iP%ufIgv3M$bs!SU2=&m5Wtz&~ zy)OCfv@eLJx`X&by9>=j9CL^XjY@ZFIwC>$sgP#0^1NYKg9W4&ID(Nwr`PN}`RTfa z;h{j}Z>TV7$M-ItBeq5yb?keX!9&(gnT4&ZXimI+d`MAKdmOCyPga;8DU61e0*^ly zQ7n}u!M;MXyfo}b!W_$E3b!JHftj+Jh#yiP(Jwf@x3x83!8qJ!eRss;o-B4=Vr$5JI3 z`yZ|!DAu%CVC?|vL~P22cxz5Ya&K73;}il(;SLRA?T=T8NkJ>!xoNlc67U| z(;t!YN`K@vp|cFOSFC$;91>9;@lTDA49(`eQr11}jh{FcJ?3_;bvrPZKwv+pz$V#g zSkA>cr|t7A)^TM!Vl~LD0Ren1GDCrBi7$i=zxxrDnES%P%U~szJX9`X?n<{PGkKpY zWQq<;8m$fAF$`(n?LgzIMdja|hAbMca`$-eR=#Z3oalu|J+@LQ#j9JKPE+%npfXJ6 zA#gU4sZfmEzM(qvB`}4(_-tLV)^EY@?sfcFKR*pD2MIdxqWG3e{stHCv8r!n;v=U< zP5KdQaAWv}5XB^?}fTUR&K0xSt187R72 z@)InnN}Dznem_*NYrs&k1VYFdLAsrt=TcgWq3)p{9_r27jm{gD@Z!v?rI?zI|5*yB z!?0Ad%dbpwKUgh(xhig^6uR7)3A1L&0xvNfz|bI%t4}2k%1gz|nPn_syLqT6Hr#bo zqnGfZw)Jl5TeE8%154A;Fwv>X)=kQCQE58$3;Q%9hA2b*0lv5oIl=8bp|Ruz;=#kO zE%`CGam=mC_|Gf~6EJDua`T^FkSjpU%t$o6F)Xp<>d$32k298wT^gEGEv8i|4*57} zr=^^6pR+nQIj20omEv$ULwRhV)*@&?&_OI9xGo0GHRR@OBal|`D*4suPs=?_L<%ZT z6B)$LCXWmXSHy8mWFLfR&IzCB6S^80oS?9#WN7-b`#I*jFj|_U9j(!R&x?y*(b3>M zNLMU@24#2~-6|u7;wFOEiW%e|aJuxpfS@7BW;&Lx>~u3makz@h-NVY3zqu)txKtNU zU@t^CvmBRgk}W>hu@euQsNQC&-znHc8JWghozQ7ooi^43TO<6c)l@!i$&j&y4N6P6h8jQh<5cBKM%Kfr-krvLgO(Yu&R5^dwx*Gr-U@Rdg{1r7{e zLSZj+w#faM*IOhrPha=kAQlcfA4ND(9d zBFHwta!B^1(g4pC@Et{Gd((|Io0@HM-ClQP>VLCL&!5W_9~+=Z{77q7Al2Y^$JYJ+ zC7=VugM2MLJtS-pLj^6bb{eKc;P_1%J5k+g|OjIX@b1 zHgkb52Ea~J0BeS@;qVWC<_0Ha(gLKxJXtCgy4^Qg?3@nSMnVJ)boR0p?IUndz z%yxxt=+I#duY|jee6e-ot?qU69EOq|F7+NVzQAjmjNf|xcEDVVJhQ(VM4 z@h!t#KUcA=fmzQd*E%p?E-u?>od@y#O|<-DU+y+fm{)}GgohzawD`mm(8jl0M48Gd z6a#+JJ7^2wl9YU)1{B3~Ot-_R{lLH ztB(4;3eZ)n8ZJT?KGE;0d=C>X;X^cBZ)~1^ZXv>PUd9=-^#gq}?AJ%HTC?UdB?jkD z;U%Z#kDwbh`O`*I)o#{QR{V?)2?T_699LJj@v?tDYdKR1q5|$=y{Z%ZBnfgq9ZPd*O}1YvJ-&I zgvv!SI~+8M)+5xO01Q}TBR|?ywjpx1>$_Dwl#`wMp0f7ch9XTsZi-XT4Cv=@Gd8{V z`I5D$%CITfg21|xY5wNg!*&xZ_#`~@Z8XKrK07vc3@p9+G$SL40Q@hV2my2f5<1F3 z1i^=W*xGHM5y$5x2_9V5_0fr%edF1;U3(^i~@MpPIfVCDz zRx`VuZPPAXKAgo6H8DYR7w8iwk?`gF0sFHiY9GYNm_ue*;%9M)b3nW!Labh5Gf@tjZZ7q zou1@q{O;G}k{PS8Xt4x`FTL@tIbGf8paFhJ^ZJz$bs5&$;vb5Xea?U&l;aI%NB-6W{ZUSS zbR7uT^~jZHi^Z)R*zH^1c5T_m#m$U3pWwD6>0V`D7$QOaIN1aUYL(!N<_X0uTjDzwu;gKr?H23L>~XOJ!du|GXM zLtqm{!1QzaOa&v5sn;Q@Va_2PI+rCSuj~u*vt05Zq}dV?g4={hRM{9HnDCY@yiC`# z0VhknpQ7TXg~$3y1h54Ba=7qbXzRKTz1fXFP--)zB_nw_CviH^%u;3a*Qwf}(uqLjSyF9Z5ad$! zOjTkKzy(aq4)aiPA^_apupsHIKj=U6a1``X2_e`zjB5JNLOe3`x|_denDotCShX=4 z1`9I_dXfm|O9;{!6axdU+oZG$Tpb%5yU1Tw{_JLhRSRrf+qZ9DA~lT|X4O99&k*3Z zVk3hTYt8Na#GtIF$~04*E8PvgmMZiJOhc%VcPO!@Glz|4tPDqbOw$CbLb@4~ReNB} z4-iV(;faz4nn}0}kB5PKO>OW+&qA@d^sKpfa)Y7cqFv#C#l!LptL;8hL!6y76Jt!1l1031i+-%;QFl;(p6cVYX;c{m}F~%$Pue8P4c2sfZL4 zHnAJylM&I;W7U^kp(T6&-Ztwor}U5D!5Efs8bcv4RX2XTULsvJTnxwW!qgso1MUQB z=v&3BG5JrEb$Gn~9kZjgFHD@iB`hGN@;ZW5M?4&$9b~H%_++^Han7gsvOpdxz#hu{ zECD>X+yhkB;d*D8hG&09Bo9KS?-2Tl!vMuKv5zg$tbAjQoz+PgefyI7~t4;58x{Bs$`v1LoE++nR~kUs?#y!5TvPOSn`ROj(74%-eP2Hx26ZKDlaKmn{Jn zXc2OAa?7nvf3`&E)r-LeLjOOoML04r=R~XdzsXVG{TvieW+YYq+PXRMGK1vhqS#_c zj**9Cx_TL0pkXCY(&T|Nhh-RS)j*;Ljv*Bh>0XS8B}t>Zr4|R+ViLn)io223dOpQp zkq8azU+Rk{7~#C-9~A`jN6eMP{k^_c`G0vvk52Ls*&qiH=0gv-4P7JFO!RQH22_dt zp6Lgs@zaGICQ%epfxZ7Xc+}|8O)2V6akc0>=Vmt_!3$8^_-?|_wxqJ}>uNVmvi6CY zreYP1R7dc70AT`~NP4M97_tk0oCVOIReZ4V)d%>l`uZk+uAn1ec2UFtReeTV!yV2W zVI%#wO6bS7)$Qzdne`h`Revm06+NA3B&aI{j6q$>Mwoq*w}XzKSy|0r)wM^D`JgMK zkDDBkzb!u>!UBJ>)wc{zlBjxp-D&UMq{hhQG3KiA^FG4lFNW9XJ_(Y)B}@n45v`#=-=>xrv5glJ~9rnv)Aed9X)Rg)rkW2M*pr)QT^WB&3HY|L0HaE zo5{AKKQ{IZT_3~x(DlZ&Pi|H5TH|I%Pno_kal^0G303c!i26!&<^KMMP9-W3ZPwz~ z@Sk9jGq)Ep>a)eHe4n5`PF0SWQA=ONG)BH;Rf~vB#7DwJEBC>&E)?8YyluZd+{-KR zd+O&3Vf0=t6-?*Yv4&f8(G$d&9Nd8vb6g415 zd@gbpm7mPIu&(uM``SPw#b%RQ=in;=;^dlGJAl(ENDAP&?0EP?vs)bPvx}@iRFX~t zaG5GAW#SRuwwj)KfDXSHRhC!@@vxQ;4i@$|K3a!XAi)FBx4rVfa}JyO&f7aO@H$u)<};8cgmlCcON5_UUJz zT3)_*rf%Y^+=z1iE7`FC8v--4mW~|+*c^nz@|jdbi#%*4uwC{D z1JzAl+w}abEEsvg8$z20PQsS>1pxRG<9X4=04*|sEbD!WD+hQ?$h@BBwcp82?JHe} zW^;)<48M(lMMsP+&bU~YP)4BhAlnM$L1q$B@c`F~F-MwBy3=z&U7P>@?(<<(;#hc6 z-=iwU1aWOafHhO(1s^`hcs1H0Sp`KyMG$Cz`BjhXjp2$7>dXq7*m9`^fWb}}mH=U( zxGsZ;ilrXqCRQ^hWw#m#4-YH>dI?6-z-pV-{Xvb%gSV~4$>>MSnqN9wjQsXDIY)>E z(uV7BqdWn%0>+z96+x4R+~CaFv+vL)(QN`4`KHZh+|Wj^>zdCqmHbtzqx-EK9Lz^A z2W1i#h~z}r$wMZ75{MwNrqD=yZXrdu@zxmCfCW*jX1l4oTnP9&q%}9tC0N-~?;bwB z_viPa;RP_0z7{nK?H(FaN14>Ykreq4bB#Ni*>sp)(;K@>PHUQMar6y+7!`KD-7FOJ&Q9F6J4=xu)v9HN8rn z4{B;@c!;oNLvUseoQ@JA$pQflj2W|9? zuOMs;I_0|!e2MoFtdx8b&Of&d!Na}6uhB#8T6**F@3w8}yG3Js)H7!G$4#2lxuPfR zp)N8TtSNA8zVd7<9p%sVm|8y}&jHG#_IhdY@PpkyzM&vKsQLEo3x71WaK#`5 z?II-yreY>F4ogH)oiG?e!zQe}va(t)-Bpp^DY?%U5_x1r6SSf@#6V;S26}{615`!k z;Mq$A)EnWb`6-UHu5uUIt>T=IDmsB_;?pqGP+Yb@ew;%J#Brd-$LYlt>p-T(>ymU! z9~;ZxPQM1OtqH{l9fB0_#kqIt|4t7J{n@gDe2aES4n4;Y=U9QkAaeJCwQ}r;=O-;l zsopxg*T?o-?<6eT##;dfAbptV;WeTcF>M3eSNnbojtQ$I`PK7m@Gvd9K z|4>b7mH2b-< zJaX&F&?aN9^qD*;0Ek|5Y{&9MW7q85^E_F>;@pVL#a9U+7$glW=yo-ff5h8Y)&wyh z#sP6-vKG`6z34pLJ^%9k0}C2o%_=PSaAV&(*By3hIRFx}Bg`7-V`jqdctWR#ji8dx z+?QHYq%NzyV-rwz)n)bBC1vhM?IOiigy$`r*p@5_JXjUN^Z$#{@SYm{RNoNTQUh%v zWhHH7J{wfJQ^TUn!HFT6d@QbzXpH04b$i>=UF+@!;OOdfSC7P7&8*#(q6Y+~%@<=zP9b~$%m@}VA)H?NGctbinBZsu z6-oo}=uR5y8tYKsxUm{J1|;Vjy>U6Ng)0d3L}0CcBW-3gKSn;we z4NVK2e5$`!jiZA6VkE$AcNLyWpQ6}V3W;5(yQ*%>_B(Y8=vzk9@SS913ziPBGO{fU zD+w}*;KbZ6r>n0&OW|TIQlVFge|8px(?jyEMGcR#lf@0Bn#DV~Gg~xNLv3R9Tw3oY zEAYdD>!JN4CJC@F&sDg)=g%)Of9^c3?nQQFX(IJ22%!|2Kl5|NfFRdc;~;;+Fertrzkm-XC1JA6yH;=*w&-_HMZT8e zT!WLRoc7a3$yk!KNFYZvPafo|weNOzk(JxMf;$DKRYlkRG@`e&Tea%ymEshU!dSEz zdIy0FCn4wl{wMZ&CU%jn;%4rl3gnasJyj^v&bU|LRLO@-P51i!tz%41nQ1!EDTvKI z{$M2)mXtd=wIyqq?EP)^sJ-Qw04lPZmj4^3k)-5*1vE~alf;@_X2~%#A=q*T_XP$r zYl-z@y-KkL2adrVg@%g|MBOQ<9fqN<70IR(W0qE}sNTqvrHrHKTv`2f0o5Cc=pCP) z91N`<;Z|@xI5j^h&rN1P#S%xBup&fwi6_6n8FZ%+Uw<^Tur#1nj*Zz-bh+ijx|44} zbE)w~yhPCs}@1`Mk%Xa$vk0-YFcJ0z>JvXb_MDpmC2z>a)Vm=_V3y$pia zq=49_Y#BC!W{)4CVv()sG(Z5hyi>4UG)VK&{aU=8%n11(4{Dik;OAKzkx zbIv`GGq&%jXlsw9NTGV7zgdxctDb0`(J$}_=?6L0025C(F2O{D|H-QmOdRfXP4OGK zD;c9W+P7j39ZH%b7z~M|`OVqs%>AKnKY?&vtg^GSd-~n2s=G`Pfk-3t#b@FDHa&KW zvAwSp-RYa(PX)jzq&{ZQWYkImQ6RvbFmvW^*ycYo@Gu~hQ#=K_XAw?-A+g)K^!}hm z+^(=7p2eoo`i>+u9FG+E!U{mxT~Pb;J|Dk+Z43WGfh`B9V;CR|EFFGMVs$pZ&&bTl z2`!IapX=7^tI_cv9wykFlresrxBB{8kZbXc`!n_^yX;`N`1s?%HW_rq$@_nO1Y~mw ziuK;D3c`lV56?fDWqKI$G(Pk|7+R1pW~y>S>V?4*qqFC)MXCe*IGBk`0;*?RDi)s2GvN6`C4W%XGGKXyV(HY`H1u6FX6$-U$QHZ3w{G34_aPFb z@K0|`e}+eL<))Thh!MkMr|Et3HF(pSdY3~1V5HE%Jb-T!7bnw#dG3R$GZ-XwG;=r^ zF!*R6kGjjCUVOmDTj$;K?VnS(-Dt@^PO{;lQCm9l`|_^suuqw_ALAx#90_LXJY% zyBaxq0@sW)G%(mfxk=qjbwEvygdfCX0X#jZvh)6XQ*N0Y<)36vBki;RIu|c4H`}}# z5>}KNL?Rl5olj^0RK>duc&L+@jUAlvy!fn2`1n89&@R)8`8@kqtjLE4L_0H4XMC&dr)&$TgQEv2l;8)2Yc`2S@v4cs8f zc;xMjW*0Et(6M{>CO2oBF81}W{TvJxO7|`F2j>@A0=bq7i~GSK1qDkVuzyM=)Sj|u z0JjMgPPfFt%gG7vANU7rb93*B`wb-x`s}ptcOPvm#RwHSY6vMFXgfr#NV|9V(R){u zWj~g+_dG_hp+**kA2Z{^o(r@iyCXi9mLl6>VoK?Mr)MzBN0Os96hjFDmDH}X^c7(e zfIT}d`^}rtQvTvK{;_>_uSihIYhs0+0LM!fuwv@#k)7`U)J)N)|A^m~PiaTlP?}e< zPO53Fx<^E20{b9ff;=x8R94HtYC)uF?Vq6yKC$%2B7La&Xl*K9^(QgcGz>W-{k`f= z^Uve%CypIUcMRHo0;YtXMr+;2j=*obCP#Hxq2ZTRu}tYKM-N`_k?ej!2>jpfIp)wD z&8%H=mRI|Gb8QJcKrK(MOoxXe*b4y$q{Jr!b{N0COd~kUrg;G0F}X}Nb5YoCuY7Zd z)DINaG~+;4Qas4&avY)N_&W8Q^#+mw2u{|3iu}1lhexy-Qd)7-pRDZVQQEI+(bS0s zt$_-ORj8&IdItATm7zNHH@p|w&i)sftEcqc?Q3FU#`iZ8g=5BY8y^<0mL(9I8#Ii? zpHiwj5+zm0n_`P!R=mn&vD^aP0P|x`PQXZa_wSp`3cjrh?F=;lI?iJSiYNSIO=wiH zYC5Pj;=NcG#rxKZdQ$iK5bXE5j<`K#YAw?PDvY#(*53oSu&S_plV9$}SOZEuN^Ht@ zp)!~!I-iyK<@1086?Ji(PxP)~W*bhb9<{V*@aYF3Yljm4RKSJfF97j!<3$xF*T8B~T_F zxEg?lHi12*caznO*m=oFy0A?QAXCy{Rqrym$D6Z5Iw+~F3nV9V)OAC>BNqGc^DSJ>kbvBldeVROU zeU|&-HUJ`{BBVw#nrN1QTx3iMj1NC2@r52A`oq4mi?`H+FTofMU_8w@aQrfHKVnfF zm4_@AVT>`E9f>bqG~E4f%citC=r{!f1PS9|^rn3|Wf$DI*Brg9yn&`UI|3NS9y&Cb z@|{Xo9Caz*MHNB(eGGtzt&}lkmbcmlD@*?0bfd>a_N|GYp zixM432Yv0njn9o&t?uGqXvcVM1V%$Fy=-%2^j-0t0@;FQN+=$DGCJS1_7r2>4Cu02 zj?an|jOGSg{nnHRY4ekp4)7Zo-&8@NMc|5I@}u59Ue$0;lK>7Q;Wg?J!~k0`AW1>pm;HDz90$%n*q&cpEq zN}1OYJq*|o300zo*j3Zw0LjWFwzKQ>!!bPq925XN_xL)iYR} zj5*q`+nz~M?5x#o-6)3=IfWznl5QNsJW(9g(2NO!^P<1AW>H5+x9!X1uUM)wYT=e4 z$)*Eq>VA|I8=t+jE5FJ$-F@L;i?Q}gLpwKaY7=m+<5kUd9ben(+SV^uF?sW9NU2}l zrkyeRcb(?>&h{|#X{^5U^-JGlwgoypRkm`^Ze9DK5PW2H^Xy-1jo!Myows?-^w$sF zt2UlD4qSCH@b}d8>FL*&&8VyS=1()*H@VO zQrYtG$_d*e{Ce|me!>7f%gE@Mbq%>F#!iQhrCeOLez^M%mqi_)H&uuox+lHYhf}NV zNkHy&eH(aPyw&j=Hr#}9J)M*^{J^0@-I;0K(?mf>PsO*FQI7}Xbpz}dEs7k**0EVP zJjPKmuX}%F(G|Se!Qz}4?fqKq={`e2q5Wq2EorGd_Mi zoly6CJ(De6aq&qXT6t{smzSYbkL?|=xMauA_}y%?vcld*@)<5p9Zf)zyOq31Ey8jWu?C`;-BVli+pEJjzeS#a!I!*H@pb zzj@Q{-f8wD2G&=Y-`Kq6!Y?^XzVnTk*m}mnewvvXMrpAuCt((2!}cyN=b0BhVAH8} zQ>DU+b%BY)b@(w=er#EvrwA&>0CWDtFn5x@{RvP3CoJVKoe$`3Mb9~D+_;RM?fTbO z*y~)?eQWz8KSQTvU2Ef?3JH7)J>+61CmXoUbp-b|J4Ya!*DflK$$1V(vfrlDlUaim z6xLW8nBPC86_k>{yjjzxA5lR*CSygQV|IeNS-f=V#E~O+B1H|Sv@GKJzQBO4k)^_> z-Kpj67pBm(&6{Vg?NxITA>>sw!NqTH&hQ`l(9CU=s{f&*gtM2@Wit{Ni_9_Z|OWl?|XIvW%@xeox;Ou;6#R`vSyfweX ziHE^@P5~8u#@lToN1sCW+2hA2NXDI28wDd{53m_Q74U?~_#O<#9^$Q)AMR>ytG_*} z=YuD?xhD`0gfVMU?K$jbS#p!t*Omn_ERdXc0d)I2jEyr|Gj&bPW7m>fD46N%w(i*Z z;DR)@Fb|XSFhCy}MeTF9(}x{o7=4~`^X<>FvbsC&1|>X;&Bf&MdJ0Xv7yQ4Lt_2$E zG>U&DjZ(*0X-1AV27|UtvT34|$!kiCXNGERL$ReI8A_s=Z6k(iJzFGEUWt%LHd=W^ zTc*-O(_`sHjVOzv_BYO+<2c9RZ@&Nc-TS-uyZ3kR9p7W^Za%6y2oNpK&tC@v>Ah~9 z2)=@srzeA(;E+G?<_!-SR1|F#L8ChRhRE+Me>PuT72?q!R@eV=BEwjjETM??&jpNFPK*sMr$>VS3~0$)6fgnNOkb65_UP(v> zl|z+3f(|Dwliby;#rjy) z&xMrBQkkp_K7N$7o?@F(OZRrE8i_r~flAN?h;bGOpGG;NiqRb?ggEEPvG2N-aN2fa z{jQ8aer1SX9?uDHQ@LaV&}w;Wdu6F#&%anSQ?alXXfSjQ>?CAO+_~J2#KR(qCQe2p zA*Hgzg=eMfZLPP-);12C27J1@bwPvACCM4&*>M07H@XsJ))5I zd0o(-RvI*upH=|9g-|hd=b6#e|7O!z9x9}r0U7QJ)dhLaOoI{xM;}H5M}2wT%IW=j z@ot7m=H&Pw$~o>mdsdDtX5%O626dkqq!M<=q$0#mBoeWsM$W~2dA|}TJ&5K4&O$yR zU33oBeH%XwkPqAD<>Lc+GF>GxNI%X$MAk<57g9`4XJp(NAFqW0aB-0+$2HkZ=~+O| zojKx#as2jfB0MT50zAZd>ZY>=AJr`7(6?Sxry^ zTnidj5b{bZk8;IwBHKcch^eXj(Xu>ywa^9s3vcc$jKacJaj0LHrFRzKf~&xONgtD@ zUf96Eqq?G=+WeyO)|M9W+3pL8ESPS51(&Lm*t)hgmhzjle6W@VFb%IhdZLnHIO7EC zXy-yD!WZ$x!A5^c0{QSU*h2XqijIMeU*rwAwys|z;A<}oBC(~-&Q!Un_VM6=06SdM zb!fCZ7!TKPC1J?v5ZeVDYGI~M1VjQbH9AmIZmJm{gsWu-uO$TFuCcakSA&h9 z3;M^tyo_kLyG0wvFL9yDi_6M3f~n#Q0&Py@KWYk_ypx)+*AX)S*)fx~3O5M`KIG|D zK8m2opo@cW2fjd;KI%^i3 zl`5nz6#Fs==t%;oM@7{ovP_vw^cHgxav>P2x8oNfy#qr-m=TzcAO$>uK)$vNxZ!P} zWh*`W;De!|C^@7T5P%C&YBXs&6xV0bPBRcB!V!ciM1zrX*eP)Lyu7^ubxfI|GBFnKVQzi~v{uFOH~aH2H7tEa<0%!gw&sPyPAB)U?M(P$$<`ys&}Zc$EE$lC`wc8} z5@3d9Z3JdGI{pR*L7C#-epaEmF=BmZi_zX4OBdX-BTZ9r*CL(Rm?Wr(lQv=)&}VcQ zvShPwR?x}wKW&*DDVV-R$o5p%)R^kdGluLs;K1wPe7suFyCbE~3V4RVCj`lhq3MRr ziC**52%YT!*=uv|KD2vaGKB%PLrW|8xE+I|M$2{wH0h9(_Y`}ltg9_<_4_*$*Q$`( fMH&Dz!kC&BbjRQa+3eiA_=#}sUFu5e literal 0 HcmV?d00001 diff --git a/control/mpc_lateral_controller/image/vehicle_kinematics.png b/control/mpc_lateral_controller/image/vehicle_kinematics.png new file mode 100644 index 0000000000000000000000000000000000000000..2d0eb5f26af71194dc9018688afad2d665e47bfe GIT binary patch literal 36676 zcmeFZcRbc@A3v<@vWo0oMkSRM5t*f=G$hH+N+L6a?6NAAM3j+)kd=&#q$N>ynIW4H znZNhZb^o5{|L5`H&+l=3j?d@4j`R94-2;s4xYtooP%vsA)HqH-v8IQD zVy!404SvV+s8k~UkIGq1`y?HHdDB^j;@`PkG!0x%T(WX;H@keE!rI}|#q&FyEiRuw z@8E26$z_7_wK9H4+V-S@i~8mBW-hju90X6=UObQAq@a-6B_-WooWDzMAU<@r!az)_ z;BJ|LSbtgh{?K3zC} zjoazh=WM0nv9C4lz3g^_Z}D>Zr#j2a#j%UkvBkx=btK)j2jUM))jHf-3i&*`$4 z3B`sD4aaL(M1_T4umV*-?R!JRwLI&3b4yDqMYmBut>kM)lGgLe z6d}piLv3^oB-nrU_diZerM`9R*1Pxbujz-}p|2?0UVJJ@uP-gq_@Pl6d=cTwfERJlbrN`5}P3f_rVCdrNW)~rU@ZLT4{K7)D z$HxSB?1=EXmUf-2hO~LE!7&4a(DfXW6<@!yrl+T82BuxFZoms}PEJl1mypm!?k(YjSb33gr;A6{2iS2||q+E=b4oE6d)hwy+;bnHIumXQgxsEw?w ztXzZFqg%JmoUWdNJlqpa7OI(;!-JkLl>ae=Kc#`&%rMp+VK0d8T^Yz}b&H(#%0hO3Ihm;yTq4qTK2H>m4(k_I2puu?5N51nce<# za8Nz{WEIwSz-QF;QYJpdySLrlf}bBMhBP$jy(})StgB=67i?X8VKv%W<|QsJUU7H( z=|^9OZYCr|R#a5b*XJFe+(_DI+tc*)%Gr^Y$4z!ZbZa&A0@WVp%$=_@FfkEWSX{(M zixgOy48e@?JO1~`Qbd;D*zWJ2an2ruq$IDc^R~LK!hWAHX^w;L* zU{XO(pVD1=y)5VN@1Ln&Ki#lYCMBFCqQRz_pP%2|TNC!~;Gdn9JEzK$w`)NUzhlz=aj*01QB%k8V+qc*5*;AzOszfZg zxR~q8l`GAf=Nsv+<=1oFH&|{j;kH7lw#CZqIb&iHH9Tx5&bBV|TnT$_Zmy%ND>cRZ z-@j&kZzCKX9V$ zKHl5G>a*)sxxnH`EA=JP9P$H$f`iT5UYvjFGPIG2Unw-}Y!M2YZ+v{bdGKBT<V7MI}oqMrE?w89e?E^IY1uwqyvk7=l zR?_|{rxQ*})!`OxvXLQ2*U4%3t5>fun>Mhq1$K9v#+|Ci22cL}{etOKz353TEv?C> z(}nT*7K+@8yu&|#Qt7cZw6ug^ zr5_a(Y&w*>(Z|OJ+nMmS{*H1{em#(Q^`o|KWBSH>?=3^a!`~EM?6?^d6S6or(f8%CIz9;&~*G}1vI&Pl06ty_8h6#{Im^z!y z+h5QWeGGfQ{q*xdJQHSa`O3nDrJ&< z>{@6pa_s-G>03)n-@99z4{B?x>gzX$&rL+``&OQoMoY`Y>z9$ST}oPd0|&>Rm?GIh zPcJV$jJU3qKSjSrN8fl&l!aip(^r;!As}Pa2A~7OqS|ETH;2(n$2DloD5uu)tBNPL zZIa<;EMFMj{_Weh?rLTg4M)da<`x!@kEcIbKGT>}1o-jg3k$aYW^{DG{QUft;++Ps zIzNBbjaPJM3Sr_?yL4%1r}y*`rP*&MCTC{y=R`hpV-UX6MO7TbXx(|Bd`&;2 z#<_l9NQoxAYTaS~+}wxkf-hfQpJrXK@-Gw9P)a#{61dp7e_s zFIf2bBfot4a^;j}q{_>r^mKan@$c8#?BAkOPcC*3y9@zFQ_39*XVFd-Qp`jspuRjtrw6wQSDy^-pwjntuPd%u!qVS7~ zVm9`k(j2kqJ8JuYIpx_^>^eq#XjoV^Dy#d~FZt}}&T?b|N3~f#jMLD2)0A;~D#K)X z-SYCX$DcOqT-&ct=$-R~goHw`U%!Ud0Z8XK{$0WT$E!^jnloedSZrmuDRK&(crTPw zb3V=rL z+lE=}I3{T5_)k?p1o>;7N7S4cF``f;ba;JIq(;RX`T6--s48FipIP|*=Z}`Xy@cPTcA0hlyZZOve&!JUJ`fFe zX<~I{CllY^nbvWqCn<|tw{ESR@R?Iw8rbt1ur#NRnI&ukw)+?Tt+h@b9-OC6oqC#) z5fB~CDkUY=JvfMoasF$mx@QD_$J^Umlus?;gEiKglY!>vz(DUnUEHssq1Z_!ui*G^ zN~pVZl6T6knQtGQDIMifFG>`2QV8l*GJ_W?qFM2qptq)*|T*?;%aGMg|=+5tXeb6 zEd21u68fr;k`gaK9RP@5TACQ!I_mE~e)Nou?X%5`JPh5qeyYiVd`GQ)DW91m*y^2P7NheN++Jwua1>*Dro zmXf;sAu;Wkc=yoI^~_8OyvU=>OorFXW0!zv{4VJVHrmJ>OFxOfP;`E;U#p;RfRdD! zmfpN|>sm#{{*m|s7XjzlIWi$$FL%7w1l+@hKhn<_>@V-Hy+$@M@Zj{z&dyGBiNNIK z&7?n^JsT!_p;^ac<<~Fq=f-6>uw%dx8#45>)U2#TmzI{E@akemFjYMIBKELs+7$Ho zv5--@H&@H^b9oNSx1JvXgab?~FE7V_`5j7CGcw{me*E}=1RJ$##ecL3pY-Qt1+3Yv z=;*v(li}?QC2whQd z_wEf7<%^QSn>VL<+b6OuNJ>f?6glwW_y;rckl~J{1U@*EDCU|rjOl`oNKw(z!PC&t zFgZ098_j+Thz_tpTv9SPF;SqZs;YZ@ynIXb>7@DY0A}T!IZc)gJ4Dc(FxaGG8UFtL z`!q8%U;nX#gTpTF2>hwHzRNAXJs<9FCrqSdqCD)h@s;x*Y8iE#Zyd*SVB`b6Gcqzh z&CX8TMZ4pMFdi6ng3;OOvv_gKmMuE1k}{pi&$Zb!UEJJ+_w3==%#?hs7|Wb*jR%+ zD@Mo!-2(%E-W_{kAORX{bMa!$j}rHu@$tx%lr3>uLVy_rD)C$@H7iS)T8su2ntC|l zO*>IG$8Th0#9u5jtk=>6a9FRh%DebyECBWG^E*0G5N-PT^XJTb!^WdRpL%S78Blq2 z3=H|tX~u_#UpSn*t*^8A_pgwQ%(qtt@4@fp=u|>yS|6*2kdZSpGeyEyJvOJg@pGeXd9*b(H3xNc-b~l4LlLwYyi6^ggsTQ-aGHO^Ud9FJsvl`i39XK(*zr|;jxSkB%y>qJc#m;Bk? zrsg+80s|ktdc|E(Q1Cz6u`;c)%9@an@H8u{=Aojy=`PNk%l(J2k}8fHnp!7nY0FDW z6ag!8?b}{xuQI*uS~VZPDa+rXzi~rbWglHE@Wl65uIn+`E5YVA@bf#IC_Z$mXvP}U zO;1nH;I+>_phygqkhv~j0Xzul2a}|h(5(}F7Pb=jJ1}51VjUsC9m5{DX8-x~BF{21 zvc#0Nqv|x{KGp=^#UK z(y6Gap~fS9u`3`Puo!;Y130hgy>A9Yqx;uwbT|G+j z@>rn`&HqY{+69_7)=^{uG)T98eO`H2t4Zyu&(=NyMyPe$jZ=<^XI9royMFS#Pb=Gp z^?7q+({>gfp0KZJNBhY1{`D(Izna2vdBK&ianb>@eU~qQzNuz3N&ekeaiS8(H;H=u zWhgdMwx!UO4HsMNtgmNoYHC8625Kd%VoJ)s#GDt5`8X9IutWit z+Pu;dPw68=#-`yT9Z}ZtA0;7uwNc5XrM#OrZ*H#rdAZp2rN^`BoM>6vTihXNcF=wp zDIoaJ1yq{u^8vNx-dR2`jH%Gw+bcCzf9?a3HS+f}GB614+{wIS#}42-^@9gPXLF00 zRERLrS<1y7L8Fzt;o`-MAQ0CKvw{KTO3TW!>dy_I%Xtz&h8ZVLBpN6K6BE%m@WUt} zU0q%9$)LQv>F`c>fC(rc1aYviu~9wL4G9emRVW#s65GCJ|Di+czS+q-bd^VR6kVz& zWjH(C+H$#W;v1RS{FJuh?s!p6O-=D_+ti$$r2!)`G9q8TlppC?2iki~oUOU|`_$c^ zmZ#2JTZ=tER}zd_MRvd-*SsdatGc!GGn%c9jZMWhN?OOId8g9Js`X!nTpZoqeY-ED zzNXc$VSY>c8v_Fk<)K4|a(q{P$Xvy0?26Ud6;}s{c`Ty|KYjpQ$!(%D;z*nv2If~Q z#VA3#=B}u&fz5Plp-2)|fPRbPqEzU`#m85ZdN^kCy;vdyp(_v8Vt$=Z`3z}MCp&Urh*`pkXpdPrn$pJ;OaBLNf&cDb!rndRP>BJgNeC!cB4uLzQjsfPll*0tr`6Muo~wp+&bY34Iq8A8yY0Ed+elQbKED4-(m* zcC)A`4KN6n@TK=(DN>JE*ZGBoUXzu66UV{Nd@ooeoakkz_W|`>h(2lf_ZJ>Po9X5{wU$Fu1^R8l>}Y|Qsu0OB2>lZ9+Yxa zeI)ealjBl_m;TVW-o z?*m(sX{o2?DJN<_^LcrA2#SbM8yg!#kHH`XuC4$GX!!m;{J{fmrMd6Ur1iXh{d%@L zaOjoSoTP4o(sgO;&saq&f=12F&AWg8d_&>$$-|El8$||%t7{LY_4>Vg_vV<_ti!f+ zF!boUE|1Jl`=y!y(|+mb2m|%A?D<*`}~n6bkQ*D-kK#UM^_oV9jJp*@n!0+)s?xP;o%$D5%aP30s=2) z{z@xY6qS_lp!)&7;>-o=h*kp^5`p4yjHD{md4LfG1%=jJ3)&ZXc^8#0yr}0<^!3IN zVL(%cz}e1h$bI8UZ5UCsrMEC{5P%R5iv8~MXDw))ynK9+Ek&=^>G;C>kb1PBQv<@wX~VBMaSxdElg=xUp{NeZKkK1T_!Fsp~HkU5dVwN5| zeVUe;nK=_Jzj4QjnV)2IJTbGkh=kPIGu)Kn=;Tz1Pe+ZPiR)Xnn&tuvIh}2+i4{yr zN)o-OtsocLWG4$LGS~a>Wr$Y%X-5;ae0-EwX3|t1mzVRup0C+CIoo1lvAVL1A}w(n zdk{?{AfreK6c^gKI(` zVr<+LP;uXWLl|QN{Wp|P(X9g0AE5Yvu`&NY+^?b{fRW!?aDhYaV*8AN?zyBPBI_K9 z7Ni4_DEQ-~d-SMpx81MUQuouRIX=fLP`bOjQ&Cf&iP{QlrTK z^oq3i)vExT7uV`b#&n!4wHSQ#&q`@draSeIszU^(puiczk#u&;lJO#&c;Kd5c5d#5 z+9-ho02!c*c<)EY(@mvf2kcXw3=O%_)gCq3_4M|x4XZIfF{Z0Ob;uX0rXvP1nFo6x zGGTo0;$(n`1A8zeI{Iti@>@$2^4eRU!4$c*`2b#z6bRZ5Mb4QlrL(B~S33P=7@O|swy?*d8M*|+HvyoYQRZ_oOsP^Zd_>dW=hCqq+z2B#=Ble!52Zfs3tdj z8eXt*AY+uj(o%|0Yoeh;i6KUZyZan{+LpR4ewuo3P|fWf9X$gBH1HQ_%j;Wjc#M`h z;?;;qg&CKUlG6QmFtI2>(a6}C37VO8;?+NoCyxB7Y(np17NkB0^WyjPG@8`4ckd2v z5fQ0`a;3YiTU?0m{{PJaz#M?5Vv1u1cM1cmP@&OrX)3rcr0l#@?5r!;w#QIvO!w$0 zgB}}sp;xc=Lcub}+{e_oU(-dikBRtKqPq)+l{{y}f#cFlxz zLbU>bzH_L5bBV!`=8?Za9L7W=0TM-VVAGH3>jyVB9=9nlBohMeB*t@Q;2@Vi2uAeH zKR*i#3wz=F0Q2v6agot~ZbVPPoT-yW95z6B(h%_5Fn2`9HtcJj*EDRL3dZqoZu&;y z*!PwZv{V?KuU>gE)Af{0)XhW_B7jG1rfwphOT2=`#iOzJ@6*8pQ8*jk)Y%z{j{*a%Dxi13h(tr7SZU9%2GJ=fX!5M%;^G1aD{yc%7g2hhvk@ne zY#uic&lL8@0&tpWJ@^4G$%L`O6hIgPCEs!9*Y*GrsS9CAoV77sT+`5OWTAQLHm1Lnxvf(tEjai~!QfP#va_NaVOtGyhWJ|)2_ zMv}F}%)EEcYMS?f3E?R+!Gd&fiJkwK(v5L2~WH=-rW7587uBKX8J#4s$hd#Dk@vWc+DZ<4;2pOdqq*m-dB zqshv~J(oJ)R8&wv;v<_V8(s!uz<+7U8!QIxdMy^MZ*qEV6==8NZ~PEsR>!};&l{Dv zF@hVASripjAD_96ooY>1Ru+_vYjJTr|Dhh*?(8+tNh1)Hcm%5!gcj%&ERb301IxUX zM@dG;dg!ijv<0sQl4{6`oloQ9^R(AKT=s2k_sE0{S? zpFLB99zzxaa{&DX<|LgzX`k`RSGiMDQ_;w;>81rFCU&WF1ZYPntXsdn;oG;sU%zZX z=>Y0>dvmZrPT6qU~tz!7)K6W7}}?#q%;W&Yz@UXyV*cd-oCCA z3&wWhYblV}*$>`M>9Gc}lZM+O(eIC)JQ+xy(?-U8dY}$aHr_??i%$5}henb`3Fekk zvA`VosQ6!4^UNi>-EpVB4YP*UR2K^n3jOVV7w9!LEiudPQh02HY>szU~I(esF zs`2l|0goODg6A6+QPsJKd)l{TfKkTFJFSIo3XPbPo4X1we?x0)D4{oqwtV$Gstqq3 zc`Jy%0R+E({Tl6Dxt^1JUba}BU<~p*F)@8rLF-vG|G5}&LHuHACtK$(0kebNk=zi} zJ52jWSUDV})?#O|1kd5EaVKK=H5V$OvJ+ZWR#s+E;BHn%Y;16Y@PT@`CtW-D$6FFX6$?<|bgX8t6!G*ajlWWnpQFKHP9e5Z+0c-IXsRp(Gq;qnIZY`lA2=%5ypLt}408Xj=m^AbKa2q=amQK-Sn)Q%mySuiWI!<*E|x0IY` znVCfM->ay2>pmiBp>#Gf56%>%+!?rV!OqUHr-~Y^VY9MwXS=TWYGf0=q*MeHG57 zjEu`$RfRu>c6N5hPMx9#f(Nvucdq=}rl$FCg0su!wK0?#N1;r5k*Xq$9!|!|ZB3b! zoby)iT49@Ef>l3|y^wiC{%yhL8MNx&dV-Efq>j(iJ zmN;9;0O|;ZI{&%hz2Gow?zezq#H_3_&mCVwQ%=7cn`wG)ujeTcJ1CFf^W?oxp8S?l zpBfZ_%#KZiRICp1bZP~B82}G(Oi3|{MxWuhpuIlti5d$P=KQ0_kJmt*o_fDkgJ_Zm*(ZkfwPq_W&R6`i)W9(TV?nGLZm6av>HfZte~JE^5;pm3o;TczcZ)VRK(xCrF{X!J2qBR6UIT1 z9?GC}VK@Vso#5l?`B#3}7b&#tR!72!Re@=E&W>XG|k}?Sa*yM7)JB0lP?wD7s``ec5Hqf!*5bm5uCB2$a5;xHDs>qo?N6*M(3&5x;@KgV={3ia^%U!rWYRS!YN#ugndy zroaDMnLT?f@LH{}T(^I-E2vA_E&0|kUcOvaBg|h%G@!vo!`61|bCcIhIC}6hJ-oa+ zTpm2Im(8Ck!+(Q`_29t+q$q5h*M7CkNFNmDth16vqtHV$)MFzl%7?nvdCS+?NeXZW zH%-8r7|C<~=nf}OvH?Wn!Jp)xe+SBi$qa&BlWS268Or)$_9o2@R(WlroP)xCK=n|C z9HE&Kvl$vEPAz`PwbX6%nCf+u!Rx}gAxTs!)%~WXf)FmUg#P4QX~LLc+q9_%kst_l zYL_od-P>uxL?Jh}<61EvJ3rkwu1)`=J0dL7pC?bg_t8(hC%rSBr`mmfpBun@t%@Eu*M`! zb$F*Zj;{_Le&%0$Y2p^U&3{f0Y&iTU3!o?XMM$`OO*tDo@cUQAty>#NP79R|npz`W zuOw~j^`R~Pt;T=ISOzf(up|hUh&yBaQ&Gq{XY_Fx{#{rwuX`Zt0Tuk#ojaC4jxNa` zRR4rrFQ_0uAPC<9MCV9~W@Kd1KsjdMza4>8h~i z1pe&vVh12^etx3S?GdKT$cA88uyzHWYCIomRXtb1&X7bUA$EwL2kh*g)d?{gZ76eb z)Wsf9+m7!M7pDWUs{LO?75*sF&v=&ar9JW1Kd$ zYEsaEv!bK>tf)(6z)NlPZhh=Wv|QD~Vl#^NW@2I#%xx&?Nf{X*UxgU7Pb<1T_jn-~ zf7oB}5khh3Yk>frBtU9a_dq*pza_;^Ml!$HQm9XZ(IH_70)+612ACsMIKAV?*8+1O zdJea;EpQ^aaChC^o*px!*FJn0=os7wbak2Fkq^vB{|6qE1TP*&+UN}+LoghrM+hk< zi5ni>2SEAq%Csm^5^PI<*KaYxEmBZ?Y-|M;#2_7T!BR&_HdWoe4rRA@&uC zrXg^HXf6S^@87>SD75E-XOr0xY$YwRBj#hn*RKKaML=@Raqi({!UrmfjZO%ounOI& zbc0!WzMIm^gla>B%k?BW$Z#Y#k?RqV6Ad0^R>qYDlIH{Rui$?3$py$Is%EC15fB~Y(4 z%|If~kPOHb4qzdmW{_2q*n$fy8b7UgMs{04TB*ZuD3<9~TwK`I#Xmg&xSV`^K>)OP4eatYP|o8jlcXT8tzEk7S>l1(S~>&q{J zt#P-cqNh54M8XS>ozbZ-7CBa)O9|0NOGUZ2>#_kj;UK z0?|8fcFNC>0!jfz&OS%gy){GdO<;~5u(1*U5Aw?m4K_B4u(pZBhYoB_ew$ylgksn#JeDY^cUwp^1m$mr8=?CC%38fgTCh|2{vB&y#*>~01h$4 zpG@O2Za82-^+ASNg;(kTWT6ZY9n4f%F4PNqkE55zzU*<+-lf3)yACz%v*pmqn!8;9)hCO3C>}Xl;hBJUNt> z*bB?^rTYXwiiNoUh=Z08Y6kL;sK{6Pm+zSzJibkbgoHFeOCnM1pYNmP-N$*MbwOl? z;S80;OfHT@aS(xlGG>YnAm{vz!IYa&#p$=LzL5k#%nqO8RrcnDn5Yf`6DT1U-Ic_7 z(MJo%3;4QzJ3V{6_aO_v?^O^jMCLSbQ2~Pl$2_v6`wn& zfgLS58o%V_KYa%663$I6SX9G*7YrcJSYRnV`tP0wXjorhSVw`YI9O7*&9a4r*H87; zl1n4#CTgP5X3Gn+#DOIb3_%%JwmuDut0w&=%*suOuj<%|69J^ganSZ-Vv?)}hzJQa z;5hC_N?bjLeFsqDKBxcZnh!}7hfH!+n6D#%Xq#|t||Gg8127u zxjSf%uR9Kw1z~P!-2HVm5w~}7B4SMkr_Oh&*7prgV%FK46s@DwqJ}zn>=}cIOON2y zk$^vGIx|CGiQ9uMGxi)38AYRm4u>tX^g3X;k^H>ILG>>r2u>0(P(U#Ss%mR#v&;T) zlaMzGqXLbgGv?6Dn|~h(@dwE8NY9gTtGw`Qvr(DnCIDa!@`A2C}roLsLt2m7vaKJ@hF%`2hzxUs%3nplN0`5K+v%C??4z&@gA^$VaQPtBlRxqaCO zy^ZuDat+~U|HGg*30yz47-`O$@0=?S$>F4j*`7PuW~&HQMinjT_C2 zM0qu)`EXXB9Kj761{&g)AOQv*LvCMU>VV-8nG@H&cyNaXAuC>gQBMl&!I2IyO`tQf z`XptA^!*Ed^?69IJrCVGul>6mNjv#V$c9PpE4f&kbb#BJ*9={2Wob~QuP;hP%hy*0 zd0~VrJvTQdj2Sb?3k71tB3^LJ%c!FI*eBhSa6{JsWPaLY1vS zCqXZ;NT;70RUQzy`hWFc2%E&sAt5iMooy5SH8ijR+}7T#k!VatuUzPH6{oTx`2eYG zUfyt$7lbMchX)KJXZjTD4jugb3n50a_5ZE{BKEZrk<6jhOI2&|k-JN}mL=WBzh8%% z?`6EL!JkwdJ*Xc<2waO(=|&R*nF+=m#oV4u7Febu;S>;lpSHm|Sh}@suQVlYXiy|J=b$iIvk>9&lce|g0 z(UBQP2D2m)-MuYE7^|zxU8@l|`ALXyAU*1_@^|oGycvBDEHwJL|3GnthBO}6(EpQ_ zG`tx6g>ef3VKU5QX)O>Hai#$^3hmqcNv;)m$no-JPaEn_H)3q8uxW>H0?Gka0gjVk zRCNgRW<(^AV_x-t}zk>_m=5WR9>h zasvl?h?L)Te(B&{4I7c1#z-cyAXYKm?!0bd2Eg|=>C*T+~ zY!s$j3$b8ov1^qdgPmk6;NKDS^EGjWEpE>xB&}YT?Tog0fAhLg^TB*^?bQp1Gh$$~ zKr$zMz#EbZB(`hE({b&EePv~0l^@^}DqW6b#REGP8~smMuS553=t=H<+qNnK@Sw3` z|H-{J61PFL?B>IVjJO0s!CD;`$}fPAB`gy33wM+xP0Gpcb$^PL274y?HaUmyq3256 zgrHi3G0XKF);NlAmd%Fy68mvI02GxVnz*hd8iaq|!Ys!9R5-i=?p;?oFdDEG5Au7@ zZ_=5W2k>OS_C7e0+zUW!NnH9V2E6eGZ;CMgBql>I?s$-x8I~g?@%kucXg=M+kX;8& z;IR?Wdu7mfg%;^JuneLI<3^7k(%O8`(phy?%~{2>GXHNDfP!`36$UfUlp5vJ;x~Ge zUhWyDDpy|Q-A>EvbSKg1D$h~`sU#>D=$xNOD>E|md*c+K1%pAXw%Yst;$=-7|6s~4l3rJ z&o!`L5a3{AgNCsVJ|vumV1PD2R+6H?wQ__%!S3J*B4V(l@@HH|{+VLg+Ud0yN_ z`aNQ@`T%OPo{7m(1cDICLtBu(&@2JNaLPjosw^`7HJHj(fP1!fc2y&@mqA)_IzAzg zb@0$3?wR$AderxQ-G}e*wg8rXQc!TWs!ENQDWtt|tZTT*t^giBVn4gNBS^|bE{=ZP zy55LAo!|{iw~XooayrIPis469mhT|$dIK&ld}mTmz=fvhx0tN69`wdSS{(E}VtyMB zDknxEZ6SH?)tl9ou2r6rAD@x0u(h=%I|%0hTHCeio{GWg9+$o8PoJ9N9tbi)Bo5Yn zx%gYNBeXh)qO%X36dxEyd?*HY+Q`a!CdYKm?CdNFWKMY?xV{;o$f(+Yjxl}TqK+{S zCH~nM<7_dMS5e1uX!ftpd2eN2CRz;oe%$dGob0KFOum7YwfgYRvN!lJvAZp3aHpUm z@oahW(8Mu1A)%!=lYhNE%8ZrxnNjzUF%YX>2U8x}2JXS%N6t_AM~-oJ3=}iO7w$`2 zGZ9*izRRm{IS}?71C4s3{+-tiGv{I5ze~}MHYoMjjaT|!dWAKhazC!xVczd&JeT%0 zoyGud6gjf{I!`(r3{=`*{&0Y>GykXK(%+e{M-_aQE3v7Yk)9q=P8a~+^hp$0TUS?f+cx4TVFc-C z+=Zhc`$lV#;|c&Ym?-d71mr%@CvZ{`Fs87Yq(Z8F{LJvTv9c{AsmaOe%YSXs?5n=C zw!VWedIdm?v^L$eXiQ`F9fogq`b@3I2nVpdNx|N`o0RP2Y7(g@T3TuMaU)ly{Is+X za-GO?ABHQEw-gApXdga2BCYzd$MKl4@#jE#R!&7X3H^-O+rbqVL_=X(kf*!(k6DfnUAHx3v~GGm-R4&&*6IE{=sL z6n*E8%r7^$uofTgY_%(zwfQ;g zX=`tv^7JXeBhE-NVb2d9Jt`(Cse7*D`)l!_Ms9skyRAY>h7OWBUMFCKg6jv zsDS9*7+SaP-mO7Z#;W)#V*>&bUg!GUS4;MTH!(?ePUrBS#My1h$nLLjJH+(8gwl{Ph!(Kk@J3 zju^fz0*1>Us$NiQ$2hLKrlkSJOh;gA9{vX0>MJbRVgQ}W(bGA69I*Synr^{VpH zq&jY7LjsgI^CA%UcEWI|L5;Wg1$lhZrc>!bqOB>m0RRxXpsUiizNs&5ZSODnO!Gi- z_)vOfnm7uyS06TfSvNj5mipqwZPKJcvrCP4MvERX#~lQ9eJct_n7q3se@=8Z)iW*7%hdB|bned~R+7&CXp#&R_!AMBGO1bw^rhmsqf zx;6ZnnQ?>;2Q;b+%M#rL^40^S9ZQWTp4xG(9d7*vdjIdzb-*>u=eOZp>ZYdMH_yw; zaxWTFSU?Gum zhJ=OT@oXfH6{m}hRqs{oa^hJ%J(8f<`!EufaQxIM&9i5Dm_h>Z9Ii=*t4=>d-jBJR zID7UZV&&xC=1Y$$VQkx{PdYx60RqGiM0z%O)SsV8y&y#-K8RCcW7Sc4s2RFx)!3w_ zCQU>~FtiXbA?B^9Zv49^N8;YSdxu;F)4Z_H9g~VfSKh)Ge}UT;_>LBB5Ci<1sGMA3 zy<7MpvyG|yL(qmxO5#9|E{`xsbMb7O8LXgrprG7%O6F})rfOoItszi*Bg zzX@uT2pxE~>xQpi)IDEmH6;g9r!XIM5|tl9*+6Pd+Uk=aehjwj6P;K!q>wh-F8_Fs zZogGryt}(H0MG$4jP{WuB2rSvA2wxrPi>FR##;cx;PW9wsRlO+FVc;YJU{#`9dHDP z6%Ym~{Ivmhp1$3lU8?5bFs|PAvADcEK|O?N z3WGkm$qsFDJt(@t}1M$^L6qnD0xNE&tHDy6BmZ%r->Sj$>KG4UAS)w`0^M`GX0oW+AQm*Ovy$;+)-Md`AYtdS~%%&xUFj*Aul#IHb=y3 z0pIWqEt}ycBkic0#*@#KU)xvdP~?ncF*z(iF}RXAh^#G%9_6)tx30RUm5e;fovkOH zeEIPsOL@Ri9>}%AJ+Z^lHE$s*Z+qM>xXn}jF($w9cVkdaFhY%nvhq_m$t42rH&%XAeTE6+)c2%veQYQ1H#% z!@wMmElZTTu`>E+&b)_ZNP@xu{ow*C2~K@)@m)cSE-H)lf%?sRyU_n|_XZk4o>iUs zRBw$Adc^+iEw8s&f_!5Vpl1ib97lt+xo`m&Ql7=BV1Tgl@+#T8#>U0PDY%Vt!tgqe z06D_M2y>o+qepJv;l2>>q(a0UM5&30h9?2zU3aN;iUv6q%0D*?4YTgoSs9)^yA@=6 z%x&(k;?3q9mbs&921+i6igKi4p8>ET4myc1pwYv$Kyny=5XJbkcDC!@PF#{gouh|9 z4oU_d0H!20j`*84sAk{P)B2&VtBl<)dy6mkuUnm4T`?hFG=j(Y=Gh3XLnlrSw8A3* z3KlM;@Qd5uncIP5_`|)cA4hRGm>Y!O8Y(rGLl24XKfd~(%T_Ni{+Ta}UtfVL{)?k? z{l*R4XODr650ibdG+WB+yXh`8+ZtSu`PNBm`sE^P5R3bN427E1fsUD2OkI3edOhk)DbiP^ro>5aHg$}l`QjN&H3-^}U6WE%gOJy_osghw zWAp1KtM8rhpBO}7pg0#g_jg@GSG4+cUllb6X*a4id7NwXbxm@|*Z?kPAfFZsYwZEf z1FmdwsrV=XHrVwhYDRJW%VLKr?~(ULiEm(G zA(v+%fN(MduL&~rQ%+3YSpLDI)aAgxE>feO>}}RzF9*GejDN(4;MGL$ws^bCtcnUk z)i_LDgVF!kt!Oc7 zZX00V(63(=_HwNF%Aaj9`SepSZ?mv7pMnI?-``KVE;u}h71m#5>sIY^T2u^lds2A{ zFlBK1<8{R_wM^gN7D4hUqq3)KuQVsaaC;B76CHtEAHw%AZIO@&N0WcHo_?1=X5t}C;vClzedr82cuv@7 zrN2LH2mIB#=$e+AdJ8X#grNzXmqf=gfwxd?huf|5+LXGlPO!ZJL_qH9gucEO9tXmL z42HIPbEm#1A09i`KmrjR@GHwaI-%g}=&Ry)oZ4XH=Ha`m(0s3lg;`Vu(jyu2$My^p z`xam}z<6T$*vs+Y$Pxe;PAu${9jP5B=}%?1e1u<4d;~I@v45pAjfXAIpHKf$ymDu% z4}LI2J@UO3BeTD8z4jV0S)fP|(+J@lr;;C(hZJ7@aKI(Ezfkq8Q7QW|BSoXH0}3J) zuo8J?dLUi;=3RYv*e*a<#7;>2s_=-Wkiakrlk#}0sU0r%J3&*0OoI5P8>9e z*e)s>93Rh%HG|yW10(oAc1s?VIm8+GqYms_g%?0r9Qk6K<0nsQ;E`b>lczata`i5_ z!5sa?qK*iJiR|U1&wpU^S(#3p_Fbu8eGK8COtRm*s+#1AnE+R>`aD@GT9qYYCW#B1 z7j;bi^~Uyrxvl+@w!Nzh9~3GvZgSqm@Mh?^yhA83Fo)C3p(qXn6<Ej2K?p@+=*M6iXT}OotsVD;gi8zs&>kYj zxC|X9UkiuByUX-=%w;AB5s2H7Th>Hb3>8$Fn*b})C|Ju&O0xl-#GzxljzS62Qgt`e?(Gc zHG&N(FBEk^*u%{92LNttY(%l1N2h@hz`R%CAUz|X9l&P@v%mnp&?_Z3_ZC(uo%Q7% zhnC8Oj#VW#sEl|i_MOJzAN$EI)1|2>-z{=-_i$+f>-SH3f~MV?XUz`~ph=CGu@?IJuNv)UHUhfDQp>L&^*`&bG#pocp$IY-k9RUiIOU z?8SDO*N_sIt|J$n5ez+7v%ug%X40HnyKPwxXOGk@i$qzgF56~Dyk0yM=_v<{CT>rb}_2F+2 zqt2bHBWM+0IZ2DNjBl*7glmlkn$Dv#uVVdlg!4xIpaqmMP#tpC=f+c?J-Y#NMo1S% zFEql$)ulo38Gkevp%RDXTCe3*-c6foPyu+9UV?LlgsurJ|AIASNn%HnaQGsTc3Q0( za{1jSuzDW>hLT}+w~`;joH9r{-O!NaUM{1=(e;vfxpvSHphUgv*zGS^4fCD0$#bb`u=fPP1<;?Cc3jezm3^KkE7+)^TeIDBy~{1Qxadm$*I(eE|v?1uSFig2K?UeEqdac3Hq z;}-w>XB$$Kk||TkJXFFqCn}Vp2uVmq$rOd6nNk@;i6j{dAyO)-sALF<5<)UpnvhiL zIiF?!&ztk=yg1i&_T|OicF%Kn-}hR-;XC}+=nTZU=zT1P+cb=*j%VRnSX?j(A2j=D zHu=1&Vq<50`PurG@)5vGrjZlxfEz#>Q9Sz>6wHTeW{_Cxu%zEf(MSPO&|4F@sp>-_ zBOig{5X5?Eue#u~-__OC+|u%1wU5+;FPUy+Br7ltFeJ_;*4XlZNjXRrLo>@cF{ z?v$1T6m&SV7Nxih6kRb9y1Y&Fq{NHunzmy5-rY?T_25n}Plh9T_hruyGzoi084BYt zP88=v=|xFSZ~7!ff2*uquyVRbnza~vW2w>FctNIHR2j&NFg>z0D5%g`o>d)wDBfR1 zRXNk{#rWPG>5wxCe)*37id#8yTd>jrO_3D|h$w5MxAz{u|)afu;z7=T)2A+b5+5f1f~I&DgbqPv*^e1g32$ zszKy3%%zNYDmb&P6lYHzIT;|MCLTTwh zzy@~_&s^YU08d(n*F4#%_RvPN8Eqsy{>X?&t;5Fb2n_u3J$FP1RXcV3|jLPJdwfc|b?HUrei=y$(cmYyIyqEL(~X|8gkeh;L3_|Als5V9nb zUA^|+d3%3O-10=LMFclcKXm^!0>cnMEM8&VFFqq04`2GW?1({JQS7z!)~#9zR+`Gc zqVu2Tp&_5;W&Ca|+A%8p@iNSTG}C+@+DWWk`rz`7*7`xECz}eH;}~n`rTqT>iHjby zXU#f8Jx^j3uB?2=Y`d%HOl$~aq5*~EjCeEyURi+c1UN4%FF&u+;hV#K1gvzsof?i5 zF^*KIa*Srp`gTn&%P8S_V^YqcyP+1brZLz;{HY+=nP4V!R&FlId#Wnc`q*MW5X2a5 z5#uV&=ghf9>ao0Hvu)zzVrYiWFvrn&C24R_{W0=Zb4vZwui9%@HdR2H6YISGub5L$XM&%uiX&*phyJ;;kqH^p!Xx5zFGj2W6ybSWB z+x&B$pa`kD=zTOSulUl_$iMQ^IjA{KS_85SoPQ8u6wvtB{L`M_?+*qYrUu-1$1Wvq zV_AtprCDsDfZu2v1zJE)1F3~hX^i7LrUSxt_!n13M@I+H&!I*tJlXoUlY<9+BSSo9 z9oGpL(O%Th_Z|&nJ>RR{?FdLVfb_# z0)*lwQ-i%GYZ9#};c&&AOh^c&PGy4yEa~|C?c2v__|C`1E(atjcironDv&-gy#(ab z$lP2Ru+#y?aJiG2L1adoYk$EF`Qc|x=5f75D>-@jkI)dj+NT8t)8HLQZ4aZSL?Mz8 zASPJ<4^N*5M+<48#4FIHGXx*s`1zr2Y32@4f?s9bRLdm4ro`P=?La)GU?fb5Jw-JD zZAVa zig{?Ug%1SITbWn{?|F4%uSVA|8)Bm5)Sb+7{O<(i|HlZjfJMCw93&_|mbF{mANtY9 z$0z3sI)kFj%+pf`^l1fF&DHgFl{r3Y7Q2(BZ!^GGPv;x4mDxjR1VlH^y^C&~O`{UF z@ki8{K0SKeXAt!ZYDn-Lj41rT(=S`>?T+2H5zZ0Fl{SZS&uaC*W+_JJBqp5u7CIpN zUWih+{>CxSKwjIn?#2=so+NeCd+V#3ZnThet;G(b3NXFG}}ng1nwv@o&kaxYVsBEEjq}>=-A= z$H4IFZhlY8HkH5F@MCwU@IPHv%SZ zpc=bpaZ{4J;WLH3N+pApGvA+7xv10cr@}kB0L-rs#Hd+OkYfpY$=e0`%3ht=v7zTK z4~0huv|lup*SQPgZjzf;%~F$PFN^A(wo9EZPY*wYwto+zg3=AIf3(q7&(0dWJku_F zXxAtik0lLh)Vovulq!lL7ctL(L`;O)fD*vVRnNWm;&hHeG6UO_@xF&>>`vx8TE?%CBNNhz#g2AYv#)SX z9#ZtpHPty~NtX9yT5x+!FE5LKmKC1y1$AwH-6x1aV6_jOu{@SWG{8@i$GoA zY0GspwXaOQ^Wnvv^4cwo$;&R?V3TOIbI+dMzv|Htu69;9oV(-hhq*~py6EpQ6_3z7 ztQr(pY$L`%-`&}HF!^4?Dj|qns|;l9D4C+Q{8;niWC{hMy%-Du*D`V>En&8;&$6hz zn0*n$m(~YoeHoZt9}e2$7`mTMji%S%=Xaow7}QQ1at%F1nAXyXHXSnWZtiUfl8K=H z3#;SU6rbZEY5&@E;w!Kz@C1ga z;Jf`()#OI*nkl=xQ%r(y+_H?vteXa!k$c2V(I2<`X&{lMt+EP=kKBr(w|E0l0pU zbVx;Uhqq>#;MfUNaN(NX^@mO))>&9s zh(ZDogLNU`K{W8%bei%qSywV*Tuzhv_Cj$SsB%)zt`QOG0ZlJgLZa9JodPsc${eHj zjBlZU?*;>VSv~#m%RCwx8bScG6wF9W$hcGK+L@UCA7(E^0;9qMzP(Cc==Lmr)5J)M ztqmyO#Z)mOA}!+0y61~2lo?rXcxH2zYbuS?8Rnu3D#fqEf3I%Fp1U7T-nenp?d{e; zP`WN@)@JAhnUjW_*n6sWW8mw^Ow-sxn%_)R>4H-z+eBLNg{g7;7Z&I?>{li&8132? zo#VD|QXJ1!Ads`CU=lSWWxus|gMG{U5iNH2GJCsuWH}G!DXu=S@4tM1JZR@SeVsA^ z6wJLb?a&5IEv?UrKEGT0G(L;MTDyW^`tbPV2q5$m)!$Ehgm3s%yG1BeM2`!nMpH*e z$+gL1;wb^eOB%jXY&DcYS)ZDJ57^R{+_s?tz3RAjWQLE|!Q z)25%TGrmNUP=u(8)`9mvSY6#VyJVhh?K|G#w&EFO6Kr7i!;{mhz96Ln# zLh#*~tX=!Zg(x^u5ylUAh6;bp0-YXt0#m&+Pg;+aL8!VKX-fV&Va zVu%G;N#O^X2;a@)G;O2u0>Oa5H$*wuy?e~_6&6;7^lR`s^lKn=Vy-)TU%qLrt$n}w zv><{yVMj9QTqw_p0lNxU_sQ?^pe3#tj+-D!Eld4zp{-fKD{TYWkrTl)nm$W+u%syF zL<0GP;B6cpM-e6Mhcqu26J|seNKu0Mi^_{N zP8SAlx@yguc`Il3l9v&kECVBA3+=AGBm~8vZ@y%)8yIrMD8$Ma11`Xt&@!NVqMi}u z0KBZA82=zW{)npOH0n3tVl=R^*NxB@T(!DH=}Zj_+CHbm@TD)QTQ;_E7vBhNz|PDn zofB8Wm*b0~<3zRwulRE9zhlM_1CIa_S=}&C`3Hfx`IKG*kKmd?I>|4@#z{&_$~$Uj zACMToHK3?sL9WfPIQHj>mL;;zJ|Crhol8O`bz5}s^lZeV;oXqC>?tG#{O=-aHL4?n z%RAFbHfMmvDj3@Ty2hS@U~Br=s$7NYE(e7Hr7(Kg2`(RHT~qs9vM`~TgQvA2@Uh&S z-rNvoUD)=2kq;w5!(MAPxvmSHR;%>lT{Xa8XRln@4}1XIEfgGtB{74}B?TnxBl%Z& zTx+)g1PI8NN&|h39xDU~iirA1ZO)BrEf`oL6M|#JiFp(r==tVMi46_y5^WY`>h3-f zIFa$}bPLI@l|7*dkodq%0I9-1zjsYd;cqDmK;-HIm;oJ5K!DYQXA?58moInbe$uB- z?b2l$#)PPd5E_rQV6#Y$Jvbby>{9X46lqZOr}L*DU6+%>9fNo7w8b)2 z{^FwfjHmyp*DC4+wF9~Ub?TJlajT~TW+iC%>(?#PQsDlWOeGGPv4}mJmKKRmPMF*X zHSTH02_+DYhG027O4c-@{YRkXh!uIq0`osLeK*nM44>nqm9YQOXTr=wzH2PK5h`3M z;8@TE@I7ZvoS3Rm3hPIkYT)Yn%S-CjzSb+I_I}?3$!1{HpcL_2e+Zz$04WTMLKK<6 zv5D=&lxIEISmoN|sUW=&majz0NdRHo1dX*k`53r|=9q2}+^t4H2GBoi*IvA_ z$vs1d>s7g=fMMQp)4R0k&0FYglBsZvW5N&`eUVa-`oJgGIbiDuK|fm892(~F7mew3 zICnZUkx*7gnxbj~%?8_`t40;b<*3IjTr-6I-BN;jv~_3kW>k)37|{fN6J8PaQ@4htCm7Sf$5eX0DJ-|;U!=2S&!_3 zxTq8QvP56!Jb~YfDqIYb6HF5-8NHLC;PU#)n3TEN=42Z(pVu_|aQ zKC|deQjzqA%;Km?=4)IJRj8~^I)Bo5o9>WBej3?+2dW&M^FYCeYHH%~()0un<@QA5 zvb}8w92`A2?b(oAUH6}KnE&%1JR1WeMQ$f`5wSI_Zyw>LQ=F_TDVgHgoHeT<4H1&K z3z!&)AGrP%_>YCY2)l=#$+V7!J1%=Tr`A_UliS27oeoU!zcab4vhou<>1O>~5AlH5 z*<#T_u#zoW51Xf8m|GNOt~9O3GOD_>0IaCt2=}y7P!}VeUXPcI>0AA?rR77RaW3im zgKH`$QP?82!&0MA;p;{No z7qpwqRWH;;)Dnq}&m9$P$+d&kHL7+MRoH|63zZDSBzZWOl`s=gE9SFbWz~=Ri_|r?ed5 zbHIm!4!r;PvA3P;S2jxdZx>|8D<2;dZZHX6@I8?2)D^@3(ePJsrH#1G&Z2X^*;JKE za1|6exJ^ObmEcMC3S!hLP9;Xu1ktN3Pb%KZRNxoM&ixUGDBsc#>LkjKkF*3%PM?wR z0ED3{GFr0a*ee%LWwel*q z+@W=A)|`%ySEf)YT)kko`H;E@wfd>?FV|wvJB06SJ0bDl(W4KrRNP`}4DJdw?c7G^ z3~Sy@KXnb6PZ2t^N`53) ze{gNq56ai$v&KE7j0Yb?=%C}J&0)KX!syVc(5t0)hx$`vOduVjcW2V*G58LV^Tl$Y zKHGM;!rfmfIPR{`wiuO8#pK?f-UMMyrRO&Tc;vzKQFj-Qt>0^_Ppef1F$+V zx<~jag?5hNRwvfW<=!4rR4Fx)Rj&#JE;=~lG-G-gP@5}UzIW_O$@`!1=Mp#1-Tf`q zJ$ksBpm=_9-_`&2e13Upt~j;`d@S&e-Q2-P_kLcZq_4AxShqjaMxkRz2TBVuMS$M` z2!6um^3WTL{GMt~KKlGgV@a3fC0b~dAH&W}*izFMdK^!&s2Cj{AKRJl*jwq==}!~= zmCVNW=-e&oY`!CG2ubm;%ktVwA<@BLgrs;M=!ov-(}vHitXKi$NSb#{K0=NNY|5EB z!p4fG%6hWvnP0_S^@EBJD0Ooi*tf5k00*u?l0iWxw*Plzi|0LlWxCmp?U@sJs9$fg z)88f7wQHw7eI7xg-KLo^AVT=2_nKw&yS=*VSUFqg#m3`@rpiBxnxZBFEC5A$!IQ?@ z-nV~$gEz0t!Y4Ejd0FX-Eh&enDhe31VYbMD1s_EPQ8)hVrfsgiBkl^-DJ1$BiO?W)t8iK6>JHS4?P zpro6=&M>yz4vC~Ol# zQw4j(vp(PXp1+dazx#P!XMN6bRvU*wSmEj?wFr$Y&rpIGbjz0HiHp{p3Dc^pp7HCy zlnEV$o);+AmM{9luwZ*)Ib|q4>jqQ0Htn8+BIMMMYw#;xu2WPeh{72X3>DS9f2%{@ zfZAVi%icvCeJWmqC|o)U%Cv0*VjW%hr{gN?h)zt&{2$3k#|dc^WKkoUcKrtxJh61lzlpM?9d^r zbc2vEvKnOpz~J1FnAE)}J<+BX=voL*88C{d<~y8wJSGqJTa2q-$?Q)1iX#uVxuRq@ z;Qo;-D&5G1a5^QkdYneMG9BjL%;ngT-MxGTB|12LzhfnMM{Q`l@xq3sqehOxW@x#aR@Cs z@-PNktzboCIG#Cq#@66==UZ!%CAO&iZNxJ-lY7L}sUHoZ*A}mss&g1=-D|9I^0SL& zElclH;4?HvOgGp7%_^)SVyB@h80DB;QZ4T&$6LrESO@G?c1P~Wg11d7Mrb3FJ2jvn zM9j^f`hIAVrbt!qPzKWs!WIi%8=F|vK_dByp>n(LjQXnat!Yuuf#NqjB7VbXRO~r9 z@iwEOV69c6`9a5Fo#3Dd~&i#1Yqals7pZ9a*vLiwcLtd zg^7K)RuG-P+a0%v9Y}+M_<$4MZZkYxu$N4eqJ$cw)77u7{r_Z0UC$$sJf*c;g#Tws zbD0_2;4TnmZqH?M%ha<^pQ@c%)^}tk2~k?3D7^*31D7L&{|H7|Cce50F22jtqjf$H zOo9bg=)8#QA~aXTWju!Cu3p_-{ifwvn34zzPnEm%*CO^U`}4j#c^1Yeoh{fD zq6=^gLT0LTYJ4C9N(jaSh{44I6r)P~TZgf?LE8)Z_0ID0=F5f{xg~&Hj_oC?4YD2g zAY`L(Gi+Ev$I`g3T6OZ&sa7NsUI5Ld0GfBjm zhy;-{i~x&yCg+*d#}@4`za-d*Flin4`t>rkr?k%=e|Am+=vlCTQN<@Ai6(3EwdUC7 zP`7cb0;49|0=M{Xvvp58IaHm}=kJwb{)B9t7|C7pUj9~rLcp;;_n@)kxh+wUNfiZ?XQw! z>C%e2DW>itv`XLvJcshy2OF77a{u^b z4>2PO3puz1e4|jp;ou4W+-e6|TwAWxL;HnylHX=c#pmxAv`VI=CsByG2LiQX-~(+H zL=e;4?nC{`b?8v><0u$8@5`A3)QAc-?rHxyl>T(OX{GKj!poK;@`ba%Nt2(Ioxyj4 zqdAHe^9>Nlg5J45 zgXh=zELqjI$!$!%&pzqK;#aSP8;J$?4yD6LDe@U%A(CVCDzXVdDp71|4YN+wnhd#gJ z&F!vApAML+dH=}4gF-kZ9@U*YAgjpnIEo+w<_!~_5hRFf>e4qW7v=->fR;e`3rV!7 zfo(NMpV^`GzP7)*XRyrTu?5mRza6LZzGQKdU7}T!PB&FmvG*a;SftFHSOry~t849b z2|buFhS45_W3Pk~^|Cf>Whtw!YWB3xWc`4ihE*frD0wdAPGUYzMa0RCy_cb8Vs~@P zV!n#d!a{764yOX0uu4vGwEfG2(vDMgqt@S>?0iURtcpCfoxtFnoMxQPe^=)Yj4h%n zEg{cDEJKUf1zzcGuCmV3&kX#d^gCFse#A1u30z^{i4%L$TXOF>e^zf;mhKrYG=QVR z#kf5XQC02F8vfk*0CmrHevhW6zqzbCSx%eiqWY+s$vBdS%^K9UbxL;jsywk>G;v(Aob_KqG(P zqY|hFHk{H_ZB}vcG5;Fv(*9vPFgOBjLrQ>u{dM`KN z+Ue@sbMz(^$aHK8hGVO{+OqVu@jqfNmL$F5b1wwuY`W!8m7=%0_K|31q%8*BBMb}be5Cd?=g^wqI^H8NxPSZf3t~I z#~E97IMjx+4g^V9KLExsT$v1Ki5#D!oT>QLbm=pXxnbleuWiZbAU-iuHdve91aDSs>~0tsDhu8P+2tB#1Ue>K(&}ezHCfb6 zdLKg8H+T9%XG~Lz+JdVf*~a)nBvsQ~S@1;>|fFP|MAslZRk5NO&_rhR*H)o*=zLjZO>W|+N19c&siPhlbE zgW^i>?3IW=-aGeKe{CkUSOapZ=Jm6am{{VeE5y)HQv}C~&e`>ost6tLn@sdy1p5S` za%C+G{utf=DF*fZ)(Qo<$)z|U?avK9Jaaz3K-D4t8YP5q=%GI|ha#(NQ>&7;mw2X7 z4G8c=-AKM@`ld#3(0{EdXFH|E)@trtF_wgn;B0P>h2SshkGe~w38vHmkzg=@BvsB9 zSJ>%a)7Mj1ZLryK@gQczJiE#fb@bX4n!@ivot>hY_(Bo9aifq(<}0K7Rs zfV>!;1f6LQWJZ5T$D^;OcYAVL@Y71Km}TOHQDS-{MeIJp`Xdv6xQS6-jhlp00xUd# zbw<-U78v41A+IM*fsZM)Z{Hp_;;DoHGW+Y!a-~vS(obK#dVnbfm`okzaN7>uv~gf> znz%G-ITJsj6NFZ>QzvnN;Z`NEajPjdqz%Ss+_uj}o zzzTuZ2J7e?W7n`2c*IXzb<>x1HvA{Jv5o4Ofg0Es83x`TRX7sFkfTQ@etqF24XeZi zXNez*J&f=XF^9oqAMt8O@SM~#DLTZ1bbI4(ZF=5H%KdS&YW$@o<@Wl(wJwhzB6Ho9$iS8MR& z-*@8=Xix7uZRwL~uP*knoOq^it=6hF>zX63C$_BKShsAk^m^jc&lZhldo5Ng)G2l_ zwC|{M!2X}wtV#0ilc%OUNzJPduC99e@Zbs$zk1KL`yx^&y;W=3TGia*savfmIWoil zABncVY-@>)Y$qAXEv0_)5?}RcDiVo7khVk;pkynN$j>b6bFIoDtK--viR87WL#9Nc zqW^#KG4=m1KbSm=yXtU#-I`6C<}Y8qeAkTAE-6dCyQlGoe;Jpy-rd~_USQX>eh1Gm zA*sPr7lJapr><|8JF`^k#YDj}j{SBo-O-)(83XM5l?}vC$FG~zPz{n&&cWzx{mWDP zo?s27G1jV)xh=EQTKRUF=6}`Z<#o-O?E|yiafbYCX{xTEEx+MjcR~N;eo)pENRwup zni?O>$;sKoSkuZksS9zl?8v!$H<5^8s;E49_wED)8E>$Ekao9( zojc_e6cuwn)H;F)J;=*D%-&qNGG@@AL0#l!5|Kpg-LvN_W$F#jhIk6WuCi?kN=o9$ zLX&?!F>pzJ6Rp^GYWsefmiskwjaz;;c)D|tOaj(6jtyKx1R6GCL=ldXOAIMpn!G`; zbb}@M`>Pw9V`-xnZB4VjWSwROt#xof%(GSBH%QJ5>9?otrE}+u0KoRID@NOQU%EKM zI}K&>Sw=q1B$6E0Q4OX$NMI7fr;i^8ltfrQmyvW%*6z^ZxcwsWf#D~JY#LE{gNv_^ znK0oz2R&a}nreaPWUiCb zF>K8-G1(1x^Yg**I7j3{RLtf>xeePcbDBruiwY zJei|{GB_%DSsAa6^ z6UKU-;b+VF+xe?josW)*Szuui&C!Fr#Pf-X3$Th!;V zDcL@JrRMYJBr70tijOtPWTCV3RqW>JK7SrA2^fEMjJ<(DRz`YJrEBbk3&t=M8^5Ri zW24oH&q0N6;vDxh$||dC4trZ|^JO$Di|SBhq?gIs^*8rAYUz8%l-!o@e#_I)f8?5c z$N5w{Vw($rcc01b^Qn_wrFkTw*gK}97O{WJy5j51u5n4>J@$#%Z1WtIMl{@b8Y&#C zB&Wzhg9jrzJ%zVw0e0O0Dx=M`-FNIpia#HmXZA~%)O3Hym0;+G4H@!;raggj1~{yY z`k1_I&SNz+4CHzjv4boD5#0ati}|MaGYyl9U6m!~a-DK~u!3F&!a8^5${a=B;0~<(rQr%COq#!6w&_Ab z!hF;{h18M>=v^m7n$Gm^K6Q2fOt-J-@E0sz9D!%#Q+?BH#g*2^$0{Pj!}EXtPVRRg z2)uq!Zv02r)K7Kp3pihhUcicz6b_#GIN^Qv8i~=sW1Z6t*i-Fy=o6C}aelb0^x^Pv zZ?~@~zRsi!&EOt;W}GHhw3qR-N^v>MdH~JrcQ|+RvoDgqhm=Yu6})(H4rYDnjZHJJ zTFyFnu>NLC-D`(oM*cr?KA633r!#hJG(pJkXmd`XhC{tcX0+;q%t5 zyTtQgw#3-;@Zu@*v-!4B{r03P2j7LGBqY?~%q@rZn&|rNNI+m9fiaQdS8Sd0=V$6h znX#mz1LY+@WIE+6-N|jr_)T>A7$hbsvxx7PZs5k2nCaB|(-6WN4<9e~kkt4b z>zw1`!qnDgbgzwg7C6M~GG>)kD^^V7TY+AY35SpyKGrvdHxoIvJLg=acs`$+x)?yO z06knCl!qfdso1&PhN{Q6kzKoYC;J^y9VU6WMyz+XHmmz7kn51RqKG}~y}Z(>%-7$r z-}z~!BzbbbJ&ST5J`63XUbuO4B10)op^o6&X2DDzY`M9)gQOJi@dk?<}UNY#esA%_ECYNlo?NQtHfG@7)r~!_NOlarOVFO8Q&Z e{lC9-gPQ4>eFd5${mLZ#GjqD>w9EQ7+y585_T!5H literal 0 HcmV?d00001 diff --git a/control/mpc_lateral_controller/model_predictive_control_algorithm.md b/control/mpc_lateral_controller/model_predictive_control_algorithm.md new file mode 100644 index 0000000000000..9dec0def2e477 --- /dev/null +++ b/control/mpc_lateral_controller/model_predictive_control_algorithm.md @@ -0,0 +1,389 @@ +# MPC Algorithm + +## Introduction + +Model Predictive Control (MPC) is a control method that solves an optimization problem during each control cycle to determine an optimal control sequence based on a given vehicle model. The calculated sequence of control inputs is used to control the system. + +In simpler terms, an MPC controller calculates a series of control inputs that optimize the state and output trajectories to achieve the desired behavior. The key characteristics of an MPC control system can be summarized as follows: + +1. Prediction of Future Trajectories: MPC computes a control sequence by predicting the future state and output trajectories. The first control input is applied to the system, and this process repeats in a receding horizon manner at each control cycle. +2. Handling of Constraints: MPC is capable of handling constraints on the state and input variables during the optimization phase. This ensures that the system operates within specified limits. +3. Handling of Complex Dynamics: MPC algorithms can handle complex dynamics, whether they are linear or nonlinear in nature. + +The choice between a linear or nonlinear model or constraint equation depends on the specific formulation of the MPC problem. If any nonlinear expressions are present in the motion equation or constraints, the optimization problem becomes nonlinear. In the following sections, we provide a step-by-step explanation of how linear and nonlinear optimization problems are solved within the MPC framework. Note that in this documentation, we utilize the linearization method to accommodate the nonlinear model. + +## Linear MPC formulation + +### Formulate as an optimization problem + +This section provides an explanation of MPC specifically for linear systems. In the following section, it also demonstrates the formulation of a vehicle path following problem as an application. + +In the linear MPC formulation, all motion and constraint expressions are linear. For the path following problem, let's assume that the system's motion can be described by a set of equations, denoted as (1). The state evolution and measurements are presented in a discrete state space format, where matrices $A$, $B$, and $C$ represent the state transition, control, and measurement matrices, respectively. + +$$ +\begin{gather} +x_{k+1}=Ax_{k}+Bu_{k}+w_{k}, y_{k}=Cx_{k} \tag{1} \\ +x_{k}\in R^{n},u_{k}\in R^{m},w_{k}\in R^{n}, y_{k}\in R^{l}, A\in R^{n\times n}, B\in R^{n\times m}, C\in R^{l \times n} +\end{gather} +$$ + +Equation (1) represents the state-space equation, where $x_k$ represents the internal states, $u_k$ denotes the input, and $w_k$ represents a known disturbance caused by linearization or problem structure. The measurements are indicated by the variable $y_k$. + +It's worth noting that another advantage of MPC is its ability to effectively handle the disturbance term $w$. While it is referred to as a disturbance here, it can take various forms as long as it adheres to the equation's structure. + +The state transition and measurement equations in (1) are iterative, moving from time $k$ to time $k+1$. By propagating the equation starting from an initial state and control pair $(x_0, u_0)$ along with a specified horizon of $N$ steps, one can predict the trajectories of states and measurements. + +For simplicity, let's assume the initial state is $x_0$ with $k=0$. + +To begin, we can compute the state $x_1$ at $k=1$ using equation (1) by substituting the initial state into the equation. Since we are seeking a solution for the input sequence, we represent the inputs as decision variables in the symbolic expressions. + +$$ +\begin{align} +x_{1} = Ax_{0} + Bu_{0} + w_{0} \tag{2} +\end{align} +$$ + +Then, when $k=2$, using also equation (2), we get + +$$ +\begin{align} +x_{2} & = Ax_{1} + Bu_{1} + w_{1} \\ +& = A(Ax_{0} + Bu_{0} + w_{0}) + Bu_{1} + w_{1} \\ +& = A^{2}x_{0} + ABu_{0} + Aw_{0} + Bu_{1} + w_{1} \\ +& = A^{2}x_{0} + \begin{bmatrix}AB & B \end{bmatrix}\begin{bmatrix}u_{0}\\ u_{1} \end{bmatrix} + \begin{bmatrix}A & I \end{bmatrix}\begin{bmatrix}w_{0}\\ w_{1} \end{bmatrix} \tag{3} +\end{align} +$$ + +When $k=3$ , from equation (3) + +$$ +\begin{align} +x_{3} & = Ax_{2} + Bu_{2} + w_{2} \\ +& = A(A^{2}x_{0} + ABu_{0} + Bu_{1} + Aw_{0} + w_{1} ) + Bu_{2} + w_{2} \\ +& = A^{3}x_{0} + A^{2}Bu_{0} + ABu_{1} + A^{2}w_{0} + Aw_{1} + Bu_{2} + w_{2} \\ +& = A^{3}x_{0} + \begin{bmatrix}A^{2}B & AB & B \end{bmatrix}\begin{bmatrix}u_{0}\\ u_{1} \\ u_{2} \end{bmatrix} + \begin{bmatrix} A^{2} & A & I \end{bmatrix}\begin{bmatrix}w_{0}\\ w_{1} \\ w_{2} \end{bmatrix} \tag{4} +\end{align} +$$ + +If $k=n$ , then + +$$ +\begin{align} +x_{n} = A^{n}x_{0} + \begin{bmatrix}A^{n-1}B & A^{n-2}B & \dots & B \end{bmatrix}\begin{bmatrix}u_{0}\\ u_{1} \\ \vdots \\ u_{n-1} \end{bmatrix} + \begin{bmatrix} A^{n-1} & A^{n-2} & \dots & I \end{bmatrix}\begin{bmatrix}w_{0}\\ w_{1} \\ \vdots \\ w_{n-1} \end{bmatrix} +\tag{5} +\end{align} +$$ + +Putting all of them together with (2) to (5) yields the following matrix equation; + +$$ +\begin{align} +\begin{bmatrix}x_{1}\\ x_{2} \\ x_{3} \\ \vdots \\ x_{n} \end{bmatrix} = \begin{bmatrix}A^{1}\\ A^{2} \\ A^{3} \\ \vdots \\ A^{n} \end{bmatrix}x_{0} + \begin{bmatrix}B & 0 & \dots & & 0 \\ AB & B & 0 & \dots & 0 \\ A^{2}B & AB & B & \dots & 0 \\ \vdots & \vdots & & & 0 \\ A^{n-1}B & A^{n-2}B & \dots & AB & B \end{bmatrix}\begin{bmatrix}u_{0}\\ u_{1} \\ u_{2} \\ \vdots \\ u_{n-1} \end{bmatrix} \\ + +\begin{bmatrix}I & 0 & \dots & & 0 \\ A & I & 0 & \dots & 0 \\ A^{2} & A & I & \dots & 0 \\ \vdots & \vdots & & & 0 \\ A^{n-1} & A^{n-2} & \dots & A & I \end{bmatrix}\begin{bmatrix}w_{0}\\ w_{1} \\ w_{2} \\ \vdots \\ w_{n-1} \end{bmatrix} +\tag{6} +\end{align} +$$ + +In this case, the measurements (outputs) become; $y_{k}=Cx_{k}$, so + +$$ +\begin{align} +\begin{bmatrix}y_{1}\\ y_{2} \\ y_{3} \\ \vdots \\ y_{n} \end{bmatrix} = \begin{bmatrix}C & 0 & \dots & & 0 \\ 0 & C & 0 & \dots & 0 \\ 0 & 0 & C & \dots & 0 \\ \vdots & & & \ddots & 0 \\ 0 & \dots & 0 & 0 & C \end{bmatrix}\begin{bmatrix}x_{1}\\ x_{2} \\ x_{3} \\ \vdots \\ x_{n} \end{bmatrix} \tag{7} +\end{align} +$$ + +We can combine equations (6) and (7) into the following form: + +$$ +\begin{align} +X = Fx_{0} + GU +SW, Y=HX \tag{8} +\end{align} +$$ + +This form is similar to the original state-space equations (1), but it introduces new matrices: the state transition matrix $F$, control matrix $G$, disturbance matrix $W$, and measurement matrix $H$. In these equations, $X$ represents the predicted states, given by $\begin{bmatrix}x_{1} & x_{2} & \dots & x_{n} \end{bmatrix}^{T}$. + +Now that $G$, $S$, $W$, and $H$ are known, we can express the output behavior $Y$ for the next $n$ steps as a function of the input $U$. This allows us to calculate the control input $U$ so that $Y(U)$ follows the target trajectory $Y_{ref}$. + +The next step is to define a cost function. The cost function generally uses the following quadratic form; + +$$ +\begin{align} +J = (Y - Y_{ref})^{T}Q(Y - Y_{ref}) + (U - U_{ref})^{T}R(U - U_{ref}) \tag{9} +\end{align} +$$ + +where $U_{ref}$ is the target or steady-state input around which the system is linearized for $U$. + +This cost function is the same as that of the LQR controller. The first term of $J$ penalizes the deviation from the reference trajectory. The second term penalizes the deviation from the reference (or steady-state) control trajectory. The $Q$ and $R$ are the cost weights Positive and Positive semi-semidefinite matrices. + +Note: in some cases, $U_{ref}=0$ is used, but this can mean the steering angle should be set to $0$ even if the vehicle is turning a curve. Thus $U_{ref}$ is used for the explanation here. This $U_{ref}$ can be pre-calculated from the curvature of the target trajectory or the steady-state analyses. + +As the resulting trajectory output is now $Y=Y(x_{0}, U)$, the cost function depends only on U and the initial state conditions which yields the cost $J=J(x_{0}, U)$. Let’s find the $U$ that minimizes this. + +Substituting equation (8) into equation (9) and tidying up the equation for $U$. + +$$ +\begin{align} +J(U) &= (H(Fx_{0}+GU+SW)-Y_{ref})^{T}Q(H(Fx_{0}+GU+SW)-Y_{ref})+(U-U_{ref})^{T}R(U-U_{ref}) \\ +& =U^{T}(G^{T}H^{T}QHG+R)U+2\left\{(H(Fx_{0}+SW)-Yref)^{T}QHG-U_{ref}^{T}R\right\}U +(\rm{constant}) \tag{10} +\end{align} +$$ + +This equation is a quadratic form of $U$ (i.e. $U^{T}AU+B^{T}U$) + +The coefficient matrix of the quadratic term of $U$, $G^{T}C^{T}QCG+R$ , is positive definite due to the positive and semi-positive definiteness requirement for $Q$ and $R$. Therefore, the cost function is a convex quadratic function in U, which can efficiently be solved by convex optimization. + +### Apply to vehicle path-following problem (nonlinear problem) + +Because the path-following problem with a kinematic vehicle model is nonlinear, we cannot directly use the linear MPC methods described in the preceding section. There are several ways to deal with a nonlinearity such as using the nonlinear optimization solver. Here, the linearization is applied to the nonlinear vehicle model along the reference trajectory, and consequently, the nonlinear model is converted into a linear time-varying model. + +For a nonlinear kinematic vehicle model, the discrete-time update equations are as follows: + +$$ +\begin{align} +x_{k+1} &= x_{k} + v\cos\theta_{k} \text{d}t \\ +y_{k+1} &= y_{k} + v\sin\theta_{k} \text{d}t \\ +\theta_{k+1} &= \theta_{k} + \frac{v\tan\delta_{k}}{L} \text{d}t \tag{11} \\ +\delta_{k+1} &= \delta_{k} - \tau^{-1}\left(\delta_{k}-\delta_{des}\right)\text{d}t +\end{align} +$$ + +![vehicle_kinematics](./image/vehicle_kinematics.png) + +The vehicle reference is the center of the rear axle and all states are measured at this point. The states, parameters, and control variables are shown in the following table. + +| Symbol | Represent | +| -------------- | ------------------------------------------------------------- | +| $v$ | Vehicle speed measured at the center of rear axle | +| $\theta$ | Yaw (heading angle) in global coordinate system | +| $\delta$ | Vehicle steering angle | +| $\delta_{des}$ | Vehicle target steering angle | +| $L$ | Vehicle wheelbase (distance between the rear and front axles) | +| $\tau$ | Time constant for the first order steering dynamics | + +We assume in this example that the MPC only generates the steering control, and the trajectory generator gives the vehicle speed along the trajectory. + +The kinematic vehicle model discrete update equations contain trigonometric functions; sin and cos, and the vehicle coordinates $x$, $y$, and yaw angles are global coordinates. In path tracking applications, it is common to reformulate the model in error dynamics to convert the control into a regulator problem in which the targets become zero (zero error). + +![vehicle_error_kinematics](./image/vehicle_error_kinematics.png) + +We make small angle assumptions for the following derivations of linear equations. Given the nonlinear dynamics and omitting the longitudinal coordinate $x$, the resulting set of equations become; + +$$ +\begin{align} +y_{k+1} &= y_{k} + v\sin\theta_{k} \text{d}t \\ +\theta_{k+1} &= \theta_{k} + \frac{v\tan\delta_{k}}{L} \text{d}t - \kappa_{r}v\cos\theta_{k}\text{d}t +\tag{12} \\ +\delta_{k+1} &= \delta_{k} - \tau^{-1}\left(\delta_{k}-\delta_{des}\right)\text{d}t +\end{align} +$$ + +Where $\kappa_{r}\left(s\right)$ is the curvature along the trajectory parametrized by the arc length. + +There are three expressions in the update equations that are subject to linear approximation: the lateral deviation (or lateral coordinate) $y$, the heading angle (or the heading angle error) $\theta$, and the steering $\delta$. We can make a small angle assumption on the heading angle $\theta$. + +In the path tracking problem, the curvature of the trajectory $\kappa_{r}$ is known in advance. At the lower speeds, the Ackermann formula approximates the reference steering angle $\theta_{r}$(this value corresponds to the $U_{ref}$ mentioned above). The Ackerman steering expression can be written as; + +$$ +\begin{align} +\delta_{r} = \arctan\left(L\kappa_{r}\right) +\end{align} +$$ + +When the vehicle is turning a path, its steer angle $\delta$ should be close to the value $\delta_{r}$. Therefore, $\delta$ can be expressed, + +$$ +\begin{align} +\delta = \delta_{r} + \Delta \delta, \Delta\delta \ll 1 +\end{align} +$$ + +Substituting this equation into equation (12), and approximate $\Delta\delta$ to be small. + +$$ +\begin{align} +\tan\delta &\simeq \tan\delta_{r} + \frac{\text{d}\tan\delta}{\text{d}\delta} \Biggm|_{\delta=\delta_{r}}\Delta\delta \\ +&= \tan \delta_{r} + \frac{1}{\cos^{2}\delta_{r}}\Delta\delta \\ +&= \tan \delta_{r} + \frac{1}{\cos^{2}\delta_{r}}\left(\delta-\delta_{r}\right) \\ +&= \tan \delta_{r} - \frac{\delta_{r}}{\cos^{2}\delta_{r}} + \frac{1}{\cos^{2}\delta_{r}}\delta +\end{align} +$$ + +Using this, $\theta_{k+1}$ can be expressed + +$$ +\begin{align} +\theta_{k+1} &= \theta_{k} + \frac{v\tan\delta_{k}}{L}\text{d}t - \kappa_{r}v\cos\delta_{k}\text{d}t \\ +&\simeq \theta_{k} + \frac{v}{L}\text{d}t\left(\tan\delta_{r} - \frac{\delta_{r}}{\cos^{2}\delta_{r}} + \frac{1}{\cos^{2}\delta_{r}}\delta_{k} \right) - \kappa_{r}v\text{d}t \\ +&= \theta_{k} + \frac{v}{L}\text{d}t\left(L\kappa_{r} - \frac{\delta_{r}}{\cos^{2}\delta_{r}} + \frac{1}{\cos^{2}\delta_{r}}\delta_{k} \right) - \kappa_{r}v\text{d}t \\ +&= \theta_{k} + \frac{v}{L}\frac{\text{d}t}{\cos^{2}\delta_{r}}\delta_{k} - \frac{v}{L}\frac{\delta_{r}\text{d}t}{\cos^{2}\delta_{r}} +\end{align} +$$ + +Finally, the linearized time-varying model equation becomes; + +$$ +\begin{align} +\begin{bmatrix} y_{k+1} \\ \theta_{k+1} \\ \delta_{k+1} \end{bmatrix} = \begin{bmatrix} 1 & v\text{d}t & 0 \\ 0 & 1 & \frac{v}{L}\frac{\text{d}t}{\cos^{2}\delta_{r}} \\ 0 & 0 & 1 - \tau^{-1}\text{d}t \end{bmatrix} \begin{bmatrix} y_{k} \\ \theta_{k} \\ \delta_{k} \end{bmatrix} + \begin{bmatrix} 0 \\ 0 \\ \tau^{-1}\text{d}t \end{bmatrix}\delta_{des} + \begin{bmatrix} 0 \\ -\frac{v}{L}\frac{\delta_{r}\text{d}t}{\cos^{2}\delta_{r}} \\ 0 \end{bmatrix} +\end{align} +$$ + +This equation has the same form as equation (1) of the linear MPC assumption, but the matrices $A$, $B$, and $w$ change depending on the coordinate transformation. To make this explicit, the entire equation is written as follows + +$$ +\begin{align} +x_{k+1} = A_{k}x_{k} + B_{k}u_{k}+w_{k} +\end{align} +$$ + +Comparing equation (1), $A \rightarrow A_{k}$. This means that the $A$ matrix is a linear approximation in the vicinity of the trajectory after $k$ steps (i.e., $k* \text{d}t$ seconds), and it can be obtained if the trajectory is known in advance. + +Using this equation, write down the update equation likewise (2) ~ (6) + +$$ +\begin{align} +\begin{bmatrix} + x_{1} \\ x_{2} \\ x_{3} \\ \vdots \\ x_{n} +\end{bmatrix} += \begin{bmatrix} + A_{1} \\ A_{1}A_{0} \\ A_{2}A_{1}A_{0} \\ \vdots \\ \prod_{i=0}^{n-1} A_{k} +\end{bmatrix} +x_{0} + +\begin{bmatrix} + B_{0} & 0 & \dots & & 0 \\ A_{1}B_{0} & B_{1} & 0 & \dots & 0 \\ A_{2}A_{1}B_{0} & A_{2}B_{1} & B_{2} & \dots & 0 \\ \vdots & \vdots & &\ddots & 0 \\ \prod_{i=1}^{n-1} A_{k}B_{0} & \prod_{i=2}^{n-1} A_{k}B_{1} & \dots & A_{n-1}B_{n-1} & B_{n-1} +\end{bmatrix} +\begin{bmatrix} + u_{0} \\ u_{1} \\ u_{2} \\ \vdots \\ u_{n-1} +\end{bmatrix} + +\begin{bmatrix} +I & 0 & \dots & & 0 \\ A_{1} & I & 0 & \dots & 0 \\ A_{2}A_{1} & A_{2} & I & \dots & 0 \\ \vdots & \vdots & &\ddots & 0 \\ \prod_{i=1}^{n-1} A_{k} & \prod_{i=2}^{n-1} A_{k} & \dots & A_{n-1} & I +\end{bmatrix} +\begin{bmatrix} + w_{0} \\ w_{1} \\ w_{2} \\ \vdots \\ w_{n-1} +\end{bmatrix} +\end{align} +$$ + +As it has the same form as equation (6), convex optimization is applicable for as much as the model in the former section. + +## The cost functions and constraints + +In this section, we give the details on how to set up the cost function and constraint conditions. + +### The cost function + +#### Weight for error and input + +MPC states and control weights appear in the cost function in a similar way as LQR (9). In the vehicle path following the problem described above, if C is the unit matrix, the output $y = x = \left[y, \theta, \delta\right]$. (To avoid confusion with the y-directional deviation, here $e$ is used for the lateral deviation.) + +As an example, let's determine the weight matrix $Q_{1}$ of the evaluation function for the number of prediction steps $n=2$ system as follows. + +$$ +\begin{align} +Q_{1} = \begin{bmatrix} q_{e} & 0 & 0 & 0 & 0& 0 \\ 0 & q_{\theta} & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & q_{e} & 0 & 0 \\ 0 & 0 & 0 & 0 & q_{\theta} & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \end{bmatrix} +\end{align} +$$ + +The first term in the cost function (9) with $n=2$, is shown as follow ($Y_{ref}$ is set to $0$) + +$$ +\begin{align} +q_{e}\left(e_{0}^{2} + e_{1}^{2} \right) + q_{\theta}\left(\theta_{0}^{2} + \theta_{1}^{2} \right) +\end{align} +$$ + +This shows that $q_{e}$ is the weight for the lateral error and $q$ is for the angular error. In this example, $q_{e}$ acts as the proportional - P gain and $q_{\theta}$ as the derivative - D gain for the lateral tracking error. The balance of these factors (including R) will be determined through actual experiments. + +#### Weight for non-diagonal term + +MPC can handle the non-diagonal term in its calculation (as long as the resulting matrix is positive definite). + +For instance, write $Q_{2}$ as follows for the $n=2$ system. + +$$ +\begin{align} +Q_{2} = \begin{bmatrix} 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & q_{d} & 0 & 0 & -q_{d} \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & -q_{d} & 0 & 0 & q_{d} \end{bmatrix} +\end{align} +$$ + +Expanding the first term of the evaluation function using $Q_{2}$ + +$$ +\begin{align} +q_{d}\left(\delta_{0}^{2} -2\delta_{0}\delta_{1} + \delta_{1}^{2} \right) = q_{d}\left( \delta_{0} - \delta_{1}\right)^{2} +\end{align} +$$ + +The value of $q_{d}$ is weighted by the amount of change in $\delta$, which will prevent the tire from moving quickly. By adding this section, the system can evaluate the balance between tracking accuracy and change of steering wheel angle. + +Since the weight matrix can be added linearly, the final weight can be set as $Q = Q_{1} + Q_{2}$. + +Furthermore, MPC optimizes over a period of time, the time-varying weight can be considered in the optimization. + +### Constraints + +#### Input constraint + +The main advantage of MPC controllers is the capability to deal with any state or input constraints. The constraints can be expressed as box constraints, such as "the tire angle must be within ±30 degrees", and can be put in the following form; + +$$ +\begin{align} +u_{min} < u < u_{max} +\end{align} +$$ + +The constraints must be linear and convex in the linear MPC applications. + +#### Constraints on the derivative of the input + +We can also put constraints on the input deviations. As the derivative of steering angle is $\dot{u}$, its box constraint is + +$$ +\begin{align} +\dot{u}_{min} < \dot{u} < \dot{u}_{max} +\end{align} +$$ + +Discretisizing $\dot{u}$ as $\left(u_{k} - u_{k-1}\right)/\text{d}t$ and multiply both sides by dt the resulting constraint become linear and convex + +$$ +\begin{align} +\dot{u}_{min}\text{d}t < u_{k} - u_{k-1} < \dot{u}_{max}\text{d}t +\end{align} +$$ + +Along the prediction or control horizon, i.e for setting $n=3$ + +$$ +\begin{align} +\dot{u}_{min}\text{d}t < u_{1} - u_{0} < \dot{u}_{max}\text{d}t \\ +\dot{u}_{min}\text{d}t < u_{2} - u_{1} < \dot{u}_{max}\text{d}t +\end{align} +$$ + +and aligning the inequality signs + +$$ +\begin{align} +u_{1} - u_{0} &< \dot{u}_{max}\text{d}t \\ + +u_{1} + u_{0} &< -\dot{u}_{min}\text{d}t \\ +u_{2} - u_{1} &< \dot{u}_{max}\text{d}t \\ + +u_{2} + u_{1} &< - \dot{u}_{min}\text{d}t +\end{align} +$$ + +We can obtain a matrix expression for the resulting constraint equation in the form of + +$$ +\begin{align} +Ax \leq b +\end{align} +$$ + +Thus, putting this inequality to fit the form above, the constraints against $\dot{u}$ can be included at the first-order approximation level. + +$$ +\begin{align} +\begin{bmatrix} -1 & 1 & 0 \\ 1 & -1 & 0 \\ 0 & -1 & 1 \\ 0 & 1 & -1 \end{bmatrix}\begin{bmatrix} u_{0} \\ u_{1} \\ u_{2} \end{bmatrix} \leq \begin{bmatrix} \dot{u}_{max}\text{d}t \\ -\dot{u}_{min}\text{d}t \\ \dot{u}_{max}\text{d}t \\ -\dot{u}_{min}\text{d}t \end{bmatrix} +\end{align} +$$ From 1bf505638c35fbfb36f0675294c66d81e2dadd48 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 3 Jul 2023 05:00:30 +0900 Subject: [PATCH 069/118] style: fix typos in PlotJuggler config files (#3618) Signed-off-by: Kenji Miyake --- .../config/controller_monitor.xml | 12 ++++++------ .../config/error_rqt_multiplot.xml | 2 +- ..._pursuit_lateral_controller_plotjuggler_debug.xml | 10 +++++----- .../config/plot_juggler_trajectory_follower.xml | 8 ++++---- .../config/plot_juggler_obstacle_cruise_planner.xml | 10 +++++----- .../config/plot_juggler_adaptive_cruise.xml | 8 ++++---- .../config/plot_juggler_slow_down.xml | 8 ++++---- .../config/planning_validator_plotjugler_config.xml | 10 +++++----- .../config/processing_time_ms.xml | 8 ++++---- 9 files changed, 38 insertions(+), 38 deletions(-) diff --git a/control/control_performance_analysis/config/controller_monitor.xml b/control/control_performance_analysis/config/controller_monitor.xml index c5189ccec4110..cb3f38e55e5f0 100644 --- a/control/control_performance_analysis/config/controller_monitor.xml +++ b/control/control_performance_analysis/config/controller_monitor.xml @@ -287,7 +287,7 @@ - + @@ -381,7 +381,7 @@ - + @@ -389,7 +389,7 @@ - + @@ -405,14 +405,14 @@ - + - + - + sum = 0 sum = sum + math.abs(value) diff --git a/control/control_performance_analysis/config/error_rqt_multiplot.xml b/control/control_performance_analysis/config/error_rqt_multiplot.xml index b80449fb9067e..8597cbdaa253e 100644 --- a/control/control_performance_analysis/config/error_rqt_multiplot.xml +++ b/control/control_performance_analysis/config/error_rqt_multiplot.xml @@ -726,7 +726,7 @@ true 30 - Measured and Computed Steerings Plot + Measured and Computed Steering Plot diff --git a/control/pure_pursuit/config/pure_pursuit_lateral_controller_plotjuggler_debug.xml b/control/pure_pursuit/config/pure_pursuit_lateral_controller_plotjuggler_debug.xml index 284380c654255..9e0fc652652c3 100644 --- a/control/pure_pursuit/config/pure_pursuit_lateral_controller_plotjuggler_debug.xml +++ b/control/pure_pursuit/config/pure_pursuit_lateral_controller_plotjuggler_debug.xml @@ -77,7 +77,7 @@ - + @@ -85,7 +85,7 @@ - + @@ -98,15 +98,15 @@ - + - + - + diff --git a/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml b/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml index 303ba94ddb399..6956db84aff56 100644 --- a/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml +++ b/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml @@ -243,13 +243,13 @@ - + - + @@ -263,11 +263,11 @@ - + - + diff --git a/planning/obstacle_cruise_planner/config/plot_juggler_obstacle_cruise_planner.xml b/planning/obstacle_cruise_planner/config/plot_juggler_obstacle_cruise_planner.xml index b1a5275feda37..75500da8d2d49 100644 --- a/planning/obstacle_cruise_planner/config/plot_juggler_obstacle_cruise_planner.xml +++ b/planning/obstacle_cruise_planner/config/plot_juggler_obstacle_cruise_planner.xml @@ -145,13 +145,13 @@ - + - + @@ -167,15 +167,15 @@ - + - + - + diff --git a/planning/obstacle_stop_planner/config/plot_juggler_adaptive_cruise.xml b/planning/obstacle_stop_planner/config/plot_juggler_adaptive_cruise.xml index 5770820fbba1d..b7c37e5077c55 100644 --- a/planning/obstacle_stop_planner/config/plot_juggler_adaptive_cruise.xml +++ b/planning/obstacle_stop_planner/config/plot_juggler_adaptive_cruise.xml @@ -102,14 +102,14 @@ - + - + @@ -121,11 +121,11 @@ - + - + diff --git a/planning/obstacle_stop_planner/config/plot_juggler_slow_down.xml b/planning/obstacle_stop_planner/config/plot_juggler_slow_down.xml index cbb840b12552a..92b56c2d2e6e4 100644 --- a/planning/obstacle_stop_planner/config/plot_juggler_slow_down.xml +++ b/planning/obstacle_stop_planner/config/plot_juggler_slow_down.xml @@ -57,13 +57,13 @@ - + - + @@ -81,11 +81,11 @@ - + - + diff --git a/planning/planning_validator/config/planning_validator_plotjugler_config.xml b/planning/planning_validator/config/planning_validator_plotjugler_config.xml index d331ed9985dfc..d6afc0b017d32 100644 --- a/planning/planning_validator/config/planning_validator_plotjugler_config.xml +++ b/planning/planning_validator/config/planning_validator_plotjugler_config.xml @@ -120,13 +120,13 @@ - + - + @@ -140,15 +140,15 @@ - + - + - + diff --git a/sensing/pointcloud_preprocessor/config/processing_time_ms.xml b/sensing/pointcloud_preprocessor/config/processing_time_ms.xml index 5da1ec3720fb0..569e2e34df670 100644 --- a/sensing/pointcloud_preprocessor/config/processing_time_ms.xml +++ b/sensing/pointcloud_preprocessor/config/processing_time_ms.xml @@ -29,7 +29,7 @@ - + @@ -37,7 +37,7 @@ - + @@ -53,11 +53,11 @@ - + - + From 679c94b1bde7a023eea8155314c5597602526e98 Mon Sep 17 00:00:00 2001 From: Ambroise Vincent Date: Sun, 2 Jul 2023 22:21:38 +0200 Subject: [PATCH 070/118] ci: add JSON Schema validation (#4122) * ci: add JSON Schema validation Leverage the json-schema-check action from the autoware-github-actions repository. Issue-Id: SCM-6366 Signed-off-by: Ambroise Vincent Change-Id: I5f284e96b2eddc652a6da8c0338f92c411277c04 * Update .github/workflows/json-schema-check.yaml Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --------- Signed-off-by: Ambroise Vincent Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .github/workflows/json-schema-check.yaml | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) create mode 100644 .github/workflows/json-schema-check.yaml diff --git a/.github/workflows/json-schema-check.yaml b/.github/workflows/json-schema-check.yaml new file mode 100644 index 0000000000000..3d0c0b83d8746 --- /dev/null +++ b/.github/workflows/json-schema-check.yaml @@ -0,0 +1,17 @@ +name: json-schema-check + +on: + pull_request: + paths: + - "**/schema/*.schema.json" + - "**/config/*.param.yaml" + +jobs: + json-schema-check: + runs-on: ubuntu-latest + steps: + - name: Check out repository + uses: actions/checkout@v3 + + - name: Run json-schema-check + uses: autowarefoundation/autoware-github-actions/json-schema-check@v1 From 01366133938655ae1b1fe698bbd24abec15dcd94 Mon Sep 17 00:00:00 2001 From: Kah Hooi Tan <41041286+tkhmy@users.noreply.github.com> Date: Mon, 3 Jul 2023 11:36:49 +0900 Subject: [PATCH 071/118] feat: add vehicle status api (#2930) * add vehicle status api Signed-off-by: tkhmy * update msgs Signed-off-by: tkhmy * change naming Signed-off-by: tkhmy * ada none Signed-off-by: tkhmy * change naming Signed-off-by: tkhmy * add publish geoposition Signed-off-by: tkhmy * add door status Signed-off-by: tkhmy * change variable naming Signed-off-by: tkhmy * change variable naming Signed-off-by: tkhmy * update license Signed-off-by: tkhmy * fix gps convert Signed-off-by: tkhmy * add support for UTM reverse Signed-off-by: tkhmy * fix naming Signed-off-by: tkhmy * update naming Signed-off-by: tkhmy * fix naming Signed-off-by: tkhmy * remote door status Signed-off-by: tkhmy * clean up vehicle.hpp Signed-off-by: tkhmy * fix missing declare Signed-off-by: tkhmy * move convert to cpp Signed-off-by: tkhmy * move convert to timer callback Signed-off-by: tkhmy * set to nan when no projector info Signed-off-by: tkhmy * added checking message valid Signed-off-by: tkhmy * fix msgs Signed-off-by: tkhmy --------- Signed-off-by: tkhmy --- .../include/autoware_ad_api_specs/vehicle.hpp | 20 ++ .../localization.hpp | 10 + .../include/component_interface_specs/map.hpp | 36 +++ .../component_interface_specs/vehicle.hpp | 76 +++++++ common/component_interface_specs/package.xml | 3 + system/default_ad_api/CMakeLists.txt | 2 + .../launch/default_ad_api.launch.py | 1 + system/default_ad_api/package.xml | 4 + system/default_ad_api/src/vehicle.cpp | 208 ++++++++++++++++++ system/default_ad_api/src/vehicle.hpp | 91 ++++++++ 10 files changed, 451 insertions(+) create mode 100644 common/component_interface_specs/include/component_interface_specs/map.hpp create mode 100644 common/component_interface_specs/include/component_interface_specs/vehicle.hpp create mode 100644 system/default_ad_api/src/vehicle.cpp create mode 100644 system/default_ad_api/src/vehicle.hpp diff --git a/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp index 4d5acd544b41d..0baf8531d00c8 100644 --- a/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp +++ b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp @@ -17,11 +17,31 @@ #include +#include +#include #include namespace autoware_ad_api::vehicle { +struct VehicleKinematics +{ + using Message = autoware_adapi_v1_msgs::msg::VehicleKinematics; + static constexpr char name[] = "/api/vehicle/kinematics"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + +struct VehicleStatus +{ + using Message = autoware_adapi_v1_msgs::msg::VehicleStatus; + static constexpr char name[] = "/api/vehicle/status"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + struct Dimensions { using Service = autoware_adapi_v1_msgs::srv::GetVehicleDimensions; diff --git a/common/component_interface_specs/include/component_interface_specs/localization.hpp b/common/component_interface_specs/include/component_interface_specs/localization.hpp index 89740ffbb1f4c..70c590c837927 100644 --- a/common/component_interface_specs/include/component_interface_specs/localization.hpp +++ b/common/component_interface_specs/include/component_interface_specs/localization.hpp @@ -19,6 +19,7 @@ #include #include +#include #include namespace localization_interface @@ -48,6 +49,15 @@ struct KinematicState static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; +struct Acceleration +{ + using Message = geometry_msgs::msg::AccelWithCovarianceStamped; + static constexpr char name[] = "/localization/acceleration"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + } // namespace localization_interface #endif // COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/map.hpp b/common/component_interface_specs/include/component_interface_specs/map.hpp new file mode 100644 index 0000000000000..f0cce7a7f97a2 --- /dev/null +++ b/common/component_interface_specs/include/component_interface_specs/map.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 COMPONENT_INTERFACE_SPECS__MAP_HPP_ +#define COMPONENT_INTERFACE_SPECS__MAP_HPP_ + +#include + +#include + +namespace map_interface +{ + +struct MapProjectorInfo +{ + using Message = tier4_map_msgs::msg::MapProjectorInfo; + static constexpr char name[] = "/map/map_projector_type"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; +}; + +} // namespace map_interface + +#endif // COMPONENT_INTERFACE_SPECS__MAP_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/vehicle.hpp b/common/component_interface_specs/include/component_interface_specs/vehicle.hpp new file mode 100644 index 0000000000000..ecbf7a21e1299 --- /dev/null +++ b/common/component_interface_specs/include/component_interface_specs/vehicle.hpp @@ -0,0 +1,76 @@ +// 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 COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ +#define COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ + +#include + +#include +#include +#include +#include +#include + +namespace vehicle_interface +{ + +struct SteeringStatus +{ + using Message = autoware_auto_vehicle_msgs::msg::SteeringReport; + static constexpr char name[] = "/vehicle/status/steering_status"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + +struct GearStatus +{ + using Message = autoware_auto_vehicle_msgs::msg::GearReport; + static constexpr char name[] = "/vehicle/status/gear_status"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + +struct TurnIndicatorStatus +{ + using Message = autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport; + static constexpr char name[] = "/vehicle/status/turn_indicators_status"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + +struct HazardLightStatus +{ + using Message = autoware_auto_vehicle_msgs::msg::HazardLightsReport; + static constexpr char name[] = "/vehicle/status/hazard_lights_status"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + +struct EnergyStatus +{ + using Message = tier4_vehicle_msgs::msg::BatteryStatus; + static constexpr char name[] = "/vehicle/status/battery_charge"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + +} // namespace vehicle_interface + +#endif // COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ diff --git a/common/component_interface_specs/package.xml b/common/component_interface_specs/package.xml index d4fe460a6daea..7ebc3f0d1bea9 100644 --- a/common/component_interface_specs/package.xml +++ b/common/component_interface_specs/package.xml @@ -14,6 +14,9 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_auto_vehicle_msgs + tier4_map_msgs + tier4_vehicle_msgs ament_lint_auto autoware_lint_common diff --git a/system/default_ad_api/CMakeLists.txt b/system/default_ad_api/CMakeLists.txt index 28eec2e8eefc0..7bb80164bb9a0 100644 --- a/system/default_ad_api/CMakeLists.txt +++ b/system/default_ad_api/CMakeLists.txt @@ -12,6 +12,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/operation_mode.cpp src/planning.cpp src/routing.cpp + src/vehicle.cpp src/vehicle_info.cpp src/utils/route_conversion.cpp src/compatibility/autoware_state.cpp @@ -26,6 +27,7 @@ rclcpp_components_register_nodes(${PROJECT_NAME} "default_ad_api::OperationModeNode" "default_ad_api::PlanningNode" "default_ad_api::RoutingNode" + "default_ad_api::VehicleNode" "default_ad_api::VehicleInfoNode" ) diff --git a/system/default_ad_api/launch/default_ad_api.launch.py b/system/default_ad_api/launch/default_ad_api.launch.py index c9a3abf9f8e5d..fdb79d517206d 100644 --- a/system/default_ad_api/launch/default_ad_api.launch.py +++ b/system/default_ad_api/launch/default_ad_api.launch.py @@ -49,6 +49,7 @@ def generate_launch_description(): create_api_node("operation_mode", "OperationModeNode"), create_api_node("planning", "PlanningNode"), create_api_node("routing", "RoutingNode"), + create_api_node("vehicle", "VehicleNode"), create_api_node("vehicle_info", "VehicleInfoNode"), ] container = ComposableNodeContainer( diff --git a/system/default_ad_api/package.xml b/system/default_ad_api/package.xml index 3e11cbb2952ed..032335fdddfd2 100644 --- a/system/default_ad_api/package.xml +++ b/system/default_ad_api/package.xml @@ -19,13 +19,17 @@ autoware_adapi_version_msgs autoware_auto_planning_msgs autoware_auto_system_msgs + autoware_auto_vehicle_msgs autoware_planning_msgs component_interface_specs component_interface_utils + lanelet2_extension motion_utils + nav_msgs rclcpp rclcpp_components std_srvs + tier4_api_msgs tier4_control_msgs tier4_system_msgs vehicle_info_util diff --git a/system/default_ad_api/src/vehicle.cpp b/system/default_ad_api/src/vehicle.cpp new file mode 100644 index 0000000000000..4cd7f370a55fc --- /dev/null +++ b/system/default_ad_api/src/vehicle.cpp @@ -0,0 +1,208 @@ +// 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 "vehicle.hpp" + +#include + +namespace default_ad_api +{ + +using GearReport = vehicle_interface::GearStatus::Message; +using ApiGear = autoware_adapi_v1_msgs::msg::Gear; +using TurnIndicatorsReport = vehicle_interface::TurnIndicatorStatus::Message; +using ApiTurnIndicator = autoware_adapi_v1_msgs::msg::TurnIndicators; +using HazardLightsReport = vehicle_interface::HazardLightStatus::Message; +using ApiHazardLight = autoware_adapi_v1_msgs::msg::HazardLights; +using MapProjectorInfo = map_interface::MapProjectorInfo::Message; + +std::unordered_map gear_type_ = { + {GearReport::NONE, ApiGear::UNKNOWN}, {GearReport::NEUTRAL, ApiGear::NEUTRAL}, + {GearReport::DRIVE, ApiGear::DRIVE}, {GearReport::DRIVE_2, ApiGear::DRIVE}, + {GearReport::DRIVE_3, ApiGear::DRIVE}, {GearReport::DRIVE_4, ApiGear::DRIVE}, + {GearReport::DRIVE_5, ApiGear::DRIVE}, {GearReport::DRIVE_6, ApiGear::DRIVE}, + {GearReport::DRIVE_7, ApiGear::DRIVE}, {GearReport::DRIVE_8, ApiGear::DRIVE}, + {GearReport::DRIVE_9, ApiGear::DRIVE}, {GearReport::DRIVE_10, ApiGear::DRIVE}, + {GearReport::DRIVE_11, ApiGear::DRIVE}, {GearReport::DRIVE_12, ApiGear::DRIVE}, + {GearReport::DRIVE_13, ApiGear::DRIVE}, {GearReport::DRIVE_14, ApiGear::DRIVE}, + {GearReport::DRIVE_15, ApiGear::DRIVE}, {GearReport::DRIVE_16, ApiGear::DRIVE}, + {GearReport::DRIVE_17, ApiGear::DRIVE}, {GearReport::DRIVE_18, ApiGear::DRIVE}, + {GearReport::REVERSE, ApiGear::REVERSE}, {GearReport::REVERSE_2, ApiGear::REVERSE}, + {GearReport::PARK, ApiGear::PARK}, {GearReport::LOW, ApiGear::LOW}, + {GearReport::LOW_2, ApiGear::LOW}, +}; + +std::unordered_map turn_indicator_type_ = { + {TurnIndicatorsReport::DISABLE, ApiTurnIndicator::DISABLE}, + {TurnIndicatorsReport::ENABLE_LEFT, ApiTurnIndicator::LEFT}, + {TurnIndicatorsReport::ENABLE_RIGHT, ApiTurnIndicator::RIGHT}, +}; + +std::unordered_map hazard_light_type_ = { + {HazardLightsReport::DISABLE, ApiHazardLight::DISABLE}, + {HazardLightsReport::ENABLE, ApiHazardLight::ENABLE}, +}; + +VehicleNode::VehicleNode(const rclcpp::NodeOptions & options) : Node("vehicle", options) +{ + const auto adaptor = component_interface_utils::NodeAdaptor(this); + group_cli_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + adaptor.init_pub(pub_kinematics_); + adaptor.init_pub(pub_status_); + adaptor.init_sub(sub_kinematic_state_, this, &VehicleNode::kinematic_state); + adaptor.init_sub(sub_acceleration_, this, &VehicleNode::acceleration_status); + adaptor.init_sub(sub_steering_, this, &VehicleNode::steering_status); + adaptor.init_sub(sub_gear_state_, this, &VehicleNode::gear_status); + adaptor.init_sub(sub_turn_indicator_, this, &VehicleNode::turn_indicator_status); + adaptor.init_sub(sub_map_projector_info_, this, &VehicleNode::map_projector_info); + adaptor.init_sub(sub_hazard_light_, this, &VehicleNode::hazard_light_status); + adaptor.init_sub(sub_energy_level_, this, &VehicleNode::energy_status); + + const auto rate = rclcpp::Rate(10); + timer_ = rclcpp::create_timer(this, get_clock(), rate.period(), [this]() { on_timer(); }); +} + +uint8_t VehicleNode::mapping( + std::unordered_map hash_map, uint8_t input, uint8_t default_value) +{ + if (hash_map.find(input) == hash_map.end()) { + return default_value; + } else { + return hash_map[input]; + } +} + +void VehicleNode::kinematic_state( + const localization_interface::KinematicState::Message::ConstSharedPtr msg_ptr) +{ + kinematic_state_msgs_ = msg_ptr; +} + +Eigen::Vector3d VehicleNode::toBasicPoint3dPt(const geometry_msgs::msg::Point src) +{ + Eigen::Vector3d dst; + dst.x() = src.x; + dst.y() = src.y; + dst.z() = src.z; + return dst; +} + +void VehicleNode::acceleration_status( + const localization_interface::Acceleration::Message::ConstSharedPtr msg_ptr) +{ + acceleration_msgs_ = msg_ptr; +} + +void VehicleNode::steering_status( + const vehicle_interface::SteeringStatus::Message::ConstSharedPtr msg_ptr) +{ + steering_status_msgs_ = msg_ptr; +} + +void VehicleNode::gear_status(const GearReport::ConstSharedPtr msg_ptr) +{ + gear_status_msgs_ = msg_ptr; +} + +void VehicleNode::turn_indicator_status(const TurnIndicatorsReport::ConstSharedPtr msg_ptr) +{ + turn_indicator_status_msgs_ = msg_ptr; +} + +void VehicleNode::hazard_light_status(const HazardLightsReport::ConstSharedPtr msg_ptr) +{ + hazard_light_status_msgs_ = msg_ptr; +} + +void VehicleNode::energy_status( + const vehicle_interface::EnergyStatus::Message::ConstSharedPtr msg_ptr) +{ + energy_status_msgs_ = msg_ptr; +} + +void VehicleNode::map_projector_info(const MapProjectorInfo::ConstSharedPtr msg_ptr) +{ + map_projector_info_ = msg_ptr; +} + +void VehicleNode::publish_kinematics() +{ + if (!kinematic_state_msgs_ || !acceleration_msgs_) return; + + autoware_ad_api::vehicle::VehicleKinematics::Message vehicle_kinematics; + vehicle_kinematics.pose.header = kinematic_state_msgs_->header; + vehicle_kinematics.pose.pose = kinematic_state_msgs_->pose; + vehicle_kinematics.twist.header = kinematic_state_msgs_->header; + vehicle_kinematics.twist.header.frame_id = kinematic_state_msgs_->child_frame_id; + vehicle_kinematics.twist.twist = kinematic_state_msgs_->twist; + if (map_projector_info_->type == "MGRS") { + lanelet::GPSPoint projected_gps_point = lanelet::projection::MGRSProjector::reverse( + toBasicPoint3dPt(kinematic_state_msgs_->pose.pose.position), map_projector_info_->mgrs_grid); + vehicle_kinematics.geographic_pose.header = kinematic_state_msgs_->header; + vehicle_kinematics.geographic_pose.header.frame_id = "global"; + vehicle_kinematics.geographic_pose.position.latitude = projected_gps_point.lat; + vehicle_kinematics.geographic_pose.position.longitude = projected_gps_point.lon; + vehicle_kinematics.geographic_pose.position.altitude = projected_gps_point.ele; + } else if (map_projector_info_->type == "UTM") { + lanelet::GPSPoint position{ + map_projector_info_->map_origin.latitude, map_projector_info_->map_origin.longitude}; + lanelet::Origin origin{position}; + lanelet::projection::UtmProjector projector{origin}; + lanelet::GPSPoint projected_gps_point = + projector.reverse(toBasicPoint3dPt(kinematic_state_msgs_->pose.pose.position)); + vehicle_kinematics.geographic_pose.header = kinematic_state_msgs_->header; + vehicle_kinematics.geographic_pose.header.frame_id = "global"; + vehicle_kinematics.geographic_pose.position.latitude = projected_gps_point.lat; + vehicle_kinematics.geographic_pose.position.longitude = projected_gps_point.lon; + vehicle_kinematics.geographic_pose.position.altitude = projected_gps_point.ele; + } else { + vehicle_kinematics.geographic_pose.position.latitude = std::numeric_limits::quiet_NaN(); + vehicle_kinematics.geographic_pose.position.longitude = + std::numeric_limits::quiet_NaN(); + vehicle_kinematics.geographic_pose.position.altitude = std::numeric_limits::quiet_NaN(); + } + vehicle_kinematics.accel.header = acceleration_msgs_->header; + vehicle_kinematics.accel.accel = acceleration_msgs_->accel; + pub_kinematics_->publish(vehicle_kinematics); +} + +void VehicleNode::publish_status() +{ + if ( + !steering_status_msgs_ || !gear_status_msgs_ || !turn_indicator_status_msgs_ || + hazard_light_status_msgs_ || energy_status_msgs_) + return; + + autoware_ad_api::vehicle::VehicleStatus::Message vehicle_status; + vehicle_status.stamp = now(); + vehicle_status.steering_tire_angle = steering_status_msgs_->steering_tire_angle; + vehicle_status.gear.status = mapping(gear_type_, gear_status_msgs_->report, ApiGear::UNKNOWN); + vehicle_status.turn_indicators.status = + mapping(turn_indicator_type_, turn_indicator_status_msgs_->report, ApiTurnIndicator::UNKNOWN); + vehicle_status.hazard_lights.status = + mapping(hazard_light_type_, hazard_light_status_msgs_->report, ApiHazardLight::UNKNOWN); + vehicle_status.energy_percentage = energy_status_msgs_->energy_level; + pub_status_->publish(vehicle_status); +} + +void VehicleNode::on_timer() +{ + publish_kinematics(); + publish_status(); +} + +} // namespace default_ad_api + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::VehicleNode) diff --git a/system/default_ad_api/src/vehicle.hpp b/system/default_ad_api/src/vehicle.hpp new file mode 100644 index 0000000000000..90f8b686206c5 --- /dev/null +++ b/system/default_ad_api/src/vehicle.hpp @@ -0,0 +1,91 @@ +// 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 VEHICLE_HPP_ +#define VEHICLE_HPP_ + +#include "lanelet2_extension/projection/mgrs_projector.hpp" + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include + +#include + +// This file should be included after messages. +#include "utils/types.hpp" + +namespace default_ad_api +{ + +class VehicleNode : public rclcpp::Node +{ +public: + explicit VehicleNode(const rclcpp::NodeOptions & options); + +private: + rclcpp::CallbackGroup::SharedPtr group_cli_; + Pub pub_kinematics_; + Pub pub_status_; + Sub sub_kinematic_state_; + Sub sub_acceleration_; + Sub sub_steering_; + Sub sub_gear_state_; + Sub sub_turn_indicator_; + Sub sub_hazard_light_; + Sub sub_energy_level_; + Sub sub_map_projector_info_; + rclcpp::TimerBase::SharedPtr timer_; + + localization_interface::KinematicState::Message::ConstSharedPtr kinematic_state_msgs_; + localization_interface::Acceleration::Message::ConstSharedPtr acceleration_msgs_; + vehicle_interface::SteeringStatus::Message::ConstSharedPtr steering_status_msgs_; + vehicle_interface::GearStatus::Message::ConstSharedPtr gear_status_msgs_; + vehicle_interface::TurnIndicatorStatus::Message::ConstSharedPtr turn_indicator_status_msgs_; + vehicle_interface::HazardLightStatus::Message::ConstSharedPtr hazard_light_status_msgs_; + vehicle_interface::EnergyStatus::Message::ConstSharedPtr energy_status_msgs_; + map_interface::MapProjectorInfo::Message::ConstSharedPtr map_projector_info_; + + void kinematic_state( + const localization_interface::KinematicState::Message::ConstSharedPtr msg_ptr); + void acceleration_status( + const localization_interface::Acceleration::Message::ConstSharedPtr msg_ptr); + void steering_status(const vehicle_interface::SteeringStatus::Message::ConstSharedPtr msg_ptr); + void gear_status(const vehicle_interface::GearStatus::Message::ConstSharedPtr msg_ptr); + void turn_indicator_status( + const vehicle_interface::TurnIndicatorStatus::Message::ConstSharedPtr msg_ptr); + void map_projector_info(const map_interface::MapProjectorInfo::Message::ConstSharedPtr msg_ptr); + void hazard_light_status( + const vehicle_interface::HazardLightStatus::Message::ConstSharedPtr msg_ptr); + void energy_status(const vehicle_interface::EnergyStatus::Message::ConstSharedPtr msg_ptr); + uint8_t mapping( + std::unordered_map hash_map, uint8_t input, uint8_t default_value); + void publish_kinematics(); + void publish_status(); + void on_timer(); + Eigen::Vector3d toBasicPoint3dPt(const geometry_msgs::msg::Point src); +}; + +} // namespace default_ad_api + +#endif // VEHICLE_HPP_ From e0187723d17dead16a441812af5a4dd4ab04354d Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Mon, 3 Jul 2023 15:31:45 +0900 Subject: [PATCH 072/118] fix(radar_tracks_msg_converter): fix twist conversion (#3963) * fix(radar_tracks_msg_converter): fix twist conversion Signed-off-by: scepter914 * update README Signed-off-by: scepter914 * fix typo Signed-off-by: scepter914 * fix orientation_availability Signed-off-by: scepter914 --------- Signed-off-by: scepter914 --- .../radar_tracks_msgs_converter/README.md | 4 +- .../radar_tracks_msgs_converter_node.hpp | 2 +- .../radar_tracks_msgs_converter_node.cpp | 126 +++++------------- 3 files changed, 39 insertions(+), 93 deletions(-) diff --git a/perception/radar_tracks_msgs_converter/README.md b/perception/radar_tracks_msgs_converter/README.md index a16cd5945801b..c29d8ee424549 100644 --- a/perception/radar_tracks_msgs_converter/README.md +++ b/perception/radar_tracks_msgs_converter/README.md @@ -13,8 +13,8 @@ This package convert from [radar_msgs/msg/RadarTracks](https://github.com/ros-pe - `~/input/radar_objects` (radar_msgs/msg/RadarTracks.msg): Input radar topic - `~/input/odometry` (nav_msgs/msg/Odometry.msg): Ego vehicle odometry topic - Output - - `~/output/radar_detected_objects` (autoware_auto_perception_msgs/msg/DetectedObject.idl): The topic converted to Autoware's message - - `~/output/radar_tracked_objects` (autoware_auto_perception_msgs/msg/TrackedObject.idl): The topic converted to Autoware's message + - `~/output/radar_detected_objects` (autoware_auto_perception_msgs/msg/DetectedObject.idl): The topic converted to Autoware's message. This is used for radar sensor fusion detection and radar detection. + - `~/output/radar_tracked_objects` (autoware_auto_perception_msgs/msg/TrackedObject.idl): The topic converted to Autoware's message. This is used for tracking layer sensor fusion. ### Parameters diff --git a/perception/radar_tracks_msgs_converter/include/radar_tracks_msgs_converter/radar_tracks_msgs_converter_node.hpp b/perception/radar_tracks_msgs_converter/include/radar_tracks_msgs_converter/radar_tracks_msgs_converter_node.hpp index d5738c80dcca9..62ebb2ec0146b 100644 --- a/perception/radar_tracks_msgs_converter/include/radar_tracks_msgs_converter/radar_tracks_msgs_converter_node.hpp +++ b/perception/radar_tracks_msgs_converter/include/radar_tracks_msgs_converter/radar_tracks_msgs_converter_node.hpp @@ -93,7 +93,7 @@ class RadarTracksMsgsConverterNode : public rclcpp::Node // Core geometry_msgs::msg::PoseWithCovariance convertPoseWithCovariance(); TrackedObjects convertRadarTrackToTrackedObjects(); - DetectedObjects convertRadarTrackToDetectedObjects(); + DetectedObjects convertTrackedObjectsToDetectedObjects(TrackedObjects & objects); uint8_t convertClassification(const uint16_t classification); }; 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 eb4a497e70495..5d3dd3b997f24 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 @@ -14,6 +14,8 @@ #include "radar_tracks_msgs_converter/radar_tracks_msgs_converter_node.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + #include #ifdef ROS_DISTRO_GALACTIC @@ -153,94 +155,36 @@ void RadarTracksMsgsConverterNode::onTimer() node_param_.new_frame_id, header.frame_id, header.stamp, rclcpp::Duration::from_seconds(0.01)); TrackedObjects tracked_objects = convertRadarTrackToTrackedObjects(); - DetectedObjects detected_objects = convertRadarTrackToDetectedObjects(); + DetectedObjects detected_objects = convertTrackedObjectsToDetectedObjects(tracked_objects); if (!tracked_objects.objects.empty()) { pub_tracked_objects_->publish(tracked_objects); pub_detected_objects_->publish(detected_objects); } } -DetectedObjects RadarTracksMsgsConverterNode::convertRadarTrackToDetectedObjects() +DetectedObjects RadarTracksMsgsConverterNode::convertTrackedObjectsToDetectedObjects( + TrackedObjects & objects) { DetectedObjects detected_objects; - detected_objects.header = radar_data_->header; - detected_objects.header.frame_id = node_param_.new_frame_id; - using POSE_IDX = tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - using RADAR_IDX = tier4_autoware_utils::xyz_upper_covariance_index::XYZ_UPPER_COV_IDX; + detected_objects.header = objects.header; - for (auto & radar_track : radar_data_->tracks) { + for (auto & object : objects.objects) { DetectedObject detected_object; - detected_object.existence_probability = 1.0; + detected_object.shape = object.shape; - detected_object.shape.type = Shape::BOUNDING_BOX; - detected_object.shape.dimensions = radar_track.size; - - // kinematics + // kinematics setting DetectedObjectKinematics kinematics; + kinematics.orientation_availability = + autoware_auto_perception_msgs::msg::DetectedObjectKinematics::SIGN_UNKNOWN; kinematics.has_twist = true; kinematics.has_twist_covariance = true; - - // convert by tf - geometry_msgs::msg::PoseStamped radar_pose_stamped{}; - radar_pose_stamped.pose.position = radar_track.position; - geometry_msgs::msg::PoseStamped transformed_pose_stamped{}; - tf2::doTransform(radar_pose_stamped, transformed_pose_stamped, *transform_); - kinematics.pose_with_covariance.pose = transformed_pose_stamped.pose; - - { - auto & pose_cov = kinematics.pose_with_covariance.covariance; - auto & radar_position_cov = radar_track.position_covariance; - pose_cov[POSE_IDX::X_X] = radar_position_cov[RADAR_IDX::X_X]; - pose_cov[POSE_IDX::X_Y] = radar_position_cov[RADAR_IDX::X_Y]; - pose_cov[POSE_IDX::X_Z] = radar_position_cov[RADAR_IDX::X_Z]; - pose_cov[POSE_IDX::Y_X] = radar_position_cov[RADAR_IDX::X_Y]; - pose_cov[POSE_IDX::Y_Y] = radar_position_cov[RADAR_IDX::Y_Y]; - pose_cov[POSE_IDX::Y_Z] = radar_position_cov[RADAR_IDX::Y_Z]; - pose_cov[POSE_IDX::Z_X] = radar_position_cov[RADAR_IDX::X_Z]; - pose_cov[POSE_IDX::Z_Y] = radar_position_cov[RADAR_IDX::Y_Z]; - pose_cov[POSE_IDX::Z_Z] = radar_position_cov[RADAR_IDX::Z_Z]; - } - - // convert by tf - geometry_msgs::msg::Vector3Stamped radar_velocity_stamped{}; - radar_velocity_stamped.vector = radar_track.velocity; - geometry_msgs::msg::Vector3Stamped transformed_vector3_stamped{}; - tf2::doTransform(radar_velocity_stamped, transformed_vector3_stamped, *transform_); - kinematics.twist_with_covariance.twist.linear = transformed_vector3_stamped.vector; - - // twist compensation - if (node_param_.use_twist_compensation) { - if (odometry_data_) { - kinematics.twist_with_covariance.twist.linear.x += odometry_data_->twist.twist.linear.x; - kinematics.twist_with_covariance.twist.linear.y += odometry_data_->twist.twist.linear.y; - kinematics.twist_with_covariance.twist.linear.z += odometry_data_->twist.twist.linear.z; - } else { - RCLCPP_INFO(get_logger(), "Odometry data is not coming"); - } - } - - { - auto & twist_cov = kinematics.twist_with_covariance.covariance; - auto & radar_vel_cov = radar_track.velocity_covariance; - twist_cov[POSE_IDX::X_X] = radar_vel_cov[RADAR_IDX::X_X]; - twist_cov[POSE_IDX::X_Y] = radar_vel_cov[RADAR_IDX::X_Y]; - twist_cov[POSE_IDX::X_Z] = radar_vel_cov[RADAR_IDX::X_Z]; - twist_cov[POSE_IDX::Y_X] = radar_vel_cov[RADAR_IDX::X_Y]; - twist_cov[POSE_IDX::Y_Y] = radar_vel_cov[RADAR_IDX::Y_Y]; - twist_cov[POSE_IDX::Y_Z] = radar_vel_cov[RADAR_IDX::Y_Z]; - twist_cov[POSE_IDX::Z_X] = radar_vel_cov[RADAR_IDX::X_Z]; - twist_cov[POSE_IDX::Z_Y] = radar_vel_cov[RADAR_IDX::Y_Z]; - twist_cov[POSE_IDX::Z_Z] = radar_vel_cov[RADAR_IDX::Z_Z]; - } + kinematics.twist_with_covariance = object.kinematics.twist_with_covariance; + kinematics.pose_with_covariance = object.kinematics.pose_with_covariance; detected_object.kinematics = kinematics; // classification - ObjectClassification classification; - classification.probability = 1.0; - classification.label = convertClassification(radar_track.classification); - detected_object.classification.emplace_back(classification); - + detected_object.classification = object.classification; detected_objects.objects.emplace_back(detected_object); } return detected_objects; @@ -263,14 +207,34 @@ TrackedObjects RadarTracksMsgsConverterNode::convertRadarTrackToTrackedObjects() tracked_object.shape.type = Shape::BOUNDING_BOX; tracked_object.shape.dimensions = radar_track.size; - // kinematics + // kinematics setting TrackedObjectKinematics kinematics; kinematics.orientation_availability = TrackedObjectKinematics::AVAILABLE; kinematics.is_stationary = false; - // convert by tf + // Twist conversion + geometry_msgs::msg::Vector3 compensated_velocity = radar_track.velocity; + if (node_param_.use_twist_compensation) { + if (odometry_data_) { + compensated_velocity.x += odometry_data_->twist.twist.linear.x; + compensated_velocity.y += odometry_data_->twist.twist.linear.y; + compensated_velocity.z += odometry_data_->twist.twist.linear.z; + } else { + RCLCPP_INFO(get_logger(), "Odometry data is not coming"); + } + } + kinematics.twist_with_covariance.twist.linear.x = std::sqrt( + compensated_velocity.x * compensated_velocity.x + + compensated_velocity.y * compensated_velocity.y); + + // Pose conversion geometry_msgs::msg::PoseStamped radar_pose_stamped{}; radar_pose_stamped.pose.position = radar_track.position; + + double yaw = tier4_autoware_utils::normalizeRadian( + std::atan2(compensated_velocity.y, compensated_velocity.x)); + radar_pose_stamped.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw); + geometry_msgs::msg::PoseStamped transformed_pose_stamped{}; tf2::doTransform(radar_pose_stamped, transformed_pose_stamped, *transform_); kinematics.pose_with_covariance.pose = transformed_pose_stamped.pose; @@ -289,24 +253,6 @@ TrackedObjects RadarTracksMsgsConverterNode::convertRadarTrackToTrackedObjects() pose_cov[POSE_IDX::Z_Z] = radar_position_cov[RADAR_IDX::Z_Z]; } - // convert by tf - geometry_msgs::msg::Vector3Stamped radar_velocity_stamped{}; - radar_velocity_stamped.vector = radar_track.velocity; - geometry_msgs::msg::Vector3Stamped transformed_vector3_stamped{}; - tf2::doTransform(radar_velocity_stamped, transformed_vector3_stamped, *transform_); - kinematics.twist_with_covariance.twist.linear = transformed_vector3_stamped.vector; - - // twist compensation - if (node_param_.use_twist_compensation) { - if (odometry_data_) { - kinematics.twist_with_covariance.twist.linear.x += odometry_data_->twist.twist.linear.x; - kinematics.twist_with_covariance.twist.linear.y += odometry_data_->twist.twist.linear.y; - kinematics.twist_with_covariance.twist.linear.z += odometry_data_->twist.twist.linear.z; - } else { - RCLCPP_INFO(get_logger(), "Odometry data is not coming"); - } - } - { auto & twist_cov = kinematics.twist_with_covariance.covariance; auto & radar_vel_cov = radar_track.velocity_covariance; From f6e1e3620bbcb2d7ed2eb9e99639b56c865b0954 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 3 Jul 2023 15:47:24 +0900 Subject: [PATCH 073/118] chore: update maintainer (#4140) Signed-off-by: Kenji Miyake Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- common/global_parameter_loader/package.xml | 2 +- common/tier4_api_utils/package.xml | 1 - common/tier4_autoware_utils/package.xml | 1 - common/tier4_debug_tools/package.xml | 2 +- control/external_cmd_selector/package.xml | 3 --- control/joy_controller/package.xml | 3 --- control/lane_departure_checker/package.xml | 2 -- control/obstacle_collision_checker/package.xml | 2 -- control/pure_pursuit/package.xml | 1 - launch/tier4_autoware_api_launch/package.xml | 1 - launch/tier4_system_launch/package.xml | 1 - planning/scenario_selector/package.xml | 3 --- sensing/livox/livox_tag_filter/package.xml | 2 +- system/component_state_monitor/package.xml | 1 - system/dummy_diag_publisher/package.xml | 1 - system/dummy_infrastructure/package.xml | 2 +- system/emergency_handler/package.xml | 1 - system/system_error_monitor/package.xml | 1 - system/topic_state_monitor/package.xml | 2 +- 19 files changed, 5 insertions(+), 27 deletions(-) diff --git a/common/global_parameter_loader/package.xml b/common/global_parameter_loader/package.xml index 5fa46351930cf..4c2568b9aec98 100644 --- a/common/global_parameter_loader/package.xml +++ b/common/global_parameter_loader/package.xml @@ -4,7 +4,7 @@ global_parameter_loader 0.1.0 The global_parameter_loader package - Kenji Miyake + Ryohsuke Mitsudome Apache License 2.0 ament_cmake_auto diff --git a/common/tier4_api_utils/package.xml b/common/tier4_api_utils/package.xml index e8f0691a992d0..091f512480150 100644 --- a/common/tier4_api_utils/package.xml +++ b/common/tier4_api_utils/package.xml @@ -7,7 +7,6 @@ Takagi, Isamu yabuta Kah Hooi Tan - Kenji Miyake Apache License 2.0 ament_cmake_auto diff --git a/common/tier4_autoware_utils/package.xml b/common/tier4_autoware_utils/package.xml index 0f5f3f64ee957..ff3fa65f034b3 100644 --- a/common/tier4_autoware_utils/package.xml +++ b/common/tier4_autoware_utils/package.xml @@ -5,7 +5,6 @@ 0.1.0 The tier4_autoware_utils package Takamasa Horibe - Kenji Miyake Takayuki Murooka Yutaka Shimizu Apache License 2.0 diff --git a/common/tier4_debug_tools/package.xml b/common/tier4_debug_tools/package.xml index b7e0952b72178..8f03a3b55cf26 100644 --- a/common/tier4_debug_tools/package.xml +++ b/common/tier4_debug_tools/package.xml @@ -4,7 +4,7 @@ tier4_debug_tools 0.1.0 The tier4_debug_tools package - Kenji Miyake + Ryohsuke Mitsudome Apache License 2.0 ament_cmake_auto diff --git a/control/external_cmd_selector/package.xml b/control/external_cmd_selector/package.xml index 1b27c9f07915a..4d8cc5a385494 100644 --- a/control/external_cmd_selector/package.xml +++ b/control/external_cmd_selector/package.xml @@ -4,7 +4,6 @@ external_cmd_selector 0.1.0 The external_cmd_selector package - Kenji Miyake Taiki Tanaka Tomoya Kimura Shumpei Wakabayashi @@ -14,8 +13,6 @@ Takayuki Murooka Apache License 2.0 - Kenji Miyake - ament_cmake_auto autoware_cmake diff --git a/control/joy_controller/package.xml b/control/joy_controller/package.xml index 0c2defb2fc768..79ee9f27868f2 100644 --- a/control/joy_controller/package.xml +++ b/control/joy_controller/package.xml @@ -4,7 +4,6 @@ joy_controller 0.1.0 The joy_controller package - Kenji Miyake Taiki Tanaka Tomoya Kimura Shumpei Wakabayashi @@ -14,8 +13,6 @@ Takayuki Murooka Apache License 2.0 - Kenji Miyake - ament_cmake_auto autoware_cmake diff --git a/control/lane_departure_checker/package.xml b/control/lane_departure_checker/package.xml index 617c391f2f284..d4e845ec97d82 100644 --- a/control/lane_departure_checker/package.xml +++ b/control/lane_departure_checker/package.xml @@ -7,8 +7,6 @@ Kyoichi Sugahara Apache License 2.0 - Kenji Miyake - ament_cmake_auto autoware_cmake diff --git a/control/obstacle_collision_checker/package.xml b/control/obstacle_collision_checker/package.xml index 8a202ac689229..46b0b18191e81 100644 --- a/control/obstacle_collision_checker/package.xml +++ b/control/obstacle_collision_checker/package.xml @@ -4,7 +4,6 @@ obstacle_collision_checker 0.1.0 The obstacle_collision_checker package - Kenji Miyake Taiki Tanaka Tomoya Kimura Shumpei Wakabayashi @@ -14,7 +13,6 @@ Takayuki Murooka Apache License 2.0 - Kenji Miyake Satoshi Tanaka ament_cmake diff --git a/control/pure_pursuit/package.xml b/control/pure_pursuit/package.xml index ef0810c695ea1..30356b856fbac 100644 --- a/control/pure_pursuit/package.xml +++ b/control/pure_pursuit/package.xml @@ -8,7 +8,6 @@ Apache License 2.0 Berkay Karaman - Kenji Miyake Takamasa Horibe ament_cmake_auto diff --git a/launch/tier4_autoware_api_launch/package.xml b/launch/tier4_autoware_api_launch/package.xml index bed0b9e58ca75..4d41ad0ac4a83 100644 --- a/launch/tier4_autoware_api_launch/package.xml +++ b/launch/tier4_autoware_api_launch/package.xml @@ -7,7 +7,6 @@ Takagi, Isamu yabuta Kah Hooi Tan - Kenji Miyake Ryohsuke Mitsudome Apache License 2.0 diff --git a/launch/tier4_system_launch/package.xml b/launch/tier4_system_launch/package.xml index 5e3fc3ff061f8..0870a384ea7d3 100644 --- a/launch/tier4_system_launch/package.xml +++ b/launch/tier4_system_launch/package.xml @@ -4,7 +4,6 @@ tier4_system_launch 0.1.0 The tier4_system_launch package - Kenji Miyake Fumihito Ito asana17 Apache License 2.0 diff --git a/planning/scenario_selector/package.xml b/planning/scenario_selector/package.xml index 7dd9fc071976d..53c29613a1de8 100644 --- a/planning/scenario_selector/package.xml +++ b/planning/scenario_selector/package.xml @@ -4,7 +4,6 @@ scenario_selector 0.1.0 The scenario_selector ROS 2 package - Kenji Miyake Taiki Tanaka Tomoya Kimura Shumpei Wakabayashi @@ -14,8 +13,6 @@ Takayuki Murooka Apache License 2.0 - Kenji Miyake - ament_cmake_auto autoware_cmake diff --git a/sensing/livox/livox_tag_filter/package.xml b/sensing/livox/livox_tag_filter/package.xml index f60bef1de5f10..4fe994766027b 100644 --- a/sensing/livox/livox_tag_filter/package.xml +++ b/sensing/livox/livox_tag_filter/package.xml @@ -4,7 +4,7 @@ livox_tag_filter 0.1.0 The livox_tag_filter package - Kenji Miyake + Ryohsuke Mitsudome Apache License 2.0 ament_cmake_auto diff --git a/system/component_state_monitor/package.xml b/system/component_state_monitor/package.xml index ce20787704035..60d0fd0577ef0 100644 --- a/system/component_state_monitor/package.xml +++ b/system/component_state_monitor/package.xml @@ -7,7 +7,6 @@ Takagi, Isamu yabuta Kah Hooi Tan - Kenji Miyake Apache License 2.0 ament_cmake_auto diff --git a/system/dummy_diag_publisher/package.xml b/system/dummy_diag_publisher/package.xml index 86da760b99a46..1df190b282038 100644 --- a/system/dummy_diag_publisher/package.xml +++ b/system/dummy_diag_publisher/package.xml @@ -4,7 +4,6 @@ dummy_diag_publisher 0.1.0 The dummy_diag_publisher ROS 2 package - Kenji Miyake Akihiro Sakurai Fumihito Ito Apache License 2.0 diff --git a/system/dummy_infrastructure/package.xml b/system/dummy_infrastructure/package.xml index 654feb5ffc7cf..b1cf997b58eeb 100644 --- a/system/dummy_infrastructure/package.xml +++ b/system/dummy_infrastructure/package.xml @@ -4,7 +4,7 @@ dummy_infrastructure 0.0.0 dummy_infrastructure - Kenji Miyake + Ryohsuke Mitsudome Apache License 2.0 ament_cmake_auto diff --git a/system/emergency_handler/package.xml b/system/emergency_handler/package.xml index 4ee6674b2f569..eb87a63503988 100644 --- a/system/emergency_handler/package.xml +++ b/system/emergency_handler/package.xml @@ -4,7 +4,6 @@ emergency_handler 0.1.0 The emergency_handler ROS 2 package - Kenji Miyake Makoto Kurihara Apache License 2.0 diff --git a/system/system_error_monitor/package.xml b/system/system_error_monitor/package.xml index ba8a682204f5f..c6560209854d3 100644 --- a/system/system_error_monitor/package.xml +++ b/system/system_error_monitor/package.xml @@ -4,7 +4,6 @@ system_error_monitor 0.1.1 The system_error_monitor package in ROS 2 - Kenji Miyake Fumihito Ito Apache License 2.0 diff --git a/system/topic_state_monitor/package.xml b/system/topic_state_monitor/package.xml index 3405a63b4af39..057d58d00d5a1 100644 --- a/system/topic_state_monitor/package.xml +++ b/system/topic_state_monitor/package.xml @@ -4,7 +4,7 @@ topic_state_monitor 0.1.0 The topic_state_monitor package - Kenji Miyake + Ryohsuke Mitsudome Apache License 2.0 ament_cmake_auto From fbd403214ccbd1cc1f2bc8904abcd91ef0f8a201 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Mon, 3 Jul 2023 07:00:25 +0000 Subject: [PATCH 074/118] chore: update CODEOWNERS (#4138) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/CODEOWNERS | 35 +++++++++++++++++------------------ 1 file changed, 17 insertions(+), 18 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 98dc5c47506d2..ca03cd9a56adc 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -14,7 +14,7 @@ common/component_interface_tools/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp m common/component_interface_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp common/cuda_utils/** daisuke.nishimatsu@tier4.jp manato.hirabayashi@tier4.jp common/fake_test_node/** opensource@apex.ai -common/global_parameter_loader/** kenji.miyake@tier4.jp +common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp common/goal_distance_calculator/** taiki.tanaka@tier4.jp common/grid_map_utils/** maxime.clement@tier4.jp common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp @@ -29,14 +29,14 @@ common/rtc_manager_rviz_plugin/** taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/tensorrt_common/** daisuke.nishimatsu@tier4.jp dan.umeda@tier4.jp manato.hirabayashi@tier4.jp common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp -common/tier4_api_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp +common/tier4_api_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp common/tier4_automatic_goal_rviz_plugin/** dawid.moszynski@robotec.ai shumpei.wakabayashi@tier4.jp -common/tier4_autoware_utils/** kenji.miyake@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +common/tier4_autoware_utils/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp common/tier4_calibration_rviz_plugin/** tomoya.kimura@tier4.jp common/tier4_control_rviz_plugin/** taiki.tanaka@tier4.jp common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp common/tier4_debug_rviz_plugin/** takayuki.murooka@tier4.jp -common/tier4_debug_tools/** kenji.miyake@tier4.jp +common/tier4_debug_tools/** ryohsuke.mitsudome@tier4.jp common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp takamasa.horibe@tier4.jp common/tier4_perception_rviz_plugin/** yukihiro.saito@tier4.jp common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp yutaka.shimizu@tier4.jp @@ -51,11 +51,11 @@ 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/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/external_cmd_selector/** fumiya.watanabe@tier4.jp kenji.miyake@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/joy_controller/** fumiya.watanabe@tier4.jp kenji.miyake@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/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 +control/joy_controller/** 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/lane_departure_checker/** kyoichi.sugahara@tier4.jp control/mpc_lateral_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -control/obstacle_collision_checker/** fumiya.watanabe@tier4.jp kenji.miyake@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/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/pure_pursuit/** takamasa.horibe@tier4.jp @@ -68,7 +68,7 @@ evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai evaluator/localization_evaluator/** dominik.jargot@robotec.ai evaluator/planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp launch/map4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryohei.sasaki@map.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp -launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp +launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp launch/tier4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp launch/tier4_map_launch/** koji.minoda@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp @@ -76,7 +76,7 @@ launch/tier4_perception_launch/** shunsuke.miura@tier4.jp yoshi.ri@tier4.jp yuki launch/tier4_planning_launch/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -launch/tier4_system_launch/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp kenji.miyake@tier4.jp +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 takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp localization/gyro_odometer/** yamato.ando@tier4.jp @@ -128,7 +128,6 @@ perception/traffic_light_classifier/** shunsuke.miura@tier4.jp yukihiro.saito@ti perception/traffic_light_fine_detector/** mingyu.li@tier4.jp perception/traffic_light_map_based_detector/** yukihiro.saito@tier4.jp perception/traffic_light_multi_camera_fusion/** mingyu.li@tier4.jp -perception/traffic_light_selector/** isamu.takagi@tier4.jp 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 @@ -168,7 +167,7 @@ planning/sampling_based_planner/bezier_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/frenet_planner/** maxime.clement@tier4.jp planning/sampling_based_planner/path_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp -planning/scenario_selector/** fumiya.watanabe@tier4.jp kenji.miyake@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 +planning/scenario_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 planning/static_centerline_optimizer/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp planning/surround_obstacle_checker/** satoshi.ota@tier4.jp sensing/geo_pos_conv/** yamato.ando@tier4.jp @@ -176,7 +175,7 @@ sensing/gnss_poser/** yamato.ando@tier4.jp sensing/image_diagnostics/** dai.nguyen@tier4.jp sensing/image_transport_decompressor/** yukihiro.saito@tier4.jp sensing/imu_corrector/** yamato.ando@tier4.jp -sensing/livox/livox_tag_filter/** kenji.miyake@tier4.jp +sensing/livox/livox_tag_filter/** ryohsuke.mitsudome@tier4.jp sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp sensing/radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp sensing/radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp @@ -188,19 +187,19 @@ simulator/fault_injection/** keisuke.shima@tier4.jp simulator/simple_planning_simulator/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp system/autoware_auto_msgs_adapter/** isamu.takagi@tier4.jp mfc@leodrive.ai system/bluetooth_monitor/** fumihito.ito@tier4.jp -system/component_state_monitor/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp kenji.miyake@tier4.jp makoto.yabuta@tier4.jp +system/component_state_monitor/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp system/default_ad_api/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/default_ad_api_helpers/ad_api_adaptors/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp 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 kenji.miyake@tier4.jp -system/dummy_infrastructure/** kenji.miyake@tier4.jp -system/emergency_handler/** kenji.miyake@tier4.jp makoto.kurihara@tier4.jp +system/dummy_diag_publisher/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp +system/dummy_infrastructure/** ryohsuke.mitsudome@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 -system/system_error_monitor/** fumihito.ito@tier4.jp kenji.miyake@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/** kenji.miyake@tier4.jp +system/topic_state_monitor/** ryohsuke.mitsudome@tier4.jp system/velodyne_monitor/** fumihito.ito@tier4.jp tools/simulator_test/simulator_compatibility_test/** shpark@morai.ai vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp From 47db336fbd85ce8560e2e368510500cea1e1eec7 Mon Sep 17 00:00:00 2001 From: DMoszynski <121798334+dmoszynski@users.noreply.github.com> Date: Mon, 3 Jul 2023 10:29:19 +0200 Subject: [PATCH 075/118] fix(fault_injection_node): fix history_depth in subscriber qos (#4042) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * fix(fault_injection_node): fix history_depth in sub qos Signed-off-by: Dawid Moszyński * fix(fault_injection_node): add test cases Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * fix(fault_injection): fix test Signed-off-by: Dawid Moszyński * fix(test_fault_injection): ensure that publication takes place Signed-off-by: Dawid Moszyński * ref(test_fault_injection): remove unused import Signed-off-by: Dawid Moszyński --------- Signed-off-by: Dawid Moszyński Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> --- .../fault_injection_node.cpp | 2 +- .../test/test_fault_injection_node.test.py | 49 +++++++++++++++++++ 2 files changed, 50 insertions(+), 1 deletion(-) diff --git a/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp b/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp index b0306b38fe3fd..9b86fa2de4294 100644 --- a/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp +++ b/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp @@ -55,7 +55,7 @@ FaultInjectionNode::FaultInjectionNode(rclcpp::NodeOptions node_options) // Subscriber sub_simulation_events_ = this->create_subscription( - "~/input/simulation_events", rclcpp::QoS{1}, + "~/input/simulation_events", rclcpp::QoS{rclcpp::KeepLast(10)}, std::bind(&FaultInjectionNode::onSimulationEvents, this, _1)); // Load all config diff --git a/simulator/fault_injection/test/test_fault_injection_node.test.py b/simulator/fault_injection/test/test_fault_injection_node.test.py index 887c39f449a23..4556aaaca8d80 100644 --- a/simulator/fault_injection/test/test_fault_injection_node.test.py +++ b/simulator/fault_injection/test/test_fault_injection_node.test.py @@ -127,6 +127,55 @@ def test_node_link(self): self.assertGreaterEqual(self.get_num_valid_data(msg_buffer, DiagnosticStatus.ERROR), 1) + def test_receive_multiple_message_simultaneously(self): + """ + Test for https://github.com/autowarefoundation/autoware.universe/pull/4042. + + Expect fault_injection_node can receive multiple messages simultaneously. + """ + msg_buffer = [] + self.test_node.create_subscription( + DiagnosticArray, "/diagnostics", lambda msg: msg_buffer.append(msg), 10 + ) + + # Call spin_once() so that the publisher publish messages simultaneously + pub_events_1 = self.test_node.create_publisher(SimulationEvents, "/simulation/events", 10) + pub_events_2 = self.test_node.create_publisher(SimulationEvents, "/simulation/events", 10) + rclpy.spin_once(self.test_node, timeout_sec=0.1) + pub_events_1.publish( + SimulationEvents( + fault_injection_events=[ + FaultInjectionEvent(name="cpu_temperature", level=FaultInjectionEvent.ERROR) + ] + ) + ) + pub_events_2.publish( + SimulationEvents( + fault_injection_events=[ + FaultInjectionEvent(name="cpu_usage", level=FaultInjectionEvent.ERROR) + ] + ) + ) + + # Wait until the subscriber receive messages + end_time = time.time() + self.evaluation_time + while time.time() < end_time: + rclpy.spin_once(self.test_node, timeout_sec=1.0) + + # Verify the number of received messages + self.assertGreater(len(msg_buffer), 0) + + # Verify the latest message + for stat in msg_buffer[-1].status: + if stat.name == "fault_injection: CPU Load Average": + self.assertEqual(stat.level, DiagnosticStatus.OK) + elif stat.name == "fault_injection: CPU Temperature": + self.assertEqual(stat.level, DiagnosticStatus.ERROR) + elif stat.name == "fault_injection: CPU Usage": + self.assertEqual(stat.level, DiagnosticStatus.ERROR) + else: + self.fail(f"Unexpected status name: {stat.name}") + @launch_testing.post_shutdown_test() class TestProcessOutput(unittest.TestCase): From 56b9ed8587098e95eec243dc41df0840bfadcb65 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 3 Jul 2023 20:46:54 +0900 Subject: [PATCH 076/118] feat(start_planner): add option for lane departure (#4151) Signed-off-by: kosuke55 --- .../config/start_planner/start_planner.param.yaml | 1 + .../docs/behavior_path_planner_start_planner_design.md | 1 + .../utils/start_planner/start_planner_parameters.hpp | 1 + .../src/scene_module/start_planner/manager.cpp | 2 ++ .../src/utils/start_planner/shift_pull_out.cpp | 6 ++++-- 5 files changed, 9 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml index 80114889d7e74..fe98d7aa2a839 100644 --- a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml +++ b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml @@ -8,6 +8,7 @@ collision_check_distance_from_end: 1.0 # shift pull out enable_shift_pull_out: true + check_shift_path_lane_departure: false minimum_shift_pull_out_distance: 0.0 deceleration_interval: 15.0 lateral_jerk: 0.5 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 37ff48bb717d5..345cb5d1f4329 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 @@ -105,6 +105,7 @@ Pull out distance is calculated by the speed, lateral deviation, and the lateral | Name | Unit | Type | Description | Default value | | :------------------------------ | :----- | :----- | :------------------------------------------------------------------------------------------------------------------- | :------------ | | enable_shift_pull_out | [-] | bool | flag whether to enable shift pull out | true | +| check_shift_path_lane_departure | [-] | bool | flag whether to check if shift path footprints are out of lane | false | | shift_pull_out_velocity | [m/s] | double | velocity of shift pull out | 2.0 | | pull_out_sampling_num | [-] | int | Number of samplings in the minimum to maximum range of lateral_jerk | 4 | | maximum_lateral_jerk | [m/s3] | double | maximum lateral jerk | 2.0 | diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp index 02a3b6169166a..73d922cfde270 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp @@ -35,6 +35,7 @@ struct StartPlannerParameters double collision_check_distance_from_end; // shift pull out bool enable_shift_pull_out; + bool check_shift_path_lane_departure; double minimum_shift_pull_out_distance; int lateral_acceleration_sampling_num; double lateral_jerk; 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 bba6f2b7b0da3..23265e4058956 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 @@ -44,6 +44,8 @@ StartPlannerModuleManager::StartPlannerModuleManager( node->declare_parameter(ns + "collision_check_distance_from_end"); // shift pull out p.enable_shift_pull_out = node->declare_parameter(ns + "enable_shift_pull_out"); + p.check_shift_path_lane_departure = + node->declare_parameter(ns + "check_shift_path_lane_departure"); p.minimum_shift_pull_out_distance = node->declare_parameter(ns + "minimum_shift_pull_out_distance"); p.lateral_acceleration_sampling_num = diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index b11bb7731b826..fc24c3d9f2d20 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -100,8 +100,10 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) const auto expanded_lanes = utils::expandLanelets( drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, dp.drivable_area_types_to_skip); - if (lane_departure_checker_->checkPathWillLeaveLane( - utils::transformToLanelets(expanded_lanes), path_start_to_end)) { + if ( + parameters_.check_shift_path_lane_departure && + lane_departure_checker_->checkPathWillLeaveLane( + utils::transformToLanelets(expanded_lanes), path_start_to_end)) { continue; } From 2424d6b770d9623e9ddadbeae32e6e8d32a67348 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 4 Jul 2023 10:23:12 +0900 Subject: [PATCH 077/118] fix(default_ad_api): pointer check (#4154) fix pointer check Signed-off-by: Takagi, Isamu --- system/default_ad_api/src/vehicle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/default_ad_api/src/vehicle.cpp b/system/default_ad_api/src/vehicle.cpp index 4cd7f370a55fc..43e5d1955fc2b 100644 --- a/system/default_ad_api/src/vehicle.cpp +++ b/system/default_ad_api/src/vehicle.cpp @@ -181,7 +181,7 @@ void VehicleNode::publish_status() { if ( !steering_status_msgs_ || !gear_status_msgs_ || !turn_indicator_status_msgs_ || - hazard_light_status_msgs_ || energy_status_msgs_) + !hazard_light_status_msgs_ || !energy_status_msgs_) return; autoware_ad_api::vehicle::VehicleStatus::Message vehicle_status; From 80a433fafda15e4ca686ba2f2a20b9ef95377311 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 4 Jul 2023 13:35:24 +0900 Subject: [PATCH 078/118] feat(shift_decider): keep parking gear command after the state transitions from arrived_goal (#4155) Signed-off-by: tomoya.kimura --- control/shift_decider/src/shift_decider.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/control/shift_decider/src/shift_decider.cpp b/control/shift_decider/src/shift_decider.cpp index 3fcd45d8e51d1..6f24578bf8d8e 100644 --- a/control/shift_decider/src/shift_decider.cpp +++ b/control/shift_decider/src/shift_decider.cpp @@ -86,7 +86,10 @@ void ShiftDecider::updateCurrentShiftCmd() shift_cmd_.command = current_gear_ptr_->report; } } else { - if (autoware_state_->state == AutowareState::ARRIVED_GOAL && park_on_goal_) { + if ( + (autoware_state_->state == AutowareState::ARRIVED_GOAL || + autoware_state_->state == AutowareState::WAITING_FOR_ROUTE) && + park_on_goal_) { shift_cmd_.command = GearCommand::PARK; } else { shift_cmd_.command = current_gear_ptr_->report; From 01bf2c68e4fb5775dea580e48a51ff7602bd96ef Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 4 Jul 2023 17:31:00 +0900 Subject: [PATCH 079/118] fix(closest_velocity_checker): add planning acceleration (#4159) Signed-off-by: Takamasa Horibe --- .../scripts/closest_velocity_checker.py | 28 ++++++++++--------- 1 file changed, 15 insertions(+), 13 deletions(-) diff --git a/planning/planning_debug_tools/scripts/closest_velocity_checker.py b/planning/planning_debug_tools/scripts/closest_velocity_checker.py index 292a2ae49ae9c..4123766a947b0 100755 --- a/planning/planning_debug_tools/scripts/closest_velocity_checker.py +++ b/planning/planning_debug_tools/scripts/closest_velocity_checker.py @@ -43,11 +43,12 @@ OBSTACLE_STOP = 3 LAT_ACC = 4 VELOCITY_OPTIMIZE = 5 -CONTROL_CMD = 6 -VEHICLE_CMD = 7 -CONTROL_CMD_ACC = 8 -VEHICLE_CMD_ACC = 9 -DATA_NUM = 10 +ACCELERATION_OPTIMIZE = 6 +CONTROL_CMD = 7 +VEHICLE_CMD = 8 +CONTROL_CMD_ACC = 9 +VEHICLE_CMD_ACC = 10 +DATA_NUM = 11 class VelocityChecker(Node): @@ -94,8 +95,6 @@ def __init__(self): self.sub4 = self.create_subscription( Trajectory, scenario + "/motion_velocity_smoother/debug/trajectory_lateral_acc_filtered", - # TODO: change to following string after fixing bug of autoware - # '/motion_velocity_optimizer/debug/trajectory_lateral_acc_filtered', self.CallBackLataccTrajectory, 1, ) @@ -157,9 +156,9 @@ def printInfo(self): if self.count == 0: self.get_logger().info("") self.get_logger().info( - "| Map Limit | Behavior | Obs Avoid | Obs Stop | External Lim | LatAcc Filtered " - "| Optimized | Control VelCmd | Control AccCmd | Vehicle VelCmd | Vehicle AccCmd " - "| AW Engage | VC Engage | Localization Vel | Vehicle Vel | [km/h] | Distance [m] " + "| Behavior Path | Behavior Vel | Obs Avoid | Obs Stop | External Lim | LatAcc Filtered " + "| Optimized Vel | Optimized Acc | Control VelCmd | Control AccCmd | Vehicle VelCmd | Vehicle AccCmd " + "| AW Engage | VC Engage | Localization Vel | Vehicle Vel | Distance [m] |" ) # noqa: E501 mps2kmph = 3.6 distance_to_stopline = self.distance_to_stopline @@ -170,6 +169,7 @@ def printInfo(self): vel_external_lim = self.external_v_lim * mps2kmph vel_latacc_filtered = self.data_arr[LAT_ACC] * mps2kmph vel_optimized = self.data_arr[VELOCITY_OPTIMIZE] * mps2kmph + acc_optimized = self.data_arr[ACCELERATION_OPTIMIZE] vel_ctrl_cmd = self.data_arr[CONTROL_CMD] * mps2kmph acc_ctrl_cmd = self.data_arr[CONTROL_CMD_ACC] vel_vehicle_cmd = self.data_arr[VEHICLE_CMD] * mps2kmph @@ -187,9 +187,9 @@ def printInfo(self): else ("True" if self.vehicle_engage is True else "False") ) self.get_logger().info( - "| {0: 9.2f} | {1: 8.2f} | {2: 9.2f} | {3: 8.2f} | {4: 12.2f} " - "| {5: 15.2f} | {6: 9.2f} | {7: 14.2f} | {8: 14.2f} | {9: 14.2f} | {10: 14.2f} " - "| {11:>9s} | {12:>9s} | {13: 16.2f} | {14: 11.2f} | | {15: 10.2f}".format( # noqa: E501 + "| {0: 13.2f} | {1: 12.2f} | {2: 9.2f} | {3: 8.2f} | {4: 12.2f} " + "| {5: 15.2f} | {6: 13.2f} | {7: 13.2f} | {8: 14.2f} | {9: 14.2f} | {10: 14.2f} | {11: 14.2f} " + "| {12:>9s} | {13:>9s} | {14: 16.2f} | {15: 11.2f} | {16: 12.2f} |".format( # noqa: E501 vel_map_lim, vel_behavior, vel_obs_avoid, @@ -197,6 +197,7 @@ def printInfo(self): vel_external_lim, vel_latacc_filtered, vel_optimized, + acc_optimized, vel_ctrl_cmd, acc_ctrl_cmd, vel_vehicle_cmd, @@ -268,6 +269,7 @@ def CallBackScenarioTrajectory(self, msg): # self.get_logger().info('VELOCITY_OPTIMIZE called') closest = self.calcClosestTrajectory(msg) self.data_arr[VELOCITY_OPTIMIZE] = msg.points[closest].longitudinal_velocity_mps + self.data_arr[ACCELERATION_OPTIMIZE] = msg.points[closest].acceleration_mps2 return def CallBackControlCmd(self, msg): From 14b2720b7319eb04e71441d49d35b90cdc5685fb Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 4 Jul 2023 23:06:13 +0900 Subject: [PATCH 080/118] feat(multi_object_tracker): suppress yaw rotation oscillation problem in bicycle tracking model (#4146) * enable only tracking and prediction Signed-off-by: yoshiri * set bicycle model parameter to be understeered Signed-off-by: yoshiri * Revert "enable only tracking and prediction" This reverts commit d97db405c1083fa8aefc4027da35f19308cbd7e3. --------- Signed-off-by: yoshiri --- .../multi_object_tracker/src/tracker/model/bicycle_tracker.cpp | 2 +- .../src/tracker/model/big_vehicle_tracker.cpp | 2 +- .../src/tracker/model/normal_vehicle_tracker.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp index 5de81eb2d4538..75667f0b60fbb 100644 --- a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp @@ -135,7 +135,7 @@ BicycleTracker::BicycleTracker( ekf_.init(X, P); // Set lf, lr - double point_ratio = 0.5; // comes to front if larger + double point_ratio = 0.2; // under steered if smaller than 0.5 lf_ = bounding_box_.length * point_ratio; lr_ = bounding_box_.length * (1.0 - point_ratio); } diff --git a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp index 458509cf06e86..3fcbdc2f794aa 100644 --- a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp @@ -150,7 +150,7 @@ BigVehicleTracker::BigVehicleTracker( setNearestCornerOrSurfaceIndex(self_transform); // this index is used in next measure step // Set lf, lr - double point_ratio = 0.5; // comes to front if larger + double point_ratio = 0.1; // under steered if smaller than 0.5 lf_ = bounding_box_.length * point_ratio; lr_ = bounding_box_.length * (1.0 - point_ratio); } diff --git a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp index 000f728892d11..713bd58360c32 100644 --- a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp @@ -150,7 +150,7 @@ NormalVehicleTracker::NormalVehicleTracker( setNearestCornerOrSurfaceIndex(self_transform); // this index is used in next measure step // Set lf, lr - double point_ratio = 0.5; // comes to front if larger + double point_ratio = 0.2; // under steered if smaller than 0.5 lf_ = bounding_box_.length * point_ratio; lr_ = bounding_box_.length * (1.0 - point_ratio); } From d9b938cb444d815ce0e03294c47d781ae4b77ae6 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 4 Jul 2023 23:07:28 +0900 Subject: [PATCH 081/118] docs(multi_object_tracker): add tracking model description (#4161) * enable only tracking and prediction Signed-off-by: yoshiri * set bicycle model parameter to be understeered Signed-off-by: yoshiri * Revert "enable only tracking and prediction" This reverts commit d97db405c1083fa8aefc4027da35f19308cbd7e3. * add tracking model description Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- perception/multi_object_tracker/README.md | 2 + .../image/anchor_point.drawio.svg | 732 ++++++++++++++++++ .../image/kinematic_bicycle_model.png | Bin 0 -> 26917 bytes .../image/nearest_corner_or_side.drawio.svg | 230 ++++++ perception/multi_object_tracker/models.md | 98 +++ 5 files changed, 1062 insertions(+) create mode 100644 perception/multi_object_tracker/image/anchor_point.drawio.svg create mode 100644 perception/multi_object_tracker/image/kinematic_bicycle_model.png create mode 100644 perception/multi_object_tracker/image/nearest_corner_or_side.drawio.svg create mode 100644 perception/multi_object_tracker/models.md diff --git a/perception/multi_object_tracker/README.md b/perception/multi_object_tracker/README.md index cef4b3857d372..0cc8f1708e334 100644 --- a/perception/multi_object_tracker/README.md +++ b/perception/multi_object_tracker/README.md @@ -90,6 +90,8 @@ Example: Also, this algorithm doesn't care about blind spots. In general, since too close obstacles aren't visible due to the sensing performance limit, please take enough margin to obstacles. --> +See the [model explanations](models.md). + ## (Optional) Error detection and handling + +### Known limits, drawbacks + +- When the anchor point is further than the detection center, the tracking will be more affected by the yaw detection noise. + - This can be result in unintended yaw rotation or position drift. + +## References + +[1] Schubert, Robin & Richter, Eric & Wanielik, Gerd. (2008). Comparison and evaluation of advanced motion models for vehicle tracking. 1 - 6. 10.1109/ICIF.2008.4632283. +[2] Kong, Jason & Pfeiffer, Mark & Schildbach, Georg & Borrelli, Francesco. (2015). Kinematic and dynamic vehicle models for autonomous driving control design. 1094-1099. 10.1109/IVS.2015.7225830. From 08faeeb238b1606b60fc4424e8b87121ac3265fa Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 4 Jul 2023 23:19:18 +0900 Subject: [PATCH 082/118] chore(behavior_path_planner): fix typo and remove unnecessary comment (#4168) Signed-off-by: kosuke55 --- .../src/scene_module/goal_planner/goal_planner_module.cpp | 2 +- .../src/scene_module/start_planner/start_planner_module.cpp | 3 --- 2 files changed, 1 insertion(+), 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 c7725b0ccf0f0..f55d505ea9337 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 @@ -284,7 +284,7 @@ bool GoalPlannerModule::isExecutionRequested() const return lanelet::utils::isInLanelet(goal_pose, current_lane); }); - // check that goal is in current neghibor shoulder lane + // check that goal is in current neighbor shoulder lane const bool goal_is_in_current_shoulder_lanes = std::invoke([&]() { lanelet::ConstLanelet neighbor_shoulder_lane{}; for (const auto & lane : current_lanes) { 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 3540b616aa78f..35f1e2b2b9408 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 @@ -112,7 +112,6 @@ bool StartPlannerModule::isExecutionRequested() const tier4_autoware_utils::pose2transform(planner_data_->self_odometry->pose.pose)); // Check if ego is not out of lanes - // const auto current_lanes = utils::getExtendedCurrentLanes(planner_data_); const double backward_path_length = planner_data_->parameters.backward_path_length + parameters_->max_back_distance; const auto current_lanes = @@ -310,7 +309,6 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() return output; } - // const auto current_lanes = utils::getExtendedCurrentLanes(planner_data_); const double backward_path_length = planner_data_->parameters.backward_path_length + parameters_->max_back_distance; const auto current_lanes = @@ -588,7 +586,6 @@ void StartPlannerModule::updatePullOutStatus() status_.pull_out_lane_ids = utils::getIds(status_.pull_out_lanes); } -// make this class? std::vector StartPlannerModule::searchPullOutStartPoses() { std::vector pull_out_start_pose{}; From 681ba74d7b287e1cabf0e9d3ada04ed3733f9a12 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 4 Jul 2023 23:34:23 +0900 Subject: [PATCH 083/118] feat(behavior_path_planner): add getExtendedCurrentLanes with length args (#4166) Signed-off-by: kosuke55 --- .../behavior_path_planner/utils/utils.hpp | 10 ++++ .../behavior_path_planner/src/utils/utils.cpp | 51 ++++++++++++++++++- 2 files changed, 60 insertions(+), 1 deletion(-) 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 a8be9cdbe1c3e..783b637baeb0f 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 @@ -358,12 +358,22 @@ lanelet::ConstLanelets getCurrentLanes(const std::shared_ptr 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); + +lanelet::ConstLanelets extendPrevLane( + const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes); + lanelet::ConstLanelets extendLanes( const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes); lanelet::ConstLanelets getExtendedCurrentLanes( const std::shared_ptr & planner_data); +lanelet::ConstLanelets getExtendedCurrentLanes( + const std::shared_ptr & planner_data, const double backward_length, + const double forward_length); + lanelet::ConstLanelets calcLaneAroundPose( const std::shared_ptr route_handler, const geometry_msgs::msg::Pose & pose, const double forward_length, const double backward_length, diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 708f4b6f4823f..6dbe0559ea266 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -2607,7 +2607,7 @@ lanelet::ConstLanelets getCurrentLanesFromPath( current_lane, current_pose, p.backward_path_length, p.forward_path_length); } -lanelet::ConstLanelets extendLanes( +lanelet::ConstLanelets extendNextLane( const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes) { auto extended_lanes = lanes; @@ -2618,6 +2618,14 @@ lanelet::ConstLanelets extendLanes( extended_lanes.push_back(next_lanes.front()); } + return extended_lanes; +} + +lanelet::ConstLanelets extendPrevLane( + const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes) +{ + auto extended_lanes = lanes; + // Add previous lane const auto prev_lanes = route_handler->getPreviousLanelets(extended_lanes.front()); if (!prev_lanes.empty()) { @@ -2627,6 +2635,47 @@ lanelet::ConstLanelets extendLanes( return extended_lanes; } +lanelet::ConstLanelets extendLanes( + const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes) +{ + auto extended_lanes = extendNextLane(route_handler, lanes); + extended_lanes = extendPrevLane(route_handler, extended_lanes); + + return extended_lanes; +} + +lanelet::ConstLanelets getExtendedCurrentLanes( + const std::shared_ptr & planner_data, const double backward_length, + const double forward_length) +{ + auto lanes = getCurrentLanes(planner_data); + + double forward_length_sum = 0.0; + double backward_length_sum = 0.0; + + while (backward_length_sum < backward_length) { + auto extended_lanes = extendPrevLane(planner_data->route_handler, lanes); + if (extended_lanes.size() > lanes.size()) { + backward_length_sum += lanelet::utils::getLaneletLength2d(extended_lanes.front()); + } else { + break; // no more previous lanes to add + } + lanes = extended_lanes; + } + + while (forward_length_sum < forward_length) { + auto extended_lanes = extendNextLane(planner_data->route_handler, lanes); + if (extended_lanes.size() > lanes.size()) { + forward_length_sum += lanelet::utils::getLaneletLength2d(extended_lanes.back()); + } else { + break; // no more next lanes to add + } + lanes = extended_lanes; + } + + return lanes; +} + lanelet::ConstLanelets getExtendedCurrentLanes( const std::shared_ptr & planner_data) { From 1e37272d8353087037981ed651f4e5a876b28374 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 5 Jul 2023 09:08:01 +0900 Subject: [PATCH 084/118] fix(default_ad_api): pointer check (#4169) * disable vehicle status api Signed-off-by: Takagi, Isamu * add pointer check Signed-off-by: Takagi, Isamu --------- Signed-off-by: Takagi, Isamu --- system/default_ad_api/src/vehicle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/default_ad_api/src/vehicle.cpp b/system/default_ad_api/src/vehicle.cpp index 43e5d1955fc2b..d22e065d37c5f 100644 --- a/system/default_ad_api/src/vehicle.cpp +++ b/system/default_ad_api/src/vehicle.cpp @@ -138,7 +138,7 @@ void VehicleNode::map_projector_info(const MapProjectorInfo::ConstSharedPtr msg_ void VehicleNode::publish_kinematics() { - if (!kinematic_state_msgs_ || !acceleration_msgs_) return; + if (!kinematic_state_msgs_ || !acceleration_msgs_ || !map_projector_info_) return; autoware_ad_api::vehicle::VehicleKinematics::Message vehicle_kinematics; vehicle_kinematics.pose.header = kinematic_state_msgs_->header; From 18fdbef144311981121ea303532dfed536f77a0a Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 5 Jul 2023 09:48:48 +0900 Subject: [PATCH 085/118] docs: fix msg type in traffic_light_multi_camera_fusion/README.md (#4158) doc: fix msg type in traffic_light_multi_camera_fusion/README.md --- perception/traffic_light_multi_camera_fusion/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/traffic_light_multi_camera_fusion/README.md b/perception/traffic_light_multi_camera_fusion/README.md index ded0613a202ad..238c9b6507ad0 100644 --- a/perception/traffic_light_multi_camera_fusion/README.md +++ b/perception/traffic_light_multi_camera_fusion/README.md @@ -20,9 +20,9 @@ You don't need to configure these topics manually. Just provide the `camera_name ## Output topics -| Name | Type | Description | -| -------------------------- | ---------------------------------------------- | ---------------------------------- | -| `~/output/traffic_signals` | tier4_perception_msgs::TrafficLightSignalArray | traffic light signal fusion result | +| Name | Type | Description | +| -------------------------- | ------------------------------------------------- | ---------------------------------- | +| `~/output/traffic_signals` | autoware_perception_msgs::TrafficLightSignalArray | traffic light signal fusion result | ## Node parameters From cf1fc7ee002b85e093919318f351e021dea7e705 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Wed, 5 Jul 2023 13:30:33 +0900 Subject: [PATCH 086/118] refactor(ndt_scan_matcher): integrate ndt_align_srv into ndt_scan_matcher_core.cpp (#4165) Refactor ndt_align_srv Signed-off-by: Shintaro SAKODA --- localization/ndt_scan_matcher/CMakeLists.txt | 1 - .../ndt_scan_matcher/map_update_module.hpp | 16 +- .../ndt_scan_matcher_core.hpp | 6 +- .../pose_initialization_module.hpp | 80 ---------- .../src/map_update_module.cpp | 111 -------------- .../src/ndt_scan_matcher_core.cpp | 103 ++++++++++++- .../src/pose_initialization_module.cpp | 140 ------------------ 7 files changed, 103 insertions(+), 354 deletions(-) delete mode 100644 localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_initialization_module.hpp delete mode 100644 localization/ndt_scan_matcher/src/pose_initialization_module.cpp diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index 0a04f1bb60466..1d5a9d5ac5320 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -33,7 +33,6 @@ ament_auto_add_executable(ndt_scan_matcher src/pose_array_interpolator.cpp src/tf2_listener_module.cpp src/map_module.cpp - src/pose_initialization_module.cpp src/map_update_module.cpp ) 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 f7966879a5cb0..61034e02e9c91 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 @@ -27,7 +27,6 @@ #include #include #include -#include #include #include @@ -56,9 +55,7 @@ class MapUpdateModule std::shared_ptr> state_ptr); private: - void service_ndt_align( - const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, - tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res); + friend class NDTScanMatcher; void callback_ekf_odom(nav_msgs::msg::Odometry::ConstSharedPtr odom_ptr); void map_update_timer_callback(); @@ -68,19 +65,9 @@ class MapUpdateModule void update_map(const geometry_msgs::msg::Point & position); bool should_update_map(const geometry_msgs::msg::Point & position) const; void publish_partial_pcd_map(); - geometry_msgs::msg::PoseWithCovarianceStamped align_using_monte_carlo( - const std::shared_ptr & ndt_ptr, - const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_with_cov); - void publish_point_cloud( - const rclcpp::Time & sensor_ros_time, const std::string & frame_id, - const std::shared_ptr> & sensor_points_mapTF_ptr); rclcpp::Publisher::SharedPtr loaded_pcd_pub_; - rclcpp::Publisher::SharedPtr - ndt_monte_carlo_initial_pose_marker_pub_; - rclcpp::Publisher::SharedPtr sensor_aligned_pose_pub_; - rclcpp::Service::SharedPtr service_; rclcpp::Client::SharedPtr pcd_loader_client_; rclcpp::TimerBase::SharedPtr map_update_timer_; @@ -97,7 +84,6 @@ class MapUpdateModule std::shared_ptr tf2_listener_module_; std::shared_ptr> state_ptr_; - int initial_estimate_particles_num_; std::optional last_update_position_ = std::nullopt; std::optional current_position_ = std::nullopt; const double dynamic_map_loading_update_distance_; 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 7c9dab4c8103b..d6fc22e3b768c 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 @@ -19,7 +19,6 @@ #include "ndt_scan_matcher/map_module.hpp" #include "ndt_scan_matcher/map_update_module.hpp" -#include "ndt_scan_matcher/pose_initialization_module.hpp" #include "ndt_scan_matcher/tf2_listener_module.hpp" #include @@ -32,6 +31,7 @@ #include #include #include +#include #include #include @@ -99,7 +99,6 @@ class NDTScanMatcher : public rclcpp::Node const std::string source_frame, const std::string target_frame, const pcl::shared_ptr> sensor_points_input_ptr, pcl::shared_ptr> sensor_points_output_ptr); - void update_transforms(); void publish_tf( const rclcpp::Time & sensor_ros_time, const geometry_msgs::msg::Pose & result_pose_msg); @@ -200,12 +199,13 @@ class NDTScanMatcher : public rclcpp::Node bool is_activated_; std::shared_ptr tf2_listener_module_; std::unique_ptr map_module_; - std::unique_ptr pose_init_module_; std::unique_ptr map_update_module_; // cspell: ignore degrounded bool estimate_scores_for_degrounded_scan_; double z_margin_for_ground_removal_; + + bool use_dynamic_map_loading_; }; #endif // NDT_SCAN_MATCHER__NDT_SCAN_MATCHER_CORE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_initialization_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_initialization_module.hpp deleted file mode 100644 index d936a97a77ba7..0000000000000 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/pose_initialization_module.hpp +++ /dev/null @@ -1,80 +0,0 @@ -// Copyright 2015-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 NDT_SCAN_MATCHER__POSE_INITIALIZATION_MODULE_HPP_ -#define NDT_SCAN_MATCHER__POSE_INITIALIZATION_MODULE_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 -#include - -#include -#include -#include - -#include -#include - -#include -#include -#include - -class PoseInitializationModule -{ - using PointSource = pcl::PointXYZ; - using PointTarget = pcl::PointXYZ; - using NormalDistributionsTransform = - pclomp::MultiGridNormalDistributionsTransform; - -public: - PoseInitializationModule( - 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); - -private: - void service_ndt_align( - const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, - tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res); - - geometry_msgs::msg::PoseWithCovarianceStamped align_using_monte_carlo( - const std::shared_ptr & ndt_ptr, - const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_with_cov); - void publish_point_cloud( - const rclcpp::Time & sensor_ros_time, const std::string & frame_id, - const std::shared_ptr> & sensor_points_mapTF_ptr); - - rclcpp::Service::SharedPtr service_; - rclcpp::Publisher::SharedPtr sensor_aligned_pose_pub_; - rclcpp::Publisher::SharedPtr - ndt_monte_carlo_initial_pose_marker_pub_; - int initial_estimate_particles_num_; - - std::shared_ptr ndt_ptr_; - std::mutex * ndt_ptr_mutex_; - std::string map_frame_; - rclcpp::Logger logger_; - rclcpp::Clock::SharedPtr clock_; - std::shared_ptr tf2_listener_module_; - std::shared_ptr> state_ptr_; -}; - -#endif // NDT_SCAN_MATCHER__POSE_INITIALIZATION_MODULE_HPP_ diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 2a128568bb13c..a2d0f444623ec 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -41,14 +41,6 @@ MapUpdateModule::MapUpdateModule( node->declare_parameter("dynamic_map_loading_map_radius")), lidar_radius_(node->declare_parameter("lidar_radius")) { - initial_estimate_particles_num_ = node->declare_parameter("initial_estimate_particles_num"); - - sensor_aligned_pose_pub_ = - node->create_publisher("monte_carlo_points_aligned", 10); - ndt_monte_carlo_initial_pose_marker_pub_ = - node->create_publisher( - "monte_carlo_initial_pose_marker", 10); - auto main_sub_opt = rclcpp::SubscriptionOptions(); main_sub_opt.callback_group = main_callback_group; @@ -61,12 +53,6 @@ MapUpdateModule::MapUpdateModule( loaded_pcd_pub_ = node->create_publisher( "debug/loaded_pointcloud_map", rclcpp::QoS{1}.transient_local()); - service_ = node->create_service( - "ndt_align_srv", - std::bind( - &MapUpdateModule::service_ndt_align, this, std::placeholders::_1, std::placeholders::_2), - rclcpp::ServicesQoS().get_rmw_qos_profile(), map_callback_group_); - pcd_loader_client_ = node->create_client("pcd_loader_service"); while (!pcd_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) { @@ -84,43 +70,6 @@ MapUpdateModule::MapUpdateModule( map_callback_group_); } -void MapUpdateModule::service_ndt_align( - const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, - tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res) -{ - // get TF from pose_frame to map_frame - auto TF_pose_to_map_ptr = std::make_shared(); - tf2_listener_module_->get_transform( - clock_->now(), map_frame_, req->pose_with_covariance.header.frame_id, TF_pose_to_map_ptr); - - // transform pose_frame to map_frame - const auto mapTF_initial_pose_msg = transform(req->pose_with_covariance, *TF_pose_to_map_ptr); - update_map(mapTF_initial_pose_msg.pose.pose.position); - - if (ndt_ptr_->getInputTarget() == nullptr) { - res->success = false; - RCLCPP_WARN(logger_, "No InputTarget"); - return; - } - - if (ndt_ptr_->getInputSource() == nullptr) { - res->success = false; - RCLCPP_WARN(logger_, "No InputSource"); - return; - } - - // mutex Map - std::lock_guard lock(*ndt_ptr_mutex_); - - (*state_ptr_)["state"] = "Aligning"; - res->pose_with_covariance = align_using_monte_carlo(ndt_ptr_, mapTF_initial_pose_msg); - (*state_ptr_)["state"] = "Sleeping"; - res->success = true; - res->pose_with_covariance.pose.covariance = req->pose_with_covariance.pose.covariance; - - last_update_position_ = res->pose_with_covariance.pose.pose.position; -} - void MapUpdateModule::callback_ekf_odom(nav_msgs::msg::Odometry::ConstSharedPtr odom_ptr) { current_position_ = odom_ptr->pose.pose.position; @@ -229,66 +178,6 @@ void MapUpdateModule::update_ndt( publish_partial_pcd_map(); } -geometry_msgs::msg::PoseWithCovarianceStamped MapUpdateModule::align_using_monte_carlo( - const std::shared_ptr & ndt_ptr, - const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_with_cov) -{ - if (ndt_ptr->getInputTarget() == nullptr || ndt_ptr->getInputSource() == nullptr) { - RCLCPP_WARN(logger_, "No Map or Sensor PointCloud"); - return geometry_msgs::msg::PoseWithCovarianceStamped(); - } - - // generateParticle - const auto initial_poses = - create_random_pose_array(initial_pose_with_cov, initial_estimate_particles_num_); - - std::vector particle_array; - auto output_cloud = std::make_shared>(); - - for (unsigned int i = 0; i < initial_poses.size(); i++) { - const auto & initial_pose = initial_poses[i]; - 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(); - - Particle particle( - initial_pose, matrix4f_to_pose(ndt_result.pose), ndt_result.transform_probability, - ndt_result.iteration_num); - particle_array.push_back(particle); - const auto marker_array = make_debug_markers( - clock_->now(), map_frame_, tier4_autoware_utils::createMarkerScale(0.3, 0.1, 0.1), particle, - i); - ndt_monte_carlo_initial_pose_marker_pub_->publish(marker_array); - - auto sensor_points_mapTF_ptr = std::make_shared>(); - tier4_autoware_utils::transformPointCloud( - *ndt_ptr->getInputSource(), *sensor_points_mapTF_ptr, ndt_result.pose); - publish_point_cloud(initial_pose_with_cov.header.stamp, map_frame_, sensor_points_mapTF_ptr); - } - - auto best_particle_ptr = std::max_element( - std::begin(particle_array), std::end(particle_array), - [](const Particle & lhs, const Particle & rhs) { return lhs.score < rhs.score; }); - - geometry_msgs::msg::PoseWithCovarianceStamped result_pose_with_cov_msg; - result_pose_with_cov_msg.header.stamp = initial_pose_with_cov.header.stamp; - result_pose_with_cov_msg.header.frame_id = map_frame_; - result_pose_with_cov_msg.pose.pose = best_particle_ptr->result_pose; - - return result_pose_with_cov_msg; -} - -void MapUpdateModule::publish_point_cloud( - const rclcpp::Time & sensor_ros_time, const std::string & frame_id, - const std::shared_ptr> & sensor_points_mapTF_ptr) -{ - sensor_msgs::msg::PointCloud2 sensor_points_mapTF_msg; - pcl::toROSMsg(*sensor_points_mapTF_ptr, sensor_points_mapTF_msg); - sensor_points_mapTF_msg.header.stamp = sensor_ros_time; - sensor_points_mapTF_msg.header.frame_id = frame_id; - sensor_aligned_pose_pub_->publish(sensor_points_mapTF_msg); -} - void MapUpdateModule::publish_partial_pcd_map() { pcl::PointCloud map_pcl = ndt_ptr_->getVoxelPCD(); 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 88e43a8f01980..400e4570cd5b4 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -150,6 +150,9 @@ NDTScanMatcher::NDTScanMatcher() output_pose_covariance_[i] = output_pose_covariance[i]; } + initial_estimate_particles_num_ = + this->declare_parameter("initial_estimate_particles_num", initial_estimate_particles_num_); + rclcpp::CallbackGroup::SharedPtr initial_pose_callback_group; initial_pose_callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -211,7 +214,15 @@ NDTScanMatcher::NDTScanMatcher() ndt_marker_pub_ = this->create_publisher("ndt_marker", 10); diagnostics_pub_ = this->create_publisher("/diagnostics", 10); + ndt_monte_carlo_initial_pose_marker_pub_ = + this->create_publisher( + "monte_carlo_initial_pose_marker", 10); + service_ = this->create_service( + "ndt_align_srv", + std::bind( + &NDTScanMatcher::service_ndt_align, this, std::placeholders::_1, std::placeholders::_2), + rclcpp::ServicesQoS().get_rmw_qos_profile(), main_callback_group); service_trigger_node_ = this->create_service( "trigger_node_srv", std::bind( @@ -223,15 +234,13 @@ NDTScanMatcher::NDTScanMatcher() tf2_listener_module_ = std::make_shared(this); - if (this->declare_parameter("use_dynamic_map_loading")) { + 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_); } else { map_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_, main_callback_group); - pose_init_module_ = std::make_unique( - this, &ndt_ptr_mtx_, ndt_ptr_, tf2_listener_module_, map_frame_, main_callback_group, - state_ptr_); } } @@ -689,3 +698,89 @@ void NDTScanMatcher::service_trigger_node( res->success = true; return; } + +void NDTScanMatcher::service_ndt_align( + const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, + tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res) +{ + // get TF from pose_frame to map_frame + auto TF_pose_to_map_ptr = std::make_shared(); + tf2_listener_module_->get_transform( + get_clock()->now(), map_frame_, req->pose_with_covariance.header.frame_id, TF_pose_to_map_ptr); + + // transform pose_frame to map_frame + const auto mapTF_initial_pose_msg = transform(req->pose_with_covariance, *TF_pose_to_map_ptr); + if (use_dynamic_map_loading_) { + map_update_module_->update_map(mapTF_initial_pose_msg.pose.pose.position); + } + + if (ndt_ptr_->getInputTarget() == nullptr) { + res->success = false; + RCLCPP_WARN(get_logger(), "No InputTarget"); + return; + } + + if (ndt_ptr_->getInputSource() == nullptr) { + res->success = false; + RCLCPP_WARN(get_logger(), "No InputSource"); + return; + } + + // mutex Map + std::lock_guard lock(ndt_ptr_mtx_); + + (*state_ptr_)["state"] = "Aligning"; + res->pose_with_covariance = align_using_monte_carlo(ndt_ptr_, mapTF_initial_pose_msg); + (*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, + 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(); + } + + // generateParticle + const auto initial_poses = + create_random_pose_array(initial_pose_with_cov, initial_estimate_particles_num_); + + std::vector particle_array; + auto output_cloud = std::make_shared>(); + + for (unsigned int i = 0; i < initial_poses.size(); i++) { + const auto & initial_pose = initial_poses[i]; + 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(); + + Particle particle( + initial_pose, matrix4f_to_pose(ndt_result.pose), ndt_result.transform_probability, + ndt_result.iteration_num); + particle_array.push_back(particle); + const auto marker_array = make_debug_markers( + get_clock()->now(), map_frame_, tier4_autoware_utils::createMarkerScale(0.3, 0.1, 0.1), + particle, i); + ndt_monte_carlo_initial_pose_marker_pub_->publish(marker_array); + + auto sensor_points_mapTF_ptr = std::make_shared>(); + tier4_autoware_utils::transformPointCloud( + *ndt_ptr->getInputSource(), *sensor_points_mapTF_ptr, ndt_result.pose); + publish_point_cloud(initial_pose_with_cov.header.stamp, map_frame_, sensor_points_mapTF_ptr); + } + + auto best_particle_ptr = std::max_element( + std::begin(particle_array), std::end(particle_array), + [](const Particle & lhs, const Particle & rhs) { return lhs.score < rhs.score; }); + + geometry_msgs::msg::PoseWithCovarianceStamped result_pose_with_cov_msg; + result_pose_with_cov_msg.header.stamp = initial_pose_with_cov.header.stamp; + result_pose_with_cov_msg.header.frame_id = map_frame_; + result_pose_with_cov_msg.pose.pose = best_particle_ptr->result_pose; + + return result_pose_with_cov_msg; +} diff --git a/localization/ndt_scan_matcher/src/pose_initialization_module.cpp b/localization/ndt_scan_matcher/src/pose_initialization_module.cpp deleted file mode 100644 index 2814085fee07c..0000000000000 --- a/localization/ndt_scan_matcher/src/pose_initialization_module.cpp +++ /dev/null @@ -1,140 +0,0 @@ -// Copyright 2022 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 "ndt_scan_matcher/pose_initialization_module.hpp" - -PoseInitializationModule::PoseInitializationModule( - 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) -: ndt_ptr_(ndt_ptr), - ndt_ptr_mutex_(ndt_ptr_mutex), - map_frame_(map_frame), - logger_(node->get_logger()), - clock_(node->get_clock()), - tf2_listener_module_(tf2_listener_module), - state_ptr_(state_ptr) -{ - initial_estimate_particles_num_ = - node->declare_parameter("initial_estimate_particles_num", initial_estimate_particles_num_); - - sensor_aligned_pose_pub_ = - node->create_publisher("monte_carlo_points_aligned", 10); - ndt_monte_carlo_initial_pose_marker_pub_ = - node->create_publisher( - "monte_carlo_initial_pose_marker", 10); - - service_ = node->create_service( - "ndt_align_srv", - std::bind( - &PoseInitializationModule::service_ndt_align, this, std::placeholders::_1, - std::placeholders::_2), - rclcpp::ServicesQoS().get_rmw_qos_profile(), main_callback_group); -} - -void PoseInitializationModule::service_ndt_align( - const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, - tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res) -{ - // get TF from pose_frame to map_frame - auto TF_pose_to_map_ptr = std::make_shared(); - tf2_listener_module_->get_transform( - clock_->now(), map_frame_, req->pose_with_covariance.header.frame_id, TF_pose_to_map_ptr); - - // transform pose_frame to map_frame - const auto mapTF_initial_pose_msg = transform(req->pose_with_covariance, *TF_pose_to_map_ptr); - - if (ndt_ptr_->getInputTarget() == nullptr) { - res->success = false; - RCLCPP_WARN(logger_, "No InputTarget"); - return; - } - - if (ndt_ptr_->getInputSource() == nullptr) { - res->success = false; - RCLCPP_WARN(logger_, "No InputSource"); - return; - } - - // mutex Map - std::lock_guard lock(*ndt_ptr_mutex_); - - (*state_ptr_)["state"] = "Aligning"; - res->pose_with_covariance = align_using_monte_carlo(ndt_ptr_, mapTF_initial_pose_msg); - (*state_ptr_)["state"] = "Sleeping"; - res->success = true; - res->pose_with_covariance.pose.covariance = req->pose_with_covariance.pose.covariance; -} - -geometry_msgs::msg::PoseWithCovarianceStamped PoseInitializationModule::align_using_monte_carlo( - const std::shared_ptr & ndt_ptr, - const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_with_cov) -{ - if (ndt_ptr->getInputTarget() == nullptr || ndt_ptr->getInputSource() == nullptr) { - RCLCPP_WARN(logger_, "No Map or Sensor PointCloud"); - return geometry_msgs::msg::PoseWithCovarianceStamped(); - } - - // generateParticle - const auto initial_poses = - create_random_pose_array(initial_pose_with_cov, initial_estimate_particles_num_); - - std::vector particle_array; - auto output_cloud = std::make_shared>(); - - for (unsigned int i = 0; i < initial_poses.size(); i++) { - const auto & initial_pose = initial_poses[i]; - 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(); - - Particle particle( - initial_pose, matrix4f_to_pose(ndt_result.pose), ndt_result.transform_probability, - ndt_result.iteration_num); - particle_array.push_back(particle); - const auto marker_array = make_debug_markers( - clock_->now(), map_frame_, tier4_autoware_utils::createMarkerScale(0.3, 0.1, 0.1), particle, - i); - ndt_monte_carlo_initial_pose_marker_pub_->publish(marker_array); - - auto sensor_points_mapTF_ptr = std::make_shared>(); - tier4_autoware_utils::transformPointCloud( - *ndt_ptr->getInputSource(), *sensor_points_mapTF_ptr, ndt_result.pose); - publish_point_cloud(initial_pose_with_cov.header.stamp, map_frame_, sensor_points_mapTF_ptr); - } - - auto best_particle_ptr = std::max_element( - std::begin(particle_array), std::end(particle_array), - [](const Particle & lhs, const Particle & rhs) { return lhs.score < rhs.score; }); - - geometry_msgs::msg::PoseWithCovarianceStamped result_pose_with_cov_msg; - result_pose_with_cov_msg.header.stamp = initial_pose_with_cov.header.stamp; - result_pose_with_cov_msg.header.frame_id = map_frame_; - result_pose_with_cov_msg.pose.pose = best_particle_ptr->result_pose; - - return result_pose_with_cov_msg; -} - -void PoseInitializationModule::publish_point_cloud( - const rclcpp::Time & sensor_ros_time, const std::string & frame_id, - const std::shared_ptr> & sensor_points_mapTF_ptr) -{ - sensor_msgs::msg::PointCloud2 sensor_points_mapTF_msg; - pcl::toROSMsg(*sensor_points_mapTF_ptr, sensor_points_mapTF_msg); - sensor_points_mapTF_msg.header.stamp = sensor_ros_time; - sensor_points_mapTF_msg.header.frame_id = frame_id; - sensor_aligned_pose_pub_->publish(sensor_points_mapTF_msg); -} From 76742c1ef212304feeba5838720dab9074883f28 Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Wed, 5 Jul 2023 15:02:07 +0900 Subject: [PATCH 087/118] feat(radar_tracks_noise_filter): add radar_tracks_noise_filter (#4037) * feature(radar_tracks_noise_filter): add radar_tracks_noise_filter Signed-off-by: scepter914 * update README Signed-off-by: scepter914 * style(pre-commit): autofix * fix package.xml test error Signed-off-by: scepter914 * update README Signed-off-by: scepter914 * apply pre-commit Signed-off-by: scepter914 * fix default parapmeter in src Signed-off-by: scepter914 * change default parameter Signed-off-by: scepter914 --------- Signed-off-by: scepter914 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../radar_tracks_noise_filter/CMakeLists.txt | 40 ++++++ sensing/radar_tracks_noise_filter/README.md | 34 +++++ .../radar_tracks_noise_filter_node.hpp | 66 ++++++++++ .../radar_tracks_noise_filter.launch.xml | 17 +++ sensing/radar_tracks_noise_filter/package.xml | 26 ++++ .../radar_tracks_noise_filter_node.cpp | 122 ++++++++++++++++++ 6 files changed, 305 insertions(+) create mode 100644 sensing/radar_tracks_noise_filter/CMakeLists.txt create mode 100644 sensing/radar_tracks_noise_filter/README.md create mode 100644 sensing/radar_tracks_noise_filter/include/radar_tracks_noise_filter/radar_tracks_noise_filter_node.hpp create mode 100644 sensing/radar_tracks_noise_filter/launch/radar_tracks_noise_filter.launch.xml create mode 100644 sensing/radar_tracks_noise_filter/package.xml create mode 100644 sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp diff --git a/sensing/radar_tracks_noise_filter/CMakeLists.txt b/sensing/radar_tracks_noise_filter/CMakeLists.txt new file mode 100644 index 0000000000000..517a3f1df72f1 --- /dev/null +++ b/sensing/radar_tracks_noise_filter/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5) +project(radar_tracks_noise_filter) + +# Compile options +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_EXTENSIONS OFF) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# Dependencies +find_package(autoware_cmake REQUIRED) +autoware_package() + +# Targets +ament_auto_add_library(radar_tracks_noise_filter_node_component SHARED + src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp +) + +rclcpp_components_register_node(radar_tracks_noise_filter_node_component + PLUGIN "radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode" + EXECUTABLE radar_tracks_noise_filter_node +) + +# Tests +if(BUILD_TESTING) + list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_uncrustify) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +# Package +ament_auto_package( + INSTALL_TO_SHARE + launch +) diff --git a/sensing/radar_tracks_noise_filter/README.md b/sensing/radar_tracks_noise_filter/README.md new file mode 100644 index 0000000000000..f1251b4f4ee74 --- /dev/null +++ b/sensing/radar_tracks_noise_filter/README.md @@ -0,0 +1,34 @@ +# radar_tracks_noise_filter + +This package contains a radar object filter module for `radar_msgs/msg/RadarTrack`. +This package can filter noise objects in RadarTracks. + +## Algorithm + +The core algorithm of this package is `RadarTrackCrossingNoiseFilterNode::isNoise()` function. +See the function and the parameters for details. + +- Y-axis threshold + +Radar can detect x-axis velocity as doppler velocity, but cannot detect y-axis velocity. +Some radar can estimate y-axis velocity inside the device, but it sometimes lack precision. +In y-axis threshold filter, if y-axis velocity of RadarTrack is more than `velocity_y_threshold`, it treats as noise objects. + +## Input + +| Name | Type | Description | +| ---------------- | ------------------------------ | ------------------- | +| `~/input/tracks` | radar_msgs/msg/RadarTracks.msg | 3D detected tracks. | + +## Output + +| Name | Type | Description | +| -------------------------- | ------------------------------ | ---------------- | +| `~/output/noise_tracks` | radar_msgs/msg/RadarTracks.msg | Noise objects | +| `~/output/filtered_tracks` | radar_msgs/msg/RadarTracks.msg | Filtered objects | + +## Parameters + +| Name | Type | Description | Default value | +| :--------------------- | :----- | :--------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| `velocity_y_threshold` | double | Y-axis velocity threshold [m/s]. If y-axis velocity of RadarTrack is more than `velocity_y_threshold`, it treats as noise objects. | 7.0 | diff --git a/sensing/radar_tracks_noise_filter/include/radar_tracks_noise_filter/radar_tracks_noise_filter_node.hpp b/sensing/radar_tracks_noise_filter/include/radar_tracks_noise_filter/radar_tracks_noise_filter_node.hpp new file mode 100644 index 0000000000000..9b329da3e5579 --- /dev/null +++ b/sensing/radar_tracks_noise_filter/include/radar_tracks_noise_filter/radar_tracks_noise_filter_node.hpp @@ -0,0 +1,66 @@ +// 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 RADAR_TRACKS_NOISE_FILTER__RADAR_TRACKS_NOISE_FILTER_NODE_HPP_ +#define RADAR_TRACKS_NOISE_FILTER__RADAR_TRACKS_NOISE_FILTER_NODE_HPP_ + +#include "rclcpp/rclcpp.hpp" + +#include "radar_msgs/msg/radar_tracks.hpp" + +#include +#include +#include + +namespace radar_tracks_noise_filter +{ +using radar_msgs::msg::RadarTrack; +using radar_msgs::msg::RadarTracks; + +class RadarTrackCrossingNoiseFilterNode : public rclcpp::Node +{ +public: + explicit RadarTrackCrossingNoiseFilterNode(const rclcpp::NodeOptions & node_options); + + struct NodeParam + { + double velocity_y_threshold{}; + }; + +private: + // Subscriber + rclcpp::Subscription::SharedPtr sub_tracks_{}; + + // Callback + void onTracks(const RadarTracks::ConstSharedPtr msg); + + // Publisher + rclcpp::Publisher::SharedPtr pub_noise_tracks_{}; + rclcpp::Publisher::SharedPtr pub_filtered_tracks_{}; + + // Parameter Server + OnSetParametersCallbackHandle::SharedPtr set_param_res_; + rcl_interfaces::msg::SetParametersResult onSetParam( + const std::vector & params); + + // Parameter + NodeParam node_param_{}; + + // Core + bool isNoise(const RadarTrack & radar_track); +}; + +} // namespace radar_tracks_noise_filter + +#endif // RADAR_TRACKS_NOISE_FILTER__RADAR_TRACKS_NOISE_FILTER_NODE_HPP_ diff --git a/sensing/radar_tracks_noise_filter/launch/radar_tracks_noise_filter.launch.xml b/sensing/radar_tracks_noise_filter/launch/radar_tracks_noise_filter.launch.xml new file mode 100644 index 0000000000000..f38fe36b50af4 --- /dev/null +++ b/sensing/radar_tracks_noise_filter/launch/radar_tracks_noise_filter.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/sensing/radar_tracks_noise_filter/package.xml b/sensing/radar_tracks_noise_filter/package.xml new file mode 100644 index 0000000000000..3af9658535687 --- /dev/null +++ b/sensing/radar_tracks_noise_filter/package.xml @@ -0,0 +1,26 @@ + + + + radar_tracks_noise_filter + 0.1.0 + radar_tracks_noise_filter + Sathshi Tanaka + Shunsuke Miura + Apache License 2.0 + Sathshi Tanaka + + ament_cmake_auto + + geometry_msgs + radar_msgs + rclcpp + rclcpp_components + + autoware_cmake + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp b/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp new file mode 100644 index 0000000000000..b58bd7799122a --- /dev/null +++ b/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp @@ -0,0 +1,122 @@ +// 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 "radar_tracks_noise_filter/radar_tracks_noise_filter_node.hpp" + +#include +#include +#include + +namespace +{ +template +bool update_param( + const std::vector & params, const std::string & name, T & value) +{ + const auto itr = std::find_if( + params.cbegin(), params.cend(), + [&name](const rclcpp::Parameter & p) { return p.get_name() == name; }); + + // Not found + if (itr == params.cend()) { + return false; + } + + value = itr->template get_value(); + return true; +} +} // namespace + +namespace radar_tracks_noise_filter +{ +using radar_msgs::msg::RadarTrack; +using radar_msgs::msg::RadarTracks; + +RadarTrackCrossingNoiseFilterNode::RadarTrackCrossingNoiseFilterNode( + const rclcpp::NodeOptions & node_options) +: Node("radar_tracks_noise_filter", node_options) +{ + // Parameter Server + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&RadarTrackCrossingNoiseFilterNode::onSetParam, this, std::placeholders::_1)); + + // Node Parameter + node_param_.velocity_y_threshold = declare_parameter("velocity_y_threshold", 7.0); + + // Subscriber + sub_tracks_ = create_subscription( + "~/input/tracks", rclcpp::QoS{1}, + std::bind(&RadarTrackCrossingNoiseFilterNode::onTracks, this, std::placeholders::_1)); + + // Publisher + pub_noise_tracks_ = create_publisher("~/output/noise_tracks", 1); + pub_filtered_tracks_ = create_publisher("~/output/filtered_tracks", 1); +} + +void RadarTrackCrossingNoiseFilterNode::onTracks(const RadarTracks::ConstSharedPtr msg) +{ + RadarTracks noise_tracks; + RadarTracks filtered_tracks; + noise_tracks.header = msg->header; + filtered_tracks.header = msg->header; + + for (const auto & radar_track : msg->tracks) { + if (isNoise(radar_track)) { + noise_tracks.tracks.emplace_back(radar_track); + } else { + filtered_tracks.tracks.emplace_back(radar_track); + } + } + // publish + pub_noise_tracks_->publish(noise_tracks); + pub_filtered_tracks_->publish(filtered_tracks); +} + +rcl_interfaces::msg::SetParametersResult RadarTrackCrossingNoiseFilterNode::onSetParam( + const std::vector & params) +{ + rcl_interfaces::msg::SetParametersResult result; + + try { + // Node Parameter + { + auto & p = node_param_; + + // Update params + update_param(params, "velocity_y_threshold", p.velocity_y_threshold); + } + } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { + result.successful = false; + result.reason = e.what(); + return result; + } + + result.successful = true; + result.reason = "success"; + return result; +} + +bool RadarTrackCrossingNoiseFilterNode::isNoise(const RadarTrack & radar_track) +{ + if (std::abs(radar_track.velocity.y) < node_param_.velocity_y_threshold) { + return false; + } else { + return true; + } +} + +} // namespace radar_tracks_noise_filter + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode) From 6f116759266f8eaa882a2bd37efa77155f040b2f Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Wed, 5 Jul 2023 15:02:46 +0900 Subject: [PATCH 088/118] feat(object_velocity_splitter): add object_velocity_splitter (#4093) * feat(object_velocity_splitter): add object_velocity_splitter Signed-off-by: scepter914 * apply pre-commit Signed-off-by: scepter914 * fix package.xml test error Signed-off-by: scepter914 --------- Signed-off-by: scepter914 --- .../object_velocity_splitter/CMakeLists.txt | 40 ++++++ perception/object_velocity_splitter/README.md | 23 ++++ .../object_velocity_splitter_node.hpp | 67 ++++++++++ .../object_velocity_splitter.launch.xml | 17 +++ .../object_velocity_splitter/package.xml | 28 +++++ .../object_velocity_splitter_node.cpp | 116 ++++++++++++++++++ 6 files changed, 291 insertions(+) create mode 100644 perception/object_velocity_splitter/CMakeLists.txt create mode 100644 perception/object_velocity_splitter/README.md create mode 100644 perception/object_velocity_splitter/include/object_velocity_splitter/object_velocity_splitter_node.hpp create mode 100644 perception/object_velocity_splitter/launch/object_velocity_splitter.launch.xml create mode 100644 perception/object_velocity_splitter/package.xml create mode 100644 perception/object_velocity_splitter/src/object_velocity_splitter_node/object_velocity_splitter_node.cpp diff --git a/perception/object_velocity_splitter/CMakeLists.txt b/perception/object_velocity_splitter/CMakeLists.txt new file mode 100644 index 0000000000000..bcc56f522f0a8 --- /dev/null +++ b/perception/object_velocity_splitter/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5) +project(object_velocity_splitter) + +# Compile options +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_EXTENSIONS OFF) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# Dependencies +find_package(autoware_cmake REQUIRED) +autoware_package() + +# Targets +ament_auto_add_library(object_velocity_splitter_node_component SHARED + src/object_velocity_splitter_node/object_velocity_splitter_node.cpp +) + +rclcpp_components_register_node(object_velocity_splitter_node_component + PLUGIN "object_velocity_splitter::ObjectVelocitySplitterNode" + EXECUTABLE object_velocity_splitter_node +) + +# Tests +if(BUILD_TESTING) + list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_uncrustify) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +# Package +ament_auto_package( + INSTALL_TO_SHARE + launch +) diff --git a/perception/object_velocity_splitter/README.md b/perception/object_velocity_splitter/README.md new file mode 100644 index 0000000000000..9dcd535a5a10f --- /dev/null +++ b/perception/object_velocity_splitter/README.md @@ -0,0 +1,23 @@ +# object_velocity_splitter + +This package contains a object filter module for [autoware_auto_perception_msgs/msg/DetectedObject](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_perception_msgs/msg/DetectedObject.idl). +This package can split DetectedObjects into two messages by object's speed. + +## Input + +| Name | Type | Description | +| ----------------- | ----------------------------------------------------- | -------------------- | +| `~/input/objects` | autoware_auto_perception_msgs/msg/DetectedObjects.msg | 3D detected objects. | + +## Output + +| Name | Type | Description | +| ----------------------------- | ----------------------------------------------------- | ----------------------- | +| `~/output/low_speed_objects` | autoware_auto_perception_msgs/msg/DetectedObjects.msg | Objects with low speed | +| `~/output/high_speed_objects` | autoware_auto_perception_msgs/msg/DetectedObjects.msg | Objects with high speed | + +## Parameters + +| Name | Type | Description | Default value | +| :------------------- | :----- | :-------------------------------------------------- | :------------ | +| `velocity_threshold` | double | Velocity threshold parameter to split objects [m/s] | 3.0 | diff --git a/perception/object_velocity_splitter/include/object_velocity_splitter/object_velocity_splitter_node.hpp b/perception/object_velocity_splitter/include/object_velocity_splitter/object_velocity_splitter_node.hpp new file mode 100644 index 0000000000000..9b1857f614997 --- /dev/null +++ b/perception/object_velocity_splitter/include/object_velocity_splitter/object_velocity_splitter_node.hpp @@ -0,0 +1,67 @@ +// 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 OBJECT_VELOCITY_SPLITTER__OBJECT_VELOCITY_SPLITTER_NODE_HPP_ +#define OBJECT_VELOCITY_SPLITTER__OBJECT_VELOCITY_SPLITTER_NODE_HPP_ + +#include "rclcpp/rclcpp.hpp" + +#include "autoware_auto_perception_msgs/msg/detected_objects.hpp" + +#include +#include +#include +#include + +namespace object_velocity_splitter +{ +using autoware_auto_perception_msgs::msg::DetectedObject; +using autoware_auto_perception_msgs::msg::DetectedObjects; + +class ObjectVelocitySplitterNode : public rclcpp::Node +{ +public: + explicit ObjectVelocitySplitterNode(const rclcpp::NodeOptions & node_options); + + struct NodeParam + { + double velocity_threshold{}; + }; + +private: + // Subscriber + rclcpp::Subscription::SharedPtr sub_objects_{}; + + // Callback + void onObjects(const DetectedObjects::ConstSharedPtr msg); + + // Data Buffer + DetectedObjects::ConstSharedPtr objects_data_{}; + + // Publisher + rclcpp::Publisher::SharedPtr pub_high_speed_objects_{}; + rclcpp::Publisher::SharedPtr pub_low_speed_objects_{}; + + // Parameter Server + OnSetParametersCallbackHandle::SharedPtr set_param_res_; + rcl_interfaces::msg::SetParametersResult onSetParam( + const std::vector & params); + + // Parameter + NodeParam node_param_{}; +}; + +} // namespace object_velocity_splitter + +#endif // OBJECT_VELOCITY_SPLITTER__OBJECT_VELOCITY_SPLITTER_NODE_HPP_ diff --git a/perception/object_velocity_splitter/launch/object_velocity_splitter.launch.xml b/perception/object_velocity_splitter/launch/object_velocity_splitter.launch.xml new file mode 100644 index 0000000000000..42d7f3d61f386 --- /dev/null +++ b/perception/object_velocity_splitter/launch/object_velocity_splitter.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/perception/object_velocity_splitter/package.xml b/perception/object_velocity_splitter/package.xml new file mode 100644 index 0000000000000..06ec834920012 --- /dev/null +++ b/perception/object_velocity_splitter/package.xml @@ -0,0 +1,28 @@ + + + + object_velocity_splitter + 0.1.0 + object_velocity_splitter + Sathshi Tanaka + Shunsuke Miura + Yoshi Ri + Apache License 2.0 + Sathshi Tanaka + + ament_cmake_auto + + autoware_auto_perception_msgs + geometry_msgs + rclcpp + rclcpp_components + tier4_autoware_utils + + autoware_cmake + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/perception/object_velocity_splitter/src/object_velocity_splitter_node/object_velocity_splitter_node.cpp b/perception/object_velocity_splitter/src/object_velocity_splitter_node/object_velocity_splitter_node.cpp new file mode 100644 index 0000000000000..775f612b8caeb --- /dev/null +++ b/perception/object_velocity_splitter/src/object_velocity_splitter_node/object_velocity_splitter_node.cpp @@ -0,0 +1,116 @@ +// 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 "object_velocity_splitter/object_velocity_splitter_node.hpp" + +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#include +#include +#include + +namespace +{ +template +bool update_param( + const std::vector & params, const std::string & name, T & value) +{ + const auto itr = std::find_if( + params.cbegin(), params.cend(), + [&name](const rclcpp::Parameter & p) { return p.get_name() == name; }); + + // Not found + if (itr == params.cend()) { + return false; + } + + value = itr->template get_value(); + return true; +} +} // namespace + +namespace object_velocity_splitter +{ +using autoware_auto_perception_msgs::msg::DetectedObject; +using autoware_auto_perception_msgs::msg::DetectedObjects; + +ObjectVelocitySplitterNode::ObjectVelocitySplitterNode(const rclcpp::NodeOptions & node_options) +: Node("object_velocity_splitter", node_options) +{ + // Parameter Server + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&ObjectVelocitySplitterNode::onSetParam, this, std::placeholders::_1)); + + // Node Parameter + node_param_.velocity_threshold = declare_parameter("velocity_threshold", 3.0); + + // Subscriber + sub_objects_ = create_subscription( + "~/input/objects", rclcpp::QoS{1}, + std::bind(&ObjectVelocitySplitterNode::onObjects, this, std::placeholders::_1)); + + // Publisher + pub_high_speed_objects_ = create_publisher("~/output/high_speed_objects", 1); + pub_low_speed_objects_ = create_publisher("~/output/low_speed_objects", 1); +} + +void ObjectVelocitySplitterNode::onObjects(const DetectedObjects::ConstSharedPtr objects_data_) +{ + DetectedObjects high_speed_objects; + DetectedObjects low_speed_objects; + high_speed_objects.header = objects_data_->header; + low_speed_objects.header = objects_data_->header; + + for (const auto & object : objects_data_->objects) { + if ( + std::abs(tier4_autoware_utils::calcNorm( + object.kinematics.twist_with_covariance.twist.linear)) < node_param_.velocity_threshold) { + low_speed_objects.objects.emplace_back(object); + } else { + high_speed_objects.objects.emplace_back(object); + } + } + // publish + pub_high_speed_objects_->publish(high_speed_objects); + pub_low_speed_objects_->publish(low_speed_objects); +} + +rcl_interfaces::msg::SetParametersResult ObjectVelocitySplitterNode::onSetParam( + const std::vector & params) +{ + rcl_interfaces::msg::SetParametersResult result; + + try { + // Node Parameter + { + auto & p = node_param_; + + // Update params + update_param(params, "velocity_threshold", p.velocity_threshold); + } + } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { + result.successful = false; + result.reason = e.what(); + return result; + } + + result.successful = true; + result.reason = "success"; + return result; +} + +} // namespace object_velocity_splitter + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(object_velocity_splitter::ObjectVelocitySplitterNode) From 3d2f446e60598f158d11668a8e2017b909e07b29 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Wed, 5 Jul 2023 15:45:31 +0900 Subject: [PATCH 089/118] feat(roi_cluster_fusion): check whether cluster RoI is inside of RoI detected by 2D detector (#4147) * feat: check whether cluster roi is inside of roi detected by 2D detector Signed-off-by: ktro2828 * feat: add option whether only allow cluster RoIs inside detector RoIs Signed-off-by: ktro2828 * Update perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp Co-authored-by: Yukihiro Saito Signed-off-by: ktro2828 * style(pre-commit): autofix Signed-off-by: ktro2828 --------- Signed-off-by: ktro2828 Co-authored-by: Yukihiro Saito Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../docs/roi-cluster-fusion.md | 20 ++++++++++--------- .../roi_cluster_fusion/node.hpp | 2 ++ .../utils/geometry.hpp | 4 ++++ .../launch/roi_cluster_fusion.launch.xml | 2 ++ .../src/roi_cluster_fusion/node.cpp | 8 +++++++- .../src/utils/geometry.cpp | 11 ++++++++++ 6 files changed, 37 insertions(+), 10 deletions(-) diff --git a/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md b/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md index 4b2be683efc18..c746de3e733a2 100644 --- a/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md +++ b/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md @@ -32,15 +32,17 @@ The clusters are projected onto image planes, and then if the ROIs of clusters a ### Core Parameters -| Name | Type | Description | -| --------------------------- | ----- | ----------------------------------------------------------------------------- | -| `use_iou_x` | bool | calculate IoU only along x-axis | -| `use_iou_y` | bool | calculate IoU only along y-axis | -| `use_iou` | bool | calculate IoU both along x-axis and y-axis | -| `use_cluster_semantic_type` | bool | if `false`, the labels of clusters are overwritten by `UNKNOWN` before fusion | -| `iou_threshold` | float | the IoU threshold to overwrite a label of clusters with a label of roi | -| `rois_number` | int | the number of input rois | -| `debug_mode` | bool | If `true`, subscribe and publish images for visualization. | +| Name | Type | Description | +| --------------------------- | ----- | -------------------------------------------------------------------------------- | +| `use_iou_x` | bool | calculate IoU only along x-axis | +| `use_iou_y` | bool | calculate IoU only along y-axis | +| `use_iou` | bool | calculate IoU both along x-axis and y-axis | +| `use_cluster_semantic_type` | bool | if `false`, the labels of clusters are overwritten by `UNKNOWN` before fusion | +| `only_allow_inside_cluster` | bool | if `true`, the only clusters contained inside RoIs by a detector | +| `roi_scale_factor` | float | the scale factor for offset of detector RoIs if `only_allow_inside_cluster=true` | +| `iou_threshold` | float | the IoU threshold to overwrite a label of clusters with a label of roi | +| `rois_number` | int | the number of input rois | +| `debug_mode` | bool | If `true`, subscribe and publish images for visualization. | ## Assumptions / Known limits diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp index 5d6aba9b7d51d..b838de11bf7ec 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_cluster_fusion/node.hpp @@ -42,6 +42,8 @@ class RoiClusterFusionNode bool use_iou_y_{false}; bool use_iou_{false}; bool use_cluster_semantic_type_{false}; + bool only_allow_inside_cluster_{false}; + float roi_scale_factor_{1.1f}; float iou_threshold_{0.0f}; bool remove_unknown_; float trust_distance_; diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/geometry.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/geometry.hpp index 9d69410c69900..7ffac150a1e87 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/geometry.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/geometry.hpp @@ -60,6 +60,10 @@ void transformPoints( const std::vector & input_points, const Eigen::Affine3d & affine_transform, std::vector & output_points); +bool is_inside( + const sensor_msgs::msg::RegionOfInterest & outer, + const sensor_msgs::msg::RegionOfInterest & inner, const float outer_offset_scale = 1.1); + } // namespace image_projection_based_fusion #endif // IMAGE_PROJECTION_BASED_FUSION__UTILS__GEOMETRY_HPP_ diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index 2bf9af331ca45..a946da66f2488 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -74,6 +74,8 @@ + + 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 e15d47a01521c..af3dd15d98abc 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 @@ -40,6 +40,8 @@ RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options) use_iou_y_ = declare_parameter("use_iou_y", false); use_iou_ = declare_parameter("use_iou", false); use_cluster_semantic_type_ = declare_parameter("use_cluster_semantic_type", false); + only_allow_inside_cluster_ = declare_parameter("only_allow_inside_cluster_", false); + roi_scale_factor_ = declare_parameter("roi_scale_factor", 1.1); iou_threshold_ = declare_parameter("iou_threshold", 0.1); remove_unknown_ = declare_parameter("remove_unknown", false); trust_distance_ = declare_parameter("trust_distance", 100.0); @@ -177,7 +179,11 @@ void RoiClusterFusionNode::fuseOnSingleImage( if (use_iou_y_) { iou_y = calcIoUY(cluster_map.second, feature_obj.feature.roi); } - if (max_iou < iou + iou_x + iou_y) { + const bool passed_inside_cluster_gate = + only_allow_inside_cluster_ + ? is_inside(feature_obj.feature.roi, cluster_map.second, roi_scale_factor_) + : true; + if (max_iou < iou + iou_x + iou_y && passed_inside_cluster_gate) { index = cluster_map.first; max_iou = iou + iou_x + iou_y; } diff --git a/perception/image_projection_based_fusion/src/utils/geometry.cpp b/perception/image_projection_based_fusion/src/utils/geometry.cpp index dc35b754d0f01..9ea49256650ee 100644 --- a/perception/image_projection_based_fusion/src/utils/geometry.cpp +++ b/perception/image_projection_based_fusion/src/utils/geometry.cpp @@ -162,4 +162,15 @@ void transformPoints( } } +bool is_inside( + const sensor_msgs::msg::RegionOfInterest & outer, + const sensor_msgs::msg::RegionOfInterest & inner, const double outer_offset_scale) +{ + const double lower_scale = 1.0 - std::abs(outer_offset_scale - 1.0); + return outer.x_offset * lower_scale <= inner.x_offset && + outer.y_offset * lower_scale <= inner.y_offset && + inner.x_offset + inner.width <= (outer.x_offset + outer.width) * outer_offset_scale && + inner.y_offset + inner.height <= (outer.y_offset + outer.height) * outer_offset_scale; +} + } // namespace image_projection_based_fusion From 58b2044565203537eeb837c4f587558347befc4d Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Wed, 5 Jul 2023 18:15:05 +0900 Subject: [PATCH 090/118] feat(lane_change): update lane change object filter (#4172) * feat(lane_change): update lane change object filter Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka * update Signed-off-by: yutaka --------- Signed-off-by: yutaka --- .../src/scene_module/lane_change/normal.cpp | 2 +- .../src/utils/lane_change/utils.cpp | 11 ++++++++++- 2 files changed, 11 insertions(+), 2 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 41561493e08d6..361cb5548dc40 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 @@ -777,7 +777,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const // get lanes used for detection const auto backward_target_lanes_for_object_filtering = utils::lane_change::getBackwardLanelets( - route_handler, path.target_lanelets, current_pose, lane_change_parameters.backward_lane_length); + route_handler, target_lanes, current_pose, lane_change_parameters.backward_lane_length); const auto dynamic_object_indices = utils::lane_change::filterObject( *dynamic_objects, current_lanes, target_lanes, backward_target_lanes_for_object_filtering, 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 6d1b4486856e1..44b4275bfa2f0 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -1156,11 +1156,20 @@ LaneChangeTargetObjectIndices filterObject( } // check if the object intersects with current lanes - if (current_polygon && boost::geometry::intersects(current_polygon.value(), obj_polygon)) { + if ( + current_polygon && boost::geometry::intersects(current_polygon.value(), obj_polygon) && + max_dist_ego_to_obj >= 0.0) { + // check only the objects that are in front of the ego vehicle filtered_obj_indices.current_lane.push_back(i); continue; } + // ignore all objects that are behind the ego vehicle and not on the current and target + // lanes + if (max_dist_ego_to_obj < 0.0) { + continue; + } + filtered_obj_indices.other_lane.push_back(i); } From ddb6160d4bdc2b3e0c797bb9f0fae4c4ce72d572 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Wed, 5 Jul 2023 18:15:29 +0900 Subject: [PATCH 091/118] docs(traffic_light_arbiter): fix the datatype of input topics (#4156) docs(traffic_light_arbiter): fix the type of input topics Signed-off-by: Tomohito Ando --- perception/traffic_light_arbiter/README.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/perception/traffic_light_arbiter/README.md b/perception/traffic_light_arbiter/README.md index f90e24a2ebd1f..952119020c215 100644 --- a/perception/traffic_light_arbiter/README.md +++ b/perception/traffic_light_arbiter/README.md @@ -12,11 +12,11 @@ A node that merges traffic light/signal state from image recognition and externa #### Input -| Name | Type | Description | -| -------------------------------- | -------------------------------------------- | -------------------------------------------------------- | -| ~/sub/vector_map | autoware_auto_mapping_msgs::msg::HADMapBin | The vector map to get valid traffic signal ids. | -| ~/sub/perception_traffic_signals | autoware_perception_msgs::msg::TrafficSignal | The traffic signals from the image recognition pipeline. | -| ~/sub/external_traffic_signals | autoware_perception_msgs::msg::TrafficSignal | The traffic signals from an external system. | +| Name | Type | Description | +| -------------------------------- | ------------------------------------------------- | -------------------------------------------------------- | +| ~/sub/vector_map | autoware_auto_mapping_msgs::msg::HADMapBin | The vector map to get valid traffic signal ids. | +| ~/sub/perception_traffic_signals | autoware_perception_msgs::msg::TrafficSignalArray | The traffic signals from the image recognition pipeline. | +| ~/sub/external_traffic_signals | autoware_perception_msgs::msg::TrafficSignalArray | The traffic signals from an external system. | #### Output From 334cb04cdf2eac3001fec0cbca6a3123cc23adae Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 5 Jul 2023 18:43:55 +0900 Subject: [PATCH 092/118] fix(vehicle_cmd_gate): use the current state for filtering when stopped (#4174) Signed-off-by: Maxime CLEMENT --- control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index 25221c652e81d..42e54d20416d8 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -503,6 +503,11 @@ AckermannControlCommand VehicleCmdGate::filterControlCommand(const AckermannCont if (mode.is_in_transition) { filter_on_transition_.filterAll(dt, current_steer_, out); } else { + // When ego is stopped and the input command is not stopping, + // use the actual vehicle longitudinal state for the filtering + // this is to prevent the jerk limits being applied and causing + // a delay when restarting the vehicle. + if (ego_is_stopped && !input_cmd_is_stopping) filter_.setPrevCmd(current_status_cmd); filter_.filterAll(dt, current_steer_, out); } @@ -521,14 +526,6 @@ AckermannControlCommand VehicleCmdGate::filterControlCommand(const AckermannCont // filter in manual mode. prev_values.longitudinal = out.longitudinal; // TODO(Horibe): to be removed - // When ego is stopped and the input command is stopping, - // use the actual vehicle longitudinal state for the next filtering - // this is to prevent the jerk limits being applied on the "stop acceleration" - // which may be negative and cause delays when restarting the vehicle. - if (ego_is_stopped && input_cmd_is_stopping) { - prev_values.longitudinal = current_status_cmd.longitudinal; - } - filter_.setPrevCmd(prev_values); filter_on_transition_.setPrevCmd(prev_values); From dd6cd800f62d58fb03e1fc64ad0c2c81e77a0b58 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 5 Jul 2023 18:48:01 +0900 Subject: [PATCH 093/118] feat: rename traffic signal element (#4129) * feat(traffic_light_arbiter): rename traffic signal element Signed-off-by: Takagi, Isamu * feat(traffic_light_selector): remove traffic light selector Signed-off-by: Takagi, Isamu * fix(traffic_light_arbiter): fix node name Signed-off-by: Takagi, Isamu * update topic name Signed-off-by: Takagi, Isamu * update message type Signed-off-by: Takagi, Isamu * update message type Signed-off-by: Takagi, Isamu --------- Signed-off-by: Takagi, Isamu Co-authored-by: Kenzo Lobos Tsunekawa --- .../include/traffic_light_arbiter/traffic_light_arbiter.hpp | 3 +-- .../launch/traffic_light_arbiter.launch.xml | 2 +- .../traffic_light_arbiter/src/traffic_light_arbiter.cpp | 2 +- perception/traffic_light_multi_camera_fusion/src/node.cpp | 4 ++-- .../src/traffic_light_map_visualizer/node.cpp | 6 +++--- 5 files changed, 8 insertions(+), 9 deletions(-) diff --git a/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp b/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp index eb7a13088b2c6..afb5984c288fc 100644 --- a/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp +++ b/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp @@ -18,7 +18,6 @@ #include #include -#include #include #include @@ -31,7 +30,7 @@ class TrafficLightArbiter : public rclcpp::Node explicit TrafficLightArbiter(const rclcpp::NodeOptions & options); private: - using Element = autoware_perception_msgs::msg::TrafficLightElement; + using Element = autoware_perception_msgs::msg::TrafficSignalElement; using LaneletMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; using TrafficSignalArray = autoware_perception_msgs::msg::TrafficSignalArray; using TrafficSignal = autoware_perception_msgs::msg::TrafficSignal; diff --git a/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml b/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml index 9e261981d4096..42944450378d6 100644 --- a/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml +++ b/perception/traffic_light_arbiter/launch/traffic_light_arbiter.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp b/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp index fac3bc1092615..eb940fc18c32d 100644 --- a/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp +++ b/perception/traffic_light_arbiter/src/traffic_light_arbiter.cpp @@ -45,7 +45,7 @@ std::vector filter_traffic_signals(const LaneletMapConstPt } // namespace lanelet TrafficLightArbiter::TrafficLightArbiter(const rclcpp::NodeOptions & options) -: Node("traffic_light_selector", options) +: Node("traffic_light_arbiter", options) { external_time_tolerance_ = this->declare_parameter("external_time_tolerance", 5.0); perception_time_tolerance_ = this->declare_parameter("perception_time_tolerance", 1.0); diff --git a/perception/traffic_light_multi_camera_fusion/src/node.cpp b/perception/traffic_light_multi_camera_fusion/src/node.cpp index 7500193a3b643..d7e82af4af079 100644 --- a/perception/traffic_light_multi_camera_fusion/src/node.cpp +++ b/perception/traffic_light_multi_camera_fusion/src/node.cpp @@ -97,11 +97,11 @@ V at_or(const std::unordered_map & map, const K & key, const V & value) return map.count(key) ? map.at(key) : value; } -autoware_perception_msgs::msg::TrafficLightElement convert( +autoware_perception_msgs::msg::TrafficSignalElement convert( const tier4_perception_msgs::msg::TrafficLightElement & input) { typedef tier4_perception_msgs::msg::TrafficLightElement OldElem; - typedef autoware_perception_msgs::msg::TrafficLightElement NewElem; + typedef autoware_perception_msgs::msg::TrafficSignalElement NewElem; static const std::unordered_map color_map( {{OldElem::RED, NewElem::RED}, {OldElem::AMBER, NewElem::AMBER}, diff --git a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp index ced36476e00ef..a9d107e78a1c4 100644 --- a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp +++ b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp @@ -167,18 +167,18 @@ void TrafficLightMapVisualizerNode::trafficSignalsCallback( visualization_msgs::msg::Marker marker; if ( isAttributeValue(pt, "color", "red") && - elem.color == autoware_perception_msgs::msg::TrafficLightElement::RED) { + elem.color == autoware_perception_msgs::msg::TrafficSignalElement::RED) { lightAsMarker( get_node_logging_interface(), pt, &marker, "traffic_light", current_time); } else if ( // NOLINT isAttributeValue(pt, "color", "green") && - elem.color == autoware_perception_msgs::msg::TrafficLightElement::GREEN) { + elem.color == autoware_perception_msgs::msg::TrafficSignalElement::GREEN) { lightAsMarker( get_node_logging_interface(), pt, &marker, "traffic_light", current_time); } else if ( // NOLINT isAttributeValue(pt, "color", "yellow") && - elem.color == autoware_perception_msgs::msg::TrafficLightElement::AMBER) { + elem.color == autoware_perception_msgs::msg::TrafficSignalElement::AMBER) { lightAsMarker( get_node_logging_interface(), pt, &marker, "traffic_light", current_time); } else { From e95909d21e2b7ff0cf19585baeca0187c0f638c1 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 5 Jul 2023 18:57:34 +0900 Subject: [PATCH 094/118] feat(avoidance): improve avoidance stop & decel behavior (#4141) * feat(path_shifter): add utils Signed-off-by: satoshi-ota * feat(avoidance): shorten avoidance stop distance Signed-off-by: satoshi-ota * feat(avoidance): insert slow down speed Signed-off-by: satoshi-ota * fix(avoidance): don't set stoppable=true for objects that ego doesn't have to avoid Signed-off-by: satoshi-ota * refactor(avoidance): rename unreadable variable name Signed-off-by: satoshi-ota * docs(avoidance): add new parameter description Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 3 + .../behavior_path_planner_avoidance_design.md | 19 +++-- .../utils/avoidance/avoidance_module_data.hpp | 9 +++ .../utils/avoidance/helper.hpp | 9 +-- .../utils/path_shifter/path_shifter.hpp | 3 + .../src/marker_util/avoidance/debug.cpp | 6 +- .../avoidance/avoidance_module.cpp | 80 ++++++++++++++----- .../src/scene_module/avoidance/manager.cpp | 6 ++ .../src/utils/avoidance/utils.cpp | 40 ++++++---- .../src/utils/path_shifter/path_shifter.cpp | 12 +++ 10 files changed, 133 insertions(+), 54 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 7c785efa0d5a9..d5f908ae9856f 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -144,6 +144,8 @@ min_avoidance_distance: 10.0 # [m] min_nominal_avoidance_speed: 7.0 # [m/s] min_sharp_avoidance_speed: 1.0 # [m/s] + min_slow_down_speed: 1.38 # [m/s] + buf_slow_down_speed: 0.56 # [m/s] # For yield maneuver yield: @@ -153,6 +155,7 @@ stop: min_distance: 10.0 # [m] max_distance: 20.0 # [m] + stop_buffer: 1.0 # [m] constraints: # vehicle slows down under longitudinal constraints diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md index b290a1efa90da..e1de6b5a59314 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md @@ -677,14 +677,16 @@ namespace: `avoidance.avoidance.lateral.` namespace: `avoidance.avoidance.longitudinal.` -| Name | Unit | Type | Description | Default value | -| :----------------------------------- | :---- | :----- | :----------------------------------------------------------------------------------------------------- | :------------ | -| prepare_time | [s] | double | Avoidance shift starts from point ahead of this time x ego_speed to avoid sudden path change. | 2.0 | -| longitudinal_collision_safety_buffer | [s] | double | Longitudinal collision buffer between target object and shift line. | 0.0 | -| min_prepare_distance | [m] | double | Minimum distance for "prepare_time" x "ego_speed". | 1.0 | -| min_avoidance_distance | [m] | double | Minimum distance of avoidance path (i.e. this distance is needed even if its lateral jerk is very low) | 10.0 | -| min_nominal_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a nominal situation (\*1). | 7.0 | -| min_sharp_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a sharp situation (\*1). | 1.0 | +| Name | Unit | Type | Description | Default value | +| :----------------------------------- | :---- | :----- | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------- | +| prepare_time | [s] | double | Avoidance shift starts from point ahead of this time x ego_speed to avoid sudden path change. | 2.0 | +| longitudinal_collision_safety_buffer | [s] | double | Longitudinal collision buffer between target object and shift line. | 0.0 | +| min_prepare_distance | [m] | double | Minimum distance for "prepare_time" x "ego_speed". | 1.0 | +| min_avoidance_distance | [m] | double | Minimum distance of avoidance path (i.e. this distance is needed even if its lateral jerk is very low) | 10.0 | +| min_nominal_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a nominal situation (\*1). | 7.0 | +| min_sharp_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a sharp situation (\*1). | 1.0 | +| min_slow_down_speed | [m/s] | double | Minimum slow speed for avoidance prepare section. | 1.38 (5km/h) | +| buf_slow_down_speed | [m/s] | double | Buffer for controller tracking error. Basically, vehicle always cannot follow velocity profile precisely. Therefore, the module inserts lower speed than target speed that satisfies conditions to avoid object within accel/jerk constraints so that the avoidance path always can be output even if the current speed is a little bit higher than target speed. | 0.57 (2.0km/h) | ### Yield maneuver parameters @@ -702,6 +704,7 @@ namespace: `avoidance.stop.` | :----------- | :--- | :----- | :---------------------------------------------------------------------------------------------------- | :------------ | | min_distance | [m] | double | Minimum stop distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 10.0 | | max_distance | [m] | double | Maximum stop distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 20.0 | +| stop_buffer | [m] | double | Buffer distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 1.0 | ### Constraints parameters 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 0b016db9c9c2c..2485dee6128b0 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 @@ -196,6 +196,9 @@ struct AvoidanceParameters // maximum stop distance double stop_max_distance; + // stop buffer + double stop_buffer; + // start avoidance after this time to avoid sudden path change double prepare_time; @@ -216,6 +219,12 @@ struct AvoidanceParameters // distance for avoidance. Need a sharp avoidance path to avoid the object. double min_sharp_avoidance_speed; + // minimum slow down speed + double min_slow_down_speed; + + // slow down speed buffer + double buf_slow_down_speed; + // The margin is configured so that the generated avoidance trajectory does not come near to the // road shoulder. double road_shoulder_safety_margin{1.0}; 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 194c62aaeec5a..a756c9518825d 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 @@ -74,13 +74,6 @@ class AvoidanceHelper return std::max(getEgoSpeed(), parameters_->min_sharp_avoidance_speed); } - float getMaximumAvoidanceEgoSpeed() const - { - return parameters_->target_velocity_matrix.at(parameters_->col_size - 1); - } - - float getMinimumAvoidanceEgoSpeed() const { return parameters_->target_velocity_matrix.front(); } - double getNominalPrepareDistance() const { const auto & p = parameters_; @@ -103,7 +96,7 @@ class AvoidanceHelper { const auto & p = parameters_; const auto distance_by_jerk = PathShifter::calcLongitudinalDistFromJerk( - shift_length, p->nominal_lateral_jerk, getMinimumAvoidanceEgoSpeed()); + shift_length, p->max_lateral_jerk, p->min_sharp_avoidance_speed); return std::max(p->min_avoidance_distance, distance_by_jerk); } 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 76119a18646ab..93c3a4a768c0b 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 @@ -136,6 +136,9 @@ class PathShifter // Utility Functions //////////////////////////////////////// + static double calcFeasibleVelocityFromJerk( + const double lateral, const double jerk, const double distance); + static double calcLongitudinalDistFromJerk( const double lateral, const double jerk, const double velocity); diff --git a/planning/behavior_path_planner/src/marker_util/avoidance/debug.cpp b/planning/behavior_path_planner/src/marker_util/avoidance/debug.cpp index 10fcec3d8a324..0235bbb57f464 100644 --- a/planning/behavior_path_planner/src/marker_util/avoidance/debug.cpp +++ b/planning/behavior_path_planner/src/marker_util/avoidance/debug.cpp @@ -120,9 +120,11 @@ MarkerArray createObjectInfoMarkerArray(const ObjectDataArray & objects, std::st marker.id = uuidToInt32(object.object.object_id); marker.pose = object.object.kinematics.initial_pose_with_covariance.pose; std::ostringstream string_stream; - string_stream << std::fixed << std::setprecision(2); + string_stream << std::fixed << std::setprecision(2) << std::boolalpha; string_stream << "ratio:" << object.shiftable_ratio << " [-]\n" - << "lateral: " << object.lateral << " [-]\n" + << "lateral:" << object.lateral << " [m]\n" + << "necessity:" << object.avoid_required << " [-]\n" + << "stoppable:" << object.is_stoppable << " [-]\n" << "stop_factor:" << object.to_stop_factor_distance << " [m]\n" << "move_time:" << object.move_time << " [s]\n" << "stop_time:" << object.stop_time << " [s]\n"; 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 587afb1fdee57..8b729e4fd8835 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 @@ -343,8 +343,8 @@ ObjectData AvoidanceModule::createObjectData( const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; const auto object_closest_index = findNearestIndex(path_points, object_pose.position); const auto object_closest_pose = path_points.at(object_closest_index).point.pose; - const auto t = utils::getHighestProbLabel(object.classification); - const auto object_parameter = parameters_->object_parameters.at(t); + const auto object_type = utils::getHighestProbLabel(object.classification); + const auto object_parameter = parameters_->object_parameters.at(object_type); ObjectData object_data{}; @@ -571,8 +571,8 @@ void AvoidanceModule::fillDebugData(const AvoidancePlanningData & data, DebugDat } const auto o_front = data.stop_target_object.get(); - const auto t = utils::getHighestProbLabel(o_front.object.classification); - const auto object_parameter = parameters_->object_parameters.at(t); + 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 & vehicle_width = planner_data_->parameters.vehicle_width; @@ -620,6 +620,8 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif return; } + insertPrepareVelocity(path); + switch (data.state) { case AvoidanceState::NOT_AVOID: { break; @@ -631,7 +633,6 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif break; } case AvoidanceState::AVOID_PATH_NOT_READY: { - insertPrepareVelocity(path); insertWaitPoint(parameters_->use_constraints_for_decel, path); break; } @@ -860,8 +861,8 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( const auto nominal_return_distance = helper_.getNominalAvoidanceDistance(return_shift); // use each object param - const auto t = utils::getHighestProbLabel(o.object.classification); - const auto object_parameter = parameters_->object_parameters.at(t); + const auto object_type = utils::getHighestProbLabel(o.object.classification); + const auto object_parameter = parameters_->object_parameters.at(object_type); /** * Is there enough distance from ego to object for avoidance? @@ -3231,15 +3232,15 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const // D4: o_front.longitudinal // D5: base_link2front - const auto t = utils::getHighestProbLabel(object.object.classification); - const auto object_parameter = parameters_->object_parameters.at(t); + const auto object_type = utils::getHighestProbLabel(object.object.classification); + const auto object_parameter = parameters_->object_parameters.at(object_type); const auto avoid_margin = object_parameter.safety_buffer_lateral * object.distance_factor + object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; const auto variable = helper_.getMinimumAvoidanceDistance( helper_.getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin)); - const auto constant = - p->min_prepare_distance + object_parameter.safety_buffer_longitudinal + base_link2front; + const auto constant = p->min_prepare_distance + object_parameter.safety_buffer_longitudinal + + base_link2front + p->stop_buffer; return object.longitudinal - std::clamp(variable + constant, p->stop_min_distance, p->stop_max_distance); @@ -3350,23 +3351,64 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const { const auto & data = avoidance_data_; + // do nothing if there is no avoidance target. if (data.target_objects.empty()) { return; } - if (!!data.stop_target_object) { - if (data.stop_target_object.get().reason != AvoidanceDebugFactor::TOO_LARGE_JERK) { - return; - } + // insert slow down speed only when the avoidance maneuver is not initiated. + if (data.avoiding_now) { + return; } - if (data.avoiding_now) { + // insert slow down speed only when no shift line is approved. + if (!path_shifter_.getShiftLines().empty()) { return; } - const auto decel_distance = helper_.getFeasibleDecelDistance(0.0); - utils::avoidance::insertDecelPoint( - getEgoPosition(), decel_distance, 0.0, shifted_path.path, slow_pose_); + const auto object = data.target_objects.front(); + + // calculate shift length for front object. + const auto & vehicle_width = planner_data_->parameters.vehicle_width; + const auto object_type = utils::getHighestProbLabel(object.object.classification); + const auto object_parameter = parameters_->object_parameters.at(object_type); + const auto avoid_margin = object_parameter.safety_buffer_lateral * object.distance_factor + + object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; + const auto shift_length = + helper_.getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin); + + // check slow down feasibility + const auto min_avoid_distance = helper_.getMinimumAvoidanceDistance(shift_length); + const auto distance_to_object = object.longitudinal; + const auto remaining_distance = distance_to_object - min_avoid_distance; + const auto decel_distance = + helper_.getFeasibleDecelDistance(parameters_->min_sharp_avoidance_speed); + if (remaining_distance < decel_distance) { + return; + } + + // decide slow down lower limit. + const auto lower_speed = object.avoid_required ? 0.0 : parameters_->min_slow_down_speed; + + // insert slow down speed. + const auto start_idx = planner_data_->findEgoIndex(shifted_path.path.points); + for (size_t i = start_idx; i < shifted_path.path.points.size(); ++i) { + const auto distance_from_ego = calcSignedArcLength(shifted_path.path.points, start_idx, i); + + // slow down speed is inserted only in front of the object. + const auto shift_longitudinal_distance = distance_to_object - distance_from_ego; + if (shift_longitudinal_distance < min_avoid_distance) { + break; + } + + // target speed with nominal jerk limits. + const double v_target = PathShifter::calcFeasibleVelocityFromJerk( + shift_length, parameters_->nominal_lateral_jerk, shift_longitudinal_distance); + const double v_original = shifted_path.path.points.at(i).point.longitudinal_velocity_mps; + const double v_insert = std::max(v_target - parameters_->buf_slow_down_speed, lower_speed); + + shifted_path.path.points.at(i).point.longitudinal_velocity_mps = std::min(v_original, v_insert); + } } std::shared_ptr AvoidanceModule::get_debug_msg_array() const 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 f9a652a4cec27..55b06fd66fa87 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -163,6 +163,8 @@ AvoidanceModuleManager::AvoidanceModuleManager( p.min_avoidance_distance = get_parameter(node, ns + "min_avoidance_distance"); p.min_nominal_avoidance_speed = get_parameter(node, ns + "min_nominal_avoidance_speed"); p.min_sharp_avoidance_speed = get_parameter(node, ns + "min_sharp_avoidance_speed"); + p.min_slow_down_speed = get_parameter(node, ns + "min_slow_down_speed"); + p.buf_slow_down_speed = get_parameter(node, ns + "buf_slow_down_speed"); } // yield @@ -176,6 +178,7 @@ AvoidanceModuleManager::AvoidanceModuleManager( std::string ns = "avoidance.stop."; p.stop_min_distance = get_parameter(node, ns + "min_distance"); p.stop_max_distance = get_parameter(node, ns + "max_distance"); + p.stop_buffer = get_parameter(node, ns + "stop_buffer"); } // constraints @@ -288,12 +291,15 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "prepare_time", p->prepare_time); + updateParam(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed); + updateParam(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed); } { const std::string ns = "avoidance.stop."; updateParam(parameters, ns + "max_distance", p->stop_max_distance); updateParam(parameters, ns + "min_distance", p->stop_min_distance); + updateParam(parameters, ns + "stop_buffer", p->stop_buffer); } { diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 5fd1457042693..d92adaae62c97 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -101,28 +101,28 @@ bool isOnRight(const ObjectData & obj) bool isTargetObjectType( const PredictedObject & object, const std::shared_ptr & parameters) { - const auto t = utils::getHighestProbLabel(object.classification); + const auto object_type = utils::getHighestProbLabel(object.classification); - if (parameters->object_parameters.count(t) == 0) { + if (parameters->object_parameters.count(object_type) == 0) { return false; } - return parameters->object_parameters.at(t).is_target; + return parameters->object_parameters.at(object_type).is_target; } bool isVehicleTypeObject(const ObjectData & object) { - const auto t = utils::getHighestProbLabel(object.object.classification); + const auto object_type = utils::getHighestProbLabel(object.object.classification); - if (t == ObjectClassification::UNKNOWN) { + if (object_type == ObjectClassification::UNKNOWN) { return false; } - if (t == ObjectClassification::PEDESTRIAN) { + if (object_type == ObjectClassification::PEDESTRIAN) { return false; } - if (t == ObjectClassification::BICYCLE) { + if (object_type == ObjectClassification::BICYCLE) { return false; } @@ -422,8 +422,8 @@ std::vector generateObstaclePolygonsForDrivableArea( continue; } - const auto t = utils::getHighestProbLabel(object.object.classification); - const auto object_parameter = parameters->object_parameters.at(t); + const auto object_type = utils::getHighestProbLabel(object.object.classification); + const auto object_parameter = parameters->object_parameters.at(object_type); // generate obstacle polygon const double diff_poly_buffer = @@ -535,8 +535,8 @@ void fillObjectEnvelopePolygon( { using boost::geometry::within; - const auto t = utils::getHighestProbLabel(object_data.object.classification); - const auto object_parameter = parameters->object_parameters.at(t); + const auto object_type = utils::getHighestProbLabel(object_data.object.classification); + const auto object_parameter = parameters->object_parameters.at(object_type); const auto & envelope_buffer_margin = object_parameter.envelope_buffer_margin * object_data.distance_factor; @@ -567,8 +567,8 @@ void fillObjectMovingTime( ObjectData & object_data, ObjectDataArray & stopped_objects, const std::shared_ptr & parameters) { - const auto t = utils::getHighestProbLabel(object_data.object.classification); - const auto object_parameter = parameters->object_parameters.at(t); + const auto object_type = utils::getHighestProbLabel(object_data.object.classification); + const auto object_parameter = parameters->object_parameters.at(object_type); const auto & object_vel = object_data.object.kinematics.initial_twist_with_covariance.twist.linear.x; @@ -618,8 +618,8 @@ void fillAvoidanceNecessity( ObjectData & object_data, const ObjectDataArray & registered_objects, const double vehicle_width, const std::shared_ptr & parameters) { - const auto t = utils::getHighestProbLabel(object_data.object.classification); - const auto object_parameter = parameters->object_parameters.at(t); + const auto object_type = utils::getHighestProbLabel(object_data.object.classification); + const auto object_parameter = parameters->object_parameters.at(object_type); const auto safety_margin = 0.5 * vehicle_width + object_parameter.safety_buffer_lateral * object_data.distance_factor; @@ -657,6 +657,12 @@ void fillObjectStoppableJudge( { if (!parameters->use_constraints_for_decel) { object_data.is_stoppable = true; + return; + } + + if (!object_data.avoid_required) { + object_data.is_stoppable = false; + return; } const auto id = object_data.object.object_id; @@ -796,8 +802,8 @@ void filterTargetObjects( const auto object_closest_index = findNearestIndex(path_points, object_pose.position); const auto object_closest_pose = path_points.at(object_closest_index).point.pose; - const auto t = utils::getHighestProbLabel(o.object.classification); - const auto object_parameter = parameters->object_parameters.at(t); + const auto object_type = utils::getHighestProbLabel(o.object.classification); + const auto object_parameter = parameters->object_parameters.at(object_type); if (!isTargetObjectType(o.object, parameters)) { o.reason = AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE; 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 c1058969434d9..eb752220d3690 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 @@ -554,6 +554,18 @@ double PathShifter::calcShiftTimeFromJerk(const double lateral, const double jer return t_total; } +double PathShifter::calcFeasibleVelocityFromJerk( + const double lateral, const double jerk, const double distance) +{ + const double j = std::abs(jerk); + const double l = std::abs(lateral); + const double d = std::abs(distance); + if (j < 1.0e-8) { + return 1.0e10; // TODO(Horibe) maybe invalid arg? + } + return d / (4.0 * std::pow(0.5 * l / j, 1.0 / 3.0)); +} + double PathShifter::calcLongitudinalDistFromJerk( const double lateral, const double jerk, const double velocity) { From c9280db0f945217d9f95e49d2f76ee4adab1fdac Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 5 Jul 2023 19:10:59 +0900 Subject: [PATCH 095/118] fix(avoidance): don't output new candidate path if there is huge offset between the ego and previous output path (#4150) * fix(avoidance): don't output new candidate path if there is huge offset between the ego and previous output path Signed-off-by: satoshi-ota * docs(avoidance): add parameter description Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 1 + .../behavior_path_planner_avoidance_design.md | 15 ++++++++------- .../utils/avoidance/avoidance_module_data.hpp | 3 +++ .../scene_module/avoidance/avoidance_module.cpp | 15 +++++++++++++++ .../src/scene_module/avoidance/manager.cpp | 1 + 5 files changed, 28 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index d5f908ae9856f..f73520e8d7c40 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -127,6 +127,7 @@ safety_check_idling_time: 1.5 # [s] safety_check_accel_for_rss: 2.5 # [m/ss] safety_check_hysteresis_factor: 2.0 # [-] + safety_check_ego_offset: 1.0 # [m] # For avoidance maneuver avoidance: diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md index e1de6b5a59314..33ff0db7cc150 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md @@ -655,13 +655,14 @@ namespace: `avoidance.target_filtering.` namespace: `avoidance.safety_check.` -| Name | Unit | Type | Description | Default value | -| :----------------------------- | ------ | ------ | --------------------------------------------------------------------------------- | ------------- | -| safety_check_backward_distance | [m] | double | Backward distance to search the dynamic objects. | 50.0 | -| safety_check_time_horizon | [s] | double | Time horizon to check lateral/longitudinal margin is enough or not. | 10.0 | -| safety_check_idling_time | [t] | double | Time delay constant that be use for longitudinal margin calculation based on RSS. | 1.5 | -| safety_check_accel_for_rss | [m/ss] | double | Accel constant that be used for longitudinal margin calculation based on RSS. | 2.5 | -| safety_check_hysteresis_factor | [-] | double | Hysteresis factor that be used for chattering prevention. | 2.0 | +| Name | Unit | Type | Description | Default value | +| :----------------------------- | ------ | ------ | ---------------------------------------------------------------------------------------------------------- | ------------- | +| safety_check_backward_distance | [m] | double | Backward distance to search the dynamic objects. | 50.0 | +| safety_check_time_horizon | [s] | double | Time horizon to check lateral/longitudinal margin is enough or not. | 10.0 | +| safety_check_idling_time | [t] | double | Time delay constant that be use for longitudinal margin calculation based on RSS. | 1.5 | +| safety_check_accel_for_rss | [m/ss] | double | Accel constant that be used for longitudinal margin calculation based on RSS. | 2.5 | +| safety_check_hysteresis_factor | [-] | double | Hysteresis factor that be used for chattering prevention. | 2.0 | +| safety_check_ego_offset | [m] | double | Output new avoidance path **only when** the offset between ego and previous output path is less than this. | 1.0 | ### Avoidance maneuver parameters 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 2485dee6128b0..63166b0cbf7df 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 @@ -187,6 +187,9 @@ struct AvoidanceParameters // transit hysteresis (unsafe to safe) double safety_check_hysteresis_factor; + // don't output new candidate path if the offset between ego and path is larger than this. + double safety_check_ego_offset; + // keep target velocity in yield maneuver double yield_velocity; 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 8b729e4fd8835..6cf187268e4ca 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 @@ -494,6 +494,21 @@ void AvoidanceModule::fillEgoStatus( const auto can_yield_maneuver = canYieldManeuver(data); + const size_t ego_seg_idx = + planner_data_->findEgoSegmentIndex(helper_.getPreviousSplineShiftPath().path.points); + const auto offset = std::abs(motion_utils::calcLateralOffset( + helper_.getPreviousSplineShiftPath().path.points, getEgoPosition(), ego_seg_idx)); + + // don't output new candidate path if the offset between the ego and previous output path is + // larger than threshold. + // TODO(Satoshi OTA): remove this workaround + if (offset > parameters_->safety_check_ego_offset) { + data.safe_new_sl.clear(); + data.candidate_path = helper_.getPreviousSplineShiftPath(); + RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "unsafe. canceling candidate path..."); + return; + } + /** * If the avoidance path is safe, use unapproved_new_sl for avoidance path generation. */ 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 55b06fd66fa87..9b7a8b68b969d 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -142,6 +142,7 @@ AvoidanceModuleManager::AvoidanceModuleManager( p.safety_check_accel_for_rss = get_parameter(node, ns + "safety_check_accel_for_rss"); p.safety_check_hysteresis_factor = get_parameter(node, ns + "safety_check_hysteresis_factor"); + p.safety_check_ego_offset = get_parameter(node, ns + "safety_check_ego_offset"); } // avoidance maneuver (lateral) From af4ce27ed0779af11dd849202b7d8d965d81e0ea Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 6 Jul 2023 04:17:50 +0900 Subject: [PATCH 096/118] feat(map_height_fitter): add service node (#4128) * add map height fitter node Signed-off-by: Takagi, Isamu * fix response success Signed-off-by: Takagi, Isamu --------- Signed-off-by: Takagi, Isamu --- .../src/pose_initializer/gnss_module.cpp | 9 ++- map/map_height_fitter/CMakeLists.txt | 6 +- .../map_height_fitter/map_height_fitter.hpp | 3 +- .../launch/map_height_fitter.launch.xml | 10 ++++ map/map_height_fitter/package.xml | 1 + .../src/map_height_fitter.cpp | 52 +++++++++-------- map/map_height_fitter/src/node.cpp | 58 +++++++++++++++++++ .../src/initial_pose_adaptor.cpp | 9 +-- 8 files changed, 116 insertions(+), 32 deletions(-) create mode 100644 map/map_height_fitter/launch/map_height_fitter.launch.xml create mode 100644 map/map_height_fitter/src/node.cpp diff --git a/localization/pose_initializer/src/pose_initializer/gnss_module.cpp b/localization/pose_initializer/src/pose_initializer/gnss_module.cpp index 7e87c43de83da..e8762c8c6f493 100644 --- a/localization/pose_initializer/src/pose_initializer/gnss_module.cpp +++ b/localization/pose_initializer/src/pose_initializer/gnss_module.cpp @@ -43,7 +43,10 @@ geometry_msgs::msg::PoseWithCovarianceStamped GnssModule::get_pose() Initialize::Service::Response::ERROR_GNSS, "The GNSS pose is out of date."); } - auto result = *pose_; - result.pose.pose.position = fitter_.fit(result.pose.pose.position, result.header.frame_id); - return result; + PoseWithCovarianceStamped pose = *pose_; + const auto fitted = fitter_.fit(pose.pose.pose.position, pose.header.frame_id); + if (fitted) { + pose.pose.pose.position = fitted.value(); + } + return pose; } diff --git a/map/map_height_fitter/CMakeLists.txt b/map/map_height_fitter/CMakeLists.txt index ddab6db192aaa..fb5b3feac6418 100644 --- a/map/map_height_fitter/CMakeLists.txt +++ b/map/map_height_fitter/CMakeLists.txt @@ -10,4 +10,8 @@ ament_auto_add_library(map_height_fitter SHARED ) target_link_libraries(map_height_fitter ${PCL_LIBRARIES}) -ament_auto_package() +ament_auto_add_executable(node + src/node.cpp +) + +ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/map/map_height_fitter/include/map_height_fitter/map_height_fitter.hpp b/map/map_height_fitter/include/map_height_fitter/map_height_fitter.hpp index c5056073c82cb..95ca3f3dfbea0 100644 --- a/map/map_height_fitter/include/map_height_fitter/map_height_fitter.hpp +++ b/map/map_height_fitter/include/map_height_fitter/map_height_fitter.hpp @@ -20,6 +20,7 @@ #include #include +#include #include namespace map_height_fitter @@ -32,7 +33,7 @@ class MapHeightFitter final public: MapHeightFitter(rclcpp::Node * node); ~MapHeightFitter(); - Point fit(const Point & position, const std::string & frame); + std::optional fit(const Point & position, const std::string & frame); private: struct Impl; diff --git a/map/map_height_fitter/launch/map_height_fitter.launch.xml b/map/map_height_fitter/launch/map_height_fitter.launch.xml new file mode 100644 index 0000000000000..2edbdb831590d --- /dev/null +++ b/map/map_height_fitter/launch/map_height_fitter.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/map/map_height_fitter/package.xml b/map/map_height_fitter/package.xml index ab4f5ce205385..b288da6aca2cb 100644 --- a/map/map_height_fitter/package.xml +++ b/map/map_height_fitter/package.xml @@ -21,6 +21,7 @@ tf2 tf2_geometry_msgs tf2_ros + tier4_localization_msgs ament_lint_auto autoware_lint_common diff --git a/map/map_height_fitter/src/map_height_fitter.cpp b/map/map_height_fitter/src/map_height_fitter.cpp index 5fb0243d1042a..1eb1edd04a68a 100644 --- a/map/map_height_fitter/src/map_height_fitter.cpp +++ b/map/map_height_fitter/src/map_height_fitter.cpp @@ -32,9 +32,9 @@ struct MapHeightFitter::Impl explicit Impl(rclcpp::Node * node); void on_map(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); - void get_partial_point_cloud_map(const Point & point); + bool get_partial_point_cloud_map(const Point & point); double get_ground_height(const tf2::Vector3 & point) const; - Point fit(const Point & position, const std::string & frame); + std::optional fit(const Point & position, const std::string & frame); tf2::BufferCore tf2_buffer_; tf2_ros::TransformListener tf2_listener_; @@ -83,17 +83,17 @@ void MapHeightFitter::Impl::on_map(const sensor_msgs::msg::PointCloud2::ConstSha pcl::fromROSMsg(*msg, *map_cloud_); } -void MapHeightFitter::Impl::get_partial_point_cloud_map(const Point & point) +bool MapHeightFitter::Impl::get_partial_point_cloud_map(const Point & point) { const auto logger = node_->get_logger(); if (!cli_map_) { RCLCPP_WARN_STREAM(logger, "Partial map loading in pointcloud_map_loader is not enabled"); - return; + return false; } if (!cli_map_->service_is_ready()) { RCLCPP_WARN_STREAM(logger, "Partial map loading in pointcloud_map_loader is not ready"); - return; + return false; } const auto req = std::make_shared(); @@ -107,7 +107,7 @@ void MapHeightFitter::Impl::get_partial_point_cloud_map(const Point & point) while (status != std::future_status::ready) { RCLCPP_INFO(logger, "waiting response"); if (!rclcpp::ok()) { - return; + return false; } status = future.wait_for(std::chrono::seconds(1)); } @@ -131,6 +131,7 @@ void MapHeightFitter::Impl::get_partial_point_cloud_map(const Point & point) map_frame_ = res->header.frame_id; map_cloud_ = pcl::PointCloud::Ptr(new pcl::PointCloud); pcl::fromROSMsg(pcd_msg, *map_cloud_); + return true; } double MapHeightFitter::Impl::get_ground_height(const tf2::Vector3 & point) const @@ -162,32 +163,37 @@ double MapHeightFitter::Impl::get_ground_height(const tf2::Vector3 & point) cons return std::isfinite(height) ? height : point.getZ(); } -Point MapHeightFitter::Impl::fit(const Point & position, const std::string & frame) +std::optional MapHeightFitter::Impl::fit(const Point & position, const std::string & frame) { const auto logger = node_->get_logger(); tf2::Vector3 point(position.x, position.y, position.z); - RCLCPP_INFO(logger, "map fit1: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ()); + RCLCPP_INFO(logger, "original point: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ()); if (cli_map_) { - map_cloud_.reset(); - get_partial_point_cloud_map(position); + if (!get_partial_point_cloud_map(position)) { + return std::nullopt; + } } - if (map_cloud_) { - try { - const auto stamped = tf2_buffer_.lookupTransform(map_frame_, frame, tf2::TimePointZero); - tf2::Transform transform{tf2::Quaternion{}, tf2::Vector3{}}; - tf2::fromMsg(stamped.transform, transform); - point = transform * point; - point.setZ(get_ground_height(point)); - point = transform.inverse() * point; - } catch (tf2::TransformException & exception) { - RCLCPP_WARN_STREAM(logger, "failed to lookup transform: " << exception.what()); - } + if (!map_cloud_) { + RCLCPP_WARN_STREAM(logger, "point cloud map is not ready"); + return std::nullopt; + } + + try { + const auto stamped = tf2_buffer_.lookupTransform(map_frame_, frame, tf2::TimePointZero); + tf2::Transform transform{tf2::Quaternion{}, tf2::Vector3{}}; + tf2::fromMsg(stamped.transform, transform); + point = transform * point; + point.setZ(get_ground_height(point)); + point = transform.inverse() * point; + } catch (tf2::TransformException & exception) { + RCLCPP_WARN_STREAM(logger, "failed to lookup transform: " << exception.what()); + return std::nullopt; } - RCLCPP_INFO(logger, "map fit2: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ()); + RCLCPP_INFO(logger, "modified point: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ()); Point result; result.x = point.getX(); @@ -205,7 +211,7 @@ MapHeightFitter::~MapHeightFitter() { } -Point MapHeightFitter::fit(const Point & position, const std::string & frame) +std::optional MapHeightFitter::fit(const Point & position, const std::string & frame) { return impl_->fit(position, frame); } diff --git a/map/map_height_fitter/src/node.cpp b/map/map_height_fitter/src/node.cpp new file mode 100644 index 0000000000000..55702dc08450d --- /dev/null +++ b/map/map_height_fitter/src/node.cpp @@ -0,0 +1,58 @@ +// 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 "map_height_fitter/map_height_fitter.hpp" + +#include + +#include + +using tier4_localization_msgs::srv::PoseWithCovarianceStamped; + +class MapHeightFitterNode : public rclcpp::Node +{ +public: + MapHeightFitterNode() : Node("map_height_fitter"), fitter_(this) + { + const auto on_service = [this]( + const PoseWithCovarianceStamped::Request::SharedPtr req, + const PoseWithCovarianceStamped::Response::SharedPtr res) { + const auto & pose = req->pose_with_covariance; + const auto fitted = fitter_.fit(pose.pose.pose.position, pose.header.frame_id); + if (fitted) { + res->pose_with_covariance = req->pose_with_covariance; + res->pose_with_covariance.pose.pose.position = fitted.value(); + res->success = true; + } else { + res->success = false; + } + }; + srv_ = create_service("~/service", on_service); + } + +private: + map_height_fitter::MapHeightFitter fitter_; + rclcpp::Service::SharedPtr srv_; +}; + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + rclcpp::executors::MultiThreadedExecutor executor; + auto node = std::make_shared(); + executor.add_node(node); + executor.spin(); + executor.remove_node(node); + rclcpp::shutdown(); +} diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp index a3dd1e7d0d9de..5d34653244ea2 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp @@ -47,10 +47,11 @@ InitialPoseAdaptor::InitialPoseAdaptor() : Node("initial_pose_adaptor"), fitter_ void InitialPoseAdaptor::on_initial_pose(const PoseWithCovarianceStamped::ConstSharedPtr msg) { - const auto & point = msg->pose.pose.position; - const auto & frame = msg->header.frame_id; - auto pose = *msg; - pose.pose.pose.position = fitter_.fit(point, frame); + PoseWithCovarianceStamped pose = *msg; + const auto fitted = fitter_.fit(pose.pose.pose.position, pose.header.frame_id); + if (fitted) { + pose.pose.pose.position = fitted.value(); + } pose.pose.covariance = rviz_particle_covariance_; const auto req = std::make_shared(); From d905e383b05c2143b0a862c218b473ede56f3037 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 6 Jul 2023 09:56:25 +0900 Subject: [PATCH 097/118] refactor(behavior_velocity_crosswalk_module): clean up the code (#4157) * refactor Signed-off-by: Takayuki Murooka * use tier4_autoware_utils's boost types Signed-off-by: Takayuki Murooka * return Point instead of Point2d Signed-off-by: Takayuki Murooka * remove unnecessary lambda function Signed-off-by: Takayuki Murooka * add Line2d in tier4_autoware_utils Signed-off-by: Takayuki Murooka * remove unnecessary member variable Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../geometry/boost_geometry.hpp | 1 + .../src/scene_crosswalk.cpp | 162 ++++++++---------- .../src/scene_crosswalk.hpp | 30 ++-- .../src/scene_walkway.cpp | 47 ++--- .../src/scene_walkway.hpp | 5 +- .../src/util.cpp | 40 +++-- .../src/util.hpp | 6 +- 7 files changed, 132 insertions(+), 159 deletions(-) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_geometry.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_geometry.hpp index 453675c4fb201..91f9ab09a1e08 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_geometry.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_geometry.hpp @@ -34,6 +34,7 @@ using Box2d = boost::geometry::model::box; using LineString2d = boost::geometry::model::linestring; using LinearRing2d = boost::geometry::model::ring; using Polygon2d = boost::geometry::model::polygon; +using Line2d = boost::geometry::model::linestring; using MultiPoint2d = boost::geometry::model::multi_point; using MultiLineString2d = boost::geometry::model::multi_linestring; using MultiPolygon2d = boost::geometry::model::multi_polygon; diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 2ac4521c4c79e..473ec745c93ac 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -29,9 +29,6 @@ namespace behavior_velocity_planner { namespace bg = boost::geometry; -using Point = bg::model::d2::point_xy; -using Polygon = bg::model::polygon; -using Line = bg::model::linestring; using motion_utils::calcArcLength; using motion_utils::calcLateralOffset; using motion_utils::calcLongitudinalOffsetPoint; @@ -42,6 +39,8 @@ using motion_utils::insertTargetPoint; using tier4_autoware_utils::createPoint; using tier4_autoware_utils::getPoint; using tier4_autoware_utils::getPose; +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Polygon2d; using tier4_autoware_utils::pose2transform; using tier4_autoware_utils::toHexString; @@ -55,7 +54,7 @@ geometry_msgs::msg::Point32 createPoint32(const double x, const double y, const p.z = z; return p; } -geometry_msgs::msg::Polygon toMsg(const Polygon & polygon, const double z) +geometry_msgs::msg::Polygon toMsg(const Polygon2d & polygon, const double z) { geometry_msgs::msg::Polygon ret; for (const auto & p : polygon.outer()) { @@ -63,11 +62,11 @@ geometry_msgs::msg::Polygon toMsg(const Polygon & polygon, const double z) } return ret; } -Polygon createOneStepPolygon( +Polygon2d createOneStepPolygon( const geometry_msgs::msg::Pose & p_front, const geometry_msgs::msg::Pose & p_back, const geometry_msgs::msg::Polygon & base_polygon) { - Polygon one_step_polygon{}; + Polygon2d one_step_polygon{}; { geometry_msgs::msg::Polygon out_polygon{}; @@ -76,7 +75,7 @@ Polygon createOneStepPolygon( tf2::doTransform(base_polygon, out_polygon, geometry_tf); for (const auto & p : out_polygon.points) { - one_step_polygon.outer().push_back(Point(p.x, p.y)); + one_step_polygon.outer().push_back(Point2d(p.x, p.y)); } } @@ -87,11 +86,11 @@ Polygon createOneStepPolygon( tf2::doTransform(base_polygon, out_polygon, geometry_tf); for (const auto & p : out_polygon.points) { - one_step_polygon.outer().push_back(Point(p.x, p.y)); + one_step_polygon.outer().push_back(Point2d(p.x, p.y)); } } - Polygon hull_polygon{}; + Polygon2d hull_polygon{}; bg::convex_hull(one_step_polygon, hull_polygon); bg::correct(hull_polygon); @@ -102,22 +101,18 @@ void sortCrosswalksByDistance( lanelet::ConstLanelets & crosswalks) { const auto compare = [&](const lanelet::ConstLanelet & l1, const lanelet::ConstLanelet & l2) { - const std::vector l1_intersects = + const auto l1_intersects = getPolygonIntersects(ego_path, l1.polygon2d().basicPolygon(), ego_pos, 2); - const std::vector l2_intersects = + const auto l2_intersects = getPolygonIntersects(ego_path, l2.polygon2d().basicPolygon(), ego_pos, 2); if (l1_intersects.empty() || l2_intersects.empty()) { return true; } - const auto dist_l1 = calcSignedArcLength( - ego_path.points, size_t(0), - createPoint(l1_intersects.front().x(), l1_intersects.front().y(), ego_pos.z)); + const auto dist_l1 = calcSignedArcLength(ego_path.points, size_t(0), l1_intersects.front()); - const auto dist_l2 = calcSignedArcLength( - ego_path.points, size_t(0), - createPoint(l2_intersects.front().x(), l2_intersects.front().y(), ego_pos.z)); + const auto dist_l2 = calcSignedArcLength(ego_path.points, size_t(0), l2_intersects.front()); return dist_l1 < dist_l2; }; @@ -169,23 +164,17 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto logger_, planner_param_.show_processing_time, "- step1: %f ms", stop_watch_.toc("total_processing_time", false)); - path_intersects_.clear(); - const auto & ego_pos = planner_data_->current_odometry->pose.position; - const auto intersects = + const auto path_intersects = getPolygonIntersects(ego_path, crosswalk_.polygon2d().basicPolygon(), ego_pos, 2); - for (const auto & p : intersects) { - path_intersects_.push_back(createPoint(p.x(), p.y(), ego_pos.z)); - } - for (const auto & p : crosswalk_.polygon2d().basicPolygon()) { debug_data_.crosswalk_polygon.push_back(createPoint(p.x(), p.y(), ego_pos.z)); } if (crosswalk_.hasAttribute("safety_slow_down_speed")) { // Safety slow down is on - if (applySafetySlowDownSpeed(*path)) { + if (applySafetySlowDownSpeed(*path, path_intersects)) { ego_path = *path; } } @@ -194,8 +183,9 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto logger_, planner_param_.show_processing_time, "- step2: %f ms", stop_watch_.toc("total_processing_time", false)); - const auto nearest_stop_point_with_factor = findNearestStopPointWithFactor(ego_path); - const auto rtc_stop_point_with_factor = findRTCStopPointWithFactor(ego_path); + const auto nearest_stop_point_with_factor = + findNearestStopPointWithFactor(ego_path, path_intersects); + const auto rtc_stop_point_with_factor = findRTCStopPointWithFactor(ego_path, path_intersects); RCLCPP_INFO_EXPRESSION( logger_, planner_param_.show_processing_time, "- step3: %f ms", @@ -204,24 +194,23 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto setSafe(!nearest_stop_point_with_factor); if (isActivated()) { - if (!nearest_stop_point_with_factor) { - if (!rtc_stop_point_with_factor) { - setDistance(std::numeric_limits::lowest()); - return true; - } + if (nearest_stop_point_with_factor) { + const auto target_velocity = + calcTargetVelocity(nearest_stop_point_with_factor->first, ego_path); + insertDecelPointWithDebugInfo( + nearest_stop_point_with_factor->first, + std::max(planner_param_.min_slow_down_velocity, target_velocity), *path); + return true; + } + if (rtc_stop_point_with_factor) { const auto crosswalk_distance = calcSignedArcLength(ego_path.points, ego_pos, getPoint(rtc_stop_point_with_factor->first)); setDistance(crosswalk_distance); return true; } - const auto target_velocity = - calcTargetVelocity(nearest_stop_point_with_factor->first, ego_path); - insertDecelPointWithDebugInfo( - nearest_stop_point_with_factor->first, - std::max(planner_param_.min_slow_down_velocity, target_velocity), *path); - + setDistance(std::numeric_limits::lowest()); return true; } @@ -253,39 +242,29 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto } boost::optional> CrosswalkModule::getStopLine( - const PathWithLaneId & ego_path, bool & exist_stopline_in_map) const + const PathWithLaneId & ego_path, bool & exist_stopline_in_map, + const std::vector & path_intersects) const { const auto & ego_pos = planner_data_->current_odometry->pose.position; - - const auto get_stop_point = - [&](const auto & stop_line) -> boost::optional { - const auto intersects = getLinestringIntersects( - ego_path, lanelet::utils::to2D(stop_line).basicLineString(), ego_pos, 2); - - if (intersects.empty()) { - return boost::none; - } - - return createPoint(intersects.front().x(), intersects.front().y(), ego_pos.z); - }; - for (const auto & stop_line : stop_lines_) { - const auto p_stop_line = get_stop_point(stop_line); - if (!p_stop_line) { + const auto p_stop_lines = getLinestringIntersects( + ego_path, lanelet::utils::to2D(stop_line).basicLineString(), ego_pos, 2); + if (p_stop_lines.empty()) { continue; } exist_stopline_in_map = true; - const auto dist_ego_to_stop = calcSignedArcLength(ego_path.points, ego_pos, p_stop_line.get()); - return std::make_pair(dist_ego_to_stop, p_stop_line.get()); + const auto dist_ego_to_stop = + calcSignedArcLength(ego_path.points, ego_pos, p_stop_lines.front()); + return std::make_pair(dist_ego_to_stop, p_stop_lines.front()); } { exist_stopline_in_map = false; - if (!path_intersects_.empty()) { - const auto p_stop_line = path_intersects_.front(); + if (!path_intersects.empty()) { + const auto p_stop_line = path_intersects.front(); const auto dist_ego_to_stop = calcSignedArcLength(ego_path.points, ego_pos, p_stop_line) - planner_param_.stop_line_distance; return std::make_pair(dist_ego_to_stop, p_stop_line); @@ -296,12 +275,13 @@ boost::optional> CrosswalkModule::g } boost::optional> -CrosswalkModule::findRTCStopPointWithFactor(const PathWithLaneId & ego_path) +CrosswalkModule::findRTCStopPointWithFactor( + const PathWithLaneId & ego_path, const std::vector & path_intersects) { const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; bool exist_stopline_in_map; - const auto p_stop_line = getStopLine(ego_path, exist_stopline_in_map); + const auto p_stop_line = getStopLine(ego_path, exist_stopline_in_map, path_intersects); if (!p_stop_line) { return {}; } @@ -322,7 +302,8 @@ CrosswalkModule::findRTCStopPointWithFactor(const PathWithLaneId & ego_path) } boost::optional> -CrosswalkModule::findNearestStopPointWithFactor(const PathWithLaneId & ego_path) +CrosswalkModule::findNearestStopPointWithFactor( + const PathWithLaneId & ego_path, const std::vector & path_intersects) { StopFactor stop_factor; @@ -335,13 +316,14 @@ CrosswalkModule::findNearestStopPointWithFactor(const PathWithLaneId & ego_path) return {}; } - const auto crosswalk_attention_range = getAttentionRange(sparse_resample_path); + const auto crosswalk_attention_range = getAttentionRange(sparse_resample_path, path_intersects); const auto & ego_pos = planner_data_->current_odometry->pose.position; const auto & objects_ptr = planner_data_->predicted_objects; const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; bool exist_stopline_in_map; - const auto p_stop_line = getStopLine(sparse_resample_path, exist_stopline_in_map); + const auto p_stop_line = + getStopLine(sparse_resample_path, exist_stopline_in_map, path_intersects); if (!p_stop_line) { return {}; } @@ -355,7 +337,7 @@ CrosswalkModule::findNearestStopPointWithFactor(const PathWithLaneId & ego_path) const auto ego_polygon = createVehiclePolygon(planner_data_->vehicle_info_); - Polygon attention_area; + Polygon2d attention_area; for (size_t j = 0; j < sparse_resample_path.points.size() - 1; ++j) { const auto & p_ego_front = sparse_resample_path.points.at(j).point.pose; const auto & p_ego_back = sparse_resample_path.points.at(j + 1).point.pose; @@ -376,7 +358,7 @@ CrosswalkModule::findNearestStopPointWithFactor(const PathWithLaneId & ego_path) debug_data_.ego_polygons.push_back(toMsg(ego_one_step_polygon, ego_pos.z)); - std::vector unions; + std::vector unions; bg::union_(attention_area, ego_one_step_polygon, unions); if (!unions.empty()) { attention_area = unions.front(); @@ -390,7 +372,8 @@ CrosswalkModule::findNearestStopPointWithFactor(const PathWithLaneId & ego_path) const auto obj_uuid = toHexString(object.object_id); if (isVehicle(object)) { - found_stuck_vehicle = found_stuck_vehicle || isStuckVehicle(sparse_resample_path, object); + found_stuck_vehicle = + found_stuck_vehicle || isStuckVehicle(sparse_resample_path, object, path_intersects); } if (!isTargetType(object)) { @@ -495,7 +478,8 @@ CrosswalkModule::findNearestStopPointWithFactor(const PathWithLaneId & ego_path) return std::make_pair(stop_pose.get().position, stop_factor); } -std::pair CrosswalkModule::getAttentionRange(const PathWithLaneId & ego_path) +std::pair CrosswalkModule::getAttentionRange( + const PathWithLaneId & ego_path, const std::vector & path_intersects) { stop_watch_.tic(__func__); @@ -503,12 +487,12 @@ std::pair CrosswalkModule::getAttentionRange(const PathWithLaneI double near_attention_range = 0.0; double far_attention_range = 0.0; - if (path_intersects_.size() < 2) { + if (path_intersects.size() < 2) { return std::make_pair(near_attention_range, far_attention_range); } - near_attention_range = calcSignedArcLength(ego_path.points, ego_pos, path_intersects_.front()); - far_attention_range = calcSignedArcLength(ego_path.points, ego_pos, path_intersects_.back()); + near_attention_range = calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front()); + far_attention_range = calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back()); near_attention_range -= planner_param_.crosswalk_attention_range; far_attention_range += planner_param_.crosswalk_attention_range; @@ -631,28 +615,24 @@ void CrosswalkModule::clampAttentionRangeByNeighborCrosswalks( auto reverse_ego_path = ego_path; std::reverse(reverse_ego_path.points.begin(), reverse_ego_path.points.end()); - const std::vector prev_crosswalk_intersects = getPolygonIntersects( + const auto prev_crosswalk_intersects = getPolygonIntersects( reverse_ego_path, prev_crosswalk.get().polygon2d().basicPolygon(), ego_pos, 2); if (!prev_crosswalk_intersects.empty()) { - const auto dist_to_prev_crosswalk = calcSignedArcLength( - ego_path.points, ego_pos, - createPoint( - prev_crosswalk_intersects.front().x(), prev_crosswalk_intersects.front().y(), ego_pos.z)); + const auto dist_to_prev_crosswalk = + calcSignedArcLength(ego_path.points, ego_pos, prev_crosswalk_intersects.front()); near_attention_range = std::max(near_attention_range, dist_to_prev_crosswalk); } } if (next_crosswalk) { - const std::vector next_crosswalk_intersects = + const auto next_crosswalk_intersects = getPolygonIntersects(ego_path, next_crosswalk.get().polygon2d().basicPolygon(), ego_pos, 2); if (!next_crosswalk_intersects.empty()) { - const auto dist_to_next_crosswalk = calcSignedArcLength( - ego_path.points, ego_pos, - createPoint( - next_crosswalk_intersects.front().x(), next_crosswalk_intersects.front().y(), ego_pos.z)); + const auto dist_to_next_crosswalk = + calcSignedArcLength(ego_path.points, ego_pos, next_crosswalk_intersects.front()); far_attention_range = std::min(far_attention_range, dist_to_next_crosswalk); } @@ -674,7 +654,7 @@ void CrosswalkModule::clampAttentionRangeByNeighborCrosswalks( } std::vector CrosswalkModule::getCollisionPoints( - const PathWithLaneId & ego_path, const PredictedObject & object, const Polygon & attention_area, + const PathWithLaneId & ego_path, const PredictedObject & object, const Polygon2d & attention_area, const std::pair & crosswalk_attention_range) { stop_watch_.tic(__func__); @@ -695,12 +675,12 @@ std::vector CrosswalkModule::getCollisionPoints( const auto p_obj_back = obj_path.path.at(i + 1); const auto obj_one_step_polygon = createOneStepPolygon(p_obj_front, p_obj_back, obj_polygon); - std::vector tmp_intersects{}; + std::vector tmp_intersects{}; bg::intersection(obj_one_step_polygon, attention_area, tmp_intersects); if (bg::within(obj_one_step_polygon, attention_area)) { for (const auto & p : obj_one_step_polygon.outer()) { - const Point point{p.x(), p.y()}; + const Point2d point{p.x(), p.y()}; tmp_intersects.push_back(point); } } @@ -789,9 +769,10 @@ CollisionPointState CrosswalkModule::getCollisionPointState( return CollisionPointState::YIELD; } -bool CrosswalkModule::applySafetySlowDownSpeed(PathWithLaneId & output) +bool CrosswalkModule::applySafetySlowDownSpeed( + PathWithLaneId & output, const std::vector & path_intersects) { - if (path_intersects_.empty()) { + if (path_intersects.empty()) { return false; } @@ -808,7 +789,7 @@ bool CrosswalkModule::applySafetySlowDownSpeed(PathWithLaneId & output) // the range until to the point where ego will have a const safety slow down speed auto safety_slow_point_range = - calcSignedArcLength(ego_path.points, ego_pos, path_intersects_.front()); + calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front()); const auto & safety_slow_margin = planner_data_->vehicle_info_.max_longitudinal_offset_m + safety_slow_down_distance; safety_slow_point_range -= safety_slow_margin; @@ -824,7 +805,7 @@ bool CrosswalkModule::applySafetySlowDownSpeed(PathWithLaneId & output) } else { // the range until to the point where ego will start accelerate auto safety_slow_end_point_range = - calcSignedArcLength(ego_path.points, ego_pos, path_intersects_.back()); + calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back()); if (safety_slow_end_point_range > 0) { // insert constant ego speed until the end of the crosswalk @@ -838,7 +819,8 @@ bool CrosswalkModule::applySafetySlowDownSpeed(PathWithLaneId & output) } bool CrosswalkModule::isStuckVehicle( - const PathWithLaneId & ego_path, const PredictedObject & object) const + const PathWithLaneId & ego_path, const PredictedObject & object, + const std::vector & path_intersects) const { const auto & obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear; if (planner_param_.stuck_vehicle_velocity < std::hypot(obj_vel.x, obj_vel.y)) { @@ -851,13 +833,13 @@ bool CrosswalkModule::isStuckVehicle( return false; } - if (path_intersects_.size() < 2) { + if (path_intersects.size() < 2) { return false; } const auto & ego_pos = planner_data_->current_odometry->pose.position; const double near_attention_range = - calcSignedArcLength(ego_path.points, ego_pos, path_intersects_.back()); + calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back()); const double far_attention_range = near_attention_range + planner_param_.stuck_vehicle_attention_range; diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index d53bc30471426..2edade84bb87b 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -29,9 +29,6 @@ #include #include -#include -#include -#include #include #include @@ -55,6 +52,7 @@ using autoware_auto_perception_msgs::msg::TrafficLight; using autoware_auto_planning_msgs::msg::PathWithLaneId; using lanelet::autoware::Crosswalk; using tier4_api_msgs::msg::CrosswalkStatus; +using tier4_autoware_utils::Polygon2d; using tier4_autoware_utils::StopWatch; class CrosswalkModule : public SceneModuleInterface @@ -108,21 +106,24 @@ class CrosswalkModule : public SceneModuleInterface int64_t module_id_; boost::optional> findRTCStopPointWithFactor( - const PathWithLaneId & ego_path); + const PathWithLaneId & ego_path, + const std::vector & path_intersects); boost::optional> findNearestStopPointWithFactor( - const PathWithLaneId & ego_path); + const PathWithLaneId & ego_path, + const std::vector & path_intersects); boost::optional> getStopLine( - const PathWithLaneId & ego_path, bool & exist_stopline_in_map) const; + const PathWithLaneId & ego_path, bool & exist_stopline_in_map, + const std::vector & path_intersects) const; std::vector getCollisionPoints( const PathWithLaneId & ego_path, const PredictedObject & object, - const boost::geometry::model::polygon> & - attention_area, - const std::pair & crosswalk_attention_range); + const Polygon2d & attention_area, const std::pair & crosswalk_attention_range); - std::pair getAttentionRange(const PathWithLaneId & ego_path); + std::pair getAttentionRange( + const PathWithLaneId & ego_path, + const std::vector & path_intersects); void insertDecelPointWithDebugInfo( const geometry_msgs::msg::Point & stop_point, const float target_velocity, @@ -138,12 +139,15 @@ class CrosswalkModule : public SceneModuleInterface CollisionPointState getCollisionPointState(const double ttc, const double ttv) const; - bool applySafetySlowDownSpeed(PathWithLaneId & output); + bool applySafetySlowDownSpeed( + PathWithLaneId & output, const std::vector & path_intersects); float calcTargetVelocity( const geometry_msgs::msg::Point & stop_point, const PathWithLaneId & ego_path) const; - bool isStuckVehicle(const PathWithLaneId & ego_path, const PredictedObject & object) const; + bool isStuckVehicle( + const PathWithLaneId & ego_path, const PredictedObject & object, + const std::vector & path_intersects) const; bool isRedSignalForPedestrians() const; @@ -161,8 +165,6 @@ class CrosswalkModule : public SceneModuleInterface lanelet::ConstLineStrings3d stop_lines_; - std::vector path_intersects_; - // Parameter PlannerParam planner_param_; diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_walkway.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_walkway.cpp index 1265e73223eff..119591c225e36 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_walkway.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_walkway.cpp @@ -22,9 +22,6 @@ namespace behavior_velocity_planner { namespace bg = boost::geometry; -using Point = bg::model::d2::point_xy; -using Polygon = bg::model::polygon; -using Line = bg::model::linestring; using motion_utils::calcLongitudinalOffsetPose; using motion_utils::calcSignedArcLength; using motion_utils::findNearestSegmentIndex; @@ -58,39 +55,29 @@ WalkwayModule::WalkwayModule( } boost::optional> WalkwayModule::getStopLine( - const PathWithLaneId & ego_path, bool & exist_stopline_in_map) const + const PathWithLaneId & ego_path, bool & exist_stopline_in_map, + const std::vector & path_intersects) const { const auto & ego_pos = planner_data_->current_odometry->pose.position; - - const auto get_stop_point = - [&](const auto & stop_line) -> boost::optional { - const auto intersects = getLinestringIntersects( - ego_path, lanelet::utils::to2D(stop_line).basicLineString(), ego_pos, 2); - - if (intersects.empty()) { - return boost::none; - } - - return createPoint(intersects.front().x(), intersects.front().y(), ego_pos.z); - }; - for (const auto & stop_line : stop_lines_) { - const auto p_stop_line = get_stop_point(stop_line); - if (!p_stop_line) { + const auto p_stop_lines = getLinestringIntersects( + ego_path, lanelet::utils::to2D(stop_line).basicLineString(), ego_pos, 2); + if (p_stop_lines.empty()) { continue; } exist_stopline_in_map = true; - const auto dist_ego_to_stop = calcSignedArcLength(ego_path.points, ego_pos, p_stop_line.get()); - return std::make_pair(dist_ego_to_stop, p_stop_line.get()); + const auto dist_ego_to_stop = + calcSignedArcLength(ego_path.points, ego_pos, p_stop_lines.front()); + return std::make_pair(dist_ego_to_stop, p_stop_lines.front()); } { exist_stopline_in_map = false; - if (!path_intersects_.empty()) { - const auto p_stop_line = path_intersects_.front(); + if (!path_intersects.empty()) { + const auto p_stop_line = path_intersects.front(); const auto dist_ego_to_stop = calcSignedArcLength(ego_path.points, ego_pos, p_stop_line) - planner_param_.stop_line_distance; return std::make_pair(dist_ego_to_stop, p_stop_line); @@ -110,23 +97,17 @@ bool WalkwayModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_ const auto input = *path; - path_intersects_.clear(); - const auto & ego_pos = planner_data_->current_odometry->pose.position; - const auto intersects = + const auto path_intersects = getPolygonIntersects(input, walkway_.polygon2d().basicPolygon(), ego_pos, 2); - for (const auto & p : intersects) { - path_intersects_.push_back(createPoint(p.x(), p.y(), ego_pos.z)); - } - - if (path_intersects_.empty()) { + if (path_intersects.empty()) { return false; } if (state_ == State::APPROACH) { bool exist_stopline_in_map; - const auto p_stop_line = getStopLine(input, exist_stopline_in_map); + const auto p_stop_line = getStopLine(input, exist_stopline_in_map, path_intersects); if (!p_stop_line) { return false; } @@ -148,7 +129,7 @@ bool WalkwayModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_ /* get stop point and stop factor */ StopFactor stop_factor; stop_factor.stop_pose = stop_pose.get(); - stop_factor.stop_factor_points.push_back(path_intersects_.front()); + stop_factor.stop_factor_points.push_back(path_intersects.front()); planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose.get(), diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_walkway.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_walkway.hpp index 40ae4d9bbf1b0..a32038e17fab4 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_walkway.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_walkway.hpp @@ -58,7 +58,8 @@ class WalkwayModule : public SceneModuleInterface int64_t module_id_; [[nodiscard]] boost::optional> getStopLine( - const PathWithLaneId & ego_path, bool & exist_stopline_in_map) const; + const PathWithLaneId & ego_path, bool & exist_stopline_in_map, + const std::vector & path_intersects) const; enum class State { APPROACH, STOP, SURPASSED }; @@ -66,8 +67,6 @@ class WalkwayModule : public SceneModuleInterface lanelet::ConstLineStrings3d stop_lines_; - std::vector path_intersects_; - // State machine State state_; diff --git a/planning/behavior_velocity_crosswalk_module/src/util.cpp b/planning/behavior_velocity_crosswalk_module/src/util.cpp index 3c8d456ab8864..3674f5e415b1a 100644 --- a/planning/behavior_velocity_crosswalk_module/src/util.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/util.cpp @@ -42,28 +42,26 @@ namespace behavior_velocity_planner { - namespace bg = boost::geometry; -using Point = bg::model::d2::point_xy; -using Polygon = bg::model::polygon; -using Line = bg::model::linestring; using motion_utils::calcSignedArcLength; using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::Line2d; +using tier4_autoware_utils::Point2d; -std::vector getPolygonIntersects( +std::vector getPolygonIntersects( const PathWithLaneId & ego_path, const lanelet::BasicPolygon2d & polygon, const geometry_msgs::msg::Point & ego_pos, const size_t max_num = std::numeric_limits::max()) { - std::vector intersects{}; + std::vector intersects{}; bool found_max_num = false; for (size_t i = 0; i < ego_path.points.size() - 1; ++i) { const auto & p_back = ego_path.points.at(i).point.pose.position; const auto & p_front = ego_path.points.at(i + 1).point.pose.position; - const Line segment{{p_back.x, p_back.y}, {p_front.x, p_front.y}}; + const Line2d segment{{p_back.x, p_back.y}, {p_front.x, p_front.y}}; - std::vector tmp_intersects{}; + std::vector tmp_intersects{}; bg::intersection(segment, polygon, tmp_intersects); for (const auto & p : tmp_intersects) { @@ -79,7 +77,7 @@ std::vector getPolygonIntersects( } } - const auto compare = [&](const Point & p1, const Point & p2) { + const auto compare = [&](const Point2d & p1, const Point2d & p2) { const auto dist_l1 = calcSignedArcLength(ego_path.points, size_t(0), createPoint(p1.x(), p1.y(), ego_pos.z)); @@ -91,23 +89,28 @@ std::vector getPolygonIntersects( std::sort(intersects.begin(), intersects.end(), compare); - return intersects; + // convert tier4_autoware_utils::Point2d to geometry::msg::Point + std::vector geometry_points; + for (const auto & p : intersects) { + geometry_points.push_back(createPoint(p.x(), p.y(), ego_pos.z)); + } + return geometry_points; } -std::vector getLinestringIntersects( +std::vector getLinestringIntersects( const PathWithLaneId & ego_path, const lanelet::BasicLineString2d & linestring, const geometry_msgs::msg::Point & ego_pos, const size_t max_num = std::numeric_limits::max()) { - std::vector intersects{}; + std::vector intersects{}; bool found_max_num = false; for (size_t i = 0; i < ego_path.points.size() - 1; ++i) { const auto & p_back = ego_path.points.at(i).point.pose.position; const auto & p_front = ego_path.points.at(i + 1).point.pose.position; - const Line segment{{p_back.x, p_back.y}, {p_front.x, p_front.y}}; + const Line2d segment{{p_back.x, p_back.y}, {p_front.x, p_front.y}}; - std::vector tmp_intersects{}; + std::vector tmp_intersects{}; bg::intersection(segment, linestring, tmp_intersects); for (const auto & p : tmp_intersects) { @@ -123,7 +126,7 @@ std::vector getLinestringIntersects( } } - const auto compare = [&](const Point & p1, const Point & p2) { + const auto compare = [&](const Point2d & p1, const Point2d & p2) { const auto dist_l1 = calcSignedArcLength(ego_path.points, size_t(0), createPoint(p1.x(), p1.y(), ego_pos.z)); @@ -135,7 +138,12 @@ std::vector getLinestringIntersects( std::sort(intersects.begin(), intersects.end(), compare); - return intersects; + // convert tier4_autoware_utils::Point2d to geometry::msg::Point + std::vector geometry_points; + for (const auto & p : intersects) { + geometry_points.push_back(createPoint(p.x(), p.y(), ego_pos.z)); + } + return geometry_points; } lanelet::Optional getStopLineFromMap( diff --git a/planning/behavior_velocity_crosswalk_module/src/util.hpp b/planning/behavior_velocity_crosswalk_module/src/util.hpp index 10602b11c3c2e..d585cf521dc73 100644 --- a/planning/behavior_velocity_crosswalk_module/src/util.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/util.hpp @@ -36,9 +36,9 @@ namespace behavior_velocity_planner { -namespace bg = boost::geometry; using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using autoware_auto_planning_msgs::msg::PathWithLaneId; +using tier4_autoware_utils::Point2d; enum class CollisionPointState { YIELD, EGO_PASS_FIRST, EGO_PASS_LATER, IGNORE }; @@ -72,11 +72,11 @@ struct DebugData std::vector obj_polygons; }; -std::vector> getPolygonIntersects( +std::vector getPolygonIntersects( const PathWithLaneId & ego_path, const lanelet::BasicPolygon2d & polygon, const geometry_msgs::msg::Point & ego_pos, const size_t max_num); -std::vector> getLinestringIntersects( +std::vector getLinestringIntersects( const PathWithLaneId & ego_path, const lanelet::BasicLineString2d & linestring, const geometry_msgs::msg::Point & ego_pos, const size_t max_num); From f8e74c5ee4abb5591ea6e6135010dc84fc18e627 Mon Sep 17 00:00:00 2001 From: beyzanurkaya <32412808+beyzanurkaya@users.noreply.github.com> Date: Thu, 6 Jul 2023 08:23:10 +0300 Subject: [PATCH 098/118] feat(behavior_velocity_intersection_module): consider NPC vehicles driving on the wrong direction lane on intersection (#3947) * add missing argument Signed-off-by: beyza * add consider_wrong_direction_vehicle var Signed-off-by: beyza * get consider_wrong_direction_vehicle param Signed-off-by: beyza * change the angle condition Signed-off-by: beyza * add option for the wrong direction NPCs Signed-off-by: beyza * add missing param Signed-off-by: beyza * add size condition for adj_followings Signed-off-by: beyza * add missing param Signed-off-by: beyza * 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> --- .../config/intersection.param.yaml | 2 +- .../src/manager.cpp | 2 ++ .../src/scene_intersection.cpp | 4 ++- .../src/scene_intersection.hpp | 1 + .../src/scene_merge_from_private_road.cpp | 2 ++ .../src/scene_merge_from_private_road.hpp | 2 ++ .../src/util.cpp | 33 ++++++++++++++----- .../src/util.hpp | 2 +- 8 files changed, 36 insertions(+), 12 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 719d0b7ac78d5..5afc318dfdbff 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -11,7 +11,7 @@ stop_overshoot_margin: 0.5 # [m] overshoot margin for stuck, collision detection use_intersection_area: false path_interpolation_ds: 0.2 # [m] - + consider_wrong_direction_vehicle: false stuck_vehicle: use_stuck_stopline: false # stopline generate before the intersection lanelet when is_stuck stuck_vehicle_detect_dist: 3.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 8ccd725756e09..22fbfd00b1cf0 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -53,6 +53,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) node.declare_parameter(ns + ".common.use_intersection_area"); ip.common.path_interpolation_ds = node.declare_parameter(ns + ".common.path_interpolation_ds"); + ip.common.consider_wrong_direction_vehicle = + node.declare_parameter(ns + ".common.consider_wrong_direction_vehicle"); ip.stuck_vehicle.use_stuck_stopline = node.declare_parameter(ns + ".stuck_vehicle.use_stuck_stopline"); diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 0512e90197237..bc6b54c23edd6 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -660,7 +660,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( planning_utils::getLaneletsOnPath(*path, lanelet_map_ptr, current_pose); intersection_lanelets_ = util::getObjectiveLanelets( lanelet_map_ptr, routing_graph_ptr, assigned_lanelet, lanelets_on_path, associative_ids_, - interpolated_path_info, planner_param_.common.attention_area_length, tl_arrow_solid_on); + interpolated_path_info, planner_param_.common.attention_area_length, + planner_param_.occlusion.occlusion_attention_area_length, + planner_param_.common.consider_wrong_direction_vehicle, tl_arrow_solid_on); } const auto & conflicting_lanelets = intersection_lanelets_.value().conflicting; diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 38cf17d2eba7d..2bd8cb28941d8 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -59,6 +59,7 @@ class IntersectionModule : public SceneModuleInterface double intersection_max_acc; //! used for calculating intersection velocity double stop_overshoot_margin; //! overshoot margin for stuck, collision detection bool use_intersection_area; + bool consider_wrong_direction_vehicle; double path_interpolation_ds; } common; struct StuckVehicle 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 2cac559bc0687..84136b6b7beb6 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 @@ -91,6 +91,8 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR intersection_lanelets_ = util::getObjectiveLanelets( lanelet_map_ptr, routing_graph_ptr, assigned_lanelet, lanelets_on_path, associative_ids_, interpolated_path_info, planner_param_.attention_area_length, + planner_param_.occlusion_attention_area_length, + planner_param_.consider_wrong_direction_vehicle, false /* tl_arrow_solid on does not matter here*/); } const auto & first_conflicting_area = intersection_lanelets_.value().first_conflicting_area; diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp index da41bb4d695cd..aa334f11be84d 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp @@ -60,6 +60,8 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface double stop_line_margin; double stop_duration_sec; double path_interpolation_ds; + double occlusion_attention_area_length; + bool consider_wrong_direction_vehicle; }; MergeFromPrivateRoadModule( diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 88b2599dae03a..51d8e286fe764 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -402,7 +402,7 @@ IntersectionLanelets getObjectiveLanelets( const lanelet::ConstLanelet assigned_lanelet, const lanelet::ConstLanelets & lanelets_on_path, const std::set & associative_ids, const InterpolatedPathInfo & interpolated_path_info, const double detection_area_length, const double occlusion_detection_area_length, - const bool tl_arrow_solid_on) + const bool consider_wrong_direction_vehicle, const bool tl_arrow_solid_on) { const auto turn_direction = assigned_lanelet.attributeOr("turn_direction", "else"); @@ -446,6 +446,7 @@ IntersectionLanelets getObjectiveLanelets( // get conflicting lanes on assigned lanelet const auto & conflicting_lanelets = lanelet::utils::getConflictingLanelets(routing_graph_ptr, assigned_lanelet); + const auto & adjacent_followings = routing_graph_ptr->following(conflicting_lanelets.back()); // final objective lanelets lanelet::ConstLanelets detection_lanelets; @@ -460,14 +461,26 @@ IntersectionLanelets getObjectiveLanelets( if (turn_direction == std::string("straight") && has_traffic_light) { // if assigned lanelet is "straight" with traffic light, detection area is not necessary } else { - // otherwise we need to know the priority from RightOfWay - for (const auto & conflicting_lanelet : conflicting_lanelets) { - if ( - lanelet::utils::contains(yield_lanelets, conflicting_lanelet) || - lanelet::utils::contains(ego_lanelets, conflicting_lanelet)) { - continue; + if (consider_wrong_direction_vehicle) { + for (const auto & conflicting_lanelet : conflicting_lanelets) { + if (lanelet::utils::contains(yield_lanelets, conflicting_lanelet)) { + continue; + } + detection_lanelets.push_back(conflicting_lanelet); + if (!adjacent_followings.empty()) { + detection_lanelets.push_back(adjacent_followings.front()); + } + } + } else { + // otherwise we need to know the priority from RightOfWay + for (const auto & conflicting_lanelet : conflicting_lanelets) { + if ( + lanelet::utils::contains(yield_lanelets, conflicting_lanelet) || + lanelet::utils::contains(ego_lanelets, conflicting_lanelet)) { + continue; + } + detection_lanelets.push_back(conflicting_lanelet); } - detection_lanelets.push_back(conflicting_lanelet); } } @@ -988,7 +1001,9 @@ bool checkAngleForTargetLanelets( const double ll_angle = lanelet::utils::getLaneletAngle(ll, pose.position); const double pose_angle = tf2::getYaw(pose.orientation); const double angle_diff = tier4_autoware_utils::normalizeRadian(ll_angle - pose_angle); - if (std::fabs(angle_diff) < detection_area_angle_thr) { + if ( + std::fabs(angle_diff) < detection_area_angle_thr / 2 || + std::fabs(angle_diff) > detection_area_angle_thr) { return true; } } diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index c65a4e6e886a0..89931a5db10fc 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -58,7 +58,7 @@ IntersectionLanelets getObjectiveLanelets( const lanelet::ConstLanelet assigned_lanelet, const lanelet::ConstLanelets & lanelets_on_path, const std::set & associative_ids, const InterpolatedPathInfo & interpolated_path_info, const double detection_area_length, const double occlusion_detection_area_length, - const bool tl_arrow_solid_on = false); + const bool consider_wrong_direction_vehicle, const bool tl_arrow_solid_on = false); /** * @brief Generate a stop line for stuck vehicle From b5de8a3ebda58181b19e7f51c67e0faa80d587fd Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim <36835765+ahmeddesokyebrahim@users.noreply.github.com> Date: Thu, 6 Jul 2023 11:02:32 +0300 Subject: [PATCH 099/118] feat(routing-no-drivable-lanes): proposing solution for routing no_drivable_lane (#3954) * feat(routing-no-drivable-lanes): proposing solution for routing no-drivable lanes using getRouteVia method Signed-off-by: AhmedEbrahim * style(pre-commit): autofix * feat(routing-no-drivable-lanes): fixing review comments / adding comments to added functions / proper naming Signed-off-by: AhmedEbrahim * style(pre-commit): autofix --------- Signed-off-by: AhmedEbrahim Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/route_handler/route_handler.hpp | 19 ++++++ planning/route_handler/src/route_handler.cpp | 61 ++++++++++++++++++- 2 files changed, 77 insertions(+), 3 deletions(-) diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 927b423873d5f..8b5c7524e7a25 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -425,6 +425,25 @@ class RouteHandler // for path PathWithLaneId updatePathTwist(const PathWithLaneId & path) const; + /** + * @brief Checks if a path has a no_drivable_lane or not + * @param path lanelet path + * @return true if the lanelet path includes at least one no_drivable_lane, false if it does not + * include any. + */ + bool hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & path) const; + /** + * @brief Searches for a path between start and goal lanelets that does not include any + * no_drivable_lane. If there is more than one path fount, the function returns the shortest path + * that does not include any no_drivable_lane. + * @param start_lanelet start lanelet + * @param goal_lanelet goal lanelet + * @param drivable_lane_path output path that does not include no_drivable_lane. + * @return true if a path without any no_drivable_lane found, false if this path is not found. + */ + bool findDrivableLanePath( + const lanelet::Lanelet & start_lanelet, const lanelet::Lanelet & goal_lanelet, + lanelet::routing::LaneletPath & drivable_lane_path) const; }; } // namespace route_handler #endif // ROUTE_HANDLER__ROUTE_HANDLER_HPP_ diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 534bd344f6443..f3db1cadf02a1 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1994,11 +1994,28 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints( return false; } - const auto shortest_path = optional_route->shortestPath(); - path_lanelets->reserve(shortest_path.size()); - for (const auto & llt : shortest_path) { + const lanelet::routing::LaneletPath shortest_path = optional_route->shortestPath(); + bool shortest_path_has_no_drivable_lane = hasNoDrivableLaneInPath(shortest_path); + lanelet::routing::LaneletPath drivable_lane_path; + bool drivable_lane_path_found = false; + + if (shortest_path_has_no_drivable_lane) { + drivable_lane_path_found = + findDrivableLanePath(start_lanelet, goal_lanelet, drivable_lane_path); + } + + lanelet::routing::LaneletPath path; + if (drivable_lane_path_found) { + path = drivable_lane_path; + } else { + path = shortest_path; + } + + path_lanelets->reserve(path.size()); + for (const auto & llt : path) { path_lanelets->push_back(llt); } + return true; } @@ -2042,4 +2059,42 @@ lanelet::ConstLanelets RouteHandler::getMainLanelets( return main_lanelets; } +bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & path) const +{ + for (const auto & llt : path) { + const std::string no_drivable_lane_attribute = llt.attributeOr("no_drivable_lane", "no"); + if (no_drivable_lane_attribute == "yes") { + return true; + } + } + + return false; +} + +bool RouteHandler::findDrivableLanePath( + const lanelet::Lanelet & start_lanelet, const lanelet::Lanelet & goal_lanelet, + lanelet::routing::LaneletPath & drivable_lane_path) const +{ + double drivable_lane_path_length2d = std::numeric_limits::max(); + bool drivable_lane_path_found = false; + + for (const auto & llt : road_lanelets_) { + lanelet::ConstLanelets via_lanelet; + via_lanelet.push_back(llt); + const lanelet::Optional optional_route = + routing_graph_ptr_->getRouteVia(start_lanelet, via_lanelet, goal_lanelet, 0); + + if ((optional_route) && (!hasNoDrivableLaneInPath(optional_route->shortestPath()))) { + if (optional_route->length2d() < drivable_lane_path_length2d) { + drivable_lane_path_length2d = optional_route->length2d(); + drivable_lane_path = optional_route->shortestPath(); + drivable_lane_path_found = true; + } + } + via_lanelet.clear(); + } + + return drivable_lane_path_found; +} + } // namespace route_handler From 1419f329161518b400183cfeba63150d26f8f1c6 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 6 Jul 2023 23:07:23 +0900 Subject: [PATCH 100/118] fix(dynamic_avoidance): ignore objects on LC target lane (#4137) * fix(dynamic_avoidance): ignore objects on LC target lane Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance/dynamic_avoidance.param.yaml | 2 ++ .../dynamic_avoidance/dynamic_avoidance_module.hpp | 1 + .../dynamic_avoidance/dynamic_avoidance_module.cpp | 12 +++++++++++- .../src/scene_module/dynamic_avoidance/manager.cpp | 4 ++++ 4 files changed, 18 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml index 0b8f35bac3131..85f60e21cf528 100644 --- a/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml +++ b/planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml @@ -16,6 +16,8 @@ successive_num_to_entry_dynamic_avoidance_condition: 5 + min_obj_lat_offset_to_ego_path: 0.3 # [m] + drivable_area_generation: lat_offset_from_obstacle: 0.8 # [m] max_lat_offset_to_avoid: 0.5 # [m] 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 32735b72913fa..6d2b66ff025c1 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 @@ -48,6 +48,7 @@ struct DynamicAvoidanceParameters bool avoid_pedestrian{false}; double min_obstacle_vel{0.0}; int successive_num_to_entry_dynamic_avoidance_condition{0}; + double min_obj_lat_offset_to_ego_path{0.0}; // drivable area generation double lat_offset_from_obstacle{0.0}; 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 262fbb55301ba..11198a49360fb 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 @@ -325,7 +325,8 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() const const auto objects_in_right_lanes = getObjectsInLanes(input_objects, right_lanes); const auto objects_in_left_lanes = getObjectsInLanes(input_objects, left_lanes); - // 4. check if object will cut into the ego lane or cut out to the next lane. + // 4. check if object will not cut into the ego lane or cut out to the next lane, + // or close to the ego's path considering ego's lane change. // NOTE: The oncoming object will be ignored. constexpr double epsilon_path_lat_diff = 0.3; std::vector output_objects_candidate; @@ -380,6 +381,15 @@ DynamicAvoidanceModule::calcTargetObjectsCandidate() const continue; } + // Ignore object that is close to the ego's path. + const double lat_offset_to_path = + motion_utils::calcLateralOffset(prev_module_path->points, object.pose.position); + if ( + std::abs(lat_offset_to_path) < planner_data_->parameters.vehicle_width / 2.0 + + parameters_->min_obj_lat_offset_to_ego_path) { + continue; + } + // get previous object if it exists const auto prev_target_object_candidate = DynamicAvoidanceObjectCandidate::getObjectFromUuid( prev_target_objects_candidate_, object.uuid); diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index 08188343f1d64..cfc57e480af85 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -42,6 +42,8 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( p.min_obstacle_vel = node->declare_parameter(ns + "min_obstacle_vel"); p.successive_num_to_entry_dynamic_avoidance_condition = node->declare_parameter(ns + "successive_num_to_entry_dynamic_avoidance_condition"); + p.min_obj_lat_offset_to_ego_path = + node->declare_parameter(ns + "min_obj_lat_offset_to_ego_path"); } { // drivable_area_generation @@ -92,6 +94,8 @@ void DynamicAvoidanceModuleManager::updateModuleParams( updateParam( parameters, ns + "successive_num_to_entry_dynamic_avoidance_condition", p->successive_num_to_entry_dynamic_avoidance_condition); + updateParam( + parameters, ns + "min_obj_lat_offset_to_ego_path", p->min_obj_lat_offset_to_ego_path); } { // drivable_area_generation From cde4c92bcb1ebb7f94d97d92a9ef65d72dea793c Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Fri, 7 Jul 2023 00:51:08 +0900 Subject: [PATCH 101/118] feat(elevation_map_loader): add error handling for std::runtime_error (#4187) * feat(elevation_map_loader): Add error handling for std::runtime_error Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(elevation_map_loader): add error message output Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> --------- Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> --- .../elevation_map_loader/src/elevation_map_loader_node.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/perception/elevation_map_loader/src/elevation_map_loader_node.cpp b/perception/elevation_map_loader/src/elevation_map_loader_node.cpp index ff3d998aabc0b..096e084a70286 100644 --- a/perception/elevation_map_loader/src/elevation_map_loader_node.cpp +++ b/perception/elevation_map_loader/src/elevation_map_loader_node.cpp @@ -141,7 +141,8 @@ void ElevationMapLoaderNode::publish() try { is_bag_loaded = grid_map::GridMapRosConverter::loadFromBag( *data_manager_.elevation_map_path_, "elevation_map", elevation_map_); - } catch (rosbag2_storage_plugins::SqliteException & e) { + } catch (const std::runtime_error & e) { + RCLCPP_ERROR(this->get_logger(), e.what()); is_bag_loaded = false; } if (!is_bag_loaded) { From ca37348c7fe6fb3e4fed7fd54c06027a335bac2d Mon Sep 17 00:00:00 2001 From: Mingyu1991 <115005477+Mingyu1991@users.noreply.github.com> Date: Fri, 7 Jul 2023 07:57:00 +0900 Subject: [PATCH 102/118] feat(traffic_light_occlusion_predictor): add traffic_light_occlusion_predictor (#4050) * add traffic_light_occlusion_predictor Signed-off-by: Mingyu Li * update README Signed-off-by: Mingyu Li * update occlusion package I/F Signed-off-by: Mingyu Li * revert wrong update of README.md Signed-off-by: Mingyu Li * update perception_utils Signed-off-by: Mingyu Li * add _deg to variables and update README Signed-off-by: Mingyu Li * fix Cmakelists Signed-off-by: Shunsuke Miura --------- Signed-off-by: Mingyu Li Signed-off-by: Shunsuke Miura Co-authored-by: Shunsuke Miura --- common/perception_utils/CMakeLists.txt | 1 + .../perception_utils/prime_synchronizer.hpp | 354 ++++++++++++++++++ .../perception_utils/traffic_light_utils.hpp | 52 +++ common/perception_utils/package.xml | 2 + .../src/traffic_light_utils.cpp | 79 ++++ .../ros/pcl_conversion.hpp | 72 ++++ common/tier4_autoware_utils/package.xml | 1 + .../CMakeLists.txt | 32 ++ .../README.md | 36 ++ ...affic_light_occlusion_predictor.param.yaml | 11 + .../images/occlusion.png | Bin 0 -> 281848 bytes .../nodelet.hpp | 102 +++++ .../occlusion_predictor.hpp | 95 +++++ ...affic_light_occlusion_predictor.launch.xml | 20 + .../package.xml | 36 ++ .../src/nodelet.cpp | 138 +++++++ .../src/occlusion_predictor.cpp | 250 +++++++++++++ 17 files changed, 1281 insertions(+) create mode 100644 common/perception_utils/include/perception_utils/prime_synchronizer.hpp create mode 100644 common/perception_utils/include/perception_utils/traffic_light_utils.hpp create mode 100644 common/perception_utils/src/traffic_light_utils.cpp create mode 100644 common/tier4_autoware_utils/include/tier4_autoware_utils/ros/pcl_conversion.hpp create mode 100644 perception/traffic_light_occlusion_predictor/CMakeLists.txt create mode 100644 perception/traffic_light_occlusion_predictor/README.md create mode 100644 perception/traffic_light_occlusion_predictor/config/traffic_light_occlusion_predictor.param.yaml create mode 100644 perception/traffic_light_occlusion_predictor/images/occlusion.png create mode 100644 perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp create mode 100644 perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/occlusion_predictor.hpp create mode 100644 perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml create mode 100644 perception/traffic_light_occlusion_predictor/package.xml create mode 100644 perception/traffic_light_occlusion_predictor/src/nodelet.cpp create mode 100644 perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp diff --git a/common/perception_utils/CMakeLists.txt b/common/perception_utils/CMakeLists.txt index 338874a41a3f7..146591c865b5d 100644 --- a/common/perception_utils/CMakeLists.txt +++ b/common/perception_utils/CMakeLists.txt @@ -8,6 +8,7 @@ find_package(Boost REQUIRED) ament_auto_add_library(perception_utils SHARED src/predicted_path_utils.cpp + src/traffic_light_utils.cpp src/conversion.cpp ) diff --git a/common/perception_utils/include/perception_utils/prime_synchronizer.hpp b/common/perception_utils/include/perception_utils/prime_synchronizer.hpp new file mode 100644 index 0000000000000..5af44595b8fb2 --- /dev/null +++ b/common/perception_utils/include/perception_utils/prime_synchronizer.hpp @@ -0,0 +1,354 @@ +// 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 PERCEPTION_UTILS__PRIME_SYNCHRONIZER_HPP_ +#define PERCEPTION_UTILS__PRIME_SYNCHRONIZER_HPP_ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace perception_utils +{ + +/** + * @brief This class implemented a multi-topic approximate time synchronizer. + * Different from message_filters::sync::ApproximateTime, this class assumes there's a primary topic + * and more than one secondary topics and the registered callback function will always been called + * for every primary topic message, while for message_filters::sync::ApproximateTime, the callback + * function will be called only when all topics are synchronized. + * + * For every primary topic message M1, when this class receives it, the class would check whether it + * could gather one message of every secondary topic whose timestamp is similar to that of M1. If + * yes, the registered callback function would be called at once with M1 and the gathered messages. + * Otherwise, it would wait for some time. After that, the class would collect secondary messages + * again. For secondary topics that can't find any message with similar timestamp to M1, nullptr + * would be used instead and the registered function would be called. + * + * This class assumes the message types of the primary topic and secondary topics are defined during + * compile-time. It should be noted that the registered callback function is too slow, it would + * block the thread and the primary message couldn't be received. + * + * @tparam PrimeMsgT Primary topic message type + * @tparam SecondaryMsgT Secondary topic message types + */ +template +class PrimeSynchronizer +{ + typedef double StampT; + +public: + /** + * @brief Construct a new Prime Synchronizer object + * + * @param node_ptr node handler pointer + * @param topics topic vector. topics[0] corresponds to primary topic and the others + * correspond to secondary topics + * @param qos qos vector. configured for every topic + * @param callback registered callback function, would be called when the messages are + * synchronized + * @param max_delay_t maximum timestamp different (seconds) between primary topic message and + * any other secondary topic message + * @param max_wait_t maximum wait time (seconds) before the messages are synchronized + */ + PrimeSynchronizer( + rclcpp::Node * node_ptr, const std::vector & topics, + const std::vector & qos, + std::function + callback, + StampT max_delay_t = 0.2, StampT max_wait_t = 0.1) + : node_ptr_(node_ptr), callback_(callback), max_delay_t_(max_delay_t), max_wait_t_(max_wait_t) + { + assert((topics.size() == sizeof...(SecondaryMsgT) + 1) && "Incorrect topic number"); + assert(topics.size() == qos.size() && "topic size not equal to qos size!"); + prime_subscriber_ = node_ptr_->create_subscription( + topics[0], qos[0], std::bind(&PrimeSynchronizer::primeCallback, this, std::placeholders::_1)); + initSecondaryListener( + std::vector(topics.begin() + 1, topics.end()), + std::vector(qos.begin() + 1, qos.end())); + std::chrono::nanoseconds wait_duration(static_cast(1e9 * max_wait_t)); + timer_ = rclcpp::create_timer( + node_ptr_, node_ptr_->get_clock(), wait_duration, + std::bind(&PrimeSynchronizer::timerCallback, this)); + timer_->cancel(); + } + +private: + /** + * @brief initialize the secondary topic subscribers. + * Have to use template recursion method to indexing the subscriber tuple + * + * @tparam Idx secondary subscriber tuple index + * @param topics topics vector + * @param qos qos vector + */ + template + void initSecondaryListener( + const std::vector & topics, const std::vector & qos) + { + if constexpr (Idx < sizeof...(SecondaryMsgT)) { + typedef std::tuple_element_t> type; + std::get(sec_subscriber_) = node_ptr_->create_subscription( + topics[Idx], qos[Idx], + std::bind(&PrimeSynchronizer::secondaryCallback, this, std::placeholders::_1)); + initSecondaryListener(topics, qos); + } + } + + /** + * @brief Collect the Idx-th secondary messages with similar timestamp to prime message, + * which is stored in argv[0] and write to argv[Idx + 1] + * + * @tparam Idx secondary subscriber tuple index + * @param argv output tuple + */ + template + void collectSecondaryMsg( + std::tuple & + argv) + { + if constexpr (Idx < sizeof...(SecondaryMsgT)) { + /* + if can't find any message for this topic, write nullptr + */ + if (std::get(sec_messages_).empty()) { + std::get(argv) = nullptr; + } else { + StampT prime_stamp = convertStampFormat(std::get<0>(argv)->header.stamp); + StampT min_delay = std::numeric_limits::max(); + auto best_sec_msg = std::get(sec_messages_).begin()->second; + /* + find the message with closest timestamp to primary message + */ + for (const auto & sec_msg_p : std::get(sec_messages_)) { + StampT delay = std::abs(prime_stamp - sec_msg_p.first); + if (delay < min_delay) { + min_delay = delay; + best_sec_msg = sec_msg_p.second; + } + } + std::get(argv) = min_delay < max_delay_t_ ? best_sec_msg : nullptr; + } + collectSecondaryMsg(argv); + } + } + + /** + * @brief check if all messages in argv are valid (not equal to nullptr) + * + * @tparam Idx + * @param argv + * @return true All messages are not nullptr + * @return false At least one message in the tuplc is nullptr + */ + template + bool isArgvValid( + const std::tuple< + typename PrimeMsgT::ConstSharedPtr, typename SecondaryMsgT::ConstSharedPtr...> & argv) + { + if constexpr (Idx < sizeof...(SecondaryMsgT) + 1) { + return (std::get(argv) != nullptr) && isArgvValid(argv); + } + return true; + } + + inline StampT convertStampFormat(const std_msgs::msg::Header::_stamp_type & stamp) + { + return rclcpp::Time(stamp).seconds(); + } + + /** + * @brief callback function when primary message is received + * + * @param msg + */ + void primeCallback(const typename PrimeMsgT::ConstSharedPtr msg) + { + prime_cnt++; + timer_->cancel(); + assert(prime_messages_.size() <= 1); + /* + if there are old prime messages waiting for synchronization with secondary messages, + stop waiting and call the registered callback function with prime message and synchronized + secondary messages. For secondary topics that are not synchronized, use nullptr. + */ + for (auto & p : prime_messages_) { + tryCallback(p.first, true); + } + prime_messages_.clear(); + /* + update the prime messages + */ + StampT stamp = convertStampFormat(msg->header.stamp); + prime_messages_.insert(std::make_pair(stamp, msg)); + /* + check if secondary messages are all ready to synchronize with prime message. + If yes, process it immediately + */ + if (tryCallback(stamp, false)) { + prime_messages_.clear(); + } else { + timer_->reset(); + } + // RCLCPP_INFO_STREAM(node_ptr_->get_logger(), "primary message count = " << prime_cnt); + } + + /** + * @brief callback function when secondary message is received. + * + * @tparam M Type of the secondary message + * @tparam Idx Idx of the type + * @param msg + */ + template + void secondaryCallback(const typename M::ConstSharedPtr msg) + { + /* + insert the new secondary message + */ + StampT stamp = convertStampFormat(msg->header.stamp); + auto & msg_map = std::get(sec_messages_); + msg_map.insert(std::make_pair(stamp, msg)); + assert(prime_messages_.size() <= 1); + /* + check if any prime message can gather all secondary messages. + */ + for (auto it = prime_messages_.begin(); it != prime_messages_.end();) { + /* + Try to synchronize. If succeeds, remove the handled primary message + */ + if (tryCallback(it->first, false)) { + timer_->cancel(); + it = prime_messages_.erase(it); + } else { + it++; + } + } + + /* + this should not happen. Just in case. + */ + if (prime_messages_.empty() && msg_map.empty()) { + RCLCPP_ERROR_STREAM(node_ptr_->get_logger(), "Empty prime_messages and secondary_messages"); + return; + } + /* + remove old secondary messages. + */ + StampT stamp_thres = + prime_messages_.empty() ? msg_map.rbegin()->first : prime_messages_.begin()->first; + for (auto it = msg_map.begin(); it != msg_map.end();) { + if (stamp_thres - it->first > max_delay_t_) { + it = msg_map.erase(it); + } else { + it++; + } + } + } + + /** + * @brief Timer callback. The maximum wait time exceeds. Handle all stored primary messages. + * + */ + void timerCallback() + { + timer_->cancel(); + assert(prime_messages_.size() <= 1); + for (auto & p : prime_messages_) { + tryCallback(p.first, true); + } + prime_messages_.clear(); + } + + /** + * @brief Try to synchronize. If ignoreInvalidSecMsg is set to true, + * the registered function would be called with the primary message with given timestamp and + * collected secondary messages even if not all secondary messages are collected. Otherwise, the + * registered function would not be called except all secondary messages are collected. + * + * @param stamp + * @param ignoreInvalidSecMsg + * @return true + * @return false + */ + bool tryCallback(StampT stamp, bool ignoreInvalidSecMsg = true) + { + if (prime_messages_.count(stamp) == 0) { + return true; + } + std::tuple argv; + std::get<0>(argv) = prime_messages_[stamp]; + collectSecondaryMsg(argv); + if (ignoreInvalidSecMsg || isArgvValid(argv)) { + std::apply(callback_, argv); + return true; + } + return false; + } + /** + * @brief node pointer + * + */ + rclcpp::Node * node_ptr_; + /** + * @brief The registered callback function that would be called when the prime message and sub + * messages are synchronized or timeout + * + */ + std::function + callback_; + /** + * @brief the prime message subscriber + * + */ + typename rclcpp::Subscription::SharedPtr prime_subscriber_; + /** + * @brief the secondary message subscriber tuple + * + */ + std::tuple::SharedPtr...> sec_subscriber_; + /** + * @brief map to store the prime messages using timestamp of the messages as key. + * + */ + std::map prime_messages_; + rclcpp::TimerBase::SharedPtr timer_; + /** + * @brief tuple of maps to store the secondary messages using timestamp of the messages as key + * + */ + std::tuple...> sec_messages_; + /* + maximum wait time (seconds) before the secondary messages are collected + */ + double max_wait_t_; + /* + maximum delay time (seconds) between a secondary message and the primary message + */ + double max_delay_t_; + int prime_cnt = 0; +}; + +} // namespace perception_utils + +#endif // PERCEPTION_UTILS__PRIME_SYNCHRONIZER_HPP_ diff --git a/common/perception_utils/include/perception_utils/traffic_light_utils.hpp b/common/perception_utils/include/perception_utils/traffic_light_utils.hpp new file mode 100644 index 0000000000000..be21536953ce7 --- /dev/null +++ b/common/perception_utils/include/perception_utils/traffic_light_utils.hpp @@ -0,0 +1,52 @@ +// 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 PERCEPTION_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ +#define PERCEPTION_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ + +#include "tier4_perception_msgs/msg/traffic_light_element.hpp" +#include "tier4_perception_msgs/msg/traffic_light_roi.hpp" +#include "tier4_perception_msgs/msg/traffic_signal.hpp" + +#include +#include +#include +#include + +namespace perception_utils +{ + +namespace traffic_light +{ + +bool isRoiValid( + const tier4_perception_msgs::msg::TrafficLightRoi & roi, uint32_t width, uint32_t height); + +void setRoiInvalid(tier4_perception_msgs::msg::TrafficLightRoi & roi); + +bool isSignalUnknown(const tier4_perception_msgs::msg::TrafficSignal & signal); + +void setSignalUnknown(tier4_perception_msgs::msg::TrafficSignal & signal, float confidence = -1); + +tf2::Vector3 getTrafficLightTopLeft(const lanelet::ConstLineString3d & traffic_light); + +tf2::Vector3 getTrafficLightBottomRight(const lanelet::ConstLineString3d & traffic_light); + +tf2::Vector3 getTrafficLightCenter(const lanelet::ConstLineString3d & traffic_light); + +} // namespace traffic_light + +} // namespace perception_utils + +#endif // PERCEPTION_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ diff --git a/common/perception_utils/package.xml b/common/perception_utils/package.xml index bc1d1b8b6bece..2fa9ccfbb430c 100644 --- a/common/perception_utils/package.xml +++ b/common/perception_utils/package.xml @@ -16,9 +16,11 @@ autoware_auto_perception_msgs geometry_msgs interpolation + lanelet2_extension libboost-dev rclcpp tier4_autoware_utils + tier4_perception_msgs ament_cmake_ros ament_lint_auto diff --git a/common/perception_utils/src/traffic_light_utils.cpp b/common/perception_utils/src/traffic_light_utils.cpp new file mode 100644 index 0000000000000..5ff3b3d422945 --- /dev/null +++ b/common/perception_utils/src/traffic_light_utils.cpp @@ -0,0 +1,79 @@ +// 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 "perception_utils/traffic_light_utils.hpp" + +namespace perception_utils +{ + +namespace traffic_light +{ + +bool isRoiValid( + const tier4_perception_msgs::msg::TrafficLightRoi & roi, uint32_t width, uint32_t height) +{ + uint32_t x1 = roi.roi.x_offset; + uint32_t x2 = roi.roi.x_offset + roi.roi.width; + uint32_t y1 = roi.roi.y_offset; + uint32_t y2 = roi.roi.y_offset + roi.roi.height; + return roi.roi.width > 0 && roi.roi.height > 0 && x1 < width && y1 < height && x2 < width && + y2 < height; +} + +void setRoiInvalid(tier4_perception_msgs::msg::TrafficLightRoi & roi) +{ + roi.roi.height = roi.roi.width = 0; +} + +bool isSignalUnknown(const tier4_perception_msgs::msg::TrafficSignal & signal) +{ + return signal.elements.size() == 1 && + signal.elements[0].shape == tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN && + signal.elements[0].color == tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; +} + +void setSignalUnknown(tier4_perception_msgs::msg::TrafficSignal & signal, float confidence) +{ + signal.elements.resize(1); + signal.elements[0].shape = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + signal.elements[0].color = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + // the default value is -1, which means to not set confidence + if (confidence >= 0) { + signal.elements[0].confidence = confidence; + } +} + +tf2::Vector3 getTrafficLightTopLeft(const lanelet::ConstLineString3d & traffic_light) +{ + const auto & tl_bl = traffic_light.front(); + const double tl_height = traffic_light.attributeOr("height", 0.0); + return tf2::Vector3(tl_bl.x(), tl_bl.y(), tl_bl.z() + tl_height); +} + +tf2::Vector3 getTrafficLightBottomRight(const lanelet::ConstLineString3d & traffic_light) +{ + const auto & tl_bl = traffic_light.back(); + return tf2::Vector3(tl_bl.x(), tl_bl.y(), tl_bl.z()); +} + +tf2::Vector3 getTrafficLightCenter(const lanelet::ConstLineString3d & traffic_light) +{ + tf2::Vector3 top_left = getTrafficLightTopLeft(traffic_light); + tf2::Vector3 bottom_right = getTrafficLightBottomRight(traffic_light); + return (top_left + bottom_right) / 2; +} + +} // namespace traffic_light + +} // namespace perception_utils diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/pcl_conversion.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/pcl_conversion.hpp new file mode 100644 index 0000000000000..c66a63eb1ac51 --- /dev/null +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/pcl_conversion.hpp @@ -0,0 +1,72 @@ +// 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 TIER4_AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ +#define TIER4_AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ + +#include +#include + +#include + +namespace tier4_autoware_utils +{ +/** + * @brief a faster implementation of converting sensor_msgs::msg::PointCloud2 to + * pcl::PointCloud and transform the cloud + * + * @tparam Scalar + * @param cloud input PointCloud2 message + * @param pcl_cloud output transformed pcl cloud + * @param transform eigen transformation matrix + */ +template +void transformPointCloudFromROSMsg( + const sensor_msgs::msg::PointCloud2 & cloud, pcl::PointCloud & pcl_cloud, + const Eigen::Matrix & transform) +{ + // Copy info fields + pcl_conversions::toPCL(cloud.header, pcl_cloud.header); + pcl_cloud.width = cloud.width; + pcl_cloud.height = cloud.height; + pcl_cloud.is_dense = cloud.is_dense == 1; + + pcl::MsgFieldMap field_map; + std::vector msg_fields; + pcl_conversions::toPCL(cloud.fields, msg_fields); + pcl::createMapping(msg_fields, field_map); + + // transform point data + std::uint32_t num_points = cloud.width * cloud.height; + pcl_cloud.points.resize(num_points); + std::uint8_t * cloud_data = reinterpret_cast(&pcl_cloud.points[0]); + pcl::detail::Transformer tf(transform); + + for (std::uint32_t row = 0; row < cloud.height; ++row) { + const std::uint8_t * row_data = &cloud.data[row * cloud.row_step]; + for (std::uint32_t col = 0; col < cloud.width; ++col) { + const std::uint8_t * msg_data = row_data + col * cloud.point_step; + for (const pcl::detail::FieldMapping & mapping : field_map) { + const float * msg_ptr = reinterpret_cast(msg_data); + float * pcl_ptr = reinterpret_cast(cloud_data + mapping.struct_offset); + tf.se3(msg_ptr, pcl_ptr); + } + cloud_data += sizeof(pcl::PointXYZ); + } + } +} + +} // namespace tier4_autoware_utils + +#endif // TIER4_AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ diff --git a/common/tier4_autoware_utils/package.xml b/common/tier4_autoware_utils/package.xml index ff3fa65f034b3..fd9b315f8e4d5 100644 --- a/common/tier4_autoware_utils/package.xml +++ b/common/tier4_autoware_utils/package.xml @@ -19,6 +19,7 @@ diagnostic_msgs geometry_msgs libboost-dev + pcl_conversions pcl_ros rclcpp tf2 diff --git a/perception/traffic_light_occlusion_predictor/CMakeLists.txt b/perception/traffic_light_occlusion_predictor/CMakeLists.txt new file mode 100644 index 0000000000000..481561ed92be8 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/CMakeLists.txt @@ -0,0 +1,32 @@ +cmake_minimum_required(VERSION 3.14) +project(traffic_light_occlusion_predictor) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Eigen3 REQUIRED) +find_package(PCL 1.8 REQUIRED) + +include_directories( + SYSTEM + ${EIGEN3_INCLUDE_DIR} + ${PCL_INCLUDE_DIRS} +) + +ament_auto_add_library(traffic_light_occlusion_predictor SHARED + src/nodelet.cpp + src/occlusion_predictor.cpp +) + +rclcpp_components_register_node(traffic_light_occlusion_predictor + PLUGIN "traffic_light::TrafficLightOcclusionPredictorNodelet" + EXECUTABLE traffic_light_occlusion_predictor_node +) + +link_directories(${PCL_LIBRARY_DIRS}) +target_link_libraries(traffic_light_occlusion_predictor ${PCL_LIBRARIES}) + +ament_auto_package(INSTALL_TO_SHARE + config + launch +) diff --git a/perception/traffic_light_occlusion_predictor/README.md b/perception/traffic_light_occlusion_predictor/README.md new file mode 100644 index 0000000000000..312f9abccc464 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/README.md @@ -0,0 +1,36 @@ +# The `traffic_light_occlusion_predictor` Package + +## Overview + +`traffic_light_occlusion_predictor` receives the detected traffic lights rois and calculates the occlusion ratios of each roi with point cloud. + +For each traffic light roi, hundreds of pixels would be selected and projected into the 3D space. Then from the camera point of view, the number of projected pixels that are occluded by the point cloud is counted and used for calculating the occlusion ratio for the roi. As shown in follow image, the red pixels are occluded and the occlusion ratio is the number of red pixels divided by the total pixel numbers. + +![image](images/occlusion.png) + +If no point cloud is received or all point clouds have very large stamp difference with the camera image, the occlusion ratio of each roi would be set as 0. + +## Input topics + +| Name | Type | Description | +| -------------------- | --------------------------------------------------- | ------------------------ | +| `~input/vector_map` | autoware_auto_mapping_msgs::HADMapBin | vector map | +| `~/input/rois` | autoware_auto_perception_msgs::TrafficLightRoiArray | traffic light detections | +| `~input/camera_info` | sensor_msgs::CameraInfo | target camera parameter | +| `~/input/cloud` | sensor_msgs::PointCloud2 | LiDAR point cloud | + +## Output topics + +| Name | Type | Description | +| -------------------- | --------------------------------------------------------- | ---------------------------- | +| `~/output/occlusion` | autoware_auto_perception_msgs::TrafficLightOcclusionArray | occlusion ratios of each roi | + +## Node parameters + +| Parameter | Type | Description | +| ------------------------------------ | ------ | ------------------------------------------------------------- | +| `azimuth_occlusion_resolution_deg` | double | azimuth resolution of LiDAR point cloud (degree) | +| `elevation_occlusion_resolution_deg` | double | elevation resolution of LiDAR point cloud (degree) | +| `max_valid_pt_dist` | double | The points within this distance would be used for calculation | +| `max_image_cloud_delay` | double | The maximum delay between LiDAR point cloud and camera image | +| `max_wait_t` | double | The maximum time waiting for the LiDAR point cloud | diff --git a/perception/traffic_light_occlusion_predictor/config/traffic_light_occlusion_predictor.param.yaml b/perception/traffic_light_occlusion_predictor/config/traffic_light_occlusion_predictor.param.yaml new file mode 100644 index 0000000000000..d0230e2b12c42 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/config/traffic_light_occlusion_predictor.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + azimuth_occlusion_resolution_deg: 0.15 # degree + elevation_occlusion_resolution_deg: 0.08 # degree + max_valid_pt_dist: 50.0 + # the node would wait at most max_wait_t seconds for cloud whose timestamp different with the image is less than max_image_cloud_delay. + # If no cloud with timestamp difference smaller than max_image_cloud_delay is found, the node would publish occlusion ratio of all + # traffic lights as 0 + max_image_cloud_delay: 0.5 + max_wait_t: 0.05 + max_occlusion_ratio: 50 diff --git a/perception/traffic_light_occlusion_predictor/images/occlusion.png b/perception/traffic_light_occlusion_predictor/images/occlusion.png new file mode 100644 index 0000000000000000000000000000000000000000..94e2dc4469f3553b4854e8c281962573462f8be3 GIT binary patch literal 281848 zcmV)OK(@b$P)ZgXgFbngSdJ^%m!Gig*P; z8w3bR4+2d8&;R>>n3*9zXdwAZaDnD?I*FeiYw_$(*sd6ozdbuUM`bvWbc59IzT{99!Ci~jgO zfrfX}_>;PBfnW0aUy+Tk8%%ukp9udA2JL?$oc06)_z(I8Tfb!=_jx$8WqCo-7;}~1(ojchPwryR(j81? zm0O-aJy57ecOFOvNbE=y^jro^*d>iR&?7l8a~+8BaU$gXpwI_3U)!CH%$H$IomP~+mqL&DmhMfMwD9@XbE=!l`>7(l#XU6PR__<;8UOkx+DBa9UfxZo2r#s4x zpM@3w(g|~Zl2<=C(o$ZgOTf7sU^RH*pVh$+A`r0x2=lHIA`wCm@DM^k2mz4-Cayq0Zt%eDK5opm(C{#+jQ>3vGYYo=H|um(Y^ zL4&iAxpxCQdDsDWYOx&<>u5CIyGXx2`ge@7m0TZX#rOudNB`Txr|_@up&B>U@1GIG zFZi&_?`8XV-moOs@4Ux5|J~v5=;bTk`A-euy=vEUdf%h?^MO)YDzvp#OG}!md$PZ} z%61H?zw5`O#xQ^g@{KKua-~qm%Bjz=H#lfn26nFh&MUE?i%Ave%f_(#CnD$vMrBR+ zJsE!*Ry6!%q-3SE-=oL1@ej-4RLmH8V#HliGT3;luJ#Ag>c?$8jwpVXhOdWrsb6#L z`kB+ar|n8TJ+5%q{bEk3_Ub?F3sZjQV{GSxA?s)Ry7chG%OT$vR^aIDzWfao1Uv*e z1_C5Xz(foYDF(z45o1IO5wTte06-}MBuXhLML={X%Y9+@F(WNC;T@{CGuy~^UM2k=^_w1o@;%K2HqS=>nzYoh%9M1<=@Z4 zDBIryhkpmiyiWZCxjnqw4D_Gz+_@}&gAWHjnyGA2=XYm5oge&no8LT?t-JH5DFgWT zmFToxUlK#FANe?(r835kz=12Hd+gt6JG1=XqdGO0z6n%T!~G)73L@MTC9=wOhJ7X0 z39?14o(Tgh8abVrk?2Qq-Y}9TdM=`_Q|N`mdugos+QLNjq8Q}+(2FcipK&(R_{<6b z65ccxtgm+hir=GYNynhnPiR;^`$7ivMxihDkcltTvM>1ib8B({hyoB86bKXufr1=E zz!oD?jM!4b786oEMx>MghJpoFpiq#r97`_9CF96hj|V6NM+P_-6s4A#!8A<&eA%8q zSM%(E*nbX07%?Bn;-w6uF-G)a$5f36raYW3Tm_%U2weI&yS1p3K~^twoN>}0IVpPi z{y#8W&~|Mq{Y0*>(;V%$rT(fHvwmAq*TuZBCEwzmvphcHjaLt^%l3Bw?azVVPs7q9 zF^h>QENzCL6VYdAZSIUdQAyIw}1Ld3QF zIJ#Uzt=xD91V8IYj^DbME&gor=~XWDQ9bG#-PILHJ5OW9*Q-QanFpM72_xPW)~>B) zAaSO!uHm1xY*#M}-g&3(`<$-%e);T0Zdc`9yPlolz3dDAK2LEJ00aPm#1j#L5ZW}R zv_;&~hTE3pm^N(NhTA4_%!HD~^Kj&hoQpda9Qi;z4jji0$^abzQ$Zn{A8pg1bc)kr zVCOviOy!w^`qUWv{Dn6{^-#Z2noAkxKm=$lcTE3H3hTVTS{@xAuLjJnEcZ#YFZ$c6 z`%W_T{qWA(ng2+5)97EvFYcUx(6ywQb!=Dv^9%F+4@O#E*)wnP&gwBsUJS zvl`<;gfki{kTCF|aqg+^IMdS#yAYw3o`swoFV@eyB;UpYOC$U`sz)t+dh0aL%je#t zVI--SCYRJqvE3-jiP_;Bv)X*K5g}!}YJe9NYJ!)>cy0>(?A@z;-c&q1#k~K%JT?lF zix)kk(+QyeKn%BOgp2GuyJv0u4HKTGFan%WIi8H+zesB&6w9W&uG80bM2$#)wN7Kz z7rX=>JQ4%~2Li_cL>8|^RIfw~h*5yVc1yTzH{5SGJhlz@+YNWUW`=km6hIt@{&L1~ z6zoUDegx1Cz(527G5{0^fT#J5bjZ3hx)fTD6?(?@Jl^|5}K-H8~at5Eo6}%R_g^8aWy?G^bK9`_nD|%0GHl#GTp8^e2hO07bINY_z#6EnZaZH zb>W!&v#&C{=v@P^cShXX`s4znEQ@i)J13cb)RsRRl=uKQy;0|%-20QT)OJ(OS3u_@ zoVFBTXDcp7FhMOh8}0929>|6&r z-1$)WHd@_;Xcf%0%nk*z6?YX@f_!u$5>mOdV&^bt*7h=1XCh`Zdw-TuL&6IKzgH~d4oTs;} zqR~b3Des*(`Z|pTUDs`NE=S$skdMOr_*DX*+e5G49?JB#u=!iz+}`N8CUG@9Ivc4nR`2B56F=GzCnoNdrhc685+p8@IFbL_ooT#aHlP zKqA?Khm%zsJ!BW#3t3)t=v+dbm`*l@q!@O8g|nUK}{kkV1XLyQ^m$Ow^C<`!fe zI1msDfeHXykj?h%fy4+Rr1*n!d{_TZb`*__vZ%p}q)vqB@>@hxIG1tli5JhvR$EVB;ok-(R1GlM7VA)xO6}i-}NKiBX znG{5zI56SPgYFhW9zwJQf8+Ef4sqE;GWq3t6606zZ=h+D@jqE%Lfz zPY+W1eBTXxk^P%#jq3EGy|3ltCoQvjafSy2J?fC5f7Dvs!#3j<9Wku;kgo+y~;dYyV7Kt<0>1rjBc1(29Q zMVs~nH3G;^+W8nvO4d#`fQwJVAW6>5hgVUrfyC=O?}t|-RactowIRvx-}IT*`;G5t zqUW5vW=SsVaw1~}5zF{I@6%;0zyIcM(`m!I~C6QYlA&TX`9clLr0TL^;XS0MxSy6&G#>> z*sB;UUdC+v{gokuPJXQVY2&R^>B}oFzo7C=t*r8Rv(DP(VEw<6+pDy$%JY)OtDb%p z{uZEE!##^Q9St6gxaHRAQ?Wm2t1h8F(K9pVQXgx6XMpZAb>(>dk2=)~Ft1V3JJVf1 ztKTz0bIlJ|;S`uJ?2B$q!5d_scA16j8>C>1;nrTJzpCef1w_bFg&+Vz?}>xJ(&0G= z>;D9u{={{sy3^X!^%IF8172lP%8fZpxOgvwfCo7iD&U}T4qz}CrH+I(4~3;EhJ;qc zC6MsvSB&^hZ}_CgoEs{y`|4j&cbB=2LSs4c<&4mEKc8bxi{Z@3iX=u6K&ykhy(VrJ zupFXAp(D?u-H>L?E$9Ya*Z^VpmT@lq`UQ!7-!6j1qU*8kRHahOmSt!#lcHpuyta zH1vEWeQKX{V8SQnuK3NgJ`98TjlOUzfHA!H>Vt({QtU5!gV5*jN;GtJF`J#EaoiCx zD~&F}^ACUyG)~F?1W24&_iw&_^5U5>eFY|(NOXGbB~2f+nT6WbXsWW8x_Hcs7TFGQ z@3jQg3iw&o^MVlWPDgpu_k=muj*^!|`MSIS6PJi$p=*{GJ&33&EonTTirjDZv7%|x za_z@x?NyHsM4;%A!3rdZL-kfL>)K>y0VO&e%A5%VcWGs-9i-J$8^~iMdoh3%=!n`8 zdd={!@TY--3L>(&(Sx|tW%m$2<*9V<^zA)@h!;R&sOq&bd?78CVHN+TVewXIfb8dC z)zKDLlj43OQ)jF%1=+INXgFR|Hw(O#1YD5x&YkKqeMgb~>CV$17`-N2$@8^$FS_*R z>Kc+AjXKBpm9KqTeY$6OY#CpZUcn-N&g*rC$}?xJ(PoUS%RUh{q($z}q#WK|Jm^NQ zI{VJWt_-GL?Nn(#wF?2VCL&~T$Y6>n$Y7m{R5)VefLjST3`mrOgEwT}k@-MCP{SVr zBp5)HGKLUP5Ri)eLLtz>Kq}&mhzD{waL|EV1W2?EF(89G|(Qsz;o(3LIuMpO1n%1H$4orByW}gNep`G~F zXJ?`HenC#2f2&#+71)e>7eDdYI_pcSs6V-~OILN)HPso2n3{8-;!Mo1?dO)l1&_3c zJ_izA-m8kOqDA$hM=G!pzh!VTfE?bg|9W%H5Qho-`mliYju{I*p|l%*^DUn zVLH>cb!R5^MpO_Xzf4&?6MCPC<=g{{YGL^*>y53cS}(xF()eA5Rs1^wuczt!&P7^( zX1%^lj4%rF4>DYWu_5MC*}lq)rblMkPbV~-&@;qO9ez1V*y2VJ@_slkYe&OiInVs< zN3zyw_A=QSbnNpOjF!%2aKV`?+oKcsD|VJ-erS}Z><*6L|CJg?1)DUFq^KJ9DG z8(Kf;N*6#vw+XgN9((?(zgmsV(}7+aS?}JzteaDN?8G2`0VaG8{*)N%|G2n8+pM~s zKkpm&ng(iFjy8CE`%OJQObdG3f}p9`bMDN_UuZ{XlzRDHd&DaOy0Wb7k%f*OY>rtf z4dCZv5HVKp87H09?@0S#Gqex5)gP&SObQYR0YSk8I95<0N7SiKYzwk2m&$}qcvrhp z#Tr-220%d-NT3NdMIN3(35+82IuPN&1Z8A88mOrEbln88j*68*fmKmARNB}bR|5Bi za+=v=@$BN=Q@J)beWzO9?s*?R`y!F^T6i;)WqJAKGppJ1%P>f|mB8~6Yx(dFI9y2O z<#VfNUW19VuHUCJYI;-RgFvX~*6pqY9m{kBqq#HohIjl2t*8lOZ*QIHDH|!O*>n%{ zB#Y~jx{|kd=PU-g$SEPO(E5eUOEBRLg-(&pJUN4eu~O`OGyq&0eb!250}`Wmf&g%c zV2WT0;)Os&K|th)h={!ih%isYfg29qt4BiEhCmcR0D@iz*%1SUig+Y4AtnMP1|``c zs>B01N;*f$;te76yX!UWp~uluU-YN5{8(@Pxyhkk9?46!?;9w&>TgRU?@Zoa z$<+%UdL8}p;c5Mp%WjehysYW98QArkA=^>@dP;}}5YhAR8elBy&x+-`$D~t@#w8!w z<-q$cZe?w)!nkwPB!V3{Wz}6Hk9GCrl#J)NcTAMAJibk)wRqH*v(r~Yqb%$1gj-tf z>+?0ObDXz_yV*LU7or0c%@e`ujbMg&B{+yjn;9qp{aOi2S9f`;WpR0RvmU(B(K=45 z#CB*uSJ?a_BUVBCRs2#7!ITP3~3449Mn#X=-O}}XM zMGX$;W1YIrN;L4X7n?a5DLm`PxY8M&m81%3F@4vk~eg@$k*q zpT9_99ntD({VYvUzHB~?Dc&233%S$!So=YNX?u;EN5YL7_eA+RJrm5=#?^TZ@};bQ zTSE@|WJ#~jY9MW-bX9_xo`LpZMBVHvqp0I2yQsXpqG$Nqi}y}!nZZ(n^D?Ii!x{_~<9URKjZyN(j;ZK1FtVO?hKPS(6F zylcSRomtDG4v#57co2mN6`fPcxUBSO!jXa;8ORe?O z$y%IgeR+QJ?vU-^_1olcqo=XHfm6?4Dm^`~lB*{Vyu7&fvS?uUzJI&- z?b>WeUrE%S@%_ik@wp#58m9AhBu&$fb2v4IT#3Bx0MxY&%>DGFdSo-tD{!zQm=FrY ztz7_w04|zaC_wQ$IxULU?daNS*gu%K$gUtDt_i8CcW?R1l4tAU>0qEj)<>`{xIO_B zehWgAP6TuNc_!%3t6;oh@=@`1SLZ^l>#Q#%*YdVg8fVmbqvRr`zZaI8bEO29FL#G2 zjb-;3tiiKa$EV%^5+e)udAv|uUJ6}lksr1PFD_;^Z2U|r!@Wns3FS`Ek&>)^j+K5l zrKSoy>JpG!ZWOk1Ws8_gu74VcXhus@4r}Gv_n@J-d5xoVnLsxquTQg|OFO!nYuQ|x zO_`lA*c>-Ldjck;fLF4Fm*>`0#p0L&6o3^_a6rc1zyoAKbkQA_#P}D`VRD%O1X9lg z5dsrplrLz9`ke{}qG%8frnuc^7r`HeQs?&p@lYP$cP0?w^@CNHSkQ)7iZj@s5RNy?q_lfN_?6XJkwqzKCyCFw4T)Q$7FE z%wOZ|)U|rz>8~ZzczV?b`xN}na$P^D{jI&&O^sWIQC0)vpn-2U>8~n(9FUNKZ+LB_KLR4@sM2tl?E9|`m7uamw0La0nKYDK*cSQT}c z+62EVQ?Tt{W%s6f?H6C$w58c57Yf|phX!vPIw($$2v=cYaH-a+SFfEA^EDeoz~y$c3n?Ied9g6U$TY#?^0+y ztD=G22-W0GuuTq3s=4U~9#ojbSQ&CPk4A@=hn*c^(e45E8dUSJ*R0KGk;Yqnt11mv z8rPcL1BiakHdiIkjXqMN&UEZKxbX4%9=G%EFO6mN3Gw1wQ(*xD)sW|aLe_=`8q@>9 z=85niLS!r|nBZDYr&9P?V&#F$&WZ$e1d%_mt!*^GVt&YCV#>9q4uWt+)lRF=C7^XY5 zex-WT7)Pfz)m~iX2zn6Vr;Pb>uKLqdMt4qU&z#54a^*dpCH%7B$;v@<`>nF*SZmSu zTRqHldAV-#w;8OiU`@2wI8WQU>_fkCG@QvO89?w?c1nx3^ogu0Y3@VbGi)|{PrCsJ zHfkD8br8()re3#tG(F_XQR~ThHO9pnFn&1GvE#W<-wn==N39p_cNcX4y!TBk5mq*Zzsu z!5ctty;r5#1rsciIoA(#egCh9t6V;yfM_WH*}EU6IlQ@^axlL3P9CFCaHYV2u`XakRFt%v*-+l)*{)&Vo}QV~y4FsAl3JA1y)a zi)7a=jOAt?wu$v+KkqR8RZpBNhO6CCF`lqMyXpI+qlHiMcQwWZ001BWNklZF>YocwCgyz?mifQ#jcWfJCXzD}=ZZ3TFUg(&V$>Kn=Ghg+CL)(fKgiLkjc<)se zP*bO?`_0%l0|7N{FWpC3KlaLw%`GWy|D~NU@W#Rfe4}uftKqc28I}I{B8Q35R=smL zW#3=Dh9}n_8cz_>f}i!nQ$9~>>7Ns9;p`z^RMx5<`uG)n?}YVJZ}jECfcNsm?8u4g zTDRT|^s>AqbXuHIak%8D|5G3D%b*74XiwF<5bKXw$Oc3c|cN1_Lk2N1DrgGJq1 zL3~|{?QC8IKN_#;vz5vUXpxKZ&`7VBVdHsw&g@?5D*LPtF5>OVr*X>nYujpQb}g6H zE={E+KxDg96?K-8ItfsUU{tT6tFLfj~$(%g2vGU^O0w z^0{wF)N6k<&=6VnIX5ujM#kh?E0`QH9;bAe#n2bEa|q*(?znpF+SM0#G!R!P(4Bb$ z^U{Fz&-HgsU4s*Yzm@vy@LE2banjM(KEc+2~~IB3%)ZjaZ2Bc+L^wp*DNWfCQw1>M`gSK^C?X5!6`m! zRl6W)>?^E)>xdpZs6x)*Ay>PD;O)yhgswr2u)ZxW-|r~(%BzcFeT-^Z@O#MA>8ea*4fly>XCIOFuBD z>v*W6X5AONQ{OrIwj1m0v_sm{6VJ}vb80%WFUc&=?6(>`?dqQWHMyxt+`dc%yEW#8tXy_x~hZ>8Y15{*8A&NQc%U@xM)TSklI9S1ypQ zS!bX~{$kFd6EF*NuUiK+zT1T7Xh5h(qH29wbf9%n#$x!Weom$n5I%p_d{+W_C`qr* zXjzA+EIJvmF10~nEc2zM8L-ZRU0oZkofh{BX0kRX8b^6w4L2s)CByv#sEx~*4DHfv zGMJ!>z>TtuUo~&ia2$13Fj4;n1Y((5MM^X^uwwk=&*$133pzj3s;|{emsICkGP`w_ z=QdzOUF@7UbC+FrkNQ9DosnusL)XN<9Pnb}-0+t~d>Oqik&2zzXhnBNgL|Ow7T5Iv zzz<4zAkjZF#fYx%7o@Zz)x!&g7y0=bnD4JT3awaf z%t|jDZ=F7Kkr)rq!Q{%Kb=DqXm#7C9)1ul&$1Hc(qz zbJ2AX(CJJCg#(C7o$@3eh)|z1VB!HpS7IA*)O)Fvj8cjuH2O$tQp3+Q7y-@m0QF3u z0*VSA2n|$Jce*7f3Qs_UC9l^mBd=O|W_R4oE%wU5dMTtTfuE-^%jLBQ>h2Gqwq_Vq)bB=}DJN@M*X*_X7mdgG}RFS}`ddhYJV-zUTnhBroOC49=O`+&}I^ad?C z`P~F+RWK{}Z1t{?(qjsL6?jpcQPfo_J{N`ic)3}(J*W?j>ac&qDCd?9`xwAaovP&e zDK|q}D|j&DP7fVF--*odKk)kxkEQt?&0Lq&LvoIi1&+%c~7` z47F41?DYcDR+hOuJzFev6P;J>NXyj&<0DHM@iLqZPQ0g6m)>W)u1U;k%(lKyNBXMZ zJe99?`l#~+`x>AwvHsk3B)?X6)oyct;5my?PMNwI$nk4Q{5MYOxK-^7ZU3W|kjv_- zITs>m)po}6SF)g8It{-}e>|U1RG05EPfts&hgNyDF3nc9INi}nKm^qdHv}9wFky?c zO8|$`?C??qRM@^C3MM*dWvwt*6-=^5f@AI%=GCVLWk&87bRL%XNK_Dk`XhpZ36`}I zzQT+TU9#0HQPG$?){1K#@wHc?7JoQ@6+U^kf2&suje`?od$`j+%H_?} zp)N*2Rmqh+|vD^|&Hl z%XE$43MN`DwQZ+n9+>j>yg@GBXQRpSa4z?J9@O4n%Hp;-TauBfg_7PZS6(e39g4GV zyG42G?JoK!dU5LUXKZot{(RcVIg>Z8o@>;=N0Ze`Sg=6P7XuA#1{!w;UOx-f%k&j5 zpGneLs!sekJW;1co&;jsq0a*yqtVGN>-SYY*VH?$%6R~<=iNVF~v}7qPf4n&7KEBfK7>-eeRZ|$DKlf`S z*i|4e)eB~R=HY5(=zJom-g~y@Q6>Dv{Y4JsZ~hctoWA#&NL{}-cCAM7GWD^qjL-fN zhT^HtdcoWbFSzF_XIY=rdwx#w7+MEkD-b_*$&3fX=WOTtoPGSs&s(kQgM7bGdErND z8m$Xb{EjPi$0wg}f8N(5T*Ek}NG(6=&QFBi6l!g#jmpEhf2y^CJiq4GIl~L3RPyASY-1S5LO=-s&dSo*Lnx}mccNA zN&d3`#a8!mi!4KahZvQ2U2g&Q!rwqoK9!bl25sYj4}dMXq~g-WH4p^{fQf z2WZY<2>yd=Y;8E~K-Bn$WU#9$<<^S5!9BM!jnO?3wTy*JE3fX})iGNa$eo!?&};7Q z_{`ptqZPb5W1xA`Oa>04o-WNv#GI9(tC;oxJ7Hrx_qdJ*2KPzynXL=f>68XMtvvpG zuD5k&bata=*~;C{$LVT~pK4EC3^>jC`17H>-wu&p}teosWQRs`sC}vN0~mS zGmdb5le(IPw>SJ0Alv@dyp^+8&Kg_!w_5SOPN;zg?%%dZ)_ZlJgyhRc6ae|swRj@z zdlNQ80!)e_M4td?prYC(uF~`><$OSXNw$j$EW1gCg2M6vIS&j-y$tAndVk!(X#^Cm zwC5ngO?A>Os0c%a@=)o%K}}jtfrkosH=I2?#?P$wPR#s7-$_29bbet?<7kR~7S4p< z8>2qfSuZ-~J7F|kdOwJZuYBGwJ_ES!a8sv(5Fx0+(%h}=-ti}1N!qoJoH*qoYn?=Z z78Rt`oG`=Gbqu1$+olKup!A`m*{=IyJ4NROuO3SgI!b}kf?k+TL4_!5-k@&kOsg-Y zxa;4JG;c&yBdaY4WA<(8>fg0TOMm9xs?1h>#$B{J>FcE#xG?oxg@03oCj3A< z21k$VkWKxO(SeKk2h^Q17|w&y3(p=*xPMFn9uN=^5ttFUevtwOAY>|R0}BBn*8|y4 z+g97LHx~4qRtDyH^vb(PUtmTlqFY42XqiY9SD=7M0U_v-g7Vslap$Ze&sTP=|7?y? z9rNiQQ#1q0Y_HX ztv~x@n=yMuNHYMfUATg((gDdCl<@MjGuXZHq*Ej71_O2+%Csc$stCi4R+d&KaN}|7 zu-@>lvTTrD=f_#MRl~b_p6z~04YpOR$XxY1xN-)RP(+6S00$H* z2o!25t1Vw&YWb$)*bzcR2vOYM(J>gg&Ta+LUmeMv_1ro*p;(P2U66>XNbM8f1Y0{{ zO4e80nMcA;8#tHLXKeE-tezbt{pyP5`)}tp_LUD`?=N~oYIS9F1oCua z!4gf52$(4q*!0Rp#bRhiUNs2N>SaM@U;dhFe_{$r3_LBr)ejV8b%qYA0&1gblAsw3 zl{W@srGkY5oeA2XhZ1G|LJ^sV(qtc1FyW1n1{ep+x-&kcbc$bg}gj z1-g5awrwCJQ01{02q^~jPEgl}S|KNsXK7Mcedbb7az-v0nKLrvSlf~bF-Am0q!5u} z)P5N&&#!_9e5D9~`=fm5uj#OW2ny2ggYqv?sBtp`n;|yFuY;{Q%sC@dMxor!OBV3N zuJ*p01#i~&CD*!<@28mT zDJrgJPU^d}8M;GGDnBEl$RvtVCgq#j#+UVW4I+#fKM>-728eC&rvqsnm{|dc)}zM( zjD8e&xc2q+0t;W>nzAXrQ~6tFPY?oSCOkk|fLnc4=4`MS3cx|tjDUi?QNHSk5i;x2m86!s*%yz3_t~d)~2m( zQR}JiL_Gk6 zJVC8^X+L&=#F?Eq1Bqm&vV#F+)ePl3c)8ZFz!>1j-NYe|L^+ka$r8zZ;6{~3%pY3p}W8y>qX z(nkb(@oH`EL4}WRhH(r5DI{!^8%1m}VM`HPip|&zqmbgM zz)O>Y#jwt5SnsssICkviz`;BAvRB1QAZ%g7jS{x7VT&7X+g1TZigC%GRXH;&pC9cA zHR9En01*-;0mCsNCOrl@h6+|XB>j;%6297T9EZ?w95~9315)P7@0}sxY$EfVoQ7)I zuA^Pebm!gx4+a<`lGb;kge`5-r?oDEDSU3}47U9uf0ei<8w=ye2eQ=(bOwa>wVaFA zgEJPj9z4M4^EDwyRbFgcLc)eEB&4t*rA_5zLQJXC1FO*E#Dy$T&|`xS?Yxb4+lab1 zz&rT`GYY*fZs!c|Q7bi%YJhvaX1W5+LtTN4){Q+^OGxMjN3tJGsYZUQ523%w;6OHL zJCU!K0+15l0mg}iU+H}FRkE5L`N$$ONqn$t&@lB+z()+bFi@PX_HvdmlHc+Rn! zOM5oGS8fQrKP)$P&A~Cerl7}a3^YcaVlD@6~>LYjUb|VB~+o>C|w62s7(WK zRXd)WC24w|3VN>Hc#pu#onMqIsB{$<(1*HLo0~trj$aG*w#=#=gC>P+! zG78`Xa~p}#YZl{bL&A*`ZgInwHrzH*`rDSODq6ND134df?g#c`#}hlA{KT{Dh`i&w z1W*>k*?T6sCLthkLPEk867IO+7PeYn_ifV=KtG~8l2NKrkyWtgB0m`+a*Bn9(NQ&c z{FbJzT^ICX-EYhr!pzu@U4C?6=L5SLdN^=+nrgk20aOebF6fc569W*aF5^0lse*_o zM+YdV1R$7qLggUIdE3@ifdtn- z{fV7+Jn_U{^qijv9FU7_Y{I2^y(-9MOw2p;GIjM{>FS7E$SZDgGK3%l5h(HwmY_MQ<=W?b+xLeMg93GGl;W!Rm}6`jAQTViqvFR1!d0g zYCP4Xw;za-baNd!FC|yN4YKKn%_AJlduw3A0f=S8pG)bg#5{tXXV6bW zs;OF?nb*VtEv>WcJax5=Awa^we5ml2s;CEo zxU}_pFaV)tC-Go_p{@(1$v`R_HCZrw1N%$0OYFNDn-2_o{fdlxljmGm<%< zO$eBP%xV}PB_o$Z4do(6YB;ddfq(;n4^TOPoPkWpg?sQ29H0o&?{0j<9UJas2G$Mt z?S|X!hWqV?pp4fU*xageKMs6{C!X}gZ~n&b{EbLY5Wc~MfPA2o0@A5gV|x%063Iy4 zoo{&1L+UHuao_HE-0$M82oWKkOh0j>Qb)a>=G7*idQHWxTey}Xrm z#T`|YyD3%QPpOY5p7<_i-0mRWfwEU4p^m5(as6^>fZ`Pa!MqQ4jvh>eECzoC5heo* z0YwIIKvcm5RWPCag3?cEDuY)dM}*Ack>K{>xe6x0GJ;E+fC$|1MR$C~JHEC%9`_rz znCcX^zO3UO=quAz@;nY1m4DI`zsqm@&c6}&sMEPrftP|ng!^{K7d`M59(be&zP1N$ zn*i2Z+6LYB0Q<4y zo4)bHH@^8B-{l+M$G7OvLOAjPzh0z`5ThE?Q+91Dj_dAk#X(+s*UFI6HX(TyksSm4*{H^PEBKER_a;W{%KxGHmxi`0bU6>6LQ^Hp6 zxZ{C4J@AOaKlkm9`~8mFc5nKC#?s8CTdlbh!&~K*8wfG^U${79IH>$;U?PSHG3p62 zVbJQWNp6#oG7xo$$Jph?uuT!jr5oz6PSdOTpaKtTBlDIQ^;FBiPBZrFS|XtGfIk|z z6wu=9kL%C8&jL==>#KDqbtTV$sColq5KmYPN$W68K%ySFmQ3RoHj_Sh90#7^Tl?e_ z-{l+6{4GF5*OavZBd#F7_&(Wj!Z>ntZqtnrr%9~gc-FxdK!V5B)h=E!Ld&UJkJ`>nBV}JJjvcujgk24nG1C@4a(YB_~hLc`OvkDGgU7 zO_tR;;Cep{+%c!Hy7;aB{^*Y<_G8tAue z>(a1uh8f&k-K05ZnXX}OQ#!Ec1A95}%sV0-2rxr60QmqP1j zJMMJHmm2S1>5j)Hpy%;;)H&?^NIg}1Vn25Lrr-D%zLCmr#3O+yf?0qJXOd}FC3`P2 zOuz-54sr`O+{*(GeBoDk;46ON*Y<_4+e1ckqtvSp*1T<=YR0a0WJd!N7GxSr(w~kL z$5a>Kk{cm?$v)hk;_AjP_)XvVjom=GXA3MN7h2-&=_PR5lmfC)1cde5z_iwKA%AZC%<;Yf()kzmqA{;E*) z7-^H~MCFbLKk$pBAN-RZ_;q{e)S}?Lb5rGZeR%W*7G~`Gjw9~)jo;Yv4RIIa6ii}F z>%wHBfCoSDMZfS*_`*nH~+@Jit>7h2=tAe6~t4( z0}tGT7@PO>z+-#hcDvURY#*9_JKNTHHesI6Cw}8!_!s|1%A3+4h9fhBN-MWFR=7Ar zMvLdimMR4ukm$Dn?uqnMgG^@0G@=+HA|>h9<*t4DSFQ7}+m}wE+z>*j?KxDvuc@hK zWVBoQxAe7tA?6K12L%Y~Z7U?8-Axf%0*R?UP^VKSB;2+;?)-%>Qr=0w@VI^9aev@( ze_-U!xggxt>-bDj<38H}NR?d&j?jRF8OCieBqHgNbU%Fi*Gp^Cb!=jMi+tR1#G~d{ zr%w^p!JDX4T%)ZE@zbct>w3AiHDNa8b@x*N^WjQPRSs`X9-F5sQh*H?w0e@CO~=Z0 zV6DmdL+wplSCZl;03vQk!SXNIF4J?2Lkl^DgMsVPPT)Jfaioj}Hv#wPp z`|bn-L>U|i%=)Ffz>S^)z>T;N>(r(ags~zQln_xuLP`u2=mNojx>xY(H~^`+P?6$J>0z2CS0k43o&fAazo0$5n_}ro&jVq_L5ODgK|MG)Rec? zBC{y!xFO{mHooDGyV41J>nRcRz zOVVu$EG(FY#xwtj^1ZEN$)#Z9e<77kluC@c$S=rH3lk1L>U08ohZIB@kZ4BQEb0IQ z3<@H&HUeY-#DIi&B%G|P9*HLB`oWWCgw*Lx`rhc3h&iHUM#vCD9gG4yiUA;NU2eFQ z8y@%)BR>AZf2CjeuiGz~LZ@qTn$qt3+XZwNAOZ3Aq`ZMb&~YS|bvku)Ui!g}?|9&$ z!2TEhEBzy$!tI9p?LM`;wX2PO|HgM~*Q2#-q+NhKA|CW5qwnzxU-1i%^o4tR;C>Up za?V@sE8tz3xqJE>zmZBp%(4a}?BZzzS-l50Z=B(GvhoJB^~3Qv5+`y^FIPYUmKZ}_ zK!_<~D;sWn!-MW3Q{pfDlm5YfZU5lw_Ju9Uw6YL_=KV@@_7!6W_i-FZ)*dlvUFaJu zJISzTtq_mPX!SMAsMjAWW`OxScvZHk+K7nQ}fZFJMIHeJtvgda4L zy34Um1qKIJgTvBd3t*&P? z_aMS9x)M+Y60*3E03A^aMMl>|p~l{=U-w-PwR3b^W!Cna|60ZV97F(EzH6xPr(^t` z#nYcn+0FU;=bB(V&x?lZlVmT#nD{EQH*2DAnm5CHLjO$p69ExPyly2Sl?_|j)L6ga zhP$}N>4AH=HBql40g{#j5+tCZf(J4XAwVLQCn!W91pSh*%^e1g%s|eXO*+P>lXd)tP`~)2llmbd%WRkTTJ7+w3S0h=bT6rL0qwYi` zqueDS$scW88W-9-bP^V0V3M6!D6Nd^S7%T>k@jq_3(;W}3En1yCZ;L7*5AOF}FWL=lhhkRPdMB7ET<8Xq^_8F|YOPRtLOzKJo&n!*TC z?vdr&9r{Zl>Y9y$LIoLalZNcQ6jraj@$3n#Aff__YN0n-)zQuXF%m^Q=#G1E?H#}H zPx^&_wtw)Ieqqxoo}^Qo{M0McJ6CeMkZkU7ghRHJ5567>5TF|>P~G65koe7P7omF9 z0W33CQDtVLgqSxZ7GBnTirAu=~UVA8wov_ARI-!*#{li`H81`IQH@cLFBW^`VliQJkASAXpTnF=HzvhoORfb9qZ zEUeEnfD{a9nI}Szlyo|n5kJcHK6Fv_oRK(zB0v$+CnLA(0K`aAC%Qdz*7bZ%-j|-| zX^;jy<~f|ZxYZC$@7?C%%v}>#FhR`foluZq{XDcz*=DFIh_JRXp~(y`s65ClTYk$P zNm-{f`t+Tl$@4MEXdnZnAfSLVgENCN>yp^k%H-hRY zoFA2|%GFJ83eH1O7i!}SM9fy|&kTJZ)`{x$rQ^MMxTepj{Sv>c5bq z7_3BK5>LRvz)=`67jPE74#7NcdL+9Z0nb)xy{T~($#28jcGa-+@A3pCF`9EII4EPM z15X^-$`eN^Kp}7;onE2br%K!AAWMBEY(*5dcuAzrHnQDPQUx%6caOHKRc>I5c0B3X zfCMDJIyJz}nN1;Sd19wTW-ipf&bl(iU095nQc436Q9uOC$2t^D05Qm%`V868DIkM5 zqi_~ixbAdiMqVB7sdAhrAVK6k6VQPZlXKB+|Ehy2w#XWeH~c^Ep)e4t>n#jSgu;j! zu*G$3AVQ6_l(Y{N2cp#*@K5?L+_$an;$(}@{hsXo)`?R8?V3Y6;iMo+-Gq>)NQ*n$AXgxbb2$2y(i5g!dqgfHB~qyDzA zEkQ#sSIioq=1Z^r0H{9Y)JUiQlE#12Ha2`O^I?GNrmWWss7?`mKw!PYLqYbxk z!!5RrFSfedmKfk|R-4Il=x#*?I~_tl3`FeG)~?u_f`|Sn?Cb zn}G`3juk)y4(=BeNJu#v1CKj(HokU`4Pg3Np3?UcfCIxhSN_XI296F$pA1Sr(X?l?g}op z3KawoA{^Kri%A3|RMby`Pzs?G!jTE6KdE@$bqg=#`mZ31a9H?WNh{yJ_R0+BvUj6v zra%p_n3Cm6KN`Vx*|reij@l zV~>Xp1P~}w-M5{!zHE-QjjMA2z&a|#K#T#I+D;w>s^3FE76Zn1`Y0$?@e5X=YS{UY zjoCbEQwAn)BBCxdzJoUwT0lsMct%xxhq(I>WCYd)yEq_bkCa1;MsN>496gAyGmo!qWu>2OnZw46?%m3&7^( z55M~LJ^)3hPm+unmv{#@X@dm9Gj7=T1II3)`k;(MdF#-f-D)2+s?aev^~;}`z9{lc%?7ar*@JHv%dMuZ_#+BmE6o{MZ5nr$)d zxel`LM&z8qhpY`rkhNAw1(Bs)o?(+`b6e|DvY%p7kUO5!QR7mo4G>DGGKvpI*%|qn zMV_niDqDKX4rHvJkPzkDDYk~?Oqa+Y6lC!*OWzWkh`~FHU6cg`acVjtL|NyS5V28g z9*LTt2NaTzOnb{Rox4E##G!ex>3dMLU+wObd!)n ze&vuIoV?d5U>V4l?`DPN|DAjCgacd7H3( zBd?951$IYs&re>6P#L0))G45-ZRbsj_Sfp~rIA0?^LrL{?JTE{`<&Mgb+lC`9hKRe z_Z?H$(X-R+hg$gvRGio7=XH&K3C9UQ@i)m|Q-4pQ#ty`4WCl_I#V2~m{Xt)QeLi~jUG7l=Txt)sPqq`qW#9Ew6)39;K>pO{2R!#pRO1SI>^?XqJEwF*vl#*=DB>13G4w!)L8b{j_Z@rO@qF$`wBw0GJx2$2B2g}Y ztEUDcOzF`0<904Y_Y0<}8UeN#)#f^1fCy0YI{U$y(td#nT!OZ&)t8({j_w!gFK|F) z9dIeCP>v$|upc(}J=du?^7VG#LxsM=vL)+r?D&3uWBe1Z`{Kv7}ohmraa1VnPTJx47dOcQ8ZN+r$kK0%FQD;sk-&shw&$N^i}z^NcG5JSK%ChWWL)idtcpSmS;i3nw{ zx!Clk;*2^5)$_LPqSK~?YD7gf?xem#lV5tiZJTT=alhm1@rAFiF98zU9k;Y01sw%f z4`n&Bw7dOs4%WnGq3i3md}5NHHSk8}jYY%^vjII<_5YZr|I z50re!K*~+L6E<>85d!Kt)IlTPa=zYd4VBNM>{)cww@eA*C?DR-h%yx{6dC;*)n!K7i`=JOL9co5_O<7uTSImdDmO)V~f?PmxFYLXV6R zN(B;Zj!4QV!A*A>kb~64sQlf2>INpv3!!MAN&^w$%;nF%BcgMA&E_Yqy%5X5s{~F1 zS=mnCc?~3-{p;T1_wRS{+MsG!Roa%1uh9M*;mv2?dQ1iQY5SbiYp3Y#U2^ALr{Q|r zw%G-;{{pq`Q};1d0J1ZJan%V(N$PWOG9#ir@s~Sa1XZ z5gWUaD7TD~Ht@z`5N|r7KtVT3X!GcU z(iSV2NJuse3#xmV+h}8*@9z|7*$Z;8=~1Gn%f={20dK5;hJg*BL|~4xU0mHR(3FY- z911epNPe-K8~L`;P*Xa7_}ewV7*lFUxosCi)SrE=oCr{*n}PtZK!g-zk@t}{JmZe< z@I=BB--saI1$-7#aaP5x177Ir%y^XaX%8XRu z0mQ5xiGt=SXv!~m009FK25Iyg7`iQRIWqE|ai}4@@3PyAjULx=Dqla$^}}r6&nKSW z0wl^_P!5Qfi(B94gHfIZM-ZU;%~3(W_Q!2Q*%G!*4JQPoBwt}A3e`~HBpxQ4Oa6=p zZfTd%S*>Rv0GUzpfwC7tDxL8NS7VLY>i11z+kP{|P`{>J)Zh#V*g^s&Ad!HGBi*p4 zXWfqZ8&COuQhrMRQlo&ty3e~aSU~lh$m!4O=~5Gw^dpv04CZZ<-))Q7Hkqb&yKT7L zWD9B8)##4<{UO^*$Am<&>g|#lWzRTv`9{aSi@{Y5{?d;cldHpKILSQo05RTD2x3E& zwk>o63=TjXa(x`R0@59adTb~E=Ba4fxleRO9^F**ir$d2;!*QMGHTQ3mQ7DIEWo-vL39SD3$kFy-(SBQ=9?rReh~9^~gj! z>UoIj8E0Ns4;%u7?=NF&?X7TV;FBF$*R|9PT>(Uk@hPg}{b+b33O=nfvMiVrmB}3^dfm*AX5_kn1pg zesDNo0Vm$EY`a>2&tj%wy2bmU2Mg;YTI|}BTx(YUQZ0k%^aX9NXnpJcYqa&UO0GEE zMv$lbUdj8D0Yuc^J%9lOklkPw&aUV?y#%)lWd#kiF^ zg(X7_2?X^Ba5Gb*O}kU0fiX$ z{cQ?C!JK&_%+(!HbYXKYGQFeZf^vuvk#+PtXEoGqgvyL8c6As?w-dB2X%k{9;+b&D zB`_gTM2J8M@IJ$8&UqwY<~uhqVJzFe zkuxl=t{}pDC8+fWOT)2s&10J4r2JXXjC|Kk1VlKGL9v(;}=_j0|A5lj0YMbyW21GLQe&Bd25HtYcfW&dMZD9Sv_M$eQ80&3t#y;43 z+cxkmgUcrCu|Q&SCst3Y^g|*UFtP#XQpASLDA;ob7isTu6dZfTaTINT`|7#z|1b}O zy_YgnFG;F>Q@?${3Ir)4Cc?%M1)Hqn$Qi%s8;LeV);?)77D#qC3}`yhd!6gRmdQMJ zw2fHQK?D!6tz4ZThnGWkrrTtYZI>Z@Ux@Y752eb4Itajx&&Ub?-lS?d)n}Y$tLNUH z;u#?&>nw&i3hO9TW^fJyBB&rx)~_?Fb_wzfvI@{Tfm6_ppF>{9DOiP|{p;3A^j?V3 zBOxF{7bjK_;YJc%?Tod3!|9Wr-z zKuQ}@%sK_8Af*j4vAEw8DtJp21#po$Z^gU1g{K1%1U__%Spc%`$*p6mJ%~X2kdglg zq6y$;I(@$+uQ$r2oP=DT3G`ZPW+xmF7?#!)~pu(E|py<%1Huat=0TfZY6q%wt ziWnr{JD$Iv`2PKk=kusQfosX&00r8|8V?!CKK6{f>pF?-JSil`blX*I7bijGuL6{| zmZeYx$5O#^g4R`3Peq8>a>5a_tmQF-X_p_07%*jT@j2^Oj{|sUwZ_6*DIsm*tt?5l zO6RD&uj?gbOJ`kA1=(Q*1RQBc!Z#wzm&|dHOkLD+A1q(IM+K$Sjf*h1K@6FeqtmNE zx~_(FTi*@$wBfPc@O8W4@wnshxZ&}*RZt-w3jOe7-9l70HaM7(tsfpmJQCkKp1;5G z{rjoLsMeVq)u}vg)2jj@Z3){Z3*NUN9+H^aG!y|6(!Y<~j{7coJi~#6Z+x@PrPsA% zgafQooN&lmv_i5Y5tSXby9MtI&cZ*zWMqu8sZ7z$52}}7Yohy^(+H2O=Ue zC6t)KN!RFP=vLmYoe(;%vQVcs6`_|8M&1kZGb1aIpd>VukWmr?>YWpl%niO}IFClg z@zkkwyMF0;KiV`W_iNuX0dmN?IK55fiy>5ADfbM{H=W8SBmJ?0dN_O0gw_8?-Ir}S zj^o;Hkd*AG{{K%sm0?RH?gIvblw>=Hs_v^?PAN2U1h6qt7MN=!R_2|BZd7KVip%5v z-0^(wI!|{U`y-f$Th7_%;!@1TH;bEZk$6Fm8=?$K79`=i(>|0URp|;S_!lkz?YD$`_;~SfFTcF* zMbYy3_>0Hyw)vi`XD-Y5i<>p}X=PrNW5yor|AiCmgvgFbrFGuBU|d-Q7t=OjZ=$_Y zp*XA1SyM(y49;+CShD_4aPVyAzdbjsX+ud}!)+kKRwcH&lPkXhI3^(gO=AUibvvZe zq>Nh)WlX3kp{62COocA9NO;On6BfAxismh6+6<)utoW>v2-JX7pe* zL>9GdmP%T)A|(Vxgi&&0FeU7&OlW8l%-Ga7`zZp#_8XNmtUj}H6Lr7}(o9>P5Lw5h2{Z7zFmu;xJ{3s(c;fNg z)OD#2774&yzLTDvB+?M;Fzb=7SrZ@Sh(<%+G6fIiJ4h}zT@P8Rs8rKupO;~YtZ zb#`LK_Jad&U{~3j&)53@larmk7>Rq`K5-IDk{N~Kv>_g{R{_0N|!{%M@`+tJXX%)4awz( zl#(o$#`voOPB)_gRky;n5XlNXS)+1?{88J%7Qus&v_|K;p6E`FN<{64~oWWSB&Q*^EXk@Hixcfl2!@C8ZrX=~^7(g0ZJvlo$#k zwjypj?n>uy+s07<5|B3Sncn0ZNnJ-QvA~)o_2{jvxGy){S6Qk2uex07*naRP4edqNN~le}~0L9A-B6XVBQ)ll(hP z);eG`r)g+LU%L#ZYHJC$Hg_TGLyd9Swmk%3cbBpVBs``p(2txF+EUR<@o`sjMlBh2 zFJdLhk?#c1tMt`?geaGGSb%xk8}?^)!1{P>aBGAEi6Hzku?9&Z6JabL^M4XK&>EFK}5?!e_E?m^u%o;P`Cmeyj0_Q4uP? zjAHqf4GF z;;nrw#LNSM8|%fMgT5*u6X8Y$l-eX{F-d@6E0Q9w6%$Bx47+Bq6H04`C0AJwAr+sH zwm?@>zxbgJ7h}X$*xVb7rZ6{fBD5^=5S#jf*Jam?HQgf7_1hFc#0V$EM5=BS=pX_L zFsPY;0T=Y3Oug+2!W68OT(FdiTB-_r3@+MUB4)v|WhRn9SpyPitimkZN7!8|o=$}HC?09|~qkpQeb#?8zlVk(yK`@bYpgpKQn8LidYHBJ3sn%IDFmYup zxnNrs8RvUdZL&OTu01jrdzO{V;+~LN16N>66$zWThnTSZ6kzmxZW9gT!x2~0Vzcu3 zDAY?P9q1U!P*u>NP1e$#4aP+jRyMT!Oxre^jc6vPBf>Wz0 zLjvzt&2?KcS}j;h0k7-|4O?Tu;xt+lz*n=zO62Ck+?Hg~&bEsMrxgjt-^tc^k$4VM zbX0EOrfyD|(KO3bP6e)3sLw8+Uj{H3-C9st%A*M=>~|FKX|PDx z|8cXiC2|ouh)}@VEMB6iKnUYe7(fImt>K3L>>gqy9s(e?r(|jx0^1c(#5H0ZSXsN6 z#kV%pQWcy@yVg?BmKx>(m-3}=9!9*nB1`2#q!EKR*1AtlvH^#nb#;;sa(k^bux|Rj0XN`dgqv?&==V#xd z3}e8wk199D2apB|i%1$lSKdO@fkcaz2m=QxcMy@X#f&*d3NAfcGwTgyoXpn?kdfCkaoz$745f~`nxrt?115(XaV1W^A@f$2qb z7Jl9p0g#Qy)WI7rwqFJjpKoWYD~>mu{2j`5kc9^qu+tB|2ODS4{OWcluwMxAvVB^% z2_YN~15y8pO+~rkTyHWGw+D^giLX|7WUvazsgY<;TT-EiF{C=2gha26oxUjd+&ZsY zE4;)%Ck&ziAT$lkW7qOpj&)lwY#u9SF>w*pwN0j})?d($cWai+PJ68do}mgQvUH7B zhMvkbv{}${owpB%zF^UW*Qmu7KYIZZ9W?h9xEZZUV5j-3GHYOM)g0>FurxEDG^E6$ zv8l4|1yUNtbtUoybZe})6JV+Dv~?nc4FjQz2{V}Bc*g*YLR<79&_~5d6MFx;rAJ-3 zG^3HFyBx`(E+={R9Bdr1Sm#ba#Wz0wO)jO0dij5SK%8S3k|p zGiL@fa4&qpg!3jmCN-p%kae-P%9_!OSr-jCs>L*LucXaSjiWINJ@rc{|{R*yOGyJRfOsw*8! zJV#ddj=mV0ww0w_Z56fd+NTmT@_cT1Yyup9d_VC0fuOz#+}F#W?jv=j2IdO=oJdPaG0{7e;z)X-yUQ1L*Mz(d{S@1RHOC z&aukMpRvi`ziIcsd*Vt#VHRtO3{NSzz;f zo|UZ$`1Em&Kx;G(il~8zWzEr?kXv?se&9zz@VC_42Vr%n!`U{?1?YHEMU}Z$*)b*Z z#01vHCh!`#7+jl%y#fStX>!-5I{e-54Pb2OGj*9{X`fsRN|Oa~b1kxOMHWdkAc5{F zR18F97Tr}N35Ib3rv%@$LINTfP|JY~f&^B7XO~u{b~i8)`y~R1&~_a-K+TEayjylY}01thSK3?>==b#?TYuZ182A#8khzMvR_?j8OSuerI5i6}R#@EzO zdv`F=1AB+DN5T}$)NCNa8EC6m6r2FUSh5K$C406Xviirib6VAzywf_CUb5CAKm>+^ zh;Tkf97KeEX01T~H{Kt~UKgllFu}Swln6P?Qe=f)-It29%1|?bD++zipec>tt z5)adAMwbZ9+T@-U?*DrP56eiVcR!vlWp7Z&?E$k_!a_zV3AuFPi+pj=XsziWBBkVD!rp7yiT14nh;5O0 zfl_2mpST_YYoIvL)9&{9ra;aTBBUS~rVb)(ALKTr51})stt%}?z>*C}7+BH0y(oGl zbU@YV@MwJq0OCvmr0)Q@^E0wzb_==9<9T699||+ci<4Zh8-MV!)>zhHeYRJGz5rxC z8r|!3CZpCJwPsn)fFN#7IU(=jZYN1Qq(Db8Ym`hqYhH{}CIFGnPvwf|4HR0SdS0>v zeAy=ljS)!Laa`598KA%jD4K!^RuEAYJQ$deXGS0)U996L#MLDQ5JiE591DPOAYmW^ zV#O{wCp1p(S1Ra-97LF(Y-N^$)FcZCwWL1S3DLMi5loznA=1XC_?!E{E2bUczJ+$} zx1q!7cE#@h2#EObgM*>$TK;%bhCkRk@5*pY0r2`=zIAH)zO*kW?@Dxne~hlP<`D7L)TJl2`tj>mrWGY~=jUMnNiB4Jtz0NgO-U+31X5rYXh3c@&X zp$UwuYto%M_c9uj0R(tSz=;$74!mNpXk<*+n+gBy+GGV0u0h*Xo7loLz3m9HxL*V> zB2=>Ur7wCVj3pg)>^2JQzlRq-|SkGjFVwev{9fP+;VmDWsMXe zf?Fg+gKGj;n2anki#2jY&?-2D{~*ZeW=gGEAmd5;wY5W+$rbzI88?zFZ8O@pUEYpb8%qWvqEM-TsJqLZk2kYGXp#MA7MEqoxUEG} zf8KAB3iNh!w+U%8c2K=n#>Se_Wz*EH&n*a+rsX$)#$ik-&9(92^)PTb&L@*R4(-GW zQd@GcQkz;M*ye2jwve({?e~3e3LpgdY}?*ln>-Ds)+Gp6FE=9f$F|?-(lj3*T$?WY zKmIXGVsWl?LDpCD9V`;dXpJa~=hU~XOmTiROUwI|biO~nzw!O!fo}~wx1ikJvMAZw z4hl3!*QT*DM1)pJvf>46#2(yMYHnz`iFQ3amk65f(tw0nBsBZg1nL0{ii+s6Vq>rd zi{`#n>_tFPu^6br;Fh6bBOuKJCdnZBm!eg2bZttfLVhgep=U2xNOZ3<%Lk<_g4^WU zsbAz!4xY~SevK53 zVC$#|=wH_b>utsDzDfqQb@8lHq*e*5wz;YbuZ3rEboo5~Z9sw|kZ5R7*CrLHM>$iD z4MfOZ(!x7{ur%QcBFwGHgXuxtwW;cI=8V?c(@-r{NrKhXceQ0*0Lzv!Co7Et1rE%9 z8U`-Y(D54107C#55k%;&*yb(^=)b;jnf{3vBb3QKLfC&IyWBe~~gx~(|NM8TE zKt8^e2EnxtnNIO!K^LHrnB`NjM8p^grmai?Q;E5R^b5p95RRU4$W*10W<8F!Ym6**E z5y6nTHtjB0y#^A}?k$^w!CWx{onRi^wr0!3>&-yb>1T&y*M?^rgrp84)}uutnLCUM z*eX2kYI*qne&EO7-}w9QANcY8P_VUO+pAa<6f}uu+qB(%?v4Voj8h4&Wfx*&b|6W~ zEAL9oAwB_a1(3N+p2E|tDrS)|+Ge2MXiW#k?7{2NBC+iiWv?h|ktn5x<`==OYCEUY zwe5&>z+x0E#?(PX-w#~QWEg9#6S-xe8{sLLcyV7(kC&{^sZU|4XY(TD5-;F zud)SOtJ1_R5z`(`!9qhdK!LE=xWHbv$lDc2XcD7@Gyn)&b1H}6>g3Nrfke)z++;GK zA+eZ)s&zDiCW)%2d~IwdE(y5qx}o0TLz9o=-TTYV8N;^9#h4TC4uNF7JGpl&Os4)F zne;b7#IJ52$)oQjlHcDx{sy1k`%^_6+U%bJ6XUl=0nB!+9Ebr4UM2+;K{((^C_bf* zztlG;Qo?jB<yV|bjg;C7_8NAIRi0JJ%yvNGozTM;kR~Ild*0tb%TX4Ux`1)D}O#J6A$u(4i z{{%GfRe;3vF@gsRQtiLymM2T+=>FBjp=MpskATwa;(SKdIBnLhYT+;oS2my!erCN< zk3%$;tUd1D6c(V{RABb{=t6X!tUv{;^WL+95>Ay11D(J~D{v;TAiQ(Bhr_wy`$Ly^ z-~7}A=$EDFLUW5Q(q#+H<;j0v=a~uh+BT2x2Y&qc#@|1_-D0-Fo@{w55vC{e6?cU?1=nAXT+V*Fc4z|2g% zqqg7XkOwkbJX@rU445cu@rYZkf2<#OgMUfSY&A+vVwIfJ7BWdB(rxCpYA}Q<$w*!ay*zWbet*{ZJ1n}TMgGN#GhzBn^ z{C8#7H_!jF-2bW~hjV{e0DtwmnQNTf`|G8#4t{^zt9HH0!Z5zum?^@`*a=b_1oX+Z zDL&$bITrdL^hJU9aQ_L22xA}$Tz!>I&1+qITtd`@_EOAS2M)$CC*6CORsx6sFupf} zugPb8023#|@T+YE6J6`uV?nByI|7IfE+Ww<5J^l#tr@LJklnVGurlw&SiHyBd>+m$%H7ju`>g5hNmHRM_Gnww5Qkz z53&x;XsmD?;t)2jh*pqVHY6KD8LNbF1qc2_gFph_lk?+4g z3gBaEEEc)nd}I@+9s}-;XDL{P@O?zkhh&*Q%vZIwvDO z9cmJ3gA7&iS9hz;plKE`QL?01mT{bv{+cCG7gHpNTT`?|M7jAwabjS?;w!r)WXHZ2 zY!@Vg6>QBJvDwRDm z7uDn$x^m7En_-{@9b7Tc=Sqlya7#qAM%Y{m3W0&=sIabbyaeqA@X>(>hq?HYLnF>B zyWi)I$8<=!;q_8WlRj!7LjJJXBEqRH^71qO+xcPyg$7cFI`BLP z!Z@@qPt@f^84QyC~t+lO`wt8$BApnW^e?>zT>jbLaZFbxdNZ65C zBrH9=uQbJ3!G)!b?-GL@7el>`vlO9;RU$R=Pmqr)r;M&`VKhjPVrLx@=?wkD@od-p zx$F{d9>uKyZ0t;=@328WeCqY~hvn~oZTqNl|J3$h`|!sl82w|%F*Lrx8nTaN8`lS| zrw#jy^32TsvsR*Me|2nxJr+Vi4=i}~=q_@q8#$;g_BlA^L+*&TGm?8T2+l@4;Y=H-U0rd0*zi6bEF)m z>BWHH>0)o%(C2=Sa`Hf3ojK*1IW1sj*G}JVtN!}&{kEv@yJTESSt=#k+cvC#`+RP& zG@&jKx{J{XkYEmJ#3Ps-g}#2I!h#R0-h!hQqK}g(xY&0Z#<9|cM{|ptf_-DQ8Wm#R zZE>E(l+euVYfJR`a^3fb3vrMQZE)P8=6V)PmPG?7SP5riMVD;03 zt7|oSngDgzaY0J=z0Z38F{8(g*xa4KglovjTtDPl69A=Y6+lEFF-ZrZbH#3HiecQ3;jBVSIQtr*KbE+mn&XJ~eg@U^qrR;(}Gp2S1~{~W*HvO9SkfPQu3Ba> zjc`J38HpvIx35wd8$sV{gMwfTu?t}EbHK=Wc_>s5GU^j*XjsAlK%DfR-^UmC{jNCt z$@BlH$o&>f^hWx$9G~E-S=;|w^YG`lPro*R2|Z?vsaoT91RL>hoo;m2MnS5)C?6lr z_ZN-rd3AhJB$u=L#Q5ynQMt#wyLS){E0WGvD}$ByFP`=0DVyts2! zw@hqXMoLduyb~n>Fcy1a*@^nA$X$sHKuG$|1wc~kPeIDr)3chi(^y^i*z7s}${-fY zyB!#=i=x7VZOf*hZ0GU&TpOE{ef^E-9y*Vfv@R z!nvW4xB+CUXf2^aKaje>-^YPV9bkrQ3}+C*3|(~SM7+{5Bdgv9z@qPSm!<$FUNUM5 zMWgZ3?`)q4NB_!p#dL>_@#&=d{LWB>Aguq>+s}UC048wiB;fBR&j~#-`pDG><~oXv z^YRgg5pI0Z2k{w!{n;Mq-+J};%jY6s;3!m%KNAMxoQv(ynGp?w-zVicWne~Ll+JVo zMiBlZ)0zdd8FA2b|8V_P$$9|uAjya4DD16_rkOp^sK~W{P9hqLOORkf&qi`vRf8u0 zW7{_OkzdyZ_xnv3o-6L=;-4Ob4%1Y205N0)i{r!o`GB~n1WjOKxE6`?6mOz~VQTfE zxn6+?aIaewz+XM*1)lzPE=L79SCq1VNY@A`U9gXI$K3rBv+@dS&oBgng|U>3r7cc#Er2{F z37lUwg{aMENj7MhpyFyyo$<~2UT16J_^0?<;ESGx>HtV)I)5nvo^0&@ zUxBFC0Al`o{&xR+e28r)#+n-$D2Is&&0^zR>Q`-G81{~-Dp3aJ7Rbq zZ*XZVXqy9wQ1R@t#4o>n@#}Sr(hLoa)H5=XT9>X$FiAwy@t>Xr$M*%Xi{RSlv8Se1 z`b98-$s%EEoS3WXzOU{}ZN9jxy1aDFSEm>wfNcKj@gv<*!SQ}@fBvKz(qD4cEfQ}? zlJHJrniy_=CGZRzk8SQ+-B8Zo+I|MrTwa_|Nf7F1DOjeZwV$PjG{IA|b6F5)024VS zS%bj>Ig`38M9=~o3nTBf&Wb(+6WM%O@saLyi-g6bh(#hJ=KxllCU0Tj+I{3FdQq#v zh~KZM0KGs$zkBE9&&dD)AOJ~3K~%y{yU&5X)&L2Js1>%dwo^SaVZXeMLyrU0O+c^Fdpq5dS8IBol)Fb#6LS5-+lbX`C_AIZySW(03Vwmky|4|`qu~~4s%&M-PUds@Q^!@Xd{>)Th%%M zijoyMQ!^lu(ON-9(_o7#0T+;k>y9o*NAZAlId$f+GVW0NS&SG#ge;P6!UNnKYeLxE z^D)8exp?*a+bbdIzq*C7?vtJ8vc1nNGtJVUE5dI)8@JcY;nlSl-yi35fDOl|rj-F+ zeD8e;{rDgl1foea-*kM@beg8We|Ze@{6`Q8mFq;;6@Z<&TRHfXarHCBu+5vLg9le6 zn6}E&PAkLV!^8bJGN-eQFF#k>bB5t`3P$@z7BjG$Pdo0MRLb`tprPahE=A}g1q(&3 zsx|Fkqbvnw$*RHZ^n387juwd47m*udhPsb&bRW{U4gDwkY2;GBMwgoB(KYT}lg&cw zeBR6U6YuPW4f{_goW6Wer15xd_(~j?-c%~=1t0rP+buH<`3l#T>UUW)mLjfA*{=I) z(CBl?za94z{X4Oo${6lcV62DU7hRKV+(bWp&BP{dPG*hh3!Qa(^QMhq{Y?`ti~qyN zcWn)+R_rMVsoWQ++-n{dYm33wBJ+eGYmHZ^rGTIo30+0pV&JR=L97} zM)olr7ae3~RpO2T_HF@*HRcW;d@P1$HSkamgc*s!F;#A zeMLBXNhtXF<#*He9c`Hv;)i>#c((Sv1BuPXoo1M;70(jrF=6DnaUVbgl7I-?dsqT- zUx<#X0E@7Wgv2z5GIJk;qSq%-3)YA>?bY3B01}+UA^~#)VW3e_vxq?mOZSwKP)Eid zTDlifCx}iM)LFM7Zg+A<~_gq}6VVmWuKGv1sr6@K}>stOd?$ zW|oNFg?xPM{cDaTI}tn+kw=l6b)wdSWs#u5WbP~}tDn4Od+C9oUGA{HRx^0CK*V$N zKkl>US`lEvz_EgJoWv-f9$L`IgSzo2?0n1OGN66((&Nl)CY!_pCL<0F{uS2%f4k~`vg*%02k-~m$%Oy5stNEM4xOvz4P!?SgWLOCj|3AOgqzv z2WO@4cmG~*7|~-2mcKxNr`h#V{_*3{53$ePQ1(-|gFt^d{vFQsUw4;y)w^!_wD%cd zP}dA8?+Y$X4*tS=q!@KeJ+Z$he;e-~P z(}nIbJPsP+&1`L>*GV-x%uDHk)+vAjPhv8Bv+qri8{?2BdJxOc<4dl_y8%2N z;%=&@ht0#<9OGIzG>oUS*8P|}n8mGWmZ-4!ATz5qr(oar03vLy0R}uRZJ$G86|n3= zN!RO;AA(zxWf1GpR_b4#L>@vANbMU?MM265Mcc+&S;(NsVrHR8q;VMbjR+Q8VC*W~ z5xn!*ub~HLUU@l&4}*#(!Wcl+;jwV9(RizCeAo2tIL=Pxv|pU;JpE!x58Ekmr(^pz zM%DNP8HWO(({6D(fVnYs@Et6_Mu%+yhX5jwAnr}nz)68bQUKxB2~qT$MWV;ebgLUN z0ZoC#1SSra31pBP8Pp=d(7t0rp8wgx6p+=gDPaT?q4`}S#N8|%H4I>cMNFo}vuqI& zBX(x`_P>w)XPrI{fzP&IWhh6%>la`2hqrl{&&9eFoPXydKfC>8Tb+T3*RN3EFz~*S z+nu!oPgfZxq(`ANJneKYj{YthdO1%xUlfYxF+Iuf!>3NSh2{ry>P-AP2NCDb z#B(?~KU{PAsJZrYLMbLJVJrc`g~P7=u>nZOws#O=e{&en{eKRFYmQ|Y%N;?)C$Qn zBU1zm$8ykc?^I~-n@%gIu0Lst?%KqjwJGjl?}Ax;GI?+-k~w z90%q=5lkNVT^uhRL_~`SIP{Ha&BF`{Bh3Gv>D_4`P&kOk^H@23^hgEYxieWg4>B2s zZa+Npif){h?D~9o3x$5*u|y0);|9`dAYG2jr!LSXYT8&bp#1#7xpMTB{B!7`?%|Vnn;%$J&XQ6*Q!S+r;n44F4Z( z?*PKN;QTLdZ=|X}!R#$V)Act#sQbW##=Bn&FIVs8lcTFUj(4BF*Ih!63%AnM7&S-B8RtPEZx-G+y8I z=S+y=;TsPBa=cn|QD`d~-DRDf%!;YYB41F=Nk|=p_0Yck!Yhh&{@v>~^+7V!Em0Rt zj3>v;T(g+g1uHK@Xa#saqi=T`>}X25@d8 zkVqAct5_sh)4!UFlg+u-#{(EZBVBAdBekk~4!?}VtZq&$Rten~o3TVVBu(+Yc9W|7rjc+W5RL3~V93-#glmA^ zjcarn9kb{FKH7pdwOJONT3z68t-%65E$@BGS<`@uU#@hi#84Dn$n4gtW{V+R3~NJq zX6(8G^0x254)CTzi?@x{lDh;l4r09|gWYNPC6U1Pj`ERNkzBr}7KNF%jQ?);2SEaKW4-9gFlW(x&)7 zaQcxskUrjaLR;tZ{n0HH#T81#y?((8F|T1B7i;Uj>7kU`XDP|5*PIiWB|eD=NVTB@ zp{9Yf7~WEHUzu9wmhM@Uwv>{(pJ9?~>DZBQQsncdHTlURo_ZVrMAvdhDjl~V5MPX^ z`R^ko#Bel^!Wq2sw2v44Nk?->iRF)tqCr-iCn#OcTjPn{Iv&b7Rci29P#Q_YefmDO zm&rwQ1Mb_%!;SCR`aaG7535~M1QW`mD2{WXClbI-;hWrLjYOc;SPjT;IVaF&ruAn?LKY2d;@Mli8h!E|u7=8M17+E8~5a%w$4GkFxoF6c>{z$_5# z%aOxDgnh#`4xwX*0Xhh9lc4pJ+aD)*|KN5))-SJL-}~+@zrX!a5OMMTw_t)!jtA~P z-qR@lkdpl!tX>_iRC`i3@^bH`cvN4*)udh+x7mpS=HguJ`P~>NuPWpy3QS9P4fMBj0zQ_z6S| z|Hd}*xy$gt)qNKMf8S*#>V4mZ*1A7;2|4ZyN`cUMWe_QeK(np|%qsw~P)P8uWO{l& zH>6CUC%|Z^O?|ReyVm0xCaHHmWkS#(G0c)tXzHo{$N4xnkb;Qe*H;>*aDCin!RHO7 z3{%}d>(+Vr+%c=jK^Q#Q*qb7bHJ^~ZR0blbpN~y5&vcs3%{O%G0LH!Fa2C(Rff#gJ zds@X$>iznb&$nUdv9Axr1h>{9C7_K^BF03RzzrTKpUjmks|9B}tKeeaoBF+rY-4gy zci(EBWyx0|uM660x?Ga@(Uc@89-&p~$je4+gV6(kBbaFH;KEjh_r)Y_h+PQA?;3e_ zk;27(I1WQ*xHgl|fhR_GI*z%2V)OY6o7eNmCb1^iq(2ZTaz3OZ4~IsMik5*c*t_)N zc?S(#wMz%qudJY9h7uNt-DT`SX}|^+lEg4mf-CSXhNCH%;NFcvdEJ^{(Q?#Lc~9~U6tL&mScUFP$q&s z3oSI$yAD_Sw~oT($SC`nsOcNX!Ym0uji>sdSq6&MkE{9~%0gCyP}eTA$h!^#SFhzU z$9t^7+1EeYuHJg&F@1aj7=Rt=-v%b+`uNtfY#TF(2@qu5A2=YC?g1mPh#&4k0b*+F z2p%Z9-%J2wE};rVW+`}XPduL+wr#`nxygcC8vL1yyFwG)=m3>QpD!t>7+3;w%(p5!AC@>-!xkYhU6ex?<1IqWr{*V z0Htx7cC?49_s@ex39QCr1dikJksK`zkYL@$DB>tIEl}aj2uo; zA9rs)IMPCGqfxkZULCh#rkbS*Vu^@3ni>TF@d`)~Ku92N!V^@UcaH-S&m$;+00dN+ zuwBH`pympFS*8R=_T{%t&`OlhN&}aQmIX|-+`tKF$+!y3L~T_OdY?@DwhNHZN~Tnh z(}J3I_3LWBYM*hHA;^Tn5E~}hC|<-)0j#dC7~SW?@sm4Wx=y?ykRQ9`yeq?-&qlT| z$ykBuT?vQ(|7=J0hmqGrt(p;x>4DjOM@FHM+SoepS@ySCY@u8^?qX`QpVIwdplSp0t21fc;Z}r_;V*ck%P}1 zGiosPH?z$_{4>6!lI8#+T-XgRO*C~T!?mlmR&4u@=X1m3@xuXdqYcUc~ zce$1%!%a&~R_0cBCP1tZ+xFBs`NZ@2#Ih~|BG%P|Xx;TNXL!SDU#1|p#3t>oS`&b1 zYNc#E00;pQaUB?K5w#*pQw@Y3F%iPMHlM-6OjaYmB#fhK+>ciB!9De|B>&Jx(?KM` zPWU3z==?`+?_lC;W1y#WM{Jkl_&r!+Y>_liwMJoxdRJ2?{8E9Dw)~FLBZff4! zckH`p%C_gGKtk>-c|pw^YL<5~OJzkEfGO?}1)u>D4z)bG5I=dzr`u0ZgMYW1@hO0iBV#k>aMa1&Rl^<6MT-P*B*+tK z3AaYy=qS0&=s}5@%}bi=fbiF0I=R4Ntj&Q~o>&W#faVEI z#CaLteVN5}5N6L=V{~uw_j(_`TGgWGjX!{h>7P9xF|K{4DUIE?9ouum4+kU5GYc50?dJbmV%*ckd{t}wz2!<%Q)Gd~mWoA0;gK6&0WuDx8J zY)3lG@dYM)wdS34h>_s%U9SRZ>SVc|5=nxCoRD^4uL`(XEfSl|$sa#{;QRZ5Wm~bX zEB0EYJY=h6i_23Vr|cLfrS2jlZl>_IaCat#x-rua8^5YZSx0Oj83H1(w)MA|ox zifAc5N?-4~$aOMj&sbLt%AmKe{4-k^mz|}?NzKRc%Q*bu7V$^};?O)57wBZ5_dc@a z6wY|LDdSJ1X{$n%LZ_8q}7e z3sq^e(Q!51E6p&Uoco#K_Q{=}6SwKb{|1+PQa5!a#srYl_= zJP1K2By(ajhqqk{5Jt#P1<;FUqJX3${wN^Xhp8992sItv80yjqUwofy;x5Y-OFRpI zvruElgCz2cTklOHp!T<2oxy}ZdCIk3%R%-a>F-pVYZeLPkS7d+LOVN%u&WV7M61L^ z3Hm%_jYE?d3A0Fie}Ci0j~{qEHjRr|u&$EBUO+@f$`!dZN!*u{t}|gPmG*us&y1v* z`C6;kYZc+>sqRiYA+=Fb9x=o$kVA*R35IiLL`oj${7;dC(XGf1B8ceN`*c#Ad~g=1 zln+ghcP!t5K26u>b0;Hdnw8V@{-J(i(4e#ZI>05&L$(X%hwsOB3%j8}^ME`VpaZ}H zg}?hVy{*PZi2{<%@z?b6xShE!+6zPxuL5c!a3f#ef;nVuvbhW^C(B+5Dl;P|<<|t{ zZF7Z7t2?&+iO2IBKfZt9@4tUw-FI~fY--)mh3(3Mr8ZD%K}eHW3AXa0D?_Y(3>3uJ zh}IZYe`cBB2~6~{K{$)Q=pA{)pw>7XK!gPWZg@VQpq9K4%d%p}j!G3Z zRdA}k8HmB^uVoWh3OE^zI5uwYj5E0Lrw8IMfe3#XpMi-uzJ6y5Lgm?K-?h%4Z@sJU z{BA|xz5mmCT(y$y`&4{y!tBp<%|RC!oSK{x*ny|JAVOUr89)U2JaK}p&z!aDtCn_B zN}Z8+tHkuQuQ~8Z-*tj$Lh?DAIAc5gd7l23qj+y8>VEa2cqeku^!>3cLWYc69I&b>V6t~iZZtppDNDFe= zk*f+b8ITop#nZ!9Ku!rLr2~n*Ry?;2%X7i9WM5U6QoUC0&#fAS+wNi(EfM`M8phMu zaq~RsW1W29dgi2qRRRt);O+lz_C_Yo(|`%!+lt`x)XIX;?{PoXi?3>o!^?(@P2Lbu zP>gf+WM<9s$nj&|oE%T{;kLuEYb$Y9=?;>8J`BZE+NgqV$D)%I{bDx#iqW1~Lyy1pU{*y4rOB7S#LCB@#^`OGrqT)hV$c z)x_$~q&%w;h`J1K?NcnC0ab2nu^1Fhe4~c!Xo8QX_-Uer!6AcKkWsA_l`3}Hv0=lL zH>CPhw%YuF!n1g<^FM>L1E>6OQPW%0TbDIdT9sh2DKYho)ff!zX{JM}f zPd|Il@pxwFz6HTAlEYbOQRy#eJHtzVsp0yE2cbF$I+-NjcuGJf8jkPxJ8ri-*7YXA ze5G_DkLYDv9fg^*n@2(UlOZ&`(cFK6a4^65)z_~|-S2QfQAoFutkryQ4OiK>eIi_tpb=wND$zVv@fr0yc@y(FO9B#p45( zb^OirN-`cb0M#r0cx-rXJGM;(abNF&FPiIsey-?#ml3*<9R#w;RVXT)WJD9LG9-nfG6PHb}vs0WgPxUb{L5;zQz+&RiOlMj`2Pigc zl#b|YiZ7f35!4+F~$N%Rf7HzMajh;llsY_JKh7 zt}|a;po^XzGVbshm>3D}NQ~{W6mBLx;VZs(ucs(!ryU(6suF$E zPW#RCIO}x6M_8~*bs^L=hoP`j(~*M@9>7Fx4Xm*dAeumg2r&})DeFhbYRDN}3V~(tYM+TO>L-Xnj*F{-VPwFovcEA?_!FzEjpMm z03XGeVKfYayS6E_kGoU)Of>F)VspJ-v_V#={dqy(L{@5Dp`c}Ya^Z$q>&ICHwbG0kPsKg z$K!!bGq^QPOKW8x`Z`W9&TG6ox@}^a-|$pfoZ0MQ&2y zl@tH~AOJ~3K~zd8ad8%6@*oQa6i7hK8-V%<%d>%R2BL1}`LQ-}m_}dXRx2thcHXhI z4Y@wVY?1^>ES@a^NE$C;19upfJqKa8Dh-X*2hpnzywY~Rd+w*Ux6JBuX7*ET@3Inq zw08gA_EE9VKtwnm=u{Xn>~m-W5q8vxun9S@`;{;Dz-T#R#Q6d;KiVW3#*+P4bpQ2r z$Nhf8db?p+S1eJ(hghyFG3Kffqx64v|49c-Ou9cl8NfMOO0K?t5D{_g&+|4vIs$$2 z)X(2L^I;ncJ!{jOcbK&%jJK!~ogv_HymrAgGCFZ>XetyLEf=z1Yjanq^|oN!SFHPj z+q!_;0&o-er%WnvQnyIdRrBOa<#Q=`JT@%Lrt4RzU_%waF4b#{stb*FRv6bN>5`ep zkZ9u)IM8}K7vzNAkO+{>&zY7v{yjW0H14m^sq@2kA$3`$hk;=s!PtcH-IX5 zw=|+s9?LZ~Qk4hG_qCldPY}U4w^}RS*`^dAqX2X0u zHawrZ{2rTUZF@YPcs`zZD)_3ciG>hjnT82wq64nl% z@Yd;JkNt>z`~Bwh!i4CkT%35KD}?@l_|&P?IH08Em1dGyTG%Vo>(_f|D(jr}l%{(4 zGa~y_cqZB|qBSDc+1j+U)_MS;r2{iW(iogf_>a||J7)w7aR5!OR9b9Fv(~7g@{XN0 zQPX!VrKZ2~Xmoidn;1sfQ=vTV=#Txt#SeX9i3D(WTW?*;x!TTeHdAXfjA863$ z;?7$h7%Opg;jLiz?`)sdnugu!b}?R0@ADLRuOy8ys^g&k1uf?By-F;VfyCwQk_mFI z*%QVr8oh%1?S}jPhTCn$x~yW6D8)5|AC-=s&7IUcoS()~FXh!&I1uI&*CwMm{ltqx zPEz{^*MGlf-fxl44K&ZL&!iLZrZmAq&IM2qNw~F97$P?8IdW(GazUJPG>IYH-q*ueN9ecW@m0>;NYEcX*yWKQlVV zCQ{2&)!0LESwhruZ#%Ya#lBap>mu2S80yMIs+6cWrd*Koj_0<6 zwjHeC(A?O(T~g0Jl(X)A;k7IvVp$wOtm}%~T4YUyl68F8_+?4KYFQs^#p5aCYu8wU zS{tfcEY5pzl#OFscS;}UkIzXjN4HE={Urh@iBOlOanavw--|+CP_8o6WvV$C+_xQD z-h6J`>eiCvfWR!7bilzaYTxnHxYO@%O*8wwiS_28!0Y*R*Cq=fHz_m<{6}DWJbS3u z!8I!E_1b6+xZstSG6}~HI=k`w@!?7k$en18#B+RJ#|8(1Sr~jgoz09?*1GtVfe#z` zyI#pJL)T8)#`DKMVGw5%>SqL?aPOy|JFR4>ogcog-G6`kkO2>~>(#~%Cgd-hIG?n@ zJR{D&$J72rIh^sRP(>Im63c@1w&JGl0k?I*{kGzETXDNBSk@J#EWzja&F8|r9?zKo zds2;yp?f6A{o$z5aV^f(%l^xNc$5E@cq+eHW$*JW0PL;{x# zpB(B2fiN<{P^*}*aCGdCTT&iYmd38s8{Y0dP`E0k0 zmd0WKW;@&xr?*zE*FKyiv*4;V!i!Dbg&jl$S&lj&h#-QKRh1>%Dg$a_mT$WYRAfTB zB!km3b^u{jDY5_y`i!uF@2l8Z`Dkj5?#kq6Xg*_g3TJFGwT8+~UnJPFn!)Nl1q+c4!WEI4i%xMA}^Y#u*{QAwOFF5{9*H>Rnnd1a`F}()C9dL#QlB~OT_Jl+geo1 zSKM8oI@E1!#V_;ttnBQ+a zG|Z4$8d{Dg0dyDFpZ~acmbfM49ff9g0k-$YP+MgrkR?=60xfm+x*=VCFc>8 zGIFU{mMV+ZJvNl`M9vu&fY*YiwM`0=*izmGdZovf*s;b-Sa+LS$;pt8P1>7A+s2wY zw9|1wo|W>X;r%lXAx02kefrTh5q_%}PuJ`Q6FAx!kZkLTY|kB~WZZ5$>R!=m1(=aY z;vveCQCqN9l4Ry;ZBf>rK$I0kY)DzaAwl}THO5{WQrbQE7=T+O3`AsgX(|CkjPVh2 zT#CeQ)K;-G)E%#3-AH! zKuEjxHFl0ghyt@5n^(D66$}uhw1*fIi;E-FoRG7{i(s%gS|-fL;~^=Z|Nh30AK%!X zdv|A2AQ{_BXg?jrxyvmQRTFNzl-J3t#fe$Hr$(6?Dc*6o{gSPo%WtPeK78f)?ZXux z13JG4df`MGGr#<~Ie)&fXAK(VF}F*Qxi*onuQrg0VQ+#44}c&p^c?HJ3F4L1bTBKJ z5YHsFW;3g?!IUxqOt88(`D?8nM819mWnB&RV3X;aG1T$gao~8Pc>q(z&K1N0B3M_; zLska1WE3iBw9CrbI%`Pkq?EhH zdaL5*loP0?0d#lD6FSU+fyG4hV{d7i`%~XX{Y>Wr9fWcCd+d{OZWG3SJ>4jly9*Gp z{oC+&CnG$)=k(>DY|7MO8s^qeQ^mHC1H^4xQB{z%VEIx?4^oD?=_F(ZmPIO`$bi7o zK?G$m6RKJwvVu{mrMOJ>*oYKpRl!o0ZjD$2n7FN2mx5fx+Df~mU&S6k(YC8g)7D*e zT+3d&U_1bX*qk(-9wZP%N^EC(fAtJxLyUyhniKhb7JGEPje>P!b4?QqVNxLB>vg3b z7nf^At65yV+>&7cB&;3t;~Rhf_!~d|{uWEbbJLiJxB%VUPTikl9C~N9kvork*Z3ff ze@8-Tyb|*q4n^rj>Pmuv&R&#{PR<>GkJa_4BnAdfvN^@4?S0TtWTt)x$A3DOEd9B)v<6#uqGzexWSMFLny!;= z!3a7aX&}nS7zsNYuMAUJCq?6my;Y#@vT`00s7dO%jDkXotbE-nnyCuHV4KI4H^?Bg zcvHRj`=8j}0fyJ#|Cu<6ckeSIc$B(~lb(Tz|HAgB%J17GNERp6{A}X`V=-;7`S7;Z zVEOm^eS=ifOHAmCI;Nx=Ct(&7DIGS`5HH2zB34bodBgpF$Jf`F23{u(Y$Q+PN$T3v zv)u%fIZ@C|EAyfxxucc(I4v;He8r@x3liDhM+t*j`HWfzpHJ(YzIatEpDmh}kW)rW zj3JkL5Fy1vX~B>k==u9{c&EB!#I%(|@uHi7T1aD=B3Cg2E8poEUI6&{IJST;Fr@gM zQJTHnyh&*~R>mF8`9^0Wh%@2Z-qXPntQg=NW#!qPXp>qze(t8uB6<~A?0*Na@b1BcplGf9}N|gXwq8jF@3gz0k z=00RrfqmbF?&OTjN|$m*0YR)04JlPG7eF19R*TChvZz`W0mp)>7qvnZb7@-TXYpKq zZdp*)>@+aW7jvBwf!KnHB}T#mzpJ_M#q3do_J3+?-(E8T8=D5;Itt%T)_~A?{6&Z?Q~ln^*Y3hmz^(J`r{ruc<`p7ac})0 zeXR=hiC$kRt6wRSPOn^%{Q;zfZ=H#ehjWT@2)&=p=RfrOm_3pmM06O@>(l{-isE{) z96KT$F#wj;7Fi>(StF3ROHVL!kjtc)I?4YfB(!h`1ymQz`Xt&8P7SSAv|ZMlsJh++ zCkAImqTIDT);`n$QLK_#q+Q5&WPm(?d7qYZzO5H zI6jo=A4V82@!f|Y;^oWFj>prTk;sCIW}e)pj2r7YsUlngK!aqKQvo#~Cf(6`%yT5p=oM*?fb z-*)%l#=SN-z1P-y$(+DO;*Sn+ZY#dNzVP*R!~Nd#sY$tY0+^YtA$C!_==( zK~xsClGvFW?%OU4UNM7mavy2a;Fa6foeBE>ik0NH|pQ_?-TwQXIs-@fj+-&U+~%@hR%OzeVKDG9A* zSWKG%LJ7SS*OBb=BIEfiKGsg@gVwoc9g_W`W8cp$=3TJe$91|^vZ(jyO#TK(s9!}qtko{5GH+jA55qg()08W?Edxr}SYT322584m7j z3<;ntx{7+y0Q?Xe;VzfjUmAA<6~s+Q-z%$2QytuzHg{>--Brh87XnejNI$z|^^%>$ z!3S;E@M{hxnga^}5kOBxyB=det!c%Igq0UymX)FwA zH3Ao&&c_iF#ODxI=5|_T)ZN-27^OuzKcEfF5JhNd0FeN9Y zGYjrY@1cBpuT3p{ZTL0YPva(9fO>Fph~EwEf7nh0Odi1AET{J#<&&$QZvNQ-4(4l} z1082nky=d!J)0B_nm@Xm(4$Xp@7)d#h@(k~T-d=}82<)4kZ91rtE8PsJ9gTUu>l$2 z1|-#>8q+q$JY?GhF~oOY_!%I@FaLb|J{p1R`D?-yGpkyBMQnE+&rJjVw&#XNmNiVk$^_~@1QWI< z0uPXpkU^Q8P%dgsxGT{SLYZX|qLcdBQA$ZOoZQ0Cgs6<1^03g+6oc{<`6QU$NenF=ejSQJ$5wnCAW| zWz1OD-P>o|&8OS4u!ztR^XexTVoi&k@O5ADb-&^3e#8As8Szq37R!8NZDp3FATQ~0 z(scmD=7XR{XAM)?-`wr9!jx=u4sE+eWzZ=NADdDU>;ue)~TMJrUz^#J7 z$cgZL6g-!V?YW0C=uf3A6HtBKfnva~gNSu0`1xV zt(uT)?k;g}nX+Pf*iF}IAZ_c0=eoJTFXJ@31%grnB_L%&K}O@n1GWW3$lNgZ8~_f+ zvSw?tbis>$V^zUZR!TRQ%MK)JZMwi(#imM)O~7YBMLiql z`(z&U)u1INfgN~LivWUE!HS@O3cvVq?tI4rts7PB&T@J{yk$f)nqtZcE4ElbNZas4 zo{II43WB*koRyDjyCfn|CX|rIw`UGi>(aVt#=rn1!k9O@mmHWt$A4FfB&Ac!QgB;W z4+s~*K4V>$;F_g%Z^2u@S|KqK8GwK)x&%n9>w>@j`oh=Om!wJe6zNKrAq%^fESCS< zTG84HFguMEo+xtYzIRX&<8>Tx1`Dve-<=?bC}|!}4x(`!NH%8K$1m$WXQ1Mf?F!VK zLDQ4s`Bwa8!%Be4W(F|9KqF7h#-_%we|tqS zz%GLNw!4OiQ~(oUA+Ca))DK$SuWkZ-*4r91vmJPJFoD2SdU-6(tq^D#(*}Z;WpOtL z`w@09@3JbV_FpO4Q{>vBYZBTlTbE2*ZPp8Q ziSpE7TOh8aP`vJ@Ax0l1>T+}v`?YVigVbjzND^L+pl9YmZ3TF)H!J?C=_VM30T1uC@KUKhP8}IQhBg(d5Go4Yd-0+C?j7w}j@Lr~0zfLe1nGED~1dGm-CIL-bosV@|MD(37To zR`)csF3o9tZ>uY~BrZl>o{|dmAeaNM&j42*DSuoFZnx%|d$Hn+!p7oNOi?rjo=XNT z3kOVzRZ-A?%d$+#No1b-f~|qC2@PBRA9?S(CON7r3Q9O4tJmK1{;#?!BWyH3&>dkr zvZ~L_H$!(;*qDnDLKhIA<5A?1-lei1uq&^Z_c7TvRw(!xQE7CnzOjB?TD0qashsmA zHX06ds;f}xskOo2|D6pC2@gF|RZEpt@JtcGV9K&0!GC^r!XFchTo$_X#Jt-@SUt!n z2&)}^3^+WX!#<1&7{&w;0Ca@M#?~nNwqn~rX3>=MkAm${r`9S&3VI##3cEsHrEOLu zX+Fvct;9KC_1!;H_|dwi29V;tuzl`@6>UzPB^+oyI%d__7kNhT1?0bU z*9=FS)!X@?j^WbO`>uY%|NQfdXHmMFv2U<7nPs)hyne9}(OMhtUk})i?f{s_1M-T& z_!~;5{XXVB362$*Cq;DCkqZ6n|8OH1KFROL5a5sZ4zISsu^+k-P)>gFv&N6-rk7ql zA7fLcC{_rD-`{W8wimSa1^_;i@*p^H?DYZw zcx*%9{rY;suYbP65xKv9*%6e#^z;}}-cctd0vzDn!=6uvuLE9>9UhMZUaw>Lmbc-; zGYl?MR)^6g%GJj3nX)V=Z~0m5hT@M8X{8m^^+0CyI(-c_pz(!Z&j&oepYZ$p1>55r zet!=hIgYa&!Z4S)8c&#CcpS;*(8tz*o*NK70Ab9miUIw4zTowI!1wnC-`i`<%o6~y z>)hD(#(5r%??z#x!5LY@b%Nc8^!QL-kw7s3nO+D09%$|pymHnyGv>^Y7@Lrv&z%hk zfE5El1h)!V|LINAj|R39XB*BDO<{a~J%;k8M#KZYzTT>^=&D;@^*Rn{#{tLD;5c@L z(<{SAKLB=8qunmC+u`f$Z5yEZSk~tksc|afP876kM2yJ@tIr$A{!+TlDaP{Gn(e)i z8Rmmsn+|bpdizz0VNBS}ubpBf^ypnAU2o}|8V;#fRkSBJ6mxAFyq$Qa8F^nE;n0bO z0fFj*R;@?_U0|3><8?-Ke^40Sx#w4jRfoS=yJamorE~5@X0XdGgQ!>@jnz#gloEs}@xnQfR43qGV=kuvXp*LXO??a8KLssO}xEr*C z4PX<)VH>|2uc!?};xV}+3g6I`5w~J58k|nPF&uh(_+z){ZSeeKKj3Hw?5zPF2jFqQ zp6DsyJatQ{!Z@OpeF@fC1ZGh9xa*K9W0k80b9QW!_Xj$V9E@g7%Tj~&!Bg)xzh6#}#BwUh1`5t{jovM?G$i)Woxz#keDX9n)7F!gnaaGx0w z=i!DCq44~H5s_*`|BX9Oj@bjU{Sy1W@lC#)o_GV`eX}>{eb6NGQuXuk0Q5|9f5QIj zOI-uJ#hP2RwQ(HdhBn*R+Jk>>v##H?>susB!L|_)4WH-%M}z0rV3P0m4$s#Pug9DH zs>f})t!=Px2gs(<$3s>IHm5voI?Vyu@EQN-z=1QhEz@;`t@tL4vjqG)~(+#QOZuRx#**A_;*QVwS8;rCr7ks^+u>bl6|FF^`Z~y?iV>Q?a zb#>|a+~7DKyaH>oN7{=rsnN`!813_`r(#He(&Lehh<#U=Jh@O!R$}Cyl&~V<u>tB{DFEz4mm$@Y;-6Re#i$^eodtVuy#pT2CMzCCxgxM~@!a8SKgNWS7`Lw-UXNq&j`t1?57^rd`)>Lz=!AG5Bl3>MUUe10v_Hbu-7RH| zyABmN;Y8R3TGmXmF#+IRn?kf%@@hnM8n@p0RS6w%6%aW6A~Znso2^}auB@@V*ma+T ztVL|F!$BKhcP>#<61GXn7a=_Oq_^G7=Pn>k5^F*H%s+9?I2-A_dCvdmW3}zNJ@KmB+;DE z4;W(vFqSHXAshhvj_`iV4Ed&pfUZ0|#!OP@ei0WL05dX<{@_ighZ%vDL8S0B0AK+O zCWz%Zx(XFD2FOYpY--pX$54D^X8Qfw;rZO*`FOzhYuqv~Lcg_x8FMoQJ>39&K!d+s z@o+QkdJJTw??ZXX8#97+Sv zZLEm=^Xm)#^PgYvKmWtW<^E^5Gd#^CavHHx)3XbBA`^{}Wf4_HlJl^nl?67SQ zXzdM%Z)ms!;BW_%Tgc7r%Ql}rpHJSXKVW$9X8p(3;3=?#P1d0Ll2=Fvju?-kobqP* zuYJHKOZY_Noc{NIKznUED?E>a_1N&kT;4(Zb>o$Y#>@O;rhm9L4IGPce(VRl-`j9Q z;?l;7#KtQUU+|y*`~&~{zyBF~NZ1JUE;Q;&qY5l5R1E;JL2n4H4+B~@m_N3zZX?@v zu#swRX;+2>0H_<>)3402G5C0z8V!Z!@pZR0x! z-ogV|k)(0?pH3i=DPQCHfPLHH#VcLU*8_fi?ePBfr7klAj;Fd~h*AqU#&+kEy!=IQ z;sT<)C;T;)!9%faAPVkSNt798=i0=6=fik<>uQ7^TT2vu<}=*}MP}yncP7@tszhfu zYdxF*com}YiUjiJ>A2}yb&JWcV3m(RjiJu{CUwq0kv^BxJ|k>f9_d4oYz!fllKGleRHQ6%6=$w!LtJpgx?SP?C^LD8Tr)*EU)J=CfZ&* zym<0qv~>f-U1cS}Ta8263kir}4@wSaHiqbXcEhyvQ(YPXKv zc{4SC0|0m+1Bnc!*bdRE<_2{%LqZIQaHPb@Bknc9hzLxDK_CRbIa~Hzs1X5&{YS@G zk>KNKQSvgAYMlT!+ZflR6H(~aS>ditz7y2)5^3pt@4aG<4!v0o7A0O*rV71v4#|MP z0FWa!2ePi<@CWp+MsgdUAP71IQZ~%y5Vvx_Y4kcl=y^k59Z5tCCZQxY)Nc{T86jC!Le(`J>>aPfL zR2TpdHz018&Q7x5>-&AcxP2jDALshTz+|7eD;-|8jhJYjzf=|AcVDJ zO=%T(CbHXj_v27Sn*d-xI=uEB9kGt9QzkxSe+7WZ&;m&>FH(SeosQuVg){)nS$m&$q zuD<9|D*G%eV`4HQWIXYh8mkdl+f?E|2k~cMO$*R|*)Gujd2)VLtkQ{qO(Ss>DBE(P)N( z*E>=OhJ>RTgpCa-g8qEi9b=69WAAY6LLc+#cw#V&i5Y~)gWqLe-X<&d?nv?$`Nr6T zwlV(QMtk0y@qF&^e2#JW*ml_3J|^36T-F$jdKkBlx88Z*uIa#^8WW=1DM96n}CUM0HWQ?t*PVB zbvDTo(WtY-xNl;(H#I;S%7z#ytu^SaLGKM3bwFx-q?sQn=OG}AoDCt-ZW7y5o( z&(xW|nCdxasNT==-wmG_9IO0ZON8qAPs86SYmhsyi%dlhy6-~xX6eF#;(v*HUi$0x z)W7GqEcd>6HDU%Gol<=TWS8o}{6dGaV7ICwg8DNz|J;&spT~7GN^iSs`{xvZZe!Jps?yO4+jSy#P1xITqSlHe}pb zF&_(&`h8?6qsTOHeX`yI3TD}uxYqnGMr;|<%?Yh-|+Rd z!{fOt?ui|-n?m??tcQ7IcfE(8CjssI z?)Hhi$7IR#ttb77>svlG$j#-l!L`D}HI4xMnDwr+?x=BY5D~$#paxH>ls!O6$Fn3p!GgQV8P;gufXwyM1!4JsTw3{N_BS~3_`82Fq9)`Cv z)1pF^_Zd%%%p-|s{Ih1%XAa7tU4Pf)~p40Gt&)P(eI~ zp2f>%NMWvGOrUI(tPtYrJr1%N!1oR>z5wd`HJ;!5p{_RLTz(c@?5F+SpUxLN(fJu6 zoRE_lJSGI>M5*uJ<0jW{zU}tC?_ne6Xw#tz!04OdF4d{qakknAf|?m1a&53#y>Z_C z_v;Pc-~6W+XNfC@ooOy^5eFX`yzftVzaM%uVw1jW?m3dodLASHIYr{=9e)4!H~jba zZ}|P+Z}|Rx>k+JSgy`^5H>K(O^@iu~@8NEM2(Pys6S{>uOIX5~VWpqOodxgr8~*$I z1^@m1d#q5n`!2>`2k4FaZJaXo{Qic=W2|r-a%`>kRgH`Ii~25qcGRfb-0SWm(IYm? z5=W4k&W&e4Wn;V?C;)+8d{_?#f2kF9(tS&>*I{GvCGUJJs#Cf}*$ys01mI7vmxXEs zxvAOs*Kis9R@cN%1TWspvoSG71Hzh9s*fo3k6&*{dx_0 zku&?d(>+2@AVA`)5~A!C`HT+7`B%ywbf|kt-ea{=ZsdmTJdc-(6s|zd?FPoE7*0#rs50M#)@xG7Ey}y5d!}s?~jTbp8+cu&* zDn>Re&||TtM{jV;{X%vZNn`#uHQ?Ju4N1*+RJVX)yd@#CAS&dMFl-*@AnnY?`83wu}ux9VcVL&yutj-?61R zy8=h!CfQw;7d?@PH(l@hp&QAMV{=OJgO&R?$Ze#V?$%^jEVEaEac0Wo0pG8;3DKAM zPur$M0G{pSevxBc?G&z~psLwmjBPN324F0+2SLKmf;%~PUyKMjGI-w~yhQ#mqXEQt zAe+a*G$*h?s;5d3dh&iyA4b>rH~jbaH@sdiJw{V55)*^>=t9RY_^o#i0K8sff14g}@CaAqH7F zHXYA@{`TUD77`8HMov2oD!Mzaa57(xHuo{IqGp?{UrvefV^qeT%-oA19rq7_D$#08 zfbg%bGFJ3E?Sj6 zVz1Y`)-zm@D_TFxlMRZovQrxoVn~QFAO6^&&ZKNEGN6;q05UW7i~3UMbjIGIrENlg3~8k_Dw$ikD$e^>`2G$iP{bSuOt zt`x*);W{HiX8OrsG?ykm{iJQsTZgT6=vxQuwj$ABgGLYjmDLHpWD7TF-7TMWac=_M zXpIEA8i8#b#np}j@+cDVAao)Mcs|-!*-Xffwj>623Pj!c5Ie50{=E^QWde*MFjoC0x8SNvi?|!`2`c+>*eNtygJa*| z{d~atwdp2PbSDf6S})jA!mWSF+SPcMOMqVQ9e)4!HH7s`&Y15y3j_crh`(7Gpm96t z*L#Q8>k+ENi37xt1)$90t5DfZzzF`vip>H2*xBIP;PJAv^dIiT5Ck?N!1oz34jtbp za8el(5_eG74eH;oq1=R7QdXQgvTwS_7Yt)qZ;o~fauo`_9@LN!7m?Qvzkh$jZ&eoe zIBVBIH~#-_uR%*RR?Fn1m8!D2_fTzLH9XuH@W+6HO?*X#S z>;bL%T#wTb7!<#a(hLe>rEAdX_qQ`Lb(PU6dMkkvWVkmHVh5o6F0kjZEt4d2A{GJY zid{U7OI)_ieTInO^?HrJ@0S|xeu5)$WBzq|3dNOxw!H!6i0e+!u&L2FRzrDJ*41P8 zEX@5dheC%Ta&YYMesA#o{bGHSV1MuM{d^C;?~J%JMP-)cHLXy3CK`Mwk6FKWMJ~i_ z>S{JlYZ7B$*W?JMU&FqaTf$paQ3Shq^w3T4eq7omuFf4#j5>f?k@#WAs}kiZMXoN; z!b0Z(Rr{C4l<7G%p(sI3a7Qm}7<> zHmYJF^pW`a;_D4!WbVfSulF0io-Y>80)~U*VkXC42XU(50MUpTvuw^_D4tD?f{G~I za=Hl7&Wa4rrpbkLZ5*xnehj5pPd#FRqJ{+es^+mF&(T=V!56|xAiFy3`vEU@DSCbH zEJSTtAHWO=IcBo=p^(1#=4ge7qPjW5Is47a-ijzdx(bnsDCEQ+F&z9xT7Nge$mS|=eIh4B z$#3J!0`npUhG>v?q;n0%kepplm| zBE~HA8^Wb@fhK3zPZ*5iBK(27-I-^&{VmqE%HrGOl#)MKagRoX9px&@`o149c)6cs z+3lEN@xgC0VQMQ9V*-Zvd%WK8+RcT}d?G*4VBvAdY>>Kn9DGt1=$$cgPl722!&PJB%iavXg%ROau(%Nu z{mQxg2Os0B%kGS~aUAEaMByiC#zZnChG8SKW;^@T z+lquL3;=-dK~LkPlwD`3MR__4p=YxqaG0UG^Qw)&b9B3=7jdjQz0kq+-pv3LW5&^o z2|KU!3+*5aSjDU=uzHMWmlIm#?uAs0b%MqzS)lD{vGD;@rc`QSNJPb)fG=3=-6VP=dsLivc7Kx< z7P+e@?)g{;S4UFJPjhJ>`uw&cG3Z40D(uGZ(D+<@9w+$81kB;a+@Y>b46lMo3bPm) zqO9+50Kl&FsuLqDf27~!7V!NY@0+Oo7;Fp}nR;Bwv)oxhj*kwwJZ%I%>ceb*PtPlZ z({v%}6C0Z%r~I!>`ie238?K!pVdW5r+!6hiJVMaZvK#1t>hg9R>|U?@o=jf4gB-$2 ztLkv)G?^vQd6-kt`cq7_8Xi18?`U?u7{SsbGXX@1mtd$;ZI{p~f<)+AZje)#bk}_I zM<@;fH!d*3unMusY6NVofDC{0;nE?742#rC68v$DjY%@di46`r$65sT zfVzpm3;ke5gjedv`!%YCzz6Q8t=y^~p$I(5;J9sG7LyeVXCd)V8k8R!3toi%JAnep z-3gzh{h%ao#0eK+yr1>!WE`?&9H)uwgV`U)I1bd^^6HO%)BXm>tWpJ@83ah&k!q@D z%F)N#u6aMixgp``jAlmd{cQ)#W=wb`LuOImMOlVJQ7o$q1A{^ezD|n2f=>sG z=K%qFXGDnNrWbgLQrev_b(fQ#NG}%E{Rrt^jk6U{Uw`-&m=aCNEVL-gdLR%H><5@K z#WSBGNBq8}pag(X7Wi?cNM;`E@#JKY8MF+0!m$*UpXDSYH(?L)_`Ot!dyfh^h9^-T zm8R6l_p`C?YDD;p)QKT08Nzp~Oua6s!F4s3vJS3_Ysy$)nt8%|V-^nc=_#qEgP zE^2n8JETwEW1{LkEUu@~H!h)4|e51fG-l>qWQ3>I%t#e+4d ze2kQm^vp7qD<&Be*?C{SD%T;lNT5lVM-E727ugVYt@f{44Gg%Jqg&oh>4vP5DMiZAo~o; z9*G9jNLM5p0p9`9f=iPa5{-tDK^=KdHZ#ah&<_CGY1kNirrjZ{5!(*ivB7bS!GGw0 zhvEK2vYF8sBqG}7VJujn2i3wMf7Cb6pw>$Auno{z6%I#Ez^Rb-%A}LZGFYq}SC%&> zlwd0u?*vaB|3>hXcLm4a34xJiWk{P#r%fla#FAXZ0`Z9)M>_y^FK9r2y<#lFHX0HX z36ojxu?^(`OWay%xq1QK91YRdnPG+Hh(|nvtDnXB`Z#j$9A=Hk#Exa+3XZ zK91TppId!I2P?%L+ItU*ktw92Ic69c<}~=J&*5#1A$X;l#8j12iMy5uZ~%XsaGmYwQ@XM@`&OT6cp=AKVBnL zWF;!SdBQW-IZ;N(?DGNp?%}8uPgihmgQmk6uW_-TVjCPi0_iG|^syh;@i)gu1={oN zDX79|O&Y^t2>)Zw0m5@lUvm0|;w<)y=t#s`m2DD<~L|ex{Hn&T!I9)aZV6Mh6^>;PN;nP!&s_ zBnU8>k(3RI$kdrR%QFD@jbyz8Aa)=^7L4Ao<4jz4SS9gI!}RMKt;VEN0=RhzuR(=! zrObUIB?kc+86uhtsg8NW^=o8nTl-G{~B)b^Z z-yC2p-wX&K-&-DoQ3;rg373ziE+A7P9KZ?(I_1F0z)Go~TN?%ogAcka^UAn+(?#hz_8a)$zb* zqfdBSFdW?YH0~|`dfK42RJ?`@2Gen_H-CE)(6xJsrf^e zCPPB%@xSuo2{DkiVmW0}ULI$b#wkm-w?Q`}@;(XbgE)F8z&=jL!Hob9xmgm~6c`;T z{*1_{Er_*AM6gjGD;}Fu61L%9)k2E^Oo$63s(Z^D6cN1>))K~M6d4nri6sOCB|Jcn zeSc$OonH+XT&20su~#)1ko=_WDp~4WLQq=bpu4Bc#B!w{0|UK~OvVsgE(92UbUm>_ z3iu3yf=CrKOK!&qI~M2aodBtW-dui_*hA|i*p%MG;kiqssVw*<5&`1AL8(uKZct>1 z|M$N$Jm}gv1cbF&nm~L)0$Gl_RV0F$SXhVj1M=S>nLcsde-7-Ak6vH@2aDoagJr9?N z57Jt+PlKZ2!4fIw>C(gM+pLH%uH(n8A8zRTw7}bhpF}HuCfdGIO7BmZv9^ZU*{ClD zVH6a-)Yk%s@HuG@#m^32|L$Hew=K0CXPiW~GV@HIDzb!$c#AfrXabmK%(F5B24mpW zl8Y#$8PCGMM<>VuDsl%`fYhzh%vy&1`uk24Hl{gL-j(1dH_pkm2Yo3LH`l+?P{4l| zy3gZclG7nqS^h<@StVsu7_^Xe9dTb%{?2?WuJGAvtk(@gr}OX>gGt-zsuz5d*6aJy zGYxrCnqMBjz@;Bu& z2tH_MkjVG)t&TX2FwAX;Usm)5kf$e-zB`rcU4Z5~ot}b)5Cu>p0=&|iU_uZ9;>NKP zPSKFaaZy()bdZ3LdQ>@H=vH1r9iiAHdYJL}`7RP>#L~=j3~x->H|rN&-J$4m=Xrme zg+1d72-(mOI*3YeYNcmWnBoNzSFD_}7Pjnpg@W`c&rK_p1D>&ExAG= zGdyyn)fA5v^-Fln(^J*F2g1F{+zU17syi$3}RDe%nnBh{|P;}%n6(uMzwtWuO8RxK zoTi>&+`~3&9_tkZ$ItY)qKvt<%Yds?&N$GHF&g!=JRu#T>1b>NczJ^mRwQDzo)FaU zOp#J;P4z@jAOpdcoY3Dh(O{zn4_%SqWB$l?%fp6dOtc{>%!(RD1NH-82VJ4)^svoG z+GIN=r2!vb<{9xw5sZlyej@wySYHG;&IW--0W>}&XJt)m3?5ypx;7e>}a_RA6ffuFMjH{n%kEXO42gOSPwwA0*!~;*^fB{^=D>K-r1uBykA)y)`x^i^RaO7d3UgJ#! zyYKTfMk8>k&2y=1aTl=}dcCBvP*eGK9WwnO%pDcQSfNsA9L9g*_o-1ST~KU{W*pY_ zejoo#jvs2jOWr`9IPwG^3>7>M4qt$ir%s0D)~W71oeqRv9?$();NeWM%Jed-bhw`~ z;?x}(1V8?-IQPsSRt4A3uA5T15#~Ew>|T7F(hTV^yafQA4(UqbatMs4yWDx~>Kj>g z(Z-5A&Wl4YJ<4`r;$gl`j%JBmdDb8od%sM;4dGB4PR2(ReRHhpEz0m=>^j5C_ z6BNiQ#lsXK$W$;y4hwQ|DUt*wz8WSm@*h(Qc?zCXi^qr6crK0BAEf_26L%&xI9w0 z9aony$>{`+na#LvWNrPN%xHQGY;nb}ugWSOGmPFPpknl;-6f>xx$ZJt3um{GUk}{y zSg^q`J&u;j%_QXYIh~nJkd(wRDU9f%-BGWS%iULBDIFD)bRHFJJx5yOeNQMeNtl$D zvcO4^aq+}`BC~Co&?T8FPv~IqZ8xDB6~%}j#YvDkUI=AjWWdlwpasLPHdVz^a!#jg z`MU+ccrL)Aqh`cjiE4TrrI+V!zI0}CsU!z4`qnxAi}pN0K~Ykw5#ev)q z+n**LT!o?WS#L6jqdb-;)M zrbfk>UDx|ZByA`#vr)&|DQ^M?2n^C?%l@>pK#M|XZo5yt3ZB8t)NFclp$J^P131Hh zaVP>qtHMx+U!4Gra}@*-XTcIyV@hd;>0^L4y@k#&6ckxYrd-gQlSiN%{5~9=mB@*u zJ4Hl|t~J00rytwW3qktEUlvkxnB#I+jI2Wj=`(=2wmF^|SE48)(YJFlB0Q|VAFbdk zUUSv1Pd=}Mhr-%36_**nkAl&Er62;xn2-G)T>-3yiWux>Gx-|OZ&gBgQ0xU5${6Ctu&Z=V3e} z=wvj{u9N%bb&hh61dRSFT$@}6G6O-Nz?aLW(W230?0x*j)ri&_n-B8eL!s=CK2{_S z92*=q7^@P{p#vYm1>*n4*@yu92CWTaLMld-3rl#THy&eCH-96L-TL5UkD3e6!5LB{ zbc&&!!jqKvD$cLz@~}$FX!D~h#j$`i=zJ*0nse9q2@8ra()2NwJKom3&JQI0C&jsx zQ!}e}&og8)6z&em8V)%Pg7jH@$;IGArp1v*q-$hHK}T}~QOl@|2N12}-5rbEs z`AcBpNjHgs0%s6`?*&&Z3uEL8eN!L$h6BXitd_x#ui5NP6$IKz-!jji23aLebK3Ee z1p|_!?I4>XQxBZgk%v|rX2VA0Qn)XOICEbchnW7P{Kbwbf?6q@aO|0slah%nD7?)u zhjilCEYARDc;-w5HW{Hf#el;=8<;TaX)cj~jnOlX;pD+d8_&bJawacUMPU@rV4Z?} zMN5?0Gmn0pb+BAUX4X^sPjHol;bOl?#F=;ZvQ9Odf#s6;%un#xq|p4Os@=n9!vF(~ z#yq)%Nat>r8!A=~G*?5GI44fc2t#0A-4Z&6y^lksrQ3RmUcsO3^Rx^!3LrxK3W z5S-MB_9IMNbrf5M)Dt#PHZM{n2oQ!U&!nSphRrKLCI|cmCr?H}19C1wRolZ1{Um)7 zot9LL%7?>BN~zSuyd%yvNQ$5OHIK%s5_IqRcLh)t7U_aeG9b-(bG$*&ug~a;ApPdJ z>I{MFx9TX#;I4f#211>nM_uS2I$TXfd0JJ0X%!E}D3z0^ri-?f>z|cE=%%)V0^wG# zrY#Cm2}A`TuIgdzBu{$^WTySIU4WuIRx-BD5jnuHqJXl+7yy75@F>ibF;} z{ZaOLJEt#ERibeL8$7E9AuD4Nf*yj9h4Kg zy8Wb*?*m$nw^^C+F5OovMo~u8!7Kezyvoy0pJ4x zp#fqC%YramLo8^Iu`3GNn;zgN*oxhJ*!<@T=XI&bG{kj~~~z$AI*=g;(zl(~lb z+p6v|Z6LIi2JKmyxH5T9iwx7$XQ`#hMGIGgD}m_oGckO|l^!SPVb98sYfr4`CehHk zXQxu8x(Bz6zN8oRW`#le2vfJ|cj=!r17;S<1X~a-1z{?$Ch4zO4hawU%7zmNm7tXf zzo$&op0l-pvrAq>f(xf&rML)Efp9+t&^i;I+SdF1kW!}ke>PXzg>REC$BB=AF zamP5K6?=n&I$$4)Jh4Hcw`hwT!?9{X?2aTxMDHDt9gT*fgd-~ubi%N)m-L$Y1CG|9 z?QdH_pm8(g);nz52CxwTJXpw%fhS@!pJn1ZU?vbuam6q=(Z~K4f%$Ny0x7IlV{ZYR z7=bZ+T#_sq|KE@)C1^EExsTh(`j!lxf9HdcV^3B~=buyD!>?zspF-0*TR!W3`+hizKW2+$x;Jx ztXiS))>V5r`Mi@dRHohK>hpT9Um3~eWY?2YK`-iza7L*r)lo{HLoMiH4s#Q<__(5S1UgJNDu zS=U{Cna#*bTF!JX#zZ|+?Fj0YERu9HRpImi6CIwGTjgKnD`{UMD3VqHC%gSdCN&ou z2V5l!Fy%0&X(Eb>REvTld>BW^dc>?wgs7DXySp zTRwDF(IuSgmL#G3%KY-||EfrU&!GsWm1*&>f zX-FZ8QXY#_WO~G=@HYu8gLaEo{|Y69E$0;yJ?w3r3bW@RUF0tZ%J;TZX6$`9X@(m03J0P&P{(VOIc7Q-|P zr5c7s%CI!OfI%1~IQ0bQvO`Fhb!u+{<|SV0a4B`D6a*e>{1(P&rf zXCbvmvF(nvF8j#g*WzkrwX(@3q3FxF>qqthSGnF~Y~QDSQn%}}&w`UJfrnLmZpPVa++9%Yk9EEKc{~sI ze-TPskIH*(Ob_uSAiUFK=aI$6Y(UuImPwzPegS|t>&a?_84<^Ez`h^DwTahE4(f2g zSefX+?oDpfHX@(0)DUPRXao#PgJDPGR6dpg?fU;i}&Ho9q`w}okD-gtmc|9yq(qY=f=d9@RV9V zMk}T003%DR%DAY?{FuOep}FbVj04_u6RjN zslNG>QY3cr(4k;P_}s8;A3#_EIcvuH5-oU~p9&!Tb6%0#_$}2PyRq>Tod8@vdrHzp{l}e4V z5!c5HCAb{oRoW%uGXJ6UWj)R;$4P>zFH(e#1&2RXlzrU5TsqgNgfWPK#QKGgE~Py2 zm@ZE!O2P4H0_&peEMDfjJjv?(yY6+#@ga?mb?~HomF|&oTyWod45#N)ES`S!KxT%G za7mPzq^MYt@I_hL*_f!xRKU2Ewkpx#IEFESUTLBkGBeT;c8#zxSnK^LK+do;$XMW+s}H#mBSt#7bx2iHezv@~dagVqVC&0KM` z)k(IAJDc*7JE$@u^39VPd%D-GbY8tam(FF&t$CAaRwvk1zxVwC9?1fC2u zMR__#8g)*Q8zT!L8V}(?G{Z#<q6^E%G@KGuknwnRG)4!^yBdjW7A`cxH){Ipi{~sD2cRDM237 zcj}8oTk5TD%m)XJYFFt+SheSLJUT5+IMR>86;eG-l#?ZAy|EICrS`FSDY8wg5es>J z8gNal%ZdZqi!?Wj3n|Y4&hjM5DYOmjzN8Ez=5i`9P9YSY9gT^KbbQ=A@l&mZ%Qsw; z%M$SU`^h%7xWCMxoF09NXVjZCgfi_do>gTE`zYnlm*kOn;$h$^ZMKfZVt9`m z53B8OrX!gFA)BoG(cw6Dz@rTTOAQV@%$PtiCWcf&7z_t>bzmr6ga92nAT~h2aSSZk z-_hE*PeKL;@4q;R0DFf60ot)a-^L#T=&`Wdu|eO4s})d#x!WQdwbLi=B?68~z7QOF z_1Z7Ho)3gi!e1%myoMW9T(P-7hT&$KTQFdqI(l-D;9w%gCFERzbrtDYaYML zOgBKm@q9V9t0}Z6bzEG|&5E)Atu(|DF)5lf_l?lH`0!`t<=j2X)$PjmwGvbcV2rzh z!E?QG8=}5aQicHhDMyyZw=Y5_|4esOXjxf6NxvsW69KXXfB=wr^wcjaWoC*u-d_o| zpr1I<35vw&c^V-L@{4#*3{=aTxxtxWJ`G_g{22$!25(*3Jho!m&pGL(Q6Gw}_>Uww ztE5U*jr`SbZWqN*^Ghmsjh7PgK)9J-7+)x>DhfkKgGTQwoLM`(rf>%0j91eyqMSLS zjl_@2Nv~9r=Qn}(Sk`#p1L=6ix-hHbu4;mg^Wb@FDdn4+_Ome@`l6)u1W_e21XuYx zKYyn3QSoH&BW^X8{dmc;%I=LAWi5^fhq;N5+yGH$$UP%UCk{(88x=De{E1C&MPio~ ziD5`|JjNe%Anef5j?)AHH6(^BlbqIsaA1dqW5aa^tLJEKY|!SF3{)4Z)W&u|=L_rf zPK!2HC?0&dot!ZpM})izBM>QAk#sTGj(Vf-&cb^M+u`sfb70Pk;bwBRz-DE(wLS-c2B}1Rjton zfwkiZW@93WL3D-?)4x`6v3cB&iLA_0_$Mm|5%lW{f1RGL7BriWh_M zr%(b6)h|Lg@gpZE@??^FgQ1j~6c(JzGalv;;M%LSm6{hvL5ha?li#0vl6z6uop6!X zvAk+r$rtnjB^6&86CzHg?Ov87Nz}R3wEW^no)`&Ke)sRuoi1Huw?KSwZDLWN!=0QY z@SW(ZrSPv+l8=6sKR6JO4(QOJV}}FBY6M>~2f8ZZ5YUj1g2e`MG^?m)589yjK2Bfi z9k#8F5=hRx9V-1nPr}b~{o5g69X|oYP)F`?RNN6iTOMTy0}cz^XAIgCD`KAozO1 za6+4;z%bbW%nAlS7)>UtYuc1mg-}z9clm!hEdF9B`>?zf{al`2txVhsH&ANoYPF@l z8aGjnWGQxasqjNj770bWP9z9Q!g&WpRY_JCgYx`!(TX!?*= z8~g=cL8Hp*a)J(hs=3-}*z3#(mfz=)OC7MTeWIz@^J_qci@~@&ze-7G^qf%BfyBPS@aMa@jro96hKGzFqeO0;QLW;Rk%7Dc#+GxGW?@cTgpAs#Xgi3 zwTH+*62dwEUH%Qz@XIgNcvEom>O)myB7un%oH)ByRX#urYNXi`)A3!|e&)^Y^%UKXi;8hh>%lwMf?lZ)ZISQ@iA&Xs8+kI|4Xw!( zArra4$~%HnN3wQkK-7m3LCpz8W_b;u(YWuSwFYf#u+cCg2sXpS0pr9b zfN^1+2vYBM#hbvznArJ(Iw_*#aDM{clQEu0tHljuv}s16o*s}!X4&VY*>s7KeEgp> zFJI3Jh7W@u_m}C;wE8>1oYXPl?2{^VjGX|nDp=JqPJoseLq>U9C@4vw-RFZCtG=CA zU_8sk1uMvCte{9OqMp=9rB4=hTpe-mus+2XR& zS(z0pW8$Y&I4cgHm6z4O3brzCld+}EDxqA3=k9``(}w{x0xs2RLYjLiyACk16k`dlDkLxp<{cNnpeSsD?txT*6xRB406Gn&qO70p@ zt~eCu5k_)~movEL5rcg5HA3XcnEqlZ(fP@_Hu+=!W`p4z7!fcl5r^S}GbPlGsmpy5 zI94SN-C*5e7!iG}PH+hbz?-ofw2fec2DTa@ivBPngkduuFC!|U1ST|7Tuyi#ex<(DYXldsbTfyo!mY4~8 z8mFo?u`jQbS1ZqnXL4_@$h>9d8wN^jOf5oI9F5`C<)_Tol7v20 z`USx!X^Jr4pge=9(BD+Xh2Bkk<)=pg03ZNKL_t*PiWry_<l#lN0r9O4W&Qs`w+fKhL2=Kd^%cCikD_?f5t>r1vyD0PJjDkVZ&ndp2F>_G=KXtpZBe@zv3LpI_#x^*K2f(Kt4Tw$mOMuobD-tT;I>CeYPiz|jJy-xe5U4dJc&UR3*;Oj{OJP|$s~~RHQEmjD z^-natkZVhl2#%t4zB>US()qn1dcW)dUqGP0pM0;3nyV1e;GeRfPj#IsE2;FD-NsFI znb8WDWxJNfOqH}2Qc?U=h0Qewx4lLEHuj^yIfv27WRX=x+`2A%K>(+`PYh>@KYRL& zz9XK=8BW2#!6~&0%nYZ8*x+{1Vbyyl_!i_8D-ljLaFCpLvRA|-ECT77A>j+dgzW2F zAE_zmALN)$H)#_(!|`GCA1?_15=6#K&aPxqQJNv;k`AxNn)^J_5&zs(xIPIherfJw zVn8hLvo2Zl2I)xvZd%S&==6nPL^!(D!64oW-k3;@P;zie`QJz1C|AqBV`W_+Fc=Yw zwoO?~X34YV_4-N#_`}fx0I^q{nXlgez+=8zE9hf7}aD^I$@fP2){DHXFBnH z5o9I=a?6k*ZsTBBf(8$kuh^s8kyNPrGWf(MwqyW!uLK?k?3_+cnA(mG&nFokaJV+H z#R3S!<*5%10ve8Ur?jK|j#POK_zP-N`CKYBca4dhG3ERDVCUybqbu^9mx*fhsXs9L%zeE=F^CLX{T-+p1n<}S*a=&54({<%{2+&%;cyMNB5ku*YIdxB6bm&$Sz%|L*7wd|O$Z%Vk&u zwjx4NVwzFw&92YYBgKFiTaM7>#4c4bDrM;8Ek>PT)At6J{RRl9%4*GXlDd<4V_Asy z{k%UbbEK6#@O>GdDzFkC#8|BA3EB&13Y{;f=&!qi>Si!jex3i)2)i&M>}hUwtwxMX%DD;p4GM#KRf5XWkSTv)denGY)y zG~zh5NuFD4>e6J^GyqWt>J55pT&LAfy~9BO)P@n!jt+ere}adG8?p^|7o%)R9$aJ?eoXGQ$5CYc>`pak6C5nM}Tn9B^pVr9(73p-fr z(q$b!L%_AqL#b^{oA+mjFs_D5FKC6?Yd;mVB%Zt%U}aboP4d7y*uy1lvVS43;N+r% zQGwdt(-C|!2&_0%Ugon2?$^S2t~Z)&^YaYenTmj?uMyfgM(Eo8z!-Z;SqQmg6QXnX z(%W}G=aku%NV>~hx`Y;p`Ka5jFS4;{>#|F9a9X{QKS*z2fCIpt=p`^v+=`p|%v3BG zJ}-?4umKP>33fTs{f&V^*F|_{qCAow^x)~-Deg`eE7ydM)#J5jm^$bF z3QNjfD)>df`8TwXD8N3s@Ga{&=WR%l3p$dG^?w{p){IJjYD6qFtOA*F0%Fp>mbywD z0|k_2$C-W*O;%uIVwrIfCMqr-eVQ!e>q8)_T)Eh)U&77SI_^YUB8Y#h_7v~xFKZ8j z(U?4p425VY`|b=U-bDerp8`8H-Y1~~iphG6 zgK$~YPg`-)}=iu?!2Ja5itZSi_P0ECHf0sQNLE6E+-*Hc%@vEPYr3ih^M8b@_9~>f#?K(>&TD8Nw2x!@lY8M_I&Qv_6bzi z;ojIT%r6IHaAUfsNrj*I$(Uw@tti+bd%)vT=T$O<;NEAe3Bg*j->MzXQ1J$YKRz>) z;VonE4)gp>A2~1XL@v$rOYYyZLhmH{vtY-CBI`D@>jq{fl#MWLxakOLXf2xXiTwK; zXef^{AaIJ53qPK1aQyWni0>E?<5$d-KgY?RlpwsO80Rije0$ByQ=%!cgV%f*SV`Fqf05&eNpN?$C z25&@AhmHWl!KsD%Q~+>&)EczbVQUR&YXCG{oJN`h5beGQ>atN9)U^qq4_79>wC>ms z*xL@+npWC-2feV4XSD2hq!ElMvqE>o*wt>*Q>Cq?Z669Ez|O*bf=tuIDl5JSs~V;tis+j(@yq- zQp*iA{KyOXVj!ClL&=z!GZ_o>`yt|zn+oc9joqD!(+2;$h`Lj)FT|4eter&rZbaJ4M)%|*?lCiAjv0G(jsV;1U7o_pFzUX7pxZ>GO$ zOjE*P8Y%$!z0eQV!=ie-X&3~?w7|v5r?ar)gb%Z}Mes@mpQ;OP0D1yK7)C=Im&XwS zAT>26h7o}fa6}#ub8Z^9Npxt$NJZY~fR2#GeX1ceXlz6f5RH2#gkbO(c{+ADI3Malvzi-RRb9h0jQj^$@k2W~ zOJFKWusQ<0X9z1OQYnGX>eYx+2`OD^0ti8-RiH>akzd9HCu#w;WI2)H2w~ryJD(@y z3AD3P6JnOR>QF}!h;9(xy-?#`fKd*<=HI$P6)|yb04(4s%2Jh;>(%qYz>9` z7en;OtMn!OdhS^Cd27hi$jUGz2xs=a$eXjQRdRq#14%*6WiLsx>Zy1W(D`8=vwrMf zX?io*=JOQK0s;Hl-%9$a=yDuRpLj*WGko^+Cs;|~0+JcBu@?fs?~53#5aaF#By>l$ zN?NIt0xY^;f;tc&bVLBYs1DJrW?PW}XiVV5o3OWSvpz*on2tk)T8GBF=S7L^M1aVb z)wKiKzQf)c;67F)#2u=&4Tv^qZJgvJn3h$Tp3x(-%7sGp3AxyRJ1^0EHrsCyH;>W}`@UeSZp@|HuXBy&3>)G>aHA54XU3GV(B z_k4?uXBgoehxz2M)37M$s*ffEH8CG#*-k3s&P*t8i`+3Hd~6}tif~N=23I)Vv@jyd z6~i@X9u51g}R>;|uC=DE!jG#thaGq!7utJFdY-)-cpR1OVCNK+t$bN6CTf@6_Sw z2eiJ!aWuevANV5BzilJfHf{rrdo8q0Y{=yMC5R0mugo~KEiiu34_71MwsLeGeyUUg z)PwjsWKnif{_+i1iE2Sl@pr!QlwBf3@GLl8(EDX3at(exOG@z}Ol~OYV~mp@rVD?` zk`?D55hWs^%wFPtg!5jAqJ+}ZD!4IHX~?dPt2zVk_B10}L#nQ#WA*Q!#>-zCJXK)c zq18k!AEq~lDpr@cn=1kYpJINNl`F6CugWSxw^aw3gz?6NR~${y@{=l-80&`lIg`T5 zmd#7Q)6O$G=+%k=4UY?bTxt+h)YxBQG`wdib@zlYs0N+M4|h&8?QSNwAP__zn_7P ziGD!uZ5R=_N8OH$u_7Y0jzGbWrluLK zR>6)hC1rq?f8Fz5lweBxDZMZN0?;}A3XDmp&Tb?&YZO%~NpGwo_Qk))_0b_%o}+K~ z+#XTJh5}gt50UQPFf)ssMyr^Z$$9u-*qs>=74NfW!8d?IESQ@zsL>EEuFL&;lYW=*FN}!k zZX-%Zhq5j-RhUEK4^{`x^6pe7iX*0+EiQW&u z1L1(NM~HF^oOL=93^viNly!l^$xmP0U&Lpdrtxt$aG z{R3U`vMl&UTt&wPB}{6RBsfOGPjs!S1beS5{j}_955V0LO67e~2dA7@ zgK~XINaT0|s9G3$z0!7kC@dGs@l_iNSDLeZ5_7c}eoG(&Y+~pnEw5yGRb;KMsqFcL z|E%JtOOI-#UsA~(rK^H>9;n=(C%k{bhqLM$(EkBwd1S77`-(i5Y_QA}73sQ;qC^Bp zOA;kKXCb#S=r*@p|2`O~`i7csT6;^z#1ih08Re)ln(kK_?uF~pOfI47=V$eKK05c# zMKu~8a{-brGwK!N_5?A1D+7ifeMZ;qUR(hpX zu+z9_qPGTH>(JX+Sx_sSKR1>Ns1oV~DiL^oh7th6alcbW z8_P(s{t3*Wbwwq5dM?Xa;nK4_SU$}lt<_fw4+|Izk?ZT7j)-)%R$Nk3p`XpV7!a2v z=LKP<6P*cEPn9Ra@f<>zqELPp3jPFj;bxN+AHP2@k07c+0F^VLpFJJUtqY^lpE>U7 z^+ExiE`Tq`71PTHhQlX;eBGIqtlrB~?u=81TjeD)Kf>aztn0#<_(+W0WwV;z)8rrY zL)NV&dcimRTSYoQH6n7kUeEsntQIAgHT|$m&!bOdNCsoo1~2!x@x}ooR=um;9j^$b z{GT?J(!=Rk3>lW;Gt6iF`oF5~6@X_oS{`$43S4MzTox5W1bl|&SQ@#Gg*1AwXm2(q z_!9vT@$ytBphl^vQBdO(qDYQzRlZ1i<8^Nh8lS*KfZ)xJv2xJ?`r+y|cA&@Hw&4OL z#*06-$*V2M?X-yx(r(bPafx5|{m0|`4l$kO{&V4YUB}-p%@NN}g32VDsjiHPxl57= zNgEO>-%Zaf!>Uu&-vpY->+z4#n&fB(0d4iV-XjUr|(C8!1!$qy3 zj>>Jx_xn}(C6ZUc>z<)AJPk^6jk5#rH5aui%MTeN2?A zO1)>&<4^vxIEc@x5XU_FOPxOr!t|HJA%H30L^LZWq z=%WmY!-mjkTw2#!gSKtZIzgijTW^UmplLbc;zR(l8GC}gnuQu4&A*k)M4)j=pTbOG zg84iY2{3=VWEJV{FEWd>umWqrM}8jW;Wnak{3+XY+0k4KQKPCFLftAhl>^90DCmrb znA?0}2SJ$MFO=OYs;`5WX47PRdrs#+j#ODDf7Pz zKvM-&e2-msZ!ud-OLynUQ=Z^7WuXFC(i9((Qi;HubAtd0HS?oWh_kTq;L5AY?eTz< z-+Up^%RLvMlRuTdo-3Ys)(STZHClhw2$+NRc?E}MUhv`-Q{)HUBY%5`o&hJi6KBt`{iWcMZ6CjkHr%*N;g<{?nqTt2d}?G0e- z065&5T5GUv4SFB9U^jx$Vyk|vhKwU;rCnTKaBV`5W6=90oa>VSRBhx`_km@9-tFkM z5c_1{{?%|cXi}U1K7=2Z$n+<0C0=c5Zq>;`3q=GOt!HDx{|^3c`J_vW{e4s+VmPgO02@*LvN$GB4|^p{TPcFIfuacR)= z>OhQ8q9jkSh8+?6;*Z{sv5 zfW`_xhS4S~0<8f64MStw8g$+#A6gC;r)%^hRPd~y^k zct&@4g73ex2Ia>YI-LHUaxa5zD0Hp>3uS+9c^w61!0~G z|7c7Hh08zF1qcpXOCthj9mvsoo*6$KX$8-my1Rro_HsOA!M)w)6^Sp=g)uSfXyX}I zRC!+eY1ssjEZ%8lc-FFW$v+iLi{2}Ay6_oiocR?MjUz~xR*p8%Lri9D#i*j>jyoG?X4|2v zM4)G@c5tUZfh|?~qw~=BeH(it`nG|d;1mYZhyx;XY0~H zcc#qBh3TXIL@zNS>{K8O%zcd*uj_b-g3t_7J7q2zR@Kr<=;mx$aNkujb6J&^B&#uN z<)jiPv)c^uA5`Jv!{<#M`~2)u7sE1L5!Y5IN;8g+CpHH|p8)47Sgcx9_4>Z2#QUmH z?rk{hmzeGpqnID;H@bU@Y_#V}w5{QoAC>)JEMt=_7ap@5u&) zQ>r1-EQJSfv&(BB!Ws6OjQ3AurX09r0e8X3X8noQi35y_?;nMNITN_qE${d2k`^u# zRX|9x(QTv+q8|;PLD3f@g8Yf|9KSU9vap^NS|>tRxo6sdWK2L!vp#;MLQ;`Js5H+m z=gAabAWi~zrX&pUE8&-(2}*6W@N}3;h=P}E#|52ami=R6A{!An;U+3IH5V%tc)sF)(J^ae`lb|r zBdpRbMVgFRPoSpH`TL6I!cI^*eOcfZecwenU+;hN@XTd;$Z#rk6(Y4gd{iK;OqF4y z2D$Gvrwt%_syYV`o$BTlHxJT4mKzE@SY#gtbiS~z$rW(pXjol_kjuxb?WNJjqeNoEsBo<8h^M zT!cSa-Ol`V)_`vz{hn|A-{M6V?LA@GSJF3{`Rg(a4&w#4cn)2`aG~T*k(raxN!qHs znr~Z4Y48?lA@Jr8LY5KNBF%-L%Fq>lg?`WE*hySn=;Fg2p89hg;W6dShTz@Zz{>_h_BMpp0c4qih@3HDMhYTAr*UE3Mq)(R{*T=0y*mR( z+_azr_3_t_1CHUZWGvYm5wc>@`I0;m_pEbVR0hR8V?u#FO*vKg|Msweb8hKsfX?ci zr!Vz=Puaba>_q=xFw=g9c)7fhyg%sV?u56BKTC2Y1n=d#R=Cf6SXE`1`Y@#mn%_M| zKl|ceyVPU_FqLsns^}5G*3wrR?T@I)s{*-2mIxbRHqp?a=wcxZn z#E4iL6QZBoH6kJ;;aKkF%>EUAP`lev_B#2W>AdINwfy#HM#M@lS@w8EvQxW-pVA53 zD}I{8mF%sgmF0Q(Pox?)IYr*y0a&J?Pk%22`^5S8RVgMt!3iW?wFvyocgI+j=&kF* z#Mt5>Zb*Y^j{^CwYaBOFx7J{*Dh2=`0&)u#9ms?!z*w!|l?gZ;WZBIC5s=-nuyts? z53_}Gn?$ zf7t4)^3S30U2*n22R}v^=lZW0w7$kpz)+@BKDqqawWx;If4>f~9kn@<`OVLIYKdQT zsK`KHy`R)khck?=3k|7%Ap1jqx+0WzR`@-2Tg#wiE6VeBfA5gd;cW1EnjSSo*lktC zH_n@ory=o&`;>H{3XAObsH>}mKi3$qLuR+r^S>rxKX2Fn&EA(TNRHy%9${zI-1mRm z$uPP3o(xt|y0_r)_{8>WWpkFEA6QR;2_+wd(cvIY<#v zN^yO!WzhF(=%($XmxQVu0V|3R2$-mZidSRWwOw`xxU>oxa3La8Dy|5T@moix{ykhV zmGq~%Rql44U(2v>J3DFOeR|fy+FTb;a*6!%gb7cbGa1Upp~zOiXIX?o%#>Ebu=kf> zw$x$I1umcOx(HCI2rqw7=t zYEQ&%H`J*Iiv2_Hd!59gAdX*5Sp+bsASLn@eG0&0B2rxbsgLvv6}C8?xQ!!gO! zE9q+3*AazDnNMY~nE(oekeN`=t`gTg_fBh1%+)vSBB?Ch2V(KiA3}@s**xW6rkacb zv`N>4S)9p3y&v^w*Bvh0>X>ViLKr>LpM$2&?HlkeFLP%ip2ts4i!1q0t&xq(hc4&U zJ`1M_TrS*P^_}F|ItVAPa8v>v z?Q*&nwwX}Xde|KkwN?~4hSqMrrhnICtdX5x(}t#R)D zSg*|8bj#wy=osr^u9ZirujZPoz-J*CZof`!%dpa+AFh(MN#3mzwZyW=+aMwWhqDmR z-8-PekCI?re3@7mL}meN2$^h{TTU={GPI=r=ALo zkZ=cN==dGML`K=rh?Ir-isQxKDr|T8W^0ja+m8zHtY-eu8+ke5lH~sET{RlwqjxRX z?Wf%9WCjzR={ViMP$o9PjKN?kAgZk+6E!m;G`d@s#RPG(-)7nbW)vbE)bDx-C31uk z0II>7RsaNpYP;}`YV82X0f<9>t6Wsq!Gu;w0wR?0$OQEWO#DR{;kNq{n7FfdVP-e9 z@aOPtNZ6~C&vKMRBD0@^wKjFkapW;mBv(=gCdP882}J*QDCcQaM>w&n+b6AcWzKX( ziKd~)wWjVw;Gys~d_4E){@nN=*{Yxub{E1#R*WHHve;}DJ#}t* zm3-Zed6UUK6GdZQo;R4*6p^)GQZ>ALFyXn9`d@+x>fznj*hA;|nfa(M&iK4?EAc)i zo~M$THjQSm?P>T<&YuCl+Q8u0mduHqo%f+LvH#kg)Rs?pQDO1;*U@>6gp7P!eK(;* zI!jUnk~B<2CO;gS@Z2U~f``U~=-!7E0d~w8H&D>IuWy1X(slz9476XC4cVo4d6~(!B*H?$(37>16)ToPdcz_+1L!#=qnry6Qdym~aB&ScY*0 zQZ=z-;xxRZrm7SlyEfunG9CqhQz0!$Du@$9)KMt99@`56_(nW0jCtRwJfWWY9Cnuo zHET@scV=^AUMpww4#)cUdnRriJSzFkH5`jF^T?Fop)Z*%VR^K4GNH2{R`RSK)}x#4 zhvEAENaK_A16>1%FmE+Yq%fWWF%r(l@mzac0B>C4vJBT;9qP zjB=-?$o8d8e39ll)4GhncM!5M0_Xhsj}#sc~Mm zyXAHn+zU27%WtyTItuaqy8s9cZ~-EGx}=~%1r{|^a$)@MIM?`etg})VuKZ2et>g8w zaBWAna;;zxD%EhJ698v&B_$<7p>`2nr-=blyayCpWhjcmzCxP zLn2peNS{-;5E3$YblHy|3>|OgaLM-4@3Frqz42D*Zx{n<)=42nfCUiee(LkNp6EsH zc_ohBAY$Q1w?DsCHz8sahyg5D=U0XEg7!H*y|S*hdvG>qaX#i(&SWwN0^>lAym0Ij zp&k}s#z|vH7flAgagO|D{d?&$5RrX%&w*eEEG!gbN-q@b>0JCxHIihzNB_&qT{ETRvq=gb{sg41IO_~d9@>8>7}=07f@joDj)?p1lR>)ZqN^x zIod#ttukn!`sofo{t8l(QCaaz2 zU?Qv6hwijfUT~`?63}V5p@i&-dIL<5rZn!ic(Q=CVn{R9iP)8=_^6#O#^T9mKZd^2 zHKM?c$k5NJTewb8c9EeUtMk`vhBfFtxwVB)>5ONq9)#Km-pOiNM;vE;Qep zTkiJMCvHrKhxs`H7`L6wNnh^A(e0w|A~S=}}Bx(6ci6dz6d!QB?phAdJ6E2H-oX|q80q-$KxRdpd!lqGv%7PYx&|kdg_>7 zCWCQOzz4vB0Kbp#I~-v=wP_@a`(Im}&yL$#C7%D6g@b{uL5f+GRfKnN6zWEmGgZ#-luzRmA@ z);(FC*!lM2B-O*w^W37(k?3ng(pbi18H~#rQcetTy{Y9PiPs9I0yR6T3L@Cu1EIIq zxrs^tE4p#J6l`u#2LWyC&lQXVRr-X~XsxKntKC<}5L2s)y6>oa#a?%7(00siGjX!| zbT=4!^DP4w{!Du-fu922bLnL38C|+7(lNSB*jc`4+^6(j4cafdkrQViVnMRU9eEPh zqEhCb)KZlF+&H--bf0E&znv~aCL}G_I$hx}1&?=VNy49}z7WSEI}vXcyL_Un)Gr!i z(Tsga=JEZV6mcmWcM3bCI2LmF9r%H{r74D|be=eK()?UPv0g?z;pD$l!RI8GW%XvM zT_ik$iIK3Yt&}ZC@4cohf3V z>pa9+8gAkp$?_e`fr+zYp~PhZmCP-7YK?8_Yf>9S+$);+?C$N>t*U#CF{ zDP3x3Rccw#K(T7O_ZQ*AMfCW2NnQAU{!P#c3oK z#Yx_k86@Ai|8-n5Xe6W~N6gbv4;WFq&0{9|A!C#I3~1&~-1bTkD~Mo}(u989dQBjp zu+d6r*Gn`IK>$;Wi=mPoGvtjy)HY#MF+Cz?fDdp5j+f9I3pr8za)$?G>5XrzD!J>LfY_-rFhMhzSW#~5l-pZB z=_&ycSMD45l6P5BOSo}0W`saWn$=CV=g`F+q( z44pV*#2Fcsgdw4uSOG<>A-e}p9m|9)8=yU4G3rSfS&RoOOOrfE!Gw&Y!i}Z1dnQ;e zQ-M*X8VOMG2P?sjqHV-M_fLQs2LNyd)y~Gb$^~|{f@=Yl1LY_UM4+WtN&#kRru zg=d`CqeI!}~J zU*@0FGsMtAi4G|?sBB-9iB%FGN8sETRjN;j`sU4 zoCtuLqi(XkebnN2xqObeD%I&%&n{;+)8*DIB_B3p)LQi#JC)U3{E%4xqrqnk1>Dj| z2$+zuV4W(H--2)-GwRQ>p?N5UlAIRP5yxWUG|O@Mz;5J5yURAe6NrkNJDTYdn80## zw%$5S1QZZZ074OvLpaa?05h6dlYj}{bhP047`o@W7O(%5%Ny#`p`JIT7^xf;RQ~yD<@{AQeq7RM=YchS8faly?-!(sEu; zz1g|fr-WR&L72S|u_Q2szH=wbyFvx0Z~bzjQ{K!MKxB0NuBbK zvv{|{`a=qMIo)2kn}haNIv2?@aC#I@h%+QGj=@AYThcQ4uf&dYNI$NcRRq_9BbazN z9>4C+K}1H!8)Ennf3>$EgE&r5nfi54Pw5)@-;~#PZEzo`Jgt=zex~w&CoxNF1}yXV z_raZ{80O9!lxJpuOE&|Sxc_2NGv@C>ME=}qB$4?VpIZ*coASX}1j%_yD;Ge2r8|?Y z&fVo4;sJzv&gbd`OlVvawkh;44RcK;!B+Sa2|Isl@4L@XZ5KHdM5yqI!*Oiwu8Hjc*JD-108u;`#&hgdoZzl!VII;- z1>)1=92T^!1d@cLXA}1~aFwJUyFqJZ)5Aj-@q`nj8bM19 z(Gmn`y!NaXA*p!yR`uP8kc+5qx+V1w;@|Om5`PYpjkhLlXSFc$zwepje4M?bmM*#r zRG*Qb(R9XaGsrN8@_CVDFJ>~-SL*xTiTvcJKE69+(zKMkabVbqOLCGzyI-RHfeZAg zSKA9W!vNgrww)6P>&7u zINaS~9%%}j7V|1IITBcFCwzI?=wv?4WarHJVdj&~w@jW~XG#IW)%QEj-L$DK;FC_nCM1Ml z%O1a?!GSgKxqSHMj5tky!V6B_GzK&OEZ!ZYF^u_T==<&3@6SC$yngJEYxkQKyCmmp zg5)}PN*?c&ZKj4Y-;rUTxU>BYJ-JT9RohY0PnM=ln2T@W&UPv*F((wy|0Z(8%7vt} zK9JKezn$cHdOYd?u}_NH!~-{YFS=38;{rqs8Jp~pfWsy1NQcn(&+5K1h?C>k5X`KdpptT*oMD?qAQvTvZ$C@ksm+aJUJeV+x;;<-*A~s5dg(# z4)pe1n}LbQsQwq+Y6Wi*_-hzxihnP$OB1gto3FOd1zlgQhas`+b83Etb71034*n*0 zA)7>ZV}ALo+;YB27#-t&WnWgnY&0)Ar!2JEBM=cX%%5k%Tw{4%>$+_%|6k00^P+!8 z#>r@-70}H<#KNTnKVjaF5>Aq!DVfXM9e~i^`o{aTYo|46W;*53Io+)4_1JpAVw%^cTF6qP_2X$ zriNdV0#Jh-s6;4Ku$881*yPf>&6n4JeXFYqcQa$HIF19a*GulUXl3MDQTE+#yrxpx z<#lBPQISpHu0F0LlvLgyD)WIYqirI+d+G+A330=^fGf(RA|LHFM;`o75{j zEyV9HXKXbC5ntLL@eMru?mnC}yGdUA8bPZS)oZHW%kACxx9TiN9(Ow09XjqJlhwU9 zi^&9c1ot3z|ZF#rvko)&m(38;TP~$=SI%OK)BfnV3E>wItb zyrC^b1Rm0m(LsoEbw-g2*5KhcX4KLq$&~dRpB`V@j&)&u+#BPuaN>5NB8iJ>Q30q_ zx#f8P6;xp>B0|6G6Uav>UKny%DIL#mtP#6}28Xju+@t&6OCn zR&2)$W!szSQ`x}Vh5}&QWTFbIbFCprI$=Fo8Hk;qZ#1A5ql1SfgV#Q8!niX!w=q*iY1CJ$_HqmG0Y50vtnizQaD<(Y{OpAT!!wLu~zGxlj;5 z3q&I!dlFCp(@2nj2M;O=0i_AdDnPS$!lvWXz860dTO%PYm00O~lBT5P?vVs|M zov{%>RN97cErHXlxB?1*atDa<*fAe4Q@?3+01>fW7Q^Y0 zt;G}PR!I~_eF<&-p5F6Ji2Hi|$C6!?^IMzS^Opy8dqKnB z+9j6)^E%L@6t6;FEVWpONBu7x7Leq_=RIqc(-RQ!%*|BL;`z@xH!f_ojNI3&vEpa& z_-qD7OsC_7Js^BzUcOb2ChR_lGbQki^t|Ps(U66vp$=9lnw*b5K2*}2PN}3$o66c? zOVw6V001BWNklEcfHHoT3Mcey=(9%bm8Jtwa9kl2Xx+#LYj(nw*P4{F zK#l^Wm{6;`CEL)b?wdGp9578p-42xFh5h)zUTYBAYuQj(F1zz9HICso9O^2?4Qe~> z39-Xul^DbTXYR$r^Ay{S9P9G~;2D8*%5YA{!q?WM{wa?9!*_y-)cfz4YM;9I=pI+~ zzE<}4WB>X(j~ctLRI>I!oDYtkNEHlQ5@aCL19@VM>Cxv;I+;5f~ zo5n6KL;8nqZqsR=C+<-ztlvUEPbT*OdO(H0OsZQDJG`&rKXug`wp)_p+HOO+YrLuCMWx9U+gANolwq_7Pl)(AR?ehW~Px4K;bkJL9sBf{RX4r&cGz=gDGmr>iKJ@E;JGHM)#%z<@>(kqYk!ec+pcECpyPshR z!1gL|(Nfsj_?w<-G-go~?J>|qXUiJ0T z{`xw53L^A9=Vv*+QElHBHq!k;r_{y}tFULF;h*0NIs80#3lO27czT@P@-)8(Is@MT zB4T36d<__t%L#A|BGgZXM2eFCf{ZRi_Tmj=fzgB?QlVX$Ni=Jo>c^EK6eoGPH{Yiv zh`i#ja2@X61rt`y@}c`XSTYq;EM2Gr!6?{vNwk58QCrcUnPmY$W#DA5L|)GJeRo}E z`kehOlM;&OeAx)q%jC?=M?Q>EviGD8q1guHW{-L2BI~ql2#YA19%%;5qGhOUTQq|~ zMZ&m2>Tk*}XnRUD4Fc?biDvrLOp^4(rebOdHcbSWLA9b%0m@;5dnpCSCU;EK1C{GQ zGeQFpbeQ$Z^42VB8h4i$hoFfO<~Tso7O+Ilrq$?Dd(Rv3(xTnqIltqSs7Y1140rM& ziGIeAuX6hehY!@}LVM z7a{(1Z~JaH9qoPQ(n>r55f?ds)!pUwcX;*LkZgDM!5?L;%+waih1eGT_-_Q3>YG30)m+_P7Ae%pz6D?7E9ey)cS5HMWEna3=w=Cm zEkxR-zjFz3rva|I>L}!90rDiqap(u|0Dga|CSEJby*nCITcBaay}fFZuZQ{^D&zy^ zuVBIeL@Sj2wH)rrT9CLsHjH)~t%_2_YG*&V_P`b3q8FxBR2-+i=Z{!UeUq94brt+~0`_RNDzi!~j(WRoRqX(SQV#yLW~Bk5xqbp9b3U z*O3|YNkh>OLK*aCYu`b=DzOv*0w}hP!2%{Km-Z}q@YaEqYG?Z9bmb!j$9CY@UO4t0 z$8n$@hy7MLd5c{o_;m#%OZw^^8UBh{U3WSR4@%m>brzz3*!@5i1rgIp!N4LsH164_Y!XOnDi@0P_KgkV^jkH zT_6^)NA3y$(%9XfWiJiOiK%+c01CtQHIsmi@aKR9*0LPA##Nx=|Js!c1%>6>0WR$V z~%G`|Eh2o$VuNs8rO#^4tE@uWq%O<&+BEs@&A9e^MFluL_8$20SXjz`+%$ z2M(@y;lRc(ym-Tgt*!bWj9M9`7SKWcucG}zK!t6J?j2dt*;zkPh~qb2w>qdvM^*v2 z|5q!63Q+t_5FT`j{-=oHS>X+3YrmVKcSV(j8mQuK?!=YbehIiuP~5Z+^{A+F-^8|U zc$G~iS3!w_7Q=D1Cv~CU!%D}n!azgdGgcA(+&T!m0i(ZxBd{ksRh35UY85jI$irP_seOkhgKxtjr+EvqXJ(=gPR++#TLm+KX(%CDyBuXU%5=HKvXq&UelnC0P$O)YplWyiw z9Sv&tC@8uILMz>?m{`YR1uCJI(gb7`;B{bGKW<>6T~4>f35W=wcHC>N6-Vv+BPuGW zvY2&suvRO#Iy(-O*9$MXl#ZF(Wr6-uKLrz|VBGk8reRRVBK>*@J21Bs=W5Lo`HJ9n zz94gV%Kq2gcjv1%-?pan3!CkX#y<@rrhxQ~b$Uk2Z&}X%;&@!p=;fe0ML4IR)A%;E z7wvYZs^0+-a~{74MDz@9x|=om#r}6@N;H$p)0gb&Zq9f8&lbo%fXKl_OY^E-$vF`Liz2_jp-gOLI95ox_2jb&Pmc~g{N}N2zN;6L5(*STL%a%F#@cq2cchJz~ zV)G~e>|nKqC4`ewJCNugqFu{?c34tjpj0^(bZq~QD6DPug*}jPU_wCz2VWE_D7F1k zE!aPgm*ml)nSzH7C`1#%?H31tgWF$)fe0%+!&Q|0i4fdY+tGkTRUpy-UVH%cg{^Mj z3eZsvOq8P?ok|B#P*71&2q+@V+YQfJNvfF`Rw8WAMcX_e;bq0b4esbVg7s%FQx()F zgQ;sroWM;j-Hid>Vw%mat>QRp`y~>P#jO)CP-P=Y6`)a%isN;llmoBVXS)~>j6z$# z^;&?1J_lo8qYJW4@s}~F&Z@Bfq{;K=sQq=#D`^8}5H%Rjtjeix0 zNaFqS9{P^}6MQ=G$CS_8ctytyCeDE8S(Uv5CcX+HzQdh@h__tU?z1rV+_C%jI%Ee5 z`ImFQMXE{BQc!ax`QjQ(tbopHRGrO{chXv(RHj0<`##Cp>;hl7T;})k(u)3d>a(Q+ zC4MK(5`Y8^WYHqrn9@bhBo80rb4x5{Jy7_C!W&SjX*()|jsmK+frvxwu?|8ZMsXFd7o%}| zftvR8`xWFzWonLnM9qi#k)}z9XHBNU?wN3ZBu6!A8XnjL{9rUTZA1ej2aZGYX0QPO z?tUzLRGdb_E(K(u6h_(F{tE%84VALo(7hOjS`WI(+lGbqF z@RC(jLJ7@sgFX)9#g1p?JIgf#3I54N^wWHv-rT!rh#$!J_VZJs3jv$+AR#6t0R~}y z4!gQDgp%}PxkihOInQ5#%bvKhYUvmA@%$nLC6Qhc(S5@8=5OEZt zy=*O>EFd!xDh))twy_hJNWh5KGC0$wBA{XOrcI)SD3Co91|&qYz(CvkP}u$yNN|yY zzW~}`U_v)PlLPEpJ^HKrBMvidYJa6REkqG8LHtU91fd+x#HltQu@Q9Bxb2tFGT8nA z5v0@6;+Ep)%Ud*Pi%TvpyKnv?x^CjsQKHhpk}U(+^*abehnQ;hG&coarcn{PxN9V8 zkvk?_`lVECya%mE-#0Or4d|e1eAYh9?sw&u44gAh=k;h)?gMvsf$0~zUskriz%7C0 zU*v{Sj5CV=G>Fjee^s4c67=^_`&5X2C^lZ^P3g5j^kq^c4mDWmPYW z?A~(M(a)$jk9Ahp?7_s_WmthNyh0(AKu)_qIMur zh`^=v2nuwL) za0AT$c3K{}x1`7AvcgH&@9Chc=&8UmlJH&m8pvJ=oHx=~e9uXpePh^F0p}be&vrQo zLm&3x-gbB5cJEq+K$o_YM>e#hcmkFvQf+R;AC zmKdwlx`@Wo_#=9hw51Qxn6b5&lYJLs*+54q+x0#h0_WBj zBG3*L5%5bTK<`8_l0Ar!BVKD2(12uyhDN*yeu zJl4_YSBEArF)_vyj(yktIXQB2+W&r=#=>{yuei$z{BL)^pUS7z9%24p;KHmse**3Z zURSm7l@5AMMVAkLPn|yPWxoPws@So1v0YXmLf=i+I?XlD<;=}sKY8{z^Rlw|tjm58 zM8vp#PK|VV8N!>~1mHo`h1@VD_pz`ns<)6B=FKKECNaq`mJXl7LzD}q!s+XbEMi)L zw(B0=fy+JE8I4R7K6Y{42S`)(Y$J5=6`07z(|R-fJWk``&SCUrENmd!?^xB_Ai5?2 z6Nn%zYLd|p7#dIL8giS`pebN@-9JA+?bIMOVX9jb^m$`Ie)(Wv2WTUdolsr{+reNF z{+r-g!k!3LQ=Hd<<8|Qm`2xQfpknB-{HPPj{euJ-CrX1{*So7tTso}P|PCV*TKYB-9H1$ew+J-MTltD z+6B$N0=jVDSk+H@#xkt?5KLJT8sqo(fy63ew>cM2a(*rxbDwh!_;4)WN(^u5L;w+J zcke-1T@-GJJvfzdh7rG5T@0(`S(4V_7TGQOHHAD^Y0&g<7J`QN-gYtn&~6LbCv(oCC<bzR0K`1XKt#pydC1=j^|P5Qm7|JTl-ge%c**?|TZQbA5Fqga=paD$ zNVF51q#{MrQTM%RR<_!KM7tF(HtfK3#(fQQzv-jjv>du>VC}7&p$YBqR*lKf<5`>8 zQWwMtXqt*zu@wPD+h!(Amba=1)KrNyKL*#sI-_6(=tU$QNGNk_JMv8vqKMYA@CTY^YY`e)t^LMO zvkA^uEBJmI*9*No6qUkC+Dc9tC*jUZhH#X4KQ4Yw#g)u`rWt&EAIdLsSK7{2F z0C8!@${sKvfdily$+4-AQt=fK@wd2N1tNTuzEDhkWptItZ*{FlWGnXW zb9-E9BgO^8@!2Q!4sH6V0=>?;N{Ct!_-L#kf^@+yno6FI-}VDs57hl=GP0fmB?l&{#zD6l^uvuv z4ma9y90y*<(SXEpU^`w7NYq`nBy0vEN-fy`t3cxQia?^EX(Be!PRNza`)5V{*uXEA zlbZ;oR@6#hE^c#my!YVvJn;JO3;fBbN6VbJppYIabzq|dRe^-uVvR!q1b|ojJ@jy@ zqWdo-ugW-T#bz3b))GWrDA!KYk51(XJd`WY+_`)w_9jjWBx`?{J3=`h9Hi%7bJ^+gpB)}oHt$gQaay2%kOo62Z)F;-HjprPGd;_{310`2r;;Uqj(%bm?7lMd0Ic=f?>tbG|@ih?9a~{FOmn!~A;X|aA>x)_* z<5)KRpKelwUL6^LI0qGLTCU)Sf(Qc@G}EP&ce7<6T05YFIa$zSO(WFpIWWpfWBU@_ zF;UjqzM-mIzdIwxb1(;RpWMTr`Tb`Vkr6m1b*{JFM2a%N4kxX&bu{8bL^dFdfY)nx5* zG%Ka1nNUEnW2-w}$BvCR0TX&*-PSY`pPvU_uNRJbh!z6TtVw}H1?s+I|ER!=!%0dT zmtH}3=RqU3zM5In@!uEfXGJ+SR5`EqMXv@XXv0A}h}&Hg?czGJ3-H(h3Dsp(Dh43h zK97pMZXHNCz+jtGMz?%2`=CRkB9F9z01I zf~w(s^0Bf9gzurn0n+=qxcX5lG$ z&ZM%j&d<^s7Xa3@WhtlW4q##yr7lzGc`b@Y_!`(36kGs&g5(U%4Nm8>LKyN z8$yr!Vy3aq-}CzAm`@A20+*bGJ)!T^lAT&sV!-0Uq=JSjlls-)C$}0>3*T%FP?$1E8UB0=0EJ; z`&jKjL!x>SZ9*4Gz?J*P>21_LOxg&$J3>kuG!qQ~z!v%CUN^g{p@MgAa`Ij+M@Sr0 zNkj895OFjm!siS1RZYe&$A;r*`ymd|M!b#>Yyu`W)ktt@pn^B-|NVU7_4$d<&juuT zLnFw51iE=s1^9!3PX@ivOq6QDR%L&Mb+{&!@-b*6K3}N+ttfJ|>q`MdIdD+Liw+P9 zY6VIK=tWKQ@q+tRAVD~&U{}CWH*Cj-x;Y>bz(jv8r2!D#@JuSyQ)jB}Pc{`3h0f|b zhdna@w0#m5*J}tWHw}g5<$hhKRiT~^Jqx&%?{ysD|gh7&NtFu<$iCQ zpNZ-BLac;=EZ#8wZs&VVCkx(Gp3tG!YF{^h@hD0S{)<=cFm zW88PvN9@0OHCzeu=PQb9FmX;#9{;{XepVLp0f-#G07fIm6-!u1KF2c;Sl zIfp+34gw;o_scXBtOD}jAM)eyY~Kc;5d6^rjmD1v!=>%ZVn1x@bkLzPoF`7hVxn>7 z?(?JwAVxUR8Z&Am>`Tx_%s_$*w}oo%vSld*+DWcw&_N@4ie*ccEe)^FPaK~I>SslL zG0JOeGPP(W`rnSNw(A-;Zns}IAhCBK@!$V`HjRW33b{W5wV@Pj+)R!B3*ZwdFTy4& zkgA<5AlQa_yhfrCd!Qa0N@cvthEiTQ%8sKPc$EW$qg_T<*)$RQr|)``_Calj`Mzza z$A+yOI7B1iwG#SF0wT6;!zLZ%sI{G*#1&22Z%!BOZNszOTQT%4W_L-p4pV9>N$RKm z7BEPGi10TR`cc@uR}=Ot5vm}JR;LX(k#=xVQ89o+F6}$ybSAHz069%XEp`)kE2w9# zee&Ru+i2i0glH|NuRw&YqGSTpiJ)@>M4WtG5P1^(JKUQX=6N=2f|r;6eW$xGpZ;O@ zYd}O_ddRBbOpw0<5m_2{=y^iJ?5=XU?$-A^eyY?WpxbeDdcUKaoq>qOFCp|X z!n+Bzw_giA?D7YD5Yx0ZTq`;!Qs^Vdmf%ht4z)21l7ans=H^rdjZw-Z zq>O%ypD^4AY}U?YHPA2>V3EL$Fi+fX0u!esd>5El)y+QwM0_`>nmbos4ZL{H(^%*A zgr2i_ZlWB%CnGU+G(FsL>&~+V6Z6YG7-ZW@jmXya!XNA_$Le=!bb54dd(z3X!aQ|X z7hZi2W1-~>0=UYv{RmkBR`^O|+_MQ84*9Oc4#aS&G7rs;S+*gLGK*uo( zUbOxev@YJeVC;m?spyXSsQMoR1{dncuhP4fe|@hkr~1f#O#M}1oJ||xgmQNDhxTw4 zFueCPvUno9xbHn`>o0B>i7WsB-rU;0s-{O#6uEj2ZRGmGw}XjM7vVvJ)Q8(Iq2KM) zCcQAaa671{RMTLXNs}%bi+mNWJ)()9YA>3+$pF=6xg!hCg=O)XsI00Ct-UP9IvL0;G-WQmCln4+ceDw%nl0&gGfww=s>fTYCwWy z?}Y-1ai2s-U#${0GgoS+OC3CH?RVR-ZyUC~mBk$CiBok#+B|e<-w3VqkedJpmd|}U zX6bAVn0PP&fD2Ij$j~%OX@h~dNPHdGoj(6e%yQH%X<%?YaKOjwQ!GixsR|<8U{Il* z7;*wt+mjN;@6g2a#OCVFCLtG6j-6FT5md`p63mTpYb!rt>E~YDU*f()uJ}s6)EVBj z3BsFs{6idv&hZYmbd{Pu-%BO>-|3)N>7UUMrt#DC#vwC(oF7m9)_Fz0(Y!JwC_L7L z!(~1`?LmOUAy!)0J!=?SJRC}q)~#i=XgBux_h%ELeZn-R zd=E^7x*J#jH9rFrqos+;NE&AZ5^#0p%Mt#;^kmhX#0^@67+#Ogo!Ib#iFMgV1RTv{ zJPvH2Fn`RyXO11g4nDZA+(C`}+Fc`H+icx|1ohLJ2&hyi5YbAjV4{_tL0V}JY`8td zrM5$Xs>sqDp9|!-G%ZJg>^o+{{`vXBaWsvDH*I2eJHkaPfhs`avtWPiT_eH1BS~wS zHiFy@dFVjm)h^OF=m3=$AeW_8X1gtK)JWik_Q&X23DP|f?U|fLV%s+C`;L9v+i6p# zDuGpIkxSvC+O7|#%w;PuGca|d$b|bUotZ=n0LP2t>QAuE-4H-d<=7poY7}(UzqU*9 zNXk@>!`i=(5(nzPhOM0%x+%rlabdrmVy*bUjeCPUL zNyiHx-L%B>@fH7n(&-1`?!}pb& zR{R}pCd6yLDtCZ`3=(OKX$HO%%Ddo4gXV{)XP)xN*B!#@K({E7`e~91DcbCqb*O{s zW%YUeVQ^i;!2aF+f-q<#BtZoqrGW_r5NbJ83m~@~7-+BqdmNzXQriF`N(T{@+C|Up zqU6%$W4XoJYa|Lae-ePPzh3=9x^^dnA{_@Ll=uqlqK&A>tL=f%)qH4&cfujVOq=u= z*J>tCjDso&hk%IBhOU@Fa`mj()4ju)V;bDS+q_j0HQ8560Hm> z?0QjI1^v$cG*}#99S4SuLd-y|ZL_lnHoC&#R~kxR@u_0oH0?!U;6OC1VCHr%aEpmU z;A-10(Lh!`wzj`w-)z7VA}jz}CuKpiaV1EI4vd4`;6V2atKnLwv3}FD?P4nP1asj6 zA9*tW{|dL3@qUjpp6J`+|FCnKiFH%tU*afmec3w-KS_FD?GSTXmlNU`euuWia8~C2n7C1P=r28MKVBn! zalA=S8OFAb>uzGM97M;!Fz8)+qrzv%d{Gkj{j}OUkm&Kbe<8<{JlJq1PI|E%i8cZS zX3|vkzA_R~T0sJI{A$_AYQX>pn#|llga8vWYw`f1*tH8yGeLHGs+cytaL7?mRWGq9 zwF3!xuT+5@cztfzUmK3s(F9Quzyrq@jYLBR5N$-$M6^?w&^Aruz|n4P14AsJxVEdh zD;baoAmV@=a|KsX)PIR=Kg7Om0uZ`_Q%`8J<6&!U$JY*EBC1#r;sbrat6DtONN69E zG{bMLQ<`lM6cPGG_?Ixv+H6=AaGIcoPdcNk?!r1dhE@>fv2ED2?JD;bIibbI6iHjU zNo5@8*+2UAjC+(>U7*jobL=$O`NjVmBYRKHpvBB&t%oi>llT?S6 zc5|Z!oHy&n`E&iPT6_;EbWftC&2zpTcyRybg>Lx1;p?~in;2;_6=pEv>tE|LBEiXJ zENXOS8m)1RO>}+{=ov&gM+N)q^>QaK$#vUx02J~EW*nb8j#s-vyPe9!B8+Mskqt5gZ3Ntg>jow&w~tI> zj}J!S+B6dWR_hT^aR2l5)Sk(-5y!UKfV9eUr#F?dVcQf$%$kD+0(^JSPN}V=1FEg% z1M`J-7RJ(U7w$nd5>@Qd(Cyj$oe*mL)-(})({x6$>#L! zg}Ut>2+GM-YC70Us>K|26*Ci=hmW5==I3TkMZ>q1TZt1FV8ROve}mxsOTfgU{5(AW ziy0ocD-fY!=v-KhAs6{PZJ0d$_;NNGKbz{WsmsgoBV2(MB z0*g;$5Mn|ac}*?rFMJqzYZhq5i}O7E{5IadpvSA~ywGEe!fwxQrj7=Z+{9xfM?euj z&4PTNyS;Ef&XvRbF7szM-Kj~Knx;MF<>zBdF9MP-@V5H(ziN%(SLIXFp`q@(RwJOn zRG?MyEXH&1gB(7|^ixBA1wd%qc8b?wS1&##eWmrctW#|r@cc;LD=UYSooLR; zgN%IRwP+%!wr~n0ROls1SDtOJg#G99B9WJ)c~hZc`!J}=RS9}?wVE;&r-k6QH$p+i z{`!2$t1szYzytvlEiDZjwFlZEZ12jp1xBWMwT;ykQ~{uY!sF03;?@Z^(bOETW|~%a z)GA;?7!;Rrl98!#+~?rS?75ETRvCc6FxFicKX=(=X_>F1g>gUL;QFiFNhVe$Pg(DY zyOUHB##YJx&w-4gz}j~+T+jl{VNd&=lTL*>g*m4Us5$N1ZZUy}mq#LXi*d6bj3Vk; zt=&oTQefsq7_H_3JUs&w>0?W05N>0-e(Vh3V&Z}AJ&H~}jNQGlsED&VT-X07<;=Wz z2_lj_M-$>M(9Tqb)#|AYY1vY?xWs+7u%;dUA`sBO0WA1=eFO$IGZU`qa{wMmnn?2* z(t}&bauyU;w?mBwO~%|YJ0zI^-Tau21&UxIYMKzhN*d>ho06FiPMCOw%Zu$Dp<71{ zM9}s0=b;>FxfWh)#|gpuWd$UBUL%lkVcZ=O9!w~RP)!1;n>3NFK=bCmP+2ah0E2M|aEO4SQj_41S36p?9<`gs=!s2C z{TFf!tZF6n7+ATNf?w^UT*e1N8`#vgp#w(;69H5>)20quoD|QnBWamAoZfWE=I~&~ zG%|sX0z$vhrf`Rs-gFH3%j}o|R4~hha3;jJ?|LbX_KSA=cC}+|nHgM)0~DK(+wR_| zZvR2M_^;i|Q4iS%BfsMxGs}G%tdLg5pkpxlO@3`ka6bYudausF1an|ouP%iAF3cNn$oxhSQAfWVNL&IIA68ps)bfaw?0bq2KhA~Gv}}?{TO8N4 zL0WP7T8x1n?>{|1SamWjN7gM9FB>t`3J@0ltgpGWE&SryOV&Q?FVDUAxQh>OV^|58 z#=HWDCMz}*bCE}>nH+)igr+9^tDMH<)6+|qd)m3gs_of1oRQ`LMmK$GS_(ZawQD?D z%)Ji|8N`Z)bYR1EL=}YnssLPEWoNQN;D!C@*O`T)4P}bNrGbb_=zA^Nq^lQhOzr5= zs8o8Zh<>|s`Ukl8j^cn}z=#GynRRD|ktvcV!ZGJC_9PBhQBzUd08?FWR%dT#>e(NC@KyKRBy%`Nmv>Oczl?GV04W+bO!M*uc>%S#*Of7R~Gj1X} zoBJ)|IKk1xEJL|s)ujnPT~)sd{&g6`LmrFz`36Vhcvw>Z>uC5c_r2|MRu4}EP+kPM zre@tQ3H}Je=dLd}gojy9o3fp~hRExnZ@F=3kAm?`YeLVmf3Lz^(0{vd<2cR)`!QqX zhkY@oXBmYaTOpO-I9F(XkphEIZ3Rx|P6YAX30?9dGB zHc<(e<3Gmd`>z8SCbR>Szz$A9M-S`wJoxzTghtIn_j`K5C05fk2ljgEv6{$ICcpt# zZ@wNgnPZ+0P0S8dROk3lj+{!L5a^K|D_ejI*?m`g_pw_jA~CUQMRD@nI8QI_u4PecFkr zhN_*d6&Ew8LEz8ZYE94jUiHPH}b)OiLvYCok_omAWX#} zsti0h5TU4?<~&Sx@ceNE6TZ?3Xg6E;Z{)&u-*!12Kn5Nd)BptQz7aS^)Y_)qGeO~0 zCr_8|r_hV)nBCfwXenN=7l`_;+1tLg)2_D7Kn1X&0N~9rJ69v)`RkDo`5A+dejLF> z`?vxN-T!ULE0SYmdH`Dt^!A`Z*0cNh)cVJB3X?U6(T>VntYQQxnh-`CB)w z=<|;GtH6Glovz+14{acVz&7>TdZzFM|2qm(LB}$6^+6c4*AYmJb6ZCDz@n1*)YHZ) zP9Rc})npAejW7 z40M&jtxv08XQ%qAa zfe6PbyRF~=BF46WmUpOh4dsQZSk?$~yAjIK;|9QVh`i?1kG4XkDyp*ngeZ)ICcRPQbz zWbSu}(P{yu-xy6ZxBT+s)*SpWn`j9?;g z+C=!#qffhFtbjs_K~5NULUUh{N1w+Hh-lhQ$gpbRxr0< zb$PjkRk-)4K^v1^6PCcC`DYQ`rpJ+oE(U7~GJMdK!DO9r@on;rbF1$+S^ZjMN}k6I zh*MI6MxruMx?FCjJ0*0h^xCE@iKp-{?Eo@I;EC1RMk=a>fej>4tWSM*!-^ddS5 zJgsI}JoLdb{rPykrfi^A67V3l^R+-Olz^y2+6~XFOuCh%3C2z}=LVzNb_M$`VcyM@ z$D211RK3`3zDAjs;~%WhR_?%GbwC<(rI;2pp4h_;VG77_MUnKhzDT}P>3a>7aWx>( z_Fr%ZS5 zvyrU;LIF+l%Y}gvOw21AlzhvXLku0=7$YXNPH&V@*6j8yjc;(56VNZt|E^1Bl{3=Q zcH!06G2T^~$DEx2v5e0yfO4Oc{?csVDUmpj{HOq>t|ex|bA^G7Yiv za?KTC?J@`?%T-X{v1H88q|D|{J%R@jn9PB~+@t0sPAl%I?v!|X&_Mz8kHZblD|`LM z%4J@6bFi-Fds81jw|N1>&;Juk9GLVe%S@Y?$D*2FPpbo=g1*{=f< zAzjE+hc>zS3`-=r(9~$dArG3BAXCGpD}}ttF{bzaleqxF9tx(?!5V3&-U6$ zIz!wrxGrU!6*gn+O0O}Pq8bHFJfiPM+qtES+)X!-hCD zlc-vYY?$x2bGHrU)U*;-F+U0b+*@!kUR!gz?bA9+xqUn=`wXQ;5 z*6E|luR^WBgZU(Vn>lABcPw|#f^^|={E*Iko+2Rh#edz>1x|mj&eC=n7in!YetJ^Z&vU+x5?f*c1>BRXAMIzZ z?*%a79>d}XYdu~~+#J&HAVQx)KY=^vLK~H5A z4s`bZ7C7F@ROito5(5WQ=5cDh(ny3dbq zzQ?^Q3!Xq-#yJHOgTLtr6x>UGtO6%HO@xidE9Wy|%cX^EC0 zgHbI+W$3{|Iw;zLGxs#Kw$xi!>2(}>BE6q*Kmk~d8&>L|p#p`Q$xmStX1D3_xv*88 z4hO5eRs7ff>OOxlOKTGTOnw(bF~=IT-?=nZQ#lG0YX zCZ+vw0|AxoUWi%>jBLei1J&Jl4Z`v9VUvlPPL*xL#=C1czhcq*M(ZHT z0V0?HFkM?kt6Gi6&TTlEixU1rCcT@G;ud}pWPNn75#bH_E zs}OvW1zY!z$GOtLbl3DvA+Bd^7xyCG+ItR{w9DCR?zxz-&)kFYosG)1=&cW4E8&Hx z)!g3AKmnLNvd#i`da3~k!gO3}NQm;@a58e_mFF+x!fq0k zy@$zu>wax>!U<)$Q@KzDei?_56IH`;!aaQNO)O8{vZj|HFPi}iFRc6UZurc-LY~=g zwq^_4K0`h64c)T3>pZz zTtfi`y2ZZ-5!(8unLr;L9!!LdUs?x~O3*n)r(oM$?pJtZE&ve0gI86PU07G30K$&r zB0?=PG1Q7$H`IFIINEWss#T~~*VWQyX*Xt=CIf(-2vv{WZs2b9!8R#2bQ}Q$x#tl~ zzy+NI0(-qJ_6^~qAQb1~InA?St!=stbIB9hFuS7}`PZqtuCvxh7VScs$~hRgL&d7^ ztuIVcPAg?NNn?z+4Et{1Nhj-jWna2GMOm!U-5tkaF1hKlNv-uEcF#S;{4Aly%8`E7 z_*E0gm3L)*V2rNwMsZ-G|E<78pQA<~q5a^t^t!_OZ-@I(JTKJeqm59}Ww*!R8t$w@_9DS^4qm5-Up$h*IsZUhmbu{}o|(+R6R zRaTl@@X}xgk#2(4i$w?p?IfoL90;{+*f*UZy6U=362N#7Ppyoj9N3Nn$Lob-+i<*I zcx|7pZaz1={kq+NIEp~RW~lWR8$@mP?G-SLv6&A(WE8jEec>jWVZG=6#SqWkRh_M; zu{&YzwdHvp*J&)vkjx{$qmSIFvoGf%Ld&o;@E`@geF|kFEQN~lyOp>$e&QT`o-eh(1lzeAr7HE|l^ zdLZF66b2yDXQ`!Ofp2_%3?m4(qTXb(1iop*v3s`Gl1YZBr{hR7K*_FS+$8c2k2+fo zNhE~xkfGDwh-U6eaMkn^&5chYJa8lyQkO~R<)!5qoG2Xfy*0|J|^rtk9i@$rF={R1B#J3a(JG`|KUK1MJxshBzZwC4=cV(uid zZQVlzV7)GV`YPmC=pnCKPvFvQVoOA)h14XeV5=KG+_yHNknN*5ni>eTDkxDkce|kO z_4#QhLjl0H?Pl)OHwnsjDh@P}b>P5@2pw4PTwTF%zypw2dnc~9$rSwokbuDGG1y%; z)+Z|9Uq}&MCb)HXR%gQ`wu*|?>iZpW+T}sB|9QNaYf8fuYzECwddp>b_@d6f$*t@C z-iYaw;nif{Tvi@(JO^+`+ zKY34m#LG2070HEZx=3Wt^4m?As_}dCQ>{Xci%ijEiER#QZQB`YVStJ3B)%|YIeEU| zqw{#vwxsp<5VVKaxfJqCQy3T3Co`HgKI(s?Pp^cDY!fsSH&!G$%|cR-XU+#-YTQ6j ztAZ{Vr$otQu684bhnE(JF07*naRGvAMkDXr- z-pAZ2#E_pZKTb#C8_7KUp|8XCPHcZFkDIupX^_*%4i%7hq25o6j%i6h{9*nrs#OJn zxM1J6T~6+)U{o*_R3o;w4qcki*lx`$^4xRsgSeXpkpmIqAKAtLViJ%7xuK6hC@8d{ z(1yM2_$WI*$`5>$4}8!^0|`X{#kMyPux;4o25WoY8c5jp4g220+3&Vv-!}(3_I@Fo zGNGWhH7?$Nohgs+Ke3s7yOE`(r#&#-1Sje0grsI&waO)R5`iijz>~}RtdCLGOz>6! zvm?w80j`XF-{qc(y=f-o;<~bJW-_J?PLN4f z%WLNz&zrH^qfOWFk7uhpSFWYK0uY?|ErOnV21mv`?#KDxb~HcDa`)gK)|um*XWEGK zxi}FdPWDXn9OrMRisiKIqriW!&#%ji-`efgCSTp1g`h0NNn@Q&;C{{>e}f&keRGRn zj@PjAD$kjW?F;W7z(g~L5W|E)2nh)!`E@Wei(t`etmhd|>6`a2^g}mPyWmZghVTH) zKr_EC&7L9K+%nd+!V7>+J3Rph!lJ(~Mv$wIetK2@J$m=B6Npe5BuRp%2gHxbVqreE zvqCO5@~`?e`vvJXzcT@&Pd@&V~hp61?ro$gGWgbYDlpG>MDj2kDi zdF|pgJ!>A+bX_8-4|!PdsS7BrgA6pJ9m_U@2`jKHzMBZ??t4rBQV<~{mt0U?*iZqI zRCZUHUU_C;U@z1xe{BD8A?zRfhFUAO?Lg%Ml-kgVY9(aFnM(x?eiK5_GC25RpHvGm zXd}WiTDom7KtU-xwr$5=KJc-9;K%j@KeiwE*mmsOhy3o&Ov#%o?On^THI2nqw&Z!k zww3nhLB!Mmh#+F@GlSl0?(fnG6NV6&VNbQ49W0=WYZp1Va9c&-+Q5WXtu*Xb2-r4D z&o-7HhZFb@nJa|Znu`2DJqix`l(LBi<2YKK?(Mg18@64w6J2xBtAP4o(xYKLn2@k` zqSQm-CtYb722lTy{bpgk*DkfL@dU_C75`SymRxh2r*FJhAUw_ zo3zHhqhs$ufs&wf6=31g@_q?KT=(!f_;rToR=X#NA^9|=M7{oX44R#=O-o)20GLKX zCrP+(tio|KZfZqr{7XT?xG%sC&v3$c7tS5X7|ejuk|%SEhVJG>==q_iyWSWbfr7mc zX)+?cgkDyP|EzIB5Pq`)DhSEqx}HLqL#5+}G%BJtO^zV&%-8B zS7`<5+yy)X6)xOz&PqP4P9ySuL2w>Iny@{5pHh6F{Ye8&^Rphao8^3_iS}t;^Po^= zBHJj4iXeE*#`PtN9m@7%*mIwA+)#rK1|n|ShXN-*I|4`YgFrd7Z_qvrIt!mgdC#4s8$Nw=-DvMgv*+HoW}zaVH2qJ`jE7`G z+>4%aM?hY9^6+$nw407E(wHhErD}FdapoeQMONlLikUNj&~IU#YSc`SGkpT`BfA|P zRrjtjqh0W-8zXBM?yEN!ikblf6i{Ivo!{#}D%`v3@ZWjyizz(?2L0L3EmJz730UN5 zFG*3D+*D)TzYmR+HTzNs?rmp3Cj#>*I9eMH+MP)t^H1a88Ric)Me(s_4V-88lN34S zn|_{1;FzpsC7xm4%-mQzKAR{RhfT)5!zIMBl5oN*mQ$aRzKH4Ue)3w(`E;y(-|42E z1!??|?&+)hKt76A#1tUOOM=;=srhw202<0E9kl((9<8wW&Q88|ar|Feb~f_edViPE zNl%)K-_yTB?V5%nK;rd!VJihkQL`rQdnClX2~-*YC~mJqggkIYPVOlwpfGSYDzzXI zSB`Eix@r3313v^n{QUTdpZibz`1paJA3yN%(Kk{5_-LD|)m*6*J>@92bIYzzC`~=% zo}=`SC9dV(Y1_ZCV}+V=EAl2}kL|5#Qcs&1O(Vf*N92OQRL!i(n2OYCLx^qDUL``Q zgsQe$?9blw%tZpf0q&-ImB@3*A!bTYZ&EZsPz{Oan+<(Aln za~O8?o=-Hn>(f`P&}a2GbBuNTWjVjKK9i$ zvN?!KPsPi{fMf3iWn3GG2nRD5h|s+W`CbKYRs^R}@S20rZ$lpOInp)qD|X)Gyu7&5 zrNXlwWFnIaH?lt>e1rw)d99i~@CWBLfP(X|t7M(ru?p|2BXy2vQSS%2=5ZYNZ*aO5 z>zT4rLS~M0*NvJ3&CL3`ExHVhGbh0Us8(R5ZQ@>uW7flizjk;fd--0kZRIWiv@mBp z>rI|Xu0#0FpEQJDU*bW?6+f*c^$!+NJC75m?a79)0}-CBTT*`22#ivtj<}un(M|-B zXJ)JWA`QR=Xr^HRb36LgIumpAtL=m*wN%sdikVv(YN?{dXzhF)yV>0~)Y>++^VU}4 zLfyGCw>))(#J)TUbz{77bY5~zKf87dX9|O8^}C|wP4^8+e2;VWXg}hY()hlZYRzL~ zi-r%s*3Ec;rzc9jHBwLdL5Mu3G{5C8%OMIp=b}NH^AdzVpl5yv?w;6^eLtJXpSe8c zmZ!}-^47Ht{hi!AfpVHeJ8mZoxK z;W6|~9p6^%PChsV3qfKWC&4k7`;JHYdLDtAWN~e^-sUZB>|d2RoaWY>*<2$Qf5KT( zuj=Um%bY|EI;61z6nz;-X&AwT%i!TWv<#lfI4kGpmJv7zO+i!9n3x-X4Y;$)%x2ca z!>`l*8yBO)i5kb2NBvSI-<;(o&9QGbK%TOo7E-` zuWFVFrofI9?7)bOZm*Rn3Nu~0)dXo#yVr`t?$%HNMvsLB06l)zS`yoF*vc6dLMd(I zdb?+$=Wk5c29G|I(V5LHGpHE2*d-I-<#V^8JOdOn75_V~x5Zkab1tM@)y%~_^O%Xh zd4Sx2`ha<@Rr93$Do~h35l)>iFHegl&IF;W$CFeX5wY#jP(>6W|-STUAal{yeH)4c;cRpCjdFm z5aBM4w`5M55)!`@Ogwkf$mD?<$wLa7; z2Q37ef7qG<*>H^}NA9{&`QzgQ3`V8e{z?T?MJ?Q(O9eKxy$B!u$kbAFUqP=@rA|Qu z6@WHse|tfx|DU~g>9uWH(u2OpG3H$RJZ|~oTduOXvZ<2G4{V@RHsC^TAc1+b=^`FI zIv^yw#eaZb0UhWd(E)@JLUgcr2!jz45>{cW%A)Grdmj6ov-e(ejtm-^5%EQ4j=9#k zb;_<1jJ@X?uN;|?k&zMcuwH1U#cgeD+b;#x}nRzLak?oKqYpSx$bQKaoi^X8x=jBjU+}lJh+0hcaESVp`!H;?qMwhjLSfx7VTi70SVpECpgpUNQHVQSVlUyKRXCO(6X(z2L#)ryhlYp z(X-qFEyKCz$Df5wFn!E?aK~$iC-owTeY960Xn-Zqp)-#)m-%5oy$1x+BsYDQDpHAKRn z0Ol50KGyn=<4J(@ArEHFH*-@S7uKYI$9PsWq>}kvs-{;039>_}2Z8_u4`2_UdHvI( zP*Gn!we~&UYUz_2eArXOwB87I0DC5= zm%&%YI4Tr^+NGt|+Mbcp*90Vt#atnIXw&TU+lA=djV2Vw`7uf|8whG#uyn)}hIG(W zo6uBk<8@0{2+4TH%1!pJNWoSV+QCG`FDNvo_o%fkPXa&>Lr@x%2)##Q^Zg`Lwa>NL zAhI<8X-oOqH4?V+d#`7t$dc2$s`&o#%)e3u+rHtlZ@64G2c#DRrCXDy-!DMo_Y#OK zB(vSUQklNC)q0i8I?m20$k82pB*NKQfeClA%=n(lkJ6;+VG_0Sz1bQ~0Kztds{|VIkAVc|w_UIt zXCRQTM~8m`5j_ISI*4D!qcP5uCNVy7>IFctDzgV6g0@w(-{sJW(sdwYU2*z_zgQco z<27@vgEwmhYScFYR>%NUz6lPQFiNf96X(c%6@zZHIE@?PV3c5Y4&sVeE`_ zPk)Lk+Q9^%1wikSfJoo_t@f~zzoj(Y@3Mw}$v+7ClmpPS025573@qKZtvOn%in6t3 zIUPh$Z$uS^Zi?&m+IEP(G)KSf$sjQSV?b99A~r$U+YeeGs*tilYMba?jt#PH4M@l( zfr;pm5RcmD4_McqbsyK-3kqFn=N2U1-IM1zWC0qQ>NNH}NJ>N&Cy+H~#%k#d&R;enb^d*1~$Wejg=*d;5#f_b} zwjH?NZ*4MuM?bYzY_+!4ptcRAG%#7TAa_?;eg#6$6-X-`7#{})4@}GVwsO_B6Ucu=o1yP(6!ks?lEI~kb4{ER$Lx#lz1)KZF3S&h4q0n z$jNgG@Y)8C(<7OO7iyHw+4yc?VtBn0&_%>1U$@&G&(F_ze!k)T`w!UO7nJvHUgU8c zs9I4}haHk%YOstZyUDK*0Jil037zwd1q$i)iOV?4)%u$`tqF{bGM<9V6xR|=&^M2Y z;$hfV9RVCBpU-_Z1@}nU-vAlFI1eI*Dk(&4bWriVB(#qrueSG_Xy3YFj%&>N+#}KT zX1^YLD)N2g&GNAC`vw!Tt!|B29^TZuQ);OlNVFb_-FqbR90{gaY`NGDB4ihoi$GLR zRUJT-+BT3Yb;G6`F0y0C-ho8SkBBj!M!&{TB?A-3(G-R%R7(tP;tAJU9Y~lAO#bVM zur$8f&ZeeF7nS*}DVMzjS-(0ztkp!@I7V0a+Q3=qTS(Lry%arW0}Z-u*kQsVecr@| z`~B$4?%qAMHoPg)wuywtQ6S~sdWdelOjJ?!y>D))P2p`DHuMSgy_+Fg{d#_>1qIqF z&ubkKL)y&HChRRw`(?+|(*r{Lak;c1bK6$_fw;K;K#reTL9UONOxGWr z<8`ij_zV&Lv5fxy=R)>Fz9Wd>kc+^hqxroYuPCaqbw0pEJR6E+?FKhOXYA zl|X_IS<*CQDQ{c{AM?)7mfkF)6`Ckt_6#laMt{@Y^q!b_qKEmLnZDI=UQ=EI39q#S zuRDUTXEDCq)_nHxWias?zyJC98SmeJz=!uAuy3WU!q`E?{eHtyrSZ7}kLO=%I_J%D zL4Lt-J>{c)cQVlH1t7r{>I@J*?opd48t9&>9^yO8)*Qu2fY(1x!<48V2aHhUI|CLy ztX z_kG(S=nka;2^-p!dL$Z`L!>W#%GL( z$1R1|oQ^piRzxIx+I33m%4|b>93&a9MH7a+(KFBWafDBkjUH*q4dleL{~sU zU4~i%KYY@)jXbGh8v`4d=o=oJJXp^J$gl0JOT7%XGqFAEtE$dD7Zed4yKUUI)vZme z#69=!+JUNh>8fHjsK<3Yp^xUeeV#oR=4A*eYfvMXIm+^ z%_%wR0o;2v=W^I9Dpe4hml0iH0|S+wh&aYN!B=NRk?vdG1l!(##MAYHk3MQZ;?s{m z!qd|gPj9ZcIFNYxc*&G~AI|3Y>7+l3>-#m!zqe`p|Htpm@qLutP@8||c)siL7)*4% zIXck(Y;bJT?TX@s`$WS_HCjA6prCKaP6g39e9F%&P}13C>(w#8odLkY%})nWgk@u4hVe;2*}?%jJ_uhz(=sJ$nm^;8t!1WbmQ zmH)T_wfwsK*nP9^dkmu$V52>fdDadl(C;Mhik%#&5Ajo=e4Q>9;m09(@h;V2{$_Z0 z-Y~#n$A`a7jb z3z2#w5ZBUW0n(QBSDGK;yFD<^?8e2a>9l>{cb7pG%=04{Ol*qnx?#Vzapt@P?9>G! z$h{GJLAexcRXqoL-LM;o=;ys&8jvtRAv<<7AkqE_9QpEi)7mFgAAM4^&gcR9Jzeq9M{n@)CvVy?r#DZy?0bCqI!m-pa#ZNA`sO_JZ0>OK z_DNZkO%4-xoBlv6At% zLrB*vqF+&7uK^OPeIKsZ9oyFIZJTi2hB{p?F;BE|Yyap|kaN+7^#z#Vdf<(|5<^?u zc2YR&kuW~!D0)_(2!xn#wwkx|y6a5GdUdkM{ObV3%YOe;VK0;6_eY(Oabbb>P-sjd$3%^`;kZTPzm9L&iF(>z2!(lQz$ z2Z0Wd1hwx_UaMrucVH40m3u2}iP*MZhwb4}QTM%#0rtv7K(1CC9)07cPv9;Er5q?* z+eur5@=G~c)qkJH?x5$4@j6|TN+M<1z|H^u_5X!``LF+5cy#>LKl!iYul>n?GiVzq z^D7$H%wwKoth0LgfS==m(K`{o&z`@)U;6L=)rWNdE5G>9<3IQ_e{Hd9NLGS#5a0?cdLFoNM&&?HF66Bi$x1KmM=&%ERw}{N@+%KmD`+ z@$@`FOP1dx%b@$8f%g0-9l!L~|3%#Nn4a5lDHr_4U->WR_~_~p`)4d{dDB_e{SoEd zua#MWKmKR`6v`K0oYD;dzwukYooShf8RiMl1?OyZRF*CLmZ$kK$BaMrPyHJ9zw>t< z(*2u%=Qp8GPZYr-<`Z=HTIo-pp9mJm^$Y*PKZncT`rjVL`SC9 zAb_r^M?wLgyKEzd4ymYebU*!|xmdOJR1|G{zt!%CXhmDh-&U9F`+?otuih*44(I`t z`_|_hS8Vr+&CYdeBUS2#QcL^khNB+Xuh(mLv|`Ma1Bk-C6AfIHr-E`7Y?rntgdycT z)4Ro2Yz_a*j?1y*I4)4BkgYTz(E-H8&h>f}_PziBAOJ~3K~&nnh3?pN$EF)LY}mB4 zYXcKy!&dA}8`LE@otv;SB7=)P%g7^HOz&Q>{$7Dn)xr!W_|XZNFhG=PCo;%s#Q-Mk zwXgIs@+h@TwBb&+>EE`M)=RW&%rh}uHUNp(lfr;R2N31Ju^lK!fs_r!7L@8MCbj(Z z(VM-eM1pzk5YbK5 z(jfzYf9#WA!INI`_U&8xEV+EIP5za~oL{Sd#(M*wn-m;cSCQbCKl(AA$`$WFJOfzB zCztck&Ak}ul8^D>8DN{rwFNA)HH)w~e)0MvY*O&<-TNuVDNagjMP~v9gUo}k{eAl? zcoMu&Rs49{P!{O`!13v)fC#?)@~f=ci3THfJ+>N2x6TgL!a>os))@=rj~;6ov7>(a zDZc*fbJQRFV0feFGBBnjIn^@|GE%(o4gJ~AfB5i_?)xwNBEJ2dpWt?R!dzj7Xh&y} zuc=HX2QicXs^jOr{r2Je+b{hx-v9J-+DS*p zr2GCC{v!6bZ?SL1f8JQS73|vv-DCAHFYRyyrrd>2U6>-qI}Ir2v@0gA~c=B2Vm4$)}@6YY<|i1wh5-Vl0cz@a}+;6l__Q*GyC zn0|1yJ=AQteg_iR(C+)>du%MBm54kYfHfJD95xIT82%0Oa6sRv4x1|)0~ zv9{3#t<)p~nAj@hNl>l=xdP?V072RM9uEkI%_h8V`-c6p;W&0&>jhf0Z9KOZ>~+UQ zuh_MLh)ccTQZF4ebRba+N(T}}JE)MhlG7%eZ;EF?f~y07ws~7GA`=eP*6pW#*G(TP zC1HZj6wmS?$6y95;VgUDg?1OKjr97|m=CQ2P2jq*?h~TzRa*&G+v-_TlF|r+8p@;; z=|Ez`PAiVshIKK~unW0HYrKfy5J4$-l%x2smV#s>77=1gVB< zt`Xk|pdK7Yt+?H8`1+f{SS`}`wc-2T8#a-DwOg$(Rm=_-^P_tTJf4&#;Pd0lhjicX zcYM%i{N(e`Ez{wAxLnaQy7%kxShDP8g*=!%27=Q9`%>Y z>SrYPyv)m-*0s#1Uv-`UK&|I=TbQ5x^b6uKy?0G(d5N5{^W?k|$>nVh?xH}FpO!e* zE^B=ZBvgT~zWf?T#V9C4dzX5gsU$eLW%26p>>Qo2RM+FY*9vH|^5vIbELiwv6NAf^Lt4&W?C#h@tt@r6?TZ5S0zdQgkxCC zcTVL6j*K+F@QJ7OLd<8jZEb!tNT9#@GM5Q|$3P}V6HVY#m0Y}3B9i*1b!{fu`>Fo+lKAd&+82_6H9+wG1I_Ye5& zv!B3)i5+q|IeXfXRyqc!W<1V%P$XXB5!a97z^&f!)1Q7$w6z#g++*E7zj^U6W9?~J z0|bHTQnrV}VtdrELmn;Iyo$Z zO+=47m(}b{9xnn3#TTD{iTm?mF~|W2BzE#F&J{|XsXt!oNvRcI zeDNjTU7ym|4{O`#kEgmtWiUDC$>SU?HCQNbx0iv$*I$2wZ@>I%(i=%8R>Tj*o5IOl z_T1Cr09CSly%tDx^XRK!mLhG5{N5YkJrYVA$|gWD#7EC&ezPrDb0f!LfI?IGOnuFR zZ1&*&n%*oF;FEIDc}3i-TX=MX#$g~A3G+(?c$gst1G5!?P}_T=PdA7& zt*Bb6my0M`L;fahW4S6Q4kY?wINJP^yY)!iZn!_+QE!TRt0?z2glRhtY<>9Cb{yF1 z)_gkh%f*4j<$`VB`>w>Lqnud&^(aSVV5`7Yp;ra23S1P}v~{7Bj)s7~pFwNc-uD8n z8&vlufCUW{99shrdc{?*xYTyuYaiC+-6zt9#`J5crA@q+{wsEt)GM(P7?0T>Xmm)Y9pnHw;|Ve( zuyzIG!p^y}kD&Q<)viE3<%Jae}= zx7>YR-U1(=(|y0+@u5EBv#)<@A1&ggRzXX{LNIuq%3}1}7tdc2c1`zz8}9h&=U=3{ zmmK{842_AbYy9~!_QLVC&Fv~>duWDgZM%(r^X<2jY$)J8QsGDksBBI(uyXiTZ46T$ zy?D4>CFSSrP;Db+O}=x3#YzvJ#V4s}A;5I+GB+@-S?*)?yj};W$Ko|T5}$qcQ@=mc zsUvu1Ua^i#XXD-I6?yt|{5|4_bQ`UofBsbfiG@Qog3GxscyfzY-mE7lg6ZJWyuZ{V z(SgJ_+x5HEH*&z8=NQYt@*|1fQ~gYQxW5KSy!{$)zx)cUQ{^NNOJ_0{@pQvOfjoW! zsD(xVn2fyyBrI7GkRIaUO&h9K?9{90$HG3nu2p_6OZGET0xoMBVn3GN*qCe|ELV9nf2wFq% zz3<&t1<=yLU!NmkK1v4>x91z~&o|WPih8piiNpQ2&3}6v%G7%##2WT%!T$7gZM#SB zdjk?g@M>t2UMlpe?Y#G2QE2aau}QmzrnkC5FCAnEfE^tqY`FGbh^v7KeZr+S5Me+< z4uKpUL>!GVf`X#`+*_DzQ@p6&;e6WNI5t!1{Wv$_#p4t`)4m9V*T?iU2^@x+foP3F z3Xu2|AwO+9aJ&}V@YTxl%`ch>{sr8J`EPezcR!6S3uQ`sR;)6cpt3{85 z^#ED<-tYGYB<^?IkE4w>yk~Gx30%}#TMxz&j-^=37CX-5=r^tizS_Ti2qd0wH@v@p zz;FNbvvr(*3~|IY9H)OqYq zL;sudW93X|1B$kyoH=U^NaTHSQh}srBR}NDAwmsEe2LrpJG|6&aZXCz$|Hjc*8XZT zw1{gUcv)Lsa%^j@`26!P@fQ1ct9NFH2LRy>eP!rHn_Aa(ijQ^UOFa_DQStWe*ZA^_ zue?rBG$|k1m!6$S=Q)4JwD@!9;A;#Fb9|u4^>9893WyfZ;-)6rdJ=(%64cDyPA{r>O%(k&dwUC zgxrXc%V73P@?SnPh+yzAgA4Pq13)PCN@#01Mw7*DE70DMTWX0FH+%d(w5j_n_uDgW z&o>;;74^9S9Z0la^*3K6 zk;Kp@=;n@a5dmu3L3`63*J>c*shx4{OTli9;G=^F`n54%1}Mx?VujUZfCbxSLb{Kt zYxXCPfW-Zd z+tG$LvBSqeV%0jH=^SWza0m=E3_!w%6Z96qeFNT{$792JW*`A~if!0iJ?3ls!0YT} ztX9qsLT@D=va6C%(;RRjyf@52213+K4Ztf+Bkdqs$XE1+248YCxx--dn zwK^jI!2SMs!Hm`;@eRKC@~hNvViARQBf<$x$QZz7C}hd&rR&!$Qvp_s`$EU@7yt!{ zp^I$jwyjcWLsZf{D|TvGmyoj_=j0uyBRk|~f~;QB&q2&c1IeVHdHCXLF%qLy7j(ZK z^sM7K^BHD0VDvp$^F=;0e>0#MX&KU#xVQS-)O_6W&?Zgq14w9J^hg;{6m|bvM4+U8Ak2b7hbZ;nw)+kXNDzy_((R%NO?E;|0&Qm|XK)tIDB5-y=s zaiBTCBHdAMr8FytkeDV60^1RiyHg(nh*?NTTpotZ0Ac|qIKJ?~Jq-UiWqv-{yHToD zeWJ1mP!TPbsZ~QG_O``(-$-ujO4EQvS6;Q&ZV-rUQxsKV7jYZraI~RLDMLWlR0bv# z<4$xu{?Y+d%J`@a@Ze}+uceLm{fj^RbK%(c$>n>oV5n`ySj#g#6? zzz05*Y_!Gq)ze3KzFzU$zxcd% zlLw-FZDG0&(*XHt0TK2cJURmQOCUjuwG2O|cf5c3V7Zy|o!<{%DwVSxs|FN`W9H)t zm^h^CfNz1H|Lsq4xfK$gIBr+q zN5AzkzWL@G7YcK}8BEx71{Cn*Wibd)t6s6PZN*; zg7?I)Op>^+@dX!#c@Wim94ZZKGT9F>!FBAv{_}qk|LAZ22EO&ly$E}wivQu4{&X82 zLJkb;JE3x(WZmkS0w~D(uxfX5*$L0-F9gc3{@Y*ub^L|@^MA!RPamgpvg6$^{TX~) zHt5|ZTZ0_I*>PgW8BTlXWp?;1j`7(m209xBHd9Cr2fA8P(xacaYx>gB-E?+-MmsTs^ZyrXxc9QOlK1)J`^^y?F7Xp=tS zQZFdAE&J+2n(pn418I1Zd50@#u`0(ioXAH8C&v2_@UarU?pRfr_&z%|)XG?*1tS2&J$|DXeRZAgc;9X}JogrOJ0C}dxHHz|Y1`XG zew%~Czn#zhz1T9uA`WUB&&<(6C;xH=8 z@2=#HKleM&lc)qH!ojLlU4eNo1Qrf^lFO{*+{sSP9<{QOBQiQx{M{7iBDK_mA#>Q% zo`MK)9+u+emjCg371?(I6sNs2CBVeqT#u7lGMT| zL!9n;26KEPBFWz|P#NoUkz5uWe(hAwG_7<&04})hTj`JGaRMe*g+A)oksj~m>b((L z0umcO{^TQk^6|&`q1`1I3H@M*VAx7!Wx-o3}WZ{Oj|FTaZ47w!D+-8%;o zZ8#l+1L9+U7!Exs?5t}>zO!7qk3ryq-@6RM_WeoS z;<_@5I_u1=H8WiguV12<=0DiGc}P>g7Xuh=0)!1?!lvF6Vdru!C{KdzsbK$P!~XG( z%f~zR{*zt%rgjHDy!(Ln-@fa=CU4L0KH&c0=tG+X+p%LiF6mtA=0EF^utkve+wJCS zqL*5r8yfPd0JdJh8$6q})V|tArHMBPh20%{u7?SID!gmOciA&^q!zD0DSp0?zk5NnN|G?_8)gjjnOqk#I>>OC$6()I3(sVSmoS`LbtY-_14R9?+$T8d5t=EGP*N$N85shK~UnLNT2i4c11@K z(*sV?+|n2PYk3yRXSN7z;5Fn%v9;95wH=dR3sT1GEGvzlKbfLI7J_!;R26V;s&cc!42^OWaO#C~jN{;S= z&f)av7D_pQwvyX?61^KO86+aRS(`y-gsY%Or}FUx=%T>>F)+njNn!6*a2 zBS$#^qxie{bl?y>+!JrJq)p}R;Yp?}PMWaHa&g`oY47`a(5cx$qGEIq(=NT{QvG2- z<=~lUOaPknWn$CG^XY-EZklcq>2x~rbKaUgKo39ik6Q2Td16Lbk)9%}g(Z++jHyf7 z^O38l&^3R#0uu2}21Q7+qn$wlS}34r${jxGLzLMGHd0b`k(58aUpl5EfRf?yz>`Tg zl0J>$a&vD)DQ%bP%f91!yWoDm;yCWE7uXiF-D!<=&-n2C0UthmXbpGI&jc74ND^;` zcV0?LPIq$p+0l;1NsG^Q6e4W8cK?nVHtD&?@1O+nO^Ta*gGWF@;*!CH>yX5k6T0l9 z(bkY|%c;78resI0bwV%4A$-@~RRQnRZ5@EUM>}=;nUYz zA$@py+_xX9_^-6jTF-#aogQ^1#;aw3!o9hg4|S=B~l zTicevgB}hjEKJW|TfWMF&bPjTj&zw~$5gz4yKH3I9(WyRLz-rRVByb3b9JwYo(_VN z#O)Pma$t?g}56o4&JYo#HP>s+_nbJb2G?+L;|vN+OpSeqCIA?XwCEy%Zf zTO#fG`PnBXIfzKT5PiaRe-`sZV!2BO5y@!s1v`uVo=RmFlPS|VPUhR}5ZWs)_c?)Z z(E7bQZR6K*u-vD(WOcouX>_W_dPW34syg{2@qJTxNDvQg+P4k+r7b{l+4l}4E^Wf& z-g+c_M{^rD?E8dJIWJaiibfQ;eslxq*CWUJUv?15Q)5tJfFi=?y3ITr-sZGCSS|xk zgMKkCoO(U`*=S_&5Mtl;mWXFMG?r_gls@0PSh#G?JrL%gmJw{xdppQCT^>enI_Q>r z6Zkr`cBVh2EAu;cZXz#8WvBg*>)a5FnNKp*w;{80Z`e$ir5tj^w%0B2@O`GipASXN zycLDd@5{R>Yx*XAmB`nW?x>4WR{5PMy<>`oG8}j(B7Jp38s0SYNL(%(F4qfg&zD&7 zuj>Su4yif-iDx`NKjXuP4|xCKeX~K&H(xZt{jwoLew*}(nh)t=a<3{o_?E{3uzUbu+E2VndcXl^IZz;Ig66!sqU{+ad*(9Eb#zE;{QKyb!!<<{&|m-! ztA9H12tc&jx4cLn&g6VgKO!apMsC3GvPkn>rN6IQTLXS=zp8D=2d#oy(Rw6GIdB|p zLptoz9QGYeK{*|b*;;BF<}^A(e0U+7VDz66sS<`Z^++60-JH0#HHCBrMU-717bn z<~Z2O9B@a$EK=#$MHSno(7Lsix~lDdt$-XIEHaNO>R}4{pfV30+va$s9En$vSs)wy zkz3kr4LLv4RY=89t-={IM}*3+YAAG5<{v(M!1MDnod*5ki|6u+Fj(?>ky`vE zz2+%(r`!O9t#RL0|J(h%bza#n;jP^%c{ZV;WO$bJr22Dqkb|yvot776a6tfqd6If1 z%wC-EhF$3FRP;;te!4y~PuZ09gF4Q@8W@H)C3;t1w?C>F%6Z_Cn7&=fMYav`K8JJL zu*i-k4V%B`Z!L`3vEdVn4+x_lfwHrx6b|mRt|DCyMWL`>9~Zosz~h2e5hNfn_C{=5 z!S%Z1_I$zZcE$aEi{+lM$ASO=AOJ~3K~%w$gUdY*MHXpLy^)#skndgOl!{A!jRvKOd?6Qu2tWq|2{XUdJa*AHnu5-%{(OU=Xe3vxK@c~i976uK+( z_jv!l&7b)2{(TH%y4`3QSR2-K571yk04GH@Q8p-RGUh8mSm$o3+Qw%uI^G=C92$4X zhU+0ArHfh7T5m>NGes+75p_C0&(89TxybopFd=zAfoYD!r2z^95)hey!?Z_&I|bwJ z&RlOm2Ds(afyD{^GB8NS_Y>=z^*Cmy(`CT)eA%$?TL)ejT&`DKFIQZz2Wq|I za=Ek~3X}i`;ax0q(YcU3Wbd))x`BHdMxYQtVkl<<91FI-aEyUie?R6SB!4}Y-|4gd zf`J5|CkhwE9(hMPpT{%jgY^&dJt#eMsupn#A;on>`_&VtOgkS_9YM%Za#Y=s8lT6v z$${knxIjn0dT4Z~XW4%D(IzD@9Ob?&7yi~9SMre@9E`Rgl}ol65k#>P zQyD9jCA0{v?qqA|U-n5sbEClW@vXuzHRzut##&5YM-}| z1;+T5d6tE=)(TXhROzeM97C^!8DHr;@&Tm=cxaxf0g7&9x>9FnqY2>btb@XsLbNY= zK9EGtV;0X$OfvJ9uD8L|HUWuK_$T4SGv$4%KnyFP$N*jJuibYex zU`St1tTbueOhD__g|6*?*Wwo(M}_tl7AyPXXyd}I{A=A?{w3t9t+CxU6jTvZDPEFu ztF!b>F{9LJa3d!qHpt~UKC>29H@^M3^+??AcRWA07NIs7`yJlD>p+6$MEG@IQq3mB z%?2=JV%1U>x_7-Y+FD_u5i`{LXu$~)0|pa&+;@Fl$F!90vBh; z*g~ILq)it4MBIJfTTg_637T}h?K=dZ3B!CIRwAMXl=GEKFc@Q;I0TElDnDKDZ`t~c z1+TN*O)+v=({<^+5SM+&_2~&uPj7HM<<-bK?gFIbJde2(Y8>DUvYuqHFoK8SmzEkO z`Hd{E>&t?&ksFyV&Wt%T(PETh$whEdHkQ%?L`>J|BlAi$HHuhIn-r?Mi!^iIW?F;( z0ROW1F7tIVnDj=W+U;&_&kDrBM3RxtQU(fBi#S$wi)c!~z0*KW^B6BUUgUbo`px4J z0}?h@V#`arZW}&4UGaRo;&yw}dL-@#H9CZI8=HmQXlPSw#IoLrIgca1b0d#Xow9sK zFL|81;c*|z>pX$dmYytl&WlJ;Jx{dFwQX&d$gfY@>AdQN-YxNn)y%JpSvn1Ha} z&~)lKToHh^F>1=1zi|l?mNOmtBjV1Y7HO_9g9&51y7xE!C?6U>UY<9GHem)4Hg~zN z@(H!62WUVdb`x#jL8P`WI%)erl+po2LGP^qQ5_EBBXu03=X+L6UKJsDNf0%~&BIol z86LBGB{61u>sNBPTjp&n{maJ;Cz4an50OpYXa?QpoTSlgzG-KP--4V3oCKhOq)xBz zoFTo!CmX2#9;i@l(pXjc&ex6aG9V{w&1%CLYVWRXb0!%5njfG5?f7bCD_uznHeUhh zj{Cj%UKOf+QG!w+MPmut6MhWE;1$h+@Q*+BpTxPCqBNG7V)teE?zla-IT9Z}d`KYT zxaZ!8`~98`n3bAFDXp*J-?UOqnrk}7Z^rBC*&x6RwVv+6shL}(v!ac-(@>ou_O7m- z$4dt{eKf>ij*!!pD4k?|P8}2dc5OS;9``$r4jk^sfy@0)D~xRrk-n5`^hWSeTpB&2PL2|Y{It$6OZJS9Pf#{le2Drg}&`N*Y$F@L|vH#$YHuM%j}?@ zbGmjhT9v7&@+bha59a%frc5l~sj}qnIeW@LBKRZ2w*dr$27jRTBy>a?Qj=PXW8P5; zlRyAF(rXaG!#wOe^m^yI(C9LKMe%{s=KT2`(PBMe(F@TQui3V?x{YeZ(ZPc+0Zt<_ zI#WV#(4^~TPiQfZzCca_5`*3l`je$O)1CHqsG9ON*C`SL6QP0EBWQcgF$Y`K$?>@i z@Ay8Pff+!|4Ld6!k*^1OjDHVvHTo+gYaUJK_9>7c5MkRdNCObkhZdP%UR6=NEP2`i zdmp)uvm>7BliR9R52e~jAzD(lhijjg3?u+)yGa*q&RZ>jRur4WK`SUFV_+54&yU$V z!vdwKveM{-OwumQ99LBSs4|W5UUn{6UDZzonXTvS^-ng(5XEV$4(Dyfgh(S%G&#$& zLDR^T3v_TIgkH=A72{nt8kQHEA5l;nxGmy>)$$xJN?@FVQnZf&RVX$hQvAE3ZBmYH zv<)iXSiATRF(5%QP__+QTP_R*+Q-utcl=lUU15z=00DC-Wj<3L7)Ttx+1w5H+w%k> z4qNi|-gdJNLzXxnyx=FJBcKtUY_kW9_iFgn3?WIWu14K z)sO5aw08kkXD~suxD1ZZvXiagbh)mCZRGq}4}|YPy%ngodkB14{21y;!^0z1vXR`= z$qjG!==Ja4WnItZwDM7ckKCwXjk-oh>WwgcJpgj%|ET+amP4ap{4jTGt=!l)VYuc+ z9!3yht4%7}{MGj3>-PPbw~_1PiY^&Gr4o*_kj&A)SjDM^{B}7-1+>726=`X^S63AR z6Pn@-nyDUgGzd`mN*Bw69CASx76uWn)h*t2wY7JA z2GYLGXN0)%$rXtVz(AJ_s$C$^RQFf;s(lu|v}J&Od0idKxW!kb?RH+a4cj7b3Psg| zqT1%d5VCjYyer7&c+4BtZK`ecuwK}r1u|N2;~cRgKmxG_qB!yo6K3-w*^LM|Ej_$k;GVB9aVFt<`(aw(cYVpy2@HWa@6H z$RRL#5@=YyBjrA4ed6Ne+~lgd%5}cXqG4D5oI!(>f=!z~-AWAqy6kOY`la{QY#n?A z7;i=iDoGx>e1atHI+UFP=0T5}_I+4^2a}JLoO;7Z*EbfuYZjI*cTz^)HTz+aTPh08 z^+RHz3LaK;dbj~uI4n+6yUVI#F7z-_3?R%ITqNwGG^fqMSJ!K;l0k#VKRD(IL=29L zIWM645^}zX17lpd4thQZy=m8H;33ChvODYFO$)Sxh^>PNY~4Z%S}(-W#-W=tJJJ`r zftQUA5aD*F>lo%~V!xHqAakRwa2rLo%Hm=M)9XJl68RvWaKU&y-uHuca@r zd8yTg=BScx4><|YP)3~8?@z4esj@X+XYe`uIROdP>77Dj9;+?&YOB}?8i?>7i3TE? z+}O~gQT8=x@(M82Q~I$C#<}$@SJl4aDlIXqiaqMMhV!k%PRO98MOEX>9H)0&Z+kI& zA=|z5mK`rQg|86h(T|nF<9b0Mca{lkB_rOKfQ2jr2F^~T=-PcsVcC||ZH)0Ni6FDg z619gN{kPVo?B=?X5Q~$=VSKM1j(vr}-wT7@%iBt(^f;>sq}H~NM6I4T%cc!|Qxxo; zfK|xY)K1HW+V>;r19dwuTBW`phtpvz-0WIWb@x2(5ESX7XNxUWU^xk<@({Y_JSej@ z0S6oLReD+VZM|H^T*@pTwa@?Ppu&E79BCneQEo>GVTVA+FoUz0d_6C(&MjB`!&w7B zjNgtlJbE%_KwX}ifHxkJ{1Sbu*1Hs;Ibzalk&*_@;>ne2Qfm?~F z-+t9WF1HLGwe}rr`-X}2(Xgcl2G;7Y>q;swzn+UBj2Z=S)@KiuGq(l6LH+Ha$j&|cMqXDypdD%XY4k#E4^0f<<%O1iVF^Xhmx zt#;v}xBw9%)0Y95%&s)l(De;F@VVhCNoeAK6yPdM)b|{VKXH5VC_gDRk3W@!mkSdY z*OIAQ&=dA$EO&oq_d`8`=6aOs3&qC{eQJgExFY-{9jVnV*!3G?lV{HNEQwU}EJ|r&&IY2blOYkwm;) z$0Ze7=;Q`P$oyaM2jex}4a1!Ht)KW;6(~Th ztv4bK2_%19tX!D?CWllh5~u~$%`|LEz;#Wa*fY`wyyXbZ(N;=NF)+^w>CaRt3^UdY zf793uD4NsI-L^4$v`OjG=^A3pj+R|_dIZ!X0kjFm-GgKhvG6@oDiO1rq#idBI)*nM zF2TtldLk+7_GqM~%`Ml6_iXJv0}&GCHAOcVZ-w^ZN3Q+agm?lIT>3t=pv11aIK;A! z1`4_prrKI+ih4d832k^2jz&*gtwK?EQnpa*z)LK!F14joE zW>J;+9nMjYQHei;k&N>kK6sX8x;+{4*~2EI0Rj_4*yXW!ZY<(C5nBfmPft(y=*=6v zdGiL>r>8zC{eo@V`n;ws_LXquT46&3GCyWpk@80lIRIbq!+RzeQ1tNYJO)Rn_=yEB zP6hxR1Q2}`0bz`|AU(q2x#tb&;_eg;&H~9ux>n{{mZ|ZYub9qph*Wa)F_eot(v-e= zCPNytAkBGEt}`tE?huC#o$n(K&TEP@=|ifMqaDmFq_{EgJ<~q(JD$1Tveg6G?PG5G!c$~9a{ly~l5Z6~ z1Yzb2t{#F~8>Yd7ON~^iy2^s!K=nRTOX#A%hUC4)&=tz{`JDPW*A^w&NcUut)#2uzS=ZPb=Fbjjyn zh>&RHl^|+S6x*56#6Rl%PcF!nIai)(le4dd);MP z0Boi0%KLP^;?0{k_~he{@$}}6?;GI_MMGRs4r}>{r%6jo@qN;VR3+ z!O~Kw60&@`c)Cm)Eqsp1a@gqQ4Gcj}1$Dkn=cT4|aGGUcC7i7*g@O%$;!YsD4eUL&wx2P5%!tN=LDIH`QGVemxmvmFUn8xJmCCW39NY3rRGY%g- zNUk@4W>d|%OY^2uC79WkdSPe?rSCyw_QvQVUANM4EnLqrgB<(YeKOa@_B<35b3dgq zYAXL)0BbzRPP(NrI{QkrX4&CX=H7v57>*%IG+fDKDa}t?$Z_INzEApjplggHYus^{=MFqTUNBonD(8feXJ9Gr=(<2EZ3O|Ul4o(lz&=j^gF;?*O-Dnw{ z7-Weu0F<+`Xo=|LFlk+68j%Ai#4COXnxR*^RTO}gMzwcey~ z{w$>;*89?1YCAZ~W5^3?>8-miBY+-l{n#oM5TMqb_L*ocIor0i@#))!QYsk2MgB-8 ziJx4WvU=8aXX&yzPL6bLT79r#P5m6hnrQWnULSHPk}N8#(I~5S4v)mjt)lkjdV}ty z2)!Kbp02;gLs?wAPDodVb?Z`XTT7~WqP}H3_*uEwN6a;{{fuLt&?*!od$n=v! zrq{aorVWX+jT+B~(AZy6YvFK?_I$WW29)?Y8csh*{}}5OAq!PWE*v2 zaClNUa%8NW+}2aPqrTB_ILP1*2iZN+N6ASBQu=uC+|%;Av-}R<({~Bzak(&^_U(el z{@3-f)m?ZasmVww(w4C|@as-k)c0_n7eD890EY=o4197OLW(!UKQuARyEOpB;*Rby z%yKf?8mbp(*2VyZ^%R(GA6xeym3w|R)@fUH3Edy)`GM&IohI=#N3yQcHy zBRS@D?fjJl{gL;~SJYDNRje2t=9#RYm%InN}#=JzqrnkSDa2 zPf93SL$0+}lx;()ZSwR{YZv-Kd33IDkA(F7D{R-?B$J7^3@R+ga0elNlJ1e7_nwHs zaq*H@1*j#+=ScXZIgK6(GT26!rNw-9DOfo&g`J^`0Jw2T6W3XGrdPbm4pihg&AX9&@4nLTY;_*zW%Lgc zcTM(^;T{glLvlJ)0pjJT%hUDX@MVCIuP2*8@5lWOR$&&|9CNa;H!SO;+>h^bTs=fw zzZh3LCmoB>gA78kpb=yrSLya3Bp>Z(AflAsn_esCIaF-VD4(Ru;};W#4NN$16VKMV z#IBouioBP;?0V?Cv3Ditsf%6^1Husr=%&@~GcYm6HOkd|Kj+Qrz1KfMYbaJh-n(Yu z08`x2Q$i)7W*SETGS@x#vM6t%-PRx?>O}_J^aaM}SaQ89lHeXhNKBA>Z#Sw5k1->^$X&cFjmi9wG z55}TJ+P;lM`n$B0DGTSBGDCI@NSUM$$bri>qF08Voop`OXkbN+Om|SvXFK{ z?lkx=fGIt4*2c0;m!#-i&poOFJ86rz@`43$B;;yU?B*HUVAH*3H+_WVAU@I@LXA$BH+LI(rTxhN9Oz zXjF(V_C75R0JO5Q1x65SMm4&7P;)d*Kb!#xbI_co6FE>&8CjiX<4pQy=}bmlpFsfp zoyUPWK41>7R*y#~CpjmkqqF0&)*LL$>@<tp8mt;^LIR^f>=W#Y(`RlW~Gd{LCE+N-h);Jvj8la-cqt2bB)tL$dYiw)~m6Pfy z*O{hJt$bt-V-9CZGx$8MLWSVgbk_AuDn88d$;Lj)KV)MlGfUW5Qd*5DQXCYNK5@DM zh%271*S<>A#g}~Dx2^9T(ZEF8gQnGwT1s1`Mq00>IqWBb)!A|eAUX?0mUWbWtyI;x zgAh_KtISyDJ%@4iZJ&1?>wX8(X*xXQ@x1)TG8=mtW^h3|*d592cxA_Cd}rUyAc7qu zb{;K!9nw#rqGzVpqz7e7a%zsEV!Dpfz)+7@j?r+Z_G|_ae2iei8V-fx$qu?wKGy|m z={3KmPpZ~7oVS$f_al&7)Du{LIcTK(d(4T*>Ea}RCy(dq_b?_vdyfP?@}Wnr$h!k*Jqn_2g9#C!k8O7V z=wqMh`yvoS>7_Bkdm^-;XkUp#3#OKMbFdkd*e<7Ls&y6wvXd!aZq)gM2~BA>2w`{!PA?q zN#yB)Q3bI%4SnhKIFUi}+L-io-Gq?5xuIkkq-Ucwut&1lkiO!eVBdCZ`-W}b(+W*b z*DEd^Ncaj(qwN6IA*+ibfQ0T}^Qrxrdn6?3q_f_QCIg^qH`c*1ZFheuj6^Wu=SZ?= zpvJBxGCa_h%Zh1T0ta`}^(0IN1gL=m_hMUk49%Z4R4mXbxr3SesQ8+FQ$`tEg=tCel~z zQH5;U-}K&y2~0%qM3EAJMl-kxsR@=_>jG4B7L)NF9Bw~@K+C`+)-sl+!k6RI zZQoF~&9hsux%?ITm6ms(OpO2vB=UZi;l2~+zj2&vwdMR=xgg!M1YnS@@O!#Za3gQ! z1WJdO|082g*2caySy>9&cnl)zhIJ5sr7H)+Nl`L4C4GBZ7ZXqDnj8qz-8SacCP8x} zg9FH3|Cd#4$X8q96-{sTp)F?YX0;sOfXj4{CmBDYDri7EIWkrUQ);FwsG%a2FV|ay zL!ms`8hwZpJVS0q2e}Y!ORDZ=!)0sxL0qnvcD`J2eR^sj;^_%*-aO%Yy|jAQc~NT( zM}aqZLO9uN$yQqamCDySp2xtws_v%(x4HBR3gh0#Y`J4}NPCmKzM zceI)v+MZ}Unn40I*Y_8}1nUfvlLQnj-7!AWF;35z^TqeB>lQ<6&PMaORG_S<%z_AL%^HTWSn&K2oXmQyxYn zNw@pZ%}yz~K|^Yw%J4YP%k~pWlfi=3Gk!h;sqjU{^2p&L(=9H*n>CX?8|W9rLMKia z+c0(yNf!_Lg7X}@xuq9&eqABNm?p+Q@&%G366qV^{3HU-Pfw587+bdTc@<1pR=Pzq zou}>DEFEjA%LV(kg-)tRUYgjKK<-vR3beExQF*yx)lr+x`j;CtT$Qom z>}#f)zV*_gI_afmJYnvVOd-E1ioZE$L^Id=hI4|40h&s`o>geK7bH)~VV7gXcKB93Mc5*xyA$0~5KY0jL)~^8*9uDRouX-flHOyt3 zqfCj+<>P@D{usYzqDOv=V1hG}!LF`lLt?+OC74LM!fq@~5AS8s{YT+u@&QZ;D4p+c zB&TPz`l)yUw~UdVxuy}QJ=>%8IUDEJl2jZ_l(Ip#(f~yNp`iClv@!IpSHh@_9tmri zR&6bd4LocaMA$Dm)Ghr+eIWtw{+%aRLK&t!5ReGxiH%P`V^Eq-n8bar*rg9|lCBh42?+ox z#VeEbbeZE*t71DgZ1;N~B8ToQxA_u<96WQ9s~k9vpo1N2bb+pgR+Z}cmJ-WD25%o1 zgQV-8r^ztbwQU)1N{;ROH;+*=2~*@yY0YqYZX6RFQfkUT0{BAW4bPGt*(6 zR_2QvfDud#X(kZC0A)-wf0b!Zb}btYi&F=H=)Dsz{~!w%ba;0MR#WB}cDQJsEqG?*{z0vf;AtxLz)J^Ynx_ zZ$83DAGHnV3|!bm>wVuEaPM_gadeu(3GljD0MX)rGaQsWypv_j3=M*Tj6U6is)k`arYfjSvkYbLD^O{9% zzFyFp=|J#Shi{z^Q6||Dj(HxFqv{d9=13(UdSmi#k)2l!5Mgr${2QZ5=XhU5(Xwo3 z{&AgtDXy^$9v&xqQux@<>eikGtPIw3jr zL}T~Q&3`%rS2-i0i&<8^JYaMCH0gjSgBC~dNiZ+Sk!^oz_x}zaF0sMJ4j3Kb=WqvF8^Rd+gX=aZ!+Eny(?YE zhx3;dxnFyaL>>4^1{)+dq$gelB4}kRcO1xp2nWL@Y1Zhc`a)*SZ$1$z`cNL>Tm!Mf zO_&CcAMkg%cd38FtUSjfXdoW&FO^CDaym{cnfi&HUw_+a#@ai1|Trl>p?6@moMG}Zl_It5-?iOHqtpB6W84z;75ycNMHi+y4T}i zH6}_9uj^HS#%PBedmdST&ER24l2aZwBzlK~>P{5$qCBS&(tD-5S&#bWs+Oix!;+Tk znt=pAmdzeHQb0qgDo}g;Jzz`D=6Jw`&SgX*jr(z6+iay6@r~_5 z`Bof9+`D7lwM;33qZDl0fqHDHdkm}K{6wDnJP&53a(V_-Z1@ySa^~e3(^9Oa{tyP! zlP4J(^@D*4rz0C3OSjfgtn4JDYl~IhpyAtNG}7&CXmr&oY%kgN5(wulw+#d_RGPA=?Z_ z#@6IIq?PM2IZX?P)c7zpSWFJr0+0|-m}iOKW`8Ha4mmpo5sM?7XX0xD5tRSe9H%CE zK@VTPg3hJ`#<=Eqn^V_inskNfhzuNZ*~PoD4Cm}{`VkMwmeEG^@UhahX(*9>NBq~6 zUZ&^lcxYi%7l+Pn!X zJaTh}+^^ZU^kt}plb)qxs92h=mE?TB&f+;69st?N>1Z$YNVxJv+TdwyEoGqRJxoJh zQdR~f$;xir;{hTlRZ&YtQANRqqHUu&-L&;2)i$xx!9>YGB5zJ*M%IYZpwFCislK_E z_+rM5sb#aJDjOI%wu1Y%;ke&%96OHtfqGQbgPni4GhxQf_Jla@ciiuH+-`T=o^QC_ zZn)oW?YVEX6#yfKH4R)pM5^ql+%0uB^L zP51XUD63np|H7Q`I8&kX+VQ4@)s&^Utl6fQCJ+3baoyFbIe7i2#hg|JY$yA{P>f*0 z(qI~_d`HE7b}(o#MmTuj=X{LiY4xMlR8Ne)P*ld0Uj$M!(sUjqCdT#wQ4IIo}497i(&3X3G7x z(u>XiXv^uzJ2LF96kGp(-!|NCw@xMw9DV2Mn#1h+yH-Z+`&Ha-ZFQ*IYao2YV-5b** znM5hq5weoXG=N%>jhe`}T3t3BqeoT3W?(1!M1K3WH6kIaG+kuhh(7W9da<3W6WC&K zYZMX`>T=@Lh`K!1!4Wec154ZR&^?%fWSAZf_fq}_J*xV&8kvBv>kRe`&4uLeaJK<7 zGU0n9z!s-jJjdr&*fYH|e6QJ(zqjmbyn!QD!3c_{ami(}aM@OkBqx2pAlp+%@nIkd z9PinXBLrsm@^^7bkNm?SloLgqd{;QM!pc_3Z4qvq6{@Whj$T zXR^QQ40MG3e>_Vw+0MrDL6_&p^8FBpTLT? z5=jBD0XP^W-Rck}3P&I+ZnC-9aR4`<90m1OP!E6)3PhzIz*Y;&(RNCuqqrlXRO*6D zVeUedk409^Zu{@uwYq30%y{tdsGlVB;!eW*9;6KB#g8kdOZ%@4(Ww>!KY83@bTj(eEj$kAHV*HPai+w<+ow(h! zmqUk@Bux`4F{OLVTItc#q{OYVjYFR4(S>65LlK7VTFP}IMr{1ApAGuWf7z;B(|BSJ z2HmJ(JCly&*?%{X2^XBe z;=$jPPqR{;h8Xm(3zK<{duHVp)}(HY+404n`*QeIgvS4G(HVh+ZAY zKXlh2nRG#aWpe9hYCqjT@*s)rHV<@ax zY%XkHwqd+;st1FFQ;sQj|K$BSNRVE>F#bJd16&tvu1~WxdB5iw+m)xUFEP0Bb(s8e z>6uP|p7gZJ9u?xL7^9)yCqP6%SU!@}z}WDErIYd%g5cz!_8rrQrGFKDN}sQ@nLXQd z=!RZ*60!9mfPEM0vTfM5(pF;tF^WAA zj_ znSto3PMW+Xw>^Pi(;d_78gya=qxvVf00L5D;Fh=4dSBEBL?Lit1~NX4%i^BiXC&0C z?+kjs_gus!!(IKBD7q+(Byf@8h~+tNw8D`7;D&V0WmP4O@)LLFO>8R9nQNm9Q`#m= zt21n&llFy`aVSn>v!t9W{gZ=e(Gi4_LRtzJGZU$F6crP6!maU-dgzX^k(MU!? zX(U2^N+u4x-fpk~eCITMF#(9OB3@jW%Sw9b^5CELw9DNc3;NO&0Lu##U$zh=Lh(;b{ zbG@keqZ>ehtMtK8hzw{wh5~?jUON!$f4)aT!Z+j@!|p)Qmz015bU-O?R)}de35|w(4FbTW;Avc~1}LJX{#gl)o{rJ@7^X($M(u*{RqS&yk9JtM9iL_c*5xwa`Iq;a>u9nlfmu*h^slIILzX95|*_4 z3r4aLj~_sw9M zfJDPi&JWi!AwbEK3+a&{+m8e!L_&tUbrNwqv=ufJiJ|oleUcm3KqO?Y1GDu=JUw0U z`tquTr4I8YsuGFU*H^rJvLQ`hfBkhB+VtWGNgUc_nM<(z)w1aM#`*^%A?$am=D1UJ zKtDm003QxJ86hiYFE<%nsFKM&UdhNz6}D3@M4IB{y2{mx@c?k}_AXkR@GvNJeeV3| zulH;Tbyb!VwmCaVEr_9==!y*XebhoLr~K6LKbCIWm!$QY={zOX8Fr?jd91^d-spWB z(nQu9vCEu@9s6a&_309ZH|>3&h`kdDArqw(fGa8y+-4P~Gu&LBM_^)jPsM%IKM1l&U+J>@pG9g5QZghu8Y}k(4 zChi_&B%&YV90|*qJn5R^$$1`e6mF~U-bhT|4K4u`C(qeW7nFNH0)G`PR}u4~8eY|n z(Xq@CpH<+<37b<)88FF&YafbD;-ugwWipX^F9bZx{t>zgQd{RW{6<0}ljNFQh|qGa z-LFQ7WhvR0rzgC;ytJWB#|_6}6DM_f)uZarrk9tOMkItxd}U(nMz+vfQAOeT@g;T`v@=Va~UFX*T&-H^AcU}1+*SAh~r$IwhA31{&>%l-I(DGl( zpWMAnRtP!GJ$_jh`jER?ZG|9C06;`bfn+Z-8R_EnNvo!S(bIa_z$#Q<-7To7_DT z5qim^#*-MFQ*%+4!yu7`o4t`E=JWENkF>}dlO<2sRKI(D5<*F~R{pw9(GB%_5K%OI z4tz#=g->XHe|X3Aa||)dk}0Zree%9e@;vLpvloVVVyGTdH+}AH>Fj-{gynYfCzq`^ z)~!r?972r226i3y>WqV}+X`E?i2xJ=-=O4y zYDHl}<$|Jh!?pIX8{*XGO4NfJIk-_@2DUUJapPzp|dtZAJ#D4+*1O@q;)<7!ExP=OU z*v;z6MeeN-GU5F@a_egXX(^}M9erL=D|DZU%@GZ0QI$Cux0@R}{?$ z&v3=iAsC_&my1-88p=N|2rvd<9%hK+SMQLlX!9dlkA(C@T(1{gp8686&rf}xL|>uF zkqAE|s|6eDW(M{eU#A=&f-nk#^8Bp$tChRaibO)=@<>n$ULr||{x~Ax?@ftBhD;I; zhdVQ}lj9ukJH4xNA}__t=m~->IuXI&4E@dXi#dkxopjg%3xIdx#@6N$DA}{QeuzDl zGdKEr{%(%s;`|}xxp3@$dT-&^1a!J~z@e97{e3QDn!L02W|>rXf7CtR!@RWfJpUfl z4$;x{bo#;@C3Jc^^>+r$#J+@YBY9uNM|awOD4xE)xT6k9Aot#RxTC)l9Q z$WVheZn4l!hcd~$2p!VY_e)U#A@bNhO<;KS(^C4k-&G7+IwBn+Ic^~mnpozHw8aiZzc@E+%L|6P;~Q3eth(Vd!m zB+pB%O2gz=N%J~9Q#zL3?3hi5FnC^lC+5e4zypbI&NKlhirx?q@j}tPbOrAD0qd&=m2)2 zA(T+KM?sJBa6Wq;tE)M`dJqKwG=>)yxc6k@ageMm#HSw)P6&g<*OpA}-DW+KVv}k(P0DRzTBG6=_tXHKcA!A zxsG_u5_$zS)j47OL^N^3dqa$z(IErF+}9|dj?Hj}Ye-HvWMae^=%b$)1qEEVuLj%Y zA{#WV?Cio_xp=Ne#X<&Q{OkD^+;U$WNaDEgdXQFe2xG=#3hji7k3W#+&fAp<|zqb@hs%1Q)kY^%z=3?4-lCa%>a-tN7mW! ztU8?7x}`mG@2c*G->Ep;q4RLXCHUj+&-K;0JGXt0SVo>+Oum#z{{wcxu6zS*Ms(ua z-IxJUB}ZGtY#aBrr;9xr7Wo?OSFY2e^o(bAXVob4XrATxWP1!)dPPS`xlJwLTV!c4 zJ;4&RV`yYt$;yIE43&6R81slVeb6GdU#?eslh6!o;kI+N{}l%BjP0`N#Jy&8tQ)-H zCqWn#ets1Z`GKj8TV?`eH)Q{Qp|)dkX)8hz7nBZP$W6AkVCioDQOg5&pJ5XZ>^v+( z)(s8iPu0^5^x{ieg>T__oxL= zWOE_>JedH{p;Z!=B|QwU_$GR(&lA#l5!b!%R{ezMch7kD?j7E}e~0Vkg3I-a>*b=m zT({M&T2GxP|BaBR4H+SXI)VDx(aE=^p=XUF3unC&=zv~6)S~p7lHIuy1TWum&hzt3 zG~D%Ak21iS$eoXCiqq7w&l^iG$#r+K>~IKs;cw(Mj*MleRj^YPuXo&8wr?vpXO?TbwfW&)Za;E9I?|z*8yW?_i`e`g&y6W|W$!CCZ5ztAp=`x%Iwpx%6x8mQ z_6sDU2pRC>>C0I8WQXKNCE7dMBS9K!4sR0gFVpOL=eKv1|=?QW>0cQNJ4DXMh?tp2zNII4P#Q{p)FGA+-R910mTcQ{=)mC8gag6z{ zRk)vPZ$ux~bbY$w`S}U&o}cml{X2a4@E-eadq>F5^rffAdir{f3F*o8!To`O8IjOu zhKw3a4>s}lnXW184F@Ya&q0o+Hrb+ zK_Idxob>8EJSW%w`(E8h3|8_Z!jbqar!9P!0OK5Ay%7YiNYLHy7GAsslzSUCb>1$? zZ$c{62Hz8%1&aUH|~i!}6xhh3N?ePyQZ>^w=BmKw?s3zn+_gyXy}D*e_34jRpvv zM07H-Rd-#%8>8%{{d$+VY*?f#yM%BJ=;a@%Oo;En;v_SsYlELjBwtp|ft>G|Ni zK*q$j`sWm~KJbd!e-H)M+9KzLLDO>=M2JY2rzPUB%07X}=_JNud@okgR5bd}hL50E z_Fiepja!dN7z~OEw6?nBbC(ys!ilF67g09u*-&!i{E^tG5*(G}5cv-3h8~AN8fLu` zZgnN~s)PR?Z{LzD0LcJT{8^Gx3f0hb(5mGGt7|?#dIrvvj%G&!c{z_(jSmW50*P>Q z8G?0vgHcZKq{&-5_g%#+;H1VZ=xjF^p`%qEKka2@z!fFFlT(z9oDcuhZcp-@0SCw( zaGp%GZsEHjC5ZCjBhYGEs~DwFSgENEYkI=FcS0mS*xnLl8%k~3BUhXJw|Q^lb0Z5< zC)nk`1Ltf&-|B|dMa_pQfINba)&3;jkKm_^hXQ7m^`P`Mj_l7JsmSGOC3;fci+7_u zB@NqcgJH;og2~B)=pXeb%G&H=AZ8HRX}X{C2l9O4LIcGeN2#uUW9~s5sqgCfy?CEL zA1t7+i;gtJUJ1L--$|HaJM7vKCU50tuOr-HZD^0WITPBt@zQ*3>-Hf zHc6_J2-hPq2DLKfu6M%;bZ9kh1)%}!4$8@>KGI?}i`l75x>5j&2Ot7uWX}sB6mww-O17l7uveS26D=}1r z7Lt$>cF&2?a0W!`lqVGVn`DF~T@|iu`y&8gqP7YUSP2EO*AFTbK4q4!1OjF*w8$rL z$$+i^7G=#yMGUu{Ia6(^cQWI9fRspFHta$qp090a)BAUL|KUBhVkKiEk_i!uksPeZLnM)Y zxFF{BW#YG;rv$j;83dUT3a<+Y-E^x>UFWjbSrRHq!OX(T-w(=V7S6;6Z%6%OS8W{t zc*wu;(IV!Pa?0n<;>9b)J!9HwaxcUt)w7XAm>r7W&6BYTqxlpIkRZ!xI}NA}N96Kk zp_lDVl{IacObvkEzDYPF=_j($2_fRsAm8M?uPdVbR+sI?tSGeZ^%qWSub1z9Q}BV3 z0WW*m0}9{8BgG%w{grd^*)P|t1M{s%LdZlT6ctA~^qlqr+6lDvr3IBt_=s2}{MbMu z0v90>#pXxUP8#|~bD;jLx?YJYL#S+MlN5X~>SszY=;VYd2}!`sJ2U1pfHlS;`(a=! z#>HaE;a&52E`lq!ii1rK8ltVI#`aB7$bJB%iY9+flgc~`geLF!m3>@gPH5UI7VkVj z=82LSKz%4~-@fPxL~dn`8`$Mui58Cd(LsWXr#%~gI<(0pkJ*R=$SYWrF&TPdb&3rD zD+m`HY{o`xkt#4T%AB*76jbDWT2cmU*-4n~z9;u%@7%&S6a3s<<rk{JUjT7iEr_x`=g0P6C)cnwD+ z`oa*d07meX!u55wm!-;TY7I7GVQ6(o%Y-mQ-94U9355ooT6{x#av1sAMLH0bb2kOz zUfNtee#C{|2#1l)aBP7P?~YU&vZI$-P|PusZj6V8lP76Aeww zfS-?Gzfyh9PNvSVz$Bk$q4;_n;4e&1ikwRQSmBJEjxL|x&PYA>4RO}9YYj93Ly14) zkseZfy&OE?a(&cvegn=+TdoTpt+0DZ8(n(O1c$V)!D*}uZ=_UjF90qG=8 z-wHS8ERTnzK(kF)m01|v6VQ;VtdD{_ogkc42KPLbyv*N&VH1)~6RH}JWPhvR2Y>Nr zCi!aa>3{eUp8w15TP~~a5K;(Twv=6PB0Hkg{ZZs88Voxds@}xN{LZg@`#j!%{S$uT zKmNXI)xaOHk~u_q>1p6lKb+9Y?NkmPxQd=@uQ7i6-~Z#lwvPAy>o@$=U;O*ygCUH` zPdA`5-KO!J7)0O5q32pojbO_8-~Ik?;R7@H`}25z|64zSfA8P=x2*w*+fb%Lgaeiz z)%8x8yn7?)KuFF{B@0fE_@5^ewY~G7{iXj7Uw-`h1b_nn^1t}6slGM9)8pd+zmbT( z>~q&RR=Xkykvsl-El2tDb=#f)=YQ?5;un7O2dDA=^Z(p03lK_{@FS1^t)4RdU~t|N8&*KjN4F#$O+o zv3Bu!{crwT{NOu3-!IL6j0SkA6+_&Hw?aP5GDWT*1m|bZPh^4gpIjS`%MHVXIJ|nm znajY<@6&HSquc?jyF;Vp=QtmSko_EvfO{_-jTF3*2RKjsN3J{|_12z~`vZWTlQ5a0 z?-NfUtIJd{Dr%n~UAUlf1#tmuL5o66hDF!x@B2vf&F7Azg8D{vI0(2=Gb$C>I+0*z zl-f5Pli?*G6dn^iX50k*@He69!@oF5e2Xx2deHLkq7`7U){bA-)Hv^|NaMj z+;2Dz(!D5T2W}bW6p(2LVhw1dSSBK-NBwauJ7D<9W4@fr*Y^oXMw>&=%YYmJfq7DK&uRzL!`MbLn&&EH+O z1C?xeQ@ItC8?~N=qwfw|(Flbq-&S}+9O_X~Zx!`+px!EQYowu(2eh564}fost#_p# zwPLFUh1>6_1sj*PmxTOrO4)))#D)h>Psaa^RfqfZoGvD zf%dNXe@Y~J7!v+m_s!G3%GcSgS*0_j>=cX3XS1uZ6?Cf=x2@o|ZMun^jzt&re#e!g zpdNMDj4t;`Xb(yU88#`*r7Zx~#V;tDi86$8l~YFtT2G#Q6_yHXE1T*l`_vt+t=ff9 z`urs!6(wsApNE`eG}p%moa`y1*JMFFqWnYdk)8YJQ63%mVumz=7!cMMrv?)4G1Xa_ z^?O=x7)DlX^`qPxuleWF5%hZwhM;A(^@T6wcbaEJIQk+PAxnTD+cP2|=?fyzWQPd_;s8NOb&#C~&-EsTqQKzED#xQ+Qu*$X+J`8!v|OBav< z#S zMkeZ3vGIlt1zXv$?`@-_?bth+pw_~c$iwk^;CQ*=_VE?RO9fs5+<@bDpd1^vo%1X7Y`C0i39h39{GGQ;_LAG~%_bwGc_U$5>hvH}5a@PZyNIdEmy2nVkfO8J}Mhq28Z9?== z)8UK)p_R|R?R`h;9hbeGKjL0{t1i$Qd{oZsFqaii!E?Y1D zh|}&DuJ+i;Qscg1bm0RFL%Zv%kEuJS_}%Cv^XbNsS&xRSX8gG_021R;2YOq>PVBRSk(fv}LEq{PYc zBP>nn&nK~HLN*~TEQ%n#tf$^b_ux)?SNEc#PKr6@bIgWzAuG@nBD{Qh!Rzabn?QQN zPm*4_Hq4{q(&9ZPy^oe&oiJ_y*j5y=8x4C?PK626z-plbxAAW1W>zv zjzw8J;2UYtkVc7ePN&|R`ah<@`;%RiiG_~}&B)~+y3L+j$(FLwzNtU%d?0-;Cgi@D zW6Jm-qdL+s(vR(YAQF`-m@1CmGjUKG(j-LUQZBfZ9hdzAzSd3%q}M=(uhSZ?b;IvM=08`Cen$clKQo}vy2*xECE&^ z0q+cCtq5l%Vp&jU??^?hTC!AxZQ9ZH=DRUiG5RPt{gcj zPCe%!araUt-#%`Gx(V;vvVqP{B1&n*p%ADa3mI|n!(%qLPfP&Bwdxpuzig@PiQq`a z1H^4`PUhI_y7_4rD9o?$)2{W`@@Y7~6sqnAZV6 zH1W)1=}FqQ4VTMBcdmYVdb$(CR+hKhP4lgEIGo;OA)|MY7~l=Nu9>3JUFBts0N zKN)14#GWe{Z6R=gZSGGm+tB|&0&-lP4GlCd-dTW#chhq^gK?wtJrX<%YZ65Na{V6G zB;vk%yk4HiAV0UO`FD5Xcux-As!wLlMNCd-Btmbg{+M{Rs;geVd?N%R+7Htpk9i)y z>Gu+u7@?5^tHv}Upn~|37t~7yo*48>D7S*WZpm2o9*Nt5&HnD{b;8Y2Qf_vahp{PIO^5yzb>x)+4G=60e;E9NJQT<|;Q(_44Uc z8|Kj$133ERZRyo8JCR`tK-|{f4&W=Lo`x@JIFcH#`^G|YUs{z!5&O9hHf+iFKsfTS zZ`k{B+gh*Vw#nS52I6$w{Nav5B;;8q8pM>w*FWw8iSU(34n%HQ;z%g7v6LK?T$O6A z#LpK_<$0xfdkO{;QQa@LPk6(Sby@H+q)Um!-u8)jetyF9^YcToyWL&`h(B~r(V=xE z0{yWUDh_G$=8sK(2nj(VAnc&QLp>7B$=cFLlKpNh7C@M1jvEvBq z?e`W->5&M%60fK)74?O|2LVDPZe)a_mbMXHJs}bh0dh(!WSpyNUf?H%p@kCsa#`t( zz0(ZAuSu`MQUrK*I=vYUoEG+|T<39L5s6jo7I9b*mSq5wXo|j@=1Jy#a&u}!Jm`}1 zcD!6JeYf6C=QrGLw+@b)T<+AykpJ0te;Ti^uXufZ#Y;cFzP{qq^9>uf9truzZ`PH2 zBxW+uVo87~!v4vak7jh1x!9GYv|{gn_jUf-PM}MY0p>REfoxK)AG)-8647@#-uDgL z-p1VTGI`gvTubY9m4<>6C*>aX098VzYLmYSxc*jcAl>OM$*=kznpe>v`Rl0s&F0J@ z4#2UMExo5=%MH|rRy8qD1=xP;272Y8fanGsKegF6DQvi+m$LVSBFb-G&ei$j&U}>N z%5=Z%xbz;0=XdYGMEI?5{RBQ;uE9Sd!cjK-sqg(xAFgL0Uh2qkIC*E2_edfddE{!( zV(LA>==X_U14dfLxB0m#F! zGLi8OujFqspgTXiJpH)s_`Rnm{6E)uZ_qFP@CTj1_TdE`Y$zd-$*1Kt001BWNklmFSZ5H-$YZWYd|h2b!%^wCDAtR{{X`PoF;Ni-7HH zJrD_ML;_cUo(S8m;JEELZmku|hBP3|liY^?pIino1iYnvO9R$Thd^{4Uk&p(4dwtv8<;}bq{ z!FB-UwE~}R`1o9L`Fn?Jv5gzmDLNdmqiHG@zybkP8Pwd-5$-47ls~B0e&ZGNqr<&z zuKq;9{p95Vc&?sPF~=G(6Z{p`EuEDxnA&ez2blV&Od@b^#?z| zr|VS>i>B!~@PB^i7j$Tok()>e<2;655Bhl{5orZ8A4!)3*-+*A7CvA8@}KxQ{FA@; zyZB)z5}s6U%=kb4*gq7?CuB%}*J_y&1uLHzz4i_(IPqXZ^V{hbBNHKs`0sz_XYnum zz2DS$XZN?i_yQld4LY<=Y>1cPs2=n@(+6PIk}J>VjzD9+0r=HF@iX{0zWeKOp9ts8 zufP9*AFlS07`&6XJr2tB-TMeMxWDw}xAEtG_=DyC7QgxY4!^(mMF%p1%wY>=yMv_P z0<`@%+oke8}7duMbBTh z>|KR8Uh0J1@P-tIuMqC%3NAo2BFk@bE%ZPq{@z}QShVZ*#AIZef>DID2Vw??A`!*p z1+&QMo47)lb^xfI_b{-dv5uMUSf7GdZY z=R)__{=_4>wI$Sic10Atb4JAjI_aJL@E?B9dJ5p=&9}yoeWxTsL2ajzJt^ET)c9!2 zla!-BpOvUDTh}A8w>fLq%N5tBEB=dL{_}YM?!A^}i<1$9wz8fL)3ep2T={Su!W76v zH8KG>BH=-{cs^))m?Ea)c zxGxLKZ2pQwk=AKDpLJLKSKs*s{MSGKrwtfPfU(^3pkDVr2|9f|j}kDG2O7?D3}$5F zSAY6v@vA@mvq6vFoe+L%8=~!*>dO4Z33yw%zw(n`;;;PVm+d>(#H^Ou5TupcBn%o( z7IC~AqjRe--~X*Y`6uxo{F{FPKlzhCi7&tW5`X;5FY)DLcN_%Od&)t6qiz*D)#W|l1v`+xMfUC5k*hocabddJ z*}WES^UpxPw;4`82JGbRgPQml6W2gz_v{!6g@53ZlF}-@84R}hUqg0Cn#I-vxlqrG z)#+?!YQr-)T#_q`+QoLg-)=W(EU33kQCzu6i3D>SZ+`4HTtwDI4~VfBayJI(6AbIY zwlwTf9f3eQzY$OgbW~6+z16Fr)C$z1>#v9T5iV^*_Du?YreH;a2S(??+E6Ss_~$Fp zTAfVXl1OAAHF?Pi`7ES0iI|6&!gk=VOtKEx{GFwy=)l z2uEMGKJVK2ei;IDSZ`0*NnGyPuE_H9U^RovAaiaHjJVMp1>s%QC{_6Gdv63n@rAr? zPjjoW>{rA3G<}kMR8bogG|bRR{8#E_nKqOEK>YSLx8<^5+V64+WvS)E=yHApvfwAn z%djPrlUQz{rvj<$T*d@7wIUIr{1=K&>nk-~K&<3&lKtV+_M8zqe~@HKfrOPwXw^%V zX{eHVy3ll?A?PiT`4LBxv(=kF-mSt#aJpfHCa{qzo zPwjaEvD11nS9%XSB7l2cQLhMXJ|Ox%noHx9sOrICu4&rZ(Tdl?6J@H6ziK;EWAJCl z`ijg@AKEzHkBZzA8Thn05-}s~4C|3@^RZlhsVvD)Fp#}q`Dt;{^cZ}Y6NkB2&#%?X zW-E77;(hs7VsKx%38n2eC%am=cV*?92DGThN*jdSai}nAFBECnJ=ri=Hx7313W6C<9dck-gW zb!re~XutxzrLwYjY0!g1JgJwPRuB(JVr_X$m3V>ac~4fJJ{IY&mWiKM6}^(D@(cJEWtOPaeW#`%6R;5gU;t zj*<`le4bZJr@a8sUg(*V7Cd(&1vCT2!Hr+SsbvnUrm4n9s}B;);H-zKgp zo>Mo^ktjEr+}!VRxNo~wt=>6CaR`_9VDxio;T?gnp(J-mg?joq0CMJ{PM_WH4_(*@ z0Ix;I8o$;pf8i7T&Oe-%AwluVnoMLp@V5MsxQ8nKfEU*IfgXS7W7d5sZOzOlxgx8p zk{?74L?<#~^3!d~U<`V`!Do+M#oiuTh*eDE^j;|EdHIJ1EF!dJ1grHp^q-0lk-t56 z><(|Oj6jSEcZ`z(62lx6n}qD`9tYXKfT@CO(fLrN797VBmVx!h?n!8&W;Z-ZdT`os zM(Krc_lEKGj!5|YNiOs(tl&z{BqH4rcO^TIIrG6S9IK#FJoiT116rR}iL{n)p&?B} z$X-VU0MccpP~U-kvKm(}H!-HQR&BBKabq6K$a*F+d2m0ci+veJj-VFFu(|&OF|a3^6)&6Mg3|7$T~3 zTktt?@S^lEaR?r~4J1F}RwTl7nAV684c~gKM>(H?%=9hXyX%H_@uLaiNG4nz^~U2Z zWI|iY&EH7kef|iDj$qoSC%dVgcXfOg=h@I*xj%+M`u(tS6VK9+;}X+0`aS(BemslP z0$BsTYF4C>BvM#%rASrn-LZ!8|`t3pOFXK6D0H=t;mGiOb$WbeI81FOhA_dUmkvSGjHz` zyWtaaz!eA_PNkyfyX6IeTwYTE$J1|Dr}7gi1-9dl>xRY} zf4a8L?NbNr<@zDK=7B!->(rY8zcSLANX%tNq=CcbX|2jpYB3YpTZ!~}P>(B^=>ICS!**`6I^2hEqj# z%1MTfuqwaUW6%^{_jXVoqV!q-HilGsW60u?EV;CV0*h7~nPdiwpD0WJTIuUT`;F?T z$i{V+_X7zSz-1&CGUlFB-eflnzeraPH!j`*fv0X32D7f(qd-wx$dbrP*qS#fVgyj@ zrEWbEKG=X)L|K!2=v&;NWhK8YO^$D5V$-lIa%*Ppk;ucFCgi~lcY>dH1cY*pc|QkS zc0MTd;DR*Igupc^hT#i%K!$o9mT-cR=MzgXs0vPxX7YWWIDr|l)OO!SV+e$9N}Qt{kn_-|*Qr+SaE86jdQ+8(h}ZDA zMSiFBx_~Pp_G!{zBSeHE=M>V_ugTr-e-wX(NO=Yk!2Mdll#F>R=mxWv25$PQO#_3& zT$uGO3RemW<}Mb9*c|H}36*sLXHy7Vq>p!*A*r?We?JP_xTyVVwWc=L3c_1kepr?BHI)4pg$erL>iCTuqNA; z+z)T+*F(<(hkIJa&VtTc@q7H?|@0K&$`%04QN-Zp%N=%7%?`-XDO|Z z-+jvqfAlVs2q5L}1NKDR=hVR2JPH5IT?G4ZW{J+?u*A+`jzN~;F$_8Ldfi>j!&pY@ zfp_5Y=gk?tLQjvyiID9>wr5uV#O_JBVaRBRkMm8vH(LnBS;#H zi_(v>hXj|t-0Rktf!*{RAh&Xp0J*iBcZr|1bjCdl^xy#^=P(zj=Ml0Jt(BgnYU#jb ztc)~(ywuGef_hxL1mOE7LpjZec_2K4Ao1Oh8n1*L$Rz;#e(9U4?QWyBV&lbCMiKt2 zvT*MdTEIQ2_(P?Y!zV>^I42w%*ceuiy5cT%cbXI9?kM& zMJP09R0KNc*Ni&}p|=V%V8fIaj)Gs4de#fyWT7Q)HSFOG0G+!>fm_mdcfNjW3;s%m z*D-kWEiCP_tvmx5VOgPnUpQFJv5cCd#~f&xEh;Z$45M=xV(*-S5L?xR5yc)8j0wtuoubaQ(b; z1#tm!1##P^Vc$xz#DhQu-~yD=NJSyEV*#+C?RM*1!-$kj#2$yz4B%#CdAGe_-#5?! z(B3O0p{?I5<#C5d5N`$uCk9Eel{m*5r*Pz?P6i_%$}x!Y{Nrhjxu*aoMoPbO-J*dJ zJ7u{vXm2$vv-5L5*0$>nN-u=uwe93|(rk2*9hvvGN!O-?*IL@Wp%EZ2Aig9Sj+NIA z2?q8v5L&Eorfd=Fypxd2=@quS1^;k0kZL!G@3b?^LZch$pcqE+$)Gq zCIzaGUED*!)6>y)#qJGUEW!I^;(jd|&FYXo|15Nu%9`@sNKFX1>3T5_UG;a@)32z@B$jUi^@TN-bhHHcZpXawP)~+%w4nj*WpGc>3ZAPamG}^zIqY zPfvKdUU9kfRxu)MM5v{pZUvXi1-I)JPwx)!?Eos{vcKYZs;DpAdL<5k+-7vL5gql- z=Zs7Ukto_5L2jtR{VHy3Rj$+Hp@c&r^WCm<<0Hr%)TsAYY8VoQLx%8uT#U6-ZIP+SNrkCas;DEp(UBn zz!A${Lk&j7895H0>i1K<8FZ-gKcM&)(9n-T?%m;LJ73|!$DoS~pW7GIK_Cn1;S|^8 zayWkU;v>+n#oHN^d=ISA$nWa?PS{E**tcDYL;LM`db;B2=?T~C6_?9JNd(YV=Q{d^ zij~S>~j^>%sVa@)ai+AXMFlts+EB%AC3PI&{AdZhO7m7`QQTRNy$kwQm?*349dP z$|!xGH`yqfYQg@+hY!%!N@DPaw#?Mlhy*t1Ib8^sFRr+Lal!S&71wu9czSxmWxrtW zM1ngQ<9)~Fx}!c{fm%V#C{%DX;feq|*PVL#P#XP$ZjbhYBE$hP;0$wTi-ij>!589Ew!>2f<{e% zMvo|QRHPEcc0GZg-6+3_L_jbwnNbhD12OMpOfLsXS{Tv?@V@VrPy&*a#W^@7V~$K`Ut^?JqA({m>hO}42UiCWuUAVMVSap1VwZtpWfk$b5;kwCak zMt)`}7ddnayi?uD#Y2=ii8S$yTJMuX&?_$EDx7Ga+-$mp5#UJ-}&fuNg@$)RO=vf81&e`ENCR+0I;Ji z+QCpl!P^Et7&sV5C2X~z@}@eRT%O5~E5HYXZ~j-ouhe=R4gwzsxB~THl)8bAwp_g8 z^xo*NM52nJ+ZosZ+IocLxC3+{?C*E%A9h^cUvPQ8V1H`6s5T-|z@^Qj;C;j8asfZL zacqSM+qR*;RPc>~SAdST^d$9PISQy!8^+|w1nJNwxt1P@C<5cz%;onopqaiJFM0Wj za|?x)6xn0^gXaGSIrdU)=bYcC=+it7lawv;d;a#1Pb7Gj&k4*bks!jp?|Ap_8PD&Y z@vU!tf%os<?8 zH;2MfX~s#;?vaSWpcC0z_mkG0k*ws*^9Hv4trTbQ)hRsR3pN6dq-=%n$jxYY?f0R^TpE?c(6aSPWHMoh=u8hjfR-k& zSRDYw{)OI%zyT9^e2a@!cv==2g#7>2#kzjC62+@GX6ww4?AaZ28%=X+)sAxxDAYCi zFS?Rln0I5@fm_tpu)Rjmb+v$I*DE1IXk!Bp47g47ak&4WTa(#y85KRu9nrQrG|_oJ zo=U8s%P@y{40?-E`zNujXpXbOuu11n9!?pPr%P>+IIx6mV@t5fxzH+4_x+Ik{9 zp{O?o4uFpqPCXcOFiNcrt9LB!M-A;?eE483Qa~dNJAj=)J3u=Dmv*EJVSBe>d$*yy z->^Mz*sdG4%Z|OY9tltZ%GL*xDNQdMuGd)Gf`ED7`0w z++^#aIAggEMb7C?25X^oM?V+Ajly!DNYL56S$yPdVl!h4A%}|1y;2M4mXEE){2qhi z^`qI%W!hKI$M?1J`)l{TDh{Va_I=0m^D~~GpYW~TBk}I}*@3Oi4FQp%O??F%SrA}1 zLUB0c%G~FuNNT$hjV&?`FMDjGQRm4S0(sE)-F2Q1l1%)Vch3LlC$L&ZZ{-GK5cta+ z5XcRdxbu(^L1KpQoqUIUO79Gn{RW27s-Rv7~cb7 zGUc%`^%T|HM7EW45<%|W)IgH_ zSVeTz*cNTkeh|+*PDS>dMduw2y4&bQ8Hi~8Ik$4$Mm1|AA-^JrTFdj?3$%v8r1e#4rs-0mGqXIS>bz zZ_|X0`8r9>;#L^>8hsR{lH((QPI?u3>kk$5vEyyH-4|bcfe#;AkHoVM|7gRQMB$XK z{7WC&wC@}C&3Yy1uo!XWKE__M#VcB#r*_KEfxr-4001BWNklzX4 zu_eyF6Bsj7lq>(T%gWOmq}Um*4}3N38%XLz{qF zZ3t87kvQUH>((OyBNHx;eu$GN6FIHR@?QZ-MKkA4dXkh>_PkN!IOnM@Geai@ ziI|PA4snZjoL|$*|3~5?!0$(2iH63dNu55iN2YgZ;{W*lTn>71a{>Lh&{ zNUS%e1H3J?-i4INLC^Z{M?byaD`KJLp!SF+WWxJ1`VmqUWOPCTCwhM7hDQqm5xybI zH~Fhnl}t!)gb;}~b%HFWH-HYH9E5sQ)%}{kStW%Y3D~fvTSa~4*5lDh1|8g{AcP@J z8wyvHx?$sj{r&ShMvvzZK za3Ve@&wYiSf$PxjxsHPmE7%4z`eyLXiNwg_b5eY(!aDKumaZ6o|3+4@a!&3&QE;5j zy|*$JRSioaZ2N|%>lN3hr#{j8U0)2~+9s@)tu3b+43X=NkYOZ!9C{ln(!(#TL!C73 z9`L*P`*W93YbQX7C&QUS-jNyDz@TfU@{3;KpC}-0%hLL<#N#p*3Zw4 zNQlh(Ww@Eq4GFs*3Evwrk_aIRoIEUo%>mp^2G4Z;`M+TsM%24E`s&Y3NN|C3BWe>k`**atCI3 zH|cHPGod?fxq8>;LqP;)3_srqV(a6}CU0KP64^dAL%zt-z;LY@9G~}eF}zI9eilaj zD(PYEk@fL&fI44Ch7x@C&j*0-^oJ)3A#SSktj?{5F3pI8=_;3ZDhEa;;B?KLNZ38A z!ec|PFLy0zDf3kJ0fnvvYoaa;nOaW-_f4NGxUq)-eL#Z0zCSbR$Os`#{ntrEImnR+ z+c=s{aYBKWPPXPaU*cf!QGtVjqx2(zDg(96k!X3h^>W{^zkhzlQQNp#CPuk*@^C3A z*MjZZj&yDJ_{!i5gRcNzE9!;88>5z<3B8qU>1Ztgr*5tgRL+y1GvMU`_L58l;A1Exf`B#SHt@Ob z9`<2bnkI-xpPXny(D;;6g#)w#OEGzcmBF6+kz1$w#MEmaKmP9ByRfR*zPDwI(OZiM z(8<=NxFJpZuKQ7V1zS3anB)904+e0P&Kb@C6T*&|r(^=Y9L-2bOWE3zds(|9*KAVi zbhVy%`OWYtdXtqZJAY$$tM&GHBW8zI-#JAf`|2Y@(YxN_BP+eBjP-Y|d)=bkLTj1J zlTe0S_C_zgDK$}KDn5z+Nt{S}%C;SsT_#u?k&t~OT6{^7hjeFq(qQu=j=|6b zmC}rNY`7R@WB}e$WZcQ0z35*#cb*&Sxd(b7y9YO^f|IzOlZZ!%ery>|Qm|B&@xk5t zIehWhllHXNg9+HYcRq8OG%`3OJ=Pmve;>20InT8hT2diIf}yRtGUTK6NMO3E;+U@U ze0z(_;J1-_4)rbK5?}M>Tlqx*tUJ%wGx?NU7sG&o^h^Qzf=J|?xz|gO{f~Ze@&_(2 z#_tC51Z&Vxd*_LSk_hWP@_7i1WGwbzq+U6-4FXIYiQo}IMw>XpldSi=3ghWt)gub& z@XoMIeQy|TJrPHrA5nFgcQ`Vkf%ad2+~!Lh+|VpB4~mqs4yUU6J%J8lQ4R2-<9cU+p_VkC1WpMi0Q~u zgTkDq$W_CMQh=)D@7s-7^{MX^r(NlZgD? z__I8;9;s1gY4ZKd&)A?k9&;MF>+$%#g*%>`jS8)24j&11kh7{JqFw1&5^B9{RH!$~ zH!@LcTk=)pgV~V@(b=BBh*D-&GNBvK>5qDk1%WF-we;Q#`4-whwChrU+#|lVS=!jR zO^PlI6b6?KRBG>a=;OBvx1mgZ7d+}TM@Dw#%Eb&6rp9zC+>)<7Lyq=rs|?hw?V?u; z3fDHNqfhJrBTcqGa|RNkqQGd;^o_SG@t}D8X(FW>=LBf7jvVJLc#z}5R7o5a8(cZ$ zVKKHOo1QAp&Q#h1Q7!EvOEkpLvm*jfJpS_Ml>3s=8qTaUgm?$ zoqz+EFi%T{@BJrJzXl58-k11KlXdE1xNrM5I%%=-GS=h70GIYoCTI3F0_w4+Q7Wc& zOXKe+ghQ*D$gtnhdfQ6aM`GXi?msE0IQSSg9L&qRss;FloTP!`%`yEG&>fyX;6{1R z7jN=x`AE~GWOoe~Jm9eBGw(k)&qEEo^WNO$Mypv`GMH-jPC^^Npo2v0k3N3X@B6yM zdSJcu4Q2wK2*ee&lInXx1badnSZ!AX>md{7sS4+Vy%iP=b&Fs(ml-x8<8}w;NtxUsImP^2lV+%9e(AXFxmT2#>aDO&I*W8A0H1J<7@K z+{H<;RF?sHIrT>LH$on)T_z4={`vY~yJye$cpA@R-7}fe#m!ac_qD)4s2~(aB&ao< zZv9v~k?22}>uE!_eP&7cQMOxrxV=_5`O6Ks_DS8SjC2l)ds9$b>v2=bfwcrPf}lfZOf0Dd5{JfTEeSTS5(<}8x zB4jLj5C1Gzyuoor5tL82tsdz6v5zI^k@x--2#LaT_a19-b8lyzj7Xi6c}>i_YawRbZm(g{gIGtQakWN(wlG3lzWGoh zA$!E!>pjRsV&=vkg}ICJ9&y1)9wNzz-}o{g&*$~UmVq|XAWtdUPd#~NR#&x`1`g#b7b(Z~n4iPi;5C$P@sI5OcP z%)N_6y4@=?s8ZiJV*}OJ3sL$}dL&S{-pf&3PXxC)7VL<`d`oFxZn+$%z(jP1!+v)> zow*1Q^=iOxz2oc{&0mW8o%rnDSge%Sm(Z?7&7r2G3MnI3Gnqg)X zj7T^IJ}JfHV4l9di}m9;&!`X+X`+a#`i1(0{KZ~Nb7TP z`mqcZzmD{IB)5iwF3KAsz)H$J!#D(f|1IH#20FM zhyavW-~%CeAmm_>{P$8V^n$ygD7s-{k;MQy>6Hx=Ws^kawqJyti{72}NW8H+tMlK@ zhKFPlF_hIKqNstLhaW&l`s`dy-|^Tv>IKI6o?W^7XMxTD(p$+y{{C(t>S9Z+J72V* z=CsVpdVW2ETeb>y>W8o6OS=<*e{>nl&PdIfW3ROHJ&9|Im+xgJqOf3xV5)tu+T+kj zgzt?=6JmqC%L^sk0+EnjNS}|hUWs@<%G?fYSe z zm93JotWoaA^&Qk`?$_Nb8H?D@n1wH4qAU)d6*(p=euq|5$X1$Y(qqx z4T#JEAGfih(mUbmiyEgp!49ojKB_rOdil5Bh}I*qZ>29w+)3|#X+WcIl4$Z0hep^h z)}gn!l`cG$lfj0ra)+0f^A^njJEkK7MZ3Qm?&8mL&+$ko?w6gHOFd@~)>#*2V)vffi+*E0)aJ~ka53s{ zdu@y(U__$zL{!weW8W)UuSAQBCjzzvGY|RD>aR3nS&xMDWOyR+Xs?93GtYr6LtPH$ z!=!RP^ci&~5pG2C`6|ihv#p zT|b*$`Lf{Neb97P1j|Mupe?HMJoHRR6v5cGP9%s@>rW@NV$`}pZDY@E%z5sS5T$*) zwRQTpKH-|Y5KRikl!hn{sSPsW$%n^VQMY%n98Nz0TAD`T_sncO9^EWXo*BFQV z{^;wx2O{=HWV;cl; zkoj%W8)12tCtF8Cp5p_|<>HJ$tXnW=Njjxim=)q`2*m20*|WR#=T2paWwi2ZChLy{ z_fQ-^!v#5X)o#`}F`mcx`m!DY;p}`iyeOu927agKBD4LTf-t#u&lH2`_hZX=h`UeZ zEDlp5v5?80Py62HL)2P(PsHAPC0cy)&?X@hWAD3>2)}gmtVd#&*W&K?4lkY#*eN$` zxuj3ZRWk*-TroUoxW#TbW z@4npyLn|eFLU;g&(tCdO3PJ;a7G{d1er(6B8m93i)N7Og8v-_g+d71?>@jXs} zmx-oxk|lY9KGE9d@d$|!La}XI$U`L&z))ALRrsyiAOZs~e_0kkk3`%L_j5>uf5*$$ zBi{s<(Rd=XZy^!uyiaxaVgLHq52VS147s*&<^|_%U^=7B60+gR#Bm&m!xb^{ zN5Y*6(^|m1Y&4lEL2f>WOvLxzRtL!`PYU6Z)2~7(09(PZy<_#O|ZAsejk`bKj7UJTSSkq*}ugs_RIg;SyUOh^h*OHUi- z)XHVA$AM6h`$|c4FsPJ1H-cMBY$p+#A{QDqpNt6@)%oZlF?9Q3p)pQ(ACD3ON-BO94dpB zo>n1BvF_-L_DEa@BJr}n*v4OF9NIL+vH_q5P21vKSqW{6mwbd;Hv(FlU0bJZ{^^Ha#N*PL0Q0Ip-Mg?22b^N+vB9qk#N0dMkHG7mEgKOi7lPddMWw2&MWzT)e3F0 zxN6yxlsx9fxXek!n@PYMzte^^ipDn&$DH8)x5mhwd+na{GuJb$#A)zfT44jYkPwr; z&Ch+PrXwO)jReBW%bZZ;Vw^t z{NhL?&#AxK zShs9^GWj+VVFW|ok-8A=<>PUXh7wp zsIq^35)&jqLYOH?`~jFCW|k}@1~4!TfC&ODCYCHAF|owJ1KTsp zl0kA?hIadduC9AsANTBctzeKD5l=)$uJ!J7ZyV>Ep+b zbi=O)17NENo~nk;bri3gxrnZ<*@{3ArTRIGE7V<8kvR_E|3-L;+_+b9=Yaaqd;evq zOV=5FK@FX@K4)a&JPAyVbcGBhZoRz_iKK@|d=@RL@=20NE~+{-!moxoIVmFy_N^0K z-p@M>3~W)+J{|xW6Ua&@D*4az^y$Gc9e~10rf)k0yGLRlha{p%BJ}t|9E9Mt@zgk> ztu4y#k(_5T+Rx#%loY4HyFF^7B+9JzGK1TB!~y+geGjHv>EYQu2CBgy9OK=~>=Pgo zAYW^JF9}83ryRFG9PVZ2=zGM!9KV`ksAX40T(x8W7~Og_;=HY39wXRQz+M6OI*xcx zOm>#xQ`)fFPfaby5D5cK<%vGhPsjbUfaNjyo8r2m0$3i_2xgFR-Zxn=qvk}&JFZ59 zH5(}dXXN%uu}+rNBk`vMzL%5E{6S&aA~(Ggp_@#Fsm3h=ieZwxkg>pvbJcxS2t8N> z1Z%2{=idzAWyCcqHOL~c3Er!SrFv#%_~(<+=|-jRXHWq#rgRSOFNEt#Fo2fEDWHUv zoO5rL%N5G|0e~PUM|vii9tYi|HH3H9^})C!ao?vMCC+GD&$l|-2J_GD!*sXX_(0t@ zy&EwZS?&#si3ac$Q(9@%7Y{JO!7{d?pFyA3o8qsku zH5lSm-O){^Z(Cz}etxo#DdH%YuOil`@7;0wo|0#kq5ywh|Ec#k zh3qgL;OO<~kr1NJO;_f#C${|@*gPI8kTKf=(y>#>l+c zGM)}~fKwfF$Cg)V@@($7;j)B|soq}WZ|aD`&Hz$-KUtMT2=&*7-BSBEm-}M@NoLfY zYW7B14%2xkoN%t6KLhb|TH5L8b(BZ4Gm)6(%N@3FBNBOk+73sdZE=+sAqDt@4ASB4 zNdW|jFY3VqJ23hC5M$-0AiHK}%oJ+YiHdErON#$lc)a6G_TIDH`|r5-g^=hjB>ORD zA~jnGiN~iISj1jGxM4=Kvkb{+=bCVC+{OyBb21P?PDA6S*vLXndn%`!Ro zaKl;!DfVI<)f1>pzAX)^J$3zcL^F5Bu#&)KbYSrMUw z&UJ{#>3Kt-wIFN=J{mu3;Mo}Rcxc?;VA{xrBm$<8xMNu8o!0X}r=A;765TZFBXI?Z z2n8norSHm7PC@lpF%O}BrMUAWjAifp)%R#a9iIS22~pK;b|S7xM#}?pBxs^UB`T=y zAwZ~P)4C_=_0gyg!nP)4BNEBZ1^b7W*ewhmd!3<-aUXRLKRnl38((F=(e1WTYn$0C zB@)csr#Qfz=>vLcr<@mr!uMy;*NZ*MtL6R>PC3zy>2jgokEBsG$16f|)hnKRXjQxn z3-WWgA9}ix)S^>2J*w?~2HRoZfQy>4JhBzzLELoEFmdC}xnO>yE=E%ENPAng3%`B_;-k$}IV6anBx0xjsfS%i z?nJa7#5^5@@s>=vh(l>{D&azNPAVh(G5Bo>7Lb22rc0 z09q^aJ_%5!=)LvoC|$R&<&2kP&V1>10Dc7$fxYtDL!Fcsl+}8aMioVe1+pfb*X?9I z*RY0*5yU-)95BVRTLdgprmt91_*0o;qlg`aI2r--1TjN|_l;g)_~4h4hns!)YXfHh zq=d7Pa(U7jvgr#=`lseeh#FIa%E?Arv?Ov8t6m_i!vWfBAYJGQM_~T=(Dp3D>QG47F|p&>2BtO@_Rbx6@2T9vh?u^! z(}~2>(8)$b3aAd+_d7AsG-uk@q+b9%->-X$mt_SqyRJ;W>@t+MF2Lhea3Yz{uK>e| zTmafNPjQ+D+H|;Asx6t$l<6SEgs04|OwNcFw}OdCS59>~No z>s79|Gr};}@mYPvven+(AY1)l8D_i2U;`eg0b{vtpC2U>aYUkbIiJ~C?1YS?82UVl zJh$aDl9tmT;<7!}BV1S>t2FBU6|gU2Ho1_Tx|~(|m3(!2ZzU2r-OB1SRG8tBAZss& z{vv^xE*}Q;#fb!Naa2NIivzjU-0_`>_no$*#Sw{+MRw^GTJ8RmyY%0y__CcbbUY!&Kp-qRT*Lp_g#Z8`07*naR67{t#&be_?rxuZ@AJh&Y+&FZ zlLIeCkT~_yX8@+XUI6@)yQs2vae~veOduWzs(;~S*gj9tj4mbPOGMslM*!Z_dlCc0 z=`V~(==2gc?J8=SQA9GK^iG=-4Q*gj6RpcNVVQ#IujeI?* zggHV2aIF7x+r1zZ0W&~*vW}@Vl}S6Hydx@(NYs`CoRoSm^=-p$90!sKl!L6SQ07&( zf-Ws?s!p%SVQx<-TQ$md?%q!D*W%eV(OBu?BgkW|6G59QGBNHuK!1@8>v>(V$iMF( zt{zPNV{}49o9kb|-g{rTX!<@$=-m(}5eNKWT2ueYSP+TryKkZ&j6TL^8}tLehY-sc zk?;no&|@w*Q0WMCN%v!sUw!_nm$ML=5gg!7E5sU3j8{vs>P5%vL8AhI(_VP8{qUUW z`neJhuj9K07**O>j!0BI34}cUD2~E};qKD$I#BQ|jC=&(C{sEiZN<4D{Se@)wJ*Y| z%zAvjqEyzm{G9lYAx|Kr0o2fI1F@!T+dWO+k!Ut5v2C~1Lkzu1jbj-C$s#HYF21yB zaztJ9Q7GuaP!RCuVi&@xgBj#cpkGyHwB-y^qO4VFGVfQ_rvaKpuSz5nYeyEICz?nk zjc2_*K}%ezFDM6-bTT2-2~Dys)%ea-t#1r@M8dvf0x$dDZtHg>h-fTttjkIIGT!Q_ zs(>RBZyf=U)ZY63qUYTbEO*NbZ&CNPuB7*KDC&mYHT9aK4^;3~rJ?pHKL_pgN+GVu zP}SswCM}G9a)8z5qgQB0j6|fDfN?oeU0G3e$v>8sNklHcRd^IIVxEdv0wA6Jr(TUD zAx6l!&u+yL{82iG&s0;JR4%n$@m&Zc5qM5*J&s7!)`Y`-kubJ)OwZ&VaNTl|hmg-J zyX&!zcnG!$e}sJ;QHrA!7|&^nGRMDq-m_8Xr_xzGcU250TsfAd>KEwQL8`l%NDLXq zdyT|OCKO*P?x8*^0q|$sPDDg)XWI5g`@Ye!>xZDDZAQ%^ct=9?9f@6RR6;-RAUp1J zU(IO{36{};D@3VVh~BGgGCa$3W5XUO)uf5^;aqUt1aJ=04w7WKyDay$12ICQ zMktgS-X(PzfpEEO!f3=$Bxb!vNtf6^`o+F74)zZB-r$Yew!xPp7a}cB(7tHK7F{y(AHp(N;jpMAOJboHj#r;^36{kgu>~qZFnO2qZCW zKbIo3C0_j{_3Lu@CWOM@i|`L3_Lr=mr>RX22F8-cBKASLFd}g{ppDa06aZh5h4Q4HCMbPiXJyhwe zd#3;ipi@LUMpUNbh-D=rW2Ho)@UgRF_tCAxKj4Y)PxN|qA~BWQMSjjg_1xUEjP|Au zYQqwWiJ%UA1Qpu~1ZFa!<-j6@-z317spAMl3+I$f5Ur*+A@EWW;`F9IVSWvMD@?E+ zaX7E9ND^?HM;&B(W+tN7ZF3zDrdfyB5q2GaJYSxjuNk(&bU}}j4q?mfQ<-#HVMaPK zmUY#AazY{0zibV;Gc952qY=kJ+i17`t{i%5c0q*3i`LvfFufCzz9*p{o!(`PM$j0! zU?&nXL_5ewB(!iNkbvY-a;iwgT=4aw#0CoS8+ou^7BbMw*x)MMc^c3WoIQMXPNx5! zB{wuPnV93QK-e_Z2!7soUm-w`N0mD?*i1=>{@Zk{{G~@OcL^Od0*aMD+4y6OI3ncF ztm~#ss?bG3L#rgh$OBuNw#W0-rt+s#n=Fl0-cgiz({S%3tkcp|hT0iqLlxqb7=O^G zm61G?HPm!=!wcCSOn0)tgVZVTRKRaplez5jaqq#QNE~$9-=&`72jak{BzZ`QN!X7q zFqy?S1=Umgj>*%Fp5d$N{<8J0liAjVRN^4wD>a4bO=)UVEH}3eS5uiLqD5-oT$jA8 z5NcQHK5VQ@!xD+ZYTwi9BM?+bB=F1UEBj4!<~stY27u#wcVb%&w-z4M;>ln@hV8^D zst7XMcnP;Z-^NPrnm5v3(DM5P@Wth0=-1&dTvtRwWkn*eA`_K9#q%q>%Asyok=8zV zZletMMqp0nKk|JmBGJDE5!@e^@ytOwI_M-q zltd_jppMkL3P>jrqaCVl8boBGV{dfqTbi0U<1i~3q5jV1nBHXMVN7k3u|gAW_4{#h z@c8t@7?n8k)FxFNnwR9XhIm>@Gw?=VZJ-W79tRHuMqZHyRKiR_>cCnN)BW=~ADTv~ zBh;_+SBG_@b%i-|x^D_-ajfVhUN@PDD#-H)D8{&^{dm)2AJ3iFqV+UG3|&XoFA)2) z{bp@kP92DR+0Z1LTse?n*q8UA%(X5DyKQYMft-;SSCiO_m-B*OtL`M?nO($(jDx!eEcMW!9+&a?Y@(}5$h1xBRTlL|7-)X<^bl>kzB5XPnylAZo z&fP!DK_t{V=;0x+y7~aB#zP#vG&;({iWTKjd$Or>;G~??;pwYs(Ozqr#gPEpSNRR% zIElbEfp|%y&*Zimd1$Sbiy|nXL>$!9IRY8Pk)!+l9*BhJW-g!7XGtuRRRm@W1@{3j zQmi#3Etal63)>KPDX+&olN1oSXjqkRSl#oM(ES|2yJ3llW|>y$Gx;*{LPp{Q?FRSq z37uqt;10xuNev9a*kTrTN8@xrSo}u3!oxnQZPcG=W_pUZ5&JMCI()B8X;~H{j-uxt z9x?*K)aP&t_c`GbhZG|Sa>K}_Gt^wHjdU!-;2tTLZZHZbj=zZbGQ`miG`5)w2HOrwV3i7-%TA{a+2;RNMmxSj!S;vP4YfdBI6M8X<04=p36Xzl52oeYc z?KJCOO#khp5t{Z@SoLB%*gNTUm7ryQpZM8jheT@Ut9zA5^cBKx_JZ}hcQ5q*{d?NB z&F(?q(}~1bwJ8w^TfQ?9BPGF3hKoGI5tj#7VYX;JpQTCr7RiLisplULSwo?*V!Gt- z;)JJ1K4yKK+i4Y)2vp}MNsUBk{KFOwn|K_DwMn&K{W~K&-S0cy$M;5bdq^an6aX#v z_3I4}fG3t@h zS286X$zgBf`>4NOr}e1OR1yQL$$X*6SGXKNu9P=pRLjmp#6SpQE1AP-S)O|&tbEF+ zkO&I{z#CK}AEgXw0q9>wq;1Urc_a)9esocqVfDtP(fK&iQVijy0iVHuK!F^8g)O^z z!AO|G&4#sx{I>vtNMaTpSt1F&=^GfFCeHmGJRqtGB0v!TVIAFOn53;xEy5^%we zSAd>PiX`rAEhpHT?D6bHVjMZ{N?j+1y0|aPM){YKK>}{UJ*svs04u|Bmr?B6s?k+o z>YFss2>6SsO_=VuFcTqY5u+hs%*`A>2oXjAW})UtM~FSm(J^D59u1H5CJStRANAVf!g%Kx z+*xM5t-?Ga@kGzhFJo%cyYzxJ5?R+*oX)hI+VmE6H3tc@XM;kqe1b2;>4)%)tH!0p zyB2Xt5LH-$V}B-xnSg6n!4{JF^XdH?e=d#ALHbcuYi)SkoWveTZ>zEMiQN%MXs@plH5u#d1 z#V#{ApMVq8H=B+}dv!G;5k?Q8ZHG3lFTL;c`z%LVktgTNa7%1H<$*ZkmLR0>G$5@B}Ird*a6;D^FNNw;$)=;=wDqJ` zVn90A4Z-S}-8iGH)BWm|DiBzZ2@_`ltgeRtv#h$Kj$CE!*%uNlgQ0%tQLWiRV^cof znR{??BM)x0QSXjGB6LLJvB2B%&e|F^zb9I>cL?o4|U~b%;2& zK15_$cS=b=Jv=h)Ytq*@)|r4!@TO<(F*#t28!e{)U-|KxNc49k-o1OFZQEQgp(nE+ z>$DVswf|@PIafg8uA_;c!P^65Bmg^W$kBd9GEvL2ls4(|OeX3)JyQ2*Co3BnO>!My zCJ-9$c~}FvOhD>m&3}&zWm6(yBM^f`-0yd~-}`$J;d>+Od0^Q0=FhQAZBDk`wi5n2 z*!)|<3a4THdz2}mvR%o_4~@1cu#eK0Rhs=&Txh{YXW;pBBEi%ee(z;oUN>aKd=k9p z0x!qk@B2g~>W(CeCVVR6@tnlGcm&$+piByX5Mv~W5YjE~TI?2rjA$}`xacIhy7rcE z+JW_m%0mJBJ1MNq4pa<%OXR06-%<~mJr=K zK21HY5|zSMiGa*w;h75+qWnIAX3Ca46P}mSWRFSX!Cq+&G-${)99AqYzq<_BO=QL( zO$5*icdOwH5o8S{4a*CSOf3XusWlGIo(xb1<}`GL6hPsDUbpBl+`=$q2z!Me37<47 zVS1GL^N0t|=&fEB+3CAp1_g)wp-%jtKmS|wC;rlZNH^ZBaa(#%MEmy-`ZwjDr9b-9 zA51UC#db1czG$yn2Q~0n5r}zTK5O*%|J0AEe<7*}jp@Vx_7#2h=e~;1vAHO`c$7dv>0+>0(azI&9`?9k{U;S7A z7|CrRw-9ZA?HBa?U;G_HyCD?KjHZ{R(q77K+l)kXBJqyizkg5Kv)t#o--G_`d!OoH zL_#EtMEv)E{?F0puODl%nd!Ga|APMGfAL>VZ5L#&O;jB!9Eb<7pE&1avi`fj_%m^l$%5zd7X1qY>%;;$%GMf(2PH>F9EbGU+G&>%a1s=#PH+CG88{ zdu@&WjX&|P&^;7zEw`SBzLK$>oTbI(WTKzhu?PFE1maHj*S_74zJUDy@b~@>{pK%! z0dmc``xpN3AEB>WOGE-wPZGU}NC4K*h#(#8fU(4g=uiFb|4aYw&%Rp9eG{QS{=*;B z@3f5+l=nC_8ruo`G3QZCl?lv7AQsm|qS1fw*ZwN~TYvulqP;b;>A3x&zP;b+um3Oq zE7AAAZ$zV9Ve7t+IwZ3?GTNZSbQJ*ay9MKxTn@7)WQ-i9;zKb;H&MCre>=1=>S{Rs5Hi26b3UIrpKSnN;vrSb1 zB^8xB6=VkKcyBPmXmB!|#rbd)gW)K#ZS5o2E7Cx6+J>a1SE%@OFE3iN0H-1LEh=^WVe`Z@a&;RF6`>#Ju1mfWl2{?~B zGv~(dvupr5Gys6lEMz7k+Wz*P_V3@8*JsgZM{?#=%5qq>PiVhHL~>(Yu6>r{@89Y8 z;nUpa5uEfp&2j~M#cdjq(9wu@@7@tJTaPl4e~3;;DDGolY>GrrTtw)@{gv9H@%-M? zGyU)vKTqvd;J=@G*jFbX2-dCeAzI8F+658OcV1t+iWjo~V%zA~zWzGYr|-vm-)4%? zk>_BUvAUhxDABKe{7AHrn}}%JcY4`(y5C&SV{dX*Ml<+hMHBFhcK+drslJ@sr!(#J zYGmS-Uhnt*Qnm>Fc<9z`A@|qJ^c@lU2iyq1LjSD=o$5KZZd*N%R^C<*Lcg(}%l&(; z(f5v>{x;}H)jqw`bOy94pY3Wq7KdFJZQDr$23EY&n7;pupA!+$b{tfN`#=7N==pbk zo82ZX5_)4&?LJ*5BSIMRGF0^2xq}g zn8P}{da7-gC$@>-@9-#zDcd!yJkYSikC0eYbk&1$8 zU|^{5ltVF0E%`>7w$>=2JX~k6@;O`!Bm_za70IV?K|CB4#3BPg2Hhy5XtL3JtnpMN zB7@maZHS-rTvl8HJi`8BVFd0R_F2zOJwOo{`?GXeT!uk27b zW&_U``}x^Rd;Rr6yk~uTFgzl|**Q*Anj|f8JheTDVy*JOf1{TwH02{ZjH0P*t?iRt-d*VhtP50je@$)jG^ZS!ZhTX<$o zA{?x9vJpxmtbH+qZSqATP(O@JjNj}1PWRVW)0yK!@}Js@VMt&uGW&+m?L=D2l5*Xu zqUh#YA%D^uS?8#h(GXtScpw;)PfhvM%h<*e7S1HXMu4R-}{~#p&@_#0=cca zb?;00ieVOg#^W-uX=Gvs;yUV~xFU-eI^|erm5|5zKnQN{fo4|6QLTt}cHcjoa5ef} z$rDjvdLE~x;HZRxd5FbEv=r}z`YzanK%7~ii9qzNjPzN*whdS-RuUO0#_WbAbql-(>7?xT@`YvcIB zK0u12fe~avbCQ)l1{_NsCf+Xkr%r8% zBN;diFY3^^o1z^ZyUE->62M%ZNjK!eWB*~6gFf4eb3!8iqV@bjFUI*;=p$PTmYxM(Pqn%qP-&I`{Bw{wGeogHFkpen`HeZia zT!r9i)OR-rdEAKbqoyJ=PK@|TWsGvPrq9+32@vE(pJ%4WYy$cH9_PjFiw==T)BF@$ z@<^OjSm|LToCs`Zm16=N!w%Q_7Dfc%e)Wz3Ry8&F4-eq>fe@SbV}*HBMQ@GAOV}{~ ziXn$Z-~r>2$uKeL0))qL^p7U#$8e6FcxP(6P}{doB94O^ELj+O%t;%LH--)z%B;gK z01;H;=`meFM`CqY8rq!M?qe088sgRGR+={f(Fh>wItRdBINz>_Y|C%<<-$g8AX6OT z1H}t(Ge>X|Nkj!!F35z$yC%5A^S!4bw41&YroDw;CU+cC7wkG29wb70lhhz<6pQ+u z>vA>4tpfUIt7Hj@Y?pF79-iY7)#tPhc6_>DQJ}7;Io+{Nf4<|o$Q8-!J}iw(Y#kGJ z8-gkFX%QHm_U0`KMIsXGTDlHs9+S^7yMd#DYEm0I=g>wa76<+aWJMAIdQWs+PnOsl zK=8xB!QxGYQ3#gp*+bD^*w#l-L?#m&LPrN_d7`bPP}dKa$rW&&C0rcwY$sITkJxFq z7vC09`5y&aLPYyrXqO#2YP{XNt;H8M3G+Y@r}`beY`UI~Pb5E%gJi4{89OAT5M`mD zEu<%HD{P9A( zxpJ@>nR#?#mW6o$v~eHV@CTW3(-DasUKY|3iFOF_!PJh{Kdu4=ABJtj)2~4HR3Ns) z({9|4g=Ce9m7Rb~Oh=&R#U9ba%Hd&(Q+ci~6v2DvIW|Cn5h9B95eyN6MgZd8J4B=; z!tz=Y2qKmR43m84I5y-!P)@6Y9=ZuWyh_W4`iVf!c&8m*SSB5f>+ARXhrslFAQY9< z>#WSOq&yVDyuo>D%(YYK*>>T=h+QQ!w1Wq-^o_tc5!Ruv*`JLuPLr{F3SfY}v^9zF z5w`IBCwQOOt4*%g1|-0i4QJd4kJ$hN=Cv*)$ls9HK-Zh}M1`kN&u8IHz&Xc#a!z~S zzLENT0@|pj9eCSV-Sdsf#7HR?d;!PVye|=KRZiDqiK}<*^#=+ukKyB27c%erK|8@T zs>3^JN=#nn<}?X^!W2Q`HFHDjG^cn6xgr`RT=aCG>fI;mW0+o>es7Fv0z82jG3~7ODdM>`*Ww{|DR;yO(9{S$#$H81;d|X zYqzUUR3OAeX=NVr&ftp-KVaj%ZOB7WYPfY-y|TG2=2_tum4f{RY{P`z%-M39IA4=? zqU{ipW21I7+GOj75POKg@zNj@+8RxX5%kx^a(Wu7!3=Y+M4pzL3%k~06=6jqt>rjH zKx^M>l5mu&3Y-8|?A1#SD&(VzuPY(4SdSYWh7U8RmQu=?+(WoM6D*%flb!k+n)=-U zjK$@&5ed=rD%ArPX&6fUnlQ7I2}@S+{wP~M4n+n>A%8_?wQOuU&jSHRBoOFW*=sNB zWX;nK$HO<-8RL}pgLZNqI8eTSVmkK%<|^H2Lv2r05U8bhxfN zk3DU14AoF@uOkxsF}_+oeXpPr^{VXpQp0y5C+12d5<&4N&W|ti81%sHSZJ?TN-oqF zA>dZXaQ*Bd7Ly+E&)vH!vFvv07*naRJPYq5)siY&f_1-3S@#+n^E|x5Lk!S*gLb~Wg%V1 zn)ZHuJ7|!Iu~vVUq5A3dM|1Z;P}A-cf@DU2CFp|t0>Qy1z*AJ`!=wm7vRT0E86c*J zFdA@(Q+&aCz+6-VCOv`ZFs_iLOqZP`CK=hUS77RKGNEV40pmiJM*T~{zw!J7(p8!4 zT^>2;m3E>=@P0%~I#^q@D+1BwNQOrDWiHd4bG@hi?!GW4MAS0jkh!-sTU4Lwq7m;Joum6?9>@Q)Ng(0S5Ur-G-cX(FqC$%m~Ux#xw-IE4p)^` zi&r1`Nr#Uvq}?iF%j@fuTI@LcHkDZ<0QAO2wz{Y`8si$+a2!Z`&B=}J}#EwJ3 zBVH7Xx8H(_2q1VVdjb5@%|=$3%J)fTQzllnN}2+GV&9!Wbc}_Fi2m^V-yjj98*e1i z=-^Hun24G%{f*n-rGIY!Lwz)&buytpmG99P=R#hjD!)YDK+s&0{MDWKE=0S`x=KW^ zf9Q$c|MjmamtIeA^?ijZrVH~C9x1$d5!zRKujcz4_x%q((aT@{#UyWbC{cvf$HPWB z8gcMnza&w2fJ{u;A)@v>A4xvni1t~A(ng9z`V)6`Ak`SqKwO zp)RG-HzNA0zw)c}PyO_#^vlLmwS4#ENBTQsRjA*;@K#jT!(aZj@6&Jo&hLcPnKZoY zJN@qSi=SAv!AH=-Nl@E8Pq8Sx#5nv5KlpX}cmCGjqp+e&Ja8Ci zx>L&LKE=j}wG$-0BhkqOe)KG+&CK*?-+iF}{2%<3enR!~%TFTodm^;ocN_H(_#&+3kt`_4`NqdpU)1_$wmxyV6(Qi{NPnaMwU$ z)_^GkM4^qx&H?}Zg&+Tz{1 z`|cuQAqTRsZ^fa$j`X_?Lsm^AnekjxXW_9T8#r%OE|HIv5#O|SyfL#mKyTgSS$kMwswtZ7@yIraZf}-hz{C1kRze+^*l2wahjDj)G3qaC+Y$!0BpaNr<4Br&$vew zhN-{g3>tv|LJgwP0aU0FBkG=~JUf|qou(J8t32!I%4+>87bgN*a8n6z)guJ8fu(|! zK(X6|KxGGoaE~;2(|;d{h|`&(px=A?f`0O^{_k`g2YvO`m-OYAU(r`z_1~9YeMMh= z`6Yez^RMX3_T_ltI=&hnFqd`YdGf}y!x{op_SyD_yq1Z?}D>o}z;i=E0RpO3^L9ut(Y%Tp)w#eeqO zDUa}+0(c@)Ho@dxD!f-?HZ=hbqVU5q6H6ljL6qMW-kqBW{U?9?pHH0tF|gIwx8Rwl zP(ZB*lljyC%papa{ZId~xjno!6lmd5@*m&fN|j!emk7~+^H2N{`fvZqKQf(9cV;0^ z;;m#&{#c@ZeF zhs>c}(CB&htU9>VH2-J0(f{=H-B8Ge5!z^LLd1upyou#s0oq#FMcb*4a^uzZt!;he z@2`CS2lVg%dw-IC@asRIAOGk_^rIjBh<^B^AJLC~_(S^9kA6hI_{A^im%sOWL_hh7 z#g)qfM^?)wf`d-0+n(YN=Mel?L;z-iSiDU5%@XUsPTOx1%D&f& zc+KA!6hfJ6U2$77I-3a#&F!x?NyLf-kO+$Klf&{+DYlnCN*2wHhCUkC> z_m)H>w;y|W*}6A!rk#&YB>14CjZukmq8>QC-1xIS{#54!QBL26A_K0W{TXNu1T zsFh^vzJT0i@k&;_Bq!qw)>TI0^}MxF2?4B8F}-9#uNtl=?>eR=6$Cd>h_dHj20Z;# zai2-0`N%c$ZIcNt=WiCvH|;h2HX^~PO>3>K%kJ@H&#c>QZER{~`cN7YiGAN~ghCFV zx@p8xFn$0>!EQQO)Vi7y9l@~~r zSLQ@GLT>nCUqwSb_S8uz$!mXo-^MhfLnE*;g%g%+EU;w79HJUHn^$=pM8{YbRu0;E zr=52?c&Aivkb>t$PK z3g4oLeB$kZLoq@p5RKZ_mlEE#W-swSJ>6&NyX@Nu#FCGyARviDDd zew{@ygNqd76#x3(B6b6I(T99v5`nT@=rXq7OWmm=c#ACal{dwUJ+owx5p4fv5GwKB*a23@i^rKbYVZ}K=C-#U zMbE;;-Fp572K2=+sp}%Gx!pwl5A8hr5YTmE>fZ!0^zQfDw@=bOH6q%iZyWXRi164p z>7Ag^VFj$*%Nu1HGI$(Bw2ino&<)a2BPKe=8E({$Ml6k*Y{b(1W$OqUhwxZ%G#6Yh zOnpvhHgZ0{l4w5;BI)l(1Tw*Qy3=O%iiD^gL?ld28i{zetWwIxo|GBnT?Vbl05~mU zb$mte;lSQV>;5)C^eoL3VVJJM`Hc|O%ZNIw;eJ}2v824nrW~&6*M<0RaAKGDYIV=2ru~yd!u=8) z_~ZIrou8%yO=*MsSTvBy8I{pV*jnwIQE#0rY>l?9?<;w@-JSxGAfiAdM8v*G?7htS z17nip0Qo_Oa@kyW)@$AuEk75{0)U@Z0oL=%8K1;+)_YjSl^c{KJ5|I{Pvpc%^1j7z zEss7uAvWFSeIz_Xx?#^kr=4wQeaWL*28gmB9}x$#0@u;@t?J=T_Q`;_?x%>rq#Bt> zN{j&8MmXLs2@zn5-Y1z11OoV~x-cF+9bDx#p)fxKzQ*#T&)Y}~(^5@G$Q}r78=YD32 zZ|LVpaB}E@JTMRn1N%rObbpY{7WHK*leRM;5%&DX#Jf(#0uo^laQ|!rH)^6}qWOq~ zxg_ztnF3a53kx%Pf>7x8vpJhYd>q8W{blPh3UTK<-RMR;-G|t$jD$$q=rJrvL}=ed z=~ZZF2}tm<3i_>;Mn(j2PP)cTX$Utg-uFI?kjL?8tUhOEvaK$78i{k+6tWUzgZt%w^gLTZ9$O0E6ifr43>_L1wt zan3bRe?&IZlevFe3KdA5z{T|w3_w`60B90<=)W`_GF5_1J28#$B#sss@nNrvOr8do z!PT`Mfd_GV6UML6GR$bt_NB5nmC+806U5HXP0bBD2wl!tXBpEX{#}L&CjchLd&IUg zk)S~&WQ;!82!as_>7(Dw{*F*46r2=-Jzj21v=OoWTsRh{{!S52WMXQvQ4=K-TYuTQ zHgd@!6ZG;08!h3UQQE<1^`$k(2V#b?%t_25 zAE>lo9PHGT_l2W;1KRK@1h5i8DUgc8)3cRqj{v9Yd{;*9Fa2_9hU2}LAvRhb`yt;% z_CmN27?EX=uxk!1$uxZ2GAiqdnv41EAsL(XHJ7df0|v)C=V3|)0H5iL8EuX?F5~#- zgkgDY^7=gpm8Y-MO2^(TA14!MJ-uho%{HUR`$=V0z33hhb&sG%97ZL!?M6>eH@e;W z@9C+JNGLE+J9)p~jY#O|L^ZYPLd=!)*LR3!|yk-W~o`kG0|Y;A0Q_O)p!+y_!A}iAWkE zp@?Kd4OB0;K3BYh`>ZW*vP29!h0WIf6d7&HUc@yb;~!*=pq1+QN)d{)mMMwHx;xcT z^lwNgs`@-FBk!`dUw&s#L-&Q=j<7hh@2Omtk_an9&tP2_@N}GgfhqZYUMI1BOpl0Q z{TYF{Er)R*lJRM7kfT8Sa-~Vgm!}5hI^>$mdC`UfvWq1ar;H_$R30rqJMLv7BvcX! z7MspQjg3ffYd#{;JTIQpo~9BNVzMbxtmH&V#HQs6`q$}$lUeE0o0L#Y>%Ix0I!M~a zQ^v^90GXo|3WVYiI;6iNK}TPk{TP2c-)X0fcG~FPS6ny#qh)?bqt@w6sIb|P7oloN z3&8SCNCYN>pgIZ)>RS++6@dEGQ44Q_V%~p6Cf)>0Dv&+mUyV%YgX~Yh{Y6peatzcK%ots=k-&s2mLH^@@XYpq(jhl z9v~AdVD@ku!35uMUGkCC_Yo1XjYjy0gc69Srzabk=pz#II}##d=c`eON%BA+N`I;PSwKzzb_U-jPEOj4!ND>7-< zxfU+uF-5VOA~Q|v@e6Sa_bd2rFm0u^W+c&J#lq*vY|b)?&;u<#qW5{ zD{>+cF2?f~ve1*f09kl`$XLlcTZuqFP zv^_D!7p%_&B5yyi8M4mD?))3Iw$W`&WqP`G67l@}Y$Fo=9f=-?j!5WqCnXU0o`fv) z^wEG|zs$CQgOKx8Y~kK6mt3Z?NI6HFrk~F($iw`s0_50Bt|RYSZYojO6aQj7Q<~NpRPQK9-92}10koMu1(2FxSu96++l?8g;( zz+;OO<>7eF@{_*Y-no$Y5tE&>x@96!;$ZJc$apzgh{j9SEf7wv*FwLvXd3)rT2tFJ z7j4?=Pv4PfhmJ@T;MWUkl>N9q0SF`%5(^qfA~KnvgNS$TqY>0sY`Tx}h(5Wg3(A8~ z9NZg({&^*_>xh=o(uy%O05VWLjT{u^Fjc}TEhxv(v)WHsW6Sbh^}s$PS2}NXm}Kq7 zgx-WkJytIE@QfOF4&{r@y zvychJdAJ%~cng6jdqrvSF}N$eeL&y%BAzP}aoGz#k>165jf-Jl&#&T6KD4E2O}E<< z-JX0zLPsU45ec2zG%x9yr#6WT6q{aYOB`I!Wrgp;2$1m)1#S0__H;c(CZN4!VW8uFfu_|MQeE}0r_BS zP@hxTwsdYa5~0Tyzu{31<%wAnFxYwagOUuJ<^<=c35gL03WP$o)zl`AMax9}+Y1s% zL?4YHdq;w9I3m%BLtibm5p$o8+ov@-p(sCTIXl*(QJ`T+fNJ$94w-fRb0su+En--#vEHpe)ub7RB-VT}(NhTt}Hi zTmr36ls5zRf0RNsB7tE7dIf>1dq|0hBpheJ)9<&v@ePQ65}zT94YQjY0`w*l5sITlq2OXmCP8`&Dr=2>PXxvGL zFgdVec1cI=&W+S9)Z}K=Sn;T0TOEqlz=u~QP^CB*5)=8#52c}pcmSjbeC;=YYCT&3 zi&{9ZTP-)k`YK!Q&0OSdZWzUfoI+#d`3E4qM_kks>@V~7X57F*kKCvs(E&XRzed!* z$zBKN=7Mh<#3Pp>z|uS`gAIta^Nk#8+a) zq(7B_Eivh+HOLayMQco3Ykf-7(~X{l^(_Or&ayP9owqKjWDP-(GeU zIq)2cv&bv9v30v)?xabfnv3UH#_QTkC!3j|Mv&J^w$Mo{547uCDWBSz!SjB`0AlCa z$`(1)1lhl}j+Hr{8=hxOo#*2j8KnrVoTI|)GKg(!Bu6I_eCRS}-0{0eU)f2-raU!n zw9`S2`}ZdLbf?{95pL9y2AuVHEpb84(;4V_(Eo;}0a5nGKn0;lG9b+4JWT-&gv7_s z0yHvg+{D~Jwx>)O47xd(Ro>EmmT%g3t4K&_LM-euXzot)2SR*$Q(-R)jxwq9bhbZw zg@|osG5pfB)~^t#W;m$SDAlpW8#O}jeG~_tfsixM*LC&Wz&}hPG(u1KRNjZe?2cQaVjt zO15iBB2=&?naBZv3*`M%@(|^!%48-JM6tarWt^TlRezN3G_5?^u#^BugpWG-w%e%_ zU#IS0L0|yoHOO7%;k>A1E@CKli&t?8f+)NB4PjzC9xspUhRIad7is9UAtVpE(<%55 z%H;&^@KS8VRxtxAr5@u{z1sX{QWMkAd#2~iH}QD)bKF-b_e?r-K&(^TWROhXvqYsp z`Q~!v>Kxo&l|umP)`6S-(uMP3yl-8pGtxVYi^&%^5YtnI+p4o`vW7B!3*<(RM^raa z0hCOz4p(r(cmVboGm?tI@E8p9HD6EtP$IE$U+VRU#_>1~I;g)|jUbz$8$-Rm1A%bZ)fIvb&bW_EJML zvN)FW(|1rTxkW?B*$KDVb2y*}_n@W+9V4<4p`cbHF8Smpa1my>IT42;WN;8x7vRpU zFa`xO+sfy51#A=IBGZIPB_8lPK_<^vbzZMIV8MCZ3lbr)pYyQ_))*|&Lf|-_wT=9|BRpkB1>?$OK|F zA~6aGWL4dpLB8&fN9ZkU!ed-H-qjZGe*|ozEj}&!97PHKtNl6;l?ZcuRhui$C%ug$ z1an$v0kK&ar4v7QPAG7ylW#koDB2W&5;a@6Ha!ZC=lt5)=)@wkD|Y3Wn5^?l)8fi% z=gd5Mg#rNc-hSwnU##$jBNDnwTQwRH_r3Sn;=c$;G?4UCkaLbJPi>1;s6H*mtNV2u zAZu?-gG`K4V8D?ck>@d1aYk8HBkm0`_`nGp#cjklDgZ(cC_5}aJ2@l*8#IsX#bY9v znkV|f#DR?w>xKXEZHZVeuy0u{oFbvm!`8s$8k|BdVu2stpn0XS%(GyARW{$h1+B<+ zlf>!`*ehKao<$)Pd^MQXv~ASd*4L;N>SSX4TrPiK!k30Uh{>llG4DN@#w1KeAV`E7 z(U3{S9CF6YxTq7EpkXt_<3TVij{yrTz~0mEXPsR5(4(h>kMs15=2OKtf0A4L)R=T{ z{LCt`8Bmi2i~*{?hTQzag_Ckvp98r}mwLS@rn697FB;D{8iB+?9gL6W z_!mD@FR-}WRIw#nF6QR&{Ki`N%Ii#_Q z6MWF8PGb^EX*}H4N4fxV3{>1Udb&N)^YatEj44g;-@m8NKKsnR4dK7OG7}L2!Kewu zaU51gE_())v+Q%voH{`~x7Mc$d{;Vy=O2k<9C^A(CM+vvIO{wbzQ_jSsvIH!i6SK1 zr(hw-+|wu>_Jit!Ah8O$Iz)97(x~dpMu@ zq40RBQ0az)^3_NL!XvB@^}l##kuaRDWgGU#_H{EO3=U5*`N#xMcT8jg>d|U9xPH|j zjej7%K?-K#K;fKy+eFZYb{UOKV1C#;eP(o}yI}vkky90rHk|rDEwU@yG!~#*>>t8Tt@}7T9 zlY?g{b1(n^AOJ~3K~!`xCTOh>fW@G9WxZ$(10XiTud;$Pmer{Av%Jd$=k(1f>5u$J z4CxJ{1!)JH1_9d#p3C>3%u|EQ;361$I0h$Bse(5%JVUXFaLGG4bAo8hy@(zG%QdhN z&mWwt$%GonoR&=Sy@^0f4xU32)%32@eGOO5@{tgdmigSO=QooG9xqyNaaz;6ckk%K zhY$4O!w36n_5J=zudjED|B^t2-ffgMx6XB#fde|q>#!P;z%t6D^^8E|xKzd&3_faS z@^fq1=X22BKpx|=02WGl9xcS;`4ym>AL~TGMx?4FvB-=-kbPT%lH>uns*N!-o%YAm z2qJ^6By9`hJ^*a7A@z4xYv);DQYzjRBKUxqPz&ON8^2LuIE=(zW#2mBk#rzHF^4HUW{)5s8l# zNBa1&%il>u9FfS=oF)R1db$FAU9`&y7y)s-wr1-%=V?>(h{T#qs4UU``px042PAsr z9&N{SB5s%Kc)NcG%ag%u01Icb%{H+vml&56=UjHMrQ-H*o?_+Y?HvaMJ^|umzYot5 zBM_}YJ_1$Wi)9^(C1-!wx^pl-e^fS)&PDaklSzcw+V3h4^OK>ofvK3*_hE?jjfFdt3T=O*N8LJ8eT%?(Eo%-*hh=>&yf|v+m2K;rRk`t` zPgd@lPb{y27vg)4BkyorWk+>KM`>7eMJ@N~;enBcDDIr{FKI8P%vlb^D)~a%JM-q2 zX24ELAcSaiTCiES*xr2kS0T3~0eI@D1X*S3oUBPXKx*rqYd&}I*ji_62la1BG;g#d zM285G9JC)ybTBa;BXu2_7$XuweR(Qkmv$HvE&Nrl?TisPY}7A!9^q!2r_^scpPSkv zMSb=uIac7Kto)khMW50U3wxemLHb(&p2FHxvm9GG(2Pt&5v8?y-6 zs9Wt|wBF*!s`T8Mepb&uHXEP_JLpRF z##nz5$gX;`l94P+jf^V zuG)lOs75k@N#x_HNJd!(dxKaiweKtYh39bkUg%I2Ek`97C<_!~3ZC`@FxK2bMrV$> zP@lX5q>L)$Yc6juE3HwV9WaybbFrbvo}E}Q=RAwuV?w46)On0?i+5BgLYr6UNVpcf zJQkt;620&s5W_~8F^L$1iHh$?m^}d?)f70jo^j@}?Mq-1jXF?ZpwBTA;b*m5vkz)W z>&qnChcuMIAB}XC17#*Ex{g?I(-DiIAksfn!iNyEP-~>$!7c)a%~X((e=9KdQ2{na zNvg>se{*p zsK3~L^vZ(jg@_mV9p#kIBQS4mlFRNHjgVU-eTDuw`qr!(lo1*5*U!YqPsMvVvRi4h zgjhagXkhsG_Vm{X9nw{Xm7VMMGwUmo8KkhFY!KSt%H`9|cKlM416K{f7=G@0j~ z$IU^+)6)}u_Spw||NcF_dwHSf=V$x)91=bUJ-A&vu$e@>HN#L^VQEO8`jQK{8d*3y zuh%Z6NzboI=^N{{Oe^l231N-De#hg1m`TfYJtYr7(HS}{;+_C;>LfVi2wVG2tpTPp znF!ix1wgA&w|#00fgqdw>A3E}pU-2MI{CP=Gqj8|#1B5t>JV(0`ep^c*x?YYAYbJt z)^YB*Sjp$a!Eud(y{TMMA>{WgaDPs-C4d~ua24hbhS(0(Hu&fS4O=n4FSHKXR^_&( zZK#&dp#j6OpI?#*p>#hF*un68w#Q=mdz46+1_n%0lsl3J2JOKzPambTkJD{rU!bOq zh;Br@iS2K0=(Z2Jb|&5%@y*0Ae($I;78Lifcw?=J;6`u4{ z+|mq$iFC@+$c^QZ2n3T@Luf2?Gyv0>ui2DEKWnG-K0sJPwo*Zt3$5T3fuF4igdNU? zF&JSb3)0hXhmZ^s(FC0YPwDA?Y3Q1Q;ZBr#K85HIq9)YjphMb7n~Ja5uZToHmVC98 z0gWq}hiB^fJQ|aZOm)IE@@wTYVn=XijYr9fZj*#o*4dHxQ1m=h-GVVc=pa7Wr~H+m zHxURT%I`)5;E#Hj3e>us{NG2(E$(e26ipPruR`RSQH`|LCN@Zkf!d;dNV2@x4z zs@~J|rNerQ*CP;%a(Xx@Xht2V2}De5O(xFHOJt$4nwD&pfU@m-erBKZ9=g9xg#Pf_*0CKK^~Jhy%>>OdwEQRX5=bbHpu za#?vCee|~`5i47O=|8ehN(fSRZFB;z%UBgv&kKHudZYeT>p>v&czfE+4{f)tFK)Co z$5)L_-SlIrok(o7J#Tb-y^$P5ba4OH+r1f)U?dVpGa|v#w;O)hTH8c4iy823-2t@@ zG?|Z)QKrbYl5*>aMr*|FAZknmBNEojtNYYhjx}tUK5{5=Xig%Cl}sFCIoUq)!7}=X z0k}JRyl!lu66%5>pAt5+hWMfL44&^)FsnWElp2gaH%P;w?++ZuIF2iZPBg+G zg+=O!eMl1>GTd(4H=tT;7b+{1$2e^*3=8EX2|l@@Jd4rR#pJ{;l%)#aiG;pL{rvJw z&(C8YrZK&H_nzLpdq>aD{Y%!W+x;bLU$F_vgve0{l*AL1XC2UyIrsK*kD$L_J0lf7 z?QI72X9S{pKFgP%t>SwtnOLPij>xBJ%w*y$A9dua!}Um!m)j$9s(hYr{22kwBN0Fz zRvO~z_Z=q>WH!0Agb{7$IMX1gkDXh&*8 zQI{;*{Cq3+^VF<5BmNvNE9*VYL{gLs(^;|S`0IkiGC?At8J%rr)~Oh>jmhUL;9U`k z2>w_4HOp2L2_%Sf2M(3*q*Wy0F+wqAtK-=~ESx+Tk-+Dgkl3h%5Z#Dm6C)SflYY0z zM{9_!uR{wsi&{0h*3LIFSJIur+E2cj5H!81GaFlloVoK5dB)7=btr+L`+b zP^3enOwWUk~Q*bCQ)bSOH8pv2I)PKkudm;o&sQSm8E2JF=_ohdt{ zdr2fT1NP%VCi=0>S_^qu7h1=n(O8#qv2dQRXPr8V>(>`8BmA1ZEY~|JaRCc z;nV?y21ZFOBa3fNDv<1MeenQy_+V6wC{WN7+bghmU3y-08Gt!Alkkib>BYd|n%5@> z!36$sq8nLw1g9}Wg&~CmQflW!;(|oH0q%Kp>7mee#YaNChnXxR%sfUPp2rK+@95q8 z_qP8srZYV~J&)}ZZCmd}-1psHw0?bkwbh%HP^?EF^7%!s!Rb!2Q+{2CW4q+WIuqH!nNDRY z=kU)U%;nD@f5aD#F(a|fSFSSpfZ8t$i7go~1S>64dHcwySe)8HFcDfN$g7u+;~I*C z9HVZS#>=(vjDmVEpG+cJx<8A|c3*3awx%Rvv#pX+BoJ$IkcuOofxOP)n~{h*z9<6% z@>!NlB>dj9G*G@-uW_FSDLfku#<=qSTL=YlY>)HSuLm;0G)5$(&oaLW(bkECw7%b- z8*R_6k4ik<=yn^VbAwj}8j-D{x^1*QZL~ez=;`IDe<*rP<(3;!+c#=TAnuzJiM>%f zB8h0S(M@AmTo{(1ALS?=HZP<4@!0&oj|R#%{L2beu>qF|mw~ z)-fA9?lhslC!q>)D6#01`-yZ)&Zq-32A01JUa`VKDM|d93BVKuitL;|+VJJs+ZEv zora1`;B(qD)!TvJtPXqIw*H~Hckk)LXCG`TlfE0#%=tSAAR^lLokWCQUtj6<^&{Qy zuP{2{)0?hBF4JJX7Jl{$2v_CrbvTbkRPmwnJ)0Kr2q?cQ2k!vU&12=(pLG)9U^F4c zMS8W2>(QL5Z94#2%UO*?gb|72Wqdm>WtaY1qa_S40W(|ArF}3hOmVs*6Ezs@sYap| z76VCTd$v#d3CYBva9ypyEMy(z%ICA(F%Gve>vnZoS1HVXsi&X>rZC^$rzE)(Fhs)?YTLbxZP;8QHjx>VQQ1UAJJ|b z-JUnv_oqIyMc-q7W!mmrACb6sLechdd~7x%vCShAqrZLlOdT3T@M+UIMrMvCjwfwR zO146o8c{olk3PJ@Fd|{#Y|{}4eM4dpiK7MJs=oag#)C!roPH7-i@=iD2S55S4iQru zfL>IA6kLbe9I{7M49bupkb#-f2T4gJdR$TQN-{C7i6t%p*axRQNjs-^_M=gjtKKa% z)Lu|LrPuAX0|_;}o@YpR5C{eP8ZXm$|ATb&MM#dBG@-tAr|4|EZThYRmTRgDDC;nt z$)+;RgaTLOIBa^|;a&&IA$8_B0Z7I#INlRr5uVlfQD3WPg~%E1N;@RU2*AqpT1nTq zuG!TFfKHm+NoO*FqYT)VJUQ1LneNNYtY}vh@Atga*)Dd2Q&EE>LIZ>`5jEPj+aMC} z=);H4=!-ADpfA4ofhB zGJ*G9k$}}G#UnDE2GGH(PGekJrv2t&RxP6SN@a71_4Am#GvLTzL*VD-dbWDkarE~k zX1^d7uY*FiwyG{WuP8LVE5S3FK=5Z~7<@^{vzZaI4hHPWgwNYBeU&e+&CClj&rZ~`sMvh(u5 z40CaAa%rb=Uy+FVc}+Xvf-@lQXYAaWsX*c|FT>l@U9~H;X=eoDN@pV(B68A@j>AuU zzx89$QHenwr1`eJG-^*w?WvDS^!FrMBuyhO-a3ico^P}r2i^KgHng{$_U$0PF|~c` zWMUACz8xgu@E5JO@zV88SB51@rf`5R1$=$(`PN4x8c|=4HG(u}0RKsBBtaMZ}2DLLr&Ybs_%fUW0UScHF5%k-1U9Bp%tB8Auc)RN3=TeJ(W<7iHkTjD44$|D>_DFhr=^jD z#Sq-gtw=;ngVb6Q$xzY(ro#2H4f)V9YXgN^%IIRDrC?sICE-~Gz7Mc%TX){WVK*5s!?!kG{Ad5Jo~j~g*_e`oJPbwB zU-S!tS`TG^P}`anH?z;-ogBt|kcxpkR)U5+(hvbHf(IZ59+A49jpLP#hhhK^O{8sD zbfE;zx)UT!)k=?(SSj7mEc9MDmoP>dbOn{IZS-_|vX`nq8zU0m{qA?^d*A!s_~6{v z^!3*t>Ep+b^!3+Y6A>9%$i(6}b_0uKr2 zf1T&G3{2iBHpxV|XuzCqJU6G2_bWTAryd3v2FQHdua9;hK4N0c13WY&ZS7At_yRdx z8foc|X7a#oNhBJ_W6a;GJY(lq257-JmF1S>ogO2%nN^wVH62})5s8rNWgruoJi$x3 zI?971KDw`EI8TN3_ZoDXqx+{8@~sw)iEX4lj7GpObT&+-9?Qndx2mV>HdzDvnM};j zMOnOk;Jvj@WgUqA5A%0zvvA4wS>NAIB=UYmGRm^^Y6by)%S;CNaVk>(T!Ij_!wAHo zL}HwyCnA1g;v3O+gIO5^6JcETp66|&?KtQ-`oyH8_4iVF8!uujnYi7IRBZdL6AB{{ z;~j~<`h(EG;>%duY|tJ(mw9n_nl;y zu{JH!wo8ABdMA>dXgi4HpuXhP(eJU3*B!7g-6b3(w2idd_^v|ZMn`MZj)V4Xqph_* zO{O*4r1v1VHr~ll@Lug|?wi8}~In&5Jr2G_n@GH;mv2O>g==qIt*XObjLv z!2lxWNnmGchf?mw^H?4u4RuKG-@m8teD^zjD$^IA)90UmZtqBZ`0$?Izke5cy*$p* zdwf6-(7w~Y_wDVLS8+OXZZ!d5Efh%eY@7F2;Smy%M^aYtUd6Q<$*}!NsrA7^2957J zixJR)AHaPl4Asa{w392q<>#>+{J#F44Eoox)ay77BU-O_dc8k^{khL8&ZsRIX=kwJ z#9>S|wUOe2NTl~Bh;#d!E2bn9sbM0hv}1@n#Hardn-u`h?5jO9lL@S{vP{fpQD}R4 zpNMSfO`W5DyFHC%q5BGNA3l6GR&#qtFJq-Q{JxCUL2Ld&%iE2fpL{hq)iODbAb&}q zLo>-XaxT{;DFpq|{W2cAZ{66G6zj7~0>QcFYa($KlpJS#rSewy#}uvPqJAg4p6xv1 zHY2hZL5RkOn#pj6e$z|44)yP#!;f^e(nI?4tqC)UkasewjXe7A*pL3ZA9URNG2eyg zPDDEq-HGJRhS6#7vNah?5X(kQs1u1@#;QO>#Ns4^cKz)m!oiI8K_<4e{y7xBP$v=k zHO>7vXdgqdyi+F$yL90Of#_T5)1Zt*@E{VfFTL-H`z-q28$6bPZB3{hoh-EDpkv$m z%0JuINrZThfPL5{YEoUxi_>RBqP|{4oq&DCa#tjxOvA`T1YZQ{WI_?*3l6v-5?wGj zqcQ?m#^(td7v?dMiI7GB&gifqS6C-ZbjW7Y@b3En^tN9A3~ZR9EVi1#cC)D~-GINN z`)haJGRmv9Mz60<9x|CwK&Xu(5DBQ7OeDH2S46@MgjYud3+9B??!}Dzedbu5K$t2> zdIUjgCKRNOI|9W_Bup=08_u~1q@z7qzfFh7euK!n(T22;R#%NtvUDNGw$(b{+SZB0 zcfLd4`ObIfi_gEH&wxlMP*7lm`BM^c9EXtz-THKunn++AaTI~3ecf6cKG~*%D9h=r zr!6}8sH0UnOR(}_2=F413$D4J^j3l6g$sXxUCcGRnpw8L!cEQkIysau} z5YbM!JrRkW_I-3(Jl*L@N4V}g-FGDtWHN>Jsp;EG*2NN~YL_#x>DMWTo8%yYYfjJfpA@CrZH-LvyLby6gPT$ zy3uE!eMax!e;7pKg`S?CY;-%5812w{dU~R#=cm5J^dJ(dBbE2BY~@=*CJ+`!*uQ9p zCp|Tj&noav0Q|v6)bU)|E+na{XD)MWr@d}tUJ1`Ih>lHY`zT~Dfixl6$L}UV?qd|*0de;pl%3>$5Z{^T zPITNi+U`QfU1+;+bli#BU8vm;8@1?L8v8_a@E{VMOdP_UMDWpH&{j~WJz(xyp(AmVPD?QxefrT>zbwp5VC(K(6A4yv2P_x9l)^15?p<9`(z?jlTP^(vSIF8`$6P z17v#R^|UB;o+L5>qiEIWga62FCv$3lNWNmZPa_eoWL_5I*gGcFNToQvX3XA2+sPr{ z$Xie*jm-T)0=PJ}iQK1AYMVsVJD_el{pe;SK}p5upS!JidH0TZg=rAqUM#Z1} zTQ$!w^z!m*avfC24AOJ~3 zK~#~~MHElg^#|9S3{Z@Vd)M=nc?9X;SM5&_`wy+NlR{!03^MYAd5h_ov_+-F9SM@Y8XNCSvbT$rSBXult{-4EJ#e?J1>Y1ZjYH=TB*BNClJFv)$VW9xIVHWu3Wphmm4`9A!z zkxe(k3N{iUeH21_hwt}0$?MUX&MQ;9A9UO|YIhgd)~;0&aq#%M9_$ktndnBxm!UPo zXe;jQv>h95?Vxt-wCx+=Jh>@6=-qd9E1K0+l-^!)K7ebkk4luW22 zv+@{afb&|njc&vEKfgTpQMA#!(6+7j4n4on%e!A1dC)0NI2xf2JvcA{V+cMJL3lp) zkqifhS|`CCB56Pex(WcmgKZDMYkp>W-cdx*A!Z&k00#V+0790* z0?BjuBM?R{Axl;R5@1uZ+TC5RySlnw*Sq&-<~e7_Vi2*``qqlrC-b$vQz!TDh!qhl z*80AP*byWG6K@jB@+`$OON$E=64b)vp0dRjB-9TbA08k2EKOh8(54R`o^1Vy1^^-< zfXZ45)^#CZC`KN<=PbVGj!{Bh4GCc#NcqMj!uRvAa$c1|pWNxs!Vk7%N&}Csyu_dhYC#?5AHS}#WH6@S3v z<0G!uTenFogcsJDY=f7a7{E*>x_WX3fx4Z|6>RT^M*BgK*wbAeP zJRzE5{}xKG7D{Z!PBw{4cdTy59KSI7F4H}QcA)HNJruP->SB7U!OeDl7 zN-`p0-7giWJ5cxDOHc%RsaVS1TKxN*v}Fa#t)OhB4Lj0R@p_qQZ^W*KueX}iTLrEF zZoqO|uy^vXUK>MNZfnZ`U7ov^zBG67pU&n4xbdL^W#hQ6?SqnKQ4+C-k8i?u$B*U0 zk4Nv=fhbvQVwHsOi?!`Nc!vJdxcXm7lEW+1G7JF|b5*qDci)3o;iOy$~C%2%^ z$wbpvz4q|%fNSqD2t!9idnBTsltqU%weIQD>16eyEh+Eh;^Fav%jGHdL|o~(J9;G& zA#Xj4ExCpEo=5PO4k2(Xe(h)r4)m=pB5%q7xZq#g}#O@W@L!%0Q4I7YHR#&;lOy86c_6SH#fC-h9NfazIe zeTug7DBM|khn^7%Cx5s+5Q+X>L>%_kdR6y*@52!yq1fwgM8f6AU}O0_4`<3f58Ob< z@8)o3=Wpj3++IxM$UgBvOA={tVuJL3ltH*@n2B9ZO9Fu0OK)TXFyi30!#}cK*A*YX z`iPGoKiUwdMkLNy^*af*4~wo+%)JqhxZd{u5$!tED@{qzYDe#}K@Y>>{W411?Af`0 zR^T7^`FStivEC_;Fc4oH(EGLGWI|eI%raq3-dL*Q?okkw^tF#`8y|&(ny7UDw+OVWjmp%rpKuJrd zaf#Za_eXCM>q-PU?|(lSs?}>^nC}3PfPos8BL|4wz=LWV1R^Z^DOB(aAv$ z7AUnO3aC;#5eR{WI6YmV^70$py0whX$Ktghh0Y}zK>xq4tBG^DTyVKwyq92DsL5rB zt5!E6v2CXoPw@}m&gU~8`jDyXH4ka(WMcPT38_>78PJLo2+tSFQFUJWu7qH?5rzT) z3TwwqpGW24h{ga(FY^E4=|F-afq2j6c0RV8r&8CsoUe)Qkz)P^Hu;OImm&bpGxL>|hNQgxJb!~diA!tlV!^D}bcq+tYU^KfUq zDIvszblkr`gOR~mr{}ZYj5;wobb!;V?;g~piG12ZtpG^vz7j11=hX5YKL+hX4`^u9 zo_ZzPnj^c9ZLWPniQVm-r^QJNQrrb2ff%PL;U=k)1dum8H$}7t3NLVaRYN6(5 z$54p)z~t8Jhp`KtPl$vPl!9Wj$2k~|t=A|{0v4T}sZaKzvo3vjdcxC(Cm#m+_<+;- zgl%2nYZv)F94we6PWNO1lKHT~~caE+76z-1~ne z5Pm%NNT985y`vF|+9qjPuM1>b8;RHp>b{`X#cYq3N3DX|hcw+TH(Xz@xV~I)du^lw zSG2}^B@nj-g%+eMok*;@?whRG_MN)X3xK_%mV&Yf%C(~CUkC42QMRSE@K=Gffm_h^ z76ttS@+#Q(ire0XH(jsogD_kHxdO|zk%%^=sbaq^jYxD7Ve3lNrOnDD1+^~i3v^vK zf)PSLG-IIMguMbTYwxZxgZWM(!7WSdl+$C`IOg}GqWW=oKN(>EFCpw9F0p@exDoBn zi9*wy;@5GkP3{>%ThsKq4ray+`+_t&#DaqquX+^Hh@DviC-q zlUUMze)rxpM~|4gnO;Otz{Ah-%cDI$ibIEDh&gTlc^nSb7w?%MK+oSuG=eaaiFS>L zJo$Yt(&M!tXnmbPFjS6M<}C{%=#Rt%LmUq1^}U!^YO9AHjZ9oLqYJ&83cv`A#zTJe zO>L5qNFW^p$&RE}cNAD7t4;B$#G+%5$Hxb2aCmxp#KS{tcxXKmC6I}&_eh+2kHq7{ zgH6t`ZQI=LdV)yb$ex7y3DQ+e>cyR7PJbZFDQ>C<5Vmm$as;_^N+kIKX~4RTeqj$L z{(i7+#owi?fV3g`p1c@8*$0c)oabt$y4UM!%ELRumoLq+f(fpS4N$*7dSfVC~aOwO=c% zMZdw2rL80^dLDr$)#+vkq|fc&_p7v7oyyY2j=j63G$_`Q!^WY}a-B<+2zDb719oBa z29*({aae=w`NAE-G<{LhOF^g@*db`sW&x6)Tj6G95yY8-pjZ}FKdfKZP9o?V2L2$i z)?NqQuzAl!?~&*q<=0xVZyV0ygPw{>SsxOL0}?UUm)uj3>)xD9fbxAtBK$oH`;HC5B#a#YEbT|SZ9NjD_y^O& zni31nXK#SmI(ZOj>&sj(H*5G(f5Jn~t)XkFsB83FmMvVdX-KfmOjbRigH`}Y^sa(NR&<{7Fn^C(iV>^U19B)@>~qS zO9%6wsUvuFaI1E$Wr>nN&rDk}SK}$5#q9b8J(m(Ij@~BQnE^I$)#M)w`)CWGgp?-u zTs2yQLvjzsY?Oh~7-3$ST3bcZHBV^EraMl1jN>@&<7X(bObQ5?4Ha_;Q>;u&L0GkX z>bZkXv4Nb&QA+VH{yv=UdcERux#IQp6)&%^HpX;a)^4<$bJlQ|rBJI+bJ*LqPUm*l z=@xAU75mV-?Wxc;=cZc#a5I3HF1-mW-_nH?)r>%}`xSbDjky|fep$g*1PpO|3m7}l zQzzp2kcmVN&mA1qU3MH@NQQ$EL}+Uu69xVGyzu-nB`;E_Q#mrIZa^z8a5%Qi#XXn$ zF@R5?A-dyv-p(2u-XIvBHwD4=+zJ1^B*MZ!Jo|@4COq~4qT1mo&@qu1W#VTufEz&# z_X?CWv}i#oKwiB%5{liXR9AcCQ?UDYIp!q~dL$yDK)1u*gYaG=q5J8yut8r&o8b4~ zM#_kTs8w*i-XH?pZaXfQ z3!b-UyuQ5R^OrC9{P{D!{q|dY`t%uJzI?&+^9x>HUU9j+TH{#69>tR*2>NXR*oXq# zZUwds)G@CYgjr$(h==d?mdN^~4mhdKcp=)e5JyN$lKY~-Wwrdph6>G?N@KorhUCu z?AO*yQ7?kB3$WKtCZtbzv;eh@6e>2Xsr7tpWmy~;7KCZ27(k#iztUM>Ywhp1EVGC} zP!@8FOy~-;XW0cRK`0PmL*j&@aOLj>T~M0rR-$GFf;?LIHGtv!n=6tlM7TK(CNgeU z+*DZ)-sBs>F_O&y8Omd~{f_O(>9Y)Msd~P+t}qQfFmbSy(Q1o?Jr zC9x0uYXkXLBNG?AzFq?OYetz`e&8*~N+hBI_Md+AXusPY&-Fv?kcX4x9ayusxWF+f zx&Pu@_wThft6=k%^zr?p<2U2d_{fOsb$u_Bh#b~o>*4gh2(EPg_Bol@{3C4p#d9Vz z9=`WT?E5;E?=3)koL^+&LKyGY1({W@QJS&kcN$g<<9&@B?;{Tx4&Du~%$}M61G+bh zEoXZMrhFQEn&z`_MdFYaKf|0zFrf%*H;IIJY!OWIkqq=Bz@L?8?5Th2c-A8k)5rk* zevbq<60%?5Fml=G^SK;CqsUBduw4AYSmu#P066e*Oxp4yb4DCdAhqIlZ6DHKE=nkY zmzP(3`SJx{zI?&A-+sd9&!6%6%QK#zU-0_+ir3eRHCTzrG+jdfB7n!ixjxH4o{$cw z*<1h<1qv7OJcIr5JjM~R!^Fo3J)1CPCM&gr<(QtMw9Wi&O#3Jg6QZ{^rwxn)^$!TE zLWDniu74ka9l+K}MDLX-6_8DUzL4Cei_DpgXz3G$Z56(BgMJTv?PTJz_Z|rWZl(2r z>@^UHvKJJgo(Wm7t?TN}y0ae9ufcV%OLP|i>BBHU8S%`p_hatnVQbTIlv{XAY{+%yp)llAV@rNGCk0 zU1X@Qv5_If!F?7}67f!gWHqHkSz@FfQzkHcFTWCxg<6>?yxV{O zY%FOv-QFG6cf3CXNZ}m<_D2B8!uk$`Vu(xQ;C+_!jj#vu5InxOdS()#<Z?jM0NGqLo}?0vDP^XcJp^z=#nIN<0!CfCPi7b>=KOYf zj>4Hp@%HuEr0e%WOvZRrx8%r=>cS-2Qs(uN=Zj}>!8XIsk@PJNIReI&t>f?}o!M(n zBs@K_v4%;*ac_YGdrw=;h@&0~4%_dK;oH7vsQCqY-aJj2>3lxc=O@lz?^$q>L}VG0 zi5NCd^NdL3-XG1EhF1!TEy!zSt368n`<9oN7kqhs#+NV8`26V;K7IOxPoF>I)2C1P z{OL1ZUti5%vG>b)7no`xp526B;WT=I~&u*dFThhy|V=Bc~QfwjUHq;4DE^Y$ZE3hwZLF!xS%P$DZUK^R{YgE+Q7o<~% zr`e(N(>4YKU-+UghS9)yUwU^&AOc|s7rdomY4;W-4r`l2YF(8;tXK-oQ(JrijHN8T zhC~qDcLUHUrHkap0T|y?05fc^GMx`ta^KvF$E8EDEPTo~C3E41-JC`EJ|PZo9}ogP zEJ=>+q~n7CrAF&96d)0DmUTK#%d`>D zlc;4qQgv{~Qx9Yvyc3+h5y0?Ke5|tu zpF&w3hfSeS-e(~rL5tT~SVz4BO;%n{WZx^+btDq=me`!{_j?OCZ)UdrUi})0gvaM$ zrak)#t$#gowmVE#r~YPo<-SePhR>o{#N_34#CJrF%00ish@#N_65iWywaxf(cz%Ay^Yb&leEEXUU%ueW=P%Yvak*Tq$D30>(^)691mr{G41w{f z-dad0T=A=_do_Z7dyc~nB*Md{&|0=*4NNrZhbyaDA3lyh+s!G61MZP|nZ6Gw+eRSDlL zw?&{U(ARI1TH5y#wX~s5Rg6qX6>RIac_tPo5!y2$OPdC^eGT2g+Tu<)^hOkPgiRHx zOpIAU3rojXDVe~E6^%r!N+imHA}dxS6boQ0TbDxz6aC0&jNU~6G)du@{{sU`KHS9O zjix?6aTsJ74vwQ`gZIyqC=c-ZY3>l}KFi z`g+03%L}$`!|&{WfdAn4{%bsxZ5q^CR{V#5;xFP~{rJxyfDUU#fLBmiA*(ZgYhjW; zowB&l?+n7RtXT1Hoc?+I>)Ss&hI<_Gc&&``&br2rh(rq_ z0)l^M|IY#F>Y6d|RTliq>tDdXyZ$RJjxLv({LozWw%H!Y1mB}HMgSLoI<)Pd`?voh z)|Y31R$Vs`zpnWCzwj^OxBsL6c$#LGr~N8K7VLW^B9SHhZfP5VYuo?Rf9c=C`44{z zStq)(Ecp4a|2qD!|KvaQP(l_*LJ{MRJrZw&x4XB)`vt(S|NDO#AAj^C$TrqZDGQ!| z?bq;||LtFUE6_u5C}d!RW1s5qEL?up!OWlkD}Mz)_|4x$J)NfVTz>Hv@wfi^e{bdS z7N~EH8?{d!5r;V`h|J{SsCRHA${x>O_%Htp{K{|q#+HXf9^o5U;j7%62AWM0WU8vc<#jF<>du0 z&o6xj!ZvJ{3)f~m?Mo=gjy~K8)+^D71p3gX(w?D3p;4VopbEBST`lPXbmHJkaM!iX zbW|7g6fhxR5|JmeES{(ItPzRQ$88FIw1GaXskFshbjZ_ES0fQRw5gGZdDrLE-LkU` ziu%5-pndf|Cl=prE6pPfGEPawu|OQ)aXjw~VrH<*QJ!X^Qq%$J?Uuv($x2S!UGh*y zIVhszbdaNH#=AO^xV&O}X+u(eul^LTa>1)yreXbX`$hcS>+j%S(;g)4|s(4?@wQefaSeJ zLXSUvdQJiQ;SZNTiT@jaACHd@5U!R?q=G}hSfTI4pKc7gazrH7b;ZLU{Nyl>+b{nz zzW=}eFW9!#M4ZK|Jr`|0?}}y7Jj?R?xz{5LWtz4OM0Ef3yT5}HS}jTL@BaXQ@;811 zr_(vcE;2pN@n$eO5{mrp4Af`K)3y)4^;=lKe3{B!A0P4k|Km4tKA)%e=d$J)QXST7 zNuMSrDQr34zxsQB59{+Y*5{<>eLMa9=Xk0W`-cxnzOh`{uFQrt>D0ox%q>~T+UDK@ z2Dv}@(T}jcykLEKnalm{w|IJa!OQo*e<*L>j_QEMng4U0w5#E`ze;NL)sOx^ESFa- zm)EHb`1#Lq{^lE8|Ku-*aB>fj%ErCeV}ydRaNPjhyU(%Y#IkiCAo%ci{|?sISFEpd zx$DCNmLL5HzxT_3s(%ylYTrh@zP{piy~W;cl4Hmw^}XCOKiR8{u1mQFOODFSZ|><( zu+JogUo?w8I>8iMJWzAVat0zq;W)?-7Ihl<%oUEQrL<@oxG`Z2B5i~inM~vb=n5aB zV{Q2LRnP}X1QJp7!|PkY?Y49xQBikVpGYN;5*4KnZ88#JWCEQ)h!cn%Ky7>3i}hsa z2jAPeZXR||P+1n#rJ^o^rSFT5&+5aPW@9^nP9_x3L5T*Dj?%{x_8y6{tZmp5{I@PE zk%zulBGJbjE}{kjWO#ZU6Q{_G*&K;he){h(>dwi7?F)TOd89u>V8`A`M9hG4xPzk4 zBAXD3;j!8EOa|d*HBC7pt^2Os=+G2{qTg-q!s!enaHi^ zZ4b4`9T))o6#U%g2r-Uhp|XVI>8U^0>s8~_KzQN zKA%w^yaj!f&Chv-^VlP?8;E?fj#HRUCL+MatjCJB*I)W2oK73|t}FM3I=xqxcH|@? zUkf@l!E^74_xaEMs;%k3@#kKdu}7k`MzF!`O9;cBW`Z=3S582=Yb$m8-KUTE=9{14 z>m9gWFSuN;xL*5uNSCXxaxUqE`V@}PKX)hbIHoTVi%AMNZ9|w6!M(SWB;t_wgV3|< zVnNO0;2q|;ZGo_ zeF2OWrPjVkUHjO=%e8nRch&<#J@Dix%bp-ziw1KRYK8_rZQU zROduF6qxX=!hIKc>8wPVIDSB|@9lWKF1W0(Z5UpcZLby2cm{qj2xD8VZSlmHS8Aop zhGa%m`8ucffZS;sq=ORHRgjMAw%6;i&^`Vtg6sAEbMMyIWOUz4BnqeZ9Y8~BYrME# zuTw^FrJ0M?~Ym5zmIo(A^Nh$S?ju0BGE9w_BI%Yj@LqlKy8NyKj>bnofW_m0BT_B%e;H{a9XaJjS@@ACWKeVY)8;J^wW z;xJ7jHZjK0CL(Qujpt^=N8%8NTWf=t16INaA&*%1sb?ywaY<=%SWV|Yp|hOL0?@L?9r-IEa(gffcH zjQDJJI=h%W*s*W{6i#EChhn6m%WcHM?X`ubcz+^e5kSOCMX%|J<&n0KTNI@~Ok^Sm zm(EM+JL#)06#w3pI|S_61)CaX4a-Qx(hbJssM#qJUQ1?upCYr&iF$%E*Z; z$d#O_M;key;np2TlI~4yOczz+ffI>)5|(^AL*{g++<&&jJ5w?do}E|(7oYO~Nd7~4 zU6%3Dk-+G2DWyAKH`rDBN{)RR*iYrlT_SPYZ@6AA`1FaJ(dQ(Bw+#Fbax9*j0VV@a z`NrFGoew|Itu3^7!I`rr z!APz^9X(*gvzT!#efriF%eu7Q&sC>zU9rky_Tt_q(!PUvd3kvkahL;s6?l61X8ig1 zJ+0JQcCW9O5ML_&VH*j=d~9}%>HgM+i_#l+^2W-plYzBp7tP+#k3tgj<+IWc_T}>%Lw* zLwi8?<4{0sVl$6n0b0*T>llcru%Mtvjuk*65&}Uj0$D0* z>C;;(iCFrWt5b#CR{I!ZsilE^S%}4VCF8HbZx!{nquzGN6~GOtTctl&1xs&vv00n? zaj7d7=_Eqj2t?;LBNBo(8>f#MbA^9KL>Av}X@aX3>@LVlcyVi|h{N z;8`;9p(@SfowcgXKtVRf2N6%VnVfGCiGAPOY)ZWaZ|}zVdcETGdcpJR&Skdkw;iwh zD}G*oo)Sfdk;`Y2565O|l4sP^5?bPu?tH=LyK>ik#|_uuJUy_xuWE$68?H&JPYkMf zn|A%rzlk)tce&xymrq0vCa_kH>){cR(Bq=}ZY0|bOui<>x^39jie;^BSddgK_5N@b zO}i3_quF%$Stem{3BkK`Xz$PB59t>=ey7|yuBoXp5Sq(%qUAGkGYfTQ-rgi{?cSF! zU#2AL{aY%RflPQ@v1-rBp$HE(Io>{f`h;5sfS7~6dnBR`bK}o@31WF+cvkQ>k*Fg0 z_S0v4dH6PqjnOZ>pGeG(GjEujSZ3XBZvpa(&!0Zw=Ra4ug>XU~#;A=89tG=GPDLaT zGu$yB+SCHO-R}1m*IIGCT<}^p`>>vev>gs>BP`o)&HRkZG!ln#G87Nj^>nId5IEgX zK}aCRpA#&?&&;c`f^L|K^$sL&V7Dg))`<09b$sK2!V%}R4J0C1bQcyN(g4SAyfQM8 zg(-$hUh3AN~9Oxmt_Ig1va0HXnHsdSi~9+_66JX^RpKuqeQPX z>DL%z7F0pW6z zUhwrFea!+7hlc`b^!XSr8J2i)VT>Lel0qCV{F= z=sMnrM4#4oS#Ua?a6X@KI-PMkotlnxJ!$Ji+$Rx0Up;i+@y#Fo5roFHXP{Z-m|!#+ zqs)4Z^P2U8_2g)~2d>*fO%>mK^UY!Wekp^aGSoYY)OCVvuIUKrl!WKKWbXl6>3aE- zpZtW(`8lKT(;@DK5m z^8>Wp^xKF-GLa)qNLSMuNd(~!&Err%*kcKi+-B3zJDN84hD=nI;<)7pW zoaLC*%!tyIm{2kXJ7DjTUDEn2IXt$}B^UW*i+)RN-%sQ~ZpIpK*~nu>3+EA22{?v9 zR(-d`5E8IL$PXq8dM^`*g7$4PcL1zFS*0CsKv{w9ykR??u%1p>*Ufs}^_ymti7aaY z)`GGXlx@LsYCoW~nVD?5*QM{&7HrQpV}sbo*0qQch<({nOKta7!D-!4 z*AwJi+q|{6f^}a|>*kJMgjUU~sMj6)<%a$BhTH26auw98VA&Vk_D&e~1X319#Ik0*&5 zQ}Fi3o&0(>;xS_)NQ`m){PY6+Dd1tBe~@~)T=3=k1wa1rk2%Is-a#mmMURzCFxWbH zUuL~yIUjzt;Gw1uJNs+<<%XC21wa1XukGSMv_N`P(w&3qABT3d78hN4`r+ZherMgE z&qgemNL-&j&|;Ln-L@6wa=|y>d;=Zc!epX~PYIk!My)k~^W(f5do}df-!4O)5dhc6 zN7RYjmuxx%qYa+rl>;%>?M&`u@(zIXEE9^W2(G6S_5%WXx?b`1*T09Chlh}tGt=Ta;`>>T z1Ow!wEs%%_0er1HuG@y&!AIBY<$~Y;{oltoFE8-&?_pceC7fH__r2R2=Xc&L1<%(T zZtIHM!N>W_%L{(`)1Tt^N-GZ$S^&2T8i+&>*V4m;LGKxX&}WwLuGhmd+MX`g%WcQL zuDEPl#3fyi9z<-ShqeyQxNeB1hx2VL+qZpE)V)#PP3m$-#{#i-5VW7J%40p+8Ccbi8(wvGn7$5r{@C z1ly@&oYM(w?{QauSFpf_k?PE=I^ogUNJKdml+%LcyrLALRjm836Np7gMJEuY_LZ%l zU$})B*FZzFc=p^#OuZzt5PLLLOmwFSJ@&AN9*U_+YfUfYnS-Xn2)z2Ww9L%mkW zrLCN|>`g!uc#o@Dx2a*hhoZ;|odC8?|N7mCgejpXd7>b8%R?TTVmOYO62A*JGd`wE zBb<-zu}8;zIJEVSq4%!89E@f`ER;#$EnfsXDwaAv@VnppBmC;`eh)@U=yk#4<0GD)p78kih{vZVJUu?*;qejYb0Za{w66Zk(-Th5 z&$vB24!QY*-}){5!LR-r{%F!8!K>EhYtn(?j1W&h4mQ9I0^>v^N*VTl@Qc5MAAbE~ zy!841dHdc^e~Ql^zrr`)d}APo$BT0rmxH{FLqS-s2zUdrsM2QN`v%{Bes%&uVAy4?Tx z^Jo0*)MtV-{j7m(wDhDLicWo6SBE+qjuS32o)W`OZ5+ua!PCS*UuPwnmK1NtK2frq zmKBq_>Vmz4NKjb~*ARUh`$3Ka;^hyRez;C}eEKbp69tkb4}I$QMTa@*f^0BQzTetP!q=BqeEIeZp1=K!=WjpT z@%8zNda06tC2`} zxc#`yL-slv(@?@SQh-tDDD#ob3Y~#L{e!P^We^<4nxFeAW!kZfI4Hui<^@{7IP4T){ zwI?;Ci3vop9^h!rV>w0r1IZXR1;=^cqqMvVhB#TVeZ%Wy1M~$! zs*4~yGD#1}=Y^y=-m-Id9CLZ>zv@^FBkCH}x$LvTxzM@9XN*h;&=-kj5+N(FKCIZD zR%}lj9=>-Dzw`IcSWXM1uV(lB=^4-8e(9LJ{a!x3;P!IG_2mj&OCKe)+P+l(?4Z=X zo||-H5ql(>@QpmAUndo^3gj%nS+HCdtk(^v{f52n-Xj4tkWc~HE9$Lczt%Ri>81Bb zTv`u>Ep(xaUfhaxq1ZxomDZW)Jrp{$$x1;6?Fd^?r}<$rKyjM^#6(uX1Y*`zIE6$E zenVWTbx>0=HYJ2`4;gsAKFO+JmRO#HAdj{q$24;i_o42%9f8%O7MO($zRv4^@25jr z^juryo3L|u&fqP_@4$nM9FB>^VY=_!3%Yi2y@f$}qBsXwu0-*5g8Z(Jwn*`NQF$vT0IEY;~PmwtaA*eGq_78CA{mh zd)VG1q5Dt-hjtMpLm(A)KRi5CxVc>&k27h?{w&HH%Q|mIc54RY`M$n8`rZU33G5rb zQ<<05hl7;Z$duz>Y-m%iH|jsL+%TJ>voP)Zj@z#Gz-4G3$=>sKF^6~`WH`vPkUvZS zazhS-U<8<-`Pq0q7U5h5)Ek$?=kz{)=QshBshj+8+jO+!Qku^~nY zm}AFy{2n49{OlqVBGE_$7Qu2}u%1?I+uDaV^&W}EKe|TgLs1KSh9>QiIF&XUXm7(D zm%6s$QFX(*Z~pCa-TKI&#b;8L1)I-1-;JscYqFnyaNWSgc3ZLCR-4y&->W+~YPD&O zumAeguWhK)?z1=DU?f6z0JmaO!TOMm-3vTy@4?6KETV~EcW$#GXcsJB z&9E1QYq8SPG0VziBFWCqQuiE2(~I`6o40l>EhG*00De!?HawLqaSM9Xx-uNo6$LGQ zNFsXOtx`>l=8x3bb=_1l!3uLEqh=$;1&uQhD@uBHnD>Z8a0LF29@`MN{xS8sZEdzD z`q+Bu-_rmEwKm(f*S$?2tN?khsIrF^_&B7efo6SvuN9TZ#EeJ;z3aLf>?yV8X9pRG z@B~C0kqB;0Jth$ZL{k}&yUvoz{Fvl5{X=IFgvz5 zm}HgEyX1sgWo_hy7az`eHXe@_U3IMVf*{{H)FYuJLi!LV zJ@*k6tIgchba8Q?q5*2TF2#OjT^gxa3m~O`Zm?o0D+=0vDO=z7(LswZ%dp+9S9sP; zh(!O`x)uSd;CkJ#>Ac4KZjQqoK{m?Wv5I~#ajV#G75jDfmGf?}W9)^7Hq}1es}hPv zDj+?B1_L-znuBdlB!)XPhIi8++}9oy7^4PhKR zvY9Qox4oNCydxPIY)4Ztg3Q7vd{g3Nc3=ZLX+9Z9M3TioOb^8YlLTiugc}h28(Ve) z_vED`OK0vSFtFeD?hN5w{o10jln`(xHY$wU2PP48ObHl?NjAnM7}~73?DRDIY?@d7 z0KXH6)A@|^`P^r1+HkpCQA!D|hT%so?s+(q5eg*`y22;{Z0(`QEnuOAwM4LNc2r^u zzP<|}^uC2K6QSmNv-86iOe^N7k1W?72t-S}?2$-R9S+9Bb_nE?$|SowClYsm)T*z5 zClU$;Bav9hKyW0zM_|H0Otkb~p8bCSVu>^*vu-QWhVM#Xy%KM2T&{*2h(NL|{2#+{ z-lEoG9aaSS|wV<@2Ts@eAMG8DvK^xlS z3gWstGlK5}(-U>0d-shu8~1R0@4doGI1-5hK-igU-u7dQfh+$ziNtX_4NLdu$|Ma3 zK=ClG@6Z3~TV-2}haIWdIHxw84f?ar~Cb!g)#n2tXhanknRL?H#&= z($>0BXLH+czFI8xtnRzd)vi6Rx4jK}vSV#P>3}oL%0#X1Mj#{(_i1tLBj85{9g#$E zk3?&g&i1315nTgco7@{^n9DNTf{dEhozhL$!Z#B%n^o+Q09=E!E=|A!=MN<2S0)hx zdalJVk^v6$m`E_;G4Q1Cn&icGj~3!`rInOO$8Z9W%ox)klIq(G6sZhM{*i#CJ($P@ zg%<#u=1&vUza=QxwiUIu9zSf2)IwL_?f<+Lney54Fc!LNfoN_zplYF+zM7591SRQ| zS-{|TJr70NY?TY?PgQ_c7Sv@SB0)ou7(9ZHlMT}=!LfnT5$jqvvoL!|?}hNW%z9iy zV?c>^Mzcc-P)Hq?0h+ zBD({+S4!)VpyQ%F6j-1Q_U$u+0{&KLK^ro)Ed3h^scsBKnt-B(AbF2)Z!qAkgsCvS zJiG0W*N4I)184VVIX-(Um(cvFqs^+wMjjj}jxC(s;1q;!BmjhW z^QP5W^PnsRQhWHlzGuM0M8W|OC5VX(9kT&1g?c2`&F0x|vpBV`;3c=9lI?A+<}}Vf zd^ntjHHr65L=fn*@V7X+&&Sp>4xlazmfBmR8VdtJd7J@XDq<>}R32q=eAN0l*~s=Y zkqG%zi3myc7IwX+PFaCK2%oMo@XWv(47iU7M2FQL9L{e z&I&DLL<43H4&s(CX*)mkpsrSxu3V?|PVZ!0%M^n@~!lrlbOxQV8_3EtAQKi>1 zo_RUM^v@z6E9Kk0D1%AVa=BxWhdaku>N~_v4^NG!S8#TO_tnN+g2%wEac@fH?-vm# z=vr>7KBhVps#e2^mCW6=0oaofGa^!`bzfpQBArA8J#Ozhxc3h^gY%v_2$RdhVVSiD zV%s*Xo3AUfESXR!0V+LN+$yUdOpn8v92`{x&a4mF$>g4v-1{OT=!^ji8hBgK7O4_h zEdDH`4S(WmiD1k?Tn4;;IJq_@5@JL`W(0zWgaHq@?-=8a@iQ6lW4f+>ho1592;`8P z;l0%x0p*RP@Uw7qo~xz1M)G?tyrB-?F$QYiB>|?G4)+xWpq>X`&3)LQRqzBY33vy|iR!x9*`R$$8G*c)+7Bur<`7Ds&(p>)tA-K5)nEv+%1 znFJ8&vbv=`VHC*p-Pzt>a&XV?d8{yre)U%X03ZNKL_t&|@zI3(x#BT?HmZf@F{jq! zdK<1CrI#ae9pa|D5LZFcG}epa_{ria2)aYQne!s_wCVd~Ym(bZ>Fs*Qx?AXn__I2s z7+>voCl6KnP{1nKm?SjkRl$ryOv-ew&lq7KfWoN>DU7LeC8usWO`P;qIFwlMeLLgp zdRXX62|1aSD3Ayu5`~rFpj3hr4CPN2J;#SA8&?1Z8eNFaZd%9U8Gu01j6mtSbe73w2UZ7h9AADEAUMq0hyMCbowEq1=K^rUG2>J=9(-{xv2RuGLwINP@ zwO#%IUx|eET8YnKrv7@a26A{x8X3r2)&;#7Oo-`sw|!(c>{{^LelN%kva?iYAV>tG z=iFrKWtNeGC7mH;puwv+{0_MT`wjw)6a+X!7%kSHoU;^Y$U3oij(R#;`H5zn8H^cjgrmXt|?_w4j10yshke%#{Qr{$ikfstE;E0t61!O$`#04-5(GLeu< z$06TTOp-dFpX`64{f+UZW7Y48Ue9VFH^7ym!|cX~xvn$?cf}2!hE7yBIccV=oOj}( z%+$EaN#IC-C>9S$xBb+8nUV2j>8sq%)KH7Nz8GHrs2Gd(PP8FT{%i|lUD}-U zr|pDOUmgB@KKJh>Hk)8T_jzp*%FRKqeHTvp;b?y;ivtOc2%6(animRVFfe^rrq6g! zrT`Kku^k=tMucHXX5$o~3I_e`0mp9yI@VMXLfn&V;Cg*fhhhlP2ZzRiU>n9fHMva2 znbv##@~|lWUI#MdX{&Qq~1P|vk z&Zl#md)*ek=pQA)9php~Y-vLYP8+uK39<_ow3!g(2A~$mUfNm`D}cR!AzpPsI$ckq zO*7TjmuPJvo;j>c^GX1_Kt#VDo-KTQP@zrfg~t0(HjUiF3d)B@$slUnkLP-p#+bY@1TTQMKbQo%!8 z2JlN;L9rePUV+*_h^7^13w5~$DJ-{)5OAI5btE1h9y`!!Hq57ajG$l`x+D3Qiu#RW zkLnUZkTs5!_)H)wJnK;+4K*x)x7!R<_kI?>5eE9{dIh8_LWzjv0}~R_-(lxg4)*Cd z*w2(_s&6Jr0zvldB>%lJOMeQ?C#|FzRP}g*i(y>J<<>qUG~Ka}3OD3gW1zZa(y#2H;iWsLoiLW<3$f!rS|kd;MRilW$bSf$&V8lazMV z$?@3JJvSy}J_nPM>qsE**gf-9}yVgpr834vau3EU`$-# z-KIlAqMTCv5Ir7vd~K$${!D*pJ8c`aN>#|ZgoQ3-^?f-3=X3j*N?RMYwapu?M4}H! zYOR1v!P<$$wyoGs8{{S^*xPvD1(8VXrOjts7bg;F1wCHb+FNB?h8RFjK$-{{g6T*x0e(*FRo@YL`hsdJFRyy5RDm`usG@vm$f`u zU61u_AQFP!)!naERXX*RROiX|g=5fpQjy>&#ls!#&_rRAKTz=P`T?{5IljSOB#cs6 zZmo{Jm)*#f=E*XK7fc`lKqeDy*#eT&;&cBI{6WLkz1C z2urMy2>sTm4IA9nK7&&y6dLEgSCq0~$Bt4K)KZN|yhS1cM4em{(lysr4%dBFNO6jc zpARy<0m8C*8zJF6pHM6;AqX47mKZ{TtPYPknZ9IF%u_5kbGaiUKIZdusuFL+Bjc8fK7lEzy_4Q$0qIkRPgZC z8Rw4=I6pn$@$nH4=LeilC#=ibhAVZ$wXVGv;^Bnz^^E#v3idLv`2zqu@!<640cc@7+P~HOeFN3+$tDWp-khW33OQa7B{S*EV$wY zY4VntV=LDBs_(YK^PULl+Qn)cE5amxPkE?wb9IWF#D4}Vyn>J%A>K&vIKsnTiRl)r zsf#1S_4q)DGTpyt+z*3_Qd#`(2sc^#oOjb0GqE&XF2pfq&*7urh5V z)hwGCFwx;Lah-$)Zre)E0i05rEdEjgiO`;cldd}5SEJTxQ@JJGrxB$rTNL2*v@E6B zr*4<@gV3|uu60G}Ve9t}!>Y?r;u0kHmSIV&QL}xpGKeI^G)El?#%F!HRJzt>i$ucn zJr5z74Q=9?r$Vn$NCSe-=AjD?Al%tSke||4*cOOup5~$IHrd2na|2+su#pQUlo5mN zQa~RgBhGF#(e(jJIOYp#%zj#iAAy01u!SzUUjq3fA{CTZh7T;S+VMjAzbvcwMD#_g z+{cw(=43OZ^}ZD=pB}%Jjmi@n^2T0$f3B@IP&_~2bvX8%diF$n+W!S-Si)`nsCf!% zWm=M<3|kakFH__~@f~{%27nn1#-vy>gs-x^UcbDhe+&mQess(;!N=Z&18GuS`YxM$ z{2ou}BALlck0Z-A6quJKU*j8q$LaH`Q#iBooTnlOJ1fIbTw@_d852%okwSrS*pkle zg4^QIFd?&dG+@G^X)7pNY2wTD^E%p-%lAa}t5~htK7ROM;8=>FYz1XQ+n)-SQ$aZa zf;XVt*>_}XxFX+xilhC zluX=ukHlV3YFm1{^wsm0y0+m^N+wWx&jcAnGkR)d`#C!bGKTytJFlGckx1+TWY}D~ z9gX|v1IC@V!P1byo;gJe zK2ix!Fh7%C%qIs%K)9;iArmDZvvHaRJf$RdZ;YUXdmbNI3`w$uIAqLTl5j?VS%*yz z%=nUSXuLgwY?$31QXL_^8^Bc=-v?kb8P&SucH6P{1>g34$L)6WX(MYI8Ujz74wF2c zPS#s+?yF9p&u1eV8XwP~A1o5AEQ9PdsVyqCz!VIWEdc3po=JA-b{>KKm)?`?Ud zTe?u!BOo?AT}B`p0JPfG1bPmt3_`7^_?;-{=}{?uaD5}d&b~pzBxUAm5_)L>0s#kt zOM&SgH#)4qYls2D#qnF)oSmt#2SFxKnuWHvP9y$0g;-^jVKd`q$@;SI|v&c9b?w;aE4L+0(T0O|7+ed^@L)ZJ1_d@c^?1nLcZ{ zp>=|vRqduLYO}~_mC19XqV}+3rQ}_}Q5v=piGAOJB3MofmaSkp7cA#x_^lr{tWPVp z4;$8}4cp_2_1qVES~}=mS758C=MA!-QAAJ{U|ARJ4>!nFP%qL*1poF06NVHxTumhoBwN%NN14hXnMqPGGXkzgqXlA?wydca&6h7U|Tnb5r! zaBR_pgPfx+={~1Z9ech%dq1CWoJT~0<8mdA56wX8u?%d)V!ZJ<9t3%E(38A-?={}a zBp*vRv}VVs`5+9-8U!Cs4#{sD!%QvQf^;sitb)Ch5Pm^PE%{zwIE}Ns-uE4QZwL|+`xKIokB@e&!<$Mev=a4haT_oO)u&-dhkjVS+PM;pww{I9 zHwNLGCFK%14MQ&kNFUz4ybs@(E#)j&htm#v*Al|Er)|CS!>jv48*2r zhs#j>f~|6kam29VPPV(j78}4HZM3zZi-w&7e$Up+YzahybY1t8I>xf*D5DQS%EJWK zxUx^PH`Ylb5|f6mBipGy$MUihY5VZH6A7*Vsy91!pieUl>_-_0FGy&Cn&gH*Oh=te zDB%xef{29SI61P3l;+^O3%wWZt2LxR%d-JY)+fzZZM|0#VdYn&4K*;`$rB?~YbB=5 z5kjvU9pIJ@cxME}(l8+q{#;z=N4Ph@2*gY`DUADWEn@GG-{RM%WCBCkNqDo#E<@Tz zUnO*M^eh8(OS+a3Jwl8l^NKgOxBPS@KF8(8^0ELzy(bwR2$)2;u8+ZMeM~7UWmY5{ zIsGgV6dz1?nN+kqZE1ElptEbD@8Td`j&pj;b)DA&cvM7b3#bw#NQRwWZyJE_nfiG|1n zEc3jD%lAG@h3^LkHO<^!fK?2raIb_KNV@GdbQ&Q_IZYus17<0{kCm*czD3m(-R&aA8r5m_-I4}0B*O|({bB(?6(_k z`z=htYO^sNkcpIfOGnGD2+DaFV;0_8XRVbMM($cZxA%%UStkKTfco$+BQX2kSBIYU zP9U5s>2T68uDqRlG=>l0#dXp3q+Kh)`#NdTo}EM{BKVCz5QwK1bOpY5huCFM zKeVC8XM0>r8OcQKiJLb#9T5plSKg)sp7snp=&c}gF|bZ{d)D}KKqPcnpZmUI{zUbl zl%{(I5bRrk_LC5S=cAK}2&XEndvBJ#$%mOa{3dQ!v-vl%L zo`sobQ_B7<`<=P3wVJ`zBh;l?#!h@Sy=QW%DbldZ(N_@Ju+74ca?FTC@ViVN*mkBO z5=y^VxN5IK`w(l8+AYK#e5-MbMMU8jsz+$Uw;f8j$h0iO_VMY-TJ{8j?P10Guwi>x zu|00>_t1JCw#OAX7vKT?S0HBqC$tZ;3p$xtfU=^XIni}pu%1@z=MD8*fh*ca*Vh7E zm%eW#qTG6K#J(7Lm=g&d+N97;4MOaNu$IR(++psV$N=>{lZTy&MD?Lf(-yWAb{KLJ zJ&H|1X*1O<`eA67SKn7KFsz(Qr3{!NavZtkOyy+-M0oG$TJ(z91UhkG8etKFAAB#F zi0PTcUM3IpOLyzhfq{~2IHoNko$&bh zhz}n=gx}-iqY(`eSX|fJ71!Ghx8CcqccQ`{R%bF%N(q3QNyDBR3#z2)QFFQHA7VXI zuwUq0tc7;Rerp75-+dUEemFfFdNdFTCI?jlnbH+Uz2_mm>tH7miCDfe+6tQ&-f@uY z5`m(It^BE~$*JIB_ z>yhZc{EZIfhi6qWnMNP$3tuw0a(@d0k;?+qt}_cMtmh<`ji)6v1e(q>GUQ?;@6N@` zV6lfGKp*Nedaq0*LMe-ac1=UyOG2geR;a7Cm4m~0-9t@j1vejhFhY5o9Zp0Ke9P}} zy^-Pm=!au52=aFtqIRtJf*gT(Kap^lg~?56_hiiJY^tMca7AG_9QzaTAzD?B$$k%* zBo{K_W8MaZgOij#NkpOWwLWmK1f{5bY`yo^JrrrA;bFt+@r2XUhOO^Uk0+cSSJX2g zCxM&=^;A($eZN-JrS`&FT8y%p0bADv`)P&T1h@jYp^=AcLAfp{mww!PB$nESG_6nq z(f3%!IltUM!5nce^|suJB?@woEcLap{D z*C@gOemUwA%>H1k-y#vw-r@OnC7dwuOQFE#yb0J#sJv`AfsrGFc7I-T(J z^n?!|KH%fWk8S_qBc47ybs}*BfY#G-Z6u=YefX62NciG&J}Z;f`zG&ha^G&dl}8+I zG$HJX$OW)TL{II*vMhc2%wo=835E7VG+EkEu)WJP5{Ya_;&~;a5Ep{Gvk%N6dd^nf zy3T<9O4yr9Wc`|W&zX(nJev;hw4pi0K87!3EMh~*4CI&aPQ$<>fyn!zSA_O?%Va6! z#k5K@P>RRdz6EkLArT>93MYW>FjP#*kQjjm;A=$ax)Fz4mq*DB;S<9bT^D^=Qy$Jo zghIccP+O=#MsnWFNGRDss~`P62p#w9eTK+oY3PxCmJ~NejLn=(=p84}0JXpykazu; zp%TP$)1FF`L(&@)U&Lh)e6DagbU7!n=U_Aq7SVX3uTHDvYvaBq;TvquiQ=`4vJr|moiC*U|1`{^vUYTQJ_o~6c0~iNb#w{ zhaL}2Kh-N+z?SNy9~Ep5=QD20g0=TZoX#hl9yXjFPVM)2!ujch)6)s3$E^{Etzth_ z?AzXc>yCZtv6KQ?3Lp!xx&x|f!Ll!H7N`}#4Q;B|wYP-oZ(W>3+#wSB0|70A#neUa z3r?+l=9W0b$?{ZOK|%|!4sF_FuY|42De#tD>L%Bgvw}iB2tHH-6pv4N*~r7T`tiDM zO_zDRw#ima!OVC`Ob=^r^hxP_TGNkCvXLP0q2ZQrhOF4-;CPf_w#-X1)MYf>M{YOR zEx?UVCKGQF2_$ed{6L^>@^gAaL3|_BS1I#K6;hxqb(Lb=(ZzA*?iN~i$JUu>PJGJQ~0pPlAxSme9Uaz=p z8@AhKLnQ=oQoi}x5nMKx%N5IVg}2T&0Hw#Rg+H$TJosP*Y3X~WOeAWp4utK#w%+Q; zsJ(aMcEj!J-<8btM#FY8q2~_dRPRiUa@m_LU=Td2hS@M94+T9L)L5e7kTVUzxEKg-mCAJ47tKQ_<=-BH}=I7n_~8RUKkW{ z0xK4lzOVUSLIZ*R+ItnH?5I^xmKr`j*T@FY67o4dtL7{dUL8U;BNaZ83EAAik2&5` zLfbi|-vduN;npRR2_^Bx%0R)KP0>$v#p)C1gJ!*>Q^KEf>M*|Ko7QKpJtMfB`3OK~ z)l%Z14`}M7uy4#lvt=;?=|O**lt^j>!p62SSkvmED@vmpdDk-@ImOvyRp+ zL1;`FGJ<7`7=a^|lySoK*@9)d*LB_tBqjom6FU&Jy5`T$G1B{(1c&39rewT?`$4P_ z{&qf{ur3R3w;NEo6OphXPDez-44R*-L-5sWeaH~Ea;foZg`P+RfdT#q zGfxjWYuN(axinx$W3KJP(2+>!5Dq=o*3{{YE=D9U?2TozT5$^=6N>}=(s1TC=vu&* z3{DDNEkk67jch5Z8M~)CG|0f)5XHoqALW^d8?TU;YFra2S_(U3dM}k*oqZ&Kkk3;B zf#yvIB0-D6X*?Lk9&(3U*GEuQTvtj2bN%K1Vf7VPnx>WWWnEVrx|8!%q!9_8sfmfi z)8iAKo}O$PSOC~gCv4Yis~@Kg+trB#0IN^7??eL7biP{NwVo1PFT?9qnBF-%u2kmy zJrjS^q%y^!lxe+GZj$O!zG~?*z@U0bz%;a|XJV0n|6;Qn@t*A5 zpkFZ#Bc_RfD~Qd##;i*`v?%ZI9rLvqr++u6zQA;Uq3h||QQD5;oo#M!81&}cJId3z zAXn(|Y!_S>OYe+G>?j4OyI^11x(+SQ7_Y_U3K4v6)afV_lZpAS+OdH!%@fjV)id2{ zC2>5`p>DKv@U_y`H(C0z#!w+*Yl9adNRic;aO#(b`1F9Y!V2B^%9AM`t0#WJ-Zuk z5U?2E3nWepLBV_Y^J|Sfkdo%Cq3;#mw~=D&p5*c&Ox}<-;Y}9broh8rAj3opAW5a) z(w$(b&}BT`;VO{P5B+%7kP4~jQ@oded+ z0W7WII%KH;Zty7miwLAF{t*d)XoMn>uo)(3c#{LR9%d&cr7LYA@KpsJG-!8joE65V z-`zF>g7Wh8#n34!hAC()gm%>DXd*=#~2|cF7gtW)wxE(d}t zCZP!$hVN!T#}Xq|n-}u+oib7QS#K>rbk>>_vS&Gy7FRg6)cT$TlpjK}C)qY@epubg zWx)O;>9B=Mn6!n9cp>D}0qUhEbN={yv2MprFqX(s43ka#eR)I1qmA>9F-yMJq+pVv zsg9|SGUsP=Tzb!9oZAPB{U{AW^;5!i4Ocq0^8Z<af|Of001BWNklKZxluKj8tSbw!vNNMX% z$kG6@5el$Ti!+GSTKl4NXyX-YBN4TtftCu?y0j*T9gRSU69~;1TH;1M9+8P=I7NWP z%f9amu=WpKbPBcvEN4W*hc(e6TLk1)DFkTaElX5r^nBE?bPRN@ZHAU@T_NjAdAvfl zidt8!YwZp!DausI;SPZmlsET#L@Zdrz^{#Q#efEvKss2$wFKw+QT7XAJ2XVuW|oOV0&%7 z97ZHc@u^=s@lb=v<;`WL`RP?B<`d6kR4LyQ>Tz4s)9J%*{G;x5=qZ~2G_C8hH$tL- zUY)s!>yIX-*XyV{i3E^-=z1X5(^SS`JAqi(50h(7Ch~J{;TJZC?%W+j#xUcD!AB&5 zj}Ln$kggZ4v(!UW%0O6_GRu>({$)^E$WH4v2PXP_&MB=6?HPgCu$$8Dt?RJY8*8Ye znbFK9E!__;K*55gNU#~1Kn$Q-Fc=NfQ%Zn=5#jnQSQc^J4T>8rvlK5cJs;!r^0g+I z!Ju*8x})H_6<=!~hIcnTadiZssH|feJU|KG8vXIWeukZru9hPirs0?IF+zb!Tf^=j zWD9uqAiQHTF%yF8)|iK7n!XqpW0QN^k#8Q!gv)uDWx0|IfD&zZfbmv873?162jD6l zWl(=1;YxA-K))ES@QoM`r-z8T9&A#X2tLh}vLu|bg+QT57P*CEn_rVDXkBcmO zX;W423s8Y&7oaY!+fhZSXe6RGGQp|W{L@*X+Mr1_^wQU@Ah1UH*)qAkx5#4786d;j zk84lEp2>u!kBCHL#bu~9t(?VYYtgyy`%EqSzBdxFZ8U6Z>n)ZmwyioiI4E0a9G2Dy zhO=h4BOFOY4C|QOT3j@BK*I%?s5yTl8YS8 z!1Mtp4+P*CWSO(pII^=oNCIEvR$?Q}bSxwx$d5QjbJozYywxmY0!6DmNnoixbZIHwSU= z!*?=xPry3#8hBZ%o+Oo>oE&Wo`iPjo>kyL&)g#{DJx)YoAOy3YhH+4@x%}ru!V6IS zjM`#7=67aWsH;})3bLY)V&AGgdLW%xM4+>zFMzkl&FTOH3AQ7MI>*vm9uo+6B9f*X zwlpOhrr`;E@x38atR&y5TT#joRQ8D^x84^kQ-LmWHinx-l>E#QB0GegldWi})7d>a z1V`x}uaS%sGZ#E^68TNwu4?f{Qs-pi`02Ord${@XTLgl)C^zRrKq-@$S)5UZAyff; z!kS)B3f&*Vi`Z)*0=5^&w(2vAUyrPU8_zuWZsE`kegA3PkxXn-d1z8cKVj;?YQJH@ zqtXaPNBwQ=Avt#Mnede?v7-})(%$JLqV+}q3lRy)B%-!sClURd2(`}U1pj~H{&mff zT~!)JA?+ITz5jb%v%AYqv44nw04Z%(kF~y?^|#FvQH}F5H&P zGh%!N7bEuB==(^RjWjqzg@;bCK|@%?gOyp%bFP+^!ys)E0klQqMD5wMljhUxD+c@^T&7To)%|snoiBCt8!?^5~8rfAdP8C4W}%0dQ>sS-nWp)7=@K zYY>tOasl^3M!b={Q_cZ8Q0|I{>8ylGYhX1TduCxV=%m2I_NZi%0CO~M{5ZspV-63r z>BD1nC>6v+jmsjos*vBX`Y?)#0?I!Ew*{p7*=lp3kyD9>6K|JnEs7Ttd~5>!|@XPI!gY+(4rS$G+)>q$CaISVQO`*VhA zVHFlOP^pinH#e)ZK)VyMqn&}cc_l}qL54%vTxJ!$<;Xi6my{WeZu$iHExqDcG}Q;& z>-pc*w7r88dQVap89^12V=C1eb;rDHx7o_>BnV0_SRtXO?d-&DuB=C!b~@Jlu?baTBAn~r%sl=9jC zhu}&L(}-L0xpO9Z!;*UX+u3$@4&bG*r{H-*z!;e@w?hgcUpBex3 z&bZUWxndCgXmW`=~2wMC&6Pwof{vT-EX_|5b-X>Am#xFW4iUV^PKGM7fR=B74Ygf*n=PR&oh#x6mwDwyJ@0x6tN<$^naI4&1j%V>E&hkEw05YrG=@MHP!{*+U7il;d1y@* z63R*n5Q8t0Ak5|a@LmX-V{rH7qwiP=?tYis4U0M4<+vU0Sgdmscpkw)a$Q^XrOy|COF4O#{9el}^|3i?tCM3w4R^Ma z2k6co=R5n>ZEHR*&cr)AnGxm*PNBS${4GNKQF2rhT6*LpSaM^vCH0!+l+%}a5OFE{C8K@1wq#K@6|G0$YoF&WlBigT?47nPuJXAeAC!8DmF5fHX3&I4aB z0$cPgsFhL?hS~E|e(`je>4kHhE;K$%qNp#k?*n4QX2ysLd&>O^2K4mcFiV^KEjtV^Kwyk0sHOC4;I)Ip`&oO&-( z^icc$s^{YqAhGL}@QZXPf&#batzJzUsGFOSR3$d+TC4wHP3)=*(ITc*@O{x3(SCIW zB$&nNs1G0RTO5*h-<=ktXJANCJ!&k7{}>L4^+H0TaPUy<}L4-y4>wzCUX7>#)#8e{!a zh}A*x-#HWS9+Mshi2cZk;O9HwO!Bnl{e_KeV!+sAs~477t(<|%E5_03V1z7VQ4y0X z-dXwY&iDM60s603%p|~Zjf9`Co-EazIoVpGH$g(d2%G>1v%QxgS}+cPu{^KJk9#IW zbZE?nkcr9tnfcO-7~+Ip36W#W)sM1AVhXZgcoQ2p$;_7`(V3i@h#iXIm|lj=M52AL zBjt`&b0n~0)7pxualb14bS6|yc&{!IDZM#ZPaP8`2U;Fg#Rn~uR)F}BT(rEAjMOSp zjGvVIB3K+jd)9}RXbC8rkEIt>Gr&a8m4i5$<^Qm(kD#TtswT*R6HyyFNLLl$ zmmne`2^L>8O(e>Z5k+NKS#q;=6@K+0h_eilg>kM0OqKGdJzKm^~ZWb_)I*n z&Mlo`dm=j0r$wjcmqp7qxe7~=Gck?{WxOcy$j3Y#zIRM*)%9gh$4$m3rYrH@S_w z-0UVMCO5e+;M~k&r&#C>5eZNhOD_*!e!11zg^Q}b?D#B*GC6wVD3FG#IIRp1-2*?4 z>)7b+T;c(?htk)HkRPYNvS6&0GcN}|V z@cU7nNzz0%0nb7w>x~)_KFe#fD0eO^T#K#^N3(vV(-iIHq?^LQ^fInI%kL$4*XAm2 zWohBe<^2L2p(Fayn6w3Ktfu{!@m`PyK4g;*IV(H+S?kOMbGVKgvN*Qoa|XM>Xz2^J z&#E=6=f6Du4VL>+BCsI|cA0>so=KI3DhXtxoKe6xdw#8ytk2&t;sZ8c>7O2vZqn1J zv-LiD0y4`l$6<-@*?(BJ`s9FAP0kvHS zz^>AgC8b9y^;ysE`{&h2;NHYUu(YceP5`Mmr?x|DL*$?pzG}8WR)ta(ad(#R$6n>3 za~Q$>eh+-8G;AqaFcI%C8FGr)oZLFswH1+Lra4#Ss5^8oGJSc!ScL#z(Xvpvyd1i_ zUbPCz79#A5xyFO=Dfkx8>tXdWyc%1txyg#OXXKG(vB;&#vKC>{E~tVuL_!-wOQ5qsndI*k{sTGinQJ5?r)lanvh8w5_nD1bQL9x*si*X-vA9opM zqQ?>Aw3kiY&LO9q0myPQKc}sLZ%^}3k>Q}vpnxSnS8)Qg7RarBI5nau0DQr9fos)ISvSHLF~ zNIF5+V2N=>IX4^-7tTXypnc9eMG2C#Xp^2-wrdw#rJt?+JK3wYw1j4P+Qid)&E6f^ z`u&O~$3g|{H~PAbgZLRR6r~4zwUl-3MHP7sp08=PLe3KI1$Ne#qT40lDw32Xm+-yp zC|v}>n?^Nx&4+!QAmoR7ZkNn7#}X{2-W55pAAoWDJ`I8i&t*u1U{xS?%AJf`HI8E%X$NXZ z7K(mORJCv-j^`2OOLk7g=4M@bP9S7A8$eHBhh zxvFNU^M5Tna{?6a$(hhnLe*)|{ygM|2>?1~!Zg!~j8vmDNvY1nB2ByWiUVQkM8q?f zn@FGQht~WrhLyRE4G!CPmrh6{TcngDvm|;_M2Y7vG1MwkV{{oe@9i@JR~ukC6`2E% zLq+Y7+wG7sZqy(lvApXTIp+v+h;{LiZWzRfn}N2=@4&LW766%hgmUo&AFkM(iR2e) zVM}ft%9HFh_`>w^gz@k1Z~61*kNo-bN4~%38BWIB72H>XlhhNUb@^5d>B4>$N{tRn zz1CTtJcr~sjsOMOE93J=$XS4K5s^|BUZSB7BP<)zqI*bkT&}DASnUeRx%ZB}Z*5N* zt?dB?oiw_W-ZZl9JF9Wb>sjW-d1~ifURDPi;i>V6=&SXq@;oz?bWP_m=Ow}M#Kd{- zMJo+EOJ1%I4Q+uuppLg+Pl=T{NaDrwO@doCUGYv| z#+bp_K;mS;gs`9z5aS&^A3G5dRa*iVb0S_v^X`4bod5Z|(DyyQuG0Jf*1Ym_?i>_` zmU|rdoQ{B0rXp?dK&7_u3V-GmhaCtQ8YZ}qpA`VI0pJ%PQn)pPVwssDuopL+L&gxna>u3R zI$F|`((I8yD|rQvs@Qj7lnkKvU@p9H$l(ha;5}O8$C&d74%In4Q0x94&}IqtbIIl5 zyUQ1_8cD!Fig!wRelSTq8X2%4go*fG-Ouxs2Rjn(K>YsmTmJn19jmrsPZ@4mzPY1- z3DNiaU2eY8(!9Q<9td^kxuhPO3icCd4I5%-18P^gLQ^Mle1RFb4u9-OtRTAs?mXwW zQsS)d`||*D%}#}CWLh`XC>qf+k>W^Xxb@?p$zV4tjh<@N3uJr3N$fpCn|U`vWn16X zUZ%b>SntJqcZABE6?=7FD+ey)v2wlYIPe?#MqjniDnMA1w-Vnv@wYzF?RWcUJ6as{ z7~*QU$>=`JRPA|*iT6J|igoLzZbR>z*BP%Dwv{s8*is}+I)UF@9mT%e?)e2>|MLCy zhkL!%kFxptPm_?>)4U-Q^{J$~`4Q0KKwds>k5lj9r>?^@p}5vCEwQ4j_{n6Bc7}bw zXBX^RVL}mGp1Y$FWbZPkh|7O)9&BdHpzJRW(3Ai#l`;>%;NcjN6W~SvfJBoU6}0lgSOT;i5x;AuN$Z&DV2S7N=Tp8P5BdJ{Ex-T#mfydA%kSU6 zVnR7PG$u0hB}X_A_xqQ8edX`&=i_z@eHuLsH1{Lsmvv+9x_tPWc6gVd8{r#hh&n4F z$F;!%(kAUHt72~~Nhg5-S8)*XJ)hTb^bB^&UzRh`V%%A>Kp+YL zQDk3+(MtmZ)*XuDa0OYHtK{V-&-0AU>g1Fh(@m|kSWXklH`nkNUxCU24(*;Hs-l%$ zkrB-xnHSAo3FJ3b{u0IZIwRXMOVFZ~ge8P!9lIz%0@&Ll3RAj>WE@)41IQ>2gzS~W z$A_+9CG$;Zk+`1hV6ajF5Lz=}z{ReOK9P~xj_hxo2_YjW%pLxkvjSn4FpTPslB$Xv zCWqe0QIP;lSd4(F3~)1soM$fcdJZ@e!-wAtIb|+ITO5hoO>QF>J&4{2%buU=?2GSC zfBKTtZ6|9h)J6UfPvqB~BNW8^HtBdiFM1??|B_$7epNjoDRZhCyJX+LzT}^O{%ODe z$Up!5Bez>F?124g!Z|rlsT*hJP$m(HA!5;sO1hbU%#0O$uS#)+WssSar``)uorDHB z7f_aQbmwAi?8^7Z8{|I3Qi)z&(|YCLL^U9~iNp=v{G#)6KAUv7vv9+FqWO#EeSH%B z?KU4KP;x+dtvWm8ObA!Nau?H`s{&;*rDBF^ zQXk^HI~r1mJLuGm?D~MpetCpmW&!YAvi!KJjfFon^Z##-t+OK)tGzdAd$4V#Y+uPQ zU3W29FMnWT_e0#?^6V3q77^I!E`D$8b+K_TlXKvt zCLMHyBef|u74%315?0{~z)nOs0nNxTgS29js-Q2K(6#S{ zga(x0H29~XgxQ-A7#NDB8Q?kAn+!7ImTVz4@gYrKQBH~n>)wmVT;*!!K!%tcK6Jt) z_5_yME8$DS>X^$l9-a;TR86J0GYH*P1MSxxZ(3K|89K{hPgScr?f6{zRAk^qxQT~s z(nd{k=oM5WZ2#@TtPcs)%O+=0FIz0|w60@rX}7XdiULuJZhBxc0J|9hobUwuL114N zoj}E?6$fdlXgb6ua=%Noq@L#l;is?SG@xH%-DK6p_~#$_ z=Rg0E|NQfh{O3Rak$?X4AGsa3*qaB95a)Typ(>}UoTn6iGHu-R8GHP=Qvv77cs>dX zkB|{Bs&fxSLUM|u&|3P9>`0TZ2ou-jFd)9LPZIVCWo`5gh|3mrqIc0>%~@euz z$}e`H_DAdC@!ArOgF6v(m95;N-0qWya0YI-S*Pk=Cb_y)O;6kN7dpgj4Wr!fbMY;i z^2NE@v7#8Airn7<&TcTY2qi^L`TbZ)CrL%*-;mTbH{@hG5w-946CnCGM@fH6@U{Kr z8@7+@H%ffj^L1hn5VT^(x5qBd%U+MGV`ICw@wNbAa;cn*8mJ_5^qz)Hwp#UE3?zrV zQ5b;ge=8=?d4xeL75^@Qd)D@S4KEHwxw;mJ?nv#9s}$ocBbJ>5v7Kxk)=Jo!fNq+F z1gC=GBUKY6;TI_kr@G+D5MONfb0HK4AtJpTRg?^1t_+e63*HSG1G{GrIYcB}4v+gd zj#(~4=CZMH4qhlMb``=Sl?rkqJOspW`!u0o~;%hzQ#wnycmhGQ^yN%!5!pSfi3{eF{Z-PSpjDYB+YD|8*PQDX)3 zbx6`Bzl#%*nL^8Sn8)bV=#gwM+mi}+SwHU^oH_&p7|&;v&E>006R0)Zde|~@sW{HA zP&*zni{o(d001BWNklbSxyOAiS6{+54HNnT}PO}m8;EaVP_Iu@N_U+b}wo_H<7f+y@uC}X7z{iCDR z9o(AoJFVe$ef%yF=#hJfx+`~KB|^v<%KuUcw2YQ~C=!*NXu74>;y6-t7uzk{$Gz=D@rnc>QWg|&`#t!ug0y&|%rnu#wrDKdBII~)-XkwfGVA3o(E zt|-&8druky-Z8X#gDO9^kim}%AY$%D(6h=zrBzCvcip(!&LWaSZ6a|ArM9amyQ=yZ z)%W#bb{Xe3eX7*j!v4)sr*rLkpVs)pwi|z)LJmjS%;x?twAcXlZ^1kYn9dyD#}lIEw>;O*nIi6AQ(KA*QPxsI+noTSM0`j_8HJ8D-_q zxY0)F+BRi7RdMP(9#&b?in|0tC2pzL<8u(P=Unzqm>hDGA(%@Pf77T;=kuIPy4pQ^ zj!?H$tE?zF6AOi;PmALv$%8G)x(*S`;J^(0tbIOnvN!?wPN~lFaRrh~{JK)jPDydz zw&I+GXOUXiZiFbGvW*X*z9sK}=b#L-*j-{5*nPk5jR5bQtjmL(^4DSiS1oC60QldH z`o%#B{UF_1Cfv9??@be{@JfnT{Iq^$oW@Gjiq0tyTgL%dQ=?p?&q5^@RO00B;U6ri zho-L@p;Yb-iH*UjZ01XqTrRR8C6g)Wh|&`C8AV(72x(9##&6O`6oR14MN0~LFV+dv zJ1&(8at-K9$s^J1o-8Z>Sq3v~F862=H@*%YdQ#aU>Wn%>1U(iyH|Nu1$Uuwm1^uac z6G&}Q^+yMZImbzbxU__Dk}jw(E9&O^eqGKiIIK`xq(XjQxo`Ig7SS80lQ3s4Wd#H()_ht-*U;_Re-_H;ZR&*10z%-)D+EG0YB zKcDG5U`|LnP_;(}Lz>D^r$KzN1vYIDv`ChE)a+ZRgowLK+(u^OTT7!!#*^z5I~2YH z;TkCvjLtZUN>~Cz&P@_@vrdLm!}Gs6Di~v@CVQf%JfEk??YvDV`Zl5mrZ&z<_Bt5# zwW^h&$0f&$15r#d<%R-mu zYiT9EVQJhA@#{NYEP0gIb1>7cB;U0L+QeMHX_s3^Hb)rjqx|b3EjvCkUCV`B6xzQ( z`Y_X1N8qmB)8GnO>Dpfi1l%6S{{Ta>$V2IL3ePxR}|e3|YQ>TTxlTt=BQZ%&sO-(M1$Vrn?&&w0uj~ zc_wLM0eX`k&V7N>;e@_c!X6mB<67WVu*P_bb?w_-XH!%U822=6-0 z`~v`PK#{+z&&{sDQ9i7rRO{+c-ZL;A7;$i)6RLS$#Gl{4WABJR=#6;JiO@Do`T^B6)(a{0f zG`526X-$Uji!zs77LhtEZH%Hrv_)-PM=ilgHNX{^aGl`y8K+;6OrNj&2XG)!`9ajieJMwGb%_))6YMo9bH zJw5WSwcx7Kd*P4)t>bKW-@KwH-|d`;^3EADCrZ2XrYc8Fh8(eDwpg}mj^WF39U`*_ z!pm@YkA#ev;EH@lOG#q{%Ah#o;zQD)*go?5{Y*DA|5Gla!be@|%07*}c7iTwSe1H% z!b>Xy_w^L&_wnjpw|9xGwz(-9b|B?scJ%Hnq zX)tKS3P&@J3Y;QG{_UYTbr%i09*xjs$up9?u-M#Cv6g^HewCOFm>PceeZs|GU74+zp;$ zqTJMPWPCR!d@GXgYl=C1abunIjIT#dWduRM8OWk%{+0bq;v$!2ZIc;6*WLjY?7k*uupKjNk znZ?E}-|nEiBp;#?(W4;Q)143&`D^q>tPv5dRJ)+F_uuI9WJkA; z84?EP=|D_kdvAo8$UU8htK8@HR#leFld^)QahE1r2pvH7mW)?Ia+T z=HPPaF24{A%`YV-MCl2HF;#?GzpVxx8=zTCPCkIS_`gGy0Kcd7e&XihH_vuBLvclp{(_DIgPGKP#pMaTT&P!WmcUlZVC7iZ`P$op)aA9EPTfjtknSBEx$vu8LFa3pdAu33)~ zp=lk~W7w;LXxHla^dAo?d_GTkJRZKZ>u>q>>v!&4{d8dee9Ghb^kGnA*4JPmEn|DX z$KDaQTka1aGM8+Xb2t_R2?90w3>vg#|Zql~YihxxZzlVgVEck%iIq;r{<`5<}= z*bbQ$r-6s2ZCBS?60k+D7XU&!BI>{k``3GAc87(|r|%trt5{i0Fo&B+6xS+a^@c@n zp0wyjl@vxLV|R&kLLMqNG9Qz`7?}|=;r2cph|CN2z_{+I;Pl%He%vzNBB(YszXx4m z<0+mT>V`0uc1AZgX?L&_@dgL%%IYW8yr%oZ;6HRG+Q*aUcpv8w%zFJ1-^!^19=7SB za44NU)rFZxVXeGw3U`gAgh<-*S9&6p^^=N_d`FLjny)S-CghV4jM^Lpco{A8&$_#lbuSu8r917m2%uCsA?qTf8%R_E7woH*_0U% zYj|cnmb8sArDo_5wPP-0Ik4r>A>;7pa~UUhQqal*OA2^cEoN=}xBg(|U#n;-)ULFA zzmJt?`x0-MKaF;;`x{y=<)=79orX;$9caj_a+hG!5~Wq6$~|6}#FL_*kFRo7OmC!D z-|oM;O1eL-8$ODJC)(p-r)fA~Fp1@ed1Cc!<)|BH*)ShMbd%#a3A~FKdfO!DFtIbB zW6*qt;ZB6tqf|QHE3j#qM{Wp!M9+lJkH8SESzN5Zw!{|2quhw}MS87tP zZoorHK1Qt`BX(+^!|BqAC_QTNJsEv}ni97#fR2PDCak0O8Huz=N3p#~UxYPh+MAxV zLD??fQKE7oGE`2P$Ld^&BxKpe%o>x2GFN9v6ZUjb33HlG#gE4CbChJKxaHhhc$~YL zX8L0OCO@NL#-AL!;k9p%oqhQK==g~YW*0VYHD*imyO2O_r;r@vE(Ml8rQMJfnisIChS>n=GO|!FF3pZ)rsr!Ps)dG4E&m za4K|&?=Ugu?%6iG#C1$3;y8}jAa9t-fjpK9ci{uGJbS*E`O57mLQTqBOPFh$w)iaG z8Z=k>*eANiwRc-yIYX}^)$$+U=}LAf(_HQ^6wzW{S^w|Sp>in(rZ^GTdA;O4$3@Ac zXj9>Y(w!mDvIf}_F`tt&N8gzb-9w(x>JDQ$dn0&G!p(c;gh25;=6)?RZ5`%gH%;uA za;`_#Vbm>gXJz1L1fFffOhGRr4;K*!bZ7JkWRJw$aPIU~rOt7dp(tf&lk3DoX=szr zkpNF@X1q*>wlU;+p5FWLl*jkCe1B7~#P{q4sSO|%L>8dxCw3M}*S%3lwoa1oi(lz_ z9>bb=NPr{M8b>!LSCR>ENMX2ID9IvvKaq1D+EY~*8}^!37*gyzsE`$$-O1~=p~uC% zYXD+_1v^xe zEh>7FsMNSx^<|?=AulQH-fVsz$s3*@8xwHz}gZ;nkp=&^m`qBYSJ>w{LCjk(iJ7wtHt| zx3-)ygHm2Yrp?7SZOlS!f3%pa>-@HH5gB%cszo(HCvgMd#A8{v?g(6xzoG@TPp<-j zup}^AspuC9x+|lGUK=P0k%GSM`tP4Lp%2erIbTpFnT-P6z19~a zK#qxu$QWmYJr46R<0IpoSYrb1G4nBGNa>Ln!-qSW8~}MxoSW8;m7xqCMRF`u{g8#V zk1hP9>%ZH+#TYKax`|_XV%w)bKTsxr5f}5Q$v_&)WO>uO?}x7rHG3$Yk7sov&_b;>AB%i!)w=OXSgfLYio`C% z+g+o7sBT3%A>js$~IitGBYsEeo<+Z-t<)&hRE1>ET47Ix&4dyxt? z8!!bR@6AdSd0u1#Uwx-SfLUcD)VQ?r>r-!eSnfWLB7Lu_9KzLF%L@$}kGeC_*sxqD zU-OqeQx$Kq&fYl@yW=&;Uw{Ce?K;wrWvMut;SpsW2dWq@1C z<}P!SNE4BRTH+~1C_~F@F)j2ILxOW;l9XxTj1dLaz6OC-f0X~-v9#_ODFQ(hN(G)8 zA~}t-wtJD;B<8~^&{BIdxgpenHTR|DcMfwBF+1f(lSG4VcPy6XG-`z^rPo>3uBXiB zi^XWv=0mDuWK^sMTNT`EjdWE?@AVHW3VcJFoB+wy0Igk`w!K-QMfvW^iRfa|BIBU} zuaw*_>iyv|x&;)FWmaOX&BGZvr~S_}@4Ij~pg%|%2C&bnH)#cM3Gv2---Uw1yatV7 zPBHO1v|>e9FsKanpU*QuBj#)%9`r!WiPdxG>c@lTL5y?T5HUI*p`#9!TR2ZQx!-OP z#Hd1GwWZPbhVYe`qTWgBLGwQIL-Sc_RSGt;L?-})zLgS21%N(`4H-qm*R|M!F)z%> zau@1@=nnn`MO2QGAeioj!u0D%=TP4ma5@m$?lG)ro^wfEtOS=10tIx6gCD3KS zw?B4xh-|yBj@HZAqMC+!j(S>q9*hcw2TD|$_J#NkR0SH~)~_8LR`Dg$Thb-^G(2z~ zv*D?{mfiA7uk`Xo26p1OIYRlaq)OVuy!HTa_&|S2jOt~{XYJ`oHBoy%lCG8N*%Krr zSk0moS2|YArIg^_mslTO+Rp9!wUFOi$4$hGzN$MjbsA7;>l+O**~`+N zy2?EbC^_|g3;3@N){lA4cPr)h!_9as)kr_4OeGl?Af5yAx$&WNlS0YLhQ+NlB>+G; z5Y%E16Gs372ByYAMy}Uzl*CK1Y6cNnyJ)WY+bR0;43ksJqof(B7=;zh87s5(@+Nkh zTNQzpV_=eX_P#(#on~==1323mq(Yb#Fls%Z)$77WKkr(eO8LYiP)zw};YMpOpg`w14^juIs2l{Ml$M*- z*fE+Ao6NmzQsTm4D7^>S>wslnVW=OEhy3@~FZmtLgiow~o-vfE_hiP6{q zn8k>pUR&)w8AXm?Wa^->^K1bL4|Myb zNCyoCY-8*9-1E41QYp<4J)<`p8g>|m>kyuG&=4zmqPF(@Wf}K>U0HWl`beOoUelYvz)9wZ@Cb?5vJg-ax^-~^um`;) zRoj-P&bGK_t=^QiNH`Fs%$Q$|gR3)9E8aV2Vu#6VHppaBGfJ((ltJZfh&r`-%g#iJ z``z)W6Va_1mBqVm*Npa^No+?ls-6Kr2r!$U!OPS!bLi4+$(^!0bQGQsT7ERJ23dzG zI=mti^*E3N5xM|7{6_7!)F~}n*yK(G^DnAC0Uh6uhy42WOMd_UEq`Kp*9j)iG33Ou zOwEy~jw_6&(gg8a^h}6I^gw73NSpPY>+lv;?8JRgI+BhAO>AeU0?XyXaX^pG;k}>- zJ)8IZKAn*+PH8-Ma@3v+Y4rjs2nmzrO?2&G`#8Zzd_oY&Xf0rOlF}Mr%BlVHL zDr_jFN#Q!QXmM+em*Gf$$ziA<3AdGN4qKk#&{r7p@<1tM;|uFzqc9&v`9|eW^0K_s z#55x!s~lX(Mu~q{A=f|=nTA}D?JnkMAIHA0n(+hEP%Uexvo;h_e3o?8bnu_zh?m+j zVf24T&*oqo+%ZlUN&>Vy)4kAdopKRVTje=aMcEB2lT;B=+T;~22tPjDUNKc@cyZZK zs_M|Ca|Je$`=N8~_Uojx#R?fxUgN$fL&`jWUsD>D8Qn<0P~?)3;tDoFx(F9F_sURTLiYn(gC$)g2|`3e5-o+o9Z0WgdKVZ{cME6 z9B?uY6OmlAANf|DtKG!2QrBNswC&r>bmSp~oUfI++v22d69$s2(YR0|ne_5}pAjSg zgWu?Zj08}i){rIgHDAn<7Ts%tcNuE$K%aG*rQSnsgwGr0w$N4Nx1FPf-D@|4HxYLT zMD*~v5+ZX)ULB%Gf?`g_PT$jjoC)w0V4mj{OmKXQp-igTbC3=NQEnzfO(Yg9nB)&b zj|6}wEpUMIFfkkQ{dlG$5lg*3eYg=;ghGbqxx*}!13>+u>OB&(S7OeGs!PD4*W`?$ zH0ex;SU66{ZR%0h-PvNDPD2j=(&!OkzTS@MG~oH|cB62&pzUzoQKYE>r0w-mCz@PB ze?xbWBeb(i(0MU;fgFk4gJ%;4LZCV)`rkdT_d{-Xaw?8v_Co#sBfou4%%4A#&t@iP z^sb4B49V>uQl~_9f(?!Gk+=pcs=hOFB7!~TJ1q_bemwMt^eO{>@J+0RgVmmffi*49 zzj+ro7kG_6^#&gs6EYjvT5L^$x)4!(A(K}YU_Yt$-I1306TsGtD&3YhB zvVC8_&GR;t=CbbH{4>eB!y43SOl0?sbEEZMP;_a)dyAaZ&O; z5-vBTxHb;NVp+GD!K17*W^lf(e%IrQdhc`6SjR6qe}-Q%ft5N;FQk@Y#Y8~!9Xs5U zfJ!@HI}4#I4{fsgu2Ryjk_0@5hn2u9Tbp8;MWNQl00mB$p;fUe;m*)xI#G4m_t`vQ zCogz{in&O}=7=(~M2->9YXwxWTYfatJ`Ood#q!}pWL*gR}27xGGv=&w-@C0?q;)*bP$AO*Ab_B*t#$;>0 zkd~hE5<_8%_P#Fva5(xWkb9%bSZ&AVnJY=X2uq~ZEMCv$2oS?sMkQ!wHfJJ!4hKRC z7|5X{aAHMl%!!oHk3-=|jJTdke#Rav6B);u$wN2rs!jm7>Mi9(wu)#?MXh6m?(kW% zNpm>n$OAq1-{bj|-@kv$??1og&-Wkseti2-m(u}00jX|n!B^*f0(|O~a7SXCXY>+? z%ai#Wi4jZ5&PD@KnXS^IB67%pJ`{E!vRC3@2jZ5_!MwiB;Zes;?g#I>J?C%WI(V+E z6Sv}4h12p;6>~_dhRkP=H1t+oE;z#o$sIcj7r(*xURPA*c6T0p-RAY(^XksTuV26A z*Viw(-|x;-5wp2E*X=oblE&$xbqrr|tAVbz*(5*#=czNxLI(jj4zfDN5IyR5x)^ED?sCiS~Lqirj2K@rzFv09u@hCjaWj)2j@j zM^D3yc#y5~Bng$S=A8q7Hkh(rGv2V|*_uhxUy+9v#A@Bh+EVE<4OJmwq62>-a+Z0< zTzg^2n#eqqwC79cJmcFw!VnbP4?U)FWzUMx7s2%)*a~MG9;~lQg19D3MFs*!uNsOl z9v6QpeDK5&A2By**RF<>XdA&ZxA`BX8|d;tq^=p|qFpwYJEMh$c;EX(3sZKHUbmXAoP1Zxu1FUlkA0 z&&G_M3Eq4NhWyof9RUg={oV?)Vc;u0&(B_kzE_)c*v9XiO9tFl>~e*PQ-13`upuR(`&sECenH&)}c-5G~DuD z=lFgMNrJ-_P6V8UjniAIU1D%tAoPP<32SJV6SIyF$wFMwI5O}2L%_kKmHOejfSpIsmif6PuqPrmc;I;fBC zr~m*U07*naRBhhxf?uz7_Ub75cE`weIq9o7M5xg~n#`trHpxWPN;pYWs{g#&-EJRV zib?rg(gF@|3B_#xZ*t06MV3 zNUy-EDyOQb4&mVmY1O*%V)l4t1o4Hxc{8IT2cm}}P0=yx4vTT??yj!Yge%FB+=XuB zG3=#21^t$-g0bI7Iu)GcwF0;Dbn#c;9X)(&VOg!==37OL;RXULJN2SS+33f8FBp^P zi4X^F;Z&e^L3J(xdx+?nJrUzLMbCrEL}LPRZ8b)+&=COM(}}p^*auB;Sr#Zu>( z4H+_lWUq&CRxIkvbQn&WM9Uk?J)cjX8{uQ+V`x+M6m$Tvo3I+-PjzleM?gLti~!71 zdq&Q4_C^?1Ynp{O7h*$$L$**KvEp0KZMfgE#eH=e{Mr33U%un^*ZoWGUwMySiQ_m@ zj!HInm92*fZiH^l9?RFZ01Zs2@=I@o4@JvoBlZu0v%!<2MRn%=tNo~F;ug-G`COl; zJf08v^L>}w?GPJ~XV(|P)wT^GF1D8JmH;3^j#YT?9N4t9by6INV;SBQ>@0;5jWh%t zxXx!7==4Qvwz~rH=-jWlCt|fTU4LQ&RZ>EYKL1{+2ex~uB`JONDwB{J#Vf3HFPtYVgbOv3w_W*mwes*KjsY>LtjbIu)o;0f;idr@06!l9Qtwy*W1`=a>|c@CzQs zRC+$ZKXM@M_vw&*kt6X%PQ%yNmwbJF$v^k6xSmeW91_Jm705_`)_5OulRhlH5j#gB zu6e$MM1339oltiqVpBib4V`y5cUr#wnR&Z^-Q#?}-{tl-1mW*jc#KjKRR|a==ORISNXvX#m`br z41yz^M;Hgm`ZWVkSmE#9r=6+Re6lQuqo;G>f|=JW-)J0i0s>ma`-=V8FmAEy&c4cp z1aV^EO~W=jXQI>=2I+*_ZE@5qEl4d_MFXEKuwbVBE+ajDUFEHnvo6olCA-7$+U+JH znBZ3x_x!3FU37_7P$5~mEe}j+K>w}dkYk|L>dH;wbVw@VNJLk8;9uuweYVxM3&@K6 z6+PSotnu!YB$kiW>!c^2d}S5qn*ZnU-Kd|_DL7kCLd-#k{Ti}&;ymFn%GaRSFr-oOw zky?HPoPh+ZF_hG`O%G>TWqGN1-F5(QcmbIWF+FnG*yc#t{Wcwy+s%1)%2)7X$oR_P zUU%;ais5ABL}a&kZEHg|`Vp34=S(<%ba{Wko(l974`C`!B00G1SfnkR$MgA=$Je9w zOx*9$Bk@1~^FQ+IzrWlk+ceb?~w*T<*vY#bVP zO1L*Df#fcpzoPQ;D7+xWUStwsCBZQBwX&ewkTuWM@YQ#9=<$}~h5oDjEahBb!bOa) z55_bl0G0n~%Cq zex(&(*QAu7eJsOXU+XnzZYW8|!-TBGOH)Tw5f@M*od@Xo_D-joXF~$%%&yYPfOy?Nk zNStTRPl!B=*0}*zd15ND>eCpA$A1ot=eqyTIO82!`q_!V#O82pxcA{C@JJwk=MZ+C z&~?M^`A#ua=YgFGPYkjpl6uul?C{pTafs=Vfd(X6?QQ1&CgXOK^SF@{b%qlW!>Yc% zdy;33=Xbox#WOZY*xiUWbY{Mo+Sgr*<>d|bzWn9vjY+vbL&eJ zA98p2s!ftk#_T!3T!rDwQzJ9f^4xgCc^x)3^BkVxSUhQG=yN=BS4N}aqWZh)sZ9%fGm0oLXa+cBYp+CA%w^b&&x1R3_DHB#a61mqt2+_r zDZ__7ou@k!x14wmCjz^DWAb)74vj9zlq<5X=PExm%Q5VaByWOi(A(8oMtamR7J#@p zUhGhapuVWwA3o6lbP_p!; zwW9CdJpa_m_<=LB<79o2A>PJ%6(AA)Umcgu1d{anxi~(7P4Zd&u#%2A0!vZ8S-)Ln zw3_D)hSL{45}<1nS9$oOvifREIYj zSSK8bTR0N2oZnF^C5!+Yi#!W~5i4?2sJ?U}XcyJvkYmt2DPGdQg%_{xMfQ9SM@!c* zwOa6d6XASIud9?}1_uj8?Wp!Yo-MY4(t=T`f=|lyI7E+|=*!#gxZz~ZzYj_5&ayfiwR2d`P)Ex=%8VfAgIHE_v#xe6s z`$^ny_xbFG-kMYF{Gy>vb8`FC8CfPgnR)9-&^1Y`z*#H~1?m}E9cqbJ8FM=ne2`4P z@+}=vb|h3adLO1U!OOqieEHX3(IfHw=Z`$TzvcOWV_8?y>Wv4b^_*-2_qKQFfSe}Z zIKvAI%Cl%}6Un$Wd0Sc~1sa#AhQKN5YPLBq%-P4VYil_6N*KMY*`AU^ZE)|oB)fi% zvif(0f>(Mk>NkCVJUKJ**#5W4Iyk1(lQK$C*%k z4D;g5h6vt5Xo=JnVWV_{NH`Vu+YP&*-lqDB@${JJM^%wpdeU)VK$LKaX)h!>vGJ$g z1EESi66+5P6(>Ao=mo!a*Nc!W-=obW)uGb$dhDKGNXiF?+rqpr$|0Yrq(GVj+ZiZ_ zrX7cg*)6P4pCoPoc2i2_IF8tn^*Dx@`382e8IT4RudM*@as)VRR4+3#(J~(4|K@mO z-O~EJ1;^D$Y%;1DFfpTL+zkHWqB;{V6_SZWj|PBMA&!)1vNzF2!(4ss=SsO0epDsD zyRLPcZK`@5o%Pc~$w2)9=#7xo5wYb^6O$8j8)Aa2$YIbE>jc@I0UT!G1U#QlcP8e< z>6kxZ>XK#epd+6WekkcKB^LEO4-sEBp6bW)gdO2DpdKS|;;{BjG2pp;roFnUUzLSTSy%9anyBoIaZwezDOh50Hh-lq@h67O?3!y7{Pe?>=QYNXgAu52_ zZ-BGOfsknBBHYeIsnTR?SF%_^gaQ1dn_2;j(XuFT6HsT!yi7%CNO?v*l(>303gbDp1|2Z&2?|Rf6G!zddY?yiibE7OfWs8~-G3;l$+q9&`l_9N$hJ zgQiwG44lN~5IHm7FmV8HJLpgFkJXy6mqd;?zxj|m+I<=%hAv6E40}NMDofvw?^uB; z(u$=)F}58&5p8G_^=814FsB0!h4~Lo1PD=W*T#C8%Zi?kmn_h zOdHG8_C_46@^ri1K-Mjn7hrYA*pFe-(&o}lEnX5KEpAVl$;zOHAFS8TSd#BQ= zBPWlHnmO%N2I#8WT@JtK4Q;c>trhFLdht9;Sl#4S#;WLlSS57;has4cTTf8Nm&}Z|z zVn@YFyo-~oYuSI|OkBaVxc53>F*HL~p>4;fJs5kZ0h%xyTa7k?uKkv4%9Y=A+3G^- z9wp->dEK1{;sqk!I1;(eI9g4THdijBwAh*0qF>Gf5uAW`It+*AvV>}f9Ai$rmN|sF zC}CD63HD~%x~96XC^HVf>1h5i#bN!As zSxZD!Vhkm(N^2sqY7TEa*Byu$=43pEeg39=roIwofRlm=;ENTS9*;+iXU}0L-~nhE zd8Yj&p36Lmr;H(G)4lAG5D903>T3A9{pa+jFPw^ff6N4ORifGg&W=QsNpU8!+{(}= z*3B}VisDGn+=$7SFS*@l30C48FHKuo=8G;$J($mouT ziaQbPJfstG9EW`SlCR&7Innyz4(fS6=hD9;bt~j6D2Xzbus^VEX=_`pYW231FP!OW zHeMde!nd%99lzu=>Q`@Ny=-wU9^Vxqq#FX5q@Am!wd<|Au&tra*LUxniK{BNvp8rp z#4^7>cOLes{Of4wU?)Hkc?a1a#uGV4GTG(`EX=qCQwafoW-B!eU2qzxIl zJLXZ9P82UdvxO-puW{utLv^Jm(^$cXR;OZK%iN&Zoe8F;^KRzZC_D= zK)WP_F^JY=kGD$*!f-D`It9-tivUd`VwSr_W2K^HXjA;KM~0_02;en-XupT<4qbEw z#)yv>j>0EHoG7wTfw2pU>p*ri;M5G!vVv8De~aNuw-b(p1i!IbRv+fmt3yMJU<&Ea zRWmTS&7VYhhF;o%U1d&Gt-@ra(?E`duO@gLhwmHmh;t5eOPP@Fpm0LbAh6MWWHYX+ zq3plBJVMIIfbw679=t5hn(OPOxi*2?l~vpx&{0M$uq+B2v4|L>D3xqE6n`dr1;z`G z-k9O*bnD!VNJ#p#pB#Vv;m;2ye&bBMeBO^;gH(CFHavbzW+7+QUsvgMhl1bLurEpX zKkyGKoeM%1WSB`Sa5I;gFQ79gc24a$fpq6+ z^3>>FMb%_cxt_#KDxC;00y7rWuQM6aVgyL7I|LVpiM3^5Qwh@(fkR==!wIgB2sJ0h z>g0>5w;E7upoy5yAty56Tx6MGD1;oT)QjU(^oZp%G6dZmGJkWsw^~h%A_lwQTxt0( zpZ8-|^_R_zI)GP{=El$ixM-#y-vHEU#`}qSEOEpGr>8UzWSOo*ER-nTYrwIVFg#MblJZr{E!W9h_R^@Dqd8MNm$ZPrK5Oihq98nLdoi_<~*Zjk{qlG_oB_+pl8$-g7_CTQy zs&`2@hHr&9)B8hpny0YxA2=3%h8dfSVDy6wy-?4t3sG1r1tnEaKyxi~GvL&CqUyT8 z{3M@;uBSf{-TrmDn~};oPdf1uJF;4K_KMN6m@RI6U!$1HuB;@~U_(}8;5<=6EN}7buVQ^c4-a|T4JZ2K_^1b_hxtMLN&hS)eA=^B=eoE&EfvHs{mPf?<>6kT2P}Iua-%nLBKpuK>Bg2>MbAmrISgbYdm@@0BHI%m zH=V=s#WEU_YPq+>q-g}*7{-Qk?{imD6LV)m4#^)Gy6Ay`^3B*I0S!x!1X)qB8f2sT>RP=wLh_6Xd`QE6 zxM_x*1e%$sF~kRYN^3Nt!o3mkD;mm0uNcbtJdC&SM;b))|0-yFMc0?D2y`;$v>Ufj z?#?hc5h%BEMylD;3vG|3VdtiG$o-MKE>hX1)F%ArgG?Y9JAZenIKd~SJFb+g5-8`i zBUMUNW-ArR#tZp`3c~-ovy#6b#TsL&KYniwW*#TVUfrSj~ zq7x`=l)INsv#qep{MW>=-m@~r*UfR^ID@8KRivLB%Fg+JnVBV(6CDsZmx?9B25^pOqHZNAJcoOER03%4j0on6+4mX40o3b_6g%`KzS@o4i!d zLG}%V3t&;CTyW9)6LIu>WekybI0x)NlsMC5%rh5TDJ|FzEqi5b>`ER=4veDbC+V5r zc%=+}^mHjtNaB?th%)r^mavOYNe*K;o@X>9(W=T@<#6*qHr~sFTN<;jB>0BHGI}R? zdZqMA9kf*+6+qqUq64S|QW8M1FYEez`koVyhddv&8qe8U*t6PX9WI=y4iHIRU zlEP3Ni4bFrGlzlIDEtxTeKrh1jj5^(^OdM%_OvhHfSjXnlqBOie1kp_Zo5jlbLVQ- zH)xqZW<9eM26lGBpGKRGOa+Edgq)0&oLa8sHk<;;6wyL*0B$I916#Y(9oBw$#&KzN z8oC3)@M#V;E19DBwd5z>?G8=0ihsHpwYEmXFR4LKL*92Eu|+wy>;4xfm`;u4>w|4~ zyDF2={qcMM;4?eWk1|B5Ct{tlZ3O=!_0Nt9?5l1KeX=2<*siE=Y2DKP^zyVdvQid2 zzlZg_k~pM3vl3quT5V@smtjoRo{8{kO&Eu=me5irWFEQmqqH|;0ssIY07*naRL~T^ zv~g_bcsMDqxaLEfR0J(KDzT1jTnihRROHN&RECYIungkwZ0y>O?-%fE5Ale1TzNB_PT3%@dfaqQ=Ky*toExS7OFtG6y#fqfP64 znOMw?z}^5)AKt{R?6G8WRe{S5_dL|zfLac0C{kI!_>FoWEQ&bYh*9Ir(eGVei(on_ z3I5Yy4%Y$D>tZH@^vdE$pw~puf~79L0K6!gESu!jwQLtTDRxL=)4juot%kAJ%H`S^ zRv<<6NDMQPF}#-LFq)XBLQYunb@oa?4}qbEA*A>O(=WVX42GJ`L^vJsYd|D;g%WRi zVzIIFU3DU=1AzH*CGB8b*CK3Jw9-(n5syZkS$C|3d2v9$g97Uo^n<9lOo|n_I*_k7 z0XNUfqbn}}@)MV7gH%X{*e3m79<3F}Uc8Hg>egr0=7}-kTYaqypP%$|ZFB62!_Fq?qjoWnm#KKxHVxg>;RNUc( zLJQ|FSfu5rbE&uhzOifdb2<@oqV-dr&)HLf9gAal69HMML1sjdNutEX$IgV3pmjF6;0ZmfxX2%Xflhk=K|nX_9KQ}N-ZSjr;sDzaiT{;MdmWvV|bYzqFVPc>8-hN zCPYWr2iAdxp7bMZ_Ouz^GEY^l9jOajsRlobP6*+u+NFP+PDrLZ!2&rGSt73d;GjU? z?VO4JYZ+^5;=S5p*$0V58YMrCt4m59^32y9I#Sya7diuqEA&P~0W%w3Ywb-L24tvsVdqTL&ochy zb-7RbnD>?5?Ps4H-N5hO!~PHj$v-1J2WP^2B-E%4=P((EzjYv<^|-eFbtq8~5tNF1 zGNHh@#RSGAjLUpBH>8ukuCm+K&O=G4kjwe4Zx@mez@JR?>gjCXiIU zsg>3J!c|UV6qQ&hD~%M4fsf7ia?K}Ak-?yzr;& zI4n*C2i+*?`B4GL>8VHwgFHuRt9vLY;yP{pyb1^UPp;|BZ*hn zX^F|&2tY0*tquWYTQS3=DpR_CF<(OaZR(l&4QQl#z}U41m6U@F)UE99StU!?S9$Pr zw!{7B?_<;eAs{?gR}^=2d(Vk;!0N}npO3BDNW-Wz%SsAF&AEcXSaY=apf$=L& zx&V8j7QoEcp{O*NFvxr&<<*65N%-Q}3Umh!EoYv2$Vtx6gLAj3f$vDLeaKx&y?$T$ zzRf`|3)Xq`Dzfs4O(26qrM?)*<({K&toyvth+vE=+qO_JH7d|HWhO;vDy7)H+R(}_ zvH4tlO%89QR)oYtp$%$bsV(`wM+Hp+<{wsSLeB(Gt{!C=i-p0wW*HUs78DZPB2c%) z!p@fS7p>>w3Y~|9O|_y$Hj9Z>@iI_}?PNS?@#)xT#4@P!`JsoH3>k`5@3f>cm!!=J z>6mzpbkOSyhfbYlb})iNimMH89E_Hp@yMsn)_$n8GI_O?~;<)K`1pxKS3I9{uXKE*s>u1^?3;M>()_ zP|Ahvyw*@FtxTe3nROF63EF&lr5JV3*o{4jo@uvpyTeS1o>8r5R-hOc|FUW7Qzrt1 zT9y#L&)x`)!YsP*|KG>|6$uxP!#)VvC8;98K3Kh(M>-lB_Z5GlK73##Ux;ZY*rHPq zaaAE~bHx#7gjWzkTj(oNd)L54qJ>P3=U&FEdWBJUA_By1;#u3UxiD7<#PP+A3~ zw@hZMbOv7;R9m$ed`;CD@Fq?G*CvRws@PgEOgjq#;)A8ATu_nfAaK^ql?c;nn}9^) zM{-VtXA7Iq*y&LXOEza-J5t+pS@`MNdAq|`NZ0a1f8N`E0Bo|=VDQ+DZ{HR{^;JBFcECBESn`Ml@oqnC@)Cfm5@0_sAPUA9;&u^Pk7 zVv|R&DP`DQ0bSIBefq>)b4OxnnRZejj>HUbf%DH}^#={jv1nL~NG#!fWWE7q* zAOozdd=74_#4wRsepf0V@o_B8&a`B@jPk+;Sm;hf#D-5d!@AlI;JJsW44I0hWs_n% z%-5+HGR7f?3GHW--_!}=Nn8Tj4v0my3*%9C3h>E;%^u;NeiH zvvru6P+gRGz5;8>FfEUzm$0#7Ls00_s!3~oFE>peti&uNEq6<=R;lM*7kT~Cv`YE? zPEr5h*chism-OOVmLH}`S;#pBYW?RtpYV=*8~fk z09VB7grb-Bjv!CV+n$apJ6HCf-nWGqK0V$AO@vx0h~7u8Nmu6QBYHGXG0ag!RHq|> z@(f1;&?j}xKJOeaKjR6$FZc@eovMa~Ee%RMBb2X{b|k$JB9YN~<8g*ytCXfA&F9%7 zK}%+G7B8~3=7DPqFM%j!{+w=jtN?Bo!W`l8?OTaU#mK;HULW%pf_IQoKsk^=uyFKj zN*d-*oe9oQxMXN&S9Bp53xdW1xs&0HECFqOm(!p0VMrkXh!s*)8cdzWwR!0FS zaJ^|jG#rKmCA-xirn0w29G8brL=!3bWFI+pkl)n~s$y^$mWjENj>K$PJ|ey9+=34c zD0!Tsvh+S&?@$eAA~&3iP3Ia|1VgG5A<&d7&*5B!o{?6@Dzbx3G_u<#3*$X*AEQTVbgNNZ;QJU_Vj3IL9m=mo@;np4r;u{l4sskW>$`=4M4=bth z1GM$wYka5-G0lnO>gf#S+9*`6vc{#};|b?MQueAN;Wa0ml8iTYXs0x0)OCU;(srQ@ z-S^WY=*ZHDw7c_>&Nyru^IEcwv2iC`9=0ROs_Ws*R}L5I^tOYX2##-wmrbj-XCDC2 zqHZr82q|DP=SC)P*?~~yxLzso4~{Ef0lOz%KCY}N4qLA%jjp@an0SaOMbdc1;a`wY z4{m@#J%3k*pRm?tcPl#iZ}U<8)p>8Td6wp`f#HO$b3g> z2JF5xGpzoVIy3>G24MBYB24PACGTmdLzwV0LHC=AG zK(>h0#YAuf$i{6NK!{eP1Kteb&FMF0D0TnLqL#RMPK}@h+-3xy-RAyi2oJG2b)(YR zdA&FiS>I}8l68>d61G{aF+cDRYz}r$lwB zgK=NrS_{$dS1=LjS!Eh$e0R+9afO5-2j-K({avpPO23*;M}}!wkQR8QEli=71g50p zc}qj%@2HTB!v0K1suPhD1&{VDJ@Zu5D|f@7Aqb2c2@AJSZ7I^4Pj#aV7%`361WURW z2HjLNX652S?qI1wt8yp;1U2d`Jl#uOu>6@*c8%F}pQ5FOAVD^-4)WBr-YV9(Z)$4vwY}?9C2QeWB81iWrt7lJLf>{j! z*Z6KG9xd(IxtoS1iORD4_S{<{=gP!TCNAS9kCT_~@W9SQk1w9VC~CY16bfhA-28f; zQ&vsj0E834`YUq8js%_?l`k4nB(I$h1qfTF9!>-~COkZBe!tP3rQE8~RFbv4Uyq2w z#OJ`knW$v|O^Unt3BsYq53tf8aL*0h$CB$xy^0c^>kZm89jIa^j;@Xxrh35!ioSS_@y_=6iE_?!NF<&3O_9M*Zs z+uqvdGb-Ch+y?<)Xt>CpEbNP4RYP3j`O7e@d9#uuAJCDp z3MqoH@gjNE^33D17b>B&I8miJ4pAFEF1R`r5SC^UYmPVCv~vP?u`F+y=TKw)|IzlQ z3y!le+NeZo=Kinu>oPh&v^^3cN%wok-6>oeHX=+!T!_VCb-I)pPCDsZA~xSMu`V4E z6v8L`VQ{(8x^XW9I1+2o5;^Kl<2PLtf%3EwFw@azBI5pApP#!EaVk#~+EU3XJHYyj z$qh|5<0?LOSd)Ks$t~QJOBlq&godfgzZ~Na`t*_WPB)UkDw*4C(<0*SM!F;n;6Oy! z5d?G>gE>U8WYZ5%(9z4F>S|1K!bwK6X~g^Abd*w=QW_hc7C<5>C$UJB!+Sjr^W)#d zz0+mHk?Pm3a{?`9^m|@*0fL&N%d}>&g^wla&=ACV+v1G5GEn6Fm4-oar0hMR&Tu|N z{9xMz(A97fX<#5GQCtVG9PZ9&#lc6JG&mC708FFOXYoSgbR?705s~vUz?}`D?7WB^ z@$&TrbsVDG-xoLs&h;}$`Og0C|nrNBrGw=f6+7tSsDE}QIvgJ3R`t|!PtoE<#t$H3&Ivsnzv?`Unf~c&1q5^J{U?Y*Ebef} z{k|zAQ!75`lE)_0>lmWAsK~@j5L$0i8lW+zaceg4`6&R(2~xd|R#qn!7cplWOre_a zA)?&<=)iO050^9b@WElO;Cq!`?nLK|B<7BUIt>1Cxm*T-;b6^zUt&J1k@%yJVT_sb zH*q#GJ~oeFi3VYwu*B{()<9_C{vrtIkVn03-U5H2V7MZ5MZ#lqIv8W&9fk=`0wXox zF+*i=Ah5ECLw(RpF}wmC=;x*;3SDprkWAS>Zq;Fo{SkZXCRnlqZ5j4tlq#E(A}~WL zzO=*~6sa>1&+}{dCr)OH*@9$N*O_?a3Vr+cAAVMv@1v=qU-$Kf!N3|z%+RyuYirW%gD6zJ-dv~Wku1~5l%#T zS>9g#-=%gB;3LrRVH|OlyHlC=bZ{V+RmjWm1smqXoix`G3ukd!Taf&q5AlxaP5}e> z=8Cg$6gb~S{h^zy%qzX&^n`M%bJkW0Pd>|a&;(DYUAjCIA8*F2{?Q=GlAt}wdWEigFsS$Bafal0W*$r z$s@L^;yN6ppkq4jed*daOO)!2gqc-`UX}6`^5>v|dUso*zvxPMr7w-SKSF6?LD6HRlvVYLCn8wsNTID zJ~CB}7Ahl9IYb7Ej_B=Dk8p6C63FH$k{H%;eG~_U2IzeFAmeL~o+I}$vL)Vu(4Hnf z-*m}G82UshI;U<-9r?@{blhQH1d6i|I{3lbR?*az2J11Nl%t(mKPVJ{r_4qO%t~N0 z*3uamPyn~Cin2*Z{x|Km*?KtMHI_Eveu?TxR7DB6@}3+NaYiaVh}7ALzq*PT93>Hf zIX%EoiwYhhNQK5S}jL2N~A&)?8QCF^4@yFW}O+yKFf6r}SF`u3R&Wl?M3e zTbzy3XHVbgI_hSlW5C@AN6O^WnK;`&U8ie-228ylVureL548i2b~Et;$n|Q&$w3T1 z7{T$vN8pCa;)O)mKZYc}o>dCTs1V_*(8Nv^DVy^my)SRV4#|!|8C}OkPb>v77s5U8 zP!UfQ%b#%X1Y)?zH+s`4UOz)Cj>>4#|Cu-b4zmCqMPFUev4z?=6|u{9P%LFeqZi;r z8p;btpUpTkx?y75Q@e=$>)4G!b97V-O*XAfuK^H*fD^}gRB=_t?FDFJZb_pbK~S-H zS|-|V1f&i;s|A`xCo94RlX&4Bd=&dqej%R`cI(4f;?fyLD1_!W1m!%HDn4mrF_SDN z5nZaZ){BX(IIYuWup>-EySua`cr7cDptAZaq`Pj-HRcyEbi zOM1-fw*3-2oSE}0(Qmrr!&Q?gKk4#8ro~H_Zmo0qU>bqC)N2DgYPhrJeZA=Q^P<=O zq4jLqyuo0%TDzTwcURO@^W@9~#%KM+K0<4<;4s+Jfk>LaShAgu117^)C~#Dh4pQm~ zeMAl0gnk6Ou${1z&qp6d4K4>M|8yQYG<;Jq2(IC%*vLXQ#$$E)NBiu)7SsR!@Bh-z z&;QWt^+T`Mimi>6W?4XXmEEcMF z`ee}VjW%XOSujDRr)nCsCaWXk1{D5EUwl&Dkbin-Viw5nQ-S~GI`!0Cn|uy;9E2^C z8_I8$aEp8Ehxt1=lGWRRvq6Esqg+jIIcm{e4(0Sg$csZSVvdkyce+avlkzaD;f9B! zhT*~tQt^(UxB(Fk`@Ed*Js~sYrcXZP0$YPz_J(2Lqebk4gkT3s>Rw;c{4-R0%0jCQ zDB@^BmyZ!a|y$lgL(Vz5)`%kp0964bdf#X6mO3$$-Tp%wDl>ILtcx0}ko`{_p?L|NPJY(9h408S%?>hdIv6J{%G_B`OA6(eimk z_n|Z4eZot5^RHkmRT8p$QZ`^Wr=b(2>f|LW!Gj*1r&Sc!eg}0!0 zyIj-PAP>Z>%VGw#VNkwzf6mfUxpK+VA;?<4Ac5thudMJD7}=wZrc32FD(dmjikn$g z(xJRcz>S$Y!!i^3F@1h+c{H&;r?A(K-6ZsiCka8SvejoLJZlAp zv+6(*LeSliDWOZpTD+!w#*;Fz7$Ds2HV(#Mnm3Zw zs0vsZ?j$x%tUq@mXfZ7!dYLYNEz*yhEuyuAUdyqo?|la1FpY3ycmgHFI@Az3x9%VsF{c02j>a#7RIuqJWAOLHbyIY)bAhaO#n7@ zdD;+D!QGK90Af2(*TyUE1(!xh!!COqQ#zuaqUahZH+X59mALgSGI@s)+wN_^nM9Pu zsW(DK$6f|~Q)VQ12uB_5UD;R35+lmhtN|rWlxaBEZufs-J<7>3sdiBr=F0*z0UaRR z5w0EE`wul@ZF_0}Z^Lwr{2qkWNWcJ#8kq|5A~q3{`nK0~dsU&5NXG5wAUn3HQE3tZB&3E?_~h77#3lw0wHwf9{~6vXM!+SKiMexFP__SDBo*qm8UBlDvCxZ{h#nHsQJgIlGZM>dUK3hho$crGe<-e4XvSStK2i%~mRoL~$rI zG|5^i1=SW*yP(Of&>h|$nDsae6?krgDv1w=yJwpe6HyuU$8dq&@-C>8nSOqL=*Q^5 z9SN^^?+r3rXE2zSp7X&tvqOjRgtFUtf}!7?{$8&a{ovB3;vCl_#1kh~pB32`15%y( za)$Tp=d*9zfzY-<7;KQj7-6enAJ(gvnYg;^j*|vH=$S}z5Wt*Q{QYFv{N=@CuqEN+ zCAX)0|4s2*gxvD%uJgC+boZ#6vDqmIOSZ4j7P!N<#rB z*DD20!@txxZqHN=q&SVyc>S*~kn2%L7za6klY;^0S*?ur0_YoIEN~D8II|7Q)Q@48kJ>`36mm2rJ3+3`& zpo1ib%}t)1i*QWYquo}drB zd#i+m*p}|Bg`=K7Ia7f~OBgQtwKPX_7(!r_KU-iXqW;|YmfDERB_Seig9xahe2JIC zs_p6qm-S=JqS!1R;0F!4a3uEDZw3e)S?g^9Lkj!a`@a~{{+A2%ke5sk@Tu4jrH|!t zDKD^fF~V{`mfmsg@@*7ymX1|HM{I$WTi8X$Boni|>O6tcZFnFk_b85lpNv++?m=52 zky`MM2L0>jCuRX~7S1y#Dw-tVsXC5qo zyv@Es@OnAXr_k@cjxIC&DOdsC`z+k4qlC&VEe&l5x!c-bBVB`5#$Q?ZZ0sFFuSxXl@4NBYl!Vf^GOPhYc@JL$Eq7xrJV8(=wf}?fdwq|fT zdd91$j3E`09By!B!ttL>&TzD7nH3qJutNUHiTKJ8yy@&wVGQNI3*P}PP9E|GmM|)c zsV*b=lFZJ3fX-lt=D*vdNMZFQ0-gfuD`(+<|EMOBpoAkMkm9H%$ag)@}hJH%q`jRuJ7L z)JGh=FSIl}rj!%j>u7uMC&7$_P#*VM1-*aV(rIN&osrl=aR398*sMca&SWzbzDIzU zj*jNiCPzu0e&n0|_s;zh8}8%srq4==o`*vFkTj&FA&SU0M^*0G*E$_nSlmt+}C ztg}1o^`h6_^z-whxLoc??0Wj0Z@_k8Uz7qJBgU@CgUw4k_G$bX(sKKO@<)6*pB?0t z4k#)wH2f*6r=#GAYLSxxK{!Z4@Lch5C=@S0?%c`1WU)GpqX>dK*g3+Ty;zx zGXTARZyEdJT|c9G!}6vXiAm3w{^onSBmR?ZQ4Bz7jDxxFlQ#P14hfLyicMBp#*#Q=*^b4M++c!l&%o~lzev`OgT1cFk)_k!&(?$ zx{{0zD;R^tP;l6cxT2R0U9rqb+<+HaYw4yyVfzBG=;eFM(5oC7a}uO za#QD8Ke6eWU$CSJHY*24Vu=rh6H)d@?CL;FPQ+VP>$s9O%St_vI0$}$rA=kCwHtwy zFh4t&D|x5H(Xa8H3${ZHBxfb??le*yhHmVmL7H@y@f&0R(yneuI8VU4Y?Ub_;_O!k91U@j%&dfrKw3sx?l-bfle1atEK) zx{3oVSQZtEO{=BwbW{ck+xx~|M5Z=8tv`mDP?EkC-x z4Y1o@i%P&P4`+M<>y)4W01>?JZJz9acjbNy3&;R!wBPGs*rQOIJJ-txex~pUQ3)0M zLv%EsaUdvWm`{3-GRS2UXIg86b7L9w;N+J&Q^Td{r#0YqA`UVM#N;52K(^@F5lyW& z#&;E$$=5YaEfz51`hZd{;%tyVGcoyDwMNBr&IH}mbjSg@Gc*5j`kuT}G1Lus@ zL9h9(CpZbqN5I&o-bM7dOOY4oFbQSs#*^3w$%u40(tC>IpO2#`aP9QX0qB zNPxWbTvZ%2&J(=FAsY9H*L+`N55ZwIM!kPUE7hDWdJP5M)CQ4jJI`wpm(XHRB4YgN zaX32_rzSo55jZ*EFveky<0RSFXmf5X&AOFGciWQ_<=Zi@5>7-L!4KzykoBWAt$}4W zMk@LfCrZ4Bk-eDfcQ6h^s*a>-8F_T9ynZa2s}m8k5tiQ+V>J0ip2I0%2xq-m3Ab`fo=A_5n5R9=ty-71 zJmfdZo_Oc!eemTXkczaEjN?L>G}3sLjh@ccZmTR%V>G;M3DfHIo01Os!kw6Na)GmA zhdo#K-aTH&~;mN~qpv!WYPMo~CdNuFx^vRieUkb+E!ae;I z{%_YOA2XMve$r#jav91+LqETzbgek(^pi6j<(kYm2i^q43@*oZIfE-vq?BCg?5~W5 zuIB#pl`|6G(95OrLI36jZS2L4=_eN|aGh}n>5G8TJp;72?%6++ zwB97?N+T4vhXDtlF0R2KGpS{X;{#5~%0Hcj-b<18Lzjy6P|6kw!2BJy!>!{<0k4 zZA#-!){9=oO3Vws(ULy`qY;hVtDzqXE9GPI=ex_5ZmnZ6!Hk6Cq2{YjXW|Tc-{cMF zn|IDcNt^P~t@12NVO4LSogAnuvjN;Gb{QCud`EaQt9$>twJqI-McQ3c~+`GP!hKEj& zrA%1)z-VDK8etEqOvv0sXHU=c^|x2I8m||_eaLWZw*Id`+yE2obkv{2Rle~7ozxW) zQ60UAsVL8TsQ^c%uwWs9kB+%fv~A5X&Pw$1ZcRBTYK-nluubD=)Is17l9w7a=0vyx3>*g1Y>CNZX~H0}HF+xzFKmt=wA*hDS1I4# zD6nG0zGF^^OTIr+AZ3*^ryESz&r(VV^HFo7^!sq#M9SOTsQBrIst|8<;)%dv$YpHk zB;-foBxWRj_Y)t7OM|K!<7uqqcO#frQmRlGVKF-YOfwSplfF4Q9i8+HvUw;^(pfT` z0Vx-nL(+D>0H-LIWx>)WC<6DLI5qiky374>W?Hd~DQ6Qaj6yLw9z1nA6ZSfcvq;|v zN9vzS0pOUN&JxPuHiB5$w~5CTsySGZ@Z=-Jw}Bmpt;Li&>3DlL2(AXNkd0z;8Q@`` zbr|$Rk=QcC9e>Z9w;9)4OMsUd89@y$lTf5^4Y4 zxT;rbW7NwtT%UBvzg?%^yICDjG4cNw)@OLUEm_m-K=Q}EHLiFrioQDl@?mRpj_ACgQkxen{7qz1SjGL1U zX6H?J7}R-qiUUy`3WHIXJLN2+G}2N3B zZXD#WA&P5!HiAnyGoUQMZ@x^1JXR+qAvf9ES{EawW;hg^Aq^0LyYmj>7=g?BGk|^Z z>1q9iW&o$v#e=tySJ7+bB)1$qOkjo0k%fHT9fBTzk(1x|2el#p;j)7B3fStqk(k_CNHN#hvz9 z!s2yIGr;dIuP63U^mg$0VD>~br|8WyY*L8_I(Z8nB>E!Z+3VdZno{69!50vd@&D10 zsFi%j8hU-l9+|eLpNYH@lNmrbT@XqJgdr%eG^Swr0&IND{S#iKc%fC7&GM#&&o)FE zk`IiGN@T}$${{P6dgoVB+D(-r+l)s$e^}kcbw=hV0Xt=!QsFtULz2EqUB&$5dzhs%ZEKWbJ7>X11eb3*6L~I|n_k zuQz{tot`N1j9a34wvNjH#ys$eE!KbwAWKLk1w?Y@ncnTZyyV$he_2>TH; zk!>b+m}8$!a~jIC?V)g5b9f1rkPFE$%>4&+*4|z| zFQ)A{0f!6W?|mI~!)WZUST@-AX)q9XjIO&(EVwxhf~*6}hqe`1tMVUhoHyEaTGoW| z6|E`lomR;Wl3?%q>|w21orMlu4o>z?KzZV6(}755qS7Hj+Ue>}BjNqyW&9rUzPQl$ zY$5(#=Navo!{EGD`o%kO3IoOXa|(AK82vW%`Tt}>oK z4E&UG|LywTiMZsaa=y^pv~_Im*0wVa_0a5moX!K*cWYPb+GejDsXkw09~OduhZF>A zw=mifT3VqJu5n}Ke-jU{&m_sGmCNuwHp_W9^McX=9VqHZ^ak`QJ~j}hVs0ZO*{~S{ zbHfMmBk&90E`ks=Lfu%Wfnbg(3lNP)#m#Df5jXXK!J|(4EuspA+@SZfT=VKzCout; zNjR3$dMk`oIpFAcO5?5n5T+AEjK)ofVn#nNR>N&=S|YUfL%e;X?Nfxo-cO4IxsB6CrNsQ5s+_3XnDX5gR5GoIs|13Z;KT=44bT z*|p4JoFF)Ey5BMrdoHvS!=3XvT-b9Vj1{kaKpVK)p zpK1)7GnP^4&}cfG;Ip=H>}eP!)`CFuof@#`5CU8dWgW0$(I2nx3`vCMFsTO_E3R{6 zhWlzJS`m|>{I{?*NdMY#$i67_TT=LkS2gLO3L%b%_y2Nr=iFyI(su^=gcX(<32Jow zq0SHe<(Q~R&TpPfWmbEl)-??v4h8)S*`DFI0z>NKhr)%3e*TKz;C{fyaz}pXOFj_M zaWZ+n5i?1dP)Hz%*%%lO<7NEkiXDvJI#QPRSVs*~IE-_Xa_*9#QJu=$>z^+nijRR6 zDr4OAi!V$Iz!#g-kf^ajRsmGp-RZY8bc??)Ft-8 zAb|10*LRumM$}Dpypuj|SB-@fqUk-&Fnk`>Q{km4K0q_~;rhTBJ;X>zun2 zq5Eb?X`hilt21$Kw9Z+ua3YYu;a{SoIu6CLAfosHqd2Y*Z$)!a2!PHnU})neGBj5h z@^dDLs<2;!24jGuI}N83QAY!N7?iXdi0~`aVtLBUM58$z4HI(SwP%#!=qQ1qoFF#i z4dcq-PEE^{{l3Rpg_EzZBJpP64@OuWgLK*F?XHf*VE_*GeA3whKg`hOBRY5A6db+- z3Ozt$I%Rnbb1#5J;OpUETzu<$cSAnu1JL#ZV+;A6u18sfVp` zYvzA+9167mY{6$fkr}3-<4YCaIuj1#t=(sIg{_xUc-I{>7#*pzuHWJM=1{n-^1m*B zaCQaD&~&~`N}%LQRnv!&|D`9dt&?{zTRQ0x7?LCYSlZN+eBF?b2~)uLws3iSsEM(R zw_q3zA>N|HxkG@G28;~TLHUPgy7O?1%s~^2 zP%M3c@Lx0!4l#y=e1oEixT9E^<1bnK;UL)|Yo*HGj=8@<9!A8>_og`gy*YXzs{ud} ziW8Fdv+4KuX%^Ocs>jo$^zK6Cmx;$S2BKgp@nsb|k$x{^Cx9Bhkta*5Htzju2e3 zGC32+evE)K@u(kxG*v31VQ+BZ54f9Akg|3jYRbBRzgybMexJr1qqN~A%9@!_-s$W# z;7><_s2W9obB(!rWEp^I?+TsKK`Uk82u|h__~uQY+tKQn{KJ`f(%~0Y%~$r`m$>?m zcKSCqSaldD$?=Km{x7e0O6&7A%*DJ-{T)1)H(wa~pO$Ua!NH81%lcT|oDcGU0(rDY zp^Sg)ozoV*gYl_!=iy`CggmzD>H7ZXD;6?S?RpAPkF7pzm^^o>-#ETIKw|| zxWztLN9xtD$uVOLhK1EQoU>^q?mKoaoMH$RK7|AxJ0?U$(H<6Uzi>nqE9x*Db^sb8 zX9ZnYrZNY<_Hsx5=D7J+u-)m^JuOVM5l)GZzU9eH#qiBq2J%%SURUCt)=6znCTTWWI~J1Zt zdAyE~(z(HQ_EnS3oLtsMiqS$7u)NSkQIWR|mS{(nwnco! z`;0GiQN$fA1C@xX^$l9OebaG}Xg#jVNC03r#W=Vb5e2FDj%=E!A;Q@qw;8l=4R|10%3Tv7_d2`^v=+&T)c5Z z7#>QZbb4(Dp(9e+I?e2X)k}Dikd-r<6dK6%R78hj`u>Wt2VNQPJ?t@c?w&||MnX|G zW$Az)e0!_^gdSqJ5DvF4IB|K#Rnh@#d{SsoYIfu|oYET+pgoQcq> zyGfv^_B-j_VL;*SBY-!7Uic=h7hvHO#)s~6!tW#CTZlOiHgIDljD6VjOo$r}Ca_V? z{BpIA;D>?YAHQ;E-8WP}4?VxX^gOzZ>UnEJ7AalsPR> z%&Nt#;n-hw^dH;d_3IbAEq=9QV1-6ShlaiydP(ysP%7Q~XmTVn=OX-Yp%@_+pv#zz z@OYxZahSB8Jqy$6>vPZ<(q5%k=QH2CkTu~wt4}!=Wg>wOwqyAnu%qcPGWDZZ>}k66^)lh90pN; zz8NR)%KG+7Z9it6 zcRgOq$4=|B2;blmvDm{seGd=T#qdTx5SAow&r(}hF1u#HTm{lsAuY$!L&vhs!Kv~oHj&3AEd$#AyUk z5=I!(%z3c4!^(j`{xfmf9(F~ ztb}a)Ub@W;yk3ib_KVz-l(lF-JCQ8bM^*e$I!=^EcF@d;%jL$FeF1o_MeFsV^;+~= zFLfmRBYWXQ08WKSwre`j)Gm;tW>m4|?DC2H#^I^u?r-f3z4PTM?g_g#F*GYfOuY=rr$z?#$ zxWF2)2Br@W1& zJRzqBI`jNxh7avIh#xm}OS6l+l_E6Pt#LoGjK3x8U`{Mq1ZmFzy13g`y-enmNf0x zE59MJ0A_M$f@4OY_eb!L-vUKkm4r|@F6(fTUg}WT(k3=%N?}NznH3v{f$koIa2ly$ zCpbNl%Nq{*%zKlpF#319oF>8*PIeARqdq2xy_6xz6ImX%chorKwc^ZK0%B?&>AUn} z&Up5dg{tw6+ULZ?!81cRg`bx{0E1KBPWDW(F#2%I!#}fH(tvKa@<>7QHI+kS2hcgmU=`HC1_tc)2CJ-&Cx~i*y zt^{^P#@w%%=0^}1N&tfGARZ;hkQxxH710SXH=icKiaQLOZ8eihcG>7e_)-fBM}mlG zlVsmJq%itg5u4#8kbx)$mWUsx(#RQ-nm@*o%jn@Ikp&}r`6D4W$r7E2Yr`wWOu{Rb z5`J|UKPDy_=VdZ6y?h3TIgVsa!^~SLXTRYU&pfES{6=kg4XZ!p4$QEtTauQl()J6G5CIwKM5uhW@WFEG6Adj!kZ zXFH}u^0-$&87gKa{>0{MZ_i?NJYQ=Og)^~e^CH~D9k^&Zu#B2{yrf(RMP;2*mSg!+ zt#FofMgnOymp0)^P+buVB~80ip%MT;kXCq(GhfOdG>FjX$MAghnd+jefrYT%u7q;7 zq0VgFN13NlS1dC%-si2XE-6!{wc?J{GfMb?>u@6IT)%$|7+mmuD;Jkn5}92=lKdvw z{~v9}ZV`tPAluI8MjrAhUuPux%tY-^FueZ3nC;iUI}u;kK#lp|;uAO%ff!QG=G>>N zn$})Iv3M@|{_yY0% zZfZ+2TyV6_fzEsFfa++Roimq^%atM>V>&9rwgXv83rQ^TK@pGEPPVXj=+JJhXUFDK z(P3&LS>Y_GAx+^(#0aCm7q3rR!4-Ce8#{Lhb8TZ80q{1sx64Gh0j~CVa~|M%%eG@$ zvm!L&18S>#t)=-F6PshQ;zME&J&)Ea57}nj9g;wce5pesOg6WX25xNJwicoTFz`Xj zd}nvCicolQ!#wT_CbUW177K9oQWUEt0){^P~OuNBLKO1b7(Zl96(^M`)_{GmTKBk?@`k;AQZ*}k0D zYZ1}QHfe8geiBC^=KOd^P;@yf!9Xe!2AmUk-5#Jp@q;`Mq(x=0V5EpT{5&VuGq z)h>=pn3#NU!<9xJR#BH~hF&RhfU1H&0*z1_bp)Ant+(VZvjGJBKrzyOtL^?IH1o+D zLkkH1##>kqx948!7@mw-psV8=EbPOH2%Y14CCe?NtwZsl%RBEAfz0CI@1TvcvD$eN zzw6@9x8+ULD!O0u+tx=D{MTF`OvR3ao}RA{XKkMd>8o-q#We|9OsJpkReY}P^EJ`` zX9fUpK##we;HU!^`v0`?YAfq^I6U0rJnaDk!o`+GQhZ-qdXPfhT%UDAnh$tSc9ofc zL3Zoxy=hL#^yMVZPekWs!E>dZ0k{IpC2j9;_RZF2HzCV9xVcWt;$S5W2aVx}G}z-7gbmG2$liCe5@X#T-U)W~gx|3MX)h+> zXben~X~3IY;{WxkefSA09=bckJcR!30-IwZ`WAK(7Cx!lRh0A*kb%v{{k`eW zZ)PT#I?atuIKWO&p#MARP_?%T3~A~dSVq}-RxVf|xvi(H?RFp7V1n+khr!M(6@wCp zC9aeMo7{eHuNzJ!kaB!S;%liK@FaTQ<*e=O7SrU5erg>WEB^SYJ3n8=81%RztWlBF z1ZZ+5tq2kM2~KkUfKXVZ;HfwiQccku)uR}#BGC=q`NHcbHNu%`Z`}+k#I!flVxi5t zKOsNdF%+OkBFh!rrgfi(U`alwJYlK>y|J900Z!S18=ha={F?_WxXZ%8D6Nc2Ng%ZXz=83e&fmHFmE zQfVR~mwnYA9s_%mQD`s~{bosGpn{q~X$&W3{*a@gzl)F9)f8#_fM zXIv0+DofmtFfC~sX|`QM>Pwa{h#e8!Xz*H^^pdTO%s^|W0O`8(`m!EvZ6hgJfUCSDe|I= z-$6GEIX(heR{D6&7W8^d9{zm9j2lMqcuUS_@!*z z?p9ALCr9a1psT{Jb=6rLbRu+dM=Vz=PKAFwOP|rG3Nu(J45U1H#Pe&#Za6z2-rw7d zn?*u3rdu%vg3w}Bx=0=k% zAP?>>w3p3V_-i+VT=DyUmC{$P$ovH;YCcjn!R%is$yv3*Httx7!@Ni+oCrKBQ@)i# z$K_&a0^+cKEXN?2JsTK(S-d%_oHoEawVXJ;%M7Psk(M{JnmvG$$LZgf!s*8Ay&rn^ zWAC%1Y)=Z0q(y&%!HnYd0{l|tpBwb(fNOozozX5+~i0fr4$FjNxFyo>H%~9%QClYO^uMh zXj5&S_vB#&9*t6-j#C@Eq$w)hHB+tY->x$!zkmHjVkx(L`x(klo8bF(thVSd92Mm2 zl%}7Zh`)sk06IY^WfkT1DeI+-)7lve1JmJtW!`Vh?gRR;Kka^)x9=3vTt}CG9(ikq znoFnF&l!n8gd0ik0SM)GNpU0Weu5JcT`B+5g^FqH#8VXXk;egSpIM^P=|j1$G&)Xw z`q>Lp!?rF3B0J?Me?l>hRWz=ZWmZ;>!f)CzB41`C9CU#bT}X(`Y4GDy-GOjJ$ItoS zwoie4c}T;>c?~N4M2ez=$rMZOEg*s^@oiv=)TJ#xJK=b-P8YI|)rmS0@p}2#K8I6* zeV0A?<|sKxMLh*tp#ves2`0@rJ`RYoxWalJXlHxh)Yz{-n z^uL5F^uwLwPe9&+c%-^5^ZeQc5K0Gnto~dFK~z-^nzLo^0fQj9Dhv1!3~#oG--N!y#5Y1J-@vSTLV^`a$0 zON3sc-zsn%MLWpWwc9B@i#PGZ6dM7J6PQ*qN?}@G+TnET?gdw%39=!~P+m1SKbSnt z*mLq7bvLyaJVm~_&|<~jGmBB{uS%mk18mIbvuSx(nxyX3p3RJss}qsVE8dl^)1VE2 zgQarTL8z8j^Q4m!JYzpSV+?4|g(vhmB4kuzr&V;)J&e5F_VA2KTT+os>dTiCqPQy? zw~tDkE;U0c4WRE%>%D-BBj6;4qmPAAieqAYRw~Ipz8Non6Z_3|vtLhx^<5pKSrD=* zx~BDI4_z@1Dx}lMZHdTP1|QE!hlhrb`t)8+sNfNk`(-ww*F*36tk?O$aCb6qc&JW; z{;4#Gz?g2fFS*B(KDSRWOFTQ{&%O4cq5pn$WpljvD=*@|!SP1mmAiH2cIb9Q zyUy7V!G{^PDEfVS)24w;R59HLW9qTeBfymQGnCXG@zVoNlBMpj1K@b?i6L7CcuO9_CUvMik>fDZ~zBu`nM4CwnLq4iB5AO4t%&VB>NbF z-FpYT(brP@J=U7rD3X5&Ym++?b!1m!MnVb^rI&gdA9x9+Fz9^G#I!_WGdkBlO2{@F zA+J{+^$N$rdc8tsAeuAe?ewn(`)1$;n~YrPp)!&t2x^PmN`vPx4zmxDoG`0UH!O)t zL-|*1dRYJF#`y^74L%nsv{vl-=YA7eB;%HoXV1%X{6|=!{7v3NKE-V4gsx4 zWoDkqaCUp&`5Nh?8&PE$frlGU);uUUD<4Pf#M9t}bQsb&tM`D<47ilZrk~jOzCN3mpstH-7gb zb17#!6ZrOxfm5!7dm?UHSQN$|;Gxq6j(|_}pM7P^2x-`~D@3u#y&wXO&l;+_;rr{a zvLs1C#20)qbtKQN$jfDauWGLEMt|r?=#9_thbEl;)1+(Tze=btlgv3_+SFs-fToErzlcmiXNJ?w_`^Vkf+qx%AOj;!7`<>y*f6T)E#D-rD& z9hTxuj7$J|i$Vl?h?yEmV~?Q^d`Z_Kgh1i>+2r(kY5en$80-T5q#pppE>}n5wO%Ak zXxV8b%rET7s#FzGP z-Yg7hyZ~>=zbE2G<*}~@^Ki@RhUgakehQld>&8Ah6K}3y75^7`q|lwd+u`(VbRxh& z@ueC7X05BV;V$=X@*DZEroPEJ7(2@$;v;M4qw9=E2qvadugf(}_|d?r;?nsdM|uaT zpJ}WuPTPTRk;;$X8cJWlcq^xqS8ulrA?A1erKND|6Y=)`mF0*~C5_JS|FT4WGi&A7 zK<_AaQrw#<(t!Kx-ur-7H2TAtz*=I%5|r7Qz_8Ky2-m+|f0eK6oNrm= zpPUFN*v+cHsP`&|Le%iRJ<}yA1wYYK@mpe$rKEUU&ZHmx#YiUzCdyzm0AR1>tP^bg z1G~njalPeD*lG?3r3F#XS)Joim@L5Wnb@Xb&p}QeaKj(m$VY0rc z(vm2TS99UoL{oN9iSPCvG3kgbx0e)T3SzDbJYQ3e?l+vY^+w*lp z5zXY7S+hMmz8tR9dl;r^OcE(Q`_ejGdX$c6?UBL{;XG`(r;|{e3TgW(aK_DNBo^h2 z1laBAP!W-|o<=c+%ZxCA3+3`l+&W&maCJQ-rqoY+M=aZ^P3qLVgj~&;W8h!liICi_ z$lI(5o6yD?h+cm1jwHWp3a6=~iC(yVaxvL>JOXk!bV)!o}!1`;T{tNI;C%aTFQo6fBS}^sR@Ztx|CKtvsB_C%Pl#K1ga4<*Iue{A5m+dw^bgb@@D4&MiU%r~;p4fl1>=o`P~ef+Y9`LO*6?sp z06xoEaX^$tMl_m6LtI2?2@{d+e_%@GuLaq!ZLqeqvSCIdD@U-6m?gjVY_k#WOdO5` zGc9VcQZo1yS4a4V(cnwoCPJcj2+G;Oa52*m1|DwqggQjx`vJ_lw_`t#8l7IpqcbLZ zOPQG=A^pC@OUq=o?_03I@ujdSvN+RCGP9R)G?SvTDPMbg;!=+H)sS(qb5z)rcY=P? zDKqF!!%~DaD%na01`iA6Y=oUcw$o^LUR2ncWPP#@nregzou(5kK<7l5I6bBu#-JFS@&-H1FEms|eOB@liI=(a7tWV*~ z*7G|1gsZ!jn6@}oaGycx0$8H-bWkZ|!*w=dvK%hgH!~4)+7s%@m_vAbuCyQ2P*6KU z@;f?T!2j<0XT$Xv{5S{uP`BnREfplB!-?>uV|=UcudWX`>P|q_W6&n9DT={2@zh@e z^xvI`&v9~jI-+iZzobXWe}`czwijQkYBG*m|CityUu4R_^C?Sf-35j;(JBn-K}H%J zkdvDIY!6X;!yQU1ev${BZn{l@cy-y4%g6)on3f^eq|`^dgn zE_R$9%=#C!>%EorvvDxznMw0jTE0M-VH(ihSJ=TlfQbWOO8qN9QGE z7_NQuH&U!f0ItglKgs65y|g(3&)lA+CJx95!qVQut2aO<-G8#IZr8u&!}=$VOuXOn z{Z~ihel?nwF224*nEjAK{CpKZuygu`dzgxM#Rm)F01=Vy+*) zz!6ReyJ29Jn#7y>Qo6vpR6K(eVjhd=3ZS=fD zSeRBVoGqJ{5RiCH$X-WlbtoOPmPB$RUwk3k`^c!iJ2$;RADzj~MTSujpoeh;qpT>5 zQ%NO^5i2}^Q{p;s!uh5KS{W@r@?{7B=5WAp7VJjPeB6(POh^8snP7x?U&m~O z!KbrM9ABw^$%}lUXWHRXpZ(_sI~bD3h)*yxII(D;I}L{uQI|DITNW2p9$1@cACaKrDB+F!kqGk<@f9L|}CPkWJ!)!Gkr0i?arAA&$b zvo7tN+)5U$ZSsTTaqFgoQbLjTo%vpf|C1my#>OpoCN7`CVGx;@VvRQ zj~bwZLYVa@*Z2QGyR~<&i2xpu`K}w?1_GNW%eCxMv-jdl*!4pfECC0=(DD}gZz{~= zdNEnC(I)DXQaHpN0-ORTXfq)F@L0f9*?IL`=#mKaR0Mig*kGuE)Xdy(=@AG{UyzQYG%KY(PQ1 zP-hBz7)c5oS!q5;P(72xb_=@a#H@pz4er%j+H}1PKN~a zt8r}yE9Dv*FZBK+m(GLX1-c%&LSZX}lU%n#^ZJo5DWy0kjI8inlW}5cL;$I7G{vbRW}PJD@v4 ze_#Jt#M1#qrNZeuk}r*j2$RF%b0*T9NKmvFF+yFEJS^SGZzQ|7m_PYG@klF zlh;*s{iPvG#CbB2R~QB%`5)JX6oM(V2{7%2*_{BAC_9d4jQgmcZrbG{)Ew`b8Wf@# z5ZaClbsYLZJF~8%P611#_>%Z&S2I%kNDxSp=wdL|h14isX8bPu$5s!8QJjK)arRv` zWHLUSE#`3id@0a!!^*x9kRJZZ{87Hfp-f|Jm~Vu4LX|{=z LON)z5h^!c|ZwW1V zDagsp#KyPt|an%AZZ{s zvij?Pw^;iOx}4;QW%@p|bjA4@bqi0nitbtWD-olN%~N$&FyNiim9SPArT zfCqGvFVL_`=OKUG5L@XYjXfeX)&Yh|fz^_d^$tDLmv`JK@1zTd7C%Ne|p!MrX|bwR(M;N*r+sfNf#$l2gr0JFhiMu(Vj z#-z>!Iuz!zq@%%Ah?l;DcWThA;z)$yk6F5=)WVm2Ee)CKwlbc zr>@nw?2AwZMlie0mtFGs7|9*>36e@nlESmWzMp7>nNCo@N|Jf8bA(g zg$POc08Ns~Ir4W9+EBMUi(ZD)HR@+4%fvS|&O-Yq9N((9DaO z*3$1pJT?=ch}lHj^Kr7W2_-LD!jYv|x|dF%%|yIj;Y{dKznv|E840g{$HyJvl(H?w zfJi}qTDS=(r9w;AC~=)9*J4rHp-mi{9x3=t6$1qr!GA7W2tFitE_`chLTVQ_zvq)y#wUVUNPXcnEWA z=144qQ23HXL#DNdki!8301`|wS2BKVuHVahCuFL>s7rr0=iu%{V0z0_4mi49T0(qB z!vDCl;FU7OWz`aQ(0k-oVVOQ{1W^$FhR)xk0|^(n8#Q_B&{Ocjg$6=-*oHQm{%b9u+o1rRONLGIB zyDLwJiJ9qTaqIQ6lUB|{Rvq^82934A1N41lV-lXf#gPT|=dLjDZvD`($}KnEYf;6* zv0Gu_CHzF-@N!P@$5YC_#Peji2J_s z%QeXd51o<<Nb@{2A#At zZ+&TmyM$fy5XA>UIma zrtkIXLvv>f;QC=^Xdi6EFk^9Xx((flC@SBFGXk>yBeVfVzy>oS zVy1Uo{@4$U+&=0M7r+@^fnW|uMBCBVT27swb!V;8>I(; z0tR8WJp*-_L!$^LB3|lK5R)#oP-jeHxk{eSLqawJ?Z?CVw03@=&S!6M4@IAQEo&|P z3%*ooivvJ!%Oc`kXy6Ey=5-Sx4c6(3ff1w0L9`t82JyL~lniq-CgK=ND7W(ureE&i zIgM8YH zd=doYt}`kn#b8wKN~4f|2ym0NrN<+{!y67)4yrSEiTS|f$1hWpZ{ zQAg9zUe{}`(}Kq9bIJ zuj*Ylnp$}cUZlgmq>Een5l(Nc4@egK(w`v?ob6MNPi5C|(h$}5l?+HLh!5ALI6x;* zkYP`t;K{N0>SCLbD8%nZm7G=g3Z&lOAKBc)0ziWH&+;V9UUhyeXvh2>Yl@uOMLQ>b`^Y+_;& z8acFuWHHHRdLGWDPIky{j`Z5MKTHcSEjQy#aOJlxLYAT=0@xVa%`F^_<)Gzoo~}v{ z4d*J%{eyXZjeV1n75_5PHF6qqEQI~L1CCpEpo4qK8|U8?ED>AEYZzL{dP#dfzhOGPWvN>>-PNc~>D2xGjN4Xl#*?b8Z1eFc4ghpEn6QYh3kTp0{ z6tJ;79qI6Nv*TzN)SD_(&Uh%#pHB%%Gj80LDDpXZ&GlwzJH#DRvGdykN)yuZCh;%Kq7DV5 zMuUg-Hw)c;~GNv4CO#Cfl2C-vIH`Nc!32)nLVK`ny z6q`3!3iakhkU0=)bggte2FF52>34qJ8M-={2m6wt57{o&GR3#e_ps=4F8j_z3X*Oj*hjRC zrUM8JTbs5!l1}%)ALoTf)oFO~f-;FV?Tqt2G8j|PxsrjqQ=Zt&gXf9bfTvvndY=-e zWk{nq+9dj+K<-Al_VA{ycwpGr8T?L4Kkc_!X=C#?Tywl5CXz)&FCu;s@r(1fiRjVy z!kacLbXy+#B}_uw_{)FLT9m4t;SafEeZTyJC-z&U8+rWBb{A3joj`dTJ}L~+!C*!p zpA@A-F25O$fzDpTGE!zq9EqvrT51?ZLkgiVJh0qZ+sJ@B8A9{*>HU!6qHufkyOO6O zJ{_ty1>M1gP;Iu^fBce?UDBnV?Z&J_rS=-KQNY6;u6!C)k z!T3Q~Nb-F1D(?a(MawptMZ{P6n;++zud4f#FOCcN$UdDKQjp4D4!J`t#3ozfOmf2B zN;w*wa%^szAg*%1$QWw)t64zCdwWq2o%M>PccVPYE_RX=Q!Rrj2m3r+4A9nX#UU7J zfKsjZv_gQ(DtBC75rHGqZA7kRc|NS;q%vxKW%}D_+;Od_b6w%{9Gs0Il+%)Vnsy|x ztzGtqy$$!&Gc<%7{9K;k>crQc-;4BOd*N(o`HsXy=h4_8+S;YHeq%sB^LIih|H44s zB=H4eJ;Jk`p=$?raVs{j3(C&LI2*<6oOc&rp5FF<{&WOnUBD5b?r0d|CIax>f$jt z!VoxX?KyB)byAk?{Z?tibI`ODhdE?N zwBtLhk918b3ne2yl+){TzNrTc;H>ZTuSiz2KZw;%Nq$$Qn?`xcLoE5$-qx}La>yEg zK9UI*66p#(l=6`FKo7tG!3hJ%gce`JRlZ;wr|?lvds!?-w3~{phO*bog7^Yi4M)#n za_2|P8#=buA7KX{s!Z6RUas^Yj`s*B^@M%p;m|c!*{X5k5$_tc{kQ>O>|%Rh0Zr{Z57h3Di;;Zlt5Rx)kCu1Hw-i($i-) z2|YeyxHBaXCmB*ka{9#LV=p$Lf2Mc#U56 z+Cd|FGLMQj6v%rCt)(OO%sY&m-aqL%`e`D`ynauClXwm~MVb}SBW+ph=cTZ!W3^+S zO6gPJy>6!YM%x_W=UDa!s913Jz^&&*?Ti&9v8$;hs$Mw z{~p@>1ikO|C~d7x^4df%I%W~C*wqJeQ^=0@nI{r zu-_LGt%qc7B8PKrHLm=bx3)pHIqExq>mfWz$0-etx1hS_wNed39tj45b?$#myZS~K2aW}+o}{4qb2vv808meJpOh?m&u06XdVg|saC z%q!`7!OY&W<%5g^V>cvzMlK%Rk%1wtH2jj2o8{*|H{pySgp!~bda>?>;iu0rvrTTe zfl()E%pHB)TF(c}XkZW+7nlp0a0&p+!Z(ys*lo@JDRrQ%vGOGJ@X#*}+@r}i-jT## z;d8e~A_m^NZ8ySX*a2}|@6X*215cK}CK1xBl zX}>nCC4Xq|NBflt{5LJ{aVNst$Q%ymCO4uhD+>F5T%o;4X9AW}1&44$21moAqPL!> z9fmt?I42z(-)%~eh~yp&mIkRv$ zy_AiMa8rq_c<@1w;9q84mWjsIdcpw;M+j#}aNh>O+I6Qm8(~X>ahC95Pk@H(G0|I8jPalXgg;LAonhJ;(`^p zBMhxdgi9PY*H0`d7cH)wBpE9*IO4NtsY}eqiibEM@{dfFl)Yaf+-($SOPSp_dCHk5 z9RQ)?fc9B!ue1~NHQmQUb=)qlWkrw8=->e5ob=yk#y1}Jm^TIMXN1LCjyaxM&7ARofw1h zL$D_%()h~GKiEFNNCvN-?Wte{-f4J;U`mC-@!pAJ+Z3|Oc_v$Eeb&ph&F-zo(S6Ki z^j)4LG7%wp!Iyx2zkqwYOJ^aT7@5KDVA_sXPNOl~tjbPLg4)r?Ig!)aO&|A@|*J+$eUe(6^p`rQxxJ`er= z{_3p6W2Yn$)gP;K@t7!~M<)l#>K_LfYx*0XbT(g3`At>~fvP;k~56OeprvdoyAzDQv6L5<2mlZ~FUE zb}z9C9|a>xWL)d%i4joXkvHX}hcIHxjJorx_^@X@x}2zTIRJw)rVyc9EQ>KMBd zVZ60$?-ITP!;6`q|3sJ1%sI5o)5nc>on31STp==6e38hyJv;>fth;eC?P^^>3r3wgR zaUyur!;j5A5YZC-;F>LEdR8(o$Iv)7wkpVo<0RfbTi_!_)i^@$JdMsY@B{>m5LOqR zi*YSMVP*#0i#rU^+ZGmROTwnOcu}4(1ZXIzA!0j*(qRMv6wmoDPPbW`p7qeP9wH)I zMyNUy0r(Avf{9p-%?+amBFI3k-cW*rbirjNFk&Cg3n4||e}R+R!kfhQYgq5uNSe|v zm(7DIkQ~!6g=&;jbWr@MNn366X40a(3 z<$|%S!c20efwQc0J*v^4RZtxXTdu?p{mL)>kze|=f9cPozvp>qZ=q)kbXfKz`%%7& zVDw(;PMwKg@_jwJ9LZ+Qz==R-LPu_Vsf8Iz=1e^Nn?l?FIZcE#MX3sk=AchD!EHSe zACRQxK@P1;rC z53(=hX7YkYOUZTOZ+L&bn)`e9CO8Oc}}`UJ(T!`@`VUTD6ub# zw2Znd#7bu=qeAwY>{_f&1YtUJCi-l|ZoHxng&Z>yb(U=@&oSw7+skJrB$qWAZP!ld zSC6~(ObS~j?%1HxV~E?vA4oeTKgv$RFeY}=D&9&BuE}-%7t7HNjL*x7I5x$oPJuW<#nAaXp^M8 zya=nba}f4EK#j0xBO3nb;Q2ITi^-pIz5$A2&uid8jktio@1-lf;sQ057~EXtbAO3OXDLnC4_6dTcq8l!vV#ssVlXi4%t*qeM8`2QoOmaaSl~wF zUzW~ML~q|pe3j0ZeBewUKa0l+p6GX~-m+)UOn$x2d=gN|WbXs5Z_*jN1Q!C%Y3;NIdy^HsH zQbc#XVebg=UD6c=#)JuGBYbznB0nKw1P6YIC#VqxW{HmX`AyVLYM8TBb+XKLkNOQ z*XKMy0@G>V#%#oD`y`xZZLip!j+4KLS!b{PL!jnR`0Sco9SIOB1ub$$7rZ(-^|B;& zIRkCrU{tBG)x+(6&@5BzM>LqcATprca#92cv!#T7IyD`zCuTJ)@!{T4m^%D%9HhR0?sbXn6T z`q{dHev2OYi~A(Nc=wr!P{v4SO@W1J0(dC$*65}1mCKp3%mepGz)xbkdG1A$C-zMQ zaGdy#K?viq(&x@0(%=j};S9SnY)UbmV}`o1&imry&hF)Ipn0dc^%ay0nSn z@PqPu={^WvOuQcD$@SRY2$)S2bKYeK9tdzYU4@pR*$jUQ-cQWTv;k#dT!=Ce=o_nQ z$2t$axft4zy5LUhr9E8ZCZ3;Z_U|sNzE~KN_s%N?1~l%;d$5)fVUWkT zlwO}xHotcy)Y!y9;OSQYZdc*quqn;niUAid-*J-Vc0)Zd1om2yG7M#K<_dmf3cE{u zmC5pfT*+C8;aRe@Q!f60wSDP=<2cM*fwFrxdH;vaj4dKRa1}_pr+2?ZGj7SU!~tH5$8bgErS4R>3KIS(6tQ&ZoHZE>id51Y-W!2|fg3jl z1P)pS*;2_}R}iV*h^T`kS76izl3HR}lg-=ptt5X2f&GK)@7DNbxKW$^|=Y3Z&5iR3E7pKL9V0bIu0Lh%2 ziUPnSN5tQ#7GLz>VGkx&u+Zc!?}fRoKqhuEpP{UzuW0EN4Z|p>+$ufgdA498okQ_4 zlwY~BD!8v3x4v=f8}AXHm!0K>J6BH9lHu4u&I1V7!f0R&-G2*tOPwc6E9m3N$8AHf0&I=j z%I`tM9mAW@&m`$3+XVPazL18Z8b3&K62um$Y_`w@xP6aj+R=^UE?Xo^ji&pJ!`EHM zx8E}vU2pAWSbzUfj-1t}Gy>1c;W}t0dB4t`4@dejkZQRu^dng~1`;lq39di@C>ulH z1{ufz03ZNKL_t)1L4%xQM3bp~btaqVgX)R6CiJ?~kIT3r7XVQU8s@uXd%P=9_8y5o zbah8;XI>Uv)*hZpO7{1f`(R#@9JQ{erC8E=__sYP2vGEUN96T6g~s*PfZ1iTioF@< z%=eSdd$qa^|MAg%!d5=*vb&d|2Q`{$?K}#dD4W)SzmiT_}e92B762!G*)Q;4VrjMa#)kg*APS_mVIjbgbE_U>nk;YGYVM_#xrHs z>eCezK=eo`)g!x*qH+X(1bxhvXb&Q!3d<99=a?Bxa3N;7Q=1O~?~xE#ZwBP}FVYZh zDJ4TwdM!RNSh_-y@z2_%14a|p0Hz`2YcNs7(*?YfLW$Ida4e94Mj{Kr9#E*2)IisS zj0++@@pb^Q{Ad$IM%KY>^C%QpX`@R95;8N0Fdlj!p@2k>ga;3};L8L8dRZS^4Q;YA zl%Ot#bt_{xYMV1v5MPl%PQtMS4~%gpbGOTvOb;e}GcsC^HiIkFsyI2(I?`YNE#M&m z0$-*V5k`iAV247Qbq?5=0R*gkBY&whic|+sqCMTz;pM$9-$i;mla9q%#e#^- zCRpFs8}F+J6L*3NUvh(T8zOw=KyCQ=}$6=&gFD4lc} z6}AB^yPstG18tOqLVH2bu9o{h{ry8~N16P$WjN=?`EorEFEn0sedhoy=}q?&^JX0m z88!Vqmp1I(DTru6gPeJ;ZVxqkBW~z*1J`Xq#BKT_!$$}3FhPGOmRuH@nDcEtlGodN zCEn&kB9LHzyxDufW}_B*6uG5eGay^Zwb`)Ji=+H5WvoU&Ys5pL(>*<%pFD^vo& zTmuMO=wwnL@tHf)^(}00H0nqs!Q~>qzcz%j%r?B(sEedX+;2eytZoB{CC6*n`4U9< zzbTPo1s7-kwUp=6bG@i|#71Ptin$R=A`T~9Y&s*z0?#;8yV@MI_rw)r#Q}J$ppCzu zkTD_i2Bz4aTRvZ63<0Lt=J^9$yD;8)X7Ef7)6ZMCobq*@!QVjLDbN72&dj&0>&K|wKKHQJ`&+zQT5ZjJ``mzo zKpkSv#)p&yV6z>z9hidy2%vf>R!1NkzmV^2ma`pe+*nT9h-OO=dQZgkAYwZ3^gtrY zFc3z990}@s$Xos%e;2uGy9v@~H?+nIOVZln| z73<;qq;`QqZiT%4^91AtTUNqXxIBnc2JDTNp~A}d$hAf<4c(wH|H(Lm>0}T7v^N`Z5=3bQrVQWcTHJ0gj1R~qkJ>VbSNDBQ`p(5sd801`QWlDmCa6ZhazFhRa>-V^g- zHeMgK@|p6UEHSzB(puK_vS8u9UaqUwbMc-p-1Ck1d|4yHd^PEgLO1`^5Ea{~@~y{F zCnDSH%a?vMu~l;Ai{1dcP7nx(EG#14x$xdnT(xZI=CQnE$I(gngLTxzAam-@ERAxlG7VJlC6!8TB|`4PFaHU%apS~TrmF-o)h zRg1tLMG4()6K5tX#rXH-9YF>YHmp!`3jpl#MG$9?;Fa9S%j{Urwx5#i-hQ^<{JVk5aJ+T9~XAf-&f zj9l@mpkzZZ?6`a)>&ek%&j>5ru=V)^1m4=Or`k$4A`^2+IvpjjGzRrZfaXc0Q6NF2 z`j^0#ViJW9$F7vd>aNT=CqiOa(+%}~4Af^^M;t?=c**#pWK5H~`PbAV=xIT33lvB7 zNE}y@qE?GD;8H46=sI&gO7u4XM?kp0V7EBC14zl19{-iQd|NQF$Xgt@PsqQ;mRHpX zCSoYuZNZxba6Um33iwbm8)9)|UYD=Bgq#F#JbYt}3o$RKwcy9Hs@@s{sLhjj19$;= z!h(p0-IJ@6x!J@teDp&;D_9L^3)X=$#vVvyOKt`e2EyLg)rS)1&@VsxGTWQik&?s4 z!4-IAw|^D3w+f=1dZyl#X@h1gKZl!V(0)|mL%{LZ*E(2PZttlcW&P)evK$~8c29~iJ>3uU(pxZ`}Zl{<2-%1UCcGQ;Eja-X~FQsechN5 zNceCk2r77(Z~I&nNXRLWU^_ze*hT^@^*+$CNvrg`?Rse_WRR!n3kYjOnS5zZQ=gKPP4+mvnKX0d%oU0yxY}`s4 zcgA^aD^I--%pL6+(_8`?MXD3ciRy~@Lq@>NH~rgutj2WPTs5_ zg6B*G1`&X_Dp)@y|4EenIl?d^YCRGd!}n?62Psk74Ow!st!_OM=?G(z>xeP;wD6_W z?wcawJrXxC0Zc%r4c*B-2GUq&fyn9af(bSPVMNh^t1O0L41{53`-h< z^2SNnNy%~R@9giF&vo9yX}M0!B!XhWL;DwES_o` zP8TbU#d!ab6&%7^+@Ql7$5g)5TIlub;3s__aW0R!5K^_ zmE?TBJy@&F;;fgzS}YZMtIuJuO&0swZ2)9IuYob{Y@Dc-Vs1=%`dkT!Ltn`cTH}W!LjnLz^&Lz!QXG`Rl_~wE5#B3)5yZ{R>d?nbF$n%s5)XrKrlMhheaGH%Ram@aV7 zI^nvdd-_BjLroo{ZuM|oD0;-uCX?c2vaWx4+*uSpf72YQ5Du}mtgXEhK6cB7$V?x$ zbmN|tpAL90#jr;B8|4H=;3F8eK%z&JWf1mOnbE44frJCF7D(tq{K!$dL*xAcc)3r0 zSGFLcz7sq=o)xIooU%&}8ChGEt!@_haj%27mM74a1if=iA3`>~HQ9oQsXR=@f(oef zO{_=4y1i{J@#~s2^vWlX2W>eBa^95VqY3E2-^KENR<_>ajtJm_e=$~2L+*TK5;7=V z+z*Z`Dl#jluG<5b42*FlO~-X1<^g1AskF;?d?J_#`B-X7ZZ=hs)WjDEt5&w8$Eh`o zE4J8srDyw)KGuN~hz&kTPNvRY38_64Fnkj9tu;4AIZwFWUp{X_YjQL#18YH>tqi6< zxxeYdprK7KK)wL^qrg*vhgvZ4fDLo1iWdObaNEi0uJ%Bf3?;)kw5e9PvH1}f-eY)g zl`pBCbtD@)6=i!4w2ut4I1Fl(o?M*b3XV3O9%#WiQ2HmD{15QXAvL-~_0;XbgIlL^ zo{RJypgR2a5rE0JKc6Afr$d**p5Th}mKx#&^B6GX-Vxc51P?l5^}2U0RuDr~heEhV za9u{3=K1I~Fg%dRo{0IzJzn+pQ(}T)WLxRb>=dzp|CJ31t9!$6l6ow3amL-jaCR~7{onc=q+pko!k5pJl zl6VecLBzZYkH`~!6Ie~eMHUGD}m*^Ag9ra?GupQ)CgeiD_{BW5S^Nn zhNpyc;T4@YaEQsRk`q}Yco+fPE^Wh8a#$0OdDrSC!WceJ;&Ml0AkYhv%BBIl%Jt#b?J$f{slkC^GFx(vE@K*)haZzv3)N;D*1Gp*C6k}ed+rM-}%V4J?xd6Sp*#-eZJme#8Oe>#Hx zbiMjY!b7dMsg-Ll;JL`3?HcF1>p3-SGv7AZnkiQr!GzZ@18~wQmWL*X&Bv~Gx>rRA z%dGym?zPHP0;@?%OedHzx`cWpMg|caOprgJ)^~Mv3=D5P?ATW5I_tFJUeqA=$L)bc zEO$Ah)s`wKOcW-LC*D_X3MZ-A!(kiK*}FP53z_4$)Mk~7&$UQkc~j-?dao-}I7mxB z<;fpDEt8kZ4K`pP0jux9#5^xNHZoQKVTNiZp$&kSfm*xZOn?;;P}Fmw4Bo;&6?zlk zm^AMMfcWIpSQd78tL^ZiBE#3}|MZzx1PnC%CyXu}R1096wgGwp^O9V>X-EOiw9$Uf zo{8X*2N4*d#RIh*tBIS_2OHe@9(HC3u3wjb2FBNbe2IO0&IX(YP$Vs6 z+C5bqdjh)ctDEClD2C@ZBfo@PxbpkXta`1LHk#-52J40kO3B5L~|=xPDz2UjrlL z_X!I+9#KrqkBB#V3`MN9Q0gjK&L)h}(&Tb)CMfPN4*vt0*1D2eFgwBioHu}lxUQ8E z?zF953S{?b*jO){GNRzRwaY5&q5Pk!7FnGi+wsVH{I_9IOTf_1bWJNp7Vff(R&VW> z=kk93#Sl{Q?)bz9-xdI*xX|X`{aDROiEjsJ1u%%?VP$=_lr|?{jg;*Baj#dRJrS~5xPJ*6Da;V z1gW{g5lnD_-H=5kb-Izz!;J1M!QH>$W@?TKzLp zjq}3i`L`a4?R{!75pm-?oL_YvXI13b={eP}WA6u7Fb^b#pH(b)(91dylGd?fDeeED zgL;!RTJEFO-iaLmQzUyatmPOMR1gEw?u38v>!5w?Wf4QKB!;_Dkj1(cb{;4NtQPnJ z(%FLU;N5~$>V+8b`y`-Ug^b`N(#r9L989DvD=@C2Z#A&*t0Rp|pl|qU zYzj=VVLMZ7DcIw)Xnut4IMbP)FROev6ny3O;c9%tD80W#?M_i*Y3 zHiX!=DwtogxSR-c#3kQBnV%gyj94?0wE0c0ajwVTj}zEinOusp+Whs<)0YIEKQ79L zR2RNR(H5V?4KWDSkou(W%FcelxCh2taJ>igzM%6_Kt((t{_X)-JiwIJg1jj-I7 zi8Dw5$ORj9FvIUg{#BqfKk7iAf@rfn0`c>=e4^`8$WHoHjld$ILehdxCEo|z623e+pz9OT-jhgA z)}Dxwfy8(W8*y?8O~|&SQfwL91cv%R&5zexeXI_T`}U<3VXey9y&hnPq)5U-VQ0Op zS0P~e&-X!an!~vS7%i=-KI|fgHwC{h zWNS@)B%FAZKYKE?CgyPyDuJ{H*vO&TJ{De&A^AS4M(?U@1onF1Q{j634s^ zN$|XvHIdCg1+dc7)C=xVK`WeSE@$dRTVxB}2z{fojh1vB0Z&eA*Sy=Ue#lLx>5gyB zD`*2M*GiN1;P)f&AA&K(#%x|_K3Fo)AB zqdx~QhTwt)5RYFM?)Ss?51CIu;OUN{5uc9r{80ImJq6P7$PirrJS>>_=V7h7@%`6@ z>+1p!@fsdjsSaqY*tBK+cW1kolbu<=J|3Uw@t<4O|EI@J2R(fIdFejEnC`Q-=jHD} z20(8#Bfadlswe-qR8KW5!0e?b5ZC7eE}+`)>!b!jRbW2d_1F;S`&pv`uCEKv|NVu> zKMy?qiQb7TTRyD;aNru3`vX8O#k|EAxv05wd~UKyx)64|U3YG5?7>psXk@5{I<$0w zCGD2M9#F6;X59=stegnTN?d=k@%;5*kH430&f~+OgircyO5u>cR^94)FHO;@H!wFf zI_Yn-CqJ}nvVZx}n~J58Sd)iY$0$F#oNhy#mUj~$ryL&m9@uUzQ@_Z130=2)8AzN0 z3c>Zba6K@ zfS|)#N>wm4mj0}XrW;)XG{7hQVqoCHP`~zdurU|Y&46yjN3xJ#>R#`Si2I~{>UCRs zBm5`MxU&u z!<0nelt9Q=BDw}H^+DwtyLU%-nx)72M4ia)v|foaGF%RKG(1NFrIWEqTwEu`QwODt zLr`25!1NX*^;T#hC&C&8awx%f|2>v0RW-$%l@C;LjSJ(tj80d~lZg2zrVAqj8@0gH zjZoZgD#>^z@2ktZl}S|TJ|liVvy($hXwRT*O!Y>Pkt~|Xk`(b8Fc9Fq5_4J)!kA*K zDqXQ^mJjRlp-nl@M{Uo9FyJv^{qpm0y5_1_qk1Areg?*^m|~k+&R<_{Crm!C>%!~T z3-5p4c>j45xrjzbfBnIUuO6)7P^qC!UynSG`2Ka_`t{g)L3u?nogec3sng{*nr%D? z7=Kx_)zi%n&;CC@J_8`TUY+pYj_>P!x>|QMKGSb~uMFM_7EbZllErf9@mt~(3MLZt zwwClBRHR>=iustB&x!kb*otD$FTB6rxPQGdUw2OIyq*^x|LcjzKTi)P>{>2(AOXzx z1NZyJeZO(PZx7zphTl$2-Oloo50;<{1rtWA06ix=MjS~~R3NtOLp{?22ReuG`v3w% zr@_w$XUS&n{H*%*ma)^br$dkO!Y{8@Io@lj^=xB%-o0=V7XWc&(2$hKna`0mRe+nVKM$flOO^Drl>MF&%VqAmI@UcZX&W;n$fQ zVVnlOg6IU`E1>AkwF^l2fV$>9iq-6Fde{JP-5o3*ojKj}0Ahq)vxK@SE3Pfh6r?cm&U{L3_1vqQSrKrY|&IYP6y*r$+E?DELWR_Dr-?g zoP>KMB!gW9zW}|uA(c(@jk0l3(Az!jMs=yag2Iz&Y2&*3Lwum(K?<-(xrmbqN!X( z%WPqxmA*n(ASNd=Eogs!!8^JH*ER5XUikX+h4<^m{pU>;XRo#pwP_}<@u+#kjh&s&v zT%K?1f4H}5HT5?&LmkUs>;>n)YTK4@b<-ugxWqq>*M_J~wEoJ|Z+EEtC z7qmLlTNThQK}0k%waB5e-_u&k+sbv|b(5h}ed~Vnxg=MmkJ9+f0cZ;(IE}Rq0^+yO z_g&UM)mQTON-Y0MrOQJY#WADx9_YPzo#BgNw0tCvoA4TaC-!T$K$0Dmqs5Bso=pGrv0tdms<$;8# z&kyi1E)r#k;S)-UHh)P1yBbaskP>+RL&m}71ZlvUQhz>jvk&1XsYNOn-j42sT7;Kf zQvO|?hibh7I@HEdr!o*A&xn<-Gl-&=sYrV%QgojU6_~fMkw=lYM0x!=?%^n7Nb@8b z{n!Z5uH5bYZhe)mEtm-YcwnIlWuuj?2XPkvWg?=I_`Pvg*K2=fhLb}Yk?bWH!#8uR z)v$8hqSvj0ohWygj@^2)(8bcPVYzC8b-P}V6$G!&M*7z*i5tgLOWT$O$qs|!F^Bg& zSm4$J2yLY8t;!__wI7G~t_=<#C;;_$09z7v%;=Sn3?i<_1NYa{T1wv&_j`8Uw`-!t z=IPr*ABa*QVmybn5IqOR!-9wLsC!Jax%E!;JQ_gxHwW>(0gw~;I97`VkFJU_n#rpS@P#|LH%A4|UfFprN z2O&BY`m{h|J}2ha#C+YDuZj7-G4ELbNxJ54u*d z?3w}rr?@&MQ2@M7O@I%%r5AqL4`N=Ub9)6Y!f`Qz)X~KIV)aEYU^qK2N zvS*^OzVm@Fe;kkdwxvBUwF$QzO~p3cP*kFD2Im+m0cd!W=)iF5Dss*#!uh9cNIY9T z5my8fUT8zj&JT4Aq4nwfIXK@Gz{npJNaQgZQ&|vK#ZeNTJ+mc{;CUGvt`q)3cf5ra zAxwT>YeH8I!wLgT)~fBx5FUgSJf0)^SiPuCMJzZN!vcpPF_Bt#I@0H0J(^>$%1Y*w z<>v3C9Cg{#R>Zs)p|S^O!g+;b3V~S+!WukqDXBFvotoD7cqMj(50J}4$D(CsonE#Y zp-!x3rP9#muqOJwT`#2n*yFSsx}rqVugSRfQr6oGPYE>GXVem}89?m8-PQ*;001BW zNkl4coYvu|&%F^p zDNE_ZPiouLaCu%9JxbTlpo4-5?w$BoMP71mkIGsfwwFjhzJ5=AjitoznY|P9p3wKq z75W5XE5kgllH-TTF{H{64F?%OWFX;nmR8VK(K5knt1*ZPO!uls1N-qpHa2y#uB6vh z?-!d^?nvkvI&omj09 zgxUjpaJJ(rBp-6vQ!Eh+1N_+&5yP5pwa--Zo$Ju1xQugLTJM0M z3Nq`Hz&)cA%}8aa7vlFsy7QZK>?U!Sb)qKwj$Q~0vDF-aT2D=oeya*bcvp|9|O=#sKd zyyq4&E%vrvA2zBSynQ&raGIlAE$V8F@-f5)X3$nJna9{wIuauEovkI+(B0163M&t?RrO=0B-irBa7I5PIK=NS6a;oq* zL^%Bi!cRgXzmq=!IZ%NCUTeTps^j9%cAe0E^+~)oIqc=y(v53MbZ?93 z_1qeBzER(`3SCMTdv((1gPvI#$(FE9r<`Ri?~=%O@3a3e9<8>0p%>SQ{A!<5MCa%o`?z}1cJxBW4%FRN_3InLUwaxw+5X@v^x6w@G=GCPI#4L z#AhL{CS*~dvGhvh90?}m2VAsp13B>}o|Rg=H+mwZerTKo&+A>}|nIf~sP zQ(3n1d0jcMX!jZP77hD7ttAPCdMEOU_&wEbFRf@@^AB3*W-D4Nj9=@PLQ5=?lCAVk z8L9Hxty*3YYU{PH!2~;oPHHO0$*^IetCUgRUC;T*-k|&kTfK^ndKS}VHXKot?Una- zT^yknM;}6`MHZ*~z!0^S%6wsh)YKM92VbLs8O~^;1 zS4*+^q?HSsVd;hOixclYIjiqO;J+W-TAaoDTZ{a6L`4TO->1~vGTr)Fo!Gpu*WA*~ z^2_zDMI8Wa*Wc9O-;kW-q0PbjE{*hOq?>}Ym%IQ#dZZXKan;ZX8SHPozFIBdt^P}0 zbt%XOh+2b6uWZp+wmLTeisk!~)@RuvM8NVwI3UvF8gbm;O|CRM{5Q|IOUDO!5h^Fy z{7gfmT-1mYwuSSQUf%%bd~{we^jvg+3lj3P2G2!8x4BeSem>v`&++LWDz7?Li~0%a zn=nlrbFAcKnjY%VXnQ(VMzTNq##C3i_CSIg*}}KwdrIe}wI<8FM5swqQc&UounKXzml2_OePXn{j9DUluM9>hmvNzNt7XVNNgAHMc7I6$hEVv z*sRMTzcdpdV)?0A3)h>v4%EEbt)P3u*e}nHNHw)i@$bouf-2q zH#%CGapE}FScgHEM^P&A}EApWZ+P{2&SCzM{_4vL%{8bO4 zp!|nhUr{#DOqJwwZC+I*tX%p}N~P(sb9YZ-X%^=vvgHxed8E=CogbvQObs zG9|kH97v!7yX0-pR9aeV&K!vN9Rd%hh9I_8t>J>rk#UZT94v035IPmkVq4ycnn_-5Ml_fWiLEXcSOd;DmTKZ^e8m z<_q?D1IT$2Vw0=y;hUnys31885Zn_Hy%Y~t3d1H^ORQ2N!vTNnN{f410miV%CbqB~ zcFz=O!Zx|HphA54p)5xBM2HV*iV4?FLI(^X6NvH!gIp+!*!(SwAu(sU-XvkM42glf zJmCgTHuX~dHV8O_Hl|XOR=5r`4-Q!^)qy%7P^Sp9XmAGGBFJ9lZ;DeG|6x%D> zTk7_58!e+Oz1~%Q%J;jT6`}fo*{1oo9GcSo(8k{C%kpw6`KIJ?J~FiqHoA3LC<~K{3@W`T)11bMUndUz{IIt@*Df+Pyq{krY8&B7aoAtMy&=_*?#o?l%v7h$Ksd6w%UDJVn+k^sE}6_6=|6 zw9Rm*`X5(3q#}M4gGT@PG19xM@DxpaIscw1P@pA z82A#cwwV-cjMbYd>=hrrywVUrh6fk}0^95^ff6KFY#J&#v?-$=I0uP<(m-z~JPS$N z#Cri~$!j5nZU(H*nTnQ-^o`EJocH|tZ(%4tny@u*NErekf@&b>(VLp9G)w+{z620^ zQA7~I!YHZWowmJPZWCka*HCI+&)6U0((&JNBz5K<5^em6vI|;EhhRx(X&DNm$IcD2 zZ0ez2Af;W8Fk}RQ_a4jDc~P3(VTUob>qvWynwvC&wy~scS`0o{JwM6fCph}Iqx8w0 z_BYRDHBozHq|TD_N)EA67JpAz>|~P-Hk`cw#GH!hb1>}MKu}EX=84Pesz|Ny8=iOvdR`@|aI|@6>pnmgv zbD(AONUYyE>t6o{gGheG#;6EeQ5fm!8f1)o@cKOWt0@inhtQ?011I|S0g_T-)} zG)a0+%xNn&scHhM>$>oGKJ4>&;_(3FF>;@Y#H*9$`Yfw9RSR@K@8j3A@CSPLikFWF z@-dLCL?gd5&sjEvPM>t*bP(_rdXwFBlaZcoJbx6;wE&sK5=gkuWfvB{2E_js2vqSw zQcqxh{VXeSDL-F%W?E^#b+P4Z(4g&E(6datfHNWE$^Q&edilG_WRR9GJN<Ky z)M$G`twB+z(V1UL{N5hW!#%(5b7B40#bvei8k66pYwQDKucmv>T(xliQRr^~FM+%S z<9+#L>uGbJr(^(ec`#u^o%jQc>}VKxRNJ=DJP5%+^+H&J4)iA=ywh}6V$_}!BGzhw zY0EK+ZEhFK-Blb@!wiVydUh^{2YmJ>r>1>9rAEb$gElLfv`u zbq9&1lxb+Fepa8+>ef6dKn{ulKm`$+LBv38e3n&W2k(Ht-D992C9%~qLPQF_siq-N zIFa4Sa;smgu@0CK(`e-zPTSnnZgd8D-GXQxSh2u#DPzjUJEF_|MJyx8K08zG*(spD z07Fi+B!?qPV{hFuY6CuNFi0}ud1VkW757v#j8k(ZrhD#7P~HKQ?!GA=(`mn6E}x`&B~N3rbuJa$&e0l1fwOb1>E(w*K5*+)-P12W0Z!8Y{5Zc}?xhw> z-8BAg4s@^mnI4P%*^0UeJEfX!Mrg8oU3sy=Z`%VPV+543S`#bL9zh)Eoj^ETO-Ah2mO8KZM-c- zZ zJkP9a1K4R?oEKrZVyvtKU5n-&0QoaauX7;LjmspXR`l6hX{)y*7DQbPp=Y8fu&$|C zwoGBkmA|1C0OT#KbVTokX@LaNs0x;VBvwF~+FSlKc6CAnMd<2RpaZq3ALQr=OJ|_Igoo*-)Z$DODw|)b+~%s~nGAXE*Is z+-?x!PAB~uZi+)LF#wqpOulaRhEcMJ{5AtKf4)pqixfTI_% z=n@W%3%pyFGv~fL{`Q8ni|?QQ?pHlr@z+u*J^Z%I>{*I8sJ2$%TsGo;%RaAH-_z4# zz$r^M?Qvz>Md{}C3OZN6MnF;kkd2C7%m6*LrvvrYW$-X@zu(K}g*hj#%VhKU^#%P$ zfqw+!p9|MN59qD77|Uh(O(HjM<*Q#= zk4|B3>0fp0^HJ8d;nqyJgW>KM*E| zn6|$RRI}Hi0*Ly^q)|g^xeGFoFlI{o#E_)7DRXfuPM;m_8w3&auzrY zOrHePdL)GVA$lOuW;3foRUom;@WC#8Qp9c?3fwlHXn^H%)?4?|297I(0%;x0R!Ni? zA8cPhb{M=9m}M-ZROtodc+Aj;Ozxml5r0T6I z79_myiT69M@4ElK@qWK?zi-^{H{LCvxLX<4%8FN}bZ!B8i`UrfytkT+>tO*x1Qc=o zsOu|#fB0^s)9*cq$^{JTO!mQ_Vervm=g*Gz^jax7Jo8yVzB%-GnO_^-$)Ywo_cV4t z%iwcs%kQZitFYw9<@m`#c{ZLj@Ywmu;AySL256U{AscV}+Uyc4cu;P@aB!cx^2Yo9 z!uw^P+s_e5T-SxKUvJ=l1M(WU-WMM8Y3V;;!Gs8KOYV|8Zwn^wc^@~Y`^i$roz!x; zBnc09nErd$l~r37hUK|6#2oW}H8KG=mD>aFniBz|Hwk4^@;A$*<+R`_pn87| zaes^pUteE%em!wNZ#=&y^h<#!AYTG`E=zS&Z(Cfi*rk=FB%oij&)G1ZpLGeeQ)WsI zNSK0bjlLF0p!3N0lCX)^1LFTj>5=2=TC!9w{5{eqPrs(7CyWkuHi6}=Z0u?8K8c5)n2!YQ8J~Se9B$P(dFjn-B zM&o3T*H`Ix1I1G5$5MdPBi8G}m^LAgja$_`>KXvifp&~(SA|T_3IoN*420mRJBB zJbIw8XQ!Q(A;(I;x8FV;XIsC*kz?UM1v8)OvE|JEhh(e!`>b2F%2z#wQ)@ue{tPKF ziJYSbZ@hC&&)$a}2;O%D+7>vx{`|q~^#|`ifAIeE!hPR1#N)a!|Ct!C3)lOB$9&?6 z8;S{i43pJiz{COw*G=vroOjbi|Ml9i;J@{dd0)h>wsFAR8wmkg%Tr``3;8>&E=0&|k12e7^+a zbwR$aMziRdsbRGO%Xs02fVekql2EX3=D#T4XI%0iby=$TF3eD`UJ+3Fl;WAH4d?Y zh&Y$C=T?xSC!C2832NKsbWwgx4WyrAzJ${<=|xmF zrL&dAYV|SA-5RG#D#>g^a8ShHG7K0^xhFoz2|EY*hD78Mvp-kK~9v8qw%{tSFqWnzBtST^d zV9be`i!uxd4<{p;&s3t}!Rw8vL(C0eUU>a^;q`jq z?dSV-CxB{BH=Ong7SgZnPHRPxx_lQA3mP8Y)8IkFxZW99+|OwN#Pb1t0QwZ*DZpbu z9==p|%bH~^)qZ20(A`e}=;Oiikb2loz#wS1z z5b@{tAH4qjwt(XIZ_NA7@#6R`7C`71UU=h;8@Ei8(WlL&h}B>sh{ztm1f2z91GqBC z-I$@v_mxja!KMZlqGjjT={=H;#xwWRc>4aT5^^}_*9lWEp`e@ zRo28N@m1)(;(x3N7`Cl2XA2^tY@r|2*oSCXrAF77K+OTgz6`9t3sjE;0{o`YT6-j_ zXTngY*HtD41eaK_FueD{?z+Hu5MfYH5kW*o)Oq&h5mA#o4cI$V8rUm_SfdPqS64vN z*)jyHQ6Ty3!9)o_1rgB#Q1>FehyZJ-OffV=vM>t%k7=ET&jCY}Evcpf5({t@=GCll z*AW-6G>R^2Dw~ko-b5Ba#85AdUIGVomYyvYCXazJWg9=o&dsVzhSBS&Q12PAU`3`v z=CpCP#1|Q*_{@W#VJHdHEEGuGfm#3&!LL?8F}w0;%2v?C(yJf>zPXs>#8}>)xK?MH zo}N$cz6JA!Elv=-N_r46-{t_!u+KCesjNQKuVjmy0W^1wPAOrh+zfCkYcV`}2|_98 zIO~dT&lQ~{Cs10~;m8NT;$(M9bWMuGgJuX~N4V%%?)1 z0KUY6h^IiFreCGAARy4~gdFI2ua_~V!f_EDc*a^ zS)yKdIX-!;z-EKDA3;xS@9nL|DDc-F51lT%wepo~lDg_?%@}4$D}dPsjJ>g8-o9c> z%pICOq$%{}_X~f1|F+Nn`Hk1_-?-oJT%`&BYv7?@c*`McdZ3Vn zZ)aV;H+zi!D&MOBB7jj3CdT7}{-e-;0Q@61XW(ta_^$hb>%NI@=N`VU$Ch!c1_{PT zyVPtS*@Mj{P!KUDVsQ>O$Q49WFtN}j_lW>zU-8R3=B zmnA0Z3MMQNm}*Atg6}gS5kf>VLRAXIiGmRkNac$WWOTAXOqFFtm}YE*o;M{-v&EoB z)yoq%{j8CsGmm;|G9VxZ_o@oQ1WFV*&|WfeG~hLp_iY$n>(`Zs=|lS5<8#k04=yHTncittb%?G>#MB zJn)283sEpm=y9IV(#68-uD(RoQm!B!vpkau1(Pf%uV5DQc@TAvvj@~6|1u;4Zw%O& z;>hRna(Lhstu(jZ7*p`NOJ~-@#5D3PG05vOAN5WW1?AK>%PaL)m+w8H_WWSSph%-L zpqM(E?pHeHXiL^z?pzuzK(YYEgi>=U3cHX0x&)mM6)4X!Xp!IkKU6gEurs{L% z9b+wg-k3=Dy>cZAiypOi+Mnd#;iDMD#@_6Qry92Eez~JK{$aIgE%V2Za)3CZud{ngntRu$_9dX zZw*WXM{r;fSb}wn>@trA*a8afJ>UgFXc%txF6B_C>VeR$g`W5vwu<&9OS`)19%C3E5ij~(hxKS82&{dF~Y+7J|bQ?b6UgZ$>@L&36dgO zGE4JnHRrnhHKL2}LtRS2bI4KlJ#rRK z=yF% zCg?g>J<7G(*~Zi6&PqPR{}izFh7R&E0UE~~KJHoVI^44=hTbWElDaW~dD&*O@L=Kv zynj!;9&h})Uby5B2L6u^eR^YD!{SzG5? zmA#SzVQzz@`PefHg|32CnxeD=qP2y0Pw~5ZOIpWrEMG{M`OLi=tzj-~M$+44f&+;) z(AWYCo?Jb7c-*oNN%S)DlBj7j?US1e$32KQ+$ObmIXDFajV_@;4 zbsBz3gCffC7+mM|TGfY$sTR0m9gDI=Fag+PW@m@%Os_e&n!&oob!u)PsL?j8whu$n zVhYu}jFevGEW%O7*gdIgMv;jFWo-y5I3Mk7UG~ghVKf2j0dRT^O+#scOcdrMAItZ= zsfeBkmh(YD#3h$!AF@~s2{{dQN@L=^5V(=U{l+EEGw+d@xBYf2ZnX*7Ib;linlobe zD~Kp6uKJT*aUmyCGO*j^-P5+%J)JFmzHsUgh+g(_pq7gh3|gOi z*)eo*urZ28jlRs+m1T=xjXx1|O7;Rtmw9$talNF+)dec8d@k$WpD%i@g-tT&z1F}; z`n_0&?HkTd= z3L;|ILaxd(eKp2;Ww33HO4d_;55@g^;&t8lBQFg6f#~qX0&I!cxwdBW5EdU3A2e)1 zV34&Ftes6(6)Ak#v(Iw82s0$}6Osp``NB)3ch2nGzGWIsJQn7Clu!DNo;e1qr=$6C zvgL>{jMDS;TM&2n#Pb7L-$V9iGVxLe- z0YF?wK2E1tT?*>!@uI+P4r!2{1|paM*BK;?WeAYU=@4J1_e?AXjDiWo5U1fZ_P{Dy zwv&g^TO{hEqnuw715MP02-OnAxrV}w3H1%u()k4|vX~L5MQx+@npfHFnBxNA!9+17 zWhKFkrXf+M0fGi2*z3Q63nPZ$| zF#@PfPMolL1~DJQRy7mIP`f9ihBGZPQ+Y*^g6HgV`0rwnl^h${06QyvBVof%8r>WW6e#Q0n*n##f!B+NK!gk^_}%XOH|G~J zK)|h8Nu|5t+eqiLyoaL)4S6#qsoh`Ssp4;-@|@duKTsKU`QGxVW3z@*&*pCd*aIj0 zOdBZryf^LjS@K9dle(P&guv{_?EGDOB-+RCTkvq#+VBxX-1gBam;;!icwZCm@x~v# zAbJ6};Cj6Ah(KZkr!yN*PI7c&fwgI9)xodx>^fQ<>XI$7+#ZsY_C~>?V>JRKP*`|f z?`wCfVaW5OC7&&wey{0grWs({pVxSvH&js_xgKvoRgvPVMeBd}#NwQRyVhJEusZo_y=js!jV8nNP*_eg9*nj*NM z;9*^~Kx+<8((nU)dl?s77%C{mYvwxW)%c?&JpCYmoM47}CAuUXli&b$tj! zmiM@9yX*W^g7eMAqHYf#b)TNe-?e+!uzz8za$Gd$5&1~blUKeeOZJJpvIh2CoK1r&>VwK|dw zlkh(_yjZ3O7!Uj4A-2fO!;=+TWaxpX@h{$2^Ig{K82d{tbOHeCB}l{dja@IyWACOu zK(b*wj=AYW*^f>d!h+O57_V_4(d?2|3UU6w3kR%<@86=+00000NkvXXu0mjf&mr4V literal 0 HcmV?d00001 diff --git a/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp new file mode 100644 index 0000000000000..2117b650efc41 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp @@ -0,0 +1,102 @@ +// 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 TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__NODELET_HPP_ +#define TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__NODELET_HPP_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace traffic_light +{ +class TrafficLightOcclusionPredictorNodelet : public rclcpp::Node +{ +public: + explicit TrafficLightOcclusionPredictorNodelet(const rclcpp::NodeOptions & node_options); + +private: + struct Config + { + double azimuth_occlusion_resolution_deg; + double elevation_occlusion_resolution_deg; + double max_valid_pt_dist; + double max_image_cloud_delay; + double max_wait_t; + int max_occlusion_ratio; + }; + +private: + /** + * @brief receive the lanelet2 map + * + * @param input_msg + */ + void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg); + /** + * @brief subscribers + * + */ + void syncCallback( + const tier4_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr in_signal_msg, + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr in_roi_msg, + const sensor_msgs::msg::CameraInfo::ConstSharedPtr in_cam_info_msg, + const sensor_msgs::msg::PointCloud2::ConstSharedPtr in_cloud_msg); + + rclcpp::Subscription::SharedPtr map_sub_; + /** + * @brief publishers + * + */ + rclcpp::Publisher::SharedPtr signal_pub_; + + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + std::map traffic_light_position_map_; + Config config_; + /** + * @brief main class for calculating the occlusion probability + * + */ + std::shared_ptr cloud_occlusion_predictor_; + + typedef perception_utils::PrimeSynchronizer< + tier4_perception_msgs::msg::TrafficSignalArray, + tier4_perception_msgs::msg::TrafficLightRoiArray, sensor_msgs::msg::CameraInfo, + sensor_msgs::msg::PointCloud2> + SynchronizerType; + + std::shared_ptr synchronizer_; +}; +} // namespace traffic_light +#endif // TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__NODELET_HPP_ diff --git a/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/occlusion_predictor.hpp b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/occlusion_predictor.hpp new file mode 100644 index 0000000000000..9c14cd992fac8 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/occlusion_predictor.hpp @@ -0,0 +1,95 @@ +// Copyright 2023-2026 the Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// + +#ifndef TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__OCCLUSION_PREDICTOR_HPP_ +#define TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__OCCLUSION_PREDICTOR_HPP_ + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace traffic_light +{ + +struct Ray +{ + float azimuth; + float elevation; + float dist; +}; + +class CloudOcclusionPredictor +{ +public: + CloudOcclusionPredictor( + rclcpp::Node * node_ptr, float max_valid_pt_distance, float azimuth_occlusion_resolution_deg, + float elevation_occlusion_resolution_deg); + + void predict( + const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg, + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & rois_msg, + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & cloud_msg, + const tf2_ros::Buffer & tf_buffer, + const std::map & traffic_light_position_map, + std::vector & occlusion_ratios); + +private: + uint32_t predict(const pcl::PointXYZ & roi_top_left, const pcl::PointXYZ & roi_bottom_right); + + void filterCloud( + const pcl::PointCloud & cloud_in, const std::vector & roi_tls, + const std::vector & roi_brs, pcl::PointCloud & cloud_out); + + void sampleTrafficLightRoi( + const pcl::PointXYZ & top_left, const pcl::PointXYZ & bottom_right, + uint32_t horizontal_sample_num, uint32_t vertical_sample_num, + pcl::PointCloud & cloud_out); + + void calcRoiVectex3D( + const tier4_perception_msgs::msg::TrafficLightRoi & roi, + const image_geometry::PinholeCameraModel & pinhole_model, + const std::map & traffic_light_position_map, + const tf2::Transform & tf_camera2map, pcl::PointXYZ & top_left, pcl::PointXYZ & bottom_right); + + std::map > > lidar_rays_; + rclcpp::Node * node_ptr_; + float max_valid_pt_distance_; + float azimuth_occlusion_resolution_deg_; + float elevation_occlusion_resolution_deg_; +}; + +} // namespace traffic_light + +#endif // TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__OCCLUSION_PREDICTOR_HPP_ diff --git a/perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml b/perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml new file mode 100644 index 0000000000000..795267b920e24 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/perception/traffic_light_occlusion_predictor/package.xml b/perception/traffic_light_occlusion_predictor/package.xml new file mode 100644 index 0000000000000..813f2914b7c4b --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/package.xml @@ -0,0 +1,36 @@ + + + + traffic_light_occlusion_predictor + 0.1.0 + The traffic_light_occlusion_predictor package + Mingyu Li + Apache License 2.0 + + ament_cmake_auto + + autoware_cmake + + autoware_auto_geometry + autoware_auto_mapping_msgs + geometry_msgs + image_geometry + lanelet2_extension + pcl_msgs + perception_utils + rclcpp + rclcpp_components + sensor_msgs + tf2 + tf2_eigen + tf2_ros + tier4_autoware_utils + tier4_perception_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/perception/traffic_light_occlusion_predictor/src/nodelet.cpp b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp new file mode 100644 index 0000000000000..90d96b4c9cbfc --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp @@ -0,0 +1,138 @@ +// 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 "traffic_light_occlusion_predictor/nodelet.hpp" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include +#include + +namespace traffic_light +{ + +TrafficLightOcclusionPredictorNodelet::TrafficLightOcclusionPredictorNodelet( + const rclcpp::NodeOptions & node_options) +: Node("traffic_light_occlusion_predictor_node", node_options), + tf_buffer_(this->get_clock()), + tf_listener_(tf_buffer_) +{ + using std::placeholders::_1; + using std::placeholders::_2; + using std::placeholders::_3; + using std::placeholders::_4; + + // subscribers + map_sub_ = create_subscription( + "~/input/vector_map", rclcpp::QoS{1}.transient_local(), + std::bind(&TrafficLightOcclusionPredictorNodelet::mapCallback, this, _1)); + + // publishers + signal_pub_ = + create_publisher("~/output/traffic_signals", 1); + // configuration parameters + config_.azimuth_occlusion_resolution_deg = + declare_parameter("azimuth_occlusion_resolution_deg", 0.15); + config_.elevation_occlusion_resolution_deg = + declare_parameter("elevation_occlusion_resolution_deg", 0.08); + config_.max_valid_pt_dist = declare_parameter("max_valid_pt_dist", 50.0); + config_.max_image_cloud_delay = declare_parameter("max_image_cloud_delay", 1.0); + config_.max_wait_t = declare_parameter("max_wait_t", 0.02); + config_.max_occlusion_ratio = declare_parameter("max_occlusion_ratio", 50); + + cloud_occlusion_predictor_ = std::make_shared( + this, config_.max_valid_pt_dist, config_.azimuth_occlusion_resolution_deg, + config_.elevation_occlusion_resolution_deg); + + const std::vector topics{ + "~/input/traffic_signals", "~/input/rois", "~/input/camera_info", "~/input/cloud"}; + const std::vector qos(topics.size(), rclcpp::SensorDataQoS()); + synchronizer_ = std::make_shared( + this, topics, qos, + std::bind(&TrafficLightOcclusionPredictorNodelet::syncCallback, this, _1, _2, _3, _4), + config_.max_image_cloud_delay, config_.max_wait_t); +} + +void TrafficLightOcclusionPredictorNodelet::mapCallback( + const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg) +{ + traffic_light_position_map_.clear(); + auto lanelet_map_ptr = std::make_shared(); + + lanelet::utils::conversion::fromBinMsg(*input_msg, lanelet_map_ptr); + lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr); + std::vector all_lanelet_traffic_lights = + lanelet::utils::query::autowareTrafficLights(all_lanelets); + for (auto tl_itr = all_lanelet_traffic_lights.begin(); tl_itr != all_lanelet_traffic_lights.end(); + ++tl_itr) { + lanelet::AutowareTrafficLightConstPtr tl = *tl_itr; + + auto lights = tl->trafficLights(); + for (auto lsp : lights) { + if (!lsp.isLineString()) { // traffic lights must be linestrings + continue; + } + lanelet::ConstLineString3d string3d = static_cast(lsp); + traffic_light_position_map_[lsp.id()] = + perception_utils::traffic_light::getTrafficLightCenter(string3d); + } + } +} + +void TrafficLightOcclusionPredictorNodelet::syncCallback( + const tier4_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr in_signal_msg, + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr in_roi_msg, + const sensor_msgs::msg::CameraInfo::ConstSharedPtr in_cam_info_msg, + const sensor_msgs::msg::PointCloud2::ConstSharedPtr in_cloud_msg) +{ + tier4_perception_msgs::msg::TrafficSignalArray out_msg = *in_signal_msg; + std::vector occlusion_ratios; + if ( + in_cloud_msg == nullptr || in_cam_info_msg == nullptr || in_roi_msg == nullptr || + in_roi_msg->rois.size() != in_signal_msg->signals.size()) { + occlusion_ratios.resize(in_roi_msg->rois.size(), 0); + } else { + cloud_occlusion_predictor_->predict( + in_cam_info_msg, in_roi_msg, in_cloud_msg, tf_buffer_, traffic_light_position_map_, + occlusion_ratios); + } + for (size_t i = 0; i < occlusion_ratios.size(); i++) { + if (occlusion_ratios[i] >= config_.max_occlusion_ratio) { + perception_utils::traffic_light::setSignalUnknown(out_msg.signals[i]); + } + } + signal_pub_->publish(out_msg); +} + +} // namespace traffic_light + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(traffic_light::TrafficLightOcclusionPredictorNodelet) diff --git a/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp b/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp new file mode 100644 index 0000000000000..eff8921a897a3 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp @@ -0,0 +1,250 @@ +// Copyright 2023-2026 the Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// + +#include "traffic_light_occlusion_predictor/occlusion_predictor.hpp" + +namespace +{ + +traffic_light::Ray point2ray(const pcl::PointXYZ & pt) +{ + traffic_light::Ray ray; + ray.dist = std::sqrt(pt.x * pt.x + pt.y * pt.y + pt.z * pt.z); + ray.elevation = RAD2DEG(std::atan2(pt.y, std::hypot(pt.x, pt.z))); + ray.azimuth = RAD2DEG(std::atan2(pt.x, pt.z)); + return ray; +} + +} // namespace + +namespace traffic_light +{ + +CloudOcclusionPredictor::CloudOcclusionPredictor( + rclcpp::Node * node_ptr, float max_valid_pt_distance, float azimuth_occlusion_resolution_deg, + float elevation_occlusion_resolution_deg) +: node_ptr_(node_ptr), + max_valid_pt_distance_(max_valid_pt_distance), + azimuth_occlusion_resolution_deg_(azimuth_occlusion_resolution_deg), + elevation_occlusion_resolution_deg_(elevation_occlusion_resolution_deg) +{ +} + +void CloudOcclusionPredictor::predict( + const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg, + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & rois_msg, + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & cloud_msg, + const tf2_ros::Buffer & tf_buffer, + const std::map & traffic_light_position_map, + std::vector & occlusion_ratios) +{ + if (camera_info_msg == nullptr || rois_msg == nullptr || cloud_msg == nullptr) { + return; + } + occlusion_ratios.resize(rois_msg->rois.size()); + // get transformation from cloud to camera + Eigen::Matrix4d camera2cloud; + try { + camera2cloud = + tf2::transformToEigen(tf_buffer.lookupTransform( + camera_info_msg->header.frame_id, cloud_msg->header.frame_id, + rclcpp::Time(camera_info_msg->header.stamp), + rclcpp::Duration::from_seconds(0.2))) + .matrix(); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM( + node_ptr_->get_logger(), "Error: cannot get transform from << " + << camera_info_msg->header.frame_id << " to " + << cloud_msg->header.frame_id); + return; + } + // get transformation from map to camera + tf2::Transform tf_camera2map; + try { + geometry_msgs::msg::TransformStamped tf_stamped = tf_buffer.lookupTransform( + camera_info_msg->header.frame_id, "map", rclcpp::Time(camera_info_msg->header.stamp), + rclcpp::Duration::from_seconds(0.2)); + tf2::fromMsg(tf_stamped.transform, tf_camera2map); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM( + node_ptr_->get_logger(), + "Error: cannot get transform from << " << camera_info_msg->header.frame_id << " to map"); + return; + } + + std::vector roi_tls(rois_msg->rois.size()), roi_brs(rois_msg->rois.size()); + image_geometry::PinholeCameraModel pinhole_model; + pinhole_model.fromCameraInfo(*camera_info_msg); + for (size_t i = 0; i < rois_msg->rois.size(); i++) { + calcRoiVectex3D( + rois_msg->rois[i], pinhole_model, traffic_light_position_map, tf_camera2map, roi_tls[i], + roi_brs[i]); + } + + lidar_rays_.clear(); + // points in camera frame + pcl::PointCloud cloud_camera; + // points within roi + pcl::PointCloud cloud_roi; + tier4_autoware_utils::transformPointCloudFromROSMsg(*cloud_msg, cloud_camera, camera2cloud); + + filterCloud(cloud_camera, roi_tls, roi_brs, cloud_roi); + + for (const pcl::PointXYZ & pt : cloud_roi) { + Ray ray = ::point2ray(pt); + lidar_rays_[static_cast(ray.azimuth)][static_cast(ray.elevation)].push_back(ray); + } + for (size_t i = 0; i < roi_tls.size(); i++) { + occlusion_ratios[i] = predict(roi_tls[i], roi_brs[i]); + } +} + +void CloudOcclusionPredictor::calcRoiVectex3D( + const tier4_perception_msgs::msg::TrafficLightRoi & roi, + const image_geometry::PinholeCameraModel & pinhole_model, + const std::map & traffic_light_position_map, + const tf2::Transform & tf_camera2map, pcl::PointXYZ & top_left, pcl::PointXYZ & bottom_right) +{ + if (traffic_light_position_map.count(roi.traffic_light_id) == 0) { + return; + } + double dist2cam = (tf_camera2map * traffic_light_position_map.at(roi.traffic_light_id)).length(); + { + cv::Point2d pixel(roi.roi.x_offset, roi.roi.y_offset); + cv::Point2d rectified_pixel = pinhole_model.rectifyPoint(pixel); + cv::Point3d ray = pinhole_model.projectPixelTo3dRay(rectified_pixel); + double ray_len = std::sqrt(ray.ddot(ray)); + top_left.x = dist2cam * ray.x / ray_len; + top_left.y = dist2cam * ray.y / ray_len; + top_left.z = dist2cam * ray.z / ray_len; + } + { + cv::Point2d pixel(roi.roi.x_offset + roi.roi.width, roi.roi.y_offset + roi.roi.height); + cv::Point2d rectified_pixel = pinhole_model.rectifyPoint(pixel); + cv::Point3d ray = pinhole_model.projectPixelTo3dRay(rectified_pixel); + double ray_len = std::sqrt(ray.ddot(ray)); + bottom_right.x = dist2cam * ray.x / ray_len; + bottom_right.y = dist2cam * ray.y / ray_len; + bottom_right.z = dist2cam * ray.z / ray_len; + } +} + +void CloudOcclusionPredictor::filterCloud( + const pcl::PointCloud & cloud_in, const std::vector & roi_tls, + const std::vector & roi_brs, pcl::PointCloud & cloud_out) +{ + float min_x = 0, max_x = 0, min_y = 0, max_y = 0, min_z = 0, max_z = 0; + for (const auto & pt : roi_tls) { + min_x = std::min(min_x, pt.x); + max_x = std::max(max_x, pt.x); + min_y = std::min(min_y, pt.y); + max_y = std::max(max_y, pt.y); + min_z = std::min(min_z, pt.z); + max_z = std::max(max_z, pt.z); + } + for (const auto & pt : roi_brs) { + min_x = std::min(min_x, pt.x); + max_x = std::max(max_x, pt.x); + min_y = std::min(min_y, pt.y); + max_y = std::max(max_y, pt.y); + min_z = std::min(min_z, pt.z); + max_z = std::max(max_z, pt.z); + } + const float min_dist_to_cam = 1.0f; + cloud_out.clear(); + for (const auto & pt : cloud_in) { + if ( + pt.x < min_x || pt.x > max_x || pt.y < min_y || pt.y > max_y || pt.z < min_z || + pt.z > max_z) { + continue; + } + float dist = pt.getVector3fMap().squaredNorm(); + if ( + dist <= min_dist_to_cam * min_dist_to_cam || + dist >= max_valid_pt_distance_ * max_valid_pt_distance_) { + continue; + } + cloud_out.push_back(pt); + } +} + +void CloudOcclusionPredictor::sampleTrafficLightRoi( + const pcl::PointXYZ & top_left, const pcl::PointXYZ & bottom_right, + uint32_t horizontal_sample_num, uint32_t vertical_sample_num, + pcl::PointCloud & cloud_out) +{ + cloud_out.clear(); + float x1 = top_left.x; + float y1 = top_left.y; + float z1 = top_left.z; + float x2 = bottom_right.x; + float y2 = bottom_right.y; + float z2 = bottom_right.z; + for (uint32_t i1 = 0; i1 < horizontal_sample_num; i1++) { + for (uint32_t i2 = 0; i2 < vertical_sample_num; i2++) { + float x = x1 + (x2 - x1) * i1 / (horizontal_sample_num - 1); + float y = y1 + (y2 - y1) * i2 / (vertical_sample_num - 1); + float z = z1 + (z2 - z1) * i1 / (horizontal_sample_num - 1); + cloud_out.push_back(pcl::PointXYZ(x, y, z)); + } + } +} + +uint32_t CloudOcclusionPredictor::predict( + const pcl::PointXYZ & roi_top_left, const pcl::PointXYZ & roi_bottom_right) +{ + const uint32_t horizontal_sample_num = 20; + const uint32_t vertical_sample_num = 20; + static_assert(horizontal_sample_num > 1 && vertical_sample_num > 1); + const float min_dist_from_occlusion_to_tl = 5.0f; + + pcl::PointCloud tl_sample_cloud; + sampleTrafficLightRoi( + roi_top_left, roi_bottom_right, horizontal_sample_num, vertical_sample_num, tl_sample_cloud); + uint32_t occluded_num = 0; + for (const pcl::PointXYZ & tl_pt : tl_sample_cloud) { + Ray tl_ray = ::point2ray(tl_pt); + bool occluded = false; + // the azimuth and elevation range to search for points that may occlude tl_pt + int min_azimuth = static_cast(tl_ray.azimuth - azimuth_occlusion_resolution_deg_); + int max_azimuth = static_cast(tl_ray.azimuth + azimuth_occlusion_resolution_deg_); + int min_elevation = static_cast(tl_ray.elevation - elevation_occlusion_resolution_deg_); + int max_elevation = static_cast(tl_ray.elevation + elevation_occlusion_resolution_deg_); + /** + * search among lidar rays whose azimuth and elevation angle are close to the tl_ray. + * for a lidar ray r1 whose azimuth and elevation are very close to tl_pt, + * and the distance from r1 to camera is smaller than the distance from tl_pt to camera, + * then tl_pt is occluded by r1. + */ + for (int azimuth = min_azimuth; (azimuth <= max_azimuth) && !occluded; azimuth++) { + for (int elevation = min_elevation; (elevation <= max_elevation) && !occluded; elevation++) { + for (const Ray & lidar_ray : lidar_rays_[azimuth][elevation]) { + if ( + std::abs(lidar_ray.azimuth - tl_ray.azimuth) <= azimuth_occlusion_resolution_deg_ && + std::abs(lidar_ray.elevation - tl_ray.elevation) <= + elevation_occlusion_resolution_deg_ && + lidar_ray.dist < tl_ray.dist - min_dist_from_occlusion_to_tl) { + occluded = true; + break; + } + } + } + } + occluded_num += occluded; + } + return 100 * occluded_num / tl_sample_cloud.size(); +} + +} // namespace traffic_light From db72d847d61fafcaed0b8528dd97647c5b1dc56a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 7 Jul 2023 12:09:10 +0900 Subject: [PATCH 103/118] feat(avoidance): extend lanelets for target filtering (#4189) Signed-off-by: satoshi-ota --- .../src/utils/avoidance/utils.cpp | 24 ++++++++++++++++--- 1 file changed, 21 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index d92adaae62c97..8ffd4b52e74af 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -797,6 +797,25 @@ void filterTargetObjects( ? calcSignedArcLength(path_points, ego_pos, rh->getGoalPose().position) : std::numeric_limits::max(); + // extend lanelets if the reference path is cut for lane change. + const auto & ego_pose = planner_data->self_odometry->pose.pose; + lanelet::ConstLanelets extend_lanelets = data.current_lanelets; + while (rclcpp::ok()) { + const double lane_length = lanelet::utils::getLaneletLength2d(extend_lanelets); + const auto arclength = lanelet::utils::getArcCoordinates(extend_lanelets, ego_pose); + const auto next_lanelets = rh->getNextLanelets(extend_lanelets.back()); + + if (next_lanelets.empty()) { + break; + } + + if (lane_length - arclength.length < planner_data->parameters.forward_path_length) { + extend_lanelets.push_back(next_lanelets.front()); + } else { + break; + } + } + for (auto & o : objects) { const auto & object_pose = o.object.kinematics.initial_pose_with_covariance.pose; const auto object_closest_index = findNearestIndex(path_points, object_pose.position); @@ -955,16 +974,15 @@ void filterTargetObjects( // check traffic light const auto to_traffic_light = - utils::getDistanceToNextTrafficLight(object_pose, data.current_lanelets); + 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 & ego_pose = planner_data->self_odometry->pose.pose; const auto to_crosswalk = - utils::getDistanceToCrosswalk(ego_pose, data.current_lanelets, *rh->getOverallGraphPtr()) - + utils::getDistanceToCrosswalk(ego_pose, extend_lanelets, *rh->getOverallGraphPtr()) - o.longitudinal; { const auto stop_for_crosswalk = From 4693a77e3d4b4f0f2bf0611fb517e7897f4d4510 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 7 Jul 2023 12:24:30 +0900 Subject: [PATCH 104/118] perf(behavior_path_planner): simplify calculateDistanceLimit for dynamic drivable area expansion (#4163) * Add a test for the calculateDistanceLimit function Signed-off-by: Maxime CLEMENT * Remove use of boost::geometry::within to improve performance Signed-off-by: Maxime CLEMENT * [TMP] run behavior_path_planner with gdb Signed-off-by: Maxime CLEMENT * Revert "[TMP] run behavior_path_planner with gdb" This reverts commit b291af4cb55ff2d83148f84bb9272bc61e1f86a8. --------- Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.cpp | 8 +++- .../drivable_area_expansion/expansion.cpp | 12 +----- .../test/test_drivable_area_expansion.cpp | 38 +++++++++++++++++++ 3 files changed, 46 insertions(+), 12 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 819265b70abbe..21e3580c1f19a 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 @@ -33,13 +33,19 @@ void expandDrivableArea( { const auto uncrossable_lines = extractUncrossableLines(*route_handler.getLaneletMapPtr(), params.avoid_linestring_types); + multilinestring_t uncrossable_lines_in_range; + const auto & p = path.points.front().point.pose.position; + for (const auto & line : uncrossable_lines) + if (boost::geometry::distance(line, point_t{p.x, p.y}) < params.max_path_arc_length) + uncrossable_lines_in_range.push_back(line); const auto path_footprints = createPathFootprints(path, params); const auto predicted_paths = createObjectFootprints(dynamic_objects, params); const auto expansion_polygons = params.expansion_method == "lanelet" ? createExpansionLaneletPolygons( path_lanes, route_handler, path_footprints, predicted_paths, params) - : createExpansionPolygons(path, path_footprints, predicted_paths, uncrossable_lines, params); + : createExpansionPolygons( + path, path_footprints, predicted_paths, uncrossable_lines_in_range, params); const auto expanded_drivable_area = createExpandedDrivableAreaPolygon(path, expansion_polygons); updateDrivableAreaBounds(path, expanded_drivable_area); } diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp index 4bdbdedf44c77..79e15bf4e68d7 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp @@ -25,10 +25,6 @@ double calculateDistanceLimit( const multilinestring_t & limit_lines) { auto dist_limit = std::numeric_limits::max(); - boost::geometry::for_each_point(limit_lines, [&](const auto & point) { - if (boost::geometry::within(point, expansion_polygon)) - dist_limit = std::min(dist_limit, boost::geometry::distance(point, base_ls)); - }); multipoint_t intersections; boost::geometry::intersection(expansion_polygon, limit_lines, intersections); for (const auto & p : intersections) @@ -42,16 +38,10 @@ double calculateDistanceLimit( { auto dist_limit = std::numeric_limits::max(); for (const auto & polygon : limit_polygons) { - for (const auto & p : polygon.outer()) { - if (boost::geometry::within(p, expansion_polygon)) { - dist_limit = std::min(dist_limit, boost::geometry::distance(p, base_ls)); - } - } multipoint_t intersections; boost::geometry::intersection(expansion_polygon, polygon, intersections); - for (const auto & p : intersections) { + for (const auto & p : intersections) dist_limit = std::min(dist_limit, boost::geometry::distance(p, base_ls)); - } } return dist_limit; } diff --git a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp index d1e9873e92c4c..7c4967be14bb8 100644 --- a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include "behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp" +#include "behavior_path_planner/utils/drivable_area_expansion/expansion.hpp" #include "behavior_path_planner/utils/drivable_area_expansion/path_projection.hpp" #include "behavior_path_planner/utils/drivable_area_expansion/types.hpp" #include "lanelet2_extension/utility/message_conversion.hpp" @@ -288,3 +289,40 @@ TEST(DrivableAreaExpansionProjection, expandDrivableArea) EXPECT_NEAR(path.right_bound[2].x, 2.0, eps); EXPECT_NEAR(path.right_bound[2].y, -1.0, eps); } + +TEST(DrivableAreaExpansion, calculateDistanceLimit) +{ + using drivable_area_expansion::calculateDistanceLimit; + using drivable_area_expansion::linestring_t; + using drivable_area_expansion::multilinestring_t; + using drivable_area_expansion::polygon_t; + + { + const linestring_t base_ls = {{0.0, 0.0}, {10.0, 0.0}}; + const multilinestring_t uncrossable_lines = {}; + const polygon_t expansion_polygon = { + {{0.0, -4.0}, {0.0, 4.0}, {10.0, 4.0}, {10.0, -4.0}, {10.0, -4.0}}, {}}; + const auto limit_distance = + calculateDistanceLimit(base_ls, expansion_polygon, uncrossable_lines); + EXPECT_NEAR(limit_distance, std::numeric_limits::max(), 1e-9); + } + { + const linestring_t base_ls = {{0.0, 0.0}, {10.0, 0.0}}; + const linestring_t uncrossable_line = {{0.0, 2.0}, {10.0, 2.0}}; + const polygon_t expansion_polygon = { + {{0.0, -4.0}, {0.0, 4.0}, {10.0, 4.0}, {10.0, -4.0}, {10.0, -4.0}}, {}}; + const auto limit_distance = + calculateDistanceLimit(base_ls, expansion_polygon, {uncrossable_line}); + EXPECT_NEAR(limit_distance, 2.0, 1e-9); + } + { + const linestring_t base_ls = {{0.0, 0.0}, {10.0, 0.0}}; + const multilinestring_t uncrossable_lines = { + {{0.0, 2.0}, {10.0, 2.0}}, {{0.0, 1.5}, {10.0, 1.0}}}; + const polygon_t expansion_polygon = { + {{0.0, -4.0}, {0.0, 4.0}, {10.0, 4.0}, {10.0, -4.0}, {10.0, -4.0}}, {}}; + const auto limit_distance = + calculateDistanceLimit(base_ls, expansion_polygon, uncrossable_lines); + EXPECT_NEAR(limit_distance, 1.0, 1e-9); + } +} From 86448a7ea39d9cfa7d58d6c0b50e9ada8d2c8649 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 7 Jul 2023 12:56:05 +0900 Subject: [PATCH 105/118] feat(probabilistic_occupancy_grid_map): add projective raytracing option from scan_origin (#4170) --- .../CMakeLists.txt | 18 +- .../README.md | 55 +-- .../binary_bayes_filter_updater.param.yaml | 2 +- .../config/grid_map_param.yaml | 22 ++ ...erscan_based_occupancy_grid_map.param.yaml | 4 +- ...tcloud_based_occupancy_grid_map.param.yaml | 11 +- ...id_map_side_view_2nd_projection.drawio.svg | 238 +++++++++++++ ...id_map.hpp => occupancy_grid_map_base.hpp} | 21 +- .../occupancy_grid_map_fixed.hpp | 47 +++ .../occupancy_grid_map_projective.hpp | 55 +++ ...intcloud_based_occupancy_grid_map_node.hpp | 6 +- .../launch/debug.launch.xml | 9 + .../package.xml | 4 + .../pointcloud-based-occupancy-grid-map.md | 28 +- .../occupancy_grid_map_base.cpp | 233 +++++++++++++ ...d_map.cpp => occupancy_grid_map_fixed.cpp} | 203 +----------- .../occupancy_grid_map_projective.cpp | 312 ++++++++++++++++++ ...intcloud_based_occupancy_grid_map_node.cpp | 50 ++- 18 files changed, 1062 insertions(+), 256 deletions(-) create mode 100644 perception/probabilistic_occupancy_grid_map/config/grid_map_param.yaml create mode 100644 perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_2nd_projection.drawio.svg rename perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/{occupancy_grid_map.hpp => occupancy_grid_map_base.hpp} (91%) create mode 100644 perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp create mode 100644 perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp create mode 100644 perception/probabilistic_occupancy_grid_map/launch/debug.launch.xml create mode 100644 perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.cpp rename perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/{occupancy_grid_map.cpp => occupancy_grid_map_fixed.cpp} (57%) create mode 100644 perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp diff --git a/perception/probabilistic_occupancy_grid_map/CMakeLists.txt b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt index 777dda051b787..facb61d82abb0 100644 --- a/perception/probabilistic_occupancy_grid_map/CMakeLists.txt +++ b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt @@ -13,16 +13,25 @@ include_directories( ${EIGEN3_INCLUDE_DIR} ) +ament_auto_add_library(${PROJECT_NAME}_common SHARED + src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp + src/utils/utils.cpp +) +target_link_libraries(${PROJECT_NAME}_common + ${PCL_LIBRARIES} +) + # PointcloudBasedOccupancyGridMap ament_auto_add_library(pointcloud_based_occupancy_grid_map SHARED src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp - src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp - src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp - src/utils/utils.cpp + src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.cpp + src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp + src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp ) target_link_libraries(pointcloud_based_occupancy_grid_map ${PCL_LIBRARIES} + ${PROJECT_NAME}_common ) rclcpp_components_register_node(pointcloud_based_occupancy_grid_map @@ -34,12 +43,11 @@ rclcpp_components_register_node(pointcloud_based_occupancy_grid_map ament_auto_add_library(laserscan_based_occupancy_grid_map SHARED src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp - src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp - src/utils/utils.cpp ) target_link_libraries(laserscan_based_occupancy_grid_map ${PCL_LIBRARIES} + ${PROJECT_NAME}_common ) rclcpp_components_register_node(laserscan_based_occupancy_grid_map diff --git a/perception/probabilistic_occupancy_grid_map/README.md b/perception/probabilistic_occupancy_grid_map/README.md index b9caaac29cb01..962bcdc6f154f 100644 --- a/perception/probabilistic_occupancy_grid_map/README.md +++ b/perception/probabilistic_occupancy_grid_map/README.md @@ -24,25 +24,29 @@ Config parameters are managed in `config/*.yaml` and here shows its outline. - Pointcloud based occupancy grid map -| Ros param name | Default value | -| --------------------------------- | ------------- | -| map_frame | "map" | -| base_link_frame | "base_link" | -| scan_origin_frame | "base_link" | -| gridmap_origin_frame | "base_link" | -| use_height_filter | true | -| enable_single_frame_mode | false | -| map_length | 100.0 [m] | -| map_width | 100.0 [m] | -| map_resolution | 0.5 [m] | -| input_obstacle_pointcloud | true | -| input_obstacle_and_raw_pointcloud | true | +| Ros param name | Default value | +| -------------------------------------------- | ------------- | +| map_frame | "map" | +| base_link_frame | "base_link" | +| scan_origin_frame | "base_link" | +| gridmap_origin_frame | "base_link" | +| use_height_filter | true | +| enable_single_frame_mode | false | +| filter_obstacle_pointcloud_by_raw_pointcloud | false | +| map_length | 150.0 [m] | +| map_resolution | 0.5 [m] | +| use_projection | false | +| projection_dz_threshold | 0.01 | +| obstacle_separation_threshold | 1.0 | +| input_obstacle_pointcloud | true | +| input_obstacle_and_raw_pointcloud | true | - Laserscan based occupancy grid map | Ros param name | Default value | | ------------------------ | ------------- | -| map_length | 100 [m] | +| map_length | 150 [m] | +| map_width | 150 [m] | | map_resolution | 0.5 [m] | | use_height_filter | true | | enable_single_frame_mode | false | @@ -55,15 +59,14 @@ Config parameters are managed in `config/*.yaml` and here shows its outline. Additional argument is shown below: -| Name | Default | Description | -| ----------------------------------------------- | ------------------------------ | ----------------------------------------------------------------------------------------------------------------------------------------- | -| `use_multithread` | `false` | whether to use multithread | -| `use_intra_process` | `false` | | -| `map_origin` | `` | parameter to override `map_origin_frame` which means grid map origin | -| `scan_origin` | `` | parameter to override `scan_origin_frame` which means scanning center | -| `output` | `occupancy_grid` | output name | -| `use_pointcloud_container` | `false` | | -| `container_name` | `occupancy_grid_map_container` | | -| `filter_obstacle_pointcloud_by_raw_pointcloud_` | `false` | only for pointcloud based method. If true, the node use raw pointcloud to filter obstacle pointcloud. Options for the limited FOV sensor. | -| `input_obstacle_pointcloud` | `false` | only for laserscan based method. If true, the node subscribe obstacle pointcloud | -| `input_obstacle_and_raw_pointcloud` | `true` | only for laserscan based method. If true, the node subscribe both obstacle and raw pointcloud | +| Name | Default | Description | +| ----------------------------------- | ------------------------------ | --------------------------------------------------------------------------------------------- | +| `use_multithread` | `false` | whether to use multithread | +| `use_intra_process` | `false` | | +| `map_origin` | `` | parameter to override `map_origin_frame` which means grid map origin | +| `scan_origin` | `` | parameter to override `scan_origin_frame` which means scanning center | +| `output` | `occupancy_grid` | output name | +| `use_pointcloud_container` | `false` | | +| `container_name` | `occupancy_grid_map_container` | | +| `input_obstacle_pointcloud` | `false` | only for laserscan based method. If true, the node subscribe obstacle pointcloud | +| `input_obstacle_and_raw_pointcloud` | `true` | only for laserscan based method. If true, the node subscribe both obstacle and raw pointcloud | diff --git a/perception/probabilistic_occupancy_grid_map/config/binary_bayes_filter_updater.param.yaml b/perception/probabilistic_occupancy_grid_map/config/binary_bayes_filter_updater.param.yaml index 4e335e35740ab..cb7bbe166f475 100644 --- a/perception/probabilistic_occupancy_grid_map/config/binary_bayes_filter_updater.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/binary_bayes_filter_updater.param.yaml @@ -5,4 +5,4 @@ occupied_to_free: 0.05 free_to_occupied: 0.2 free_to_free: 0.8 - v_ratio: 10.0 + v_ratio: 0.1 diff --git a/perception/probabilistic_occupancy_grid_map/config/grid_map_param.yaml b/perception/probabilistic_occupancy_grid_map/config/grid_map_param.yaml new file mode 100644 index 0000000000000..4a00b3131f671 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/config/grid_map_param.yaml @@ -0,0 +1,22 @@ +/**: + ros__parameters: + grid_map_topic: /perception/occupancy_grid_map/occupancy_grid_map_node/debug/grid_map + grid_map_visualizations: [grid_1st_step, grid_2nd_step, grid_3rd_step] + grid_1st_step: + type: occupancy_grid + params: + layer: filled_free_to_farthest + data_min: 0.0 + data_max: 100.0 + grid_2nd_step: + type: occupancy_grid + params: + layer: added_unknown + data_min: 0.0 + data_max: 100.0 + grid_3rd_step: + type: occupancy_grid + params: + layer: added_obstacle + data_min: 0.0 + data_max: 100.0 diff --git a/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml b/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml index b8ec4d7f24046..9dcc722587e92 100644 --- a/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml @@ -13,6 +13,6 @@ max_height: 2.0 enable_single_frame_mode: false - map_length: 100.0 - map_width: 100.0 + map_length: 150.0 + map_width: 150.0 map_resolution: 0.5 diff --git a/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml b/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml index 6f00e9521c7ef..8077bdec5008e 100644 --- a/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - map_length: 100.0 # [m] + map_length: 150.0 # [m] map_resolution: 0.5 # [m] height_filter: @@ -18,4 +18,13 @@ # center of the grid map gridmap_origin_frame: "base_link" # ray-tracing center: main sensor frame is preferable like: "velodyne_top" + # base_link should not be used with "OccupancyGridMapProjectiveBlindSpot" scan_origin_frame: "base_link" + + grid_map_type: "OccupancyGridMapFixedBlindSpot" + OccupancyGridMapFixedBlindSpot: + distance_margin: 1.0 + OccupancyGridMapProjectiveBlindSpot: + projection_dz_threshold: 0.01 # [m] for avoiding null division + obstacle_separation_threshold: 1.0 # [m] fill the interval between obstacles with unknown for this length + pub_debug_grid: false diff --git a/perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_2nd_projection.drawio.svg b/perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_2nd_projection.drawio.svg new file mode 100644 index 0000000000000..437b01bd04d58 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_2nd_projection.drawio.svg @@ -0,0 +1,238 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ ground +
+
+
+
+ ground +
+
+ + + +
+
+
lidar
+
+
+
+ lidar +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
projection length
+
+
+
+ projection length +
+
+ + + +
+
+
ignored
+
+
+
+ ignored +
+
+ + + + + + + +
+
+
projected point
+
+
+
+ projected point +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp similarity index 91% rename from perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp rename to perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp index 88f2cfbc146f3..8f8e1e503d388 100644 --- a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp @@ -49,8 +49,8 @@ * David V. Lu!! *********************************************************************/ -#ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_ -#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_ +#ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_ +#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_ #include #include @@ -64,23 +64,24 @@ namespace costmap_2d using geometry_msgs::msg::Pose; using sensor_msgs::msg::PointCloud2; -class OccupancyGridMap : public nav2_costmap_2d::Costmap2D +class OccupancyGridMapInterface : public nav2_costmap_2d::Costmap2D { public: - OccupancyGridMap( + OccupancyGridMapInterface( const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution); - void updateWithPointCloud( + virtual void updateWithPointCloud( const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, - const Pose & robot_pose, const Pose & scan_origin); + const Pose & robot_pose, const Pose & scan_origin) = 0; void updateOrigin(double new_origin_x, double new_origin_y) override; - - void setCellValue(const double wx, const double wy, const unsigned char cost); - void raytrace( const double source_x, const double source_y, const double target_x, const double target_y, const unsigned char cost); + void setCellValue(const double wx, const double wy, const unsigned char cost); + using nav2_costmap_2d::Costmap2D::resetMaps; + + virtual void initRosParam(rclcpp::Node & node) = 0; private: bool worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my) const; @@ -91,4 +92,4 @@ class OccupancyGridMap : public nav2_costmap_2d::Costmap2D } // namespace costmap_2d -#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_ +#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp new file mode 100644 index 0000000000000..5755cd2c889be --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp @@ -0,0 +1,47 @@ +// Copyright 2021 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 POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_ +#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_ + +#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" + +namespace costmap_2d +{ +using geometry_msgs::msg::Pose; +using sensor_msgs::msg::PointCloud2; + +class OccupancyGridMapFixedBlindSpot : public OccupancyGridMapInterface +{ +public: + OccupancyGridMapFixedBlindSpot( + const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution); + + void updateWithPointCloud( + const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, + const Pose & robot_pose, const Pose & scan_origin) override; + + using OccupancyGridMapInterface::raytrace; + using OccupancyGridMapInterface::setCellValue; + using OccupancyGridMapInterface::updateOrigin; + + void initRosParam(rclcpp::Node & node) override; + +private: + double distance_margin_; +}; + +} // namespace costmap_2d + +#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp new file mode 100644 index 0000000000000..bc278772e9737 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp @@ -0,0 +1,55 @@ +// Copyright 2021 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 POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_ +#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_ + +#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" + +#include + +#include + +namespace costmap_2d +{ +using geometry_msgs::msg::Pose; +using sensor_msgs::msg::PointCloud2; + +class OccupancyGridMapProjectiveBlindSpot : public OccupancyGridMapInterface +{ +public: + OccupancyGridMapProjectiveBlindSpot( + const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution); + + void updateWithPointCloud( + const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, + const Pose & robot_pose, const Pose & scan_origin) override; + + using OccupancyGridMapInterface::raytrace; + using OccupancyGridMapInterface::setCellValue; + using OccupancyGridMapInterface::updateOrigin; + + void initRosParam(rclcpp::Node & node) override; + +private: + double projection_dz_threshold_; + double obstacle_separation_threshold_; + bool pub_debug_grid_; + grid_map::GridMap debug_grid_; + rclcpp::Publisher::SharedPtr debug_grid_map_publisher_ptr_; +}; + +} // namespace costmap_2d + +#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_ diff --git a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp index 595937b89bbdc..e34899bb98b0c 100644 --- a/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp @@ -15,7 +15,7 @@ #ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ #define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_ -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp" +#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" #include "updater/occupancy_grid_map_binary_bayes_filter_updater.hpp" #include "updater/occupancy_grid_map_updater_interface.hpp" @@ -41,6 +41,7 @@ namespace occupancy_grid_map { using builtin_interfaces::msg::Time; +using costmap_2d::OccupancyGridMapInterface; using costmap_2d::OccupancyGridMapUpdaterInterface; using laser_geometry::LaserProjection; using nav2_costmap_2d::Costmap2D; @@ -77,7 +78,8 @@ class PointcloudBasedOccupancyGridMapNode : public rclcpp::Node using Sync = message_filters::Synchronizer; std::shared_ptr sync_ptr_; - std::shared_ptr occupancy_grid_map_updater_ptr_; + std::unique_ptr occupancy_grid_map_ptr_; + std::unique_ptr occupancy_grid_map_updater_ptr_; // ROS Parameters std::string map_frame_; diff --git a/perception/probabilistic_occupancy_grid_map/launch/debug.launch.xml b/perception/probabilistic_occupancy_grid_map/launch/debug.launch.xml new file mode 100644 index 0000000000000..72edb00ea606a --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/launch/debug.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/perception/probabilistic_occupancy_grid_map/package.xml b/perception/probabilistic_occupancy_grid_map/package.xml index 2bd3a9aa8133c..a6f4d46242a3f 100644 --- a/perception/probabilistic_occupancy_grid_map/package.xml +++ b/perception/probabilistic_occupancy_grid_map/package.xml @@ -6,6 +6,7 @@ generate probabilistic occupancy grid map Yukihiro Saito Yoshi Ri + Mamoru Sobue Apache License 2.0 Yukihiro Saito @@ -14,6 +15,9 @@ autoware_cmake eigen3_cmake_module + grid_map_costmap_2d + grid_map_msgs + grid_map_ros laser_geometry message_filters nav2_costmap_2d diff --git a/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md b/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md index c3ab03b1842d0..626d8fde6ebdf 100644 --- a/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md +++ b/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md @@ -6,8 +6,8 @@ ### 1st step -First of all, obstacle and raw pointcloud as input are transformed into a polar coordinate system and divided into bin per angle_increment. -At this time, each point belonging to each bin is stored as range data. In addition, the x,y information in the map coordinate is also stored for ray trace on map coordinate. +First of all, input obstacle/raw pointcloud are transformed into the polar coordinate centered around `scan_origin` and divided int ocircular bins per angle_increment respectively. +At this time, each point belonging to each bin is stored as range data. In addition, the x,y information in the map coordinate is also stored for raytracing on the map coordinate. The bin contains the following information for each point - range data from origin of raytrace @@ -30,8 +30,7 @@ The ray trace is done by Bresenham's line algorithm. ![pointcloud_based_occupancy_grid_map_side_view_1st](./image/pointcloud_based_occupancy_grid_map_side_view_1st.svg) 2. Fill in the unknown cells. - Assume that unknown is behind the obstacle, since the back of the obstacle is a blind spot. - Therefore, the unknown are assumed to be the cells that are more than a distance margin from each obstacle point. + Based on the assumption that `UNKNOWN` is behind the obstacle, the cells that are more than a distance margin from each obstacle point are filled with `UNKOWN` ![pointcloud_based_occupancy_grid_map_side_view_2nd](./image/pointcloud_based_occupancy_grid_map_side_view_2nd.svg) @@ -41,9 +40,13 @@ The ray trace is done by Bresenham's line algorithm. - The obstacle point cloud is processed and may not match the raw pointcloud. - The input may be inaccurate and obstacle points may not be determined as obstacles. + When the parameter `grid_map_type` is "OccupancyGridMapProjectiveBlindSpot" and the `scan_origin` is a sensor frame like `velodyne_top` for instance, for each obstacle pointcloud, if there are no _visible_ raw pointclouds that are located above the projected ray from the `scan_origin` to that obstacle pointcloud, the cells between the obstacle pointcloud and the `projected point` are filled with `UNKNOWN`. Note that the `scan_origin` should not be `base_link` if this flag is true because otherwise all the cells behind the obstacle point clouds would be filled with `UNKNOWN`. + + ![pointcloud_based_occupancy_grid_map_side_view_2nd_projection](./image/pointcloud_based_occupancy_grid_map_side_view_2nd_projection.drawio.svg) + 3. Fill in the occupied cells. Fill in the point where the obstacle point is located with occupied. - In addition, If the distance between obstacle points is less than or equal to the distance margin, it is filled with occupied because the input may be inaccurate and obstacle points may not be determined as obstacles. + In addition, If the distance between obstacle points is less than or equal to the distance margin, that interval is filled with `OCCUPIED` because the input may be inaccurate and obstacle points may not be determined as obstacles. ![pointcloud_based_occupancy_grid_map_side_view_3rd](./image/pointcloud_based_occupancy_grid_map_side_view_3rd.svg) @@ -85,6 +88,7 @@ $$ | `use_height_filter` | bool | whether to height filter for `~/input/obstacle_pointcloud` and `~/input/raw_pointcloud`? By default, the height is set to -1~2m. | | `map_length` | double | The length of the map. -100 if it is 50~50[m] | | `map_resolution` | double | The map cell resolution [m] | +| `grid_map_type` | string | The type of grid map for estimating `UNKNOWN` region behind obstacle point clouds | ## Assumptions / Known limits @@ -104,3 +108,17 @@ In several places we have modified the external code written in BSD3 license. - The update probability of the binary Bayesian filter is currently hard-coded and requires a code change to be modified. - Since there is no special support for moving objects, the probability of existence is not increased for fast objects. + +## How to debug + +If `grid_map_type` is "OccupancyGridMapProjectiveBlindSpot" and `pub_debug_grid` is `true`, it is possible to check the each process of grid map generation by running + +```shell +ros2 launch probabilistic_occupancy_grid_map debug.launch.xml +``` + +and visualizing the following occupancy grid map topics (which are listed in config/grid_map_param.yaml): + +- `/perception/occupancy_grid_map/grid_1st_step`: `FREE` cells are filled +- `/perception/occupancy_grid_map/grid_2nd_step`: `UNKNOWN` cells are filled +- `/perception/occupancy_grid_map/grid_3rd_step`: `OCCUPIED` cells are filled diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.cpp new file mode 100644 index 0000000000000..4e71c4bda3f21 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.cpp @@ -0,0 +1,233 @@ +// Copyright 2021 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. +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, 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 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. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ + +#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp" + +#include "cost_value.hpp" +#include "utils/utils.hpp" + +#include +#include +#include + +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#include +#else +#include + +#include +#endif + +#include +namespace costmap_2d +{ +using sensor_msgs::PointCloud2ConstIterator; + +OccupancyGridMapInterface::OccupancyGridMapInterface( + const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) +: Costmap2D(cells_size_x, cells_size_y, resolution, 0.f, 0.f, occupancy_cost_value::NO_INFORMATION) +{ +} + +bool OccupancyGridMapInterface::worldToMap( + double wx, double wy, unsigned int & mx, unsigned int & my) const +{ + if (wx < origin_x_ || wy < origin_y_) { + return false; + } + + mx = static_cast(std::floor((wx - origin_x_) / resolution_)); + my = static_cast(std::floor((wy - origin_y_) / resolution_)); + + if (mx < size_x_ && my < size_y_) { + return true; + } + + return false; +} + +void OccupancyGridMapInterface::updateOrigin(double new_origin_x, double new_origin_y) +{ + // project the new origin into the grid + int cell_ox{static_cast(std::floor((new_origin_x - origin_x_) / resolution_))}; + int cell_oy{static_cast(std::floor((new_origin_y - origin_y_) / resolution_))}; + + // compute the associated world coordinates for the origin cell + // because we want to keep things grid-aligned + double new_grid_ox{origin_x_ + cell_ox * resolution_}; + double new_grid_oy{origin_y_ + cell_oy * resolution_}; + + // To save casting from unsigned int to int a bunch of times + int size_x{static_cast(size_x_)}; + int size_y{static_cast(size_y_)}; + + // we need to compute the overlap of the new and existing windows + int lower_left_x{std::min(std::max(cell_ox, 0), size_x)}; + int lower_left_y{std::min(std::max(cell_oy, 0), size_y)}; + int upper_right_x{std::min(std::max(cell_ox + size_x, 0), size_x)}; + int upper_right_y{std::min(std::max(cell_oy + size_y, 0), size_y)}; + + unsigned int cell_size_x = upper_right_x - lower_left_x; + unsigned int cell_size_y = upper_right_y - lower_left_y; + + // we need a map to store the obstacles in the window temporarily + unsigned char * local_map = new unsigned char[cell_size_x * cell_size_y]; + + // copy the local window in the costmap to the local map + copyMapRegion( + costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, + cell_size_y); + + // now we'll set the costmap to be completely unknown if we track unknown space + resetMaps(); + + // update the origin with the appropriate world coordinates + origin_x_ = new_grid_ox; + origin_y_ = new_grid_oy; + + // compute the starting cell location for copying data back in + int start_x{lower_left_x - cell_ox}; + int start_y{lower_left_y - cell_oy}; + + // now we want to copy the overlapping information back into the map, but in its new location + copyMapRegion( + local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y); + + // make sure to clean up + delete[] local_map; +} + +void OccupancyGridMapInterface::setCellValue( + const double wx, const double wy, const unsigned char cost) +{ + MarkCell marker(costmap_, cost); + unsigned int mx{}; + unsigned int my{}; + if (!worldToMap(wx, wy, mx, my)) { + RCLCPP_DEBUG(logger_, "Computing map coords failed"); + return; + } + const unsigned int index = getIndex(mx, my); + marker(index); +} + +void OccupancyGridMapInterface::raytrace( + const double source_x, const double source_y, const double target_x, const double target_y, + const unsigned char cost) +{ + unsigned int x0{}; + unsigned int y0{}; + const double ox{source_x}; + const double oy{source_y}; + if (!worldToMap(ox, oy, x0, y0)) { + RCLCPP_DEBUG( + logger_, + "The origin for the sensor at (%.2f, %.2f) is out of map bounds. So, the costmap cannot " + "raytrace for it.", + ox, oy); + return; + } + + // we can pre-compute the endpoints of the map outside of the inner loop... we'll need these later + const double origin_x = origin_x_, origin_y = origin_y_; + const double map_end_x = origin_x + size_x_ * resolution_; + const double map_end_y = origin_y + size_y_ * resolution_; + + double wx = target_x; + double wy = target_y; + + // now we also need to make sure that the endpoint we're ray-tracing + // to isn't off the costmap and scale if necessary + const double a = wx - ox; + const double b = wy - oy; + + // the minimum value to raytrace from is the origin + if (wx < origin_x) { + const double t = (origin_x - ox) / a; + wx = origin_x; + wy = oy + b * t; + } + if (wy < origin_y) { + const double t = (origin_y - oy) / b; + wx = ox + a * t; + wy = origin_y; + } + + // the maximum value to raytrace to is the end of the map + if (wx > map_end_x) { + const double t = (map_end_x - ox) / a; + wx = map_end_x - .001; + wy = oy + b * t; + } + if (wy > map_end_y) { + const double t = (map_end_y - oy) / b; + wx = ox + a * t; + wy = map_end_y - .001; + } + + // now that the vector is scaled correctly... we'll get the map coordinates of its endpoint + unsigned int x1{}; + unsigned int y1{}; + + // check for legality just in case + if (!worldToMap(wx, wy, x1, y1)) { + return; + } + + constexpr unsigned int cell_raytrace_range = 10000; // large number to ignore range threshold + MarkCell marker(costmap_, cost); + raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_range); +} + +} // namespace costmap_2d diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp similarity index 57% rename from perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp rename to perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp index b26e9a14a2b5e..cf861ffddfd08 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp @@ -11,49 +11,13 @@ // 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. -/********************************************************************* - * - * Software License Agreement (BSD License) - * - * Copyright (c) 2008, 2013, 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 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. - * - * Author: Eitan Marder-Eppstein - * David V. Lu!! - *********************************************************************/ -#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp" +#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp" #include "cost_value.hpp" #include "utils/utils.hpp" +#include #include #include @@ -73,79 +37,12 @@ namespace costmap_2d { using sensor_msgs::PointCloud2ConstIterator; -OccupancyGridMap::OccupancyGridMap( +OccupancyGridMapFixedBlindSpot::OccupancyGridMapFixedBlindSpot( const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) -: Costmap2D(cells_size_x, cells_size_y, resolution, 0.f, 0.f, occupancy_cost_value::NO_INFORMATION) +: OccupancyGridMapInterface(cells_size_x, cells_size_y, resolution) { } -bool OccupancyGridMap::worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my) const -{ - if (wx < origin_x_ || wy < origin_y_) { - return false; - } - - mx = static_cast(std::floor((wx - origin_x_) / resolution_)); - my = static_cast(std::floor((wy - origin_y_) / resolution_)); - - if (mx < size_x_ && my < size_y_) { - return true; - } - - return false; -} - -void OccupancyGridMap::updateOrigin(double new_origin_x, double new_origin_y) -{ - // project the new origin into the grid - int cell_ox{static_cast(std::floor((new_origin_x - origin_x_) / resolution_))}; - int cell_oy{static_cast(std::floor((new_origin_y - origin_y_) / resolution_))}; - - // compute the associated world coordinates for the origin cell - // because we want to keep things grid-aligned - double new_grid_ox{origin_x_ + cell_ox * resolution_}; - double new_grid_oy{origin_y_ + cell_oy * resolution_}; - - // To save casting from unsigned int to int a bunch of times - int size_x{static_cast(size_x_)}; - int size_y{static_cast(size_y_)}; - - // we need to compute the overlap of the new and existing windows - int lower_left_x{std::min(std::max(cell_ox, 0), size_x)}; - int lower_left_y{std::min(std::max(cell_oy, 0), size_y)}; - int upper_right_x{std::min(std::max(cell_ox + size_x, 0), size_x)}; - int upper_right_y{std::min(std::max(cell_oy + size_y, 0), size_y)}; - - unsigned int cell_size_x = upper_right_x - lower_left_x; - unsigned int cell_size_y = upper_right_y - lower_left_y; - - // we need a map to store the obstacles in the window temporarily - unsigned char * local_map = new unsigned char[cell_size_x * cell_size_y]; - - // copy the local window in the costmap to the local map - copyMapRegion( - costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, - cell_size_y); - - // now we'll set the costmap to be completely unknown if we track unknown space - resetMaps(); - - // update the origin with the appropriate world coordinates - origin_x_ = new_grid_ox; - origin_y_ = new_grid_oy; - - // compute the starting cell location for copying data back in - int start_x{lower_left_x - cell_ox}; - int start_y{lower_left_y - cell_oy}; - - // now we want to copy the overlapping information back into the map, but in its new location - copyMapRegion( - local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y); - - // make sure to clean up - delete[] local_map; -} - /** * @brief update Gridmap with PointCloud * @@ -154,7 +51,7 @@ void OccupancyGridMap::updateOrigin(double new_origin_x, double new_origin_y) * @param robot_pose frame of the input point cloud (usually base_link) * @param scan_origin manually chosen grid map origin frame */ -void OccupancyGridMap::updateWithPointCloud( +void OccupancyGridMapFixedBlindSpot::updateWithPointCloud( const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, const Pose & robot_pose, const Pose & scan_origin) { @@ -222,7 +119,6 @@ void OccupancyGridMap::updateWithPointCloud( } // First step: Initialize cells to the final point with freespace - constexpr double distance_margin = 1.0; for (size_t bin_index = 0; bin_index < obstacle_pointcloud_angle_bins.size(); ++bin_index) { auto & obstacle_pointcloud_angle_bin = obstacle_pointcloud_angle_bins.at(bin_index); auto & raw_pointcloud_angle_bin = raw_pointcloud_angle_bins.at(bin_index); @@ -235,7 +131,7 @@ void OccupancyGridMap::updateWithPointCloud( } else if (obstacle_pointcloud_angle_bin.empty()) { end_distance = raw_pointcloud_angle_bin.back(); } else { - end_distance = obstacle_pointcloud_angle_bin.back().range + distance_margin < + end_distance = obstacle_pointcloud_angle_bin.back().range + distance_margin_ < raw_pointcloud_angle_bin.back().range ? raw_pointcloud_angle_bin.back() : obstacle_pointcloud_angle_bin.back(); @@ -255,7 +151,7 @@ void OccupancyGridMap::updateWithPointCloud( while (raw_distance_iter != raw_pointcloud_angle_bin.end()) { if ( raw_distance_iter->range < - obstacle_pointcloud_angle_bin.at(dist_index).range + distance_margin) + obstacle_pointcloud_angle_bin.at(dist_index).range + distance_margin_) raw_distance_iter++; else break; @@ -278,7 +174,7 @@ void OccupancyGridMap::updateWithPointCloud( auto next_obstacle_point_distance = std::abs( obstacle_pointcloud_angle_bin.at(dist_index + 1).range - obstacle_pointcloud_angle_bin.at(dist_index).range); - if (next_obstacle_point_distance <= distance_margin) { + if (next_obstacle_point_distance <= distance_margin_) { continue; } else if (no_freespace_point) { const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); @@ -318,7 +214,7 @@ void OccupancyGridMap::updateWithPointCloud( auto next_obstacle_point_distance = std::abs( obstacle_pointcloud_angle_bin.at(dist_index + 1).range - obstacle_pointcloud_angle_bin.at(dist_index).range); - if (next_obstacle_point_distance <= distance_margin) { + if (next_obstacle_point_distance <= distance_margin_) { const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); const auto & target = obstacle_pointcloud_angle_bin.at(dist_index + 1); raytrace(source.wx, source.wy, target.wx, target.wy, occupancy_cost_value::LETHAL_OBSTACLE); @@ -328,85 +224,10 @@ void OccupancyGridMap::updateWithPointCloud( } } -void OccupancyGridMap::setCellValue(const double wx, const double wy, const unsigned char cost) -{ - MarkCell marker(costmap_, cost); - unsigned int mx{}; - unsigned int my{}; - if (!worldToMap(wx, wy, mx, my)) { - RCLCPP_DEBUG(logger_, "Computing map coords failed"); - return; - } - const unsigned int index = getIndex(mx, my); - marker(index); -} - -void OccupancyGridMap::raytrace( - const double source_x, const double source_y, const double target_x, const double target_y, - const unsigned char cost) +void OccupancyGridMapFixedBlindSpot::initRosParam(rclcpp::Node & node) { - unsigned int x0{}; - unsigned int y0{}; - const double ox{source_x}; - const double oy{source_y}; - if (!worldToMap(ox, oy, x0, y0)) { - RCLCPP_DEBUG( - logger_, - "The origin for the sensor at (%.2f, %.2f) is out of map bounds. So, the costmap cannot " - "raytrace for it.", - ox, oy); - return; - } - - // we can pre-compute the endpoints of the map outside of the inner loop... we'll need these later - const double origin_x = origin_x_, origin_y = origin_y_; - const double map_end_x = origin_x + size_x_ * resolution_; - const double map_end_y = origin_y + size_y_ * resolution_; - - double wx = target_x; - double wy = target_y; - - // now we also need to make sure that the endpoint we're ray-tracing - // to isn't off the costmap and scale if necessary - const double a = wx - ox; - const double b = wy - oy; - - // the minimum value to raytrace from is the origin - if (wx < origin_x) { - const double t = (origin_x - ox) / a; - wx = origin_x; - wy = oy + b * t; - } - if (wy < origin_y) { - const double t = (origin_y - oy) / b; - wx = ox + a * t; - wy = origin_y; - } - - // the maximum value to raytrace to is the end of the map - if (wx > map_end_x) { - const double t = (map_end_x - ox) / a; - wx = map_end_x - .001; - wy = oy + b * t; - } - if (wy > map_end_y) { - const double t = (map_end_y - oy) / b; - wx = ox + a * t; - wy = map_end_y - .001; - } - - // now that the vector is scaled correctly... we'll get the map coordinates of its endpoint - unsigned int x1{}; - unsigned int y1{}; - - // check for legality just in case - if (!worldToMap(wx, wy, x1, y1)) { - return; - } - - constexpr unsigned int cell_raytrace_range = 10000; // large number to ignore range threshold - MarkCell marker(costmap_, cost); - raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_range); + distance_margin_ = + node.declare_parameter("OccupancyGridMapFixedBlindSpot.distance_margin"); } } // namespace costmap_2d diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp new file mode 100644 index 0000000000000..e2282f7c711c8 --- /dev/null +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp @@ -0,0 +1,312 @@ +// Copyright 2021 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 "pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp" + +#include "cost_value.hpp" +#include "utils/utils.hpp" + +#include +#include +#include +#include + +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#include +#else +#include + +#include +#endif + +#include +namespace costmap_2d +{ +using sensor_msgs::PointCloud2ConstIterator; + +OccupancyGridMapProjectiveBlindSpot::OccupancyGridMapProjectiveBlindSpot( + const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) +: OccupancyGridMapInterface(cells_size_x, cells_size_y, resolution) +{ +} + +/** + * @brief update Gridmap with PointCloud in 3D manner + * + * @param raw_pointcloud raw point cloud on a certain frame (usually base_link) + * @param obstacle_pointcloud raw point cloud on a certain frame (usually base_link) + * @param robot_pose frame of the input point cloud (usually base_link) + * @param scan_origin manually chosen grid map origin frame + */ +void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud( + const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, + const Pose & robot_pose, const Pose & scan_origin) +{ + constexpr double min_angle = tier4_autoware_utils::deg2rad(-180.0); + constexpr double max_angle = tier4_autoware_utils::deg2rad(180.0); + constexpr double angle_increment = tier4_autoware_utils::deg2rad(0.1); + const size_t angle_bin_size = ((max_angle - min_angle) / angle_increment) + size_t(1 /*margin*/); + + // Transform from base_link to map frame + PointCloud2 map_raw_pointcloud, map_obstacle_pointcloud; // point cloud in map frame + utils::transformPointcloud(raw_pointcloud, robot_pose, map_raw_pointcloud); + utils::transformPointcloud(obstacle_pointcloud, robot_pose, map_obstacle_pointcloud); + + // Transform from map frame to scan frame + PointCloud2 scan_raw_pointcloud, scan_obstacle_pointcloud; // point cloud in scan frame + const auto scan2map_pose = utils::getInversePose(scan_origin); // scan -> map transform pose + utils::transformPointcloud(map_raw_pointcloud, scan2map_pose, scan_raw_pointcloud); + utils::transformPointcloud(map_obstacle_pointcloud, scan2map_pose, scan_obstacle_pointcloud); + + // Create angle bins + struct BinInfo3D + { + BinInfo3D( + const double _range = 0.0, const double _wx = 0.0, const double _wy = 0.0, + const double _wz = 0.0, const double _projection_length = 0.0, + const double _projected_wx = 0.0, const double _projected_wy = 0.0) + : range(_range), + wx(_wx), + wy(_wy), + wz(_wz), + projection_length(_projection_length), + projected_wx(_projected_wx), + projected_wy(_projected_wy) + { + } + double range; + double wx; + double wy; + double wz; + double projection_length; + double projected_wx; + double projected_wy; + }; + + std::vector> obstacle_pointcloud_angle_bins; + std::vector> raw_pointcloud_angle_bins; + obstacle_pointcloud_angle_bins.resize(angle_bin_size); + raw_pointcloud_angle_bins.resize(angle_bin_size); + for (PointCloud2ConstIterator iter_x(scan_raw_pointcloud, "x"), + iter_y(scan_raw_pointcloud, "y"), iter_wx(map_raw_pointcloud, "x"), + iter_wy(map_raw_pointcloud, "y"), iter_wz(map_raw_pointcloud, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_wx, ++iter_wy, ++iter_wz) { + const double angle = atan2(*iter_y, *iter_x); + const int angle_bin_index = (angle - min_angle) / angle_increment; + raw_pointcloud_angle_bins.at(angle_bin_index) + .emplace_back(std::hypot(*iter_y, *iter_x), *iter_wx, *iter_wy, *iter_wz); + } + for (PointCloud2ConstIterator iter_x(scan_obstacle_pointcloud, "x"), + iter_y(scan_obstacle_pointcloud, "y"), iter_z(scan_obstacle_pointcloud, "z"), + iter_wx(map_obstacle_pointcloud, "x"), iter_wy(map_obstacle_pointcloud, "y"), + iter_wz(map_obstacle_pointcloud, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++iter_wx, ++iter_wy, ++iter_wz) { + const double scan_z = scan_origin.position.z - robot_pose.position.z; + const double obstacle_z = (*iter_wz) - robot_pose.position.z; + const double dz = scan_z - obstacle_z; + const double angle = atan2(*iter_y, *iter_x); + const int angle_bin_index = (angle - min_angle) / angle_increment; + const double range = std::hypot(*iter_x, *iter_y); + if (dz > projection_dz_threshold_) { + const double ratio = obstacle_z / dz; + const double projection_length = range * ratio; + const double projected_wx = (*iter_wx) + ((*iter_wx) - scan_origin.position.x) * ratio; + const double projected_wy = (*iter_wy) + ((*iter_wy) - scan_origin.position.y) * ratio; + obstacle_pointcloud_angle_bins.at(angle_bin_index) + .emplace_back( + range, *iter_wx, *iter_wy, *iter_wz, projection_length, projected_wx, projected_wy); + } else { + obstacle_pointcloud_angle_bins.at(angle_bin_index) + .emplace_back( + range, *iter_wx, *iter_wy, *iter_wz, std::numeric_limits::infinity(), + std::numeric_limits::infinity(), std::numeric_limits::infinity()); + } + } + + // Sort by distance + for (auto & obstacle_pointcloud_angle_bin : obstacle_pointcloud_angle_bins) { + std::sort( + obstacle_pointcloud_angle_bin.begin(), obstacle_pointcloud_angle_bin.end(), + [](auto a, auto b) { return a.range < b.range; }); + } + for (auto & raw_pointcloud_angle_bin : raw_pointcloud_angle_bins) { + std::sort(raw_pointcloud_angle_bin.begin(), raw_pointcloud_angle_bin.end(), [](auto a, auto b) { + return a.range < b.range; + }); + } + + grid_map::Costmap2DConverter converter; + if (pub_debug_grid_) { + debug_grid_.clearAll(); + debug_grid_.setFrameId("map"); + debug_grid_.setGeometry( + grid_map::Length(size_x_ * resolution_, size_y_ * resolution_), resolution_, + grid_map::Position( + origin_x_ + size_x_ * resolution_ / 2.0, origin_y_ + size_y_ * resolution_ / 2.0)); + } + + auto is_visible_beyond_obstacle = [&](const BinInfo3D & obstacle, const BinInfo3D & raw) -> bool { + if (raw.range < obstacle.range) { + return false; + } + + if (std::isinf(obstacle.projection_length)) { + return false; + } + + // y = ax + b + const double a = -(scan_origin.position.z - robot_pose.position.z) / + (obstacle.range + obstacle.projection_length); + const double b = scan_origin.position.z; + return raw.wz > (a * raw.range + b); + }; + + // First step: Initialize cells to the final point with freespace + for (size_t bin_index = 0; bin_index < obstacle_pointcloud_angle_bins.size(); ++bin_index) { + const auto & obstacle_pointcloud_angle_bin = obstacle_pointcloud_angle_bins.at(bin_index); + const auto & raw_pointcloud_angle_bin = raw_pointcloud_angle_bins.at(bin_index); + + BinInfo3D ray_end; + if (raw_pointcloud_angle_bin.empty() && obstacle_pointcloud_angle_bin.empty()) { + continue; + } else if (raw_pointcloud_angle_bin.empty()) { + ray_end = obstacle_pointcloud_angle_bin.back(); + } else if (obstacle_pointcloud_angle_bin.empty()) { + ray_end = raw_pointcloud_angle_bin.back(); + } else { + const auto & farthest_obstacle_this_bin = obstacle_pointcloud_angle_bin.back(); + const auto & farthest_raw_this_bin = raw_pointcloud_angle_bin.back(); + ray_end = is_visible_beyond_obstacle(farthest_obstacle_this_bin, farthest_raw_this_bin) + ? farthest_raw_this_bin + : farthest_obstacle_this_bin; + } + raytrace( + scan_origin.position.x, scan_origin.position.y, ray_end.wx, ray_end.wy, + occupancy_cost_value::FREE_SPACE); + } + + if (pub_debug_grid_) + converter.addLayerFromCostmap2D(*this, "filled_free_to_farthest", debug_grid_); + + // Second step: Add uknown cell + for (size_t bin_index = 0; bin_index < obstacle_pointcloud_angle_bins.size(); ++bin_index) { + const auto & obstacle_pointcloud_angle_bin = obstacle_pointcloud_angle_bins.at(bin_index); + const auto & raw_pointcloud_angle_bin = raw_pointcloud_angle_bins.at(bin_index); + auto raw_distance_iter = raw_pointcloud_angle_bin.begin(); + for (size_t dist_index = 0; dist_index < obstacle_pointcloud_angle_bin.size(); ++dist_index) { + // Calculate next raw point from obstacle point + const auto & obstacle_bin = obstacle_pointcloud_angle_bin.at(dist_index); + while (raw_distance_iter != raw_pointcloud_angle_bin.end()) { + if (!is_visible_beyond_obstacle(obstacle_bin, *raw_distance_iter)) + raw_distance_iter++; + else + break; + } + + // There is no point farther than the obstacle point. + const bool no_visible_point_beyond = (raw_distance_iter == raw_pointcloud_angle_bin.end()); + if (no_visible_point_beyond) { + const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); + raytrace( + source.wx, source.wy, source.projected_wx, source.projected_wy, + occupancy_cost_value::NO_INFORMATION); + break; + } + + if (dist_index + 1 == obstacle_pointcloud_angle_bin.size()) { + const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); + if (!no_visible_point_beyond) { + raytrace( + source.wx, source.wy, source.projected_wx, source.projected_wy, + occupancy_cost_value::NO_INFORMATION); + } + continue; + } + + auto next_obstacle_point_distance = std::abs( + obstacle_pointcloud_angle_bin.at(dist_index + 1).range - + obstacle_pointcloud_angle_bin.at(dist_index).range); + if (next_obstacle_point_distance <= obstacle_separation_threshold_) { + continue; + } else if (no_visible_point_beyond) { + const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); + const auto & target = obstacle_pointcloud_angle_bin.at(dist_index + 1); + raytrace(source.wx, source.wy, target.wx, target.wy, occupancy_cost_value::NO_INFORMATION); + continue; + } + + auto next_raw_distance = + std::abs(obstacle_pointcloud_angle_bin.at(dist_index).range - raw_distance_iter->range); + if (next_raw_distance < next_obstacle_point_distance) { + const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); + const auto & target = *raw_distance_iter; + raytrace(source.wx, source.wy, target.wx, target.wy, occupancy_cost_value::NO_INFORMATION); + setCellValue(target.wx, target.wy, occupancy_cost_value::FREE_SPACE); + continue; + } else { + const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); + const auto & target = obstacle_pointcloud_angle_bin.at(dist_index + 1); + raytrace(source.wx, source.wy, target.wx, target.wy, occupancy_cost_value::NO_INFORMATION); + continue; + } + } + } + + if (pub_debug_grid_) converter.addLayerFromCostmap2D(*this, "added_unknown", debug_grid_); + + // Third step: Overwrite occupied cell + for (size_t bin_index = 0; bin_index < obstacle_pointcloud_angle_bins.size(); ++bin_index) { + auto & obstacle_pointcloud_angle_bin = obstacle_pointcloud_angle_bins.at(bin_index); + for (size_t dist_index = 0; dist_index < obstacle_pointcloud_angle_bin.size(); ++dist_index) { + const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); + setCellValue(source.wx, source.wy, occupancy_cost_value::LETHAL_OBSTACLE); + + if (dist_index + 1 == obstacle_pointcloud_angle_bin.size()) { + continue; + } + + auto next_obstacle_point_distance = std::abs( + obstacle_pointcloud_angle_bin.at(dist_index + 1).range - + obstacle_pointcloud_angle_bin.at(dist_index).range); + if (next_obstacle_point_distance <= obstacle_separation_threshold_) { + const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); + const auto & target = obstacle_pointcloud_angle_bin.at(dist_index + 1); + raytrace(source.wx, source.wy, target.wx, target.wy, occupancy_cost_value::LETHAL_OBSTACLE); + continue; + } + } + } + + if (pub_debug_grid_) converter.addLayerFromCostmap2D(*this, "added_obstacle", debug_grid_); + if (pub_debug_grid_) { + debug_grid_map_publisher_ptr_->publish(grid_map::GridMapRosConverter::toMessage(debug_grid_)); + } +} + +void OccupancyGridMapProjectiveBlindSpot::initRosParam(rclcpp::Node & node) +{ + projection_dz_threshold_ = + node.declare_parameter("OccupancyGridMapProjectiveBlindSpot.projection_dz_threshold"); + obstacle_separation_threshold_ = node.declare_parameter( + "OccupancyGridMapProjectiveBlindSpot.obstacle_separation_threshold"); + pub_debug_grid_ = + node.declare_parameter("OccupancyGridMapProjectiveBlindSpot.pub_debug_grid"); + debug_grid_map_publisher_ptr_ = node.create_publisher( + "~/debug/grid_map", rclcpp::QoS(1).durability_volatile()); +} + +} // namespace costmap_2d diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp index 54395477b0892..e8b53b91d81f7 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp @@ -15,6 +15,8 @@ #include "pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp" #include "cost_value.hpp" +#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp" +#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp" #include "utils/utils.hpp" #include @@ -39,8 +41,9 @@ namespace occupancy_grid_map { -using costmap_2d::OccupancyGridMap; using costmap_2d::OccupancyGridMapBBFUpdater; +using costmap_2d::OccupancyGridMapFixedBlindSpot; +using costmap_2d::OccupancyGridMapProjectiveBlindSpot; using geometry_msgs::msg::Pose; PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode( @@ -78,18 +81,41 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode( const std::string updater_type = this->declare_parameter("updater_type"); if (updater_type == "binary_bayes_filter") { - occupancy_grid_map_updater_ptr_ = std::make_shared( + occupancy_grid_map_updater_ptr_ = std::make_unique( map_length / map_resolution, map_length / map_resolution, map_resolution); } else { RCLCPP_WARN( get_logger(), "specified occupancy grid map updater type [%s] is not found, use binary_bayes_filter", updater_type.c_str()); - occupancy_grid_map_updater_ptr_ = std::make_shared( + occupancy_grid_map_updater_ptr_ = std::make_unique( map_length / map_resolution, map_length / map_resolution, map_resolution); } occupancy_grid_map_updater_ptr_->initRosParam(*this); + const std::string grid_map_type = this->declare_parameter("grid_map_type"); + if (grid_map_type == "OccupancyGridMapProjectiveBlindSpot") { + occupancy_grid_map_ptr_ = std::make_unique( + occupancy_grid_map_updater_ptr_->getSizeInCellsX(), + occupancy_grid_map_updater_ptr_->getSizeInCellsY(), + occupancy_grid_map_updater_ptr_->getResolution()); + } else if (grid_map_type == "OccupancyGridMapFixedBlindSpot") { + occupancy_grid_map_ptr_ = std::make_unique( + occupancy_grid_map_updater_ptr_->getSizeInCellsX(), + occupancy_grid_map_updater_ptr_->getSizeInCellsY(), + occupancy_grid_map_updater_ptr_->getResolution()); + } else { + RCLCPP_WARN( + get_logger(), + "specified occupancy grid map type [%s] is not found, use OccupancyGridMapFixedBlindSpot", + grid_map_type.c_str()); + occupancy_grid_map_ptr_ = std::make_unique( + occupancy_grid_map_updater_ptr_->getSizeInCellsX(), + occupancy_grid_map_updater_ptr_->getSizeInCellsY(), + occupancy_grid_map_updater_ptr_->getResolution()); + } + occupancy_grid_map_ptr_->initRosParam(*this); + // initialize debug tool { using tier4_autoware_utils::DebugPublisher; @@ -154,23 +180,21 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( } // Create single frame occupancy grid map - OccupancyGridMap single_frame_occupancy_grid_map( - occupancy_grid_map_updater_ptr_->getSizeInCellsX(), - occupancy_grid_map_updater_ptr_->getSizeInCellsY(), - occupancy_grid_map_updater_ptr_->getResolution()); - single_frame_occupancy_grid_map.updateOrigin( - gridmap_origin.position.x - single_frame_occupancy_grid_map.getSizeInMetersX() / 2, - gridmap_origin.position.y - single_frame_occupancy_grid_map.getSizeInMetersY() / 2); - single_frame_occupancy_grid_map.updateWithPointCloud( + occupancy_grid_map_ptr_->resetMaps(); + occupancy_grid_map_ptr_->updateOrigin( + gridmap_origin.position.x - occupancy_grid_map_ptr_->getSizeInMetersX() / 2, + gridmap_origin.position.y - occupancy_grid_map_ptr_->getSizeInMetersY() / 2); + occupancy_grid_map_ptr_->updateWithPointCloud( filtered_raw_pc, filtered_obstacle_pc_common, robot_pose, scan_origin); + if (enable_single_frame_mode_) { // publish occupancy_grid_map_pub_->publish(OccupancyGridMapToMsgPtr( map_frame_, input_raw_msg->header.stamp, robot_pose.position.z, - single_frame_occupancy_grid_map)); // (todo) robot_pose may be altered with gridmap_origin + *occupancy_grid_map_ptr_)); // (todo) robot_pose may be altered with gridmap_origin } else { // Update with bayes filter - occupancy_grid_map_updater_ptr_->update(single_frame_occupancy_grid_map); + occupancy_grid_map_updater_ptr_->update(*occupancy_grid_map_ptr_); // publish occupancy_grid_map_pub_->publish(OccupancyGridMapToMsgPtr( From 632f35f286e4245e6df54ba8aab8519b1329ce6b Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Fri, 7 Jul 2023 16:45:23 +0900 Subject: [PATCH 106/118] fix(behavior_path_planner): fix aborting duration (#4173) Signed-off-by: Fumiya Watanabe --- .../src/scene_module/lane_change/normal.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 361cb5548dc40..fadb445b73392 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 @@ -942,7 +942,7 @@ bool NormalLaneChange::getAbortPath() const auto [abort_start_idx, abort_start_dist] = get_abort_idx_and_distance(lane_change_parameters_->cancel.delta_time); const auto [abort_return_idx, abort_return_dist] = get_abort_idx_and_distance( - lane_change_parameters_->cancel.delta_time + lane_change_parameters_->cancel.delta_time); + lane_change_parameters_->cancel.delta_time + lane_change_parameters_->cancel.duration); if (abort_start_idx >= abort_return_idx) { RCLCPP_ERROR(logger_, "abort start idx and return idx is equal. can't compute abort path."); From 3b0671ad3e07bdbe7201a2bfa68c1358a395b388 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 7 Jul 2023 17:09:45 +0900 Subject: [PATCH 107/118] fix(goal_planner): support following lanes over the next lane (#4167) Signed-off-by: kosuke55 --- .../geometric_parallel_parking.hpp | 7 +++-- .../goal_planner/goal_planner_module.cpp | 8 ++++-- .../geometric_parallel_parking.cpp | 28 ++++++++++--------- .../goal_planner/geometric_pull_over.cpp | 3 +- .../src/utils/goal_planner/goal_searcher.cpp | 2 +- .../utils/goal_planner/shift_pull_over.cpp | 5 +++- 6 files changed, 32 insertions(+), 21 deletions(-) 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 18bf7ad54e70c..cb769a1f2884c 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 @@ -127,13 +127,14 @@ class GeometricParallelParking const Pose & center, const double radius, const double yaw, const bool is_left_turn, const bool is_forward); boost::optional calcStartPose( - const Pose & goal_pose, const double start_pose_offset, const double R_E_r, - const bool is_forward); + const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes, + const double start_pose_offset, const double R_E_r, const bool is_forward); std::vector generatePullOverPaths( const Pose & start_pose, const Pose & goal_pose, const double R_E_r, const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, const bool is_forward, const double end_pose_offset, const double velocity); - PathWithLaneId generateStraightPath(const Pose & start_pose); + PathWithLaneId generateStraightPath( + const Pose & start_pose, const lanelet::ConstLanelets & road_lanes); void setVelocityToArcPaths( std::vector & arc_paths, const double velocity, const bool set_stop_end); 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 f55d505ea9337..92b465c6ffdb2 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 @@ -152,7 +152,9 @@ void GoalPlannerModule::onTimer() mutex_.unlock(); // generate valid pull over path candidates and calculate closest start pose - const auto current_lanes = utils::getExtendedCurrentLanes(planner_data_); + const auto current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length); std::vector path_candidates{}; std::optional closest_start_pose{}; double min_start_arc_length = std::numeric_limits::max(); @@ -590,7 +592,9 @@ void GoalPlannerModule::selectSafePullOverPath() void GoalPlannerModule::setLanes() { - status_.current_lanes = utils::getExtendedCurrentLanes(planner_data_); + status_.current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length); status_.pull_over_lanes = goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_); status_.lanes = 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 528eae0d79a62..678e19e616f26 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 @@ -138,7 +138,7 @@ std::vector GeometricParallelParking::generatePullOverPaths( setVelocityToArcPaths(arc_paths, velocity, set_stop_end); // straight path from current to parking start - const auto straight_path = generateStraightPath(start_pose); + const auto straight_path = generateStraightPath(start_pose, road_lanes); // check the continuity of straight path and arc path const Pose & road_path_last_pose = straight_path.points.back().point.pose; @@ -187,7 +187,8 @@ bool GeometricParallelParking::planPullOver( for (double steer = parameters_.forward_parking_max_steer_angle; steer > min_steer_rad; steer -= steer_interval) { const double R_E_r = common_params.wheel_base / std::tan(steer); - const auto start_pose = calcStartPose(arc_end_pose, start_pose_offset, R_E_r, is_forward); + const auto start_pose = + calcStartPose(arc_end_pose, road_lanes, start_pose_offset, R_E_r, is_forward); if (!start_pose) { continue; } @@ -208,7 +209,8 @@ bool GeometricParallelParking::planPullOver( constexpr double offset_interval = 1.0; for (double start_pose_offset = 0; start_pose_offset < max_offset; start_pose_offset += offset_interval) { - const auto start_pose = calcStartPose(arc_end_pose, start_pose_offset, R_E_min_, is_forward); + const auto start_pose = + calcStartPose(arc_end_pose, road_lanes, start_pose_offset, R_E_min_, is_forward); if (!start_pose) { continue; } @@ -238,7 +240,8 @@ bool GeometricParallelParking::planPullOut( for (double end_pose_offset = 0; end_pose_offset < max_offset; end_pose_offset += offset_interval) { // pull_out end pose which is the second arc path end - const auto end_pose = calcStartPose(start_pose, end_pose_offset, R_E_min_, is_forward); + const auto end_pose = + calcStartPose(start_pose, road_lanes, end_pose_offset, R_E_min_, is_forward); if (!end_pose) { continue; } @@ -315,11 +318,10 @@ bool GeometricParallelParking::planPullOut( } boost::optional GeometricParallelParking::calcStartPose( - const Pose & goal_pose, const double start_pose_offset, const double R_E_r, const bool is_forward) + const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes, const double start_pose_offset, + const double R_E_r, const bool is_forward) { - // Not use shoulder lanes. - const auto current_lanes = utils::getExtendedCurrentLanes(planner_data_); - const auto arc_coordinates = lanelet::utils::getArcCoordinates(current_lanes, goal_pose); + const auto arc_coordinates = lanelet::utils::getArcCoordinates(road_lanes, goal_pose); // todo // When forwarding, the turning radius of the right and left will be the same. @@ -339,17 +341,17 @@ boost::optional GeometricParallelParking::calcStartPose( return start_pose; } -PathWithLaneId GeometricParallelParking::generateStraightPath(const Pose & start_pose) +PathWithLaneId GeometricParallelParking::generateStraightPath( + const Pose & start_pose, const lanelet::ConstLanelets & road_lanes) { // get straight path before parking. - const auto current_lanes = utils::getExtendedCurrentLanes(planner_data_); - const auto start_arc_position = lanelet::utils::getArcCoordinates(current_lanes, start_pose); + const auto start_arc_position = lanelet::utils::getArcCoordinates(road_lanes, start_pose); const Pose current_pose = planner_data_->self_odometry->pose.pose; - const auto current_arc_position = lanelet::utils::getArcCoordinates(current_lanes, current_pose); + const auto current_arc_position = lanelet::utils::getArcCoordinates(road_lanes, current_pose); auto path = planner_data_->route_handler->getCenterLinePath( - current_lanes, current_arc_position.length, start_arc_position.length, true); + road_lanes, current_arc_position.length, start_arc_position.length, true); path.header = planner_data_->route_handler->getRouteHeader(); if (!path.points.empty()) { path.points.back().point.longitudinal_velocity_mps = 0; 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 ed38d09f879ba..24c6d98ed09e5 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 @@ -44,7 +44,8 @@ boost::optional GeometricPullOver::plan(const Pose & goal_pose) const auto & route_handler = planner_data_->route_handler; // prepare road nad shoulder lanes - const auto road_lanes = utils::getExtendedCurrentLanes(planner_data_); + const auto road_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length); const auto shoulder_lanes = goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_); if (road_lanes.empty() || shoulder_lanes.empty()) { 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 d35842d09f056..9123beca0d95c 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 @@ -54,7 +54,7 @@ GoalCandidates GoalSearcher::search(const Pose & original_goal_pose) const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_); - auto lanes = utils::getExtendedCurrentLanes(planner_data_); + auto lanes = utils::getExtendedCurrentLanes(planner_data_, backward_length, forward_length); lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); const auto goal_arc_coords = 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 073e97e01912e..8bf20b212d51d 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 @@ -40,11 +40,14 @@ boost::optional ShiftPullOver::plan(const Pose & goal_pose) const auto & route_handler = planner_data_->route_handler; const double min_jerk = parameters_.minimum_lateral_jerk; const double max_jerk = parameters_.maximum_lateral_jerk; + const double backward_search_length = parameters_.backward_goal_search_length; + const double forward_search_length = parameters_.forward_goal_search_length; const int shift_sampling_num = parameters_.shift_sampling_num; const double jerk_resolution = std::abs(max_jerk - min_jerk) / shift_sampling_num; // get road and shoulder lanes - const auto road_lanes = utils::getExtendedCurrentLanes(planner_data_); + const auto road_lanes = + utils::getExtendedCurrentLanes(planner_data_, backward_search_length, forward_search_length); const auto shoulder_lanes = goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_); if (road_lanes.empty() || shoulder_lanes.empty()) { From 410f10df07f59dea655ea4e6597a8d169d375399 Mon Sep 17 00:00:00 2001 From: beyzanurkaya <32412808+beyzanurkaya@users.noreply.github.com> Date: Fri, 7 Jul 2023 16:00:06 +0300 Subject: [PATCH 108/118] fix(behavior_velocity_intersection_module): behavior_velocity_intersection_module dies due empty conflicting_lanelets (#4191) * fix the range problem Signed-off-by: beyza * style(pre-commit): autofix * cleanup Signed-off-by: beyza * add a flag in the checkAngleForTargetLanelets func Signed-off-by: beyza * change the angle check Signed-off-by: beyza * 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/scene_intersection.cpp | 3 ++ .../src/util.cpp | 32 +++++++++++++------ .../src/util.hpp | 3 +- 3 files changed, 28 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 bc6b54c23edd6..002c4daf4ec29 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -899,6 +899,7 @@ bool IntersectionModule::checkCollision( const auto object_direction = util::getObjectPoseWithVelocityDirection(object.kinematics); const auto is_in_adjacent_lanelets = util::checkAngleForTargetLanelets( object_direction, adjacent_lanelets, planner_param_.common.attention_area_angle_thr, + planner_param_.common.consider_wrong_direction_vehicle, planner_param_.common.attention_area_margin); if (is_in_adjacent_lanelets) { continue; @@ -913,12 +914,14 @@ bool IntersectionModule::checkCollision( } else if (util::checkAngleForTargetLanelets( object_direction, attention_area_lanelets, planner_param_.common.attention_area_angle_thr, + planner_param_.common.consider_wrong_direction_vehicle, planner_param_.common.attention_area_margin)) { target_objects.objects.push_back(object); } } else if (util::checkAngleForTargetLanelets( object_direction, attention_area_lanelets, planner_param_.common.attention_area_angle_thr, + planner_param_.common.consider_wrong_direction_vehicle, planner_param_.common.attention_area_margin)) { // intersection_area is not available, use detection_area_with_margin as before target_objects.objects.push_back(object); diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 51d8e286fe764..8108d0deaae6f 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -446,7 +446,16 @@ IntersectionLanelets getObjectiveLanelets( // get conflicting lanes on assigned lanelet const auto & conflicting_lanelets = lanelet::utils::getConflictingLanelets(routing_graph_ptr, assigned_lanelet); - const auto & adjacent_followings = routing_graph_ptr->following(conflicting_lanelets.back()); + std::vector adjacent_followings; + + for (const auto & conflicting_lanelet : conflicting_lanelets) { + for (const auto & following_lanelet : routing_graph_ptr->following(conflicting_lanelet)) { + adjacent_followings.push_back(following_lanelet); + } + for (const auto & following_lanelet : routing_graph_ptr->previous(conflicting_lanelet)) { + adjacent_followings.push_back(following_lanelet); + } + } // final objective lanelets lanelet::ConstLanelets detection_lanelets; @@ -467,9 +476,9 @@ IntersectionLanelets getObjectiveLanelets( continue; } detection_lanelets.push_back(conflicting_lanelet); - if (!adjacent_followings.empty()) { - detection_lanelets.push_back(adjacent_followings.front()); - } + } + for (const auto & adjacent_following : adjacent_followings) { + detection_lanelets.push_back(adjacent_following); } } else { // otherwise we need to know the priority from RightOfWay @@ -992,7 +1001,8 @@ Polygon2d generateStuckVehicleDetectAreaPolygon( bool checkAngleForTargetLanelets( const geometry_msgs::msg::Pose & pose, const lanelet::ConstLanelets & target_lanelets, - const double detection_area_angle_thr, const double margin) + const double detection_area_angle_thr, const bool consider_wrong_direction_vehicle, + const double margin) { for (const auto & ll : target_lanelets) { if (!lanelet::utils::isInLanelet(pose, ll, margin)) { @@ -1001,10 +1011,14 @@ bool checkAngleForTargetLanelets( const double ll_angle = lanelet::utils::getLaneletAngle(ll, pose.position); const double pose_angle = tf2::getYaw(pose.orientation); const double angle_diff = tier4_autoware_utils::normalizeRadian(ll_angle - pose_angle); - if ( - std::fabs(angle_diff) < detection_area_angle_thr / 2 || - std::fabs(angle_diff) > detection_area_angle_thr) { - return true; + if (consider_wrong_direction_vehicle) { + if (std::fabs(angle_diff) > 1.57 || std::fabs(angle_diff) < detection_area_angle_thr) { + return true; + } + } else { + if (std::fabs(angle_diff) < detection_area_angle_thr) { + return true; + } } } return false; diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 89931a5db10fc..8a539f67f73a6 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -144,7 +144,8 @@ Polygon2d generateStuckVehicleDetectAreaPolygon( bool checkAngleForTargetLanelets( const geometry_msgs::msg::Pose & pose, const lanelet::ConstLanelets & target_lanelets, - const double detection_area_angle_thr, const double margin = 0.0); + const double detection_area_angle_thr, const bool consider_wrong_direction_vehicle, + const double margin = 0.0); void cutPredictPathWithDuration( autoware_auto_perception_msgs::msg::PredictedObjects * objects_ptr, From 1893ecce1a6161a8d8a15ecb7d55ab7ed593dc43 Mon Sep 17 00:00:00 2001 From: Mingyu1991 <115005477+Mingyu1991@users.noreply.github.com> Date: Sat, 8 Jul 2023 11:25:45 +0900 Subject: [PATCH 109/118] feat(traffic_light_classifier): update traffic_light_classifier and traffic_light_fine_detector (#4125) * first commit Signed-off-by: Mingyu Li * fix typo Signed-off-by: Mingyu Li * Revert unnecessary changes Signed-off-by: Shunsuke Miura * change to fit previous revert Signed-off-by: Shunsuke Miura * fix: correct style Signed-off-by: Manato HIRABAYASHI * fix: use proper initializer Signed-off-by: Manato HIRABAYASHI * fix build_config constructor Signed-off-by: Shunsuke Miura * pre-commit Signed-off-by: Shunsuke Miura --------- Signed-off-by: Mingyu Li Signed-off-by: Shunsuke Miura Signed-off-by: Manato HIRABAYASHI Co-authored-by: Shunsuke Miura Co-authored-by: Manato HIRABAYASHI Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- .../tensorrt_common/tensorrt_common.hpp | 5 + .../tensorrt_common/src/tensorrt_common.cpp | 27 +- perception/tensorrt_classifier/CMakeLists.txt | 59 ++ .../tensorrt_classifier/calibrator.hpp | 529 ++++++++++++++++ .../include/tensorrt_classifier/preprocess.h | 181 ++++++ .../tensorrt_classifier.hpp | 132 ++++ perception/tensorrt_classifier/package.xml | 33 + .../tensorrt_classifier/src/preprocess.cu | 596 ++++++++++++++++++ .../src/tensorrt_classifier.cpp | 385 +++++++++++ .../include/tensorrt_yolox/preprocess.hpp | 67 ++ .../include/tensorrt_yolox/tensorrt_yolox.hpp | 76 ++- perception/tensorrt_yolox/src/preprocess.cu | 226 +++++++ .../tensorrt_yolox/src/tensorrt_yolox.cpp | 414 +++++++++++- .../src/tensorrt_yolox_node.cpp | 2 +- .../traffic_light_classifier/CMakeLists.txt | 20 +- .../classifier_interface.hpp | 7 +- .../cnn_classifier.hpp | 30 +- .../color_classifier.hpp | 8 +- .../traffic_light_classifier/package.xml | 1 + .../src/cnn_classifier.cpp | 181 ++---- .../src/color_classifier.cpp | 254 ++++---- .../traffic_light_classifier/src/nodelet.cpp | 22 +- .../src/single_image_debug_inference_node.cpp | 6 +- .../CMakeLists.txt | 8 +- .../traffic_light_fine_detector/nodelet.hpp | 1 + .../src/nodelet.cpp | 72 ++- 26 files changed, 2996 insertions(+), 346 deletions(-) create mode 100644 perception/tensorrt_classifier/CMakeLists.txt create mode 100644 perception/tensorrt_classifier/include/tensorrt_classifier/calibrator.hpp create mode 100644 perception/tensorrt_classifier/include/tensorrt_classifier/preprocess.h create mode 100644 perception/tensorrt_classifier/include/tensorrt_classifier/tensorrt_classifier.hpp create mode 100644 perception/tensorrt_classifier/package.xml create mode 100644 perception/tensorrt_classifier/src/preprocess.cu create mode 100644 perception/tensorrt_classifier/src/tensorrt_classifier.cpp diff --git a/common/tensorrt_common/include/tensorrt_common/tensorrt_common.hpp b/common/tensorrt_common/include/tensorrt_common/tensorrt_common.hpp index 38320625b256a..aabaea7ca6339 100644 --- a/common/tensorrt_common/include/tensorrt_common/tensorrt_common.hpp +++ b/common/tensorrt_common/include/tensorrt_common/tensorrt_common.hpp @@ -148,6 +148,11 @@ class TrtCommon // NOLINT const BuildConfig & buildConfig = BuildConfig(), const std::vector & plugin_paths = {}); + /** + * @brief Deconstruct TrtCommon + */ + ~TrtCommon(); + /** * @brief Load TensorRT engine * @param[in] engine_file_path path for a engine file diff --git a/common/tensorrt_common/src/tensorrt_common.cpp b/common/tensorrt_common/src/tensorrt_common.cpp index e926196226052..8c62fdd7e21fa 100644 --- a/common/tensorrt_common/src/tensorrt_common.cpp +++ b/common/tensorrt_common/src/tensorrt_common.cpp @@ -19,6 +19,7 @@ #include #include +#include #include #include #include @@ -59,7 +60,7 @@ nvinfer1::Dims get_input_dims(const std::string & onnx_file_path) auto parser = TrtUniquePtr(nvonnxparser::createParser(*network, logger_)); if (!parser->parseFromFile( onnx_file_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR))) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to parse ONNX"); + logger_.log(nvinfer1::ILogger::Severity::kERROR, "Failed to parse onnx file"); } const auto input = network->getInput(0); @@ -126,6 +127,10 @@ TrtCommon::TrtCommon( initLibNvInferPlugins(&logger_, ""); } +TrtCommon::~TrtCommon() +{ +} + void TrtCommon::setup() { if (!fs::exists(model_file_path_)) { @@ -417,6 +422,21 @@ bool TrtCommon::buildEngineFromOnnx( layer->setPrecision(nvinfer1::DataType::kHALF); std::cout << "Set kHALF in " << name << std::endl; } + for (int i = num - 1; i >= 0; i--) { + nvinfer1::ILayer * layer = network->getLayer(i); + auto ltype = layer->getType(); + std::string name = layer->getName(); + if (ltype == nvinfer1::LayerType::kCONVOLUTION) { + layer->setPrecision(nvinfer1::DataType::kHALF); + std::cout << "Set kHALF in " << name << std::endl; + break; + } + if (ltype == nvinfer1::LayerType::kMATRIX_MULTIPLY) { + layer->setPrecision(nvinfer1::DataType::kHALF); + std::cout << "Set kHALF in " << name << std::endl; + break; + } + } } } } @@ -427,6 +447,11 @@ bool TrtCommon::buildEngineFromOnnx( const auto input_channel = input_dims.d[1]; const auto input_height = input_dims.d[2]; const auto input_width = input_dims.d[3]; + const auto input_batch = input_dims.d[0]; + + if (input_batch > 1) { + batch_config_[0] = input_batch; + } if (batch_config_.at(0) > 1 && (batch_config_.at(0) == batch_config_.at(2))) { // Attention : below API is deprecated in TRT8.4 diff --git a/perception/tensorrt_classifier/CMakeLists.txt b/perception/tensorrt_classifier/CMakeLists.txt new file mode 100644 index 0000000000000..9f879a2c0c56d --- /dev/null +++ b/perception/tensorrt_classifier/CMakeLists.txt @@ -0,0 +1,59 @@ +cmake_minimum_required(VERSION 3.5) +project(tensorrt_classifier) + +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -O3 -Wno-write-strings -fopenmp -Wall") + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(CUDA) +find_package(CUDNN) +find_package(TENSORRT) +find_package(OpenCV REQUIRED) + +if(NOT (${CUDA_FOUND} AND ${CUDNN_FOUND} AND ${TENSORRT_FOUND})) + message(WARNING "cuda, cudnn, tensorrt libraries are not found") + return() +endif() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/tensorrt_classifier.cpp + src/preprocess.cu +) + +ament_target_dependencies(${PROJECT_NAME} + rclcpp + OpenCV +) + +target_include_directories(${PROJECT_NAME} + PUBLIC + $ + $ + ${TENSORRT_INCLUDE_DIRS} +) + +target_link_libraries(${PROJECT_NAME} + ${TENSORRT_LIBRARIES} + stdc++fs +) + +target_compile_definitions(${PROJECT_NAME} PRIVATE + TENSORRT_VERSION_MAJOR=${TENSORRT_VERSION_MAJOR} +) + +list(APPEND ${PROJECT_NAME}_LIBRARIES "${PROJECT_NAME}") + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_export_include_directories(include) +ament_export_dependencies(CUDA) +ament_export_dependencies(cudnn_cmake_module) +ament_export_dependencies(CUDNN) +ament_export_dependencies(tensorrt_cmake_module) +ament_export_dependencies(TENSORRT) + +ament_auto_package() diff --git a/perception/tensorrt_classifier/include/tensorrt_classifier/calibrator.hpp b/perception/tensorrt_classifier/include/tensorrt_classifier/calibrator.hpp new file mode 100644 index 0000000000000..e8c03d132679a --- /dev/null +++ b/perception/tensorrt_classifier/include/tensorrt_classifier/calibrator.hpp @@ -0,0 +1,529 @@ +// 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. + +/* + * Copyright (c) 2020, NVIDIA CORPORATION. All rights reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef TENSORRT_CLASSIFIER__CALIBRATOR_HPP_ +#define TENSORRT_CLASSIFIER__CALIBRATOR_HPP_ +#include "cuda_utils/cuda_check_error.hpp" +#include "cuda_utils/cuda_unique_ptr.hpp" + +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include + +namespace tensorrt_classifier +{ +class ImageStream +{ +public: + ImageStream( + int batch_size, nvinfer1::Dims input_dims, const std::vector calibration_images) + : batch_size_(batch_size), + calibration_images_(calibration_images), + current_batch_(0), + max_batches_(calibration_images.size() / batch_size_), + input_dims_(input_dims) + { + batch_.resize(batch_size_ * input_dims_.d[1] * input_dims_.d[2] * input_dims_.d[3]); + } + + int getBatchSize() const { return batch_size_; } + + int getMaxBatches() const { return max_batches_; } + + float * getBatch() { return &batch_[0]; } + + nvinfer1::Dims getInputDims() { return input_dims_; } + + /** + * @brief Preprocess in calibration + * @param[in] images input images + * @param[in] input_dims input dimensions + * @param[in] mean mean value for each channel + * @param[in] std std value for each channel + * @return vector preprocessed data + */ + std::vector preprocess( + const std::vector & images, nvinfer1::Dims input_dims, const std::vector & mean, + const std::vector & std) + { + std::vector input_h_; + int batch_size = static_cast(images.size()); + input_dims.d[0] = batch_size; + const float input_chan = static_cast(input_dims.d[1]); + const float input_height = static_cast(input_dims.d[2]); + const float input_width = static_cast(input_dims.d[3]); + std::vector dst_images; + std::vector scales_; + int volume = batch_size * input_chan * input_height * input_width; + scales_.clear(); + input_h_.resize(volume); + for (const auto & image : images) { + cv::Mat dst_image; + const float scale = std::min(input_width / image.cols, input_height / image.rows); + scales_.emplace_back(scale); + const auto scale_size = cv::Size(image.cols * scale, image.rows * scale); + cv::resize(image, dst_image, scale_size, 0, 0, cv::INTER_LINEAR); + const auto bottom = input_height - dst_image.rows; + const auto right = input_width - dst_image.cols; + copyMakeBorder(dst_image, dst_image, 0, bottom, 0, right, cv::BORDER_CONSTANT, {0, 0, 0}); + dst_images.emplace_back(dst_image); + } + + // NHWC + const size_t strides_cv[4] = { + static_cast(input_width * input_chan * input_height), + static_cast(input_width * input_chan), static_cast(input_chan), 1}; + // NCHW + const size_t strides[4] = { + static_cast(input_height * input_width * input_chan), + static_cast(input_height * input_width), static_cast(input_width), 1}; + for (int n = 0; n < batch_size; n++) { + for (int h = 0; h < input_height; h++) { + for (int w = 0; w < input_width; w++) { + for (int c = 0; c < input_chan; c++) { + // NHWC (needs RBswap) + const size_t offset_cv = + h * strides_cv[1] + w * strides_cv[2] + (input_chan - c - 1) * strides_cv[3]; + // NCHW + const size_t offset = n * strides[0] + (c)*strides[1] + h * strides[2] + w * strides[3]; + input_h_[offset] = + (static_cast(dst_images[n].data[offset_cv]) - mean[c]) / std[c]; + } + } + } + } + return input_h_; + } + + /** + * @brief Decode data in calibration + * @param[in] scale normalization (0.0-1.0) + * @return bool succ or fail + */ + bool next(const std::vector & mean, const std::vector & std) + { + if (current_batch_ == max_batches_) { + return false; + } + for (int i = 0; i < batch_size_; ++i) { + auto image = + cv::imread(calibration_images_[batch_size_ * current_batch_ + i].c_str(), cv::IMREAD_COLOR); + std::cout << current_batch_ << " " << i << " Preprocess " + << calibration_images_[batch_size_ * current_batch_ + i].c_str() << std::endl; + auto input = preprocess({image}, input_dims_, mean, std); + batch_.insert( + batch_.begin() + i * input_dims_.d[1] * input_dims_.d[2] * input_dims_.d[3], input.begin(), + input.end()); + } + + ++current_batch_; + return true; + } + /** + * @brief Reset calibration + */ + void reset() { current_batch_ = 0; } + +private: + int batch_size_; + std::vector calibration_images_; + int current_batch_; + int max_batches_; + nvinfer1::Dims input_dims_; + std::vector batch_; +}; + +/**Percentile calibration using legacy calibrator*/ +/** + * @class Int8LegacyCalibrator + * @brief Calibrator for Percentle + * @warning We are confirming bug on Tegra like Xavier and Orin. We recommand use EntropyV2 or + * MinMax calibrator + */ +class Int8LegacyCalibrator : public nvinfer1::IInt8LegacyCalibrator +{ +public: + Int8LegacyCalibrator( + ImageStream & stream, const std::string calibration_cache_file, + const std::string histogram_cache_file, + const std::vector & mean = {123.675, 116.28, 103.53}, + const std::vector & std = {58.395, 57.12, 57.375}, bool read_cache = true, + double quantile = 0.999999, double cutoff = 0.999999) + : stream_(stream), + calibration_cache_file_(calibration_cache_file), + histogranm_cache_file_(histogram_cache_file), + read_cache_(read_cache) + { + auto d = stream_.getInputDims(); + input_count_ = stream_.getBatchSize() * d.d[1] * d.d[2] * d.d[3]; + CHECK_CUDA_ERROR(cudaMalloc(&device_input_, input_count_ * sizeof(float))); + m_std = std; + m_mean = mean; + m_quantile = quantile; + m_cutoff = cutoff; + auto algType = getAlgorithm(); + switch (algType) { + case (nvinfer1::CalibrationAlgoType::kLEGACY_CALIBRATION): + std::cout << "CalibratioAlgoType : kLEGACY_CALIBRATION" << std::endl; + break; + case (nvinfer1::CalibrationAlgoType::kENTROPY_CALIBRATION): + std::cout << "CalibratioAlgoType : kENTROPY_CALIBRATION" << std::endl; + break; + case (nvinfer1::CalibrationAlgoType::kENTROPY_CALIBRATION_2): + std::cout << "CalibratioAlgoType : kENTROPY_CALIBRATION_2" << std::endl; + break; + case (nvinfer1::CalibrationAlgoType::kMINMAX_CALIBRATION): + std::cout << "CalibratioAlgoType : kMINMAX_CALIBRATION" << std::endl; + break; + default: + std::cout << "No CalibrationAlgType" << std::endl; + break; + } + } + int getBatchSize() const noexcept override { return stream_.getBatchSize(); } + + virtual ~Int8LegacyCalibrator() { CHECK_CUDA_ERROR(cudaFree(device_input_)); } + + bool getBatch(void * bindings[], const char * names[], int nb_bindings) noexcept override + { + (void)names; + (void)nb_bindings; + + if (!stream_.next(m_mean, m_std)) { + return false; + } + try { + CHECK_CUDA_ERROR(cudaMemcpy( + device_input_, stream_.getBatch(), input_count_ * sizeof(float), cudaMemcpyHostToDevice)); + } catch (const std::exception & e) { + // Do nothing + } + bindings[0] = device_input_; + return true; + } + + const void * readCalibrationCache(size_t & length) noexcept override + { + calib_cache_.clear(); + std::ifstream input(calibration_cache_file_, std::ios::binary); + input >> std::noskipws; + if (read_cache_ && input.good()) { + std::copy( + std::istream_iterator(input), std::istream_iterator(), + std::back_inserter(calib_cache_)); + } + + length = calib_cache_.size(); + if (length) { + std::cout << "Using cached calibration table to build the engine" << std::endl; + } else { + std::cout << "New calibration table will be created to build the engine" << std::endl; + } + return length ? &calib_cache_[0] : nullptr; + } + + void writeCalibrationCache(const void * cache, size_t length) noexcept override + { + std::ofstream output(calibration_cache_file_, std::ios::binary); + output.write(reinterpret_cast(cache), length); + } + + double getQuantile() const noexcept + { + printf("Quantile %f\n", m_quantile); + return m_quantile; + } + + double getRegressionCutoff(void) const noexcept + { + printf("Cutoff %f\n", m_cutoff); + return m_cutoff; + } + + const void * readHistogramCache(std::size_t & length) noexcept + { + hist_cache_.clear(); + std::ifstream input(histogranm_cache_file_, std::ios::binary); + input >> std::noskipws; + if (read_cache_ && input.good()) { + std::copy( + std::istream_iterator(input), std::istream_iterator(), + std::back_inserter(hist_cache_)); + } + + length = hist_cache_.size(); + if (length) { + std::cout << "Using cached histogram table to build the engine" << std::endl; + } else { + std::cout << "New histogram table will be created to build the engine" << std::endl; + } + return length ? &hist_cache_[0] : nullptr; + } + void writeHistogramCache(void const * ptr, std::size_t length) noexcept + { + std::ofstream output(histogranm_cache_file_, std::ios::binary); + output.write(reinterpret_cast(ptr), length); + } + +private: + ImageStream stream_; + const std::string calibration_cache_file_; + const std::string histogranm_cache_file_; + bool read_cache_{true}; + size_t input_count_; + void * device_input_{nullptr}; + std::vector calib_cache_; + std::vector hist_cache_; + // mean for preprocessing + std::vector m_mean; + // std for preprocessing + std::vector m_std; + double m_quantile; + double m_cutoff; +}; + +/** + * @class Int8LegacyCalibrator + * @brief Calibrator for Percentle + * + */ +class Int8EntropyCalibrator : public nvinfer1::IInt8EntropyCalibrator2 +{ +public: + Int8EntropyCalibrator( + ImageStream & stream, const std::string calibration_cache_file, + const std::vector & mean = {123.675, 116.28, 103.53}, + const std::vector & std = {58.395, 57.12, 57.375}, bool read_cache = true) + : stream_(stream), calibration_cache_file_(calibration_cache_file), read_cache_(read_cache) + { + auto d = stream_.getInputDims(); + input_count_ = stream_.getBatchSize() * d.d[1] * d.d[2] * d.d[3]; + m_std = std; + m_mean = mean; + + CHECK_CUDA_ERROR(cudaMalloc(&device_input_, input_count_ * sizeof(float))); + auto algType = getAlgorithm(); + switch (algType) { + case (nvinfer1::CalibrationAlgoType::kLEGACY_CALIBRATION): + std::cout << "CalibratioAlgoType : kLEGACY_CALIBRATION" << std::endl; + break; + case (nvinfer1::CalibrationAlgoType::kENTROPY_CALIBRATION): + std::cout << "CalibratioAlgoType : kENTROPY_CALIBRATION" << std::endl; + break; + case (nvinfer1::CalibrationAlgoType::kENTROPY_CALIBRATION_2): + std::cout << "CalibratioAlgoType : kENTROPY_CALIBRATION_2" << std::endl; + break; + case (nvinfer1::CalibrationAlgoType::kMINMAX_CALIBRATION): + std::cout << "CalibratioAlgoType : kMINMAX_CALIBRATION" << std::endl; + break; + default: + std::cout << "No CalibrationAlgType" << std::endl; + break; + } + } + int getBatchSize() const noexcept override { return stream_.getBatchSize(); } + + virtual ~Int8EntropyCalibrator() { CHECK_CUDA_ERROR(cudaFree(device_input_)); } + + bool getBatch(void * bindings[], const char * names[], int nb_bindings) noexcept override + { + (void)names; + (void)nb_bindings; + + if (!stream_.next(m_mean, m_std)) { + return false; + } + try { + CHECK_CUDA_ERROR(cudaMemcpy( + device_input_, stream_.getBatch(), input_count_ * sizeof(float), cudaMemcpyHostToDevice)); + } catch (const std::exception & e) { + // Do nothing + } + bindings[0] = device_input_; + return true; + } + + const void * readCalibrationCache(size_t & length) noexcept override + { + calib_cache_.clear(); + std::ifstream input(calibration_cache_file_, std::ios::binary); + input >> std::noskipws; + if (read_cache_ && input.good()) { + std::copy( + std::istream_iterator(input), std::istream_iterator(), + std::back_inserter(calib_cache_)); + } + + length = calib_cache_.size(); + if (length) { + std::cout << "Using cached calibration table to build the engine" << std::endl; + } else { + std::cout << "New calibration table will be created to build the engine" << std::endl; + } + return length ? &calib_cache_[0] : nullptr; + } + + void writeCalibrationCache(const void * cache, size_t length) noexcept override + { + std::ofstream output(calibration_cache_file_, std::ios::binary); + output.write(reinterpret_cast(cache), length); + } + +private: + ImageStream stream_; + const std::string calibration_cache_file_; + bool read_cache_{true}; + size_t input_count_; + void * device_input_{nullptr}; + std::vector calib_cache_; + std::vector hist_cache_; + // mean for preprocessing + std::vector m_mean; + // std for preprocessing + std::vector m_std; +}; + +/** + * @class Int8MinMaxCalibrator + * @brief Calibrator for MinMax + * + */ +class Int8MinMaxCalibrator : public nvinfer1::IInt8MinMaxCalibrator +{ +public: + Int8MinMaxCalibrator( + ImageStream & stream, const std::string calibration_cache_file, + const std::vector & mean = {123.675, 116.28, 103.53}, + const std::vector & std = {58.395, 57.12, 57.375}, bool read_cache = true) + : stream_(stream), calibration_cache_file_(calibration_cache_file), read_cache_(read_cache) + { + auto d = stream_.getInputDims(); + input_count_ = stream_.getBatchSize() * d.d[1] * d.d[2] * d.d[3]; + m_std = std; + m_mean = mean; + CHECK_CUDA_ERROR(cudaMalloc(&device_input_, input_count_ * sizeof(float))); + auto algType = getAlgorithm(); + switch (algType) { + case (nvinfer1::CalibrationAlgoType::kLEGACY_CALIBRATION): + std::cout << "CalibratioAlgoType : kLEGACY_CALIBRATION" << std::endl; + break; + case (nvinfer1::CalibrationAlgoType::kENTROPY_CALIBRATION): + std::cout << "CalibratioAlgoType : kENTROPY_CALIBRATION" << std::endl; + break; + case (nvinfer1::CalibrationAlgoType::kENTROPY_CALIBRATION_2): + std::cout << "CalibratioAlgoType : kENTROPY_CALIBRATION_2" << std::endl; + break; + case (nvinfer1::CalibrationAlgoType::kMINMAX_CALIBRATION): + std::cout << "CalibratioAlgoType : kMINMAX_CALIBRATION" << std::endl; + break; + default: + std::cout << "No CalibrationAlgType" << std::endl; + break; + } + } + int getBatchSize() const noexcept override { return stream_.getBatchSize(); } + + virtual ~Int8MinMaxCalibrator() { CHECK_CUDA_ERROR(cudaFree(device_input_)); } + + bool getBatch(void * bindings[], const char * names[], int nb_bindings) noexcept override + { + (void)names; + (void)nb_bindings; + + if (!stream_.next(m_mean, m_std)) { + return false; + } + try { + CHECK_CUDA_ERROR(cudaMemcpy( + device_input_, stream_.getBatch(), input_count_ * sizeof(float), cudaMemcpyHostToDevice)); + } catch (const std::exception & e) { + // Do nothing + } + bindings[0] = device_input_; + return true; + } + + const void * readCalibrationCache(size_t & length) noexcept override + { + calib_cache_.clear(); + std::ifstream input(calibration_cache_file_, std::ios::binary); + input >> std::noskipws; + if (read_cache_ && input.good()) { + std::copy( + std::istream_iterator(input), std::istream_iterator(), + std::back_inserter(calib_cache_)); + } + + length = calib_cache_.size(); + if (length) { + std::cout << "Using cached calibration table to build the engine" << std::endl; + } else { + std::cout << "New calibration table will be created to build the engine" << std::endl; + } + return length ? &calib_cache_[0] : nullptr; + } + + void writeCalibrationCache(const void * cache, size_t length) noexcept override + { + std::ofstream output(calibration_cache_file_, std::ios::binary); + output.write(reinterpret_cast(cache), length); + } + +private: + ImageStream stream_; + const std::string calibration_cache_file_; + bool read_cache_{true}; + size_t input_count_; + void * device_input_{nullptr}; + std::vector calib_cache_; + std::vector hist_cache_; + // mean for preprocessing + std::vector m_mean; + // std for preprocessing + std::vector m_std; +}; +} // namespace tensorrt_classifier + +#endif // TENSORRT_CLASSIFIER__CALIBRATOR_HPP_ diff --git a/perception/tensorrt_classifier/include/tensorrt_classifier/preprocess.h b/perception/tensorrt_classifier/include/tensorrt_classifier/preprocess.h new file mode 100644 index 0000000000000..febf909b8826e --- /dev/null +++ b/perception/tensorrt_classifier/include/tensorrt_classifier/preprocess.h @@ -0,0 +1,181 @@ +// 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 TENSORRT_CLASSIFIER__PREPROCESS_H_ +#define TENSORRT_CLASSIFIER__PREPROCESS_H_ + +#include +#include +#include +#include +#include + +typedef struct _roi +{ + int x; + int y; + int w; + int h; +} Roi; + +/** + * @brief Resize a image using bilinear interpolation on gpus + * @param[out] dst Resized image + * @param[in] src image + * @param[in] d_w width for resized image + * @param[in] d_h height for resized image + * @param[in] d_c channel for resized image + * @param[in] s_w width for input image + * @param[in] s_h height for input image + * @param[in] s_c channel for input image + * @param[in] stream cuda stream + */ +extern void resize_bilinear_gpu( + unsigned char * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, + cudaStream_t stream); + +/** + * @brief Letterbox a image on gpus + * @param[out] dst letterboxed image + * @param[in] src image + * @param[in] d_w width for letterboxing + * @param[in] d_h height foletterboxing + * @param[in] d_c channel foletterboxing + * @param[in] s_w width for input image + * @param[in] s_h height for input image + * @param[in] s_c channel for input image + * @param[in] stream cuda stream + */ +extern void letterbox_gpu( + unsigned char * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, + cudaStream_t stream); + +/** + * @brief NHWC2NHWC conversion + * @param[out] dst converted image + * @param[in] src image + * @param[in] d_w width for a image + * @param[in] d_h height for a image + * @param[in] d_c channel for a image + * @param[in] stream cuda stream + */ +extern void NCHW2NHWC_gpu( + unsigned char * dst, unsigned char * src, int d_w, int d_h, int d_c, cudaStream_t stream); + +/** + * @brief Unsigned char to float32 for inference + * @param[out] dst32 converted image + * @param[in] src image + * @param[in] d_w width for a image + * @param[in] d_h height for a image + * @param[in] d_c channel for a image + * @param[in] stream cuda stream + */ +extern void toFloat_gpu( + float * dst32, unsigned char * src, int d_w, int d_h, int d_c, cudaStream_t stream); + +/** + * @brief Resize and letterbox a image using bilinear interpolation on gpus + * @param[out] dst processsed image + * @param[in] src image + * @param[in] d_w width for output + * @param[in] d_h height for output + * @param[in] d_c channel for output + * @param[in] s_w width for input + * @param[in] s_h height for input + * @param[in] s_c channel for input + * @param[in] stream cuda stream + */ +extern void resize_bilinear_letterbox_gpu( + unsigned char * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, + cudaStream_t stream); + +/** + * @brief Optimized preprocessing including resize, letterbox, nhwc2nchw, toFloat and normalization + * for YOLOX on gpus + * @param[out] dst processsed image + * @param[in] src image + * @param[in] d_w width for output + * @param[in] d_h height for output + * @param[in] d_c channel for output + * @param[in] s_w width for input + * @param[in] s_h height for input + * @param[in] s_c channel for input + * @param[in] norm normalization + * @param[in] stream cuda stream + */ +extern void resize_bilinear_letterbox_nhwc_to_nchw32_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, + float norm, cudaStream_t stream); + +/** + * @brief Optimized preprocessing including resize, letterbox, nhwc2nchw, toFloat and normalization + * with batching for YOLOX on gpus + * @param[out] dst processsed image + * @param[in] src image + * @param[in] d_w width for output + * @param[in] d_h height for output + * @param[in] d_c channel for output + * @param[in] s_w width for input + * @param[in] s_h height for input + * @param[in] s_c channel for input + * @param[in] batch batch size + * @param[in] norm normalization + * @param[in] stream cuda stream + */ +extern void resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, int batch, + float norm, cudaStream_t stream); + +/** + * @brief Optimized preprocessing including crop, resize, letterbox, nhwc2nchw, toFloat and + * normalization with batching for YOLOX on gpus + * @param[out] dst processsed image + * @param[in] src image + * @param[in] d_w width for output + * @param[in] d_h height for output + * @param[in] d_c channel for output + * @param[in] s_w width for input + * @param[in] s_h height for input + * @param[in] s_c channel for input + * @param[in] d_roi regions of interest for cropping + * @param[in] batch batch size + * @param[in] norm normalization + * @param[in] stream cuda stream + */ +extern void crop_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, Roi * d_roi, int s_w, int s_h, + int s_c, int batch, float norm, cudaStream_t stream); + +/** + * @brief Optimized multi-scale preprocessing including crop, resize, letterbox, nhwc2nchw, toFloat + * and normalization with batching for YOLOX on gpus + * @param[out] dst processsed image + * @param[in] src image + * @param[in] d_w width for output + * @param[in] d_h height for output + * @param[in] d_c channel for output + * @param[in] s_w width for input + * @param[in] s_h height for input + * @param[in] s_c channel for input + * @param[in] d_roi regions of interest for cropping + * @param[in] batch batch size + * @param[in] norm normalization + * @param[in] stream cuda stream + */ +extern void multi_scale_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, Roi * d_roi, int s_w, int s_h, + int s_c, int batch, float norm, cudaStream_t stream); + +#endif // TENSORRT_CLASSIFIER__PREPROCESS_H_ diff --git a/perception/tensorrt_classifier/include/tensorrt_classifier/tensorrt_classifier.hpp b/perception/tensorrt_classifier/include/tensorrt_classifier/tensorrt_classifier.hpp new file mode 100644 index 0000000000000..7e2c852d369fb --- /dev/null +++ b/perception/tensorrt_classifier/include/tensorrt_classifier/tensorrt_classifier.hpp @@ -0,0 +1,132 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TENSORRT_CLASSIFIER__TENSORRT_CLASSIFIER_HPP_ +#define TENSORRT_CLASSIFIER__TENSORRT_CLASSIFIER_HPP_ + +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace tensorrt_classifier +{ +using cuda_utils::CudaUniquePtr; +using cuda_utils::CudaUniquePtrHost; +using cuda_utils::makeCudaStream; +using cuda_utils::StreamUniquePtr; + +/** + * @class TrtClassifier + * @brief TensorRT CLASSIFIER for faster inference + */ +class TrtClassifier +{ +public: + /** + * @brief Construct TrtClassifier. + * @param[in] mode_path ONNX model_path + * @param[in] precision precision for inference + * @param[in] calibration_images path for calibration files (only require for quantization) + * @param[in] batch_config configuration for batched execution + * @param[in] max_workspace_size maximum workspace for building TensorRT engine + * @param[in] mean mean for preprocess + * @param[in] std std for preprocess + * @param[in] buildConfig configuration including precision, calibration method, dla, remaining + * fp16 for first layer, remaining fp16 for last layer and profiler for builder + * @param[in] cuda whether use cuda gpu for preprocessing + */ + TrtClassifier( + const std::string & model_path, const std::string & precision, + const tensorrt_common::BatchConfig & batch_config = {1, 1, 1}, + const std::vector & mean = {123.675, 116.28, 103.53}, + const std::vector & std = {58.395, 57.12, 57.375}, + const size_t max_workspace_size = (1 << 30), const std::string & calibration_images = "", + const tensorrt_common::BuildConfig build_config = + tensorrt_common::BuildConfig("MinMax", -1, false, false, false, 0.0), + const bool cuda = false); + /** + * @brief Deconstruct TrtClassifier + */ + ~TrtClassifier(); + + /** + * @brief run inference including pre-process and post-process + * @param[out] objects results for object detection + * @param[in] images batched images + */ + bool doInference( + const std::vector & images, std::vector & results, std::vector & probs); + + /** + * @brief allocate buffer for preprocess on GPU + * @param[in] width original image width + * @param[in] height original image height + * @warning if we don't allocate buffers using it, "preprocessGpu" allocates buffers at the + * beginning + */ + void initPreprocessBuffer(int width, int height); + +private: + /** + * @brief run preprcess including resizing, letterbox, BGR2RGB, NHWC2NCHW and toFloat on CPU + * @param[in] images batching images + */ + void preprocess_opt(const std::vector & images); + + /** + * @brief run preprocess on GPU + * @param[in] images batching images + * @warning Current support is only a single batch image + */ + void preprocessGpu(const std::vector & images); + + bool feedforwardAndDecode( + const std::vector & images, std::vector & results, std::vector & probs); + + std::unique_ptr trt_common_; + + std::vector input_h_; + CudaUniquePtr input_d_; + + bool needs_output_decode_; + size_t out_elem_num_; + size_t out_elem_num_per_batch_; + CudaUniquePtr out_prob_d_; + + StreamUniquePtr stream_{makeCudaStream()}; + // mean for preprocessing + std::vector mean_; + // std for preprocessing + std::vector std_; + std::vector inv_std_; + // flg for preprecessing on GPU + bool m_cuda; + // host buffer for preprecessing on GPU + unsigned char * h_img_; + // device buffer for preprecessing on GPU + unsigned char * d_img_; + int src_width_; + int src_height_; + int batch_size_; + CudaUniquePtrHost out_prob_h_; +}; +} // namespace tensorrt_classifier + +#endif // TENSORRT_CLASSIFIER__TENSORRT_CLASSIFIER_HPP_ diff --git a/perception/tensorrt_classifier/package.xml b/perception/tensorrt_classifier/package.xml new file mode 100644 index 0000000000000..27513652ae829 --- /dev/null +++ b/perception/tensorrt_classifier/package.xml @@ -0,0 +1,33 @@ + + + tensorrt_classifier + 0.0.1 + tensorrt classifier wrapper + + Dan Umeda + Mingyu Li + >Mingyu Li + + Apache License 2.0 + + ament_cmake_auto + cudnn_cmake_module + tensorrt_cmake_module + + cudnn_cmake_module + tensorrt_cmake_module + + autoware_cmake + + cuda_utils + libopencv-dev + rclcpp + tensorrt_common + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/perception/tensorrt_classifier/src/preprocess.cu b/perception/tensorrt_classifier/src/preprocess.cu new file mode 100644 index 0000000000000..fd3d758c2c280 --- /dev/null +++ b/perception/tensorrt_classifier/src/preprocess.cu @@ -0,0 +1,596 @@ +// 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 +#include + +#include + +#define BLOCK 512 + +#define MIN(x, y) x < y ? x : y + +dim3 cuda_gridsize(size_t n) +{ + size_t k = (n - 1) / BLOCK + 1; + size_t x = k; + size_t y = 1; + if (x > 65535) { + x = ceil(sqrt(k)); + y = (n - 1) / (x * BLOCK) + 1; + } + dim3 d; + d.x = x; + d.y = y; + d.z = 1; + return d; +} + +__device__ double lerp1d(int a, int b, float w) +{ + return fma(w, (float)b, fma(-w, (float)a, (float)a)); +} + +__device__ float lerp2d(int f00, int f01, int f10, int f11, float centroid_h, float centroid_w) +{ + centroid_w = (1 + lroundf(centroid_w) - centroid_w) / 2; + centroid_h = (1 + lroundf(centroid_h) - centroid_h) / 2; + + float r0, r1, r; + r0 = lerp1d(f00, f01, centroid_w); + r1 = lerp1d(f10, f11, centroid_w); + + r = lerp1d(r0, r1, centroid_h); //+ 0.00001 + return r; +} + +__global__ void resize_bilinear_kernel( + int N, unsigned char * dst_img, unsigned char * src_img, int dst_h, int dst_w, int src_h, + int src_w, float stride_h, float stride_w) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int C = 3; + int W = dst_w; + + int c = 0; + int n = 0; + + int w = index % W; + int h = index / W; + + float centroid_h, centroid_w; + centroid_h = stride_h * (float)(h + 0.5); + centroid_w = stride_w * (float)(w + 0.5); + + int f00, f01, f10, f11; + + int src_h_idx = lroundf(centroid_h) - 1; + int src_w_idx = lroundf(centroid_w) - 1; + if (src_h_idx < 0) { + src_h_idx = 0; + } + if (src_w_idx < 0) { + src_w_idx = 0; + } + + index = C * w + C * W * h; + // Unroll + for (c = 0; c < C; c++) { + f00 = n * src_h * src_w * C + src_h_idx * src_w * C + src_w_idx * C + c; + f01 = n * src_h * src_w * C + src_h_idx * src_w * C + (src_w_idx + 1) * C + c; + f10 = n * src_h * src_w * C + (src_h_idx + 1) * src_w * C + src_w_idx * C + c; + f11 = n * src_h * src_w * C + (src_h_idx + 1) * src_w * C + (src_w_idx + 1) * C + c; + + float rs = lroundf(lerp2d( + (int)src_img[f00], (int)src_img[f01], (int)src_img[f10], (int)src_img[f11], centroid_h, + centroid_w)); + dst_img[index + c] = (unsigned char)rs; + } +} + +void resize_bilinear_gpu( + unsigned char * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, + cudaStream_t stream) +{ + int N = d_w * d_h; + float stride_h = (float)s_h / (float)d_h; + float stride_w = (float)s_w / (float)d_w; + + resize_bilinear_kernel<<>>( + N, dst, src, d_h, d_w, s_h, s_w, stride_h, stride_w); +} + +__global__ void letterbox_kernel( + int N, unsigned char * dst_img, unsigned char * src_img, int dst_h, int dst_w, int src_h, + int src_w, float scale, int letter_bot, int letter_right) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int C = 3; + int W = dst_w; + int c = 0; + + int w = index % W; + int h = index / W; + + index = (C * w) + (C * W * h); + // Unroll + int index2 = (C * w) + (C * src_w * h); + for (c = 0; c < C; c++) { + dst_img[index + c] = + (w >= letter_right || h >= letter_bot) ? (unsigned int)114 : src_img[index2 + c]; + } +} + +void letterbox_gpu( + unsigned char * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, + cudaStream_t stream) +{ + int N = d_w * d_h; + const float scale = std::min(d_w / (float)s_w, d_h / (float)s_h); + int r_h = (int)(scale * s_h); + int r_w = (int)(scale * s_w); + + float stride_h = (float)s_h / (float)r_h; + float stride_w = (float)s_w / (float)r_w; + letterbox_kernel<<>>( + N, dst, src, d_h, d_w, r_h, r_w, 1.0 / scale, r_h, r_w); +} + +__global__ void NHWC2NCHW_kernel( + int N, unsigned char * dst_img, unsigned char * src_img, int height, int width) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int chan = 3; + int c = 0; + int x = index % width; + int y = index / width; + int src_index = 0; + int dst_index = 0; + for (c = 0; c < chan; c++) { + src_index = c + (chan * x) + (chan * width * y); + dst_index = x + (width * y) + (width * height * c); + dst_img[dst_index] = src_img[src_index]; + } +} + +void NHWC2NCHW_gpu( + unsigned char * dst, unsigned char * src, int d_w, int d_h, int d_c, cudaStream_t stream) +{ + int N = d_w * d_h; + NHWC2NCHW_kernel<<>>(N, dst, src, d_h, d_w); +} + +__global__ void NCHW2NHWC_kernel( + int N, unsigned char * dst, unsigned char * src, int height, int width) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int chan = 3; + int c = 0; + int x = index % width; + int y = index / width; + int src_index = 0; + int dst_index = 0; + for (c = 0; c < chan; c++) { + // NHWC + dst_index = c + (chan * x) + (chan * width * y); + // NCHW + src_index = x + (width * y) + (width * height * c); + dst[dst_index] = src[src_index]; + } +} + +void NCHW2NHWC_gpu( + unsigned char * dst, unsigned char * src, int d_w, int d_h, int d_c, cudaStream_t stream) +{ + int N = d_w * d_h; + NCHW2NHWC_kernel<<>>(N, dst, src, d_h, d_w); +} + +__global__ void toFloat_kernel(int N, float * dst32, unsigned char * src8, int height, int width) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int chan = 3; + int c = 0; + int x = index % width; + int y = index / width; + int dst_index = 0; + for (c = 0; c < chan; c++) { + // NCHW + dst_index = x + (width * y) + (width * height * c); + dst32[dst_index] = (float)(src8[dst_index]); + } +} + +void toFloat_gpu(float * dst32, unsigned char * src, int d_w, int d_h, int d_c, cudaStream_t stream) +{ + int N = d_w * d_h; + toFloat_kernel<<>>(N, dst32, src, d_h, d_w); +} + +__global__ void resize_bilinear_letterbox_kernel( + int N, unsigned char * dst_img, unsigned char * src_img, int dst_h, int dst_w, int src_h, + int src_w, float scale, int letter_bot, int letter_right) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int C = 3; // # ChannelDim + int W = dst_w; + int c = 0; + int n = 0; // index / (C*W*H); + + int w = index % W; + int h = index / W; + + float centroid_h, centroid_w; + centroid_h = scale * (float)(h + 0.5); + centroid_w = scale * (float)(w + 0.5); + + int f00, f01, f10, f11; + + int src_h_idx = (int)lroundf(centroid_h) - 1; + int src_w_idx = (int)lroundf(centroid_w) - 1; + if (src_h_idx < 0) { + src_h_idx = 0; + } + if (src_w_idx < 0) { + src_w_idx = 0; + } + if (src_h_idx >= src_h) { + src_h_idx = src_h - 1; + } + if (src_w_idx >= src_w) { + src_w_idx = src_w - 1; + } + + index = (C * w) + (C * W * h); + // Unroll + for (c = 0; c < C; c++) { + f00 = n * src_h * src_w * C + src_h_idx * src_w * C + src_w_idx * C + c; + f01 = n * src_h * src_w * C + src_h_idx * src_w * C + (src_w_idx + 1) * C + c; + f10 = n * src_h * src_w * C + (src_h_idx + 1) * src_w * C + src_w_idx * C + c; + f11 = n * src_h * src_w * C + (src_h_idx + 1) * src_w * C + (src_w_idx + 1) * C + c; + + float rs = lroundf(lerp2d( + (int)src_img[f00], (int)src_img[f01], (int)src_img[f10], (int)src_img[f11], centroid_h, + centroid_w)); + dst_img[index + c] = (unsigned char)rs; + dst_img[index + c] = (h >= letter_bot) ? (unsigned int)114 : dst_img[index + c]; + dst_img[index + c] = (w >= letter_right) ? (unsigned int)114 : dst_img[index + c]; + } +} + +void resize_bilinear_letterbox_gpu( + unsigned char * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, + cudaStream_t stream) +{ + int N = d_w * d_h; + const float scale = std::min(d_w / (float)s_w, d_h / (float)s_h); + int r_h = (int)(scale * s_h); + int r_w = (int)(scale * s_w); + float stride_h = (float)s_h / (float)r_h; + float stride_w = (float)s_w / (float)r_w; + resize_bilinear_letterbox_kernel<<>>( + N, dst, src, d_h, d_w, s_h, s_w, 1.0 / scale, r_h, r_w); +} + +__global__ void resize_bilinear_letterbox_nhwc_to_nchw32_kernel( + int N, float * dst_img, unsigned char * src_img, int dst_h, int dst_w, int src_h, int src_w, + float scale, int letter_bot, int letter_right, float norm) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int C = 3; + int H = dst_h; + int W = dst_w; + int c = 0; + + int w = index % W; + int h = index / W; + + float centroid_h, centroid_w; + centroid_h = scale * (float)(h + 0.5); + centroid_w = scale * (float)(w + 0.5); + + int f00, f01, f10, f11; + + int src_h_idx = lroundf(centroid_h) - 1; + int src_w_idx = lroundf(centroid_w) - 1; + src_h_idx = (src_h_idx < 0) ? 0 : src_h_idx; + src_h_idx = (src_h_idx >= (src_h - 1)) ? src_h - 2 : src_h_idx; + src_w_idx = (src_w_idx < 0) ? 0 : src_w_idx; + src_w_idx = (src_w_idx >= (src_w - 1)) ? src_w - 2 : src_w_idx; + // Unroll + int stride = src_w * C; + for (c = 0; c < C; c++) { + f00 = src_h_idx * stride + src_w_idx * C + c; + f01 = src_h_idx * stride + (src_w_idx + 1) * C + c; + f10 = (src_h_idx + 1) * stride + src_w_idx * C + c; + f11 = (src_h_idx + 1) * stride + (src_w_idx + 1) * C + c; + + float rs = lroundf(lerp2d( + (int)src_img[f00], (int)src_img[f01], (int)src_img[f10], (int)src_img[f11], centroid_h, + centroid_w)); + + // NHCW + int dst_index = w + (W * h) + (W * H * c); + + dst_img[dst_index] = (float)rs; + dst_img[dst_index] = (h >= letter_bot) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] = (w >= letter_right) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] *= norm; + } +} + +void resize_bilinear_letterbox_nhwc_to_nchw32_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, + float norm, cudaStream_t stream) +{ + int N = d_w * d_h; + const float scale = std::min(d_w / (float)s_w, d_h / (float)s_h); + int r_h = scale * s_h; + int r_w = scale * s_w; + float stride_h = (float)s_h / (float)r_h; + float stride_w = (float)s_w / (float)r_w; + + resize_bilinear_letterbox_nhwc_to_nchw32_kernel<<>>( + N, dst, src, d_h, d_w, s_h, s_w, 1.0 / scale, r_h, r_w, norm); +} + +__global__ void resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel( + int N, float * dst_img, unsigned char * src_img, int dst_h, int dst_w, int src_h, int src_w, + float scale, int letter_bot, int letter_right, float norm, int batch) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int C = 3; + int H = dst_h; + int W = dst_w; + int c = 0; + // w * h * b + + int w = index % W; + int h = index / (W); + float centroid_h, centroid_w; + centroid_h = scale * (float)(h + 0.5); + centroid_w = scale * (float)(w + 0.5); + + int f00, f01, f10, f11; + + int src_h_idx = lroundf(centroid_h) - 1; + int src_w_idx = lroundf(centroid_w) - 1; + src_h_idx = (src_h_idx < 0) ? 0 : src_h_idx; + src_h_idx = (src_h_idx >= (src_h - 1)) ? src_h - 2 : src_h_idx; + src_w_idx = (src_w_idx < 0) ? 0 : src_w_idx; + src_w_idx = (src_w_idx >= (src_w - 1)) ? src_w - 2 : src_w_idx; + // Unroll + int stride = src_w * C; + int b_stride = src_h * src_w * C; + int b; + const float mean[3] = {123.675, 116.28, 103.53}; + const float std[3] = {58.395, 57.12, 57.375}; + for (b = 0; b < batch; b++) { + for (c = 0; c < C; c++) { + // NHWC + // bgr2rgb + f00 = src_h_idx * stride + src_w_idx * C + (C - c - 1) + b * b_stride; + + f01 = src_h_idx * stride + (src_w_idx + 1) * C + (C - c - 1) + b * b_stride; + + f10 = (src_h_idx + 1) * stride + src_w_idx * C + (C - c - 1) + b * b_stride; + f11 = (src_h_idx + 1) * stride + (src_w_idx + 1) * C + (C - c - 1) + b * b_stride; + + float rs = lroundf(lerp2d( + (int)src_img[f00], (int)src_img[f01], (int)src_img[f10], (int)src_img[f11], centroid_h, + centroid_w)); + + // NCHW + int dst_index = b * (W * H * C) + (W * H * c) + (W * h) + w; + + dst_img[dst_index] = (float)rs; + dst_img[dst_index] = (h >= letter_bot) ? 0.0 : dst_img[dst_index]; + dst_img[dst_index] = (w >= letter_right) ? 0.0 : dst_img[dst_index]; + dst_img[dst_index] -= mean[c]; + dst_img[dst_index] /= std[c]; + } + } +} + +void resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, int batch, + float norm, cudaStream_t stream) +{ + int N = d_w * d_h; + const float scale = std::min(d_w / (float)s_w, d_h / (float)s_h); + int r_h = scale * s_h; + int r_w = scale * s_w; + float stride_h = (float)s_h / (float)r_h; + float stride_w = (float)s_w / (float)r_w; + + resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel<<>>( + N, dst, src, d_h, d_w, s_h, s_w, 1.0 / scale, r_h, r_w, norm, batch); + /* + int b + for (b = 0; b < batch; b++) { + int index_dst = b * d_w * d_h * d_c; + int index_src = b * s_w * s_h * s_c; + resize_bilinear_letterbox_nhwc_to_nchw32_kernel<<>>(N, + &dst[index_dst], &src[index_src], d_h, d_w, s_h, s_w, 1.0/scale, r_h, r_w, norm + ); + } + */ +} + +__global__ void crop_resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel( + int N, float * dst_img, unsigned char * src_img, int dst_h, int dst_w, int src_h, int src_w, + Roi * d_roi, float norm, int batch) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int C = 3; + int H = dst_h; + int W = dst_w; + int c = 0; + // w * h * b + + int w = index % W; + int h = index / (W); + + int f00, f01, f10, f11; + + int b; + for (b = 0; b < batch; b++) { + float centroid_h, centroid_w; + int crop_h = d_roi[b].h; + int crop_w = d_roi[b].w; + int crop_y = d_roi[b].y; + int crop_x = d_roi[b].x; + float scale = (MIN(W / (float)crop_w, H / (float)crop_h)); + int letter_bot = (int)(scale * crop_h); + int letter_right = (int)(scale * crop_w); + scale = 1.0 / scale; + centroid_h = scale * (float)(h + 0.5); + centroid_w = scale * (float)(w + 0.5); + int src_h_idx = lroundf(centroid_h) - 1; + int src_w_idx = lroundf(centroid_w) - 1; + src_h_idx = (src_h_idx < 0) ? 0 : src_h_idx; + src_h_idx = (src_h_idx >= (crop_h - 1)) ? crop_h - 2 : src_h_idx; + src_w_idx = (src_w_idx < 0) ? 0 : src_w_idx; + src_w_idx = (src_w_idx >= (crop_w - 1)) ? crop_w - 2 : src_w_idx; + // Unroll + int stride = src_w * C; + int b_stride = src_h * src_w * C; + src_w_idx += crop_x; + src_h_idx += crop_y; + + for (c = 0; c < C; c++) { + // NHWC + f00 = src_h_idx * stride + src_w_idx * C + c + b * b_stride; + f01 = src_h_idx * stride + (src_w_idx + 1) * C + c + b * b_stride; + f10 = (src_h_idx + 1) * stride + src_w_idx * C + c + b * b_stride; + f11 = (src_h_idx + 1) * stride + (src_w_idx + 1) * C + c + b * b_stride; + + float rs = lroundf(lerp2d( + (int)src_img[f00], (int)src_img[f01], (int)src_img[f10], (int)src_img[f11], centroid_h, + centroid_w)); + + // NCHW + int dst_index = w + (W * h) + (W * H * c) + b * (W * H * C); + + dst_img[dst_index] = (float)rs; + dst_img[dst_index] = (h >= letter_bot) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] = (w >= letter_right) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] *= norm; + } + } +} + +void crop_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, Roi * d_roi, int s_w, int s_h, + int s_c, int batch, float norm, cudaStream_t stream) +{ + int N = d_w * d_h; + crop_resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel<<< + cuda_gridsize(N), BLOCK, 0, stream>>>(N, dst, src, d_h, d_w, s_h, s_w, d_roi, norm, batch); +} + +__global__ void multi_scale_resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel( + int N, float * dst_img, unsigned char * src_img, int dst_h, int dst_w, int src_h, int src_w, + Roi * d_roi, float norm, int batch) +{ + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int C = 3; + int H = dst_h; + int W = dst_w; + int c = 0; + // w * h * b + int w = index % W; + int h = index / (W); + int f00, f01, f10, f11, b; + for (b = 0; b < batch; b++) { + float centroid_h, centroid_w; + int crop_h = d_roi[b].h; + int crop_w = d_roi[b].w; + int crop_y = d_roi[b].y; + int crop_x = d_roi[b].x; + float scale = (MIN(W / (float)crop_w, H / (float)crop_h)); + int letter_bot = (int)(scale * crop_h); + int letter_right = (int)(scale * crop_w); + int src_h_idx, src_w_idx, stride; + scale = 1.0 / scale; + centroid_h = scale * (float)(h + 0.5); + centroid_w = scale * (float)(w + 0.5); + src_h_idx = lroundf(centroid_h) - 1; + src_w_idx = lroundf(centroid_w) - 1; + src_h_idx = (src_h_idx < 0) ? 0 : src_h_idx; + src_h_idx = (src_h_idx >= (crop_h - 1)) ? crop_h - 2 : src_h_idx; + src_w_idx = (src_w_idx < 0) ? 0 : src_w_idx; + src_w_idx = (src_w_idx >= (crop_w - 1)) ? crop_w - 2 : src_w_idx; + // Unroll + stride = src_w * C; + src_w_idx += crop_x; + src_h_idx += crop_y; + for (c = 0; c < C; c++) { + float rs; + int dst_index; + // NHWC + f00 = src_h_idx * stride + src_w_idx * C + c; + f01 = src_h_idx * stride + (src_w_idx + 1) * C + c; + f10 = (src_h_idx + 1) * stride + src_w_idx * C + c; + f11 = (src_h_idx + 1) * stride + (src_w_idx + 1) * C + c; + rs = lroundf(lerp2d( + (int)src_img[f00], (int)src_img[f01], (int)src_img[f10], (int)src_img[f11], centroid_h, + centroid_w)); + // NCHW + dst_index = w + (W * h) + (W * H * c) + b * (W * H * C); + dst_img[dst_index] = (float)rs; + dst_img[dst_index] = (h >= letter_bot) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] = (w >= letter_right) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] *= norm; + } + } +} + +void multi_scale_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, Roi * d_roi, int s_w, int s_h, + int s_c, int batch, float norm, cudaStream_t stream) +{ + int N = d_w * d_h; + multi_scale_resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel<<< + cuda_gridsize(N), BLOCK, 0, stream>>>(N, dst, src, d_h, d_w, s_h, s_w, d_roi, norm, batch); +} diff --git a/perception/tensorrt_classifier/src/tensorrt_classifier.cpp b/perception/tensorrt_classifier/src/tensorrt_classifier.cpp new file mode 100644 index 0000000000000..e9bde8cc4b4f8 --- /dev/null +++ b/perception/tensorrt_classifier/src/tensorrt_classifier.cpp @@ -0,0 +1,385 @@ +// 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 + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +static void trimLeft(std::string & s) +{ + s.erase(s.begin(), find_if(s.begin(), s.end(), [](int ch) { return !isspace(ch); })); +} + +static void trimRight(std::string & s) +{ + s.erase(find_if(s.rbegin(), s.rend(), [](int ch) { return !isspace(ch); }).base(), s.end()); +} + +std::string trim(std::string & s) +{ + trimLeft(s); + trimRight(s); + return s; +} + +bool fileExists(const std::string & file_name, bool verbose) +{ + if (!std::experimental::filesystem::exists(std::experimental::filesystem::path(file_name))) { + if (verbose) { + std::cout << "File does not exist : " << file_name << std::endl; + } + return false; + } + return true; +} + +std::vector loadListFromTextFile(const std::string filename) +{ + assert(fileExists(filename, true)); + std::vector list; + + std::ifstream f(filename); + if (!f) { + std::cout << "failed to open " << filename; + assert(0); + } + + std::string line; + while (std::getline(f, line)) { + if (line.empty()) + continue; + + else + list.push_back(trim(line)); + } + + return list; +} + +std::vector loadImageList(const std::string & filename, const std::string & prefix) +{ + std::vector fileList = loadListFromTextFile(filename); + for (auto & file : fileList) { + if (fileExists(file, false)) { + continue; + } else { + std::string prefixed = prefix + file; + if (fileExists(prefixed, false)) + file = prefixed; + else + std::cerr << "WARNING: couldn't find: " << prefixed << " while loading: " << filename + << std::endl; + } + } + return fileList; +} + +namespace tensorrt_classifier +{ +TrtClassifier::TrtClassifier( + const std::string & model_path, const std::string & precision, + const tensorrt_common::BatchConfig & batch_config, const std::vector & mean, + const std::vector & std, const size_t max_workspace_size, + const std::string & calibration_image_list_path, tensorrt_common::BuildConfig build_config, + const bool cuda) +{ + src_width_ = -1; + src_height_ = -1; + mean_ = mean; + std_ = std; + inv_std_ = std; + for (size_t i = 0; i < inv_std_.size(); i++) { + inv_std_[i] = 1.0 / inv_std_[i]; + } + batch_size_ = batch_config[2]; + if (precision == "int8") { + int max_batch_size = batch_config[2]; + nvinfer1::Dims input_dims = tensorrt_common::get_input_dims(model_path); + std::vector calibration_images; + if (calibration_image_list_path != "") { + calibration_images = loadImageList(calibration_image_list_path, ""); + } + tensorrt_classifier::ImageStream stream(max_batch_size, input_dims, calibration_images); + fs::path calibration_table{model_path}; + std::string calibName = ""; + std::string ext = ""; + if (build_config.calib_type_str == "Entropy") { + ext = "EntropyV2-"; + } else if ( + build_config.calib_type_str == "Legacy" || build_config.calib_type_str == "Percentile") { + ext = "Legacy-"; + } else { + ext = "MinMax-"; + } + ext += "calibration.table"; + calibration_table.replace_extension(ext); + fs::path histogram_table{model_path}; + ext = "histogram.table"; + histogram_table.replace_extension(ext); + + std::unique_ptr calibrator; + if (build_config.calib_type_str == "Entropy") { + calibrator.reset( + new tensorrt_classifier::Int8EntropyCalibrator(stream, calibration_table, mean_, std_)); + } else if ( + build_config.calib_type_str == "Legacy" || build_config.calib_type_str == "Percentile") { + double quantile = 0.999999; + double cutoff = 0.999999; + calibrator.reset(new tensorrt_classifier::Int8LegacyCalibrator( + stream, calibration_table, histogram_table, mean_, std_, true, quantile, cutoff)); + } else { + calibrator.reset( + new tensorrt_classifier::Int8MinMaxCalibrator(stream, calibration_table, mean_, std_)); + } + trt_common_ = std::make_unique( + model_path, precision, std::move(calibrator), batch_config, max_workspace_size, build_config); + } else { + trt_common_ = std::make_unique( + model_path, precision, nullptr, batch_config, max_workspace_size, build_config); + } + trt_common_->setup(); + + if (!trt_common_->isInitialized()) { + return; + } + + // GPU memory allocation + const auto input_dims = trt_common_->getBindingDimensions(0); + const auto input_size = + std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies()); + + const auto output_dims = trt_common_->getBindingDimensions(1); + input_d_ = cuda_utils::make_unique(batch_config[2] * input_size); + out_elem_num_ = std::accumulate( + output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); + out_elem_num_ = out_elem_num_ * batch_config[2]; + out_elem_num_per_batch_ = static_cast(out_elem_num_ / batch_config[2]); + out_prob_d_ = cuda_utils::make_unique(out_elem_num_); + out_prob_h_ = cuda_utils::make_unique_host(out_elem_num_, cudaHostAllocPortable); + + if (cuda) { + m_cuda = true; + h_img_ = NULL; + d_img_ = NULL; + + } else { + m_cuda = false; + } +} + +TrtClassifier::~TrtClassifier() +{ + if (m_cuda) { + if (h_img_) CHECK_CUDA_ERROR(cudaFreeHost(h_img_)); + if (d_img_) CHECK_CUDA_ERROR(cudaFree(d_img_)); + } +} + +void TrtClassifier::initPreprocessBuffer(int width, int height) +{ + // if size of source input has benn changed... + if (src_width_ != -1 || src_height_ != -1) { + if (width != src_width_ || height != src_height_) { + // Free cuda memory to reallocate + if (h_img_) { + CHECK_CUDA_ERROR(cudaFreeHost(h_img_)); + h_img_ = NULL; + } + if (d_img_) { + CHECK_CUDA_ERROR(cudaFree(d_img_)); + d_img_ = NULL; + } + } + } + src_width_ = width; + src_height_ = height; + if (m_cuda) { + auto input_dims = trt_common_->getBindingDimensions(0); + bool const hasRuntimeDim = std::any_of( + input_dims.d, input_dims.d + input_dims.nbDims, + [](int32_t input_dim) { return input_dim == -1; }); + if (hasRuntimeDim) { + input_dims.d[0] = batch_size_; + } + if (!h_img_) { + trt_common_->setBindingDimensions(0, input_dims); + } + if (!h_img_) { + CHECK_CUDA_ERROR(cudaMallocHost( + reinterpret_cast(&h_img_), + sizeof(unsigned char) * width * height * 3 * batch_size_)); + CHECK_CUDA_ERROR(cudaMalloc( + reinterpret_cast(&d_img_), + sizeof(unsigned char) * width * height * 3 * batch_size_)); + } + } +} + +void TrtClassifier::preprocessGpu(const std::vector & images) +{ + const auto batch_size = images.size(); + auto input_dims = trt_common_->getBindingDimensions(0); + + input_dims.d[0] = batch_size; + for (const auto & image : images) { + // if size of source input has benn changed... + int width = image.cols; + int height = image.rows; + if (src_width_ != -1 || src_height_ != -1) { + if (width != src_width_ || height != src_height_) { + // Free cuda memory to reallocate + if (h_img_) { + CHECK_CUDA_ERROR(cudaFreeHost(h_img_)); + h_img_ = NULL; + } + if (d_img_) { + CHECK_CUDA_ERROR(cudaFree(d_img_)); + d_img_ = NULL; + } + } + } + src_width_ = width; + src_height_ = height; + } + if (!h_img_) { + trt_common_->setBindingDimensions(0, input_dims); + } + const float input_height = static_cast(input_dims.d[2]); + const float input_width = static_cast(input_dims.d[3]); + int b = 0; + for (const auto & image : images) { + if (!h_img_) { + CHECK_CUDA_ERROR(cudaMallocHost( + reinterpret_cast(&h_img_), + sizeof(unsigned char) * image.cols * image.rows * 3 * batch_size)); + CHECK_CUDA_ERROR(cudaMalloc( + reinterpret_cast(&d_img_), + sizeof(unsigned char) * image.cols * image.rows * 3 * batch_size)); + } + int index = b * image.cols * image.rows * 3; + // Copy into pinned memory + memcpy(&(h_img_[index]), &image.data[0], image.cols * image.rows * 3 * sizeof(unsigned char)); + b++; + } + // Copy into device memory + CHECK_CUDA_ERROR(cudaMemcpyAsync( + d_img_, h_img_, images[0].cols * images[0].rows * 3 * batch_size * sizeof(unsigned char), + cudaMemcpyHostToDevice, *stream_)); + resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + input_d_.get(), d_img_, input_width, input_height, 3, images[0].cols, images[0].rows, 3, + batch_size, static_cast(1.0), *stream_); + // No Need for Sync and used for timer + // CHECK_CUDA_ERROR(cudaStreamSynchronize(*stream_)); +} + +void TrtClassifier::preprocess_opt(const std::vector & images) +{ + int batch_size = static_cast(images.size()); + auto input_dims = trt_common_->getBindingDimensions(0); + input_dims.d[0] = batch_size; + trt_common_->setBindingDimensions(0, input_dims); + const float input_chan = static_cast(input_dims.d[1]); + const float input_height = static_cast(input_dims.d[2]); + const float input_width = static_cast(input_dims.d[3]); + std::vector dst_images; + int volume = batch_size * input_chan * input_height * input_width; + input_h_.resize(volume); + dst_images.resize(images.size()); + // NHWC + const size_t strides_cv[4] = { + static_cast(input_width * input_chan * input_height), + static_cast(input_width * input_chan), static_cast(input_chan), 1}; + // NCHW + const size_t strides[4] = { + static_cast(input_height * input_width * input_chan), + static_cast(input_height * input_width), static_cast(input_width), 1}; +#pragma omp parallel for + for (int n = 0; n < batch_size; n++) { + const float scale = std::min(input_width / images[n].cols, input_height / images[n].rows); + const auto scale_size = cv::Size(images[n].cols * scale, images[n].rows * scale); + cv::resize(images[n], dst_images[n], scale_size, 0, 0, cv::INTER_LINEAR); + const auto bottom = input_height - dst_images[n].rows; + const auto right = input_width - dst_images[n].cols; + copyMakeBorder( + dst_images[n], dst_images[n], 0, bottom, 0, right, cv::BORDER_CONSTANT, {0, 0, 0}); + for (int h = 0; h < input_height; h++) { + for (int w = 0; w < input_width; w++) { + for (int c = 0; c < input_chan; c++) { + // NHWC (needs RBswap) + const size_t offset_cv = h * strides_cv[1] + w * strides_cv[2] + c * strides_cv[3]; + // NCHW + const size_t offset = n * strides[0] + (c)*strides[1] + h * strides[2] + w * strides[3]; + input_h_[offset] = + (static_cast(dst_images[n].data[offset_cv]) - mean_[c]) * inv_std_[c]; + } + } + } + } + CHECK_CUDA_ERROR(cudaMemcpy( + input_d_.get(), input_h_.data(), input_h_.size() * sizeof(float), cudaMemcpyHostToDevice)); + // No Need for Sync +} + +bool TrtClassifier::doInference( + const std::vector & images, std::vector & results, std::vector & probs) +{ + if (!trt_common_->isInitialized()) { + return false; + } + preprocess_opt(images); + + return feedforwardAndDecode(images, results, probs); +} + +bool TrtClassifier::feedforwardAndDecode( + const std::vector & images, std::vector & results, std::vector & probs) +{ + results.clear(); + probs.clear(); + std::vector buffers = {input_d_.get(), out_prob_d_.get()}; + trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + + int batch_size = static_cast(images.size()); + + CHECK_CUDA_ERROR(cudaMemcpyAsync( + out_prob_h_.get(), out_prob_d_.get(), sizeof(float) * out_elem_num_, cudaMemcpyDeviceToHost, + *stream_)); + cudaStreamSynchronize(*stream_); + + for (int i = 0; i < batch_size; ++i) { + float max = 0.0; + int index = 0; + float * output = out_prob_h_.get(); + for (size_t j = 0; j < out_elem_num_per_batch_; j++) { + if (max < output[j + i * out_elem_num_per_batch_]) { + max = output[j + i * out_elem_num_per_batch_]; + index = j; + } + } + probs.push_back(max); + results.push_back(index); + } + return true; +} +} // namespace tensorrt_classifier diff --git a/perception/tensorrt_yolox/include/tensorrt_yolox/preprocess.hpp b/perception/tensorrt_yolox/include/tensorrt_yolox/preprocess.hpp index f068268d2fc65..830cf184e10e8 100644 --- a/perception/tensorrt_yolox/include/tensorrt_yolox/preprocess.hpp +++ b/perception/tensorrt_yolox/include/tensorrt_yolox/preprocess.hpp @@ -23,6 +23,14 @@ namespace tensorrt_yolox { +struct Roi +{ + int x; + int y; + int w; + int h; +}; + /** * @brief Resize a image using bilinear interpolation on gpus * @param[out] dst Resized image @@ -112,6 +120,65 @@ extern void resize_bilinear_letterbox_gpu( extern void resize_bilinear_letterbox_nhwc_to_nchw32_gpu( float * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, float norm, cudaStream_t stream); + +/** + * @brief Optimized preprocessing including resize, letterbox, nhwc2nchw, toFloat and normalization + * with batching for YOLOX on gpus + * @param[out] dst processsed image + * @param[in] src image + * @param[in] d_w width for output + * @param[in] d_h height for output + * @param[in] d_c channel for output + * @param[in] s_w width for input + * @param[in] s_h height for input + * @param[in] s_c channel for input + * @param[in] batch batch size + * @param[in] norm normalization + * @param[in] stream cuda stream + */ +extern void resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, int batch, + float norm, cudaStream_t stream); + +/** + * @brief Optimized preprocessing including crop, resize, letterbox, nhwc2nchw, toFloat and + * normalization with batching for YOLOX on gpus + * @param[out] dst processsed image + * @param[in] src image + * @param[in] d_w width for output + * @param[in] d_h height for output + * @param[in] d_c channel for output + * @param[in] s_w width for input + * @param[in] s_h height for input + * @param[in] s_c channel for input + * @param[in] d_roi regions of interest for cropping + * @param[in] batch batch size + * @param[in] norm normalization + * @param[in] stream cuda stream + */ +extern void crop_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, Roi * d_roi, int s_w, int s_h, + int s_c, int batch, float norm, cudaStream_t stream); + +/** + * @brief Optimized multi-scale preprocessing including crop, resize, letterbox, nhwc2nchw, toFloat + * and normalization with batching for YOLOX on gpus + * @param[out] dst processsed image + * @param[in] src image + * @param[in] d_w width for output + * @param[in] d_h height for output + * @param[in] d_c channel for output + * @param[in] s_w width for input + * @param[in] s_h height for input + * @param[in] s_c channel for input + * @param[in] d_roi regions of interest for cropping + * @param[in] batch batch size + * @param[in] norm normalization + * @param[in] stream cuda stream + */ +extern void multi_scale_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, Roi * d_roi, int s_w, int s_h, + int s_c, int batch, float norm, cudaStream_t stream); } // namespace tensorrt_yolox #endif // TENSORRT_YOLOX__PREPROCESS_HPP_ diff --git a/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox.hpp b/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox.hpp index bdd6d6fe66861..fd50e67143d18 100644 --- a/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox.hpp +++ b/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox.hpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include @@ -82,9 +83,13 @@ class TrtYoloX const float score_threshold = 0.3, const float nms_threshold = 0.7, const tensorrt_common::BuildConfig build_config = tensorrt_common::BuildConfig(), const bool use_gpu_preprocess = false, std::string calibration_image_list_file = std::string(), - const double norm_factor = 1.0, const std::string & cache_dir = "", + const double norm_factor = 1.0, [[maybe_unused]] const std::string & cache_dir = "", const tensorrt_common::BatchConfig & batch_config = {1, 1, 1}, const size_t max_workspace_size = (1 << 30)); + /** + * @brief Deconstruct TrtYoloX + */ + ~TrtYoloX(); /** * @brief run inference including pre-process and post-process @@ -93,11 +98,29 @@ class TrtYoloX */ bool doInference(const std::vector & images, ObjectArrays & objects); + /** + * @brief run inference including pre-process and post-process + * @param[out] objects results for object detection + * @param[in] images batched images + * @param[in] rois region of interest for inference + */ + bool doInferenceWithRoi( + const std::vector & images, ObjectArrays & objects, const std::vector & roi); + + /** + * @brief run multi-scale inference including pre-process and post-process + * @param[out] objects results for object detection + * @param[in] image + * @param[in] rois region of interest for inference + */ + bool doMultiScaleInference( + const cv::Mat & image, ObjectArrays & objects, const std::vector & roi); + /** * @brief allocate buffer for preprocess on GPU * @param[in] width original image width * @param[in] height original image height - * @warning if we don't allocate buffers using it, "preprocess_gpu" allocates buffers at the + * @warning if we don't allocate buffers using it, "preprocessGpu" allocates buffers at the * beginning */ void initPreprocessBuffer(int width, int height); @@ -108,11 +131,51 @@ class TrtYoloX void printProfiling(void); private: + /** + * @brief run preprcess including resizing, letterbox, NHWC2NCHW and toFloat on CPU + * @param[in] images batching images + */ void preprocess(const std::vector & images); - // NOTE: Currently only supports a single batch image + /** + * @brief run preprocess on GPU + * @param[in] images batching images + */ void preprocessGpu(const std::vector & images); + /** + * @brief run preprcess including resizing, letterbox, NHWC2NCHW and toFloat on CPU + * @param[in] images batching images + * @param[in] rois region of interest + */ + void preprocessWithRoi(const std::vector & images, const std::vector & rois); + + /** + * @brief run preprocess on GPU + * @param[in] images batching images + * @param[in] rois region of interest + */ + void preprocessWithRoiGpu( + const std::vector & images, const std::vector & rois); + + /** + * @brief run multi-scale preprcess including resizing, letterbox, NHWC2NCHW and toFloat on CPU + * @param[in] images batching images + * @param[in] rois region of interest + */ + void multiScalePreprocess(const cv::Mat & image, const std::vector & rois); + + /** + * @brief run multi-scale preprcess including resizing, letterbox, NHWC2NCHW and toFloat on GPU + * @param[in] images batching images + * @param[in] rois region of interest + */ + void multiScalepreprocessGpu(const cv::Mat & image, const std::vector & rois); + + bool multiScaleFeedforward(const cv::Mat & image, int batch_size, ObjectArrays & objects); + bool multiScaleFeedforwardAndDecode( + const cv::Mat & images, int batch_size, ObjectArrays & objects); + bool feedforward(const std::vector & images, ObjectArrays & objects); bool feedforwardAndDecode(const std::vector & images, ObjectArrays & objects); void decodeOutputs(float * prob, ObjectArray & objects, float scale, cv::Size & img_size) const; @@ -165,7 +228,7 @@ class TrtYoloX int num_class_; float score_threshold_; float nms_threshold_; - + int batch_size_; CudaUniquePtrHost out_prob_h_; // flag whether preprocess are performed on GPU @@ -181,6 +244,11 @@ class TrtYoloX int src_width_; int src_height_; + + // host pointer for ROI + CudaUniquePtrHost roi_h_; + // device pointer for ROI + CudaUniquePtr roi_d_; }; } // namespace tensorrt_yolox diff --git a/perception/tensorrt_yolox/src/preprocess.cu b/perception/tensorrt_yolox/src/preprocess.cu index 7c9d9eff317df..3c3087c536f10 100644 --- a/perception/tensorrt_yolox/src/preprocess.cu +++ b/perception/tensorrt_yolox/src/preprocess.cu @@ -19,6 +19,8 @@ #include +#define MIN(x, y) x < y ? x : y + namespace tensorrt_yolox { constexpr size_t block = 512; @@ -368,4 +370,228 @@ void resize_bilinear_letterbox_nhwc_to_nchw32_gpu( resize_bilinear_letterbox_nhwc_to_nchw32_kernel<<>>( N, dst, src, d_h, d_w, s_h, s_w, 1.0 / scale, r_h, r_w, norm); } + +__global__ void resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel( + int N, float * dst_img, unsigned char * src_img, int dst_h, int dst_w, int src_h, int src_w, + float scale, int letter_bot, int letter_right, float norm, int batch) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int C = 3; + int H = dst_h; + int W = dst_w; + int c = 0; + // w * h * b + + int w = index % W; + int h = index / (W); + float centroid_h, centroid_w; + centroid_h = scale * (float)(h + 0.5); + centroid_w = scale * (float)(w + 0.5); + + int f00, f01, f10, f11; + + int src_h_idx = lroundf(centroid_h) - 1; + int src_w_idx = lroundf(centroid_w) - 1; + src_h_idx = (src_h_idx < 0) ? 0 : src_h_idx; + src_h_idx = (src_h_idx >= (src_h - 1)) ? src_h - 2 : src_h_idx; + src_w_idx = (src_w_idx < 0) ? 0 : src_w_idx; + src_w_idx = (src_w_idx >= (src_w - 1)) ? src_w - 2 : src_w_idx; + // Unroll + int stride = src_w * C; + int b_stride = src_h * src_w * C; + int b; + for (b = 0; b < batch; b++) { + for (c = 0; c < C; c++) { + // NHWC + f00 = src_h_idx * stride + src_w_idx * C + c + b * b_stride; + f01 = src_h_idx * stride + (src_w_idx + 1) * C + c + b * b_stride; + f10 = (src_h_idx + 1) * stride + src_w_idx * C + c + b * b_stride; + f11 = (src_h_idx + 1) * stride + (src_w_idx + 1) * C + c + b * b_stride; + + float rs = lroundf(lerp2d( + (int)src_img[f00], (int)src_img[f01], (int)src_img[f10], (int)src_img[f11], centroid_h, + centroid_w)); + + // NCHW + int dst_index = w + (W * h) + (W * H * c) + b * (W * H * C); + + dst_img[dst_index] = (float)rs; + dst_img[dst_index] = (h >= letter_bot) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] = (w >= letter_right) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] *= norm; + } + } +} + +void resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, int s_w, int s_h, int s_c, int batch, + float norm, cudaStream_t stream) +{ + int N = d_w * d_h; + const float scale = std::min(d_w / (float)s_w, d_h / (float)s_h); + int r_h = scale * s_h; + int r_w = scale * s_w; + float stride_h = (float)s_h / (float)r_h; + float stride_w = (float)s_w / (float)r_w; + + resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel<<>>( + N, dst, src, d_h, d_w, s_h, s_w, 1.0 / scale, r_h, r_w, norm, batch); + /* + int b + for (b = 0; b < batch; b++) { + int index_dst = b * d_w * d_h * d_c; + int index_src = b * s_w * s_h * s_c; + resize_bilinear_letterbox_nhwc_to_nchw32_kernel<<>>(N, + &dst[index_dst], &src[index_src], d_h, d_w, s_h, s_w, 1.0/scale, r_h, r_w, norm + ); + } + */ +} + +__global__ void crop_resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel( + int N, float * dst_img, unsigned char * src_img, int dst_h, int dst_w, int src_h, int src_w, + Roi * d_roi, float norm, int batch) +{ + // NHWC + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int C = 3; + int H = dst_h; + int W = dst_w; + int c = 0; + // w * h * b + + int w = index % W; + int h = index / (W); + + int f00, f01, f10, f11; + + int b; + for (b = 0; b < batch; b++) { + float centroid_h, centroid_w; + int crop_h = d_roi[b].h; + int crop_w = d_roi[b].w; + int crop_y = d_roi[b].y; + int crop_x = d_roi[b].x; + float scale = (MIN(W / (float)crop_w, H / (float)crop_h)); + int letter_bot = (int)(scale * crop_h); + int letter_right = (int)(scale * crop_w); + scale = 1.0 / scale; + centroid_h = scale * (float)(h + 0.5); + centroid_w = scale * (float)(w + 0.5); + int src_h_idx = lroundf(centroid_h) - 1; + int src_w_idx = lroundf(centroid_w) - 1; + src_h_idx = (src_h_idx < 0) ? 0 : src_h_idx; + src_h_idx = (src_h_idx >= (crop_h - 1)) ? crop_h - 2 : src_h_idx; + src_w_idx = (src_w_idx < 0) ? 0 : src_w_idx; + src_w_idx = (src_w_idx >= (crop_w - 1)) ? crop_w - 2 : src_w_idx; + // Unroll + int stride = src_w * C; + int b_stride = src_h * src_w * C; + src_w_idx += crop_x; + src_h_idx += crop_y; + + for (c = 0; c < C; c++) { + // NHWC + f00 = src_h_idx * stride + src_w_idx * C + c + b * b_stride; + f01 = src_h_idx * stride + (src_w_idx + 1) * C + c + b * b_stride; + f10 = (src_h_idx + 1) * stride + src_w_idx * C + c + b * b_stride; + f11 = (src_h_idx + 1) * stride + (src_w_idx + 1) * C + c + b * b_stride; + + float rs = lroundf(lerp2d( + (int)src_img[f00], (int)src_img[f01], (int)src_img[f10], (int)src_img[f11], centroid_h, + centroid_w)); + + // NCHW + int dst_index = w + (W * h) + (W * H * c) + b * (W * H * C); + + dst_img[dst_index] = (float)rs; + dst_img[dst_index] = (h >= letter_bot) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] = (w >= letter_right) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] *= norm; + } + } +} + +void crop_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, Roi * d_roi, int s_w, int s_h, + int s_c, int batch, float norm, cudaStream_t stream) +{ + int N = d_w * d_h; + crop_resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel<<< + cuda_gridsize(N), block, 0, stream>>>(N, dst, src, d_h, d_w, s_h, s_w, d_roi, norm, batch); +} + +__global__ void multi_scale_resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel( + int N, float * dst_img, unsigned char * src_img, int dst_h, int dst_w, int src_h, int src_w, + Roi * d_roi, float norm, int batch) +{ + int index = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x; + + if (index >= N) return; + int C = 3; + int H = dst_h; + int W = dst_w; + int c = 0; + // w * h * b + int w = index % W; + int h = index / (W); + int f00, f01, f10, f11, b; + for (b = 0; b < batch; b++) { + float centroid_h, centroid_w; + int crop_h = d_roi[b].h; + int crop_w = d_roi[b].w; + int crop_y = d_roi[b].y; + int crop_x = d_roi[b].x; + float scale = (MIN(W / (float)crop_w, H / (float)crop_h)); + int letter_bot = (int)(scale * crop_h); + int letter_right = (int)(scale * crop_w); + int src_h_idx, src_w_idx, stride; + scale = 1.0 / scale; + centroid_h = scale * (float)(h + 0.5); + centroid_w = scale * (float)(w + 0.5); + src_h_idx = lroundf(centroid_h) - 1; + src_w_idx = lroundf(centroid_w) - 1; + src_h_idx = (src_h_idx < 0) ? 0 : src_h_idx; + src_h_idx = (src_h_idx >= (crop_h - 1)) ? crop_h - 2 : src_h_idx; + src_w_idx = (src_w_idx < 0) ? 0 : src_w_idx; + src_w_idx = (src_w_idx >= (crop_w - 1)) ? crop_w - 2 : src_w_idx; + // Unroll + stride = src_w * C; + src_w_idx += crop_x; + src_h_idx += crop_y; + for (c = 0; c < C; c++) { + float rs; + int dst_index; + // NHWC + f00 = src_h_idx * stride + src_w_idx * C + c; + f01 = src_h_idx * stride + (src_w_idx + 1) * C + c; + f10 = (src_h_idx + 1) * stride + src_w_idx * C + c; + f11 = (src_h_idx + 1) * stride + (src_w_idx + 1) * C + c; + rs = lroundf(lerp2d( + (int)src_img[f00], (int)src_img[f01], (int)src_img[f10], (int)src_img[f11], centroid_h, + centroid_w)); + // NCHW + dst_index = w + (W * h) + (W * H * c) + b * (W * H * C); + dst_img[dst_index] = (float)rs; + dst_img[dst_index] = (h >= letter_bot) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] = (w >= letter_right) ? 114.0 : dst_img[dst_index]; + dst_img[dst_index] *= norm; + } + } +} + +void multi_scale_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + float * dst, unsigned char * src, int d_w, int d_h, int d_c, Roi * d_roi, int s_w, int s_h, + int s_c, int batch, float norm, cudaStream_t stream) +{ + int N = d_w * d_h; + multi_scale_resize_bilinear_letterbox_nhwc_to_nchw32_batch_kernel<<< + cuda_gridsize(N), block, 0, stream>>>(N, dst, src, d_h, d_w, s_h, s_w, d_roi, norm, batch); +} + } // namespace tensorrt_yolox diff --git a/perception/tensorrt_yolox/src/tensorrt_yolox.cpp b/perception/tensorrt_yolox/src/tensorrt_yolox.cpp index 0950f46f30b43..32d905eed2870 100644 --- a/perception/tensorrt_yolox/src/tensorrt_yolox.cpp +++ b/perception/tensorrt_yolox/src/tensorrt_yolox.cpp @@ -46,7 +46,7 @@ std::string trim(std::string & s) return s; } -bool existFile(const std::string & file_name, bool verbose) +bool fileExists(const std::string & file_name, bool verbose) { if (!std::experimental::filesystem::exists(std::experimental::filesystem::path(file_name))) { if (verbose) { @@ -59,7 +59,7 @@ bool existFile(const std::string & file_name, bool verbose) std::vector loadListFromTextFile(const std::string & filename) { - assert(existFile(filename, true)); + assert(fileExists(filename, true)); std::vector list; std::ifstream f(filename); @@ -84,11 +84,11 @@ std::vector loadImageList(const std::string & filename, const std:: { std::vector fileList = loadListFromTextFile(filename); for (auto & file : fileList) { - if (existFile(file, false)) { + if (fileExists(file, false)) { continue; } else { std::string prefixed = prefix + file; - if (existFile(prefixed, false)) + if (fileExists(prefixed, false)) file = prefixed; else std::cerr << "WARNING: couldn't find: " << prefixed << " while loading: " << filename @@ -111,6 +111,7 @@ TrtYoloX::TrtYoloX( src_width_ = -1; src_height_ = -1; norm_factor_ = norm_factor; + batch_size_ = batch_config[2]; if (precision == "int8") { if (build_config.clip_value <= 0.0) { if (calibration_image_list_path.empty()) { @@ -123,7 +124,7 @@ TrtYoloX::TrtYoloX( calibration_image_list_path = ""; } - int max_batch_size = 1; + int max_batch_size = batch_size_; nvinfer1::Dims input_dims = tensorrt_common::get_input_dims(model_path); std::vector calibration_images; if (calibration_image_list_path != "") { @@ -209,6 +210,7 @@ TrtYoloX::TrtYoloX( input_d_ = cuda_utils::make_unique(batch_config[2] * input_size); out_elem_num_ = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); + out_elem_num_ = out_elem_num_ * batch_config[2]; out_elem_num_per_batch_ = static_cast(out_elem_num_ / batch_config[2]); out_prob_d_ = cuda_utils::make_unique(out_elem_num_); out_prob_h_ = cuda_utils::make_unique_host(out_elem_num_, cudaHostAllocPortable); @@ -241,6 +243,18 @@ TrtYoloX::TrtYoloX( } } +TrtYoloX::~TrtYoloX() +{ + if (use_gpu_preprocess_) { + if (image_buf_h_) { + image_buf_h_.reset(); + } + if (image_buf_d_) { + image_buf_d_.reset(); + } + } +} + void TrtYoloX::initPreprocessBuffer(int width, int height) { // if size of source input has been changed... @@ -259,6 +273,12 @@ void TrtYoloX::initPreprocessBuffer(int width, int height) src_height_ = height; if (use_gpu_preprocess_) { auto input_dims = trt_common_->getBindingDimensions(0); + bool const hasRuntimeDim = std::any_of( + input_dims.d, input_dims.d + input_dims.nbDims, + [](int32_t input_dim) { return input_dim == -1; }); + if (hasRuntimeDim) { + input_dims.d[0] = batch_size_; + } if (!image_buf_h_) { trt_common_->setBindingDimensions(0, input_dims); scales_.clear(); @@ -267,10 +287,12 @@ void TrtYoloX::initPreprocessBuffer(int width, int height) const float input_width = static_cast(input_dims.d[3]); if (!image_buf_h_) { const float scale = std::min(input_width / width, input_height / height); - scales_.emplace_back(scale); + for (int b = 0; b < batch_size_; b++) { + scales_.emplace_back(scale); + } image_buf_h_ = cuda_utils::make_unique_host( - width * height * 3, cudaHostAllocWriteCombined); - image_buf_d_ = cuda_utils::make_unique(width * height * 3); + width * height * 3 * batch_size_, cudaHostAllocWriteCombined); + image_buf_d_ = cuda_utils::make_unique(width * height * 3 * batch_size_); } } } @@ -283,9 +305,8 @@ void TrtYoloX::printProfiling(void) void TrtYoloX::preprocessGpu(const std::vector & images) { const auto batch_size = images.size(); - // Currently only supports single batch in cuda preprocessing - assert(batch_size == 1); auto input_dims = trt_common_->getBindingDimensions(0); + input_dims.d[0] = batch_size; for (const auto & image : images) { // if size of source input has been changed... @@ -311,25 +332,32 @@ void TrtYoloX::preprocessGpu(const std::vector & images) } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); + int b = 0; for (const auto & image : images) { if (!image_buf_h_) { const float scale = std::min(input_width / image.cols, input_height / image.rows); scales_.emplace_back(scale); image_buf_h_ = cuda_utils::make_unique_host( - image.cols * image.rows * 3, cudaHostAllocWriteCombined); - image_buf_d_ = cuda_utils::make_unique(image.cols * image.rows * 3); + image.cols * image.rows * 3 * batch_size, cudaHostAllocWriteCombined); + image_buf_d_ = + cuda_utils::make_unique(image.cols * image.rows * 3 * batch_size); } + int index = b * image.cols * image.rows * 3; // Copy into pinned memory - memcpy(image_buf_h_.get(), &image.data[0], image.cols * image.rows * 3 * sizeof(unsigned char)); - // Copy into device memory - CHECK_CUDA_ERROR(cudaMemcpyAsync( - image_buf_d_.get(), image_buf_h_.get(), image.cols * image.rows * 3 * sizeof(unsigned char), - cudaMemcpyHostToDevice, *stream_)); - // Preprocess on GPU - resize_bilinear_letterbox_nhwc_to_nchw32_gpu( - input_d_.get(), image_buf_d_.get(), input_width, input_height, 3, image.cols, image.rows, 3, - static_cast(norm_factor_), *stream_); + memcpy( + image_buf_h_.get() + index, &image.data[0], + image.cols * image.rows * 3 * sizeof(unsigned char)); + b++; } + // Copy into device memory + CHECK_CUDA_ERROR(cudaMemcpyAsync( + image_buf_d_.get(), image_buf_h_.get(), + images[0].cols * images[0].rows * 3 * batch_size * sizeof(unsigned char), + cudaMemcpyHostToDevice, *stream_)); + // Preprocess on GPU + resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + input_d_.get(), image_buf_d_.get(), input_width, input_height, 3, images[0].cols, + images[0].rows, 3, batch_size, static_cast(norm_factor_), *stream_); } void TrtYoloX::preprocess(const std::vector & images) @@ -375,6 +403,7 @@ void TrtYoloX::preprocess(const std::vector & images) input_h_ = chw_images.isContinuous() ? flat : flat.clone(); CHECK_CUDA_ERROR(cudaMemcpy( input_d_.get(), input_h_.data(), input_h_.size() * sizeof(float), cudaMemcpyHostToDevice)); + // No Need for Sync } bool TrtYoloX::doInference(const std::vector & images, ObjectArrays & objects) @@ -396,6 +425,275 @@ bool TrtYoloX::doInference(const std::vector & images, ObjectArrays & o } } +void TrtYoloX::preprocessWithRoiGpu( + const std::vector & images, const std::vector & rois) +{ + const auto batch_size = images.size(); + auto input_dims = trt_common_->getBindingDimensions(0); + + input_dims.d[0] = batch_size; + for (const auto & image : images) { + // if size of source input has benn changed... + int width = image.cols; + int height = image.rows; + if (src_width_ != -1 || src_height_ != -1) { + if (width != src_width_ || height != src_height_) { + // Free cuda memory to reallocate + if (image_buf_h_) { + image_buf_h_.reset(); + } + if (image_buf_d_) { + image_buf_d_.reset(); + } + } + } + src_width_ = width; + src_height_ = height; + } + if (!image_buf_h_) { + trt_common_->setBindingDimensions(0, input_dims); + } + const float input_height = static_cast(input_dims.d[2]); + const float input_width = static_cast(input_dims.d[3]); + int b = 0; + scales_.clear(); + + if (!roi_h_) { + roi_h_ = cuda_utils::make_unique_host(batch_size, cudaHostAllocWriteCombined); + roi_d_ = cuda_utils::make_unique(batch_size); + } + + for (const auto & image : images) { + const float scale = std::min( + input_width / static_cast(rois[b].width), + input_height / static_cast(rois[b].height)); + scales_.emplace_back(scale); + if (!image_buf_h_) { + image_buf_h_ = cuda_utils::make_unique_host( + image.cols * image.rows * 3 * batch_size, cudaHostAllocWriteCombined); + image_buf_d_ = + cuda_utils::make_unique(image.cols * image.rows * 3 * batch_size); + } + int index = b * image.cols * image.rows * 3; + // Copy into pinned memory + // memcpy(&(m_h_img[index]), &image.data[0], image.cols * image.rows * 3 * sizeof(unsigned + // char)); + memcpy( + image_buf_h_.get() + index, &image.data[0], + image.cols * image.rows * 3 * sizeof(unsigned char)); + roi_h_[b].x = rois[b].x; + roi_h_[b].y = rois[b].y; + roi_h_[b].w = rois[b].width; + roi_h_[b].h = rois[b].height; + b++; + } + // Copy into device memory + CHECK_CUDA_ERROR(cudaMemcpyAsync( + image_buf_d_.get(), image_buf_h_.get(), + images[0].cols * images[0].rows * 3 * batch_size * sizeof(unsigned char), + cudaMemcpyHostToDevice, *stream_)); + CHECK_CUDA_ERROR(cudaMemcpyAsync( + roi_d_.get(), roi_h_.get(), batch_size * sizeof(Roi), cudaMemcpyHostToDevice, *stream_)); + crop_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + input_d_.get(), image_buf_d_.get(), input_width, input_height, 3, roi_d_.get(), images[0].cols, + images[0].rows, 3, batch_size, static_cast(norm_factor_), *stream_); +} + +void TrtYoloX::preprocessWithRoi( + const std::vector & images, const std::vector & rois) +{ + const auto batch_size = images.size(); + auto input_dims = trt_common_->getBindingDimensions(0); + input_dims.d[0] = batch_size; + trt_common_->setBindingDimensions(0, input_dims); + const float input_height = static_cast(input_dims.d[2]); + const float input_width = static_cast(input_dims.d[3]); + std::vector dst_images; + scales_.clear(); + bool letterbox = true; + int b = 0; + if (letterbox) { + for (const auto & image : images) { + cv::Mat dst_image; + cv::Mat cropped = image(rois[b]); + const float scale = std::min( + input_width / static_cast(rois[b].width), + input_height / static_cast(rois[b].height)); + scales_.emplace_back(scale); + const auto scale_size = cv::Size(rois[b].width * scale, rois[b].height * scale); + cv::resize(cropped, dst_image, scale_size, 0, 0, cv::INTER_CUBIC); + const auto bottom = input_height - dst_image.rows; + const auto right = input_width - dst_image.cols; + copyMakeBorder( + dst_image, dst_image, 0, bottom, 0, right, cv::BORDER_CONSTANT, {114, 114, 114}); + dst_images.emplace_back(dst_image); + b++; + } + } else { + for (const auto & image : images) { + cv::Mat dst_image; + const float scale = -1.0; + scales_.emplace_back(scale); + const auto scale_size = cv::Size(input_width, input_height); + cv::resize(image, dst_image, scale_size, 0, 0, cv::INTER_CUBIC); + dst_images.emplace_back(dst_image); + } + } + const auto chw_images = cv::dnn::blobFromImages( + dst_images, norm_factor_, cv::Size(), cv::Scalar(), false, false, CV_32F); + + const auto data_length = chw_images.total(); + input_h_.reserve(data_length); + const auto flat = chw_images.reshape(1, data_length); + input_h_ = chw_images.isContinuous() ? flat : flat.clone(); + CHECK_CUDA_ERROR(cudaMemcpy( + input_d_.get(), input_h_.data(), input_h_.size() * sizeof(float), cudaMemcpyHostToDevice)); + // No Need for Sync +} + +void TrtYoloX::multiScalepreprocessGpu(const cv::Mat & image, const std::vector & rois) +{ + const auto batch_size = rois.size(); + auto input_dims = trt_common_->getBindingDimensions(0); + + input_dims.d[0] = batch_size; + + // if size of source input has benn changed... + int width = image.cols; + int height = image.rows; + if (src_width_ != -1 || src_height_ != -1) { + if (width != src_width_ || height != src_height_) { + // Free cuda memory to reallocate + if (image_buf_h_) { + image_buf_h_.reset(); + } + if (image_buf_d_) { + image_buf_d_.reset(); + } + } + } + src_width_ = width; + src_height_ = height; + + if (!image_buf_h_) { + trt_common_->setBindingDimensions(0, input_dims); + } + const float input_height = static_cast(input_dims.d[2]); + const float input_width = static_cast(input_dims.d[3]); + + scales_.clear(); + + if (!roi_h_) { + roi_h_ = cuda_utils::make_unique_host(batch_size, cudaHostAllocWriteCombined); + roi_d_ = cuda_utils::make_unique(batch_size); + } + + for (size_t b = 0; b < rois.size(); b++) { + const float scale = std::min( + input_width / static_cast(rois[b].width), + input_height / static_cast(rois[b].height)); + scales_.emplace_back(scale); + roi_h_[b].x = rois[b].x; + roi_h_[b].y = rois[b].y; + roi_h_[b].w = rois[b].width; + roi_h_[b].h = rois[b].height; + } + if (!image_buf_h_) { + image_buf_h_ = cuda_utils::make_unique_host( + image.cols * image.rows * 3 * 1, cudaHostAllocWriteCombined); + image_buf_d_ = cuda_utils::make_unique(image.cols * image.rows * 3 * 1); + } + int index = 0 * image.cols * image.rows * 3; + // Copy into pinned memory + memcpy( + image_buf_h_.get() + index, &image.data[0], + image.cols * image.rows * 3 * sizeof(unsigned char)); + + // Copy into device memory + CHECK_CUDA_ERROR(cudaMemcpyAsync( + image_buf_d_.get(), image_buf_h_.get(), image.cols * image.rows * 3 * 1 * sizeof(unsigned char), + cudaMemcpyHostToDevice, *stream_)); + CHECK_CUDA_ERROR(cudaMemcpyAsync( + roi_d_.get(), roi_h_.get(), batch_size * sizeof(Roi), cudaMemcpyHostToDevice, *stream_)); + multi_scale_resize_bilinear_letterbox_nhwc_to_nchw32_batch_gpu( + input_d_.get(), image_buf_d_.get(), input_width, input_height, 3, roi_d_.get(), image.cols, + image.rows, 3, batch_size, static_cast(norm_factor_), *stream_); +} + +void TrtYoloX::multiScalePreprocess(const cv::Mat & image, const std::vector & rois) +{ + const auto batch_size = rois.size(); + auto input_dims = trt_common_->getBindingDimensions(0); + input_dims.d[0] = batch_size; + trt_common_->setBindingDimensions(0, input_dims); + const float input_height = static_cast(input_dims.d[2]); + const float input_width = static_cast(input_dims.d[3]); + std::vector dst_images; + scales_.clear(); + + for (const auto & roi : rois) { + cv::Mat dst_image; + cv::Mat cropped = image(roi); + const float scale = std::min( + input_width / static_cast(roi.width), input_height / static_cast(roi.height)); + scales_.emplace_back(scale); + const auto scale_size = cv::Size(roi.width * scale, roi.height * scale); + cv::resize(cropped, dst_image, scale_size, 0, 0, cv::INTER_CUBIC); + const auto bottom = input_height - dst_image.rows; + const auto right = input_width - dst_image.cols; + copyMakeBorder(dst_image, dst_image, 0, bottom, 0, right, cv::BORDER_CONSTANT, {114, 114, 114}); + dst_images.emplace_back(dst_image); + } + const auto chw_images = cv::dnn::blobFromImages( + dst_images, norm_factor_, cv::Size(), cv::Scalar(), false, false, CV_32F); + + const auto data_length = chw_images.total(); + input_h_.reserve(data_length); + const auto flat = chw_images.reshape(1, data_length); + input_h_ = chw_images.isContinuous() ? flat : flat.clone(); + CHECK_CUDA_ERROR(cudaMemcpy( + input_d_.get(), input_h_.data(), input_h_.size() * sizeof(float), cudaMemcpyHostToDevice)); + // No Need for Sync +} + +bool TrtYoloX::doInferenceWithRoi( + const std::vector & images, ObjectArrays & objects, const std::vector & rois) +{ + if (!trt_common_->isInitialized()) { + return false; + } + if (use_gpu_preprocess_) { + preprocessWithRoiGpu(images, rois); + } else { + preprocessWithRoi(images, rois); + } + + if (needs_output_decode_) { + return feedforwardAndDecode(images, objects); + } else { + return feedforward(images, objects); + } +} + +bool TrtYoloX::doMultiScaleInference( + const cv::Mat & image, ObjectArrays & objects, const std::vector & rois) +{ + std::vector images; + if (!trt_common_->isInitialized()) { + return false; + } + if (use_gpu_preprocess_) { + multiScalepreprocessGpu(image, rois); + } else { + multiScalePreprocess(image, rois); + } + if (needs_output_decode_) { + return multiScaleFeedforwardAndDecode(image, rois.size(), objects); + } else { + return multiScaleFeedforward(image, rois.size(), objects); + } +} + // This method is assumed to be called when specified YOLOX model contains // EfficientNMS_TRT module. bool TrtYoloX::feedforward(const std::vector & images, ObjectArrays & objects) @@ -473,6 +771,80 @@ bool TrtYoloX::feedforwardAndDecode(const std::vector & images, ObjectA return true; } +// This method is assumed to be called when specified YOLOX model contains +// EfficientNMS_TRT module. +bool TrtYoloX::multiScaleFeedforward(const cv::Mat & image, int batch_size, ObjectArrays & objects) +{ + std::vector buffers = { + input_d_.get(), out_num_detections_d_.get(), out_boxes_d_.get(), out_scores_d_.get(), + out_classes_d_.get()}; + + trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + + auto out_num_detections = std::make_unique(batch_size); + auto out_boxes = std::make_unique(4 * batch_size * max_detections_); + auto out_scores = std::make_unique(batch_size * max_detections_); + auto out_classes = std::make_unique(batch_size * max_detections_); + + CHECK_CUDA_ERROR(cudaMemcpyAsync( + out_num_detections.get(), out_num_detections_d_.get(), sizeof(int32_t) * batch_size, + cudaMemcpyDeviceToHost, *stream_)); + CHECK_CUDA_ERROR(cudaMemcpyAsync( + out_boxes.get(), out_boxes_d_.get(), sizeof(float) * 4 * batch_size * max_detections_, + cudaMemcpyDeviceToHost, *stream_)); + CHECK_CUDA_ERROR(cudaMemcpyAsync( + out_scores.get(), out_scores_d_.get(), sizeof(float) * batch_size * max_detections_, + cudaMemcpyDeviceToHost, *stream_)); + CHECK_CUDA_ERROR(cudaMemcpyAsync( + out_classes.get(), out_classes_d_.get(), sizeof(int32_t) * batch_size * max_detections_, + cudaMemcpyDeviceToHost, *stream_)); + cudaStreamSynchronize(*stream_); + + objects.clear(); + for (int i = 0; i < batch_size; ++i) { + const size_t num_detection = static_cast(out_num_detections[i]); + ObjectArray object_array(num_detection); + for (size_t j = 0; j < num_detection; ++j) { + Object object{}; + const auto x1 = out_boxes[i * max_detections_ * 4 + j * 4] / scales_[i]; + const auto y1 = out_boxes[i * max_detections_ * 4 + j * 4 + 1] / scales_[i]; + const auto x2 = out_boxes[i * max_detections_ * 4 + j * 4 + 2] / scales_[i]; + const auto y2 = out_boxes[i * max_detections_ * 4 + j * 4 + 3] / scales_[i]; + object.x_offset = std::clamp(0, static_cast(x1), image.cols); + object.y_offset = std::clamp(0, static_cast(y1), image.rows); + object.width = static_cast(std::max(0.0F, x2 - x1)); + object.height = static_cast(std::max(0.0F, y2 - y1)); + object.score = out_scores[i * max_detections_ + j]; + object.type = out_classes[i * max_detections_ + j]; + object_array.emplace_back(object); + } + objects.emplace_back(object_array); + } + return true; +} + +bool TrtYoloX::multiScaleFeedforwardAndDecode( + const cv::Mat & image, int batch_size, ObjectArrays & objects) +{ + std::vector buffers = {input_d_.get(), out_prob_d_.get()}; + trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + + CHECK_CUDA_ERROR(cudaMemcpyAsync( + out_prob_h_.get(), out_prob_d_.get(), sizeof(float) * out_elem_num_, cudaMemcpyDeviceToHost, + *stream_)); + cudaStreamSynchronize(*stream_); + objects.clear(); + + for (int i = 0; i < batch_size; ++i) { + auto image_size = image.size(); + float * batch_prob = out_prob_h_.get() + (i * out_elem_num_per_batch_); + ObjectArray object_array; + decodeOutputs(batch_prob, object_array, scales_[i], image_size); + objects.emplace_back(object_array); + } + return true; +} + void TrtYoloX::decodeOutputs( float * prob, ObjectArray & objects, float scale, cv::Size & img_size) const { diff --git a/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp b/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp index e450ba6b5817e..ec0541a52f32c 100644 --- a/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp +++ b/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2022 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. diff --git a/perception/traffic_light_classifier/CMakeLists.txt b/perception/traffic_light_classifier/CMakeLists.txt index aeea36ecde047..c4b62a932dcfd 100644 --- a/perception/traffic_light_classifier/CMakeLists.txt +++ b/perception/traffic_light_classifier/CMakeLists.txt @@ -66,6 +66,14 @@ else() endif() # Download caffemodel and prototxt +set(EFFICIENTNET_BATCH_1_HASH 82baba4fcf1abe0c040cd55005e34510) +set(EFFICIENTNET_BATCH_4_HASH 21b549c2fe4fbb20d32cc019e6d70cd7) +set(EFFICIENTNET_BATCH_6_HASH 28b408710bcb24f4cdd4d746301d4e78) +set(MOBILENET_BATCH_1_HASH caa51f2080aa2df943e4f884c41898eb) +set(MOBILENET_BATCH_4_HASH c2beaf60210f471debfe72b86d076ca0) +set(MOBILENET_BATCH_6_HASH 47255a11bde479320d703f1f45db1242) +set(LAMP_LABEL_HASH e9f45efb02f2a9aa8ac27b3d5c164905) +set(AWS_DIR https://awf.ml.dev.web.auto/perception/models/traffic_light_classifier/v2) set(DATA_PATH "${CMAKE_CURRENT_SOURCE_DIR}/data") if(NOT EXISTS "${DATA_PATH}") execute_process(COMMAND mkdir -p ${DATA_PATH}) @@ -84,14 +92,14 @@ function(download FILE_NAME FILE_HASH) else() message(STATUS "diff ${FILE_NAME}") message(STATUS "File hash changes. Downloading now ...") - file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/traffic_light_classifier/v1/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) + file(DOWNLOAD ${AWS_DIR}/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) list(GET DOWNLOAD_STATUS 0 STATUS_CODE) list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) endif() else() message(STATUS "not found ${FILE_NAME}") message(STATUS "File doesn't exists. Downloading now ...") - file(DOWNLOAD https://awf.ml.dev.web.auto/perception/models/traffic_light_classifier/v1/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) + file(DOWNLOAD ${AWS_DIR}/${FILE_NAME} ${FILE_PATH} STATUS DOWNLOAD_STATUS TIMEOUT 300) list(GET DOWNLOAD_STATUS 0 STATUS_CODE) list(GET DOWNLOAD_STATUS 1 ERROR_MESSAGE) endif() @@ -101,8 +109,12 @@ function(download FILE_NAME FILE_HASH) message(FATAL_ERROR "Error occurred during download: ${ERROR_MESSAGE}") endif() endfunction() -download(traffic_light_classifier_mobilenetv2.onnx caa51f2080aa2df943e4f884c41898eb) -download(traffic_light_classifier_efficientNet_b1.onnx 82baba4fcf1abe0c040cd55005e34510) +download(traffic_light_classifier_mobilenetv2_batch_1.onnx ${MOBILENET_BATCH_1_HASH}) +download(traffic_light_classifier_mobilenetv2_batch_4.onnx ${MOBILENET_BATCH_4_HASH}) +download(traffic_light_classifier_mobilenetv2_batch_6.onnx ${MOBILENET_BATCH_6_HASH}) +download(traffic_light_classifier_efficientNet_b1_batch_1.onnx ${EFFICIENTNET_BATCH_1_HASH}) +download(traffic_light_classifier_efficientNet_b1_batch_4.onnx ${EFFICIENTNET_BATCH_4_HASH}) +download(traffic_light_classifier_efficientNet_b1_batch_6.onnx ${EFFICIENTNET_BATCH_6_HASH}) download(lamp_labels.txt 4b2cf910d97d05d464e7c26901af3d4c) find_package(ament_cmake_auto REQUIRED) diff --git a/perception/traffic_light_classifier/include/traffic_light_classifier/classifier_interface.hpp b/perception/traffic_light_classifier/include/traffic_light_classifier/classifier_interface.hpp index c042f00e1a1ad..f4859af88d80d 100644 --- a/perception/traffic_light_classifier/include/traffic_light_classifier/classifier_interface.hpp +++ b/perception/traffic_light_classifier/include/traffic_light_classifier/classifier_interface.hpp @@ -18,7 +18,7 @@ #include #include -#include +#include #include @@ -27,8 +27,9 @@ namespace traffic_light class ClassifierInterface { public: - virtual bool getTrafficSignal( - const cv::Mat & input_image, tier4_perception_msgs::msg::TrafficSignal & traffic_signal) = 0; + virtual bool getTrafficSignals( + const std::vector & input_image, + tier4_perception_msgs::msg::TrafficSignalArray & traffic_signals) = 0; }; } // namespace traffic_light diff --git a/perception/traffic_light_classifier/include/traffic_light_classifier/cnn_classifier.hpp b/perception/traffic_light_classifier/include/traffic_light_classifier/cnn_classifier.hpp index b1c19526561b9..4f304dcb96970 100644 --- a/perception/traffic_light_classifier/include/traffic_light_classifier/cnn_classifier.hpp +++ b/perception/traffic_light_classifier/include/traffic_light_classifier/cnn_classifier.hpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include @@ -54,19 +55,14 @@ class CNNClassifier : public ClassifierInterface explicit CNNClassifier(rclcpp::Node * node_ptr); virtual ~CNNClassifier() = default; - bool getTrafficSignal( - const cv::Mat & input_image, - tier4_perception_msgs::msg::TrafficSignal & traffic_signal) override; + bool getTrafficSignals( + const std::vector & images, + tier4_perception_msgs::msg::TrafficSignalArray & traffic_signals) override; private: - void preProcess(cv::Mat & image, std::vector & tensor, bool normalize = true); - bool postProcess( - std::vector & output_data_host, - tier4_perception_msgs::msg::TrafficSignal & traffic_signal, bool apply_softmax = false); + void postProcess(int cls, float prob, tier4_perception_msgs::msg::TrafficSignal & traffic_signal); bool readLabelfile(std::string filepath, std::vector & labels); bool isColorLabel(const std::string label); - void calcSoftmax(std::vector & data, std::vector & probs, int num_output); - std::vector argsort(std::vector & tensor, int num_output); void outputDebugImage( cv::Mat & debug_image, const tier4_perception_msgs::msg::TrafficSignal & traffic_signal); @@ -114,20 +110,12 @@ class CNNClassifier : public ClassifierInterface }; rclcpp::Node * node_ptr_; - - std::unique_ptr trt_common_; - StreamUniquePtr stream_{makeCudaStream()}; + int batch_size_; + std::unique_ptr classifier_; image_transport::Publisher image_pub_; std::vector labels_; - std::vector mean_; - std::vector std_; - int batch_size_; - int input_c_; - int input_h_; - int input_w_; - int num_input_; - int num_output_; - bool apply_softmax_; + std::vector mean_; + std::vector std_; }; } // namespace traffic_light diff --git a/perception/traffic_light_classifier/include/traffic_light_classifier/color_classifier.hpp b/perception/traffic_light_classifier/include/traffic_light_classifier/color_classifier.hpp index 371e740b90ff3..9f0d97ba29cfd 100644 --- a/perception/traffic_light_classifier/include/traffic_light_classifier/color_classifier.hpp +++ b/perception/traffic_light_classifier/include/traffic_light_classifier/color_classifier.hpp @@ -22,7 +22,7 @@ #include #include -#include +#include #if __has_include() #include @@ -62,9 +62,9 @@ class ColorClassifier : public ClassifierInterface explicit ColorClassifier(rclcpp::Node * node_ptr); virtual ~ColorClassifier() = default; - bool getTrafficSignal( - const cv::Mat & input_image, - tier4_perception_msgs::msg::TrafficSignal & traffic_signal) override; + bool getTrafficSignals( + const std::vector & images, + tier4_perception_msgs::msg::TrafficSignalArray & traffic_signals) override; private: bool filterHSV( diff --git a/perception/traffic_light_classifier/package.xml b/perception/traffic_light_classifier/package.xml index 89129cf0fe9d4..ef04aae7ee3cb 100644 --- a/perception/traffic_light_classifier/package.xml +++ b/perception/traffic_light_classifier/package.xml @@ -21,6 +21,7 @@ rclcpp rclcpp_components sensor_msgs + tensorrt_classifier tensorrt_common tier4_perception_msgs diff --git a/perception/traffic_light_classifier/src/cnn_classifier.cpp b/perception/traffic_light_classifier/src/cnn_classifier.cpp index 45ef5f94af146..323b90ee1ce61 100644 --- a/perception/traffic_light_classifier/src/cnn_classifier.cpp +++ b/perception/traffic_light_classifier/src/cnn_classifier.cpp @@ -36,82 +36,72 @@ CNNClassifier::CNNClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr) precision = node_ptr_->declare_parameter("classifier_precision", "fp16"); label_file_path = node_ptr_->declare_parameter("classifier_label_path", "labels.txt"); model_file_path = node_ptr_->declare_parameter("classifier_model_path", "model.onnx"); - apply_softmax_ = node_ptr_->declare_parameter("apply_softmax", false); - mean_ = + // ros param does not support loading std::vector + // we have to load std::vector and transfer to std::vector + auto mean_d = node_ptr->declare_parameter("classifier_mean", std::vector{123.675, 116.28, 103.53}); - std_ = node_ptr->declare_parameter("classifier_std", std::vector{58.395, 57.12, 57.375}); + auto std_d = + node_ptr->declare_parameter("classifier_std", std::vector{58.395, 57.12, 57.375}); + mean_ = std::vector(mean_d.begin(), mean_d.end()); + std_ = std::vector(std_d.begin(), std_d.end()); if (mean_.size() != 3 || std_.size() != 3) { RCLCPP_ERROR(node_ptr->get_logger(), "classifier_mean and classifier_std must be of size 3"); return; } readLabelfile(label_file_path, labels_); + nvinfer1::Dims input_dim = tensorrt_common::get_input_dims(model_file_path); + assert(input_dim.d[0] > 0); + batch_size_ = input_dim.d[0]; - tensorrt_common::BatchConfig batch_config{1, 1, 1}; - size_t max_workspace_size = 1 << 30; - - trt_common_ = std::make_unique( - model_file_path, precision, nullptr, batch_config, max_workspace_size); - trt_common_->setup(); - if (!trt_common_->isInitialized()) { - return; - } - const auto input_dims = trt_common_->getBindingDimensions(0); - if (input_dims.nbDims != 4) { - RCLCPP_ERROR(node_ptr_->get_logger(), "Model input dimension must be 4!"); - } - batch_size_ = input_dims.d[0]; - input_c_ = input_dims.d[1]; - input_h_ = input_dims.d[2]; - input_w_ = input_dims.d[3]; - num_input_ = batch_size_ * input_c_ * input_h_ * input_w_; - const auto output_dims = trt_common_->getBindingDimensions(1); - num_output_ = - std::accumulate(output_dims.d, output_dims.d + output_dims.nbDims, 1, std::multiplies()); + tensorrt_common::BatchConfig batch_config{batch_size_, batch_size_, batch_size_}; + classifier_ = std::make_unique( + model_file_path, precision, batch_config, mean_, std_); if (node_ptr_->declare_parameter("build_only", false)) { RCLCPP_INFO(node_ptr_->get_logger(), "TensorRT engine is built and shutdown node."); rclcpp::shutdown(); } } -bool CNNClassifier::getTrafficSignal( - const cv::Mat & input_image, tier4_perception_msgs::msg::TrafficSignal & traffic_signal) +bool CNNClassifier::getTrafficSignals( + const std::vector & images, + tier4_perception_msgs::msg::TrafficSignalArray & traffic_signals) { - if (!trt_common_->isInitialized()) { - RCLCPP_WARN(node_ptr_->get_logger(), "failed to init tensorrt"); + if (images.size() != traffic_signals.signals.size()) { + RCLCPP_WARN(node_ptr_->get_logger(), "image number should be equal to traffic signal number!"); return false; } - - std::vector input_data_host(num_input_); - - cv::Mat image = input_image.clone(); - preProcess(image, input_data_host, true); - - auto input_data_device = cuda_utils::make_unique(num_input_); - cudaMemcpy( - input_data_device.get(), input_data_host.data(), num_input_ * sizeof(float), - cudaMemcpyHostToDevice); - - auto output_data_device = cuda_utils::make_unique(num_output_); - - // do inference - std::vector bindings = {input_data_device.get(), output_data_device.get()}; - - trt_common_->enqueueV2(bindings.data(), *stream_, nullptr); - - std::vector output_data_host(num_output_); - cudaMemcpy( - output_data_host.data(), output_data_device.get(), num_output_ * sizeof(float), - cudaMemcpyDeviceToHost); - - postProcess(output_data_host, traffic_signal, apply_softmax_); - - /* debug */ - if (0 < image_pub_.getNumSubscribers()) { - cv::Mat debug_image = input_image.clone(); - outputDebugImage(debug_image, traffic_signal); + std::vector image_batch; + int signal_i = 0; + + for (size_t image_i = 0; image_i < images.size(); image_i++) { + image_batch.emplace_back(images[image_i]); + // keep the actual batch size + size_t true_batch_size = image_batch.size(); + // insert fake image since the TRT model requires static batch size + if (image_i + 1 == images.size()) { + while (static_cast(image_batch.size()) < batch_size_) { + image_batch.emplace_back(image_batch.front()); + } + } + if (static_cast(image_batch.size()) == batch_size_) { + std::vector probs; + std::vector classes; + bool res = classifier_->doInference(image_batch, classes, probs); + if (!res || classes.empty() || probs.empty()) { + return false; + } + for (size_t i = 0; i < true_batch_size; i++) { + postProcess(classes[i], probs[i], traffic_signals.signals[signal_i]); + /* debug */ + if (0 < image_pub_.getNumSubscribers()) { + outputDebugImage(image_batch[i], traffic_signals.signals[signal_i]); + } + signal_i++; + } + image_batch.clear(); + } } - return true; } @@ -147,49 +137,10 @@ void CNNClassifier::outputDebugImage( image_pub_.publish(debug_image_msg); } -void CNNClassifier::preProcess(cv::Mat & image, std::vector & input_tensor, bool normalize) -{ - const float scale = - std::min(static_cast(input_w_) / image.cols, static_cast(input_h_) / image.rows); - const auto scale_size = cv::Size(image.cols * scale, image.rows * scale); - cv::resize(image, image, scale_size, 0, 0, cv::INTER_CUBIC); - const auto bottom = input_h_ - image.rows; - const auto right = input_w_ - image.cols; - copyMakeBorder(image, image, 0, bottom, 0, right, cv::BORDER_CONSTANT, {0, 0, 0}); - - const size_t strides_cv[3] = { - static_cast(input_w_ * input_c_), static_cast(input_c_), 1}; - const size_t strides[3] = { - static_cast(input_h_ * input_w_), static_cast(input_w_), 1}; - - for (int i = 0; i < input_h_; i++) { - for (int j = 0; j < input_w_; j++) { - for (int k = 0; k < input_c_; k++) { - const size_t offset_cv = i * strides_cv[0] + j * strides_cv[1] + k * strides_cv[2]; - const size_t offset = k * strides[0] + i * strides[1] + j * strides[2]; - if (normalize) { - input_tensor[offset] = (static_cast(image.data[offset_cv]) - mean_[k]) / std_[k]; - } else { - input_tensor[offset] = static_cast(image.data[offset_cv]); - } - } - } - } -} - -bool CNNClassifier::postProcess( - std::vector & output_tensor, tier4_perception_msgs::msg::TrafficSignal & traffic_signal, - bool apply_softmax) +void CNNClassifier::postProcess( + int class_index, float prob, tier4_perception_msgs::msg::TrafficSignal & traffic_signal) { - std::vector probs; - if (apply_softmax) { - calcSoftmax(output_tensor, probs, num_output_); - } - std::vector sorted_indices = argsort(output_tensor, num_output_); - - size_t max_indice = sorted_indices.front(); - std::string match_label = labels_[max_indice]; - float probability = apply_softmax ? probs[max_indice] : output_tensor[max_indice]; + std::string match_label = labels_[class_index]; // label names are assumed to be comma-separated to represent each lamp // e.g. @@ -224,11 +175,9 @@ bool CNNClassifier::postProcess( element.shape = label2state_[label]; } } - element.confidence = probability; + element.confidence = prob; traffic_signal.elements.push_back(element); } - - return true; } bool CNNClassifier::readLabelfile(std::string filepath, std::vector & labels) @@ -245,32 +194,6 @@ bool CNNClassifier::readLabelfile(std::string filepath, std::vector return true; } -void CNNClassifier::calcSoftmax( - std::vector & data, std::vector & probs, int num_output) -{ - float exp_sum = 0.0; - for (int i = 0; i < num_output; ++i) { - exp_sum += exp(data[i]); - } - - for (int i = 0; i < num_output; ++i) { - probs.push_back(exp(data[i]) / exp_sum); - } -} - -std::vector CNNClassifier::argsort(std::vector & tensor, int num_output) -{ - std::vector indices(num_output); - for (int i = 0; i < num_output; i++) { - indices[i] = i; - } - std::sort(indices.begin(), indices.begin() + num_output, [tensor](size_t idx1, size_t idx2) { - return tensor[idx1] > tensor[idx2]; - }); - - return indices; -} - bool CNNClassifier::isColorLabel(const std::string label) { using tier4_perception_msgs::msg::TrafficSignal; diff --git a/perception/traffic_light_classifier/src/color_classifier.cpp b/perception/traffic_light_classifier/src/color_classifier.cpp index 4b7fb37096021..51be12fce86e8 100644 --- a/perception/traffic_light_classifier/src/color_classifier.cpp +++ b/perception/traffic_light_classifier/src/color_classifier.cpp @@ -51,131 +51,141 @@ ColorClassifier::ColorClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr) std::bind(&ColorClassifier::parametersCallback, this, _1)); } -bool ColorClassifier::getTrafficSignal( - const cv::Mat & input_image, tier4_perception_msgs::msg::TrafficSignal & traffic_signal) +bool ColorClassifier::getTrafficSignals( + const std::vector & images, + tier4_perception_msgs::msg::TrafficSignalArray & traffic_signals) { - cv::Mat green_image; - cv::Mat yellow_image; - cv::Mat red_image; - filterHSV(input_image, green_image, yellow_image, red_image); - // binarize - cv::Mat green_bin_image; - cv::Mat yellow_bin_image; - cv::Mat red_bin_image; - const int bin_threshold = 127; - cv::threshold(green_image, green_bin_image, bin_threshold, 255, cv::THRESH_BINARY); - cv::threshold(yellow_image, yellow_bin_image, bin_threshold, 255, cv::THRESH_BINARY); - cv::threshold(red_image, red_bin_image, bin_threshold, 255, cv::THRESH_BINARY); - // filter noise - cv::Mat green_filtered_bin_image; - cv::Mat yellow_filtered_bin_image; - cv::Mat red_filtered_bin_image; - cv::Mat element4 = (cv::Mat_(3, 3) << 0, 1, 0, 1, 1, 1, 0, 1, 0); - cv::erode(green_bin_image, green_filtered_bin_image, element4, cv::Point(-1, -1), 1); - cv::erode(yellow_bin_image, yellow_filtered_bin_image, element4, cv::Point(-1, -1), 1); - cv::erode(red_bin_image, red_filtered_bin_image, element4, cv::Point(-1, -1), 1); - cv::dilate(green_filtered_bin_image, green_filtered_bin_image, cv::Mat(), cv::Point(-1, -1), 1); - cv::dilate(yellow_filtered_bin_image, yellow_filtered_bin_image, cv::Mat(), cv::Point(-1, -1), 1); - cv::dilate(red_filtered_bin_image, red_filtered_bin_image, cv::Mat(), cv::Point(-1, -1), 1); - - /* debug */ -#if 1 - if (0 < image_pub_.getNumSubscribers()) { - cv::Mat debug_raw_image; - cv::Mat debug_green_image; - cv::Mat debug_yellow_image; - cv::Mat debug_red_image; - cv::hconcat(input_image, input_image, debug_raw_image); - cv::hconcat(debug_raw_image, input_image, debug_raw_image); - cv::hconcat(green_image, green_bin_image, debug_green_image); - cv::hconcat(debug_green_image, green_filtered_bin_image, debug_green_image); - cv::hconcat(yellow_image, yellow_bin_image, debug_yellow_image); - cv::hconcat(debug_yellow_image, yellow_filtered_bin_image, debug_yellow_image); - cv::hconcat(red_image, red_bin_image, debug_red_image); - cv::hconcat(debug_red_image, red_filtered_bin_image, debug_red_image); - - cv::Mat debug_image; - cv::vconcat(debug_green_image, debug_yellow_image, debug_image); - cv::vconcat(debug_image, debug_red_image, debug_image); - cv::cvtColor(debug_image, debug_image, cv::COLOR_GRAY2RGB); - cv::vconcat(debug_raw_image, debug_image, debug_image); - const int width = input_image.cols; - const int height = input_image.rows; - cv::line( - debug_image, cv::Point(0, 0), cv::Point(debug_image.cols, 0), cv::Scalar(255, 255, 255), 1, - CV_AA, 0); - cv::line( - debug_image, cv::Point(0, height), cv::Point(debug_image.cols, height), - cv::Scalar(255, 255, 255), 1, CV_AA, 0); - cv::line( - debug_image, cv::Point(0, height * 2), cv::Point(debug_image.cols, height * 2), - cv::Scalar(255, 255, 255), 1, CV_AA, 0); - cv::line( - debug_image, cv::Point(0, height * 3), cv::Point(debug_image.cols, height * 3), - cv::Scalar(255, 255, 255), 1, CV_AA, 0); - - cv::line( - debug_image, cv::Point(0, 0), cv::Point(0, debug_image.rows), cv::Scalar(255, 255, 255), 1, - CV_AA, 0); - cv::line( - debug_image, cv::Point(width, 0), cv::Point(width, debug_image.rows), - cv::Scalar(255, 255, 255), 1, CV_AA, 0); - cv::line( - debug_image, cv::Point(width * 2, 0), cv::Point(width * 2, debug_image.rows), - cv::Scalar(255, 255, 255), 1, CV_AA, 0); - cv::line( - debug_image, cv::Point(width * 3, 0), cv::Point(width * 3, debug_image.rows), - cv::Scalar(255, 255, 255), 1, CV_AA, 0); - - cv::putText( - debug_image, "green", cv::Point(0, height * 1.5), cv::FONT_HERSHEY_SIMPLEX, 1.0, - cv::Scalar(255, 255, 255), 1, CV_AA); - cv::putText( - debug_image, "yellow", cv::Point(0, height * 2.5), cv::FONT_HERSHEY_SIMPLEX, 1.0, - cv::Scalar(255, 255, 255), 1, CV_AA); - cv::putText( - debug_image, "red", cv::Point(0, height * 3.5), cv::FONT_HERSHEY_SIMPLEX, 1.0, - cv::Scalar(255, 255, 255), 1, CV_AA); - const auto debug_image_msg = - cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", debug_image).toImageMsg(); - image_pub_.publish(debug_image_msg); + if (images.size() != traffic_signals.signals.size()) { + RCLCPP_WARN(node_ptr_->get_logger(), "image number should be equal to traffic signal number!"); + return false; } + for (size_t image_i = 0; image_i < images.size(); image_i++) { + const auto & input_image = images[image_i]; + auto & traffic_signal = traffic_signals.signals[image_i]; + cv::Mat green_image; + cv::Mat yellow_image; + cv::Mat red_image; + filterHSV(input_image, green_image, yellow_image, red_image); + // binarize + cv::Mat green_bin_image; + cv::Mat yellow_bin_image; + cv::Mat red_bin_image; + const int bin_threshold = 127; + cv::threshold(green_image, green_bin_image, bin_threshold, 255, cv::THRESH_BINARY); + cv::threshold(yellow_image, yellow_bin_image, bin_threshold, 255, cv::THRESH_BINARY); + cv::threshold(red_image, red_bin_image, bin_threshold, 255, cv::THRESH_BINARY); + // filter noise + cv::Mat green_filtered_bin_image; + cv::Mat yellow_filtered_bin_image; + cv::Mat red_filtered_bin_image; + cv::Mat element4 = (cv::Mat_(3, 3) << 0, 1, 0, 1, 1, 1, 0, 1, 0); + cv::erode(green_bin_image, green_filtered_bin_image, element4, cv::Point(-1, -1), 1); + cv::erode(yellow_bin_image, yellow_filtered_bin_image, element4, cv::Point(-1, -1), 1); + cv::erode(red_bin_image, red_filtered_bin_image, element4, cv::Point(-1, -1), 1); + cv::dilate(green_filtered_bin_image, green_filtered_bin_image, cv::Mat(), cv::Point(-1, -1), 1); + cv::dilate( + yellow_filtered_bin_image, yellow_filtered_bin_image, cv::Mat(), cv::Point(-1, -1), 1); + cv::dilate(red_filtered_bin_image, red_filtered_bin_image, cv::Mat(), cv::Point(-1, -1), 1); + + /* debug */ +#if 1 + if (0 < image_pub_.getNumSubscribers()) { + cv::Mat debug_raw_image; + cv::Mat debug_green_image; + cv::Mat debug_yellow_image; + cv::Mat debug_red_image; + cv::hconcat(input_image, input_image, debug_raw_image); + cv::hconcat(debug_raw_image, input_image, debug_raw_image); + cv::hconcat(green_image, green_bin_image, debug_green_image); + cv::hconcat(debug_green_image, green_filtered_bin_image, debug_green_image); + cv::hconcat(yellow_image, yellow_bin_image, debug_yellow_image); + cv::hconcat(debug_yellow_image, yellow_filtered_bin_image, debug_yellow_image); + cv::hconcat(red_image, red_bin_image, debug_red_image); + cv::hconcat(debug_red_image, red_filtered_bin_image, debug_red_image); + + cv::Mat debug_image; + cv::vconcat(debug_green_image, debug_yellow_image, debug_image); + cv::vconcat(debug_image, debug_red_image, debug_image); + cv::cvtColor(debug_image, debug_image, cv::COLOR_GRAY2RGB); + cv::vconcat(debug_raw_image, debug_image, debug_image); + const int width = input_image.cols; + const int height = input_image.rows; + cv::line( + debug_image, cv::Point(0, 0), cv::Point(debug_image.cols, 0), cv::Scalar(255, 255, 255), 1, + CV_AA, 0); + cv::line( + debug_image, cv::Point(0, height), cv::Point(debug_image.cols, height), + cv::Scalar(255, 255, 255), 1, CV_AA, 0); + cv::line( + debug_image, cv::Point(0, height * 2), cv::Point(debug_image.cols, height * 2), + cv::Scalar(255, 255, 255), 1, CV_AA, 0); + cv::line( + debug_image, cv::Point(0, height * 3), cv::Point(debug_image.cols, height * 3), + cv::Scalar(255, 255, 255), 1, CV_AA, 0); + + cv::line( + debug_image, cv::Point(0, 0), cv::Point(0, debug_image.rows), cv::Scalar(255, 255, 255), 1, + CV_AA, 0); + cv::line( + debug_image, cv::Point(width, 0), cv::Point(width, debug_image.rows), + cv::Scalar(255, 255, 255), 1, CV_AA, 0); + cv::line( + debug_image, cv::Point(width * 2, 0), cv::Point(width * 2, debug_image.rows), + cv::Scalar(255, 255, 255), 1, CV_AA, 0); + cv::line( + debug_image, cv::Point(width * 3, 0), cv::Point(width * 3, debug_image.rows), + cv::Scalar(255, 255, 255), 1, CV_AA, 0); + + cv::putText( + debug_image, "green", cv::Point(0, height * 1.5), cv::FONT_HERSHEY_SIMPLEX, 1.0, + cv::Scalar(255, 255, 255), 1, CV_AA); + cv::putText( + debug_image, "yellow", cv::Point(0, height * 2.5), cv::FONT_HERSHEY_SIMPLEX, 1.0, + cv::Scalar(255, 255, 255), 1, CV_AA); + cv::putText( + debug_image, "red", cv::Point(0, height * 3.5), cv::FONT_HERSHEY_SIMPLEX, 1.0, + cv::Scalar(255, 255, 255), 1, CV_AA); + const auto debug_image_msg = + cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", debug_image).toImageMsg(); + image_pub_.publish(debug_image_msg); + } #endif - /* --- */ - - const int green_pixel_num = cv::countNonZero(green_filtered_bin_image); - const int yellow_pixel_num = cv::countNonZero(yellow_filtered_bin_image); - const int red_pixel_num = cv::countNonZero(red_filtered_bin_image); - const double green_ratio = - static_cast(green_pixel_num) / - static_cast(green_filtered_bin_image.rows * green_filtered_bin_image.cols); - const double yellow_ratio = - static_cast(yellow_pixel_num) / - static_cast(yellow_filtered_bin_image.rows * yellow_filtered_bin_image.cols); - const double red_ratio = - static_cast(red_pixel_num) / - static_cast(red_filtered_bin_image.rows * red_filtered_bin_image.cols); - - if (yellow_ratio < green_ratio && red_ratio < green_ratio) { - tier4_perception_msgs::msg::TrafficLightElement element; - element.color = tier4_perception_msgs::msg::TrafficLightElement::GREEN; - element.confidence = std::min(1.0, static_cast(green_pixel_num) / (20.0 * 20.0)); - traffic_signal.elements.push_back(element); - } else if (green_ratio < yellow_ratio && red_ratio < yellow_ratio) { - tier4_perception_msgs::msg::TrafficLightElement element; - element.color = tier4_perception_msgs::msg::TrafficLightElement::AMBER; - element.confidence = std::min(1.0, static_cast(yellow_pixel_num) / (20.0 * 20.0)); - traffic_signal.elements.push_back(element); - } else if (green_ratio < red_ratio && yellow_ratio < red_ratio) { - tier4_perception_msgs::msg::TrafficLightElement element; - element.color = ::tier4_perception_msgs::msg::TrafficLightElement::RED; - element.confidence = std::min(1.0, static_cast(red_pixel_num) / (20.0 * 20.0)); - traffic_signal.elements.push_back(element); - } else { - tier4_perception_msgs::msg::TrafficLightElement element; - element.color = ::tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; - element.confidence = 0.0; - traffic_signal.elements.push_back(element); + /* --- */ + + const int green_pixel_num = cv::countNonZero(green_filtered_bin_image); + const int yellow_pixel_num = cv::countNonZero(yellow_filtered_bin_image); + const int red_pixel_num = cv::countNonZero(red_filtered_bin_image); + const double green_ratio = + static_cast(green_pixel_num) / + static_cast(green_filtered_bin_image.rows * green_filtered_bin_image.cols); + const double yellow_ratio = + static_cast(yellow_pixel_num) / + static_cast(yellow_filtered_bin_image.rows * yellow_filtered_bin_image.cols); + const double red_ratio = + static_cast(red_pixel_num) / + static_cast(red_filtered_bin_image.rows * red_filtered_bin_image.cols); + + if (yellow_ratio < green_ratio && red_ratio < green_ratio) { + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = tier4_perception_msgs::msg::TrafficLightElement::GREEN; + element.confidence = std::min(1.0, static_cast(green_pixel_num) / (20.0 * 20.0)); + traffic_signal.elements.push_back(element); + } else if (green_ratio < yellow_ratio && red_ratio < yellow_ratio) { + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = tier4_perception_msgs::msg::TrafficLightElement::AMBER; + element.confidence = std::min(1.0, static_cast(yellow_pixel_num) / (20.0 * 20.0)); + traffic_signal.elements.push_back(element); + } else if (green_ratio < red_ratio && yellow_ratio < red_ratio) { + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = ::tier4_perception_msgs::msg::TrafficLightElement::RED; + element.confidence = std::min(1.0, static_cast(red_pixel_num) / (20.0 * 20.0)); + traffic_signal.elements.push_back(element); + } else { + tier4_perception_msgs::msg::TrafficLightElement element; + element.color = ::tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + element.confidence = 0.0; + traffic_signal.elements.push_back(element); + } } return true; } diff --git a/perception/traffic_light_classifier/src/nodelet.cpp b/perception/traffic_light_classifier/src/nodelet.cpp index 5332f5d3baacc..90cca87245d22 100644 --- a/perception/traffic_light_classifier/src/nodelet.cpp +++ b/perception/traffic_light_classifier/src/nodelet.cpp @@ -91,20 +91,18 @@ void TrafficLightClassifierNodelet::imageRoiCallback( tier4_perception_msgs::msg::TrafficSignalArray output_msg; - for (size_t i = 0; i < input_rois_msg->rois.size(); ++i) { - const sensor_msgs::msg::RegionOfInterest & roi = input_rois_msg->rois.at(i).roi; - cv::Mat clipped_image( - cv_ptr->image, cv::Rect(roi.x_offset, roi.y_offset, roi.width, roi.height)); + output_msg.signals.resize(input_rois_msg->rois.size()); - tier4_perception_msgs::msg::TrafficSignal traffic_signal; - traffic_signal.traffic_light_id = input_rois_msg->rois.at(i).traffic_light_id; - if (!classifier_ptr_->getTrafficSignal(clipped_image, traffic_signal)) { - RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback"); - return; - } - output_msg.signals.push_back(traffic_signal); + std::vector images; + for (size_t i = 0; i < input_rois_msg->rois.size(); i++) { + output_msg.signals[i].traffic_light_id = input_rois_msg->rois.at(i).traffic_light_id; + const sensor_msgs::msg::RegionOfInterest & roi = input_rois_msg->rois.at(i).roi; + images.emplace_back(cv_ptr->image, cv::Rect(roi.x_offset, roi.y_offset, roi.width, roi.height)); + } + if (!classifier_ptr_->getTrafficSignals(images, output_msg)) { + RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback"); + return; } - output_msg.header = input_image_msg->header; traffic_signal_array_pub_->publish(output_msg); } diff --git a/perception/traffic_light_classifier/src/single_image_debug_inference_node.cpp b/perception/traffic_light_classifier/src/single_image_debug_inference_node.cpp index 10d36978224ab..179d63b8b3797 100644 --- a/perception/traffic_light_classifier/src/single_image_debug_inference_node.cpp +++ b/perception/traffic_light_classifier/src/single_image_debug_inference_node.cpp @@ -122,14 +122,14 @@ class SingleImageDebugInferenceNode : public rclcpp::Node return; } cv::cvtColor(crop, crop, cv::COLOR_BGR2RGB); - tier4_perception_msgs::msg::TrafficSignal traffic_signal; - if (!classifier_ptr_->getTrafficSignal(crop, traffic_signal)) { + tier4_perception_msgs::msg::TrafficSignalArray traffic_signal; + if (!classifier_ptr_->getTrafficSignals({crop}, traffic_signal)) { RCLCPP_ERROR(get_logger(), "failed to classify image"); return; } cv::Scalar color; cv::Scalar text_color; - for (const auto & element : traffic_signal.elements) { + for (const auto & element : traffic_signal.signals[0].elements) { auto color_str = toString(element.color); auto shape_str = toString(element.shape); auto confidence_str = std::to_string(element.confidence); diff --git a/perception/traffic_light_fine_detector/CMakeLists.txt b/perception/traffic_light_fine_detector/CMakeLists.txt index a26cafff1ee4d..a0605a6aa1a90 100644 --- a/perception/traffic_light_fine_detector/CMakeLists.txt +++ b/perception/traffic_light_fine_detector/CMakeLists.txt @@ -70,7 +70,9 @@ else() endif() # Download caffemodel and prototxt -set(PRETRAINED_MODEL_HASH f3af5bd588c6c99ccf9ca236a07ad41e) +set(PRETRAINED_MODEL_BATCH_1_HASH 2b72d085022b8ee6aacff06bd722cfda) +set(PRETRAINED_MODEL_BATCH_4_HASH 4044daa86e7776ce241e94d98a09cc0e) +set(PRETRAINED_MODEL_BATCH_6_HASH 47255a11bde479320d703f1f45db1242) set(LAMP_LABEL_HASH e9f45efb02f2a9aa8ac27b3d5c164905) set(DATA_DIR https://awf.ml.dev.web.auto/perception/models/tlr_yolox_s/v2) @@ -109,7 +111,9 @@ function(download FILE_NAME FILE_HASH) message(FATAL_ERROR "Error occurred during download: ${ERROR_MESSAGE}") endif() endfunction() -download(tlr_yolox_s.onnx ${PRETRAINED_MODEL_HASH}) +download(tlr_yolox_s_batch_1.onnx ${PRETRAINED_MODEL_BATCH_1_HASH}) +download(tlr_yolox_s_batch_4.onnx ${PRETRAINED_MODEL_BATCH_4_HASH}) +download(tlr_yolox_s_batch_6.onnx ${PRETRAINED_MODEL_BATCH_6_HASH}) download(tlr_labels.txt ${LAMP_LABEL_HASH}) if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) diff --git a/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp b/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp index f115596453835..4d14874a58242 100644 --- a/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp +++ b/perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp @@ -164,6 +164,7 @@ class TrafficLightFineDetectorNodelet : public rclcpp::Node double score_thresh_; int tlr_id_; + int batch_size_; std::unique_ptr trt_yolox_; }; // TrafficLightFineDetectorNodelet diff --git a/perception/traffic_light_fine_detector/src/nodelet.cpp b/perception/traffic_light_fine_detector/src/nodelet.cpp index 75812a072f4c6..86e77bc31cd71 100644 --- a/perception/traffic_light_fine_detector/src/nodelet.cpp +++ b/perception/traffic_light_fine_detector/src/nodelet.cpp @@ -76,8 +76,22 @@ TrafficLightFineDetectorNodelet::TrafficLightFineDetectorNodelet( if (!readLabelFile(label_path, tlr_id_, num_class)) { RCLCPP_ERROR(this->get_logger(), "Could not find tlr id"); } + + const tensorrt_common::BuildConfig build_config = + tensorrt_common::BuildConfig("MinMax", -1, false, false, false, 0.0); + + const bool cuda_preprocess = true; + const std::string calib_image_list = ""; + const double scale = 1.0; + const std::string cache_dir = ""; + nvinfer1::Dims input_dim = tensorrt_common::get_input_dims(model_path); + assert(input_dim.d[0] > 0); + batch_size_ = input_dim.d[0]; + const tensorrt_common::BatchConfig batch_config{batch_size_, batch_size_, batch_size_}; + trt_yolox_ = std::make_unique( - model_path, precision, num_class, score_thresh_, nms_threshold); + model_path, precision, num_class, score_thresh_, nms_threshold, build_config, cuda_preprocess, + calib_image_list, scale, cache_dir, batch_config); using std::chrono_literals::operator""ms; timer_ = rclcpp::create_timer( @@ -139,30 +153,50 @@ void TrafficLightFineDetectorNodelet::callback( } rosMsg2CvMat(in_image_msg, original_image, "bgr8"); - for (const auto & rough_roi : rough_roi_msg->rois) { + std::vector rois; + tensorrt_yolox::ObjectArrays inference_results; + std::vector lts; + std::vector roi_ids; + for (size_t roi_i = 0; roi_i < rough_roi_msg->rois.size(); roi_i++) { + const auto & rough_roi = rough_roi_msg->rois[roi_i]; cv::Point lt(rough_roi.roi.x_offset, rough_roi.roi.y_offset); cv::Point rb( rough_roi.roi.x_offset + rough_roi.roi.width, rough_roi.roi.y_offset + rough_roi.roi.height); fitInFrame(lt, rb, cv::Size(original_image.size())); - cv::Mat cropped_img = cv::Mat(original_image, cv::Rect(lt, rb)); - tensorrt_yolox::ObjectArrays inference_results; - if (!trt_yolox_->doInference({cropped_img}, inference_results)) { - RCLCPP_WARN(this->get_logger(), "Fail to inference"); - return; + rois.emplace_back(lt, rb); + lts.emplace_back(lt); + roi_ids.emplace_back(rough_roi.traffic_light_id); + // keep the actual batch size + size_t true_batch_size = rois.size(); + // insert fake rois since the TRT model requires static batch size + if (roi_i + 1 == rough_roi_msg->rois.size()) { + while (static_cast(rois.size()) < batch_size_) { + rois.emplace_back(rois.front()); + } } - for (tensorrt_yolox::Object & detection : inference_results[0]) { - if (detection.score < score_thresh_ || detection.type != tlr_id_) { - continue; + if (static_cast(rois.size()) == batch_size_) { + trt_yolox_->doMultiScaleInference(original_image, inference_results, rois); + for (size_t batch_i = 0; batch_i < true_batch_size; batch_i++) { + for (const tensorrt_yolox::Object & detection : inference_results[batch_i]) { + if (detection.score < score_thresh_ || detection.type != tlr_id_) { + continue; + } + cv::Point lt_roi( + lts[batch_i].x + detection.x_offset, lts[batch_i].y + detection.y_offset); + cv::Point rb_roi(lt_roi.x + detection.width, lt_roi.y + detection.height); + fitInFrame(lt_roi, rb_roi, cv::Size(original_image.size())); + tensorrt_yolox::Object det = detection; + det.x_offset = lt_roi.x; + det.y_offset = lt_roi.y; + det.width = rb_roi.x - lt_roi.x; + det.height = rb_roi.y - lt_roi.y; + id2detections[roi_ids[batch_i]].push_back(det); + } } - cv::Point lt_roi(lt.x + detection.x_offset, lt.y + detection.y_offset); - cv::Point rb_roi(lt_roi.x + detection.width, lt_roi.y + detection.height); - fitInFrame(lt_roi, rb_roi, cv::Size(original_image.size())); - tensorrt_yolox::Object det = detection; - det.x_offset = lt_roi.x; - det.y_offset = lt_roi.y; - det.width = rb_roi.x - lt_roi.x; - det.height = rb_roi.y - lt_roi.y; - id2detections[rough_roi.traffic_light_id].push_back(det); + rois.clear(); + lts.clear(); + inference_results.clear(); + roi_ids.clear(); } } detectionMatch(id2expectRoi, id2detections, out_rois); From bc9f62cb04afd8d0fd49c00ea5ab2dbcfa6d1d53 Mon Sep 17 00:00:00 2001 From: Mingyu1991 <115005477+Mingyu1991@users.noreply.github.com> Date: Sat, 8 Jul 2023 11:33:25 +0900 Subject: [PATCH 110/118] feat(tier4_perception_launch): update traffic light launch (#4176) * first commit Signed-off-by: Mingyu Li * add image number arg Signed-off-by: Shunsuke Miura * style(pre-commit): autofix * Update launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml * Update launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml * add traffic light namespace to fusion Signed-off-by: Shunsuke Miura * add tlr fusion only mode and camera number arg Signed-off-by: Shunsuke Miura * change to include traffic_light_arbiter launch Signed-off-by: Shunsuke Miura * delete relay topic type Signed-off-by: Shunsuke Miura --------- Signed-off-by: Mingyu Li Signed-off-by: Shunsuke Miura Co-authored-by: Shunsuke Miura 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> --- .../launch/perception.launch.xml | 4 + .../traffic_light.launch.xml | 154 ++++++++++++------ .../traffic_light_node_container.launch.py | 24 ++- launch/tier4_perception_launch/package.xml | 5 +- .../src/node.cpp | 4 +- 5 files changed, 129 insertions(+), 62 deletions(-) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 131388b3764b5..69d42b8509bb5 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -52,6 +52,8 @@ + + @@ -153,6 +155,8 @@ + + diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml index ea50101719d65..4dae46cbacb0a 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -2,84 +2,138 @@ + - + - + + + - - - - + + + + + + + + - + - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + - - + + + + - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + - + + + + + + + + + diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py index 964008dafa5cd..8b3d15f2cff95 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py @@ -40,6 +40,10 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("enable_image_decompressor", "True") add_launch_arg("enable_fine_detection", "True") add_launch_arg("input/image", "/sensing/camera/traffic_light/image_raw") + add_launch_arg("output/rois", "/perception/traffic_light_recognition/rois") + add_launch_arg( + "output/traffic_signals", "/perception/traffic_light_recognition/traffic_signals" + ) # traffic_light_fine_detector add_launch_arg( @@ -89,6 +93,7 @@ def create_parameter_dict(*args): package="traffic_light_classifier", plugin="traffic_light::TrafficLightClassifierNodelet", name="traffic_light_classifier", + namespace="classification", parameters=[ create_parameter_dict( "approximate_sync", @@ -102,7 +107,7 @@ def create_parameter_dict(*args): ], remappings=[ ("~/input/image", LaunchConfiguration("input/image")), - ("~/input/rois", "rois"), + ("~/input/rois", LaunchConfiguration("output/rois")), ("~/output/traffic_signals", "classified/traffic_signals"), ], extra_arguments=[ @@ -116,9 +121,9 @@ def create_parameter_dict(*args): parameters=[create_parameter_dict("enable_fine_detection")], remappings=[ ("~/input/image", LaunchConfiguration("input/image")), - ("~/input/rois", "rois"), - ("~/input/rough/rois", "rough/rois"), - ("~/input/traffic_signals", "traffic_signals"), + ("~/input/rois", LaunchConfiguration("output/rois")), + ("~/input/rough/rois", "detection/rough/rois"), + ("~/input/traffic_signals", LaunchConfiguration("output/traffic_signals")), ("~/output/image", "debug/rois"), ("~/output/image/compressed", "debug/rois/compressed"), ("~/output/image/compressedDepth", "debug/rois/compressedDepth"), @@ -138,11 +143,12 @@ def create_parameter_dict(*args): package="crosswalk_traffic_light_estimator", plugin="traffic_light::CrosswalkTrafficLightEstimatorNode", name="crosswalk_traffic_light_estimator", + namespace="classification", remappings=[ ("~/input/vector_map", "/map/vector_map"), ("~/input/route", "/planning/mission_planning/route"), ("~/input/classified/traffic_signals", "classified/traffic_signals"), - ("~/output/traffic_signals", "traffic_signals"), + ("~/output/traffic_signals", "estimated/traffic_signals"), ], extra_arguments=[{"use_intra_process_comms": False}], ), @@ -157,11 +163,10 @@ def create_parameter_dict(*args): package="topic_tools", plugin="topic_tools::RelayNode", name="classified_signals_relay", - namespace="", + namespace="classification", parameters=[ {"input_topic": "classified/traffic_signals"}, - {"output_topic": "traffic_signals"}, - {"type": "autoware_auto_perception_msgs/msg/TrafficSignalArray"}, + {"output_topic": "estimated/traffic_signals"}, ], extra_arguments=[ {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} @@ -209,12 +214,13 @@ def create_parameter_dict(*args): package="traffic_light_fine_detector", plugin="traffic_light::TrafficLightFineDetectorNodelet", name="traffic_light_fine_detector", + namespace="detection", parameters=[fine_detector_param], remappings=[ ("~/input/image", LaunchConfiguration("input/image")), ("~/input/rois", "rough/rois"), ("~/expect/rois", "expect/rois"), - ("~/output/rois", "rois"), + ("~/output/rois", LaunchConfiguration("output/rois")), ], extra_arguments=[ {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 1140d643a7083..40fc632a33f45 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -32,9 +32,12 @@ probabilistic_occupancy_grid_map shape_estimation tensorrt_yolo + topic_tools traffic_light_classifier + traffic_light_fine_detector traffic_light_map_based_detector - traffic_light_ssd_fine_detector + traffic_light_multi_camera_fusion + traffic_light_occlusion_predictor traffic_light_visualization ament_lint_auto diff --git a/perception/traffic_light_multi_camera_fusion/src/node.cpp b/perception/traffic_light_multi_camera_fusion/src/node.cpp index d7e82af4af079..892b6be62ef9d 100644 --- a/perception/traffic_light_multi_camera_fusion/src/node.cpp +++ b/perception/traffic_light_multi_camera_fusion/src/node.cpp @@ -149,8 +149,8 @@ MultiCameraFusion::MultiCameraFusion(const rclcpp::NodeOptions & node_options) is_approximate_sync_ = this->declare_parameter("approximate_sync", false); message_lifespan_ = this->declare_parameter("message_lifespan", 0.09); for (const std::string & camera_ns : camera_namespaces) { - std::string signal_topic = camera_ns + "/traffic_signals"; - std::string roi_topic = camera_ns + "/rois"; + std::string signal_topic = camera_ns + "/classification/traffic_signals"; + std::string roi_topic = camera_ns + "/detection/rois"; std::string cam_info_topic = camera_ns + "/camera_info"; roi_subs_.emplace_back( new mf::Subscriber(this, roi_topic, rclcpp::QoS{1}.get_rmw_qos_profile())); From 8c982e5656d20eabcd74e497dd8325aca1994ab9 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 9 Jul 2023 17:22:57 +0900 Subject: [PATCH 111/118] refactor(behavior_velocity_crosswalk_module): clean up the code (#4182) * refactor Signed-off-by: Takayuki Murooka * refacotr Signed-off-by: Takayuki Murooka * refactor Signed-off-by: Takayuki Murooka * refactor Signed-off-by: Takayuki Murooka * refactor Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/debug.cpp | 40 +- .../src/scene_crosswalk.cpp | 430 ++++++++++-------- .../src/scene_crosswalk.hpp | 41 +- .../src/scene_walkway.cpp | 3 +- .../src/scene_walkway.hpp | 6 +- .../src/util.hpp | 22 +- 6 files changed, 309 insertions(+), 233 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/debug.cpp b/planning/behavior_velocity_crosswalk_module/src/debug.cpp index 50882d3a8c2b8..50fd62a53cdcd 100644 --- a/planning/behavior_velocity_crosswalk_module/src/debug.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/debug.cpp @@ -92,32 +92,24 @@ visualization_msgs::msg::MarkerArray createCrosswalkMarkers( msg.markers.push_back(marker); } - { - size_t i = 0; - for (const auto & polygon : debug_data.obj_polygons) { - auto marker = createDefaultMarker( - "map", now, "object polygon", uid + i++, Marker::LINE_STRIP, - createMarkerScale(0.1, 0.0, 0.0), createMarkerColor(1.0, 0.0, 1.0, 0.999)); - for (const auto & p : polygon.points) { - marker.points.push_back(createPoint(p.x, p.y, p.z)); - } - marker.points.push_back(marker.points.front()); - msg.markers.push_back(marker); - } + for (size_t i = 0; i < debug_data.obj_polygons.size(); ++i) { + const auto & points = debug_data.obj_polygons.at(i); + auto marker = createDefaultMarker( + "map", now, "object polygon", uid + i++, Marker::LINE_STRIP, createMarkerScale(0.1, 0.0, 0.0), + createMarkerColor(1.0, 0.0, 1.0, 0.999)); + marker.points = points; + // marker.points.push_back(marker.points.front()); + msg.markers.push_back(marker); } - { - size_t i = 0; - for (const auto & polygon : debug_data.ego_polygons) { - auto marker = createDefaultMarker( - "map", now, "vehicle polygon", uid + i++, Marker::LINE_STRIP, - createMarkerScale(0.1, 0.0, 0.0), createMarkerColor(1.0, 1.0, 0.0, 0.999)); - for (const auto & p : polygon.points) { - marker.points.push_back(createPoint(p.x, p.y, p.z)); - } - marker.points.push_back(marker.points.front()); - msg.markers.push_back(marker); - } + for (size_t i = 0; i < debug_data.ego_polygons.size(); ++i) { + const auto & points = debug_data.ego_polygons.at(i); + auto marker = createDefaultMarker( + "map", now, "vehicle polygon", uid + i++, Marker::LINE_STRIP, + createMarkerScale(0.1, 0.0, 0.0), createMarkerColor(1.0, 1.0, 0.0, 0.999)); + marker.points = points; + // marker.points.push_back(marker.points.front()); + msg.markers.push_back(marker); } // Crosswalk polygon diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 473ec745c93ac..e29bc27213f36 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -36,6 +36,7 @@ using motion_utils::calcLongitudinalOffsetPose; using motion_utils::calcSignedArcLength; using motion_utils::findNearestSegmentIndex; using motion_utils::insertTargetPoint; +using motion_utils::resamplePath; using tier4_autoware_utils::createPoint; using tier4_autoware_utils::getPoint; using tier4_autoware_utils::getPose; @@ -54,14 +55,17 @@ geometry_msgs::msg::Point32 createPoint32(const double x, const double y, const p.z = z; return p; } -geometry_msgs::msg::Polygon toMsg(const Polygon2d & polygon, const double z) + +std::vector toGeometryPointVector( + const Polygon2d & polygon, const double z) { - geometry_msgs::msg::Polygon ret; + std::vector points; for (const auto & p : polygon.outer()) { - ret.points.push_back(createPoint32(p.x(), p.y(), z)); + points.push_back(createPoint(p.x(), p.y(), z)); } - return ret; + return points; } + Polygon2d createOneStepPolygon( const geometry_msgs::msg::Pose & p_front, const geometry_msgs::msg::Pose & p_back, const geometry_msgs::msg::Polygon & base_polygon) @@ -96,6 +100,7 @@ Polygon2d createOneStepPolygon( return hull_polygon; } + void sortCrosswalksByDistance( const PathWithLaneId & ego_path, const geometry_msgs::msg::Point & ego_pos, lanelet::ConstLanelets & crosswalks) @@ -154,91 +159,49 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto logger_, planner_param_.show_processing_time, "=========== module_id: %ld ===========", module_id_); - debug_data_ = DebugData(); - debug_data_.base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; *stop_reason = planning_utils::initializeStopReason(StopReason::CROSSWALK); - - auto ego_path = *path; - - RCLCPP_INFO_EXPRESSION( - logger_, planner_param_.show_processing_time, "- step1: %f ms", - stop_watch_.toc("total_processing_time", false)); - const auto & ego_pos = planner_data_->current_odometry->pose.position; - const auto path_intersects = - getPolygonIntersects(ego_path, crosswalk_.polygon2d().basicPolygon(), ego_pos, 2); + // Initialize debug data + debug_data_ = DebugData(planner_data_); for (const auto & p : crosswalk_.polygon2d().basicPolygon()) { debug_data_.crosswalk_polygon.push_back(createPoint(p.x(), p.y(), ego_pos.z)); } + recordTime(1); + // Calculate intersection between path and crosswalks + const auto path_intersects = + getPolygonIntersects(*path, crosswalk_.polygon2d().basicPolygon(), ego_pos, 2); + + // Apply safety slow down speed if defined in Lanelet2 map if (crosswalk_.hasAttribute("safety_slow_down_speed")) { - // Safety slow down is on - if (applySafetySlowDownSpeed(*path, path_intersects)) { - ego_path = *path; - } + applySafetySlowDownSpeed(*path, path_intersects); } + recordTime(2); - RCLCPP_INFO_EXPRESSION( - logger_, planner_param_.show_processing_time, "- step2: %f ms", - stop_watch_.toc("total_processing_time", false)); + // Calculate stop point + const auto default_stop_factor = findDefaultStopFactor(*path, path_intersects); + const auto nearest_stop_factor = findNearestStopFactor(*path, path_intersects); - const auto nearest_stop_point_with_factor = - findNearestStopPointWithFactor(ego_path, path_intersects); - const auto rtc_stop_point_with_factor = findRTCStopPointWithFactor(ego_path, path_intersects); + // Generate stop factor with type (NEAREST or DEFAULT) + const auto stop_factor_info = generateStopFactorInfo(nearest_stop_factor, default_stop_factor); + recordTime(3); - RCLCPP_INFO_EXPRESSION( - logger_, planner_param_.show_processing_time, "- step3: %f ms", - stop_watch_.toc("total_processing_time", false)); - - setSafe(!nearest_stop_point_with_factor); - - if (isActivated()) { - if (nearest_stop_point_with_factor) { - const auto target_velocity = - calcTargetVelocity(nearest_stop_point_with_factor->first, ego_path); - insertDecelPointWithDebugInfo( - nearest_stop_point_with_factor->first, - std::max(planner_param_.min_slow_down_velocity, target_velocity), *path); - return true; - } + // Set safe or unsafe + setSafe(!stop_factor_info || stop_factor_info->type != StopFactorInfo::Type::NEAREST); - if (rtc_stop_point_with_factor) { - const auto crosswalk_distance = - calcSignedArcLength(ego_path.points, ego_pos, getPoint(rtc_stop_point_with_factor->first)); - setDistance(crosswalk_distance); + // plan Go/Stop + const bool result = [&]() { + if (isActivated()) { + planGo(stop_factor_info, *path); + // TODO(murooka) call setDistance here return true; } - - setDistance(std::numeric_limits::lowest()); - return true; - } - - const auto & stop_point_with_factor = - [&]() -> boost::optional> { - if (nearest_stop_point_with_factor) - return nearest_stop_point_with_factor.get(); - else if (rtc_stop_point_with_factor) - return rtc_stop_point_with_factor.get(); - return {}; + return planStop(stop_factor_info, *path, stop_reason); }(); + recordTime(4); - if (!stop_point_with_factor) { - return false; - } - - const auto & stop_factor = stop_point_with_factor->second; - insertDecelPointWithDebugInfo(stop_point_with_factor->first, 0.0, *path); - planning_utils::appendStopReason(stop_factor, stop_reason); - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_factor.stop_pose, - VelocityFactor::UNKNOWN); - - RCLCPP_INFO_EXPRESSION( - logger_, planner_param_.show_processing_time, "- step4: %f ms", - stop_watch_.toc("total_processing_time", false)); - - return true; + return result; } boost::optional> CrosswalkModule::getStopLine( @@ -274,8 +237,7 @@ boost::optional> CrosswalkModule::g return {}; } -boost::optional> -CrosswalkModule::findRTCStopPointWithFactor( +boost::optional CrosswalkModule::findDefaultStopFactor( const PathWithLaneId & ego_path, const std::vector & path_intersects) { const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; @@ -297,30 +259,30 @@ CrosswalkModule::findRTCStopPointWithFactor( StopFactor stop_factor; stop_factor.stop_pose = stop_pose.get(); - - return std::make_pair(stop_pose.get().position, stop_factor); + return stop_factor; } -boost::optional> -CrosswalkModule::findNearestStopPointWithFactor( +boost::optional CrosswalkModule::findNearestStopFactor( const PathWithLaneId & ego_path, const std::vector & path_intersects) { - StopFactor stop_factor; - - bool found_pedestrians = false; - bool found_stuck_vehicle = false; - - PathWithLaneId sparse_resample_path{}; - constexpr double RESAMPLE_INTERVAL = 4.0; - if (!splineInterpolate(ego_path, RESAMPLE_INTERVAL, sparse_resample_path, logger_)) { + if (ego_path.points.size() < 2) { + RCLCPP_DEBUG(logger_, "Do not interpolate because path size is 1."); return {}; } - const auto crosswalk_attention_range = getAttentionRange(sparse_resample_path, path_intersects); const auto & ego_pos = planner_data_->current_odometry->pose.position; const auto & objects_ptr = planner_data_->predicted_objects; const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + // Resample path sparsely for less computation cost + constexpr double resample_interval = 4.0; + const auto sparse_resample_path = + resamplePath(ego_path, resample_interval, false, true, true, false); + + // Calculate attention range for crosswalk + const auto crosswalk_attention_range = getAttentionRange(sparse_resample_path, path_intersects); + + // Calculate stop line bool exist_stopline_in_map; const auto p_stop_line = getStopLine(sparse_resample_path, exist_stopline_in_map, path_intersects); @@ -328,54 +290,27 @@ CrosswalkModule::findNearestStopPointWithFactor( return {}; } - geometry_msgs::msg::Point first_stop_point{}; - double minimum_stop_dist = std::numeric_limits::max(); - const auto now = clock_->now(); const auto ignore_crosswalk = debug_data_.ignore_crosswalk = isRedSignalForPedestrians(); - const auto ego_polygon = createVehiclePolygon(planner_data_->vehicle_info_); + // Get attention area + const auto attention_area = getAttentionArea(sparse_resample_path, crosswalk_attention_range); - Polygon2d attention_area; - for (size_t j = 0; j < sparse_resample_path.points.size() - 1; ++j) { - const auto & p_ego_front = sparse_resample_path.points.at(j).point.pose; - const auto & p_ego_back = sparse_resample_path.points.at(j + 1).point.pose; - const auto front_length = - calcSignedArcLength(sparse_resample_path.points, ego_pos, p_ego_front.position); - const auto back_length = - calcSignedArcLength(sparse_resample_path.points, ego_pos, p_ego_back.position); - - if (back_length < crosswalk_attention_range.first) { - continue; - } - - if (crosswalk_attention_range.second < front_length) { - break; - } - - const auto ego_one_step_polygon = createOneStepPolygon(p_ego_front, p_ego_back, ego_polygon); - - debug_data_.ego_polygons.push_back(toMsg(ego_one_step_polygon, ego_pos.z)); - - std::vector unions; - bg::union_(attention_area, ego_one_step_polygon, unions); - if (!unions.empty()) { - attention_area = unions.front(); - bg::correct(attention_area); - } - } + // Check stuck vehicle + const bool found_stuck_vehicle = + isStuckVehicle(sparse_resample_path, objects_ptr->objects, path_intersects); + // Check pedestrian for stop + bool found_pedestrians = false; + geometry_msgs::msg::Point first_stop_point{}; + double minimum_stop_dist = std::numeric_limits::max(); + StopFactor stop_factor; for (const auto & object : objects_ptr->objects) { const auto & obj_pos = object.kinematics.initial_pose_with_covariance.pose.position; const auto & obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear; const auto obj_uuid = toHexString(object.object_id); - if (isVehicle(object)) { - found_stuck_vehicle = - found_stuck_vehicle || isStuckVehicle(sparse_resample_path, object, path_intersects); - } - if (!isTargetType(object)) { continue; } @@ -447,6 +382,7 @@ CrosswalkModule::findNearestStopPointWithFactor( } } + // Check if stop is required const auto need_to_stop = found_pedestrians || found_stuck_vehicle; if (!need_to_stop) { return {}; @@ -474,8 +410,7 @@ CrosswalkModule::findNearestStopPointWithFactor( } stop_factor.stop_pose = stop_pose.get(); - - return std::make_pair(stop_pose.get().position, stop_factor); + return stop_factor; } std::pair CrosswalkModule::getAttentionRange( @@ -483,27 +418,27 @@ std::pair CrosswalkModule::getAttentionRange( { stop_watch_.tic(__func__); - const auto & ego_pos = planner_data_->current_odometry->pose.position; - - double near_attention_range = 0.0; - double far_attention_range = 0.0; if (path_intersects.size() < 2) { - return std::make_pair(near_attention_range, far_attention_range); + return std::make_pair(0.0, 0.0); } - near_attention_range = calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front()); - far_attention_range = calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back()); - - near_attention_range -= planner_param_.crosswalk_attention_range; - far_attention_range += planner_param_.crosswalk_attention_range; + const auto & ego_pos = planner_data_->current_odometry->pose.position; + const auto near_attention_range = + calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front()) - + planner_param_.crosswalk_attention_range; + const auto far_attention_range = + calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back()) + + planner_param_.crosswalk_attention_range; - clampAttentionRangeByNeighborCrosswalks(ego_path, near_attention_range, far_attention_range); + const auto [clamped_near_attention_range, clamped_far_attention_range] = + clampAttentionRangeByNeighborCrosswalks(ego_path, near_attention_range, far_attention_range); RCLCPP_INFO_EXPRESSION( logger_, planner_param_.show_processing_time, "%s : %f ms", __func__, stop_watch_.toc(__func__, true)); - return std::make_pair(std::max(0.0, near_attention_range), std::max(0.0, far_attention_range)); + return std::make_pair( + std::max(0.0, clamped_near_attention_range), std::max(0.0, clamped_far_attention_range)); } void CrosswalkModule::insertDecelPointWithDebugInfo( @@ -530,10 +465,10 @@ void CrosswalkModule::insertDecelPointWithDebugInfo( float CrosswalkModule::calcTargetVelocity( const geometry_msgs::msg::Point & stop_point, const PathWithLaneId & ego_path) const { - const auto & max_jerk = planner_param_.max_slow_down_jerk; - const auto & max_accel = planner_param_.max_slow_down_accel; + const auto max_jerk = planner_param_.max_slow_down_jerk; + const auto max_accel = planner_param_.max_slow_down_accel; const auto & ego_pos = planner_data_->current_odometry->pose.position; - const auto & ego_vel = planner_data_->current_velocity->twist.linear.x; + const auto ego_vel = planner_data_->current_velocity->twist.linear.x; if (ego_vel < planner_param_.no_relax_velocity) { return 0.0; @@ -548,8 +483,9 @@ float CrosswalkModule::calcTargetVelocity( return margin_velocity < feasible_velocity ? feasible_velocity : 0.0; } -void CrosswalkModule::clampAttentionRangeByNeighborCrosswalks( - const PathWithLaneId & ego_path, double & near_attention_range, double & far_attention_range) +std::pair CrosswalkModule::clampAttentionRangeByNeighborCrosswalks( + const PathWithLaneId & ego_path, const double near_attention_range, + const double far_attention_range) { stop_watch_.tic(__func__); @@ -559,7 +495,7 @@ void CrosswalkModule::clampAttentionRangeByNeighborCrosswalks( const auto p_far = calcLongitudinalOffsetPoint(ego_path.points, ego_pos, far_attention_range); if (!p_near || !p_far) { - return; + return std::make_pair(near_attention_range, far_attention_range); } const auto near_idx = findNearestSegmentIndex(ego_path.points, p_near.get()); @@ -611,32 +547,39 @@ void CrosswalkModule::clampAttentionRangeByNeighborCrosswalks( } } - if (prev_crosswalk) { + const double clamped_near_attention_range = [&]() { + if (!prev_crosswalk) { + return near_attention_range; + } auto reverse_ego_path = ego_path; std::reverse(reverse_ego_path.points.begin(), reverse_ego_path.points.end()); const auto prev_crosswalk_intersects = getPolygonIntersects( reverse_ego_path, prev_crosswalk.get().polygon2d().basicPolygon(), ego_pos, 2); + if (prev_crosswalk_intersects.empty()) { + return near_attention_range; + } - if (!prev_crosswalk_intersects.empty()) { - const auto dist_to_prev_crosswalk = - calcSignedArcLength(ego_path.points, ego_pos, prev_crosswalk_intersects.front()); + const auto dist_to_prev_crosswalk = + calcSignedArcLength(ego_path.points, ego_pos, prev_crosswalk_intersects.front()); + return std::max(near_attention_range, dist_to_prev_crosswalk); + }(); - near_attention_range = std::max(near_attention_range, dist_to_prev_crosswalk); + const double clamped_far_attention_range = [&]() { + if (!next_crosswalk) { + return far_attention_range; } - } - - if (next_crosswalk) { const auto next_crosswalk_intersects = getPolygonIntersects(ego_path, next_crosswalk.get().polygon2d().basicPolygon(), ego_pos, 2); - if (!next_crosswalk_intersects.empty()) { - const auto dist_to_next_crosswalk = - calcSignedArcLength(ego_path.points, ego_pos, next_crosswalk_intersects.front()); - - far_attention_range = std::min(far_attention_range, dist_to_next_crosswalk); + if (next_crosswalk_intersects.empty()) { + return far_attention_range; } - } + + const auto dist_to_next_crosswalk = + calcSignedArcLength(ego_path.points, ego_pos, next_crosswalk_intersects.front()); + return std::min(far_attention_range, dist_to_next_crosswalk); + }(); const auto update_p_near = calcLongitudinalOffsetPoint(ego_path.points, ego_pos, near_attention_range); @@ -651,6 +594,8 @@ void CrosswalkModule::clampAttentionRangeByNeighborCrosswalks( RCLCPP_INFO_EXPRESSION( logger_, planner_param_.show_processing_time, "%s : %f ms", __func__, stop_watch_.toc(__func__, true)); + + return std::make_pair(clamped_near_attention_range, clamped_far_attention_range); } std::vector CrosswalkModule::getCollisionPoints( @@ -671,8 +616,8 @@ std::vector CrosswalkModule::getCollisionPoints( for (const auto & obj_path : object.kinematics.predicted_paths) { for (size_t i = 0; i < obj_path.path.size() - 1; ++i) { - const auto p_obj_front = obj_path.path.at(i); - const auto p_obj_back = obj_path.path.at(i + 1); + const auto & p_obj_front = obj_path.path.at(i); + const auto & p_obj_back = obj_path.path.at(i + 1); const auto obj_one_step_polygon = createOneStepPolygon(p_obj_front, p_obj_back, obj_polygon); std::vector tmp_intersects{}; @@ -692,7 +637,7 @@ std::vector CrosswalkModule::getCollisionPoints( double minimum_stop_dist = std::numeric_limits::max(); geometry_msgs::msg::Point nearest_collision_point{}; for (const auto & p : tmp_intersects) { - geometry_msgs::msg::Point cp = createPoint(p.x(), p.y(), ego_pos.z); + const auto cp = createPoint(p.x(), p.y(), ego_pos.z); const auto dist_ego2cp = calcSignedArcLength(ego_path.points, ego_pos, cp); if (dist_ego2cp < minimum_stop_dist) { @@ -718,7 +663,7 @@ std::vector CrosswalkModule::getCollisionPoints( ret.push_back( createCollisionPoint(nearest_collision_point, dist_ego2cp, dist_obj2cp, ego_vel, obj_vel)); - debug_data_.obj_polygons.push_back(toMsg(obj_one_step_polygon, ego_pos.z)); + debug_data_.obj_polygons.push_back(toGeometryPointVector(obj_one_step_polygon, ego_pos.z)); break; } @@ -769,11 +714,11 @@ CollisionPointState CrosswalkModule::getCollisionPointState( return CollisionPointState::YIELD; } -bool CrosswalkModule::applySafetySlowDownSpeed( +void CrosswalkModule::applySafetySlowDownSpeed( PathWithLaneId & output, const std::vector & path_intersects) { if (path_intersects.empty()) { - return false; + return; } const auto & ego_pos = planner_data_->current_odometry->pose.position; @@ -785,14 +730,14 @@ bool CrosswalkModule::applySafetySlowDownSpeed( if (!passed_safety_slow_point_) { // Safety slow down distance [m] - double safety_slow_down_distance = crosswalk_.attributeOr("safety_slow_down_distance", 2.0); + const double safety_slow_down_distance = + crosswalk_.attributeOr("safety_slow_down_distance", 2.0); // the range until to the point where ego will have a const safety slow down speed - auto safety_slow_point_range = - calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front()); - const auto & safety_slow_margin = + const double safety_slow_margin = planner_data_->vehicle_info_.max_longitudinal_offset_m + safety_slow_down_distance; - safety_slow_point_range -= safety_slow_margin; + const double safety_slow_point_range = + calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front()) - safety_slow_margin; const auto & p_safety_slow = calcLongitudinalOffsetPoint(ego_path.points, ego_pos, safety_slow_point_range); @@ -804,48 +749,96 @@ bool CrosswalkModule::applySafetySlowDownSpeed( } } else { // the range until to the point where ego will start accelerate - auto safety_slow_end_point_range = + const double safety_slow_end_point_range = calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back()); - if (safety_slow_end_point_range > 0) { + if (0.0 < safety_slow_end_point_range) { // insert constant ego speed until the end of the crosswalk for (auto & p : output.points) { - const auto & original_velocity = p.point.longitudinal_velocity_mps; + const float original_velocity = p.point.longitudinal_velocity_mps; p.point.longitudinal_velocity_mps = std::min(original_velocity, safety_slow_down_speed); } } } - return true; } -bool CrosswalkModule::isStuckVehicle( - const PathWithLaneId & ego_path, const PredictedObject & object, - const std::vector & path_intersects) const +Polygon2d CrosswalkModule::getAttentionArea( + const PathWithLaneId & sparse_resample_path, + const std::pair & crosswalk_attention_range) const { - const auto & obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear; - if (planner_param_.stuck_vehicle_velocity < std::hypot(obj_vel.x, obj_vel.y)) { - return false; - } + const auto & ego_pos = planner_data_->current_odometry->pose.position; + const auto ego_polygon = createVehiclePolygon(planner_data_->vehicle_info_); - const auto & obj_pos = object.kinematics.initial_pose_with_covariance.pose.position; - const auto lateral_offset = calcLateralOffset(ego_path.points, obj_pos); - if (planner_param_.max_lateral_offset < std::abs(lateral_offset)) { - return false; + Polygon2d attention_area; + for (size_t j = 0; j < sparse_resample_path.points.size() - 1; ++j) { + const auto & p_ego_front = sparse_resample_path.points.at(j).point.pose; + const auto & p_ego_back = sparse_resample_path.points.at(j + 1).point.pose; + const auto front_length = + calcSignedArcLength(sparse_resample_path.points, ego_pos, p_ego_front.position); + const auto back_length = + calcSignedArcLength(sparse_resample_path.points, ego_pos, p_ego_back.position); + + if (back_length < crosswalk_attention_range.first) { + continue; + } + + if (crosswalk_attention_range.second < front_length) { + break; + } + + const auto ego_one_step_polygon = createOneStepPolygon(p_ego_front, p_ego_back, ego_polygon); + + debug_data_.ego_polygons.push_back(toGeometryPointVector(ego_one_step_polygon, ego_pos.z)); + + std::vector unions; + bg::union_(attention_area, ego_one_step_polygon, unions); + if (!unions.empty()) { + attention_area = unions.front(); + bg::correct(attention_area); + } } + return attention_area; +} + +bool CrosswalkModule::isStuckVehicle( + const PathWithLaneId & ego_path, const std::vector & objects, + const std::vector & path_intersects) const +{ if (path_intersects.size() < 2) { return false; } - const auto & ego_pos = planner_data_->current_odometry->pose.position; - const double near_attention_range = - calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back()); - const double far_attention_range = - near_attention_range + planner_param_.stuck_vehicle_attention_range; + for (const auto & object : objects) { + if (!isVehicle(object)) { + continue; + } + + const auto & obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear; + if (planner_param_.stuck_vehicle_velocity < std::hypot(obj_vel.x, obj_vel.y)) { + continue; + } + + const auto & obj_pos = object.kinematics.initial_pose_with_covariance.pose.position; + const auto lateral_offset = calcLateralOffset(ego_path.points, obj_pos); + if (planner_param_.max_lateral_offset < std::abs(lateral_offset)) { + continue; + } - const auto dist_ego2obj = calcSignedArcLength(ego_path.points, ego_pos, obj_pos); + const auto & ego_pos = planner_data_->current_odometry->pose.position; + const double near_attention_range = + calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back()); + const double far_attention_range = + near_attention_range + planner_param_.stuck_vehicle_attention_range; - return near_attention_range < dist_ego2obj && dist_ego2obj < far_attention_range; + const auto dist_ego2obj = calcSignedArcLength(ego_path.points, ego_pos, obj_pos); + + if (near_attention_range < dist_ego2obj && dist_ego2obj < far_attention_range) { + return true; + } + } + + return false; } bool CrosswalkModule::isRedSignalForPedestrians() const @@ -970,4 +963,59 @@ geometry_msgs::msg::Polygon CrosswalkModule::createVehiclePolygon( return polygon; } + +boost::optional CrosswalkModule::generateStopFactorInfo( + const boost::optional & nearest_stop_factor, + const boost::optional & default_stop_factor) const +{ + if (nearest_stop_factor) { + return StopFactorInfo{*nearest_stop_factor, StopFactorInfo::Type::NEAREST}; + } + if (default_stop_factor) { + return StopFactorInfo{*default_stop_factor, StopFactorInfo::Type::DEFAULT}; + } + return {}; +} + +void CrosswalkModule::planGo( + const boost::optional & stop_factor_info, PathWithLaneId & ego_path) +{ + const auto & ego_pos = planner_data_->current_odometry->pose.position; + + if (!stop_factor_info) { + setDistance(std::numeric_limits::lowest()); + return; + } + + if (stop_factor_info->type == StopFactorInfo::Type::NEAREST) { + // Plan slow down + const auto target_velocity = + calcTargetVelocity(stop_factor_info->stop_factor.stop_pose.position, ego_path); + insertDecelPointWithDebugInfo( + stop_factor_info->stop_factor.stop_pose.position, + std::max(planner_param_.min_slow_down_velocity, target_velocity), ego_path); + return; + } + + // NOTE: if (stop_factor_info->type == StopFactorInfo::Type::DEFAULT) + const auto crosswalk_distance = calcSignedArcLength( + ego_path.points, ego_pos, getPoint(stop_factor_info->stop_factor.stop_pose.position)); + setDistance(crosswalk_distance); +} + +bool CrosswalkModule::planStop( + const boost::optional & stop_factor_info, PathWithLaneId & ego_path, + StopReason * stop_reason) +{ + if (!stop_factor_info) { + return false; + } + + insertDecelPointWithDebugInfo(stop_factor_info->stop_factor.stop_pose.position, 0.0, ego_path); + planning_utils::appendStopReason(stop_factor_info->stop_factor, stop_reason); + velocity_factor_.set( + ego_path.points, planner_data_->current_odometry->pose, stop_factor_info->stop_factor.stop_pose, + VelocityFactor::UNKNOWN); + return true; +} } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 2edade84bb87b..82336dcbec944 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -103,13 +103,13 @@ class CrosswalkModule : public SceneModuleInterface motion_utils::VirtualWalls createVirtualWalls() override; private: - int64_t module_id_; + const int64_t module_id_; - boost::optional> findRTCStopPointWithFactor( + boost::optional findDefaultStopFactor( const PathWithLaneId & ego_path, const std::vector & path_intersects); - boost::optional> findNearestStopPointWithFactor( + boost::optional findNearestStopFactor( const PathWithLaneId & ego_path, const std::vector & path_intersects); @@ -129,8 +129,9 @@ class CrosswalkModule : public SceneModuleInterface const geometry_msgs::msg::Point & stop_point, const float target_velocity, PathWithLaneId & output); - void clampAttentionRangeByNeighborCrosswalks( - const PathWithLaneId & ego_path, double & near_attention_range, double & far_attention_range); + std::pair clampAttentionRangeByNeighborCrosswalks( + const PathWithLaneId & ego_path, const double near_attention_range, + const double far_attention_range); CollisionPoint createCollisionPoint( const geometry_msgs::msg::Point & nearest_collision_point, const double dist_ego2cp, @@ -139,14 +140,18 @@ class CrosswalkModule : public SceneModuleInterface CollisionPointState getCollisionPointState(const double ttc, const double ttv) const; - bool applySafetySlowDownSpeed( + void applySafetySlowDownSpeed( PathWithLaneId & output, const std::vector & path_intersects); float calcTargetVelocity( const geometry_msgs::msg::Point & stop_point, const PathWithLaneId & ego_path) const; + Polygon2d getAttentionArea( + const PathWithLaneId & sparse_resample_path, + const std::pair & crosswalk_attention_range) const; + bool isStuckVehicle( - const PathWithLaneId & ego_path, const PredictedObject & object, + const PathWithLaneId & ego_path, const std::vector & objects, const std::vector & path_intersects) const; bool isRedSignalForPedestrians() const; @@ -161,19 +166,35 @@ class CrosswalkModule : public SceneModuleInterface static geometry_msgs::msg::Polygon createVehiclePolygon( const vehicle_info_util::VehicleInfo & vehicle_info); + boost::optional generateStopFactorInfo( + const boost::optional & nearest_stop_factor, + const boost::optional & default_stop_factor) const; + + void planGo(const boost::optional & stop_factor_info, PathWithLaneId & ego_path); + bool planStop( + const boost::optional & stop_factor_info, PathWithLaneId & ego_path, + StopReason * stop_reason); + + void recordTime(const int step_num) + { + RCLCPP_INFO_EXPRESSION( + logger_, planner_param_.show_processing_time, "- step%d: %f ms", step_num, + stop_watch_.toc("total_processing_time", false)); + } + lanelet::ConstLanelet crosswalk_; lanelet::ConstLineStrings3d stop_lines_; // Parameter - PlannerParam planner_param_; + const PlannerParam planner_param_; // Ignore objects std::unordered_map stopped_objects_; std::unordered_map ignore_objects_; // Debug - DebugData debug_data_; + mutable DebugData debug_data_; // Stop watch StopWatch stop_watch_; @@ -182,7 +203,7 @@ class CrosswalkModule : public SceneModuleInterface bool passed_safety_slow_point_; // whether use regulatory element - bool use_regulatory_element_; + const bool use_regulatory_element_; }; } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_walkway.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_walkway.cpp index 119591c225e36..f08d67c74c653 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_walkway.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_walkway.cpp @@ -91,8 +91,7 @@ bool WalkwayModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_ { const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; - debug_data_ = DebugData(); - debug_data_.base_link2front = base_link2front; + debug_data_ = DebugData(planner_data_); *stop_reason = planning_utils::initializeStopReason(StopReason::WALKWAY); const auto input = *path; diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_walkway.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_walkway.hpp index a32038e17fab4..761139d7e1106 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_walkway.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_walkway.hpp @@ -55,7 +55,7 @@ class WalkwayModule : public SceneModuleInterface motion_utils::VirtualWalls createVirtualWalls() override; private: - int64_t module_id_; + const int64_t module_id_; [[nodiscard]] boost::optional> getStopLine( const PathWithLaneId & ego_path, bool & exist_stopline_in_map, @@ -71,13 +71,13 @@ class WalkwayModule : public SceneModuleInterface State state_; // Parameter - PlannerParam planner_param_; + const PlannerParam planner_param_; // Debug DebugData debug_data_; // flag to use regulatory element - bool use_regulatory_element_; + const bool use_regulatory_element_; }; } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_crosswalk_module/src/util.hpp b/planning/behavior_velocity_crosswalk_module/src/util.hpp index d585cf521dc73..65cf3fa0e046c 100644 --- a/planning/behavior_velocity_crosswalk_module/src/util.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/util.hpp @@ -32,13 +32,16 @@ #include #include +#include namespace behavior_velocity_planner { using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using autoware_auto_planning_msgs::msg::PathWithLaneId; +using tier4_autoware_utils::createPoint; using tier4_autoware_utils::Point2d; +using tier4_planning_msgs::msg::StopFactor; enum class CollisionPointState { YIELD, EGO_PASS_FIRST, EGO_PASS_LATER, IGNORE }; @@ -50,11 +53,24 @@ struct CollisionPoint CollisionPointState state{CollisionPointState::EGO_PASS_FIRST}; }; +struct StopFactorInfo +{ + enum class Type { NEAREST = 0, DEFAULT }; + StopFactor stop_factor; + Type type; +}; + struct DebugData { + DebugData() = default; + explicit DebugData(const std::shared_ptr planner_data) + : base_link2front(planner_data->vehicle_info_.max_longitudinal_offset_m) + { + } + bool ignore_crosswalk{false}; double base_link2front; - double stop_judge_range; + double stop_judge_range{}; geometry_msgs::msg::Pose first_stop_pose; geometry_msgs::msg::Point nearest_collision_point; @@ -68,8 +84,8 @@ struct DebugData std::vector slow_poses; std::vector stop_factor_points; std::vector crosswalk_polygon; - std::vector ego_polygons; - std::vector obj_polygons; + std::vector> ego_polygons; + std::vector> obj_polygons; }; std::vector getPolygonIntersects( From 850eef632eda77f68f0b44936e2fc31cb0ffabc6 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 10 Jul 2023 11:22:12 +0900 Subject: [PATCH 112/118] refactor(obstacle_avoidance_planner): move the elastic band smoothing to a new package (#4114) * Add path_smoothing package Signed-off-by: Maxime CLEMENT * Add elastic band smoother node Signed-off-by: Maxime CLEMENT * Add Debug section to elastic band documentation Signed-off-by: Maxime CLEMENT * Remove elastic band from the obstacle_avoidance_planner Signed-off-by: Maxime CLEMENT * Move elastic band debug images to the path_smoothing package Signed-off-by: Maxime CLEMENT * Update launch files to run the elastic_band_smoother Signed-off-by: Maxime CLEMENT * Set path topic names based on the path_smoother_type argument Signed-off-by: Maxime CLEMENT * Publish path with backward paths Signed-off-by: Maxime CLEMENT * Rename path_smoothing -> path_smoother Signed-off-by: Maxime CLEMENT --------- Signed-off-by: Maxime CLEMENT --- .../launch/planning.launch.xml | 5 +- .../motion_planning/motion_planning.launch.py | 46 ++- .../scenario_planning.launch.xml | 4 +- .../motion_velocity_smoother.launch.xml | 6 +- .../obstacle_avoidance_planner/CMakeLists.txt | 1 - planning/obstacle_avoidance_planner/README.md | 17 +- .../obstacle_avoidance_planner.param.yaml | 32 +- .../obstacle_avoidance_planner/docs/debug.md | 19 +- .../obstacle_avoidance_planner/node.hpp | 3 - .../src/debug_marker.cpp | 1 - .../obstacle_avoidance_planner/src/node.cpp | 23 +- .../src/utils/geometry_utils.cpp | 1 - .../src/utils/trajectory_utils.cpp | 1 - planning/path_smoother/CMakeLists.txt | 42 ++ planning/path_smoother/README.md | 11 + .../config/elastic_band_smoother.param.yaml | 37 ++ .../docs/eb.md | 12 + .../include/path_smoother/common_structs.hpp | 126 ++++++ .../include/path_smoother/elastic_band.hpp} | 20 +- .../path_smoother/elastic_band_smoother.hpp | 119 ++++++ .../include/path_smoother/type_alias.hpp | 44 +++ .../path_smoother/utils/geometry_utils.hpp | 35 ++ .../path_smoother/utils/trajectory_utils.hpp | 177 +++++++++ .../launch/elastic_band_smoother.launch.xml | 17 + .../debug/eb_fixed_traj_visualization.png | Bin .../media/debug/eb_traj_visualization.png | Bin .../media/eb.svg | 0 .../media/eb_constraint.svg | 0 planning/path_smoother/package.xml | 41 ++ .../src/elastic_band.cpp} | 84 ++-- .../src/elastic_band_smoother.cpp | 373 ++++++++++++++++++ .../src/utils/trajectory_utils.cpp | 109 +++++ .../test_path_smoother_node_interface.cpp | 62 +++ 33 files changed, 1323 insertions(+), 145 deletions(-) create mode 100644 planning/path_smoother/CMakeLists.txt create mode 100644 planning/path_smoother/README.md create mode 100644 planning/path_smoother/config/elastic_band_smoother.param.yaml rename planning/{obstacle_avoidance_planner => path_smoother}/docs/eb.md (95%) create mode 100644 planning/path_smoother/include/path_smoother/common_structs.hpp rename planning/{obstacle_avoidance_planner/include/obstacle_avoidance_planner/eb_path_smoother.hpp => path_smoother/include/path_smoother/elastic_band.hpp} (85%) create mode 100644 planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp create mode 100644 planning/path_smoother/include/path_smoother/type_alias.hpp create mode 100644 planning/path_smoother/include/path_smoother/utils/geometry_utils.hpp create mode 100644 planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp create mode 100644 planning/path_smoother/launch/elastic_band_smoother.launch.xml rename planning/{obstacle_avoidance_planner => path_smoother}/media/debug/eb_fixed_traj_visualization.png (100%) rename planning/{obstacle_avoidance_planner => path_smoother}/media/debug/eb_traj_visualization.png (100%) rename planning/{obstacle_avoidance_planner => path_smoother}/media/eb.svg (100%) rename planning/{obstacle_avoidance_planner => path_smoother}/media/eb_constraint.svg (100%) create mode 100644 planning/path_smoother/package.xml rename planning/{obstacle_avoidance_planner/src/eb_path_smoother.cpp => path_smoother/src/elastic_band.cpp} (80%) create mode 100644 planning/path_smoother/src/elastic_band_smoother.cpp create mode 100644 planning/path_smoother/src/utils/trajectory_utils.cpp create mode 100644 planning/path_smoother/test/test_path_smoother_node_interface.cpp diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml index e406eb5653b0a..7e78c8842f7df 100644 --- a/launch/tier4_planning_launch/launch/planning.launch.xml +++ b/launch/tier4_planning_launch/launch/planning.launch.xml @@ -4,7 +4,8 @@ - + + @@ -43,7 +44,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index 94461c1748439..34ad4659b5ece 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -21,6 +21,7 @@ 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 @@ -41,6 +42,39 @@ def launch_setup(context, *args, **kwargs): 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" @@ -52,7 +86,7 @@ def launch_setup(context, *args, **kwargs): name="obstacle_avoidance_planner", namespace="", remappings=[ - ("~/input/path", LaunchConfiguration("input_path_topic")), + ("~/input/path", planner_input_path_topic), ("~/input/odometry", "/localization/kinematic_state"), ("~/output/path", "obstacle_avoidance_planner/trajectory"), ], @@ -73,7 +107,7 @@ def launch_setup(context, *args, **kwargs): name="path_sampler", namespace="", remappings=[ - ("~/input/path", LaunchConfiguration("input_path_topic")), + ("~/input/path", planner_input_path_topic), ("~/input/odometry", "/localization/kinematic_state"), ("~/output/path", "obstacle_avoidance_planner/trajectory"), ], @@ -251,6 +285,12 @@ def launch_setup(context, *args, **kwargs): 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, @@ -272,6 +312,7 @@ def launch_setup(context, *args, **kwargs): group = GroupAction( [ container, + smoother_loader, obstacle_avoidance_planner_loader, path_sampler_loader, obstacle_stop_planner_loader, @@ -309,6 +350,7 @@ def add_launch_arg(name: str, default_value=None, description=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") 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 dbeaae2df622b..665bd82423ea6 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 @@ -27,11 +27,11 @@ - + - + diff --git a/planning/motion_velocity_smoother/launch/motion_velocity_smoother.launch.xml b/planning/motion_velocity_smoother/launch/motion_velocity_smoother.launch.xml index 23490652ff072..78bddc2b81f4f 100644 --- a/planning/motion_velocity_smoother/launch/motion_velocity_smoother.launch.xml +++ b/planning/motion_velocity_smoother/launch/motion_velocity_smoother.launch.xml @@ -9,11 +9,11 @@ - + - + @@ -21,7 +21,7 @@ - + diff --git a/planning/obstacle_avoidance_planner/CMakeLists.txt b/planning/obstacle_avoidance_planner/CMakeLists.txt index 883ce473722fd..2662555d92341 100644 --- a/planning/obstacle_avoidance_planner/CMakeLists.txt +++ b/planning/obstacle_avoidance_planner/CMakeLists.txt @@ -22,7 +22,6 @@ ament_auto_add_library(obstacle_avoidance_planner SHARED src/node.cpp # core algorithms src/replan_checker.cpp - src/eb_path_smoother.cpp src/mpt_optimizer.cpp src/state_equation_generator.cpp # debug marker diff --git a/planning/obstacle_avoidance_planner/README.md b/planning/obstacle_avoidance_planner/README.md index 36a692ca33735..c079a57c3a2da 100644 --- a/planning/obstacle_avoidance_planner/README.md +++ b/planning/obstacle_avoidance_planner/README.md @@ -9,7 +9,6 @@ Only position and orientation of trajectory are updated in this module, and velo This package is able to -- make the trajectory smooth - make the trajectory inside the drivable area as much as possible - NOTE: Static obstacles to avoid can be removed from the drivable area. - insert stop point before the planned footprint will be outside the drivable area @@ -109,13 +108,6 @@ max_path_shape_around_ego_lat_dist - The optimization is skipped for a while sine the optimization is sometimes heavy. - The input path changes laterally longer than `replan.max_path_shape_around_ego_lat_dist` in one cycle. (default: 2.0) -### getEBTrajectory - -The latter optimization (model predictive trajectory) assumes that the reference path is smooth enough. -This function makes the input path smooth by elastic band. - -More details about elastic band can be seen [here](docs/eb.md). - ### getModelPredictiveTrajectory This module makes the trajectory kinematically-feasible and collision-free. @@ -212,17 +204,14 @@ Although it has a cons to converge to the local minima, it can get a good soluti ### Robustness -- Check if the trajectory before EB, after EB, or after MPT is not robust - - if the trajectory before EB is not robust - - if the trajectory after EB is not robust +- Check if the trajectory before or after MPT is not robust + - if the trajectory before MPT is not robust - if the trajectory after MPT is not robust - make `mpt.weight.steer_input_weight` or `mpt.weight.steer_rate_weight` larger, which are stability of steering wheel along the trajectory. ### Other options -- `option.enable_skip_optimization` skips EB and MPT optimization. -- `option.enable_smoothing` enables EB which is smoothing the trajectory for MPT. - - EB is not required if the reference path for MPT is smooth enough and does not change its shape suddenly +- `option.enable_skip_optimization` skips MPT optimization. - `option.enable_calculation_time_info` enables showing each calculation time for functions and total calculation time on the terminal. - `option.enable_outside_drivable_area_stop` enables stopping just before the generated trajectory point will be outside the drivable area. diff --git a/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml b/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml index 3f4655b78229c..624ba4defc8a0 100644 --- a/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml +++ b/planning/obstacle_avoidance_planner/config/obstacle_avoidance_planner.param.yaml @@ -1,8 +1,7 @@ /**: ros__parameters: option: - enable_smoothing: true # enable path smoothing by elastic band - enable_skip_optimization: false # skip elastic band and model predictive trajectory + enable_skip_optimization: false # skip model predictive trajectory enable_reset_prev_optimization: false # If true, optimization has no fix constraint to the previous result. enable_outside_drivable_area_stop: true # stop if the ego's trajectory footprint is outside the drivable area use_footprint_polygon_for_outside_drivable_area_check: false # If false, only the footprint's corner points are considered. @@ -30,35 +29,6 @@ max_goal_moving_dist: 15.0 # threshold of goal's moving distance for replan [m] max_delta_time_sec: 1.0 # threshold of delta time for replan [second] - # eb param - eb: - option: - enable_warm_start: true - enable_optimization_validation: false - - common: - num_points: 100 # number of points for optimization [-] - delta_arc_length: 1.0 # delta arc length for optimization [m] - - clearance: - num_joint_points: 3 # number of joint points (joint means connecting fixing and smoothing) - - clearance_for_fix: 0.0 # maximum optimizing range when applying fixing - clearance_for_joint: 0.1 # maximum optimizing range when applying jointing - clearance_for_smooth: 0.1 # maximum optimizing range when applying smoothing - - weight: - smooth_weight: 1.0 - lat_error_weight: 0.001 - - qp: - max_iteration: 10000 # max iteration when solving QP - eps_abs: 1.0e-7 # eps abs when solving OSQP - eps_rel: 1.0e-7 # eps rel when solving OSQP - - validation: # if enable_optimization_validation is true - max_error: 3.0 # [m] - # mpt param mpt: option: diff --git a/planning/obstacle_avoidance_planner/docs/debug.md b/planning/obstacle_avoidance_planner/docs/debug.md index f5bcf56a6138a..293f5b2ec1a40 100644 --- a/planning/obstacle_avoidance_planner/docs/debug.md +++ b/planning/obstacle_avoidance_planner/docs/debug.md @@ -2,7 +2,7 @@ ## Debug visualization -The visualization markers of the planning flow (Input, Elastic Band, Model Predictive Trajectory, and Output) are explained here. +The visualization markers of the planning flow (Input, Model Predictive Trajectory, and Output) are explained here. All the following markers can be visualized by @@ -38,18 +38,6 @@ The `vehicle_model` must be specified to make footprints with vehicle's size. ![drivable_area](../media/debug/drivable_area_visualization.png) -### Elastic Band (EB) - -- **EB Fixed Trajectory** - - The fixed trajectory points as a constraint of elastic band. - -![eb_fixed_traj](../media/debug/eb_fixed_traj_visualization.png) - -- **EB Trajectory** - - The optimized trajectory points by elastic band. - -![eb_traj](../media/debug/eb_traj_visualization.png) - ### Model Predictive Trajectory (MPT) - **MPT Reference Trajectory** @@ -100,7 +88,7 @@ The `vehicle_model` must be specified to make footprints with vehicle's size. ## Calculation time -The `obstacle_avoidance_planner` consists of many functions such as boundaries' width calculation, reference path smoothing, collision-free planning, etc. +The `obstacle_avoidance_planner` consists of many functions such as boundaries' width calculation, collision-free planning, etc. We can see the calculation time for each function as follows. ### Raw data @@ -169,8 +157,6 @@ For your information, the following functions for optimization and its initializ - MPT - `initOsqp` - `solveOsqp` -- EB - - `optimizeTrajectory` ### When a part of the trajectory has high curvature @@ -186,5 +172,4 @@ Please check if there is something weird by the visualization. Some of the following may have an issue. Please check if there is something weird by the visualization. -- EB Trajectory - Vehicle Circles on Trajectory diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp index b51b35fa99d49..efec8afadc56d 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp @@ -17,7 +17,6 @@ #include "motion_utils/motion_utils.hpp" #include "obstacle_avoidance_planner/common_structs.hpp" -#include "obstacle_avoidance_planner/eb_path_smoother.hpp" #include "obstacle_avoidance_planner/mpt_optimizer.hpp" #include "obstacle_avoidance_planner/replan_checker.hpp" #include "obstacle_avoidance_planner/type_alias.hpp" @@ -64,14 +63,12 @@ class ObstacleAvoidancePlanner : public rclcpp::Node bool enable_pub_debug_marker_; bool enable_debug_info_; bool enable_outside_drivable_area_stop_; - bool enable_smoothing_; bool enable_skip_optimization_; bool enable_reset_prev_optimization_; bool use_footprint_polygon_for_outside_drivable_area_check_; // core algorithms std::shared_ptr replan_checker_ptr_{nullptr}; - std::shared_ptr eb_path_smoother_ptr_{nullptr}; std::shared_ptr mpt_optimizer_ptr_{nullptr}; // parameters diff --git a/planning/obstacle_avoidance_planner/src/debug_marker.cpp b/planning/obstacle_avoidance_planner/src/debug_marker.cpp index 2b0ddbed8fbba..c78358a20bb53 100644 --- a/planning/obstacle_avoidance_planner/src/debug_marker.cpp +++ b/planning/obstacle_avoidance_planner/src/debug_marker.cpp @@ -15,7 +15,6 @@ #include "obstacle_avoidance_planner/debug_marker.hpp" #include "motion_utils/motion_utils.hpp" -#include "obstacle_avoidance_planner/eb_path_smoother.hpp" #include "obstacle_avoidance_planner/mpt_optimizer.hpp" #include "visualization_msgs/msg/marker_array.hpp" diff --git a/planning/obstacle_avoidance_planner/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index 25b65b92c0924..c1d931dd54e20 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -86,7 +86,6 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n // parameter for option enable_outside_drivable_area_stop_ = declare_parameter("option.enable_outside_drivable_area_stop"); - enable_smoothing_ = declare_parameter("option.enable_smoothing"); enable_skip_optimization_ = declare_parameter("option.enable_skip_optimization"); enable_reset_prev_optimization_ = declare_parameter("option.enable_reset_prev_optimization"); @@ -110,8 +109,6 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n // create core algorithm pointers with parameter declaration replan_checker_ptr_ = std::make_shared(this, ego_nearest_param_); - eb_path_smoother_ptr_ = std::make_shared( - this, enable_debug_info_, ego_nearest_param_, traj_param_, time_keeper_ptr_); mpt_optimizer_ptr_ = std::make_shared( this, enable_debug_info_, ego_nearest_param_, vehicle_info_, traj_param_, debug_data_ptr_, time_keeper_ptr_); @@ -136,7 +133,6 @@ rcl_interfaces::msg::SetParametersResult ObstacleAvoidancePlanner::onParam( // parameters for option updateParam( parameters, "option.enable_outside_drivable_area_stop", enable_outside_drivable_area_stop_); - updateParam(parameters, "option.enable_smoothing", enable_smoothing_); updateParam(parameters, "option.enable_skip_optimization", enable_skip_optimization_); updateParam( parameters, "option.enable_reset_prev_optimization", enable_reset_prev_optimization_); @@ -161,7 +157,6 @@ rcl_interfaces::msg::SetParametersResult ObstacleAvoidancePlanner::onParam( // parameters for core algorithms replan_checker_ptr_->onParam(parameters); - eb_path_smoother_ptr_->onParam(parameters); mpt_optimizer_ptr_->onParam(parameters); // reset planners @@ -177,7 +172,6 @@ void ObstacleAvoidancePlanner::initializePlanning() { RCLCPP_INFO(get_logger(), "Initialize planning"); - eb_path_smoother_ptr_->initialize(enable_debug_info_, traj_param_); mpt_optimizer_ptr_->initialize(enable_debug_info_, traj_param_); resetPreviousData(); @@ -185,7 +179,6 @@ void ObstacleAvoidancePlanner::initializePlanning() void ObstacleAvoidancePlanner::resetPreviousData() { - eb_path_smoother_ptr_->resetPreviousData(); mpt_optimizer_ptr_->resetPreviousData(); prev_optimized_traj_points_ptr_ = nullptr; @@ -287,7 +280,7 @@ std::vector ObstacleAvoidancePlanner::generateOptimizedTrajecto const auto & input_traj_points = planner_data.traj_points; - // 1. calculate trajectory with EB and MPT + // 1. calculate trajectory with MPT // NOTE: This function may return previously optimized trajectory points. // Also, velocity on some points will not be updated for a logic purpose. auto optimized_traj_points = optimizeTrajectory(planner_data); @@ -333,21 +326,15 @@ std::vector ObstacleAvoidancePlanner::optimizeTrajectory( return p.traj_points; } - // 2. smooth trajectory with elastic band - const auto eb_traj = - enable_smoothing_ ? eb_path_smoother_ptr_->getEBTrajectory(planner_data) : p.traj_points; - if (!eb_traj) { - return getPrevOptimizedTrajectory(p.traj_points); - } - - // 3. make trajectory kinematically-feasible and collision-free (= inside the drivable area) + // 2. make trajectory kinematically-feasible and collision-free (= inside the drivable area) // with model predictive trajectory - const auto mpt_traj = mpt_optimizer_ptr_->getModelPredictiveTrajectory(planner_data, *eb_traj); + const auto mpt_traj = + mpt_optimizer_ptr_->getModelPredictiveTrajectory(planner_data, p.traj_points); if (!mpt_traj) { return getPrevOptimizedTrajectory(p.traj_points); } - // 4. make prev trajectories + // 3. make prev trajectories prev_optimized_traj_points_ptr_ = std::make_shared>(*mpt_traj); time_keeper_ptr_->toc(__func__, " "); diff --git a/planning/obstacle_avoidance_planner/src/utils/geometry_utils.cpp b/planning/obstacle_avoidance_planner/src/utils/geometry_utils.cpp index e471baf1951db..67b500571fa06 100644 --- a/planning/obstacle_avoidance_planner/src/utils/geometry_utils.cpp +++ b/planning/obstacle_avoidance_planner/src/utils/geometry_utils.cpp @@ -15,7 +15,6 @@ #include "obstacle_avoidance_planner/utils/geometry_utils.hpp" #include "motion_utils/motion_utils.hpp" -#include "obstacle_avoidance_planner/eb_path_smoother.hpp" #include "obstacle_avoidance_planner/mpt_optimizer.hpp" #include "tf2/utils.h" diff --git a/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp b/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp index 8a4ab4384f7eb..8390cf379586b 100644 --- a/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp +++ b/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp @@ -15,7 +15,6 @@ #include "obstacle_avoidance_planner/utils/trajectory_utils.hpp" #include "motion_utils/motion_utils.hpp" -#include "obstacle_avoidance_planner/eb_path_smoother.hpp" #include "obstacle_avoidance_planner/mpt_optimizer.hpp" #include "obstacle_avoidance_planner/utils/geometry_utils.hpp" #include "tf2/utils.h" diff --git a/planning/path_smoother/CMakeLists.txt b/planning/path_smoother/CMakeLists.txt new file mode 100644 index 0000000000000..30f06f7b87f81 --- /dev/null +++ b/planning/path_smoother/CMakeLists.txt @@ -0,0 +1,42 @@ +cmake_minimum_required(VERSION 3.14) +project(path_smoother) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Eigen3 REQUIRED) + +ament_auto_add_library(path_smoother SHARED + # node + src/elastic_band_smoother.cpp + # algorithms + src/elastic_band.cpp + # utils + src/utils/trajectory_utils.cpp +) + +target_include_directories(path_smoother + SYSTEM PUBLIC + ${EIGEN3_INCLUDE_DIR} +) + +# register node +rclcpp_components_register_node(path_smoother + PLUGIN "path_smoother::ElasticBandSmoother" + EXECUTABLE elastic_band_smoother +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/test_${PROJECT_NAME}_node_interface.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) +endif() + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/planning/path_smoother/README.md b/planning/path_smoother/README.md new file mode 100644 index 0000000000000..3521ba754081f --- /dev/null +++ b/planning/path_smoother/README.md @@ -0,0 +1,11 @@ +# Path Smoothing + +## Purpose + +This package contains code to smooth a path or trajectory. + +## Features + +### Elastic Band + +More details about the elastic band can be found [here](docs/eb.md). diff --git a/planning/path_smoother/config/elastic_band_smoother.param.yaml b/planning/path_smoother/config/elastic_band_smoother.param.yaml new file mode 100644 index 0000000000000..730bc3053e7a3 --- /dev/null +++ b/planning/path_smoother/config/elastic_band_smoother.param.yaml @@ -0,0 +1,37 @@ +/**: + ros__parameters: + common: + # output + output_delta_arc_length: 0.5 # delta arc length for output trajectory [m] + output_backward_traj_length: 5.0 # backward length for backward trajectory from base_link [m] + # elastic band + elastic_band: + option: + enable_warm_start: true + enable_optimization_validation: false + + common: + num_points: 100 # number of points for optimization [-] + delta_arc_length: 1.0 # delta arc length for optimization [m] + + clearance: + num_joint_points: 3 # number of joint points (joint means connecting fixing and smoothing) + + clearance_for_fix: 0.0 # maximum optimizing range when applying fixing + clearance_for_joint: 0.1 # maximum optimizing range when applying jointing + clearance_for_smooth: 0.1 # maximum optimizing range when applying smoothing + + weight: + smooth_weight: 1.0 + lat_error_weight: 0.001 + + qp: + max_iteration: 10000 # max iteration when solving QP + eps_abs: 1.0e-7 # eps abs when solving OSQP + eps_rel: 1.0e-7 # eps rel when solving OSQP + + validation: # if enable_optimization_validation is true + max_error: 3.0 # [m] + # nearest search + ego_nearest_dist_threshold: 3.0 # [m] + ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg] diff --git a/planning/obstacle_avoidance_planner/docs/eb.md b/planning/path_smoother/docs/eb.md similarity index 95% rename from planning/obstacle_avoidance_planner/docs/eb.md rename to planning/path_smoother/docs/eb.md index 7efb1edaa62db..2c232cfa4de81 100644 --- a/planning/obstacle_avoidance_planner/docs/eb.md +++ b/planning/path_smoother/docs/eb.md @@ -159,3 +159,15 @@ $$ In addition, the beginning point is fixed and the end point as well if the end point is considered as the goal. This constraint can be applied with the upper equation by changing the distance that each point can move. + +## Debug + +- **EB Fixed Trajectory** + - The fixed trajectory points as a constraint of elastic band. + +![eb_fixed_traj](../media/debug/eb_fixed_traj_visualization.png) + +- **EB Trajectory** + - The optimized trajectory points by elastic band. + +![eb_traj](../media/debug/eb_traj_visualization.png) diff --git a/planning/path_smoother/include/path_smoother/common_structs.hpp b/planning/path_smoother/include/path_smoother/common_structs.hpp new file mode 100644 index 0000000000000..17c6bc6f162af --- /dev/null +++ b/planning/path_smoother/include/path_smoother/common_structs.hpp @@ -0,0 +1,126 @@ +// 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 PATH_SMOOTHER__COMMON_STRUCTS_HPP_ +#define PATH_SMOOTHER__COMMON_STRUCTS_HPP_ + +#include "path_smoother/type_alias.hpp" +#include "rclcpp/rclcpp.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#include +#include +#include +#include + +namespace path_smoother +{ +struct Bounds; + +struct PlannerData +{ + // input + Header header; + std::vector traj_points; // converted from the input path + std::vector left_bound; + std::vector right_bound; + + // ego + geometry_msgs::msg::Pose ego_pose; + double ego_vel{}; +}; + +struct TimeKeeper +{ + void init() { accumulated_msg = "\n"; } + + template + TimeKeeper & operator<<(const T & msg) + { + latest_stream << msg; + return *this; + } + + void endLine() + { + const auto msg = latest_stream.str(); + accumulated_msg += msg + "\n"; + latest_stream.str(""); + } + + void tic(const std::string & func_name) { stop_watch_.tic(func_name); } + + void toc(const std::string & func_name, const std::string & white_spaces) + { + const double elapsed_time = stop_watch_.toc(func_name); + *this << white_spaces << func_name << ":= " << elapsed_time << " [ms]"; + endLine(); + } + + std::string getLog() const { return accumulated_msg; } + + std::string accumulated_msg = "\n"; + std::stringstream latest_stream; + + tier4_autoware_utils::StopWatch< + std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> + stop_watch_; +}; + +struct CommonParam +{ + CommonParam() = default; + explicit CommonParam(rclcpp::Node * node) + { + output_backward_traj_length = + node->declare_parameter("common.output_backward_traj_length"); + output_delta_arc_length = node->declare_parameter("common.output_delta_arc_length"); + } + + void onParam(const std::vector & parameters) + { + using tier4_autoware_utils::updateParam; + + // common + updateParam( + parameters, "common.output_backward_traj_length", output_backward_traj_length); + updateParam(parameters, "common.output_delta_arc_length", output_delta_arc_length); + } + + double output_delta_arc_length; + double output_backward_traj_length; +}; + +struct EgoNearestParam +{ + EgoNearestParam() = default; + explicit EgoNearestParam(rclcpp::Node * node) + { + dist_threshold = node->declare_parameter("ego_nearest_dist_threshold"); + yaw_threshold = node->declare_parameter("ego_nearest_yaw_threshold"); + } + + void onParam(const std::vector & parameters) + { + using tier4_autoware_utils::updateParam; + updateParam(parameters, "ego_nearest_dist_threshold", dist_threshold); + updateParam(parameters, "ego_nearest_yaw_threshold", yaw_threshold); + } + + double dist_threshold{0.0}; + double yaw_threshold{0.0}; +}; +} // namespace path_smoother + +#endif // PATH_SMOOTHER__COMMON_STRUCTS_HPP_ diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/eb_path_smoother.hpp b/planning/path_smoother/include/path_smoother/elastic_band.hpp similarity index 85% rename from planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/eb_path_smoother.hpp rename to planning/path_smoother/include/path_smoother/elastic_band.hpp index 24a419c8bef66..9b7c4e3deb458 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/eb_path_smoother.hpp +++ b/planning/path_smoother/include/path_smoother/elastic_band.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBSTACLE_AVOIDANCE_PLANNER__EB_PATH_SMOOTHER_HPP_ -#define OBSTACLE_AVOIDANCE_PLANNER__EB_PATH_SMOOTHER_HPP_ +#ifndef PATH_SMOOTHER__ELASTIC_BAND_HPP_ +#define PATH_SMOOTHER__ELASTIC_BAND_HPP_ -#include "obstacle_avoidance_planner/common_structs.hpp" -#include "obstacle_avoidance_planner/type_alias.hpp" #include "osqp_interface/osqp_interface.hpp" +#include "path_smoother/common_structs.hpp" +#include "path_smoother/type_alias.hpp" #include @@ -27,19 +27,19 @@ #include #include -namespace obstacle_avoidance_planner +namespace path_smoother { class EBPathSmoother { public: EBPathSmoother( rclcpp::Node * node, const bool enable_debug_info, const EgoNearestParam ego_nearest_param, - const TrajectoryParam & traj_param, const std::shared_ptr time_keeper_ptr); + const CommonParam & common_param, const std::shared_ptr time_keeper_ptr); std::optional> getEBTrajectory( const PlannerData & planner_data); - void initialize(const bool enable_debug_info, const TrajectoryParam & traj_param); + void initialize(const bool enable_debug_info, const CommonParam & common_param); void resetPreviousData(); void onParam(const std::vector & parameters); @@ -99,7 +99,7 @@ class EBPathSmoother // arguments bool enable_debug_info_; EgoNearestParam ego_nearest_param_; - TrajectoryParam traj_param_; + CommonParam common_param_; EBParam eb_param_; mutable std::shared_ptr time_keeper_ptr_; rclcpp::Logger logger_; @@ -128,6 +128,6 @@ class EBPathSmoother const std::vector & optimized_points, const std::vector & traj_points, const int pad_start_idx) const; }; -} // namespace obstacle_avoidance_planner +} // namespace path_smoother -#endif // OBSTACLE_AVOIDANCE_PLANNER__EB_PATH_SMOOTHER_HPP_ +#endif // PATH_SMOOTHER__ELASTIC_BAND_HPP_ diff --git a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp new file mode 100644 index 0000000000000..f89d34997a079 --- /dev/null +++ b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp @@ -0,0 +1,119 @@ +// 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 PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ +#define PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ + +#include "motion_utils/motion_utils.hpp" +#include "path_smoother/common_structs.hpp" +#include "path_smoother/elastic_band.hpp" +#include "path_smoother/type_alias.hpp" +#include "rclcpp/rclcpp.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#include +#include +#include +#include +#include + +namespace path_smoother +{ +class ElasticBandSmoother : public rclcpp::Node +{ +public: + explicit ElasticBandSmoother(const rclcpp::NodeOptions & node_options); + +protected: + class DrivingDirectionChecker + { + public: + bool isDrivingForward(const std::vector & path_points) + { + const auto is_driving_forward = motion_utils::isDrivingForward(path_points); + is_driving_forward_ = is_driving_forward ? is_driving_forward.get() : is_driving_forward_; + return is_driving_forward_; + } + + private: + bool is_driving_forward_{true}; + }; + DrivingDirectionChecker driving_direction_checker_{}; + + // argument variables + mutable std::shared_ptr time_keeper_ptr_{nullptr}; + + // flags for some functions + bool enable_debug_info_; + + // algorithms + std::shared_ptr eb_path_smoother_ptr_{nullptr}; + + // parameters + CommonParam common_param_{}; + EgoNearestParam ego_nearest_param_{}; + + // variables for subscribers + Odometry::SharedPtr ego_state_ptr_; + + // variables for previous information + std::shared_ptr> prev_optimized_traj_points_ptr_; + + // interface publisher + rclcpp::Publisher::SharedPtr traj_pub_; + rclcpp::Publisher::SharedPtr path_pub_; + + // interface subscriber + rclcpp::Subscription::SharedPtr path_sub_; + rclcpp::Subscription::SharedPtr odom_sub_; + + // debug publisher + rclcpp::Publisher::SharedPtr debug_extended_traj_pub_; + rclcpp::Publisher::SharedPtr debug_calculation_time_pub_; + + // parameter callback + rcl_interfaces::msg::SetParametersResult onParam( + const std::vector & parameters); + OnSetParametersCallbackHandle::SharedPtr set_param_res_; + + // subscriber callback function + void onPath(const Path::SharedPtr); + + // reset functions + void initializePlanning(); + void resetPreviousData(); + + // main functions + bool isDataReady(const Path & path, rclcpp::Clock clock) const; + PlannerData createPlannerData(const Path & path) const; + std::vector generateOptimizedTrajectory(const PlannerData & planner_data); + std::vector extendTrajectory( + const std::vector & traj_points, + const std::vector & optimized_points) const; + + // functions in generateOptimizedTrajectory + std::vector optimizeTrajectory(const PlannerData & planner_data); + std::vector getPrevOptimizedTrajectory( + const std::vector & traj_points) const; + void applyInputVelocity( + std::vector & output_traj_points, + const std::vector & input_traj_points, + const geometry_msgs::msg::Pose & ego_pose) const; + void insertZeroVelocityOutsideDrivableArea( + const PlannerData & planner_data, std::vector & traj_points) const; + void publishVirtualWall(const geometry_msgs::msg::Pose & stop_pose) const; +}; +} // namespace path_smoother + +#endif // PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ diff --git a/planning/path_smoother/include/path_smoother/type_alias.hpp b/planning/path_smoother/include/path_smoother/type_alias.hpp new file mode 100644 index 0000000000000..d6434c3935d1e --- /dev/null +++ b/planning/path_smoother/include/path_smoother/type_alias.hpp @@ -0,0 +1,44 @@ +// 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 PATH_SMOOTHER__TYPE_ALIAS_HPP_ +#define PATH_SMOOTHER__TYPE_ALIAS_HPP_ + +#include "autoware_auto_planning_msgs/msg/path.hpp" +#include "autoware_auto_planning_msgs/msg/path_point.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" +#include "geometry_msgs/msg/point.hpp" +#include "geometry_msgs/msg/pose.hpp" +#include "geometry_msgs/msg/twist.hpp" +#include "nav_msgs/msg/odometry.hpp" +#include "std_msgs/msg/header.hpp" +#include "tier4_debug_msgs/msg/string_stamped.hpp" + +namespace path_smoother +{ +// std_msgs +using std_msgs::msg::Header; +// planning +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; +// navigation +using nav_msgs::msg::Odometry; +// debug +using tier4_debug_msgs::msg::StringStamped; +} // namespace path_smoother + +#endif // PATH_SMOOTHER__TYPE_ALIAS_HPP_ diff --git a/planning/path_smoother/include/path_smoother/utils/geometry_utils.hpp b/planning/path_smoother/include/path_smoother/utils/geometry_utils.hpp new file mode 100644 index 0000000000000..39783b958fa61 --- /dev/null +++ b/planning/path_smoother/include/path_smoother/utils/geometry_utils.hpp @@ -0,0 +1,35 @@ +// 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 PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ +#define PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ + +#include + +namespace path_smoother +{ +namespace geometry_utils +{ +template +bool isSamePoint(const T1 & t1, const T2 & t2) +{ + const auto p1 = tier4_autoware_utils::getPoint(t1); + const auto p2 = tier4_autoware_utils::getPoint(t2); + + constexpr double epsilon = 1e-6; + return (std::abs(p1.x - p2.x) <= epsilon && std::abs(p1.y - p2.y) <= epsilon); +} +} // namespace geometry_utils +} // namespace path_smoother +#endif // PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ diff --git a/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp b/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp new file mode 100644 index 0000000000000..a8a97964f21a4 --- /dev/null +++ b/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp @@ -0,0 +1,177 @@ +// 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 PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ +#define PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ + +#include "interpolation/linear_interpolation.hpp" +#include "interpolation/spline_interpolation.hpp" +#include "interpolation/spline_interpolation_points_2d.hpp" +#include "motion_utils/trajectory/trajectory.hpp" +#include "path_smoother/common_structs.hpp" +#include "path_smoother/type_alias.hpp" + +#include + +#include "autoware_auto_planning_msgs/msg/path_point.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" + +#include "boost/optional/optional_fwd.hpp" + +#include +#include +#include +#include +#include + +namespace path_smoother +{ +namespace trajectory_utils +{ +template +std::optional getPointIndexAfter( + const T & points, const geometry_msgs::msg::Point & target_pos, const size_t target_seg_idx, + const double max_offset, const double min_offset) +{ + if (points.empty()) { + return std::nullopt; + } + + double sum_length = + -motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); + + std::optional output_idx{std::nullopt}; + + // search forward + if (sum_length < min_offset) { + for (size_t i = target_seg_idx + 1; i < points.size(); ++i) { + sum_length += tier4_autoware_utils::calcDistance2d(points.at(i), points.at(i - 1)); + if (min_offset < sum_length) { + output_idx = i - 1; + } + if (max_offset < sum_length) { + break; + } + } + return output_idx; + } + + // search backward + for (size_t i = target_seg_idx; 0 < i; + --i) { // NOTE: use size_t since i is always positive value + sum_length -= tier4_autoware_utils::calcDistance2d(points.at(i), points.at(i - 1)); + if (sum_length < min_offset) { + output_idx = i - 1; + } + if (sum_length < max_offset) { + break; + } + } + + return output_idx; +} + +template +TrajectoryPoint convertToTrajectoryPoint(const T & 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; +} + +template +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; +} + +template +size_t findEgoSegmentIndex( + const std::vector & points, const geometry_msgs::msg::Pose & ego_pose, + const EgoNearestParam & ego_nearest_param) +{ + return motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold); +} + +Trajectory createTrajectory( + const std_msgs::msg::Header & header, const std::vector & traj_points); + +Path create_path(Path path_msg, const std::vector & traj_points); + +std::vector resampleTrajectoryPoints( + const std::vector traj_points, const double interval); + +std::vector resampleTrajectoryPointsWithoutStopPoint( + const std::vector traj_points, const double interval); + +template +std::optional updateFrontPointForFix( + std::vector & points, std::vector & points_for_fix, const double delta_arc_length, + const EgoNearestParam & ego_nearest_param) +{ + // calculate front point to insert in points as a fixed point + const size_t front_seg_idx_for_fix = trajectory_utils::findEgoSegmentIndex( + points_for_fix, tier4_autoware_utils::getPose(points.front()), ego_nearest_param); + const size_t front_point_idx_for_fix = front_seg_idx_for_fix; + const auto & front_fix_point = points_for_fix.at(front_point_idx_for_fix); + + // check if the points_for_fix is longer in front than points + const double lon_offset_to_prev_front = + motion_utils::calcSignedArcLength(points, 0, front_fix_point.pose.position); + if (0 < lon_offset_to_prev_front) { + RCLCPP_WARN( + rclcpp::get_logger("path_smoother.trajectory_utils"), + "Fixed point will not be inserted due to the error during calculation."); + return std::nullopt; + } + + const double dist = tier4_autoware_utils::calcDistance2d(points.front(), front_fix_point); + + // check if deviation is not too large + constexpr double max_lat_error = 3.0; + if (max_lat_error < dist) { + RCLCPP_WARN( + rclcpp::get_logger("path_smoother.trajectory_utils"), + "New Fixed point is too far from points %f [m]", dist); + } + + // update pose + if (dist < delta_arc_length) { + // only pose is updated + points.front() = front_fix_point; + } else { + // add new front point + T new_front_point; + new_front_point = front_fix_point; + points.insert(points.begin(), new_front_point); + } + + return front_point_idx_for_fix; +} + +void insertStopPoint( + std::vector & traj_points, const geometry_msgs::msg::Pose & input_stop_pose, + const size_t stop_seg_idx); +} // namespace trajectory_utils +} // namespace path_smoother +#endif // PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ diff --git a/planning/path_smoother/launch/elastic_band_smoother.launch.xml b/planning/path_smoother/launch/elastic_band_smoother.launch.xml new file mode 100644 index 0000000000000..db91e1e2dd97d --- /dev/null +++ b/planning/path_smoother/launch/elastic_band_smoother.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/planning/obstacle_avoidance_planner/media/debug/eb_fixed_traj_visualization.png b/planning/path_smoother/media/debug/eb_fixed_traj_visualization.png similarity index 100% rename from planning/obstacle_avoidance_planner/media/debug/eb_fixed_traj_visualization.png rename to planning/path_smoother/media/debug/eb_fixed_traj_visualization.png diff --git a/planning/obstacle_avoidance_planner/media/debug/eb_traj_visualization.png b/planning/path_smoother/media/debug/eb_traj_visualization.png similarity index 100% rename from planning/obstacle_avoidance_planner/media/debug/eb_traj_visualization.png rename to planning/path_smoother/media/debug/eb_traj_visualization.png diff --git a/planning/obstacle_avoidance_planner/media/eb.svg b/planning/path_smoother/media/eb.svg similarity index 100% rename from planning/obstacle_avoidance_planner/media/eb.svg rename to planning/path_smoother/media/eb.svg diff --git a/planning/obstacle_avoidance_planner/media/eb_constraint.svg b/planning/path_smoother/media/eb_constraint.svg similarity index 100% rename from planning/obstacle_avoidance_planner/media/eb_constraint.svg rename to planning/path_smoother/media/eb_constraint.svg diff --git a/planning/path_smoother/package.xml b/planning/path_smoother/package.xml new file mode 100644 index 0000000000000..f0e0381f1706b --- /dev/null +++ b/planning/path_smoother/package.xml @@ -0,0 +1,41 @@ + + + + path_smoother + 0.1.0 + The path_smoother package + Takayuki Murooka + Maxime CLEMENT + Apache License 2.0 + + Takayuki Murooka + Maxime CLEMENT + + ament_cmake_auto + autoware_cmake + + autoware_auto_planning_msgs + geometry_msgs + interpolation + motion_utils + nav_msgs + osqp_interface + planning_test_utils + rclcpp + rclcpp_components + std_msgs + tf2_ros + tier4_autoware_utils + tier4_debug_msgs + + ament_cmake_ros + ament_index_python + ament_lint_auto + autoware_lint_common + autoware_testing + fake_test_node + + + ament_cmake + + diff --git a/planning/obstacle_avoidance_planner/src/eb_path_smoother.cpp b/planning/path_smoother/src/elastic_band.cpp similarity index 80% rename from planning/obstacle_avoidance_planner/src/eb_path_smoother.cpp rename to planning/path_smoother/src/elastic_band.cpp index 31af863eed8f0..f46c73d8b1e83 100644 --- a/planning/obstacle_avoidance_planner/src/eb_path_smoother.cpp +++ b/planning/path_smoother/src/elastic_band.cpp @@ -12,12 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "obstacle_avoidance_planner/eb_path_smoother.hpp" +#include "path_smoother/elastic_band.hpp" #include "motion_utils/motion_utils.hpp" -#include "obstacle_avoidance_planner/type_alias.hpp" -#include "obstacle_avoidance_planner/utils/geometry_utils.hpp" -#include "obstacle_avoidance_planner/utils/trajectory_utils.hpp" +#include "path_smoother/type_alias.hpp" +#include "path_smoother/utils/geometry_utils.hpp" +#include "path_smoother/utils/trajectory_utils.hpp" +#include "tf2/utils.h" #include #include @@ -69,41 +70,43 @@ std::vector toStdVector(const Eigen::VectorXd & eigen_vec) } } // namespace -namespace obstacle_avoidance_planner +namespace path_smoother { EBPathSmoother::EBParam::EBParam(rclcpp::Node * node) { { // option - enable_warm_start = node->declare_parameter("eb.option.enable_warm_start"); + enable_warm_start = node->declare_parameter("elastic_band.option.enable_warm_start"); enable_optimization_validation = - node->declare_parameter("eb.option.enable_optimization_validation"); + node->declare_parameter("elastic_band.option.enable_optimization_validation"); } { // common - delta_arc_length = node->declare_parameter("eb.common.delta_arc_length"); - num_points = node->declare_parameter("eb.common.num_points"); + delta_arc_length = node->declare_parameter("elastic_band.common.delta_arc_length"); + num_points = node->declare_parameter("elastic_band.common.num_points"); } { // clearance - num_joint_points = node->declare_parameter("eb.clearance.num_joint_points"); - clearance_for_fix = node->declare_parameter("eb.clearance.clearance_for_fix"); - clearance_for_joint = node->declare_parameter("eb.clearance.clearance_for_joint"); - clearance_for_smooth = node->declare_parameter("eb.clearance.clearance_for_smooth"); + num_joint_points = node->declare_parameter("elastic_band.clearance.num_joint_points"); + clearance_for_fix = node->declare_parameter("elastic_band.clearance.clearance_for_fix"); + clearance_for_joint = + node->declare_parameter("elastic_band.clearance.clearance_for_joint"); + clearance_for_smooth = + node->declare_parameter("elastic_band.clearance.clearance_for_smooth"); } { // weight - smooth_weight = node->declare_parameter("eb.weight.smooth_weight"); - lat_error_weight = node->declare_parameter("eb.weight.lat_error_weight"); + smooth_weight = node->declare_parameter("elastic_band.weight.smooth_weight"); + lat_error_weight = node->declare_parameter("elastic_band.weight.lat_error_weight"); } { // qp - qp_param.max_iteration = node->declare_parameter("eb.qp.max_iteration"); - qp_param.eps_abs = node->declare_parameter("eb.qp.eps_abs"); - qp_param.eps_rel = node->declare_parameter("eb.qp.eps_rel"); + qp_param.max_iteration = node->declare_parameter("elastic_band.qp.max_iteration"); + qp_param.eps_abs = node->declare_parameter("elastic_band.qp.eps_abs"); + qp_param.eps_rel = node->declare_parameter("elastic_band.qp.eps_rel"); } // validation - max_validation_error = node->declare_parameter("eb.validation.max_error"); + max_validation_error = node->declare_parameter("elastic_band.validation.max_error"); } void EBPathSmoother::EBParam::onParam(const std::vector & parameters) @@ -111,43 +114,46 @@ void EBPathSmoother::EBParam::onParam(const std::vector & par using tier4_autoware_utils::updateParam; { // option - updateParam(parameters, "eb.option.enable_warm_start", enable_warm_start); + updateParam(parameters, "elastic_band.option.enable_warm_start", enable_warm_start); updateParam( - parameters, "eb.option.enable_optimization_validation", enable_optimization_validation); + parameters, "elastic_band.option.enable_optimization_validation", + enable_optimization_validation); } { // common - updateParam(parameters, "eb.common.delta_arc_length", delta_arc_length); - updateParam(parameters, "eb.common.num_points", num_points); + updateParam(parameters, "elastic_band.common.delta_arc_length", delta_arc_length); + updateParam(parameters, "elastic_band.common.num_points", num_points); } { // clearance - updateParam(parameters, "eb.clearance.num_joint_points", num_joint_points); - updateParam(parameters, "eb.clearance.clearance_for_fix", clearance_for_fix); - updateParam(parameters, "eb.clearance.clearance_for_joint", clearance_for_joint); - updateParam(parameters, "eb.clearance.clearance_for_smooth", clearance_for_smooth); + updateParam(parameters, "elastic_band.clearance.num_joint_points", num_joint_points); + updateParam(parameters, "elastic_band.clearance.clearance_for_fix", clearance_for_fix); + updateParam( + parameters, "elastic_band.clearance.clearance_for_joint", clearance_for_joint); + updateParam( + parameters, "elastic_band.clearance.clearance_for_smooth", clearance_for_smooth); } { // weight - updateParam(parameters, "eb.weight.smooth_weight", smooth_weight); - updateParam(parameters, "eb.weight.lat_error_weight", lat_error_weight); + updateParam(parameters, "elastic_band.weight.smooth_weight", smooth_weight); + updateParam(parameters, "elastic_band.weight.lat_error_weight", lat_error_weight); } { // qp - updateParam(parameters, "eb.qp.max_iteration", qp_param.max_iteration); - updateParam(parameters, "eb.qp.eps_abs", qp_param.eps_abs); - updateParam(parameters, "eb.qp.eps_rel", qp_param.eps_rel); + updateParam(parameters, "elastic_band.qp.max_iteration", qp_param.max_iteration); + updateParam(parameters, "elastic_band.qp.eps_abs", qp_param.eps_abs); + updateParam(parameters, "elastic_band.qp.eps_rel", qp_param.eps_rel); } } EBPathSmoother::EBPathSmoother( rclcpp::Node * node, const bool enable_debug_info, const EgoNearestParam ego_nearest_param, - const TrajectoryParam & traj_param, const std::shared_ptr time_keeper_ptr) + const CommonParam & common_param, const std::shared_ptr time_keeper_ptr) : enable_debug_info_(enable_debug_info), ego_nearest_param_(ego_nearest_param), - traj_param_(traj_param), + common_param_(common_param), time_keeper_ptr_(time_keeper_ptr), - logger_(node->get_logger().get_child("eb_path_smoother")) + logger_(node->get_logger().get_child("elastic_band_smoother")) { // eb param eb_param_ = EBParam(node); @@ -162,10 +168,10 @@ void EBPathSmoother::onParam(const std::vector & parameters) eb_param_.onParam(parameters); } -void EBPathSmoother::initialize(const bool enable_debug_info, const TrajectoryParam & traj_param) +void EBPathSmoother::initialize(const bool enable_debug_info, const CommonParam & common_param) { enable_debug_info_ = enable_debug_info; - traj_param_ = traj_param; + common_param_ = common_param; } void EBPathSmoother::resetPreviousData() @@ -182,7 +188,7 @@ EBPathSmoother::getEBTrajectory(const PlannerData & planner_data) // 1. crop trajectory const double forward_traj_length = eb_param_.num_points * eb_param_.delta_arc_length; - const double backward_traj_length = traj_param_.output_backward_traj_length; + const double backward_traj_length = common_param_.output_backward_traj_length; const size_t ego_seg_idx = trajectory_utils::findEgoSegmentIndex(p.traj_points, p.ego_pose, ego_nearest_param_); @@ -422,4 +428,4 @@ std::optional> EBPathSmoother::convertOptimizedPoin time_keeper_ptr_->toc(__func__, " "); return eb_traj_points; } -} // namespace obstacle_avoidance_planner +} // namespace path_smoother diff --git a/planning/path_smoother/src/elastic_band_smoother.cpp b/planning/path_smoother/src/elastic_band_smoother.cpp new file mode 100644 index 0000000000000..6546995f1013a --- /dev/null +++ b/planning/path_smoother/src/elastic_band_smoother.cpp @@ -0,0 +1,373 @@ +// 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 "path_smoother/elastic_band_smoother.hpp" + +#include "interpolation/spline_interpolation_points_2d.hpp" +#include "path_smoother/utils/geometry_utils.hpp" +#include "path_smoother/utils/trajectory_utils.hpp" +#include "rclcpp/time.hpp" + +#include +#include + +namespace path_smoother +{ +namespace +{ +template +std::vector concatVectors(const std::vector & prev_vector, const std::vector & next_vector) +{ + std::vector concatenated_vector; + concatenated_vector.insert(concatenated_vector.end(), prev_vector.begin(), prev_vector.end()); + concatenated_vector.insert(concatenated_vector.end(), next_vector.begin(), next_vector.end()); + return concatenated_vector; +} + +StringStamped createStringStamped(const rclcpp::Time & now, const std::string & data) +{ + StringStamped msg; + msg.stamp = now; + msg.data = data; + return msg; +} + +void setZeroVelocityAfterStopPoint(std::vector & traj_points) +{ + const auto opt_zero_vel_idx = motion_utils::searchZeroVelocityIndex(traj_points); + if (opt_zero_vel_idx) { + for (size_t i = opt_zero_vel_idx.get(); i < traj_points.size(); ++i) { + traj_points.at(i).longitudinal_velocity_mps = 0.0; + } + } +} + +bool hasZeroVelocity(const TrajectoryPoint & traj_point) +{ + constexpr double zero_vel = 0.0001; + return std::abs(traj_point.longitudinal_velocity_mps) < zero_vel; +} +} // namespace + +ElasticBandSmoother::ElasticBandSmoother(const rclcpp::NodeOptions & node_options) +: Node("path_smoother", node_options), time_keeper_ptr_(std::make_shared()) +{ + // interface publisher + traj_pub_ = create_publisher("~/output/traj", 1); + path_pub_ = create_publisher("~/output/path", 1); + + // interface subscriber + path_sub_ = create_subscription( + "~/input/path", 1, std::bind(&ElasticBandSmoother::onPath, this, std::placeholders::_1)); + odom_sub_ = create_subscription( + "~/input/odometry", 1, [this](const Odometry::SharedPtr msg) { ego_state_ptr_ = msg; }); + + // debug publisher + debug_extended_traj_pub_ = create_publisher("~/debug/extended_traj", 1); + debug_calculation_time_pub_ = create_publisher("~/debug/calculation_time", 1); + + { // parameters + // parameters for ego nearest search + ego_nearest_param_ = EgoNearestParam(this); + + // parameters for trajectory + common_param_ = CommonParam(this); + } + + eb_path_smoother_ptr_ = std::make_shared( + this, enable_debug_info_, ego_nearest_param_, common_param_, time_keeper_ptr_); + + // reset planners + initializePlanning(); + + // set parameter callback + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&ElasticBandSmoother::onParam, this, std::placeholders::_1)); +} + +rcl_interfaces::msg::SetParametersResult ElasticBandSmoother::onParam( + const std::vector & parameters) +{ + using tier4_autoware_utils::updateParam; + + // parameters for ego nearest search + ego_nearest_param_.onParam(parameters); + + // parameters for trajectory + common_param_.onParam(parameters); + + // parameters for core algorithms + eb_path_smoother_ptr_->onParam(parameters); + + // reset planners + initializePlanning(); + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + return result; +} + +void ElasticBandSmoother::initializePlanning() +{ + RCLCPP_INFO(get_logger(), "Initialize planning"); + + eb_path_smoother_ptr_->initialize(false, common_param_); + resetPreviousData(); +} + +void ElasticBandSmoother::resetPreviousData() +{ + eb_path_smoother_ptr_->resetPreviousData(); + + prev_optimized_traj_points_ptr_ = nullptr; +} + +void ElasticBandSmoother::onPath(const Path::SharedPtr path_ptr) +{ + time_keeper_ptr_->init(); + time_keeper_ptr_->tic(__func__); + + // check if data is ready and valid + if (!isDataReady(*path_ptr, *get_clock())) { + return; + } + + // 0. return if path is backward + // TODO(murooka): support backward path + const auto is_driving_forward = driving_direction_checker_.isDrivingForward(path_ptr->points); + if (!is_driving_forward) { + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 5000, + "Backward path is NOT supported. Just converting path to trajectory"); + + const auto traj_points = trajectory_utils::convertToTrajectoryPoints(path_ptr->points); + const auto output_traj_msg = trajectory_utils::createTrajectory(path_ptr->header, traj_points); + traj_pub_->publish(output_traj_msg); + path_pub_->publish(*path_ptr); + return; + } + + // 1. create planner data + const auto planner_data = createPlannerData(*path_ptr); + + // 2. generate optimized trajectory + const auto optimized_traj_points = generateOptimizedTrajectory(planner_data); + + // 3. extend trajectory to connect the optimized trajectory and the following path smoothly + auto full_traj_points = extendTrajectory(planner_data.traj_points, optimized_traj_points); + + // 4. set zero velocity after stop point + setZeroVelocityAfterStopPoint(full_traj_points); + + time_keeper_ptr_->toc(__func__, ""); + *time_keeper_ptr_ << "========================================"; + time_keeper_ptr_->endLine(); + + // publish calculation_time + // NOTE: This function must be called after measuring onPath calculation time + const auto calculation_time_msg = createStringStamped(now(), time_keeper_ptr_->getLog()); + debug_calculation_time_pub_->publish(calculation_time_msg); + + const auto output_traj_msg = + trajectory_utils::createTrajectory(path_ptr->header, full_traj_points); + traj_pub_->publish(output_traj_msg); + const auto output_path_msg = trajectory_utils::create_path(*path_ptr, full_traj_points); + path_pub_->publish(output_path_msg); +} + +bool ElasticBandSmoother::isDataReady(const Path & path, rclcpp::Clock clock) const +{ + if (!ego_state_ptr_) { + RCLCPP_INFO_SKIPFIRST_THROTTLE(get_logger(), clock, 5000, "Waiting for ego pose and twist."); + return false; + } + + if (path.points.size() < 2) { + RCLCPP_INFO_SKIPFIRST_THROTTLE(get_logger(), clock, 5000, "Path points size is less than 1."); + return false; + } + + if (path.left_bound.empty() || path.right_bound.empty()) { + RCLCPP_INFO_SKIPFIRST_THROTTLE( + get_logger(), clock, 5000, "Left or right bound in path is empty."); + return false; + } + + return true; +} + +PlannerData ElasticBandSmoother::createPlannerData(const Path & path) const +{ + // create planner data + PlannerData planner_data; + planner_data.header = path.header; + planner_data.traj_points = trajectory_utils::convertToTrajectoryPoints(path.points); + planner_data.left_bound = path.left_bound; + planner_data.right_bound = path.right_bound; + planner_data.ego_pose = ego_state_ptr_->pose.pose; + planner_data.ego_vel = ego_state_ptr_->twist.twist.linear.x; + return planner_data; +} + +std::vector ElasticBandSmoother::generateOptimizedTrajectory( + const PlannerData & planner_data) +{ + time_keeper_ptr_->tic(__func__); + + const auto & input_traj_points = planner_data.traj_points; + + // 1. calculate trajectory with Elastic Band + auto optimized_traj_points = optimizeTrajectory(planner_data); + + // 2. update velocity + applyInputVelocity(optimized_traj_points, input_traj_points, planner_data.ego_pose); + + time_keeper_ptr_->toc(__func__, " "); + return optimized_traj_points; +} + +std::vector ElasticBandSmoother::optimizeTrajectory( + const PlannerData & planner_data) +{ + time_keeper_ptr_->tic(__func__); + const auto & p = planner_data; + + const auto eb_traj = eb_path_smoother_ptr_->getEBTrajectory(planner_data); + if (!eb_traj) return getPrevOptimizedTrajectory(p.traj_points); + + time_keeper_ptr_->toc(__func__, " "); + return *eb_traj; +} + +std::vector ElasticBandSmoother::getPrevOptimizedTrajectory( + const std::vector & traj_points) const +{ + if (prev_optimized_traj_points_ptr_) return *prev_optimized_traj_points_ptr_; + return traj_points; +} + +void ElasticBandSmoother::applyInputVelocity( + std::vector & output_traj_points, + const std::vector & input_traj_points, + const geometry_msgs::msg::Pose & ego_pose) const +{ + time_keeper_ptr_->tic(__func__); + + // crop forward for faster calculation + const double output_traj_length = motion_utils::calcArcLength(output_traj_points); + constexpr double margin_traj_length = 10.0; + const auto forward_cropped_input_traj_points = [&]() { + const size_t ego_seg_idx = + trajectory_utils::findEgoSegmentIndex(input_traj_points, ego_pose, ego_nearest_param_); + return motion_utils::cropForwardPoints( + input_traj_points, ego_pose.position, ego_seg_idx, output_traj_length + margin_traj_length); + }(); + + // update velocity + size_t input_traj_start_idx = 0; + for (size_t i = 0; i < output_traj_points.size(); i++) { + // crop backward for efficient calculation + const auto cropped_input_traj_points = std::vector{ + forward_cropped_input_traj_points.begin() + input_traj_start_idx, + forward_cropped_input_traj_points.end()}; + + const size_t nearest_seg_idx = trajectory_utils::findEgoSegmentIndex( + cropped_input_traj_points, output_traj_points.at(i).pose, ego_nearest_param_); + input_traj_start_idx = nearest_seg_idx; + + // calculate velocity with zero order hold + const double velocity = cropped_input_traj_points.at(nearest_seg_idx).longitudinal_velocity_mps; + output_traj_points.at(i).longitudinal_velocity_mps = velocity; + } + + // insert stop point explicitly + const auto stop_idx = motion_utils::searchZeroVelocityIndex(forward_cropped_input_traj_points); + if (stop_idx) { + const auto input_stop_pose = forward_cropped_input_traj_points.at(stop_idx.get()).pose; + const size_t stop_seg_idx = trajectory_utils::findEgoSegmentIndex( + output_traj_points, input_stop_pose, ego_nearest_param_); + + // calculate and insert stop pose on output trajectory + trajectory_utils::insertStopPoint(output_traj_points, input_stop_pose, stop_seg_idx); + } + + time_keeper_ptr_->toc(__func__, " "); +} + +std::vector ElasticBandSmoother::extendTrajectory( + const std::vector & traj_points, + const std::vector & optimized_traj_points) const +{ + time_keeper_ptr_->tic(__func__); + + const auto & joint_start_pose = optimized_traj_points.back().pose; + + // calculate end idx of optimized points on path points + const size_t joint_start_traj_seg_idx = + trajectory_utils::findEgoSegmentIndex(traj_points, joint_start_pose, ego_nearest_param_); + + // crop trajectory for extension + constexpr double joint_traj_max_length_for_smoothing = 15.0; + constexpr double joint_traj_min_length_for_smoothing = 5.0; + const auto joint_end_traj_point_idx = trajectory_utils::getPointIndexAfter( + traj_points, joint_start_pose.position, joint_start_traj_seg_idx, + joint_traj_max_length_for_smoothing, joint_traj_min_length_for_smoothing); + + // calculate full trajectory points + const auto full_traj_points = [&]() { + if (!joint_end_traj_point_idx) { + return optimized_traj_points; + } + + const auto extended_traj_points = std::vector{ + traj_points.begin() + *joint_end_traj_point_idx, traj_points.end()}; + + // NOTE: if optimized_traj_points's back is non zero velocity and extended_traj_points' front is + // zero velocity, the zero velocity will be inserted in the whole joint trajectory. + auto modified_optimized_traj_points = optimized_traj_points; + if (!extended_traj_points.empty() && !modified_optimized_traj_points.empty()) { + modified_optimized_traj_points.back().longitudinal_velocity_mps = + extended_traj_points.front().longitudinal_velocity_mps; + } + + return concatVectors(modified_optimized_traj_points, extended_traj_points); + }(); + + // resample trajectory points + auto resampled_traj_points = trajectory_utils::resampleTrajectoryPoints( + full_traj_points, common_param_.output_delta_arc_length); + + // update stop velocity on joint + for (size_t i = joint_start_traj_seg_idx + 1; i <= joint_end_traj_point_idx; ++i) { + if (hasZeroVelocity(traj_points.at(i))) { + if (i != 0 && !hasZeroVelocity(traj_points.at(i - 1))) { + // Here is when current point is 0 velocity, but previous point is not 0 velocity. + const auto & input_stop_pose = traj_points.at(i).pose; + const size_t stop_seg_idx = trajectory_utils::findEgoSegmentIndex( + resampled_traj_points, input_stop_pose, ego_nearest_param_); + + // calculate and insert stop pose on output trajectory + trajectory_utils::insertStopPoint(resampled_traj_points, input_stop_pose, stop_seg_idx); + } + } + } + + time_keeper_ptr_->toc(__func__, " "); + return resampled_traj_points; +} +} // namespace path_smoother + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(path_smoother::ElasticBandSmoother) diff --git a/planning/path_smoother/src/utils/trajectory_utils.cpp b/planning/path_smoother/src/utils/trajectory_utils.cpp new file mode 100644 index 0000000000000..56432d16d1a7f --- /dev/null +++ b/planning/path_smoother/src/utils/trajectory_utils.cpp @@ -0,0 +1,109 @@ +// 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 "path_smoother/utils/trajectory_utils.hpp" + +#include "motion_utils/motion_utils.hpp" +#include "path_smoother/utils/geometry_utils.hpp" + +#include "autoware_auto_planning_msgs/msg/path_point.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" +#include "geometry_msgs/msg/point32.hpp" +#include "geometry_msgs/msg/pose.hpp" + +#include +#include +#include +#include +#include +#include + +namespace path_smoother +{ +namespace trajectory_utils +{ +Trajectory createTrajectory( + const std_msgs::msg::Header & header, const std::vector & traj_points) +{ + auto traj = motion_utils::convertToTrajectory(traj_points); + traj.header = header; + + return traj; +} + +Path create_path(Path path_msg, const std::vector & traj_points) +{ + path_msg.points.clear(); + PathPoint pp; + for (const auto & p : traj_points) { + pp.pose = p.pose; + pp.longitudinal_velocity_mps = p.longitudinal_velocity_mps; + pp.lateral_velocity_mps = p.lateral_velocity_mps; + pp.heading_rate_rps = p.heading_rate_rps; + pp.is_final = true; + path_msg.points.push_back(pp); + } + return path_msg; +} + +std::vector resampleTrajectoryPoints( + const std::vector traj_points, const double interval) +{ + constexpr bool enable_resampling_stop_point = true; + + const auto traj = motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = motion_utils::resampleTrajectory( + traj, interval, false, true, true, enable_resampling_stop_point); + return motion_utils::convertToTrajectoryPointArray(resampled_traj); +} + +// NOTE: stop point will not be resampled +std::vector resampleTrajectoryPointsWithoutStopPoint( + const std::vector traj_points, const double interval) +{ + constexpr bool enable_resampling_stop_point = false; + + const auto traj = motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = motion_utils::resampleTrajectory( + traj, interval, false, true, true, enable_resampling_stop_point); + return motion_utils::convertToTrajectoryPointArray(resampled_traj); +} + +void insertStopPoint( + std::vector & traj_points, const geometry_msgs::msg::Pose & input_stop_pose, + const size_t stop_seg_idx) +{ + const double offset_to_segment = motion_utils::calcLongitudinalOffsetToSegment( + traj_points, stop_seg_idx, input_stop_pose.position); + + const auto traj_spline = SplineInterpolationPoints2d(traj_points); + const auto stop_pose = traj_spline.getSplineInterpolatedPose(stop_seg_idx, offset_to_segment); + + if (geometry_utils::isSamePoint(traj_points.at(stop_seg_idx), stop_pose)) { + traj_points.at(stop_seg_idx).longitudinal_velocity_mps = 0.0; + return; + } + if (geometry_utils::isSamePoint(traj_points.at(stop_seg_idx + 1), stop_pose)) { + traj_points.at(stop_seg_idx + 1).longitudinal_velocity_mps = 0.0; + return; + } + + TrajectoryPoint additional_traj_point; + additional_traj_point.pose = stop_pose; + additional_traj_point.longitudinal_velocity_mps = 0.0; + + traj_points.insert(traj_points.begin() + stop_seg_idx + 1, additional_traj_point); +} +} // namespace trajectory_utils +} // namespace path_smoother diff --git a/planning/path_smoother/test/test_path_smoother_node_interface.cpp b/planning/path_smoother/test/test_path_smoother_node_interface.cpp new file mode 100644 index 0000000000000..b18c49b0e88b0 --- /dev/null +++ b/planning/path_smoother/test/test_path_smoother_node_interface.cpp @@ -0,0 +1,62 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "path_smoother/elastic_band_smoother.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) +{ + rclcpp::init(0, nullptr); + + auto test_manager = std::make_shared(); + + auto node_options = rclcpp::NodeOptions{}; + + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto path_smoothing_dir = ament_index_cpp::get_package_share_directory("path_smoother"); + + node_options.arguments( + {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_common.param.yaml", + "--params-file", planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + "--params-file", path_smoothing_dir + "/config/elastic_band_smoother.param.yaml"}); + + auto test_target_node = std::make_shared(node_options); + + // publish necessary topics from test_manager + test_manager->publishOdometry(test_target_node, "path_smoother/input/odometry"); + + // set subscriber with topic name + test_manager->setTrajectorySubscriber("path_smoother/output/traj"); + test_manager->setPathSubscriber("path_smoother/output/path"); + + // set input topic name (this topic is changed to test node) + test_manager->setPathInputTopicName("path_smoother/input/path"); + + // test with normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPath(test_target_node)); + + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with trajectory with empty/one point/overlapping point + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPath(test_target_node)); + + rclcpp::shutdown(); +} From 4001ee64d56fd6355afa93626942abc22630a84f Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 10 Jul 2023 11:40:30 +0900 Subject: [PATCH 113/118] feat(avoidance): output avoidance path with unsafe flag when the yield is necessary (#4183) * feat(avoidance): output avoidance path with unsafe flag when the yield is necessary Signed-off-by: satoshi-ota * feat(avoidance): keep rtc status in unsafe condition Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../avoidance/avoidance_module.hpp | 1 - .../avoidance/avoidance_module.cpp | 20 +++++++++---------- 2 files changed, 9 insertions(+), 12 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 5751e1873a579..79a1b5d0dfe4e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -580,7 +580,6 @@ class AvoidanceModule : public SceneModuleInterface return; } - initRTCStatus(); unlockNewModuleLaunch(); current_raw_shift_lines_.clear(); 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 6cf187268e4ca..11e2ccb82939e 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 @@ -114,27 +114,25 @@ bool AvoidanceModule::isExecutionRequested() const } // Check ego is in preferred lane - const auto avoid_data = avoidance_data_; - - updateInfoMarker(avoid_data); - updateDebugMarker(avoid_data, path_shifter_, debug_data_); + updateInfoMarker(avoidance_data_); + updateDebugMarker(avoidance_data_, path_shifter_, debug_data_); // there is object that should be avoid. return true. - if (!!avoid_data.stop_target_object) { + if (!!avoidance_data_.stop_target_object) { return true; } - if (avoid_data.unapproved_new_sl.empty()) { + if (avoidance_data_.unapproved_new_sl.empty()) { return false; } - return !avoid_data.target_objects.empty(); + return !avoidance_data_.target_objects.empty(); } bool AvoidanceModule::isExecutionReady() const { DEBUG_PRINT("AVOIDANCE isExecutionReady"); - return true; + return avoidance_data_.safe; } ModuleStatus AvoidanceModule::updateState() @@ -534,6 +532,7 @@ void AvoidanceModule::fillEgoStatus( * if the avoidance has already been initiated. */ if (!can_yield_maneuver) { + data.safe = true; // overwrite safety judge. data.yield_required = false; data.safe_new_sl = data.unapproved_new_sl; RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "unsafe. but could not transit yield status."); @@ -545,7 +544,7 @@ void AvoidanceModule::fillEgoStatus( */ { data.yield_required = true; - data.safe_new_sl.clear(); + data.safe_new_sl = data.unapproved_new_sl; } /** @@ -2605,8 +2604,7 @@ CandidateOutput AvoidanceModule::planCandidate() const CandidateOutput output; - auto shifted_path = data.yield_required ? utils::avoidance::toShiftedPath(data.reference_path) - : data.candidate_path; + auto shifted_path = data.candidate_path; if (!data.safe_new_sl.empty()) { // clip from shift start index for visualize utils::clipPathLength( From 1bb0aa2bbda455b4fbd37803cea20a15dae52a28 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 10 Jul 2023 12:24:46 +0900 Subject: [PATCH 114/118] chore(start_planner): fix typos (#4208) Signed-off-by: kosuke55 --- .../start_planner/start_planner_module.hpp | 2 +- .../start_planner/start_planner_module.cpp | 12 ++++++------ 2 files changed, 7 insertions(+), 7 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 6aa3ca9ac2239..313162d6473cc 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 @@ -115,7 +115,7 @@ class StartPlannerModule : public SceneModuleInterface std::shared_ptr parameters_; vehicle_info_util::VehicleInfo vehicle_info_; - std::vector> start_planner_planners_; + std::vector> start_planners_; PullOutStatus status_; std::deque odometry_buffer_; 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 35f1e2b2b9408..dd42b18666ec3 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 @@ -49,13 +49,13 @@ StartPlannerModule::StartPlannerModule( // set enabled planner if (parameters_->enable_shift_pull_out) { - start_planner_planners_.push_back( + start_planners_.push_back( std::make_shared(node, *parameters, lane_departure_checker_)); } if (parameters_->enable_geometric_pull_out) { - start_planner_planners_.push_back(std::make_shared(node, *parameters)); + start_planners_.push_back(std::make_shared(node, *parameters)); } - if (start_planner_planners_.empty()) { + if (start_planners_.empty()) { RCLCPP_ERROR(getLogger(), "Not found enabled planner"); } } @@ -257,7 +257,7 @@ CandidateOutput StartPlannerModule::planCandidate() const std::shared_ptr StartPlannerModule::getCurrentPlanner() const { - for (const auto & planner : start_planner_planners_) { + for (const auto & planner : start_planners_) { if (status_.planner_type == planner->getPlannerType()) { return planner; } @@ -458,7 +458,7 @@ void StartPlannerModule::planWithPriority( using PriorityOrder = std::vector>>; const auto make_loop_order_planner_first = [&]() { PriorityOrder order_priority; - for (const auto & planner : start_planner_planners_) { + for (const auto & planner : start_planners_) { for (size_t i = 0; i < start_pose_candidates.size(); i++) { order_priority.emplace_back(i, planner); } @@ -469,7 +469,7 @@ void StartPlannerModule::planWithPriority( const auto make_loop_order_pose_first = [&]() { PriorityOrder order_priority; for (size_t i = 0; i < start_pose_candidates.size(); i++) { - for (const auto & planner : start_planner_planners_) { + for (const auto & planner : start_planners_) { order_priority.emplace_back(i, planner); } } From 0c1b6930ec9586864a8885ce7b1293f6231f45e4 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 10 Jul 2023 13:57:34 +0900 Subject: [PATCH 115/118] refactor(behavior_path_planner): remove unused code (#4181) * feat(lane_change): remove behavior tree class from the lane chagne module (#4175) Signed-off-by: yutaka * refactor(node): remove unused config (#4180) * refactor(node): remove unused config Signed-off-by: satoshi-ota * refactor(node): clean up Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota * refactor(behavior_path_planner): don't generate drivable area in each modules Signed-off-by: satoshi-ota --------- Signed-off-by: yutaka Signed-off-by: satoshi-ota Co-authored-by: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> --- .../config/behavior_path_planner.param.yaml | 4 - ...ior_path_planner_tree_lane_change_only.xml | 86 ------------ ...path_planner_tree_lane_change_only_old.xml | 100 -------------- .../config/behavior_path_planner_tree_old.xml | 110 --------------- .../behavior_path_planner_tree_pull_out.xml | 100 -------------- ..._planner_tree_with_external_request_LC.xml | 74 ---------- .../behavior_path_planner_node.hpp | 2 +- .../lane_change/external_request.hpp | 13 -- .../scene_module/lane_change/interface.hpp | 56 -------- .../scene_module/lane_change/normal.hpp | 25 ---- .../src/behavior_path_planner_node.cpp | 11 +- .../avoidance/avoidance_module.cpp | 6 - .../goal_planner/goal_planner_module.cpp | 15 -- .../lane_change/external_request.cpp | 6 - .../scene_module/lane_change/interface.cpp | 130 ------------------ .../src/scene_module/lane_change/normal.cpp | 88 ------------ .../side_shift/side_shift_module.cpp | 7 +- .../start_planner/start_planner_module.cpp | 9 -- .../goal_planner/freespace_pull_over.cpp | 7 - .../utils/start_planner/shift_pull_out.cpp | 7 - .../behavior_path_planner/src/utils/utils.cpp | 7 - 21 files changed, 5 insertions(+), 858 deletions(-) delete mode 100644 planning/behavior_path_planner/config/behavior_path_planner_tree_lane_change_only.xml delete mode 100644 planning/behavior_path_planner/config/behavior_path_planner_tree_lane_change_only_old.xml delete mode 100644 planning/behavior_path_planner/config/behavior_path_planner_tree_old.xml delete mode 100644 planning/behavior_path_planner/config/behavior_path_planner_tree_pull_out.xml delete mode 100644 planning/behavior_path_planner/config/behavior_path_planner_tree_with_external_request_LC.xml 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 a35f920dfb482..02dc13ffd84da 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -1,10 +1,6 @@ /**: ros__parameters: verbose: false - - groot_zmq_publisher_port: 1666 - groot_zmq_server_port: 1667 - planning_hz: 10.0 backward_path_length: 5.0 forward_path_length: 300.0 diff --git a/planning/behavior_path_planner/config/behavior_path_planner_tree_lane_change_only.xml b/planning/behavior_path_planner/config/behavior_path_planner_tree_lane_change_only.xml deleted file mode 100644 index 8988dd41b50fb..0000000000000 --- a/planning/behavior_path_planner/config/behavior_path_planner_tree_lane_change_only.xml +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - desc - - - desc - - - - - - desc - - - desc - - - - desc - - - desc - - - - - - - - desc - - - - - desc - - - desc - - - - - - - - diff --git a/planning/behavior_path_planner/config/behavior_path_planner_tree_lane_change_only_old.xml b/planning/behavior_path_planner/config/behavior_path_planner_tree_lane_change_only_old.xml deleted file mode 100644 index 46b2c4a8a3f33..0000000000000 --- a/planning/behavior_path_planner/config/behavior_path_planner_tree_lane_change_only_old.xml +++ /dev/null @@ -1,100 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - desc - - - desc - - - - - - - - - desc - - - desc - - - - - desc - - - desc - - - - - - - - - - desc - - - - - - desc - - - desc - - - - - - - - - diff --git a/planning/behavior_path_planner/config/behavior_path_planner_tree_old.xml b/planning/behavior_path_planner/config/behavior_path_planner_tree_old.xml deleted file mode 100644 index 97601698c4eb7..0000000000000 --- a/planning/behavior_path_planner/config/behavior_path_planner_tree_old.xml +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - desc - - - desc - - - - - - - - - desc - - - desc - - - - - desc - - - desc - - - - - - - - - - desc - - - - - - desc - - - desc - - - - - - - - - diff --git a/planning/behavior_path_planner/config/behavior_path_planner_tree_pull_out.xml b/planning/behavior_path_planner/config/behavior_path_planner_tree_pull_out.xml deleted file mode 100644 index 32f30af69ac36..0000000000000 --- a/planning/behavior_path_planner/config/behavior_path_planner_tree_pull_out.xml +++ /dev/null @@ -1,100 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - desc - - - desc - - - - - - - - - desc - - - desc - - - - - desc - - - desc - - - - - - - - - - desc - - - - - - desc - - - desc - - - - - - - - - diff --git a/planning/behavior_path_planner/config/behavior_path_planner_tree_with_external_request_LC.xml b/planning/behavior_path_planner/config/behavior_path_planner_tree_with_external_request_LC.xml deleted file mode 100644 index 0410f775f7d17..0000000000000 --- a/planning/behavior_path_planner/config/behavior_path_planner_tree_with_external_request_LC.xml +++ /dev/null @@ -1,74 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - desc - - - - - desc - - - - desc - - - - desc - - - - desc - - - - - - - - desc - - - - desc - - - - - 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 0ec1fe0ca493a..e6ed8b7063d2c 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 @@ -153,7 +153,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node * @brief extract path from behavior tree output */ PathWithLaneId::SharedPtr getPath( - const BehaviorModuleOutput & bt_out, const std::shared_ptr & planner_data, + const BehaviorModuleOutput & output, const std::shared_ptr & planner_data, const std::shared_ptr & planner_manager); bool keepInputPoints(const std::vector> & statuses) const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp index 51a71ef7cd061..d9c77d6db337e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp @@ -33,19 +33,6 @@ class ExternalRequestLaneChange : public NormalLaneChange ExternalRequestLaneChange & operator=(ExternalRequestLaneChange &&) = delete; ~ExternalRequestLaneChange() override = default; }; - -class ExternalRequestLaneChangeBT : public NormalLaneChangeBT -{ -public: - ExternalRequestLaneChangeBT( - const std::shared_ptr & parameters, Direction direction); - - ExternalRequestLaneChangeBT(const ExternalRequestLaneChangeBT &) = delete; - ExternalRequestLaneChangeBT(ExternalRequestLaneChangeBT &&) = delete; - ExternalRequestLaneChangeBT & operator=(const ExternalRequestLaneChangeBT &) = delete; - ExternalRequestLaneChangeBT & operator=(ExternalRequestLaneChangeBT &&) = delete; - ~ExternalRequestLaneChangeBT() override = default; -}; } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__EXTERNAL_REQUEST_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp index 1171b92343e30..232437f710b6a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp @@ -136,62 +136,6 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface protected: void updateRTCStatus(const double start_distance, const double finish_distance) override; }; - -class LaneChangeBTInterface : public LaneChangeInterface -{ -public: - LaneChangeBTInterface( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters, - const std::unordered_map > & rtc_interface_ptr_map, - std::unique_ptr && module_type); - - LaneChangeBTInterface(const LaneChangeBTInterface &) = delete; - LaneChangeBTInterface(LaneChangeBTInterface &&) = delete; - LaneChangeBTInterface & operator=(const LaneChangeBTInterface &) = delete; - LaneChangeBTInterface & operator=(LaneChangeBTInterface &&) = delete; - ~LaneChangeBTInterface() override = default; - - void processOnEntry() override; - - BehaviorModuleOutput plan() override; - - BehaviorModuleOutput planWaitingApproval() override; - - CandidateOutput planCandidate() const override; - - void acceptVisitor(const std::shared_ptr & visitor) const override; - -protected: - bool is_activated_{false}; -}; - -class LaneChangeBTModule : public LaneChangeBTInterface -{ -public: - LaneChangeBTModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters); - -protected: - void updateRTCStatus(const double start_distance, const double finish_distance) override; -}; - -class ExternalRequestLaneChangeLeftBTModule : public LaneChangeBTInterface -{ -public: - ExternalRequestLaneChangeLeftBTModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters); -}; - -class ExternalRequestLaneChangeRightBTModule : public LaneChangeBTInterface -{ -public: - ExternalRequestLaneChangeRightBTModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters); -}; } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ 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 cac0252e274ae..8b3dea03a8c8b 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 @@ -110,30 +110,5 @@ class NormalLaneChange : public LaneChangeBase rclcpp::Logger logger_ = rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()); }; - -class NormalLaneChangeBT : public NormalLaneChange -{ -public: - NormalLaneChangeBT( - const std::shared_ptr & parameters, LaneChangeModuleType type, - Direction direction); - - NormalLaneChangeBT(const NormalLaneChangeBT &) = delete; - NormalLaneChangeBT(NormalLaneChangeBT &&) = delete; - NormalLaneChangeBT & operator=(const NormalLaneChangeBT &) = delete; - NormalLaneChangeBT & operator=(NormalLaneChangeBT &&) = delete; - ~NormalLaneChangeBT() override = default; - - PathWithLaneId getReferencePath() const override; - -protected: - lanelet::ConstLanelets getCurrentLanes() const override; - - int getNumToPreferredLane(const lanelet::ConstLanelet & lane) const override; - - PathWithLaneId getPrepareSegment( - const lanelet::ConstLanelets & current_lanes, const double arc_length_from_current, - const double backward_path_length, const double prepare_length) const override; -}; } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__NORMAL_HPP_ 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 7857c2962d001..76873b8e248ba 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -122,8 +122,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod createSubscriptionOptions(this)); { - RCLCPP_INFO(get_logger(), "not use behavior tree."); - const std::string path_candidate_name_space = "/planning/path_candidate/"; const std::string path_reference_name_space = "/planning/path_reference/"; @@ -508,7 +506,7 @@ void BehaviorPathPlannerNode::run() planner_data_->route_handler->setMap(*map_ptr); } - std::unique_lock lk_manager(mutex_manager_); // for bt_manager_ or planner_manager_ + std::unique_lock lk_manager(mutex_manager_); // for planner_manager_ // update route const bool is_first_time = !(planner_data_->route_handler->isHandlerReady()); @@ -523,7 +521,6 @@ void BehaviorPathPlannerNode::run() // Reset behavior tree when new route is received, // so that the each modules do not have to care about the "route jump". if (!is_first_time && !has_same_route_id) { - RCLCPP_DEBUG(get_logger(), "new route is received. reset behavior tree."); planner_manager_->reset(); } } @@ -852,16 +849,14 @@ Path BehaviorPathPlannerNode::convertToPath( } PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath( - const BehaviorModuleOutput & bt_output, const std::shared_ptr & planner_data, + const BehaviorModuleOutput & output, const std::shared_ptr & planner_data, const std::shared_ptr & planner_manager) { // TODO(Horibe) do some error handling when path is not available. - auto path = bt_output.path ? bt_output.path : planner_data->prev_output_path; + auto path = output.path ? output.path : planner_data->prev_output_path; path->header = planner_data->route_handler->getRouteHeader(); path->header.stamp = this->now(); - RCLCPP_DEBUG( - get_logger(), "BehaviorTreeManager: output is %s.", bt_output.path ? "FOUND" : "NOT FOUND"); PathWithLaneId connected_path; const auto module_status_ptr_vec = planner_manager->getSceneModuleStatus(); 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 11e2ccb82939e..58ef8f5fa5b3e 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 @@ -2369,12 +2369,6 @@ void AvoidanceModule::generateExtendedDrivableArea(BehaviorModuleOutput & output output.drivable_area_info = utils::combineDrivableAreaInfo( current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); } - - { // for old architecture - // NOTE: Obstacles to avoid are not extracted from the drivable area with an old architecture. - utils::generateDrivableArea( - *output.path, drivable_lanes, false, planner_data_->parameters.vehicle_length, planner_data_); - } } void AvoidanceModule::modifyPathVelocityToPreventAccelerationOnAvoidance(ShiftedPath & path) 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 92b465c6ffdb2..3c4feebe35529 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 @@ -584,9 +584,6 @@ void GoalPlannerModule::selectSafePullOverPath() 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); - const auto target_drivable_lanes = getNonOverlappingExpandedLanes(path, status_.lanes); - utils::generateDrivableArea( - path, target_drivable_lanes, false, planner_data_->parameters.vehicle_length, planner_data_); } } @@ -976,12 +973,6 @@ PathWithLaneId GoalPlannerModule::generateStopPath() } } - // generate drivable area - const auto drivable_lanes = utils::generateDrivableLanes(status_.current_lanes); - const auto target_drivable_lanes = getNonOverlappingExpandedLanes(reference_path, drivable_lanes); - utils::generateDrivableArea( - reference_path, target_drivable_lanes, false, common_parameters.vehicle_length, planner_data_); - return reference_path; } @@ -1011,12 +1002,6 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath() status_.stop_pose = stop_path.points.at(*stop_idx).point.pose; } - // generate drivable area - const auto drivable_lanes = utils::generateDrivableLanes(status_.current_lanes); - const auto target_drivable_lanes = getNonOverlappingExpandedLanes(stop_path, drivable_lanes); - utils::generateDrivableArea( - stop_path, target_drivable_lanes, false, common_parameters.vehicle_length, planner_data_); - return stop_path; } 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 110a993214ae4..a74a51b7e2cdb 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 @@ -34,10 +34,4 @@ ExternalRequestLaneChange::ExternalRequestLaneChange( : NormalLaneChange(parameters, LaneChangeModuleType::EXTERNAL_REQUEST, direction) { } - -ExternalRequestLaneChangeBT::ExternalRequestLaneChangeBT( - const std::shared_ptr & parameters, Direction direction) -: NormalLaneChangeBT(parameters, LaneChangeModuleType::EXTERNAL_REQUEST, direction) -{ -} } // 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 2c1ba45c3ef84..045484a7c8cd6 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 @@ -505,134 +505,4 @@ void AvoidanceByLaneChangeInterface::updateRTCStatus( rtc_interface_ptr_map_.at(direction)->updateCooperateStatus( uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now()); } - -LaneChangeBTInterface::LaneChangeBTInterface( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters, - const std::unordered_map > & rtc_interface_ptr_map, - std::unique_ptr && module_type) -: LaneChangeInterface{name, node, parameters, rtc_interface_ptr_map, std::move(module_type)} -{ -} - -void LaneChangeBTInterface::processOnEntry() -{ - module_type_->updateLaneChangeStatus(); -} - -BehaviorModuleOutput LaneChangeBTInterface::plan() -{ - resetPathCandidate(); - resetPathReference(); - is_activated_ = isActivated(); - - if (!module_type_->isValidPath()) { - return {}; - } - - auto output = module_type_->generateOutput(); - path_reference_ = getPreviousModuleOutput().reference_path; - *prev_approved_path_ = *output.path; - - updateSteeringFactorPtr(output); - clearWaitingApproval(); - - return output; -} - -BehaviorModuleOutput LaneChangeBTInterface::planWaitingApproval() -{ - const auto path = module_type_->getReferencePath(); - if (!path.points.empty()) { - *prev_approved_path_ = module_type_->getReferencePath(); - } - - BehaviorModuleOutput out; - out.path = std::make_shared(*prev_approved_path_); - out.reference_path = getPreviousModuleOutput().reference_path; - out.turn_signal_info = getPreviousModuleOutput().turn_signal_info; - - const auto candidate = planCandidate(); - path_candidate_ = std::make_shared(candidate.path_candidate); - - path_reference_ = getPreviousModuleOutput().reference_path; - updateRTCStatus( - candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change); - is_abort_path_approved_ = false; - - return out; -} - -CandidateOutput LaneChangeBTInterface::planCandidate() const -{ - LaneChangePath selected_path; - - if (module_type_->isAbortState()) { - selected_path = module_type_->getLaneChangePath(); - } else { - [[maybe_unused]] const auto [found_valid_path, found_safe_path] = - module_type_->getSafePath(selected_path); - } - - selected_path.path.header = module_type_->getRouteHeader(); - - if (selected_path.path.points.empty()) { - return {}; - } - - CandidateOutput output = assignToCandidate(selected_path, module_type_->getEgoPosition()); - - updateSteeringFactorPtr(output, selected_path); - return output; -} - -void LaneChangeBTInterface::acceptVisitor(const std::shared_ptr & visitor) const -{ - if (visitor) { - visitor->visitLaneChangeBTInterface(this); - } -} - -void SceneModuleVisitor::visitLaneChangeBTInterface(const LaneChangeBTInterface * module) const -{ - external_request_lane_change_bt_visitor_ = module->get_debug_msg_array(); -} - -LaneChangeBTModule::LaneChangeBTModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters) -: LaneChangeBTInterface{ - name, node, parameters, createRTCInterfaceMap(node, name, {"left", "right"}), - std::make_unique(parameters, LaneChangeModuleType::NORMAL, Direction::NONE)} -{ -} - -void LaneChangeBTModule::updateRTCStatus(const double start_distance, const double finish_distance) -{ - const auto direction = std::invoke([&]() -> std::string { - const auto dir = module_type_->getDirection(); - return (dir == Direction::LEFT) ? "left" : "right"; - }); - - rtc_interface_ptr_map_.at(direction)->updateCooperateStatus( - uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now()); -} - -ExternalRequestLaneChangeLeftBTModule::ExternalRequestLaneChangeLeftBTModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters) -: LaneChangeBTInterface{ - name, node, parameters, createRTCInterfaceMap(node, name, {""}), - std::make_unique(parameters, Direction::LEFT)} -{ -} - -ExternalRequestLaneChangeRightBTModule::ExternalRequestLaneChangeRightBTModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters) -: LaneChangeBTInterface{ - name, node, parameters, createRTCInterfaceMap(node, name, {""}), - std::make_unique(parameters, Direction::RIGHT)} -{ -} } // 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 fadb445b73392..eed66650520e9 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 @@ -155,7 +155,6 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) { - const auto & common_parameters = planner_data_->parameters; const auto & dp = planner_data_->drivable_area_expansion_parameters; const auto drivable_lanes = utils::lane_change::generateDrivableLanes( @@ -170,10 +169,6 @@ void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) current_drivable_area_info.drivable_lanes = expanded_lanes; output.drivable_area_info = utils::combineDrivableAreaInfo(current_drivable_area_info, prev_drivable_area_info_); - - // for old architecture - utils::generateDrivableArea( - *output.path, expanded_lanes, false, common_parameters.vehicle_length, planner_data_); } void NormalLaneChange::insertStopPoint(PathWithLaneId & path) @@ -1028,87 +1023,4 @@ bool NormalLaneChange::getAbortPath() abort_path_ = std::make_shared(abort_path); return true; } - -NormalLaneChangeBT::NormalLaneChangeBT( - const std::shared_ptr & parameters, LaneChangeModuleType type, - Direction direction) -: NormalLaneChange(parameters, type, direction) -{ -} - -PathWithLaneId NormalLaneChangeBT::getReferencePath() const -{ - PathWithLaneId reference_path; - if (!utils::isEgoWithinOriginalLane( - status_.current_lanes, getEgoPose(), planner_data_->parameters)) { - return reference_path; - } - - const auto & route_handler = getRouteHandler(); - const auto & current_pose = getEgoPose(); - const auto & common_parameters = planner_data_->parameters; - - // Set header - reference_path.header = getRouteHeader(); - - const auto current_lanes = getCurrentLanes(); - - if (current_lanes.empty()) { - return reference_path; - } - - reference_path = utils::getCenterLinePath( - *route_handler, current_lanes, current_pose, common_parameters.backward_path_length, - common_parameters.forward_path_length, common_parameters); - - const auto shift_intervals = - route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const double lane_change_buffer = - utils::calcMinimumLaneChangeLength(common_parameters, shift_intervals); - - reference_path = utils::setDecelerationVelocity( - *route_handler, reference_path, current_lanes, common_parameters.lane_change_prepare_duration, - lane_change_buffer); - - const auto & dp = planner_data_->drivable_area_expansion_parameters; - - const auto drivable_lanes = utils::generateDrivableLanes(current_lanes); - const auto shorten_lanes = utils::cutOverlappedLanes(reference_path, drivable_lanes); - const auto expanded_lanes = utils::expandLanelets( - shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, - dp.drivable_area_types_to_skip); - utils::generateDrivableArea( - reference_path, expanded_lanes, false, common_parameters.vehicle_length, planner_data_); - - return reference_path; -} - -lanelet::ConstLanelets NormalLaneChangeBT::getCurrentLanes() const -{ - return utils::getCurrentLanes(planner_data_); -} - -int NormalLaneChangeBT::getNumToPreferredLane(const lanelet::ConstLanelet & lane) const -{ - return std::abs(getRouteHandler()->getNumLaneToPreferredLane(lane)); -} - -PathWithLaneId NormalLaneChangeBT::getPrepareSegment( - const lanelet::ConstLanelets & current_lanes, const double arc_length_from_current, - const double backward_path_length, const double prepare_length) const -{ - if (current_lanes.empty()) { - return PathWithLaneId(); - } - - const double s_start = arc_length_from_current - backward_path_length; - const double s_end = arc_length_from_current + prepare_length; - - RCLCPP_DEBUG(logger_, "start: %f, end: %f", s_start, s_end); - - PathWithLaneId prepare_segment = - getRouteHandler()->getCenterLinePath(current_lanes, s_start, s_end); - - return prepare_segment; -} } // namespace behavior_path_planner 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 d235cd1866181..5102570a5e3b2 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 @@ -407,15 +407,10 @@ BehaviorModuleOutput SideShiftModule::adjustDrivableArea(const ShiftedPath & pat const auto expanded_lanes = utils::expandLanelets(shorten_lanes, left_offset, right_offset, dp.drivable_area_types_to_skip); - { // for old architecture - utils::generateDrivableArea( - output_path, expanded_lanes, false, p.vehicle_length, planner_data_); - out.path = std::make_shared(output_path); - } - { // for new architecture // NOTE: side shift module is not launched with other modules. Therefore, drivable_lanes can be // assigned without combining. + out.path = std::make_shared(output_path); out.drivable_area_info.drivable_lanes = expanded_lanes; out.drivable_area_info.is_already_expanded = true; } 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 dd42b18666ec3..2441f62ef6cf8 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 @@ -192,8 +192,6 @@ BehaviorModuleOutput StartPlannerModule::plan() } const auto target_drivable_lanes = getNonOverlappingExpandedLanes(path, status_.lanes); - utils::generateDrivableArea( - path, target_drivable_lanes, false, planner_data_->parameters.vehicle_length, planner_data_); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -322,8 +320,6 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() const auto expanded_lanes = utils::expandLanelets( drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, dp.drivable_area_types_to_skip); - utils::generateDrivableArea( - stop_path, expanded_lanes, false, planner_data_->parameters.vehicle_length, planner_data_); for (auto & p : stop_path.points) { p.point.longitudinal_velocity_mps = 0.0; } @@ -334,7 +330,6 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() current_drivable_area_info, getPreviousModuleOutput().drivable_area_info); output.path = std::make_shared(stop_path); - output.drivable_area_info.drivable_lanes = status_.lanes; output.reference_path = getPreviousModuleOutput().reference_path; output.turn_signal_info = calcTurnSignalInfo(); path_candidate_ = std::make_shared(getFullPath()); @@ -520,10 +515,6 @@ PathWithLaneId StartPlannerModule::generateStopPath() const // generate drivable area const auto target_drivable_lanes = getNonOverlappingExpandedLanes(path, status_.lanes); - // for old architecture - utils::generateDrivableArea( - path, target_drivable_lanes, false, planner_data_->parameters.vehicle_length, planner_data_); - return path; } diff --git a/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp index a3e710b853503..ebfac8a347134 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp @@ -103,19 +103,12 @@ boost::optional FreespacePullOver::plan(const Pose & goal_pose) utils::correctDividedPathVelocity(partial_paths); - const double drivable_area_margin = planner_data_->parameters.vehicle_width; for (auto & path : partial_paths) { const auto is_driving_forward = motion_utils::isDrivingForward(path.points); if (!is_driving_forward) { // path points is less than 2 return {}; } - - // for old architecture - // NOTE: drivable_area_info is assigned outside this function. - const double offset = planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; - utils::generateDrivableArea( - path, planner_data_->parameters.vehicle_length, offset, *is_driving_forward); } PullOverPath pull_over_path{}; diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index fc24c3d9f2d20..9d21dbae99171 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -114,13 +114,6 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) continue; } - // Generate drivable area - // for old architecture - // NOTE: drivable_area_info is assigned outside this function. - const auto shorten_lanes = utils::cutOverlappedLanes(shift_path, drivable_lanes); - utils::generateDrivableArea( - shift_path, shorten_lanes, false, common_parameters.vehicle_length, planner_data_); - shift_path.header = planner_data_->route_handler->getRouteHeader(); return pull_out_path; diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 6dbe0559ea266..209cfd181b0cc 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -967,7 +967,6 @@ BehaviorModuleOutput createGoalAroundPath(const std::shared_ptrparameters; const auto & route_handler = planner_data->route_handler; const auto & modified_goal = planner_data->prev_modified_goal; @@ -1002,9 +1001,6 @@ BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr(reference_path); output.reference_path = std::make_shared(reference_path); output.drivable_area_info.drivable_lanes = drivable_lanes; @@ -2286,9 +2282,6 @@ std::shared_ptr generateCenterLinePath( centerline_path->header = route_handler->getRouteHeader(); - utils::generateDrivableArea( - *centerline_path, drivable_lanes, false, p.vehicle_length, planner_data); - return centerline_path; } From 2cb75ee4d0c31c62a6f1c34c4eb1ebdd973c24ad Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Mon, 10 Jul 2023 14:07:19 +0900 Subject: [PATCH 116/118] fix: max velocity display (#4203) fix max velocity display Signed-off-by: Yukihito Saito Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- common/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp b/common/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp index 0520b7292080f..098be3a93ddd0 100644 --- a/common/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp +++ b/common/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp @@ -77,7 +77,7 @@ void MaxVelocityDisplay::onInitialize() overlay_->updateTextureSize(property_length_->getInt(), property_length_->getInt()); overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); - processMessage(last_msg_ptr_); + updateVisualization(); // QColor background_color; // background_color.setAlpha(0); From d4bb8bdb26faf17423e4188d97042b982764a603 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Mon, 10 Jul 2023 05:12:57 +0000 Subject: [PATCH 117/118] chore: sync files (#4205) Signed-off-by: GitHub Co-authored-by: shmpwk --- .github/workflows/build-and-test.yaml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 383eb2def936c..7568c89908fd7 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -27,6 +27,14 @@ jobs: - name: Check out repository uses: actions/checkout@v3 + - name: Free disk space (Ubuntu) + uses: jlumbroso/free-disk-space@v1.2.0 + with: + tool-cache: false + dotnet: false + swap-storage: false + large-packages: false + - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 From 5605b19a1d0d8fcb4d9afb45a08934dda7e595ec Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Mon, 10 Jul 2023 16:08:46 +0900 Subject: [PATCH 118/118] feat(roi_cluster_fusion): update default value of `only_allow_inside_cluster` is `true` (#4212) Signed-off-by: ktro2828 --- .../launch/roi_cluster_fusion.launch.xml | 2 +- .../src/roi_cluster_fusion/node.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index a946da66f2488..d136cc9393703 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -74,7 +74,7 @@ - + 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 af3dd15d98abc..7b0a181e3dbd0 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 @@ -40,7 +40,7 @@ RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options) use_iou_y_ = declare_parameter("use_iou_y", false); use_iou_ = declare_parameter("use_iou", false); use_cluster_semantic_type_ = declare_parameter("use_cluster_semantic_type", false); - only_allow_inside_cluster_ = declare_parameter("only_allow_inside_cluster_", false); + only_allow_inside_cluster_ = declare_parameter("only_allow_inside_cluster_", true); roi_scale_factor_ = declare_parameter("roi_scale_factor", 1.1); iou_threshold_ = declare_parameter("iou_threshold", 0.1); remove_unknown_ = declare_parameter("remove_unknown", false);

P(S5IT7R05$@o|4m?=ooV_9!1nQ=v9HyEqnh}aenBFIJ{F;7E^o*y zYo5UAb;hNupWCHm1Q)<`StRFQ(*m^8?=soq=`lbMfX5u0BLEB>nmaoOCnj)oSX^+H z51|$9#G?TSS2^& z3U-MA3ZbV-77*z}T|D!rW9ZDI%Xb}}&A;ML1Qi|f*F%1&|Ui^ix~>jWxlE$1vGR#NgdoZlX}j_u#5EZNPsID1&~&ACa*}@^B8!YPAcKRkTl!GQ43F8N!a2 z9>>6!_3>YY4BoH%U1|j)T@o)J`pB4b;Y>xJ8Z_v#Z;54Sl))+2A*}JVHUe|zyGPbL zmb@702uoGb9!wjXYt&ongV)Wk&-bpbsoL|wfwm&YWQd}49HpH#dim?`{_lOx{+p8` zUAm`IsY8hDNeHyX0DR}lWZ)!2TrL(jB5F2dKffB&wQHg*NuDwYRE-%_eu*DJz+h7o zB?%Bajog@az#m#uNkmbgOj!pQG-W5`$!5)3$#w0~w!si1c^Qzn;lg(SB27>{-yMIr zIemU|^trphfE{O#*T<;2jbHi}tW4Ho0}RV4`}*eUoFG7Wg8IPr3#M(WTTQB6o6k>E z&jahvPwoJRYSy7w0L219;%#Ey*^V=XMw<>_5y5=I8%uwJ$$0avjyx(ge7Mq@Yg$+p z&AzC*G&!zpv)`E~Dz5~M@v*V$D*kIwRdYm5JlmwSb&ZvSE$c${E2kZr&JHoP6eQbA zn0o6d>tSqC+Tw8Xzq9bX<$36qFYWlH81!(PB|>xbK1sg1Rx~)LkSNjnw*8t{eyqz!YtPJ%hk}ft0rhp@7 zZB9lG=L2L z(COFXnB&)XTxr8j&fF`_IPRIW2bQ1%A=&X!T2}%j1As_>lHN-y&7fTJ46s&lV(9;_ z42fTc?(haqixq%c5t&p^JpZB-j*6T$Q{9Dgd=>=QtAErdz=8pn)GvBeGi>D<0O|n= zrpwUZj*cr=@YIUqy$}~FfgYa`W?ZAz+%s@&27!@cjffT)Pri3SXjcMMZ)lrtZ=}en zlKr*eQ8=^;wP;qlkjLIdHcwDXC0zXG<0QC5M+Gkn>1eOBSTaakgh75Qy^gjlE!Eb< zpZeqD-@DNfYJzN!&Ms~Ky~r}L)meuRv0aL7>(1u+v9V@FG{_QzO1J;xLK)6!^&>Sd``{%Km+%EnK? zAPy9Sh$_G|8f-5}aOsF4nkoE@tN%GnsKE03 z&k0MdY4}E_+1sow;J&L{I#NNLTb}X1y+F;F7$iQR?VWb>i{SM3>#qyq0>9=waD5%t z_bbrXr!WC}C1Lp{C*0n}ymww@< zT+Cw{f;PF9Xt~de#+6R$czR3|w>~9quzrb06M-^Vx8Ztfo3xG9EZNm8ImDm3S*H*3 zP-29Z%|j_MmgYd}!K3ra@5n7c1z`Ei?n`vO-|BX?gOA<6hur`692bSO?gr=e+O{p3 zdbafgce8_oBe10z z=_?zxpOFBgoC&W}D=Lnkx(OE0RAchEBCj=mZza)Q2yDVp`)Vu^z=1aBswN?!h&a~( z92UzuG%U&QRsR_t-bT7L1=|^H$0JHw5)J}9i&1)alv$FrDu($&-kAIMZ;G>H4C!+e zyk@}E^S<8$s%emY*U}?MZ-cF@C`IF;^54fG~viq;TZ=nc*#J$?C zx2Nc%15riV=>v0=HyAL!pHhAcYm}jg}#7%FSfKq;+X?y*)pTo)8$`7-4 z_-!V~Xg5?42XTg!Ia9fp#Xd-r#)HOZ-G9#V*XH9+TztbLStz^lU@kP0W8@Wdw3jDM zoT@!;)v>(YlPyz2KsdVehuO6)P^CM{_W7@m$dWZYgb?69V2Qkjpnd(%TYpCH{!?bD z?OUrP8I_Q?eu&csM17A+TI`=pU|gG#5&6Fwi{DN>&>rJ69@P<#%nw)zbjFRCZ+)6T zq>}2uDTuUt|4Xqq@u|_ITgb*QQ-RZQfKY)+&b7JNJ$6u*-Dil{nPI|P^tZJID$z?O z(JjE&`9<`L!Xyk((f%@tt6qK;GZc0%qSm$QF5W71q;B%;bz^kxBZTgQBZue#0p+Q! zASZ`>olwmYo)Q4`zC%C~EFfLUR2aw}11`9h_af=Z{vf~sDZ&cXgw79>AP3P%)TUQ) zcQnH?SD5_y@07r+5;i?Q4vd+5+q2C#tK6`RY zs9I*Yz}mrya}!nwK>xeBgm`A!|SO)j`;} z7DDp8+OH!QbrL`42?@p|2FgEm_>cn~M!7VC%kSU(1|xhS6}%4ttl+^D}kXp0EX3GJ3?#=3Y!*$^Slq;51iw(L30Wc zjnw8dVvW?Ft3Q<>Ku;LmE0-G`KE~q&CXOzZhKfh1q+Xf>gZyu&@BcMQU-2# zi}XSzz_P|BpiyD4!bB%*TM`7_HWmlH9^06*Jo|+`dzqIarJD?#abS`OVldW2qX+{v zTglx%8GVfF^Hq2=*&G#v(Fdl1i-}Et!PPd*D`ROoL;2D5#1#6=QeBrQwC0;FC9rA@ zAHIC(ZuHwHF>yIM9Bq~&DzcgX;cxqr5TV-)yJjfima1kbzKMvKAs%y|XZkwwc6+nt zjdB3>C!PRYA{>)5P$*IdCHWc7;<$B2kzmfmIWW9k>++9_ii+y6@U6b?0KR%4CD6&& zjEcFe3<<$%;!!^|KFKN?W_A`$GBC7P*CBEmJWrt^FK3a-#`CuWUj8kpV@)+L^XVni zAZ__{!)Q8>BL1nVhry{BoBzS(qt@u3B$mPZ^Pk(rtkjzey&N(Qq%lRVOdX@ z`a+xWtz`5c?_t{@Z^pu1k@=w?R2Dz*>Xz8jyhV4T80QSjq=^ zel^V=ltZS?)ZmfGwbnlx#q?CqEBh$vg9nn7T*j{t2?`WLWFNz%*ofZVy+bnr=R177 z$yOI}Xe{pePJG-!@{=O`TJ74q{@}2EIA(OYQ?=UKci3UsQbZ3P56mac_0Xo^?;RGr z>IOfx^nYyNTKcQ)TCFi}VF!OMX-Hd`O;HzeOkyjZDK(JNqdeI3I2v}}J1N3rtG}x- zoP_J#WS{nI(?~H=aaJ?&vXche2PXq`%#nR)z=8Hjh<8}MfkPZJ2;)P(UCs(tf>+>~KeayZx^pD8{g3?eAX;o77R}*VYC*W?k(oz6#a_ zY|(_%qHL&RQ^?YpAOMe}XnHi3Nr#EHdyETZhN+zg^-7rgxk91-koRDYVEl43hfRzO z*$P{o=%q5Zlrzf7YL1nChKtY%1RG7k6DdN43c3?MLDkr|+{$U4${*TjU!z~;)W%bG zR#ru&$0xLRbYsT$Bxo|5<*Hr4s)Q_QxUezKiY{OV5{@0-0|_9P5G8}EB%bYKd z{t?YLec;42gv}Dla{l_KqN!rCmK)DG@DVNgbeA0I?41Mmnc~&NgTt7A2h+(=S%Lb< zl0QKiR(zUlhLeadfhDHP-qxiZ&yy9ruvkI2i4A8wfKmLSWY-f%aOsxS%O9*$5~WA} zzp;nmISKJ)2*F;JHRU6jS@ED~7UJT9(B%tRSVL@b6D*T{ByZq>(0BnG@HjuHsBrCE zRauSFqw!MJMQ^)QOubcEhx)Cbrf8^XwA{MrB`-QO4nD@K&Di<9pQ%&0%?mO*J^VzX zz)~NhK8h#*Xck@g5RugP-kd-KL3oBF@@$~VG!9ohL~dj9JB4}Yv5 zn0LiZN+v7uC;GuR_~40gRTYY zSC=t4=+Y)K;^fFXRA)j-=xlK2>20J7$;`M3%RQPm3c91$15zJ9t?(+j+iL3q43I*3 zo6e=Mi4;c1r5;{_^AP=`FKl>!t$5AN>y#Aye_DV7k-yoFh&l;mL-?=cqvfey;0kdl z&=pF|H9`+4EDQ_&r0mDWFUW{8iTy;_pi}c&cP(o`n_#MPtU~;!7Rhvh76G=4Kv>^s zt&c~=PxleeN~JwVy{o080Yi&(-=r%O2+tUo5~C))Jkq2M=?A6=s`Hcxzc! z{UK!4#b1il#!Pj)vntZ3qPEZz4*|`W^QYD zMh?db%(4JYkyyW>M9G(&b(Q0nR8-n+zW0mmtcGyDPSIQWG)SFBAL3-5Xn^2uxvBYv zcX=|?z4J5}Q1B21^>bR21>T7enS~|GR{!0_X2sqpVR~31GD;8dqAEM2JHR}43$|=Q z!9qf5WAh*jx)sTvez!;q-8sd^mAQ4$KD_S4>rP13HWYyI3(_{IVER~Gd$(~%NkLHD zZgCIimRJ1|`7eBLS|}(oon_Mz0%nU3Va)H3-Q}19hoDFb8=OcoBWp^C0Z0C8?%|@Z zc8=>XiGG#sbRol}x&>srk;biD{--zuXaPXAHz@$1azKCv+=~FQ_m3(9R1A7Yh6F2D zKA7n4zOB*cd!sr{D6zCR5fYNE@)i^&a>~(IvZC2|7|WW_!El&eMw;KN@Q{)dxEWFF ze9a4G4d5xtZqZte47RmT=zO zszbWBh(Fh2_FZ#|Xou~Zx=!~5@g9vLJ8*;%#pTBYhxQGGwwiMD;At1@9>@Qwq{$lJ z%P~X1Jld$D*!TmSz4U=Y0%UvlRp~}-{wt;V6&ik8i#aqp;&H%6oHK&0WT$rmJe5}7A^ek*LtQ_+iod`Sb8D) zS>D$C5UApCBPy1Jr18|A+*(&~1~kYlU$zuk zwt=Bl#O|iwp;|^5l_&z<%QGkvmW14-_}!!U>0-U^=#)~i(005lvfhIAC3X4)1#2uo zP0=m&N2~firFE#L1A5pOUkng%*|sZuh4)sl3v@O=%uS9Ao@lP7?&ek<$L|R|7_W0W zjMP^hMpLYG`M>|A5Ug(b-XU3vEDZF3kgVP`-H7sn0fma-y{oZ8x=Fn|w>7VLDF%h| z33LquLE#P^ckW_W{6r6Py<@&&R1k#JuWm;|Bef#fS_T z+72PNcY~xR6}v2Uq$C`9flTKt3K$4{tYAAHe3h{I3~VO59-G2c_(_x zK-7Oaj)?s&wINAvS2EV`g!TQE_IgBR`?LF z)FcJ>&Bq!VThd?T-1{l&c<86RDnzDPi0)eG?eBQR>J2@cdv`s9!k zOlx(@Lt6Zk`IH=fux_%-UbF8V%$X^*dOJs{f zis}X=e7UMvq~?y~3Olx6=`va3388-3TGi*)B&|+@e!$Y!T|?+~-xmHU|9z5X4xvS* z%Bq|1o{?#t0kWtVQ3fXmwgkuMih$;C)W~)x_7`xsncnz|{AYne;fgCSSfk7;8=An` ztd9u1xrN=U$frc9U&1gW`mB8z5E}$dLp8Vg-PRMdid%rdw9nFrC-)Id(uINX1o5qW z%pN}lU|!`ux_!HBFg26Yk;hn@qUbr_gaW57H3SA=I!w73_5fNm@M;e=nZ0hVWD z0EU3&zRdIGF?mkM^U;^k9>j_~*>sKN1*s1H0_$|*y~dny3x&|bbC-S5+aNoV9yVxQ z>wXeU_276{9Q9;tcfm7$nYPuStdv}5>~%Ok9PXlM$2m$@`dO2B)GLvPgT7>f>97^o zej(rCAo%jvBuga=phh#k&C3X5Sg)Y&Y$$bK7&FFpfX(wR-*(0UMr!~G8KMq4N!xu@ z6#X@e8RM0pnuWfloc|La1(a9KcE#50A1#a!36?Y6CODxLj7!PU`}m#-kbpb+`NiJ) z#L}yXVMrVP)ATpDbo5+JG}N4}J18RuH}t*qmfkqkjuu6&vdI@ME>Vkq&bD(s1e;RI ztz6rR-7oXVex^Pc1n2Tq9n3~LbBhPIHRWtI=SXlq%|1TihgP|Mz<9Gsz4gS#Prta! zI~hYsU<5IJ5aV3q*v`qN9a+U@00W^hC4jnpza$&e>iGm;C6-b(2HQ{nWja{6D5v zdAl_7R<_!pV)Q|9ilvC|($^lfL(<}_rHU|Z7@)C|G$NB7sjA*~joD;~Y)9C}HUanI zJp>DRDS8>mHndhj-a6~%`4vXeGSAJ`9G0!U5%Q1Y5!G3KK08$%SN{iVX9{%n^dwdi z-OFBA4ay@;!Fz-xyU%3xFL7RPl|YZ+)IzesJ>P#ki(3~2i5~2BCJ8&HT&x@t|E0B? zN*Sp*VczEpKZ$&Ld`kWQ^SiNgg$zSoKDR*=mM*W!&k24=|NcksHi?U+pLSmkOV zMxF&hLdM|gRs@G~_67voV#*;|OLEb~AN9ZcrRiqg zb+G8^!(FgS5E$F-iNX8Og@4`HNF%W>x$oi;EzXR(1j}*H5@Vz<cn$dB5yPM7&iKMJ9cG_rs$lHF) zdozJE>wvEQ6`Z2p;%7Q=jVcE$Jl(G)k8H`8n7pb0KT{W%K(JbZ!U(mDpOo|KPu|{qdVMry4 zp@^6plAnZu!GkdxBFdYpuZ&HscfEmqkvXt7s=D@mB-OD4RyA}(xp)vKSJzE8uSHkK z2(?tHFrY)Hd1%wy&#`0*5vi$C*^DAE1RSq$GPVBn02B>{KXN7AZw}-X18zGV{oed2 zZ89T+6#w}S#nf`O*riKi0)$V_p3Yz7`2uNEGrc505%YBVX*sfcRnsUEgr6zYWDneb z9d3pf6r+jD@_#J*nHbIuG_#R)rD>#q(*potjRARoteKh&kdHW@!3%U5=T~$kRL0ruRB94evb3rlDvWO$N=@@Po7 z68u4QVW-pt7kyojkU$Nz!Di2ijpe6=irc1LqBGgauT7VRhhnA+FNd57viBgdriJp6 z^eRd&`(|}J7`PemGbhQz|I9xDMLB$1miSVVwC%K`dj5|6&tnYsRWTnFv`JiMFz^ooFKSn+0 zUaJ68#%UJbUVgN@tyMUQ&m>x!hV|g}0UXkq_oIov^Unspip{ff=;P1(^k=GfHL;_2 z!m+h`mF-_V^3XYT7M%O}nRKRu^AdMZe<8vt^@{Z+E z4&M26drvg$tJKJK@l(5Ro83=5hfET-3z=$Y^Dv20Kdh~wXq$Rv=tOp z%NLa!Pr9#L3a0D+C)*}H72C#weho+>>0}n;MR3a1jRzkQ=k2ncF3;o1--dT)~aPyXTACl{hI08@ttM3 zILwX$Ae$V%6|i9bXhd8n)nqVulU7zXev9@epUbB@j`l2i)KK1aI%1}_QOSj_t54-Uk?KPvsN=fKyW%=eUn*;YAb_lhBTETjzAYnBv+;_E(~Eo9 z*G(Gq0Vi6)u{+0vFMNcs7PI#Jk9S(qXo_n>3=xnvE} zYUi?OXF;Q`U1!l0$zIKrKHv;4Z`)J$@xOuRZSwmlgrgiW2`W z{S}V&dyU|-Lhh6ELLP%ZE|(XT0XxJ;bg-Lw4_TDw`KhPk7P%ws| zOJ;$$b`>Q+jOjHhUh_=4wlQVje;7Kdr=+|*TW!r+p=~J5Gt}&^VSe&npPGsWuG^M%4RT`dFFtl_eITxo*jK`=zA0fUC;=vX(M+kxN9A@T! zo9?i`Xu@>qLkooP@5yYE${IVP$Rl$UZO9|#GvUT`$vzli$HDQ4x$or#3WzefoPZ$~ zDx{3DkGD`m?ZClosN7_lO-Rc?G?st8ua(1TFl(+!i$HCW<+pj$^V5ktK8$7OwB^-% z-OpVe=qEzvj%JP{IylF66YgzUQ3Scs0DDXC90ZMikJiC(Ed5QwoN(9XYAO7}#MX`qUHd^+5;vpQU5HT2K^4f(J3W$;=mCWKQ*L zla0fBd}!6ldS9Z{{IZq~Z?#do>i5ys4pXYWE^POmRgP)2KV5966{N#}OwZz!{dzE* z;fv@+NOtj12Z?ejcS!0@@@7sTna>HYq(|xEU{v zX!wRsp?CY$;au55WWLyf8{O<;z>xaU)<^#BX%709)i(>XoQpYm1RU5viTF5t@Mkvu z!X}JAHp?J}Ve~!nym~>(o@czqTU(cP$_E^@YF&c(-iKLu+Rmr4VZ1ZYm;NdI<5U|9cy zX6WZQzIMHpOM~_ zziC*Ko%uY^)aAY6Y|AEOjfKP-J zOyW8i5iV2*rGHg7kB6kG=3`mTV=&xf3^8YWfAxeR*=`W}C`Mde7@~!le@J(?<-E{n z?X~lR?8~rYAM-wpijF7*m2Qbx?i0ohCkQXvrpy}K*|BbqZ4F2)WdD8~1j}xkN1HC2 zS^p?*0;t$Uguc_A60d*#-58o=mT&Q$peeU->gSH#b5p;0gP`|_c-5UVUt3*4MGQaV|9>nQS+6UU#@8659QNj5=#x{0YH90Fl0 zs$l)R3HJ!nJ2FZ;9)uFNV%z!>(~k+OuY+P1)BDvHX}fu?O0 z*E69lg4mS@-9_Q{V|B8wK4nudhg3ZMex^otAYcV}Yb719|SBSC(Fp#fT#(Dt)@Ns%^#P%XMwIj0mIC>_KVJH0e zu^Rq2VArsY2@vlALZ(z@s}maAksA}qx%lsH4yp?Iwt^8V{H}Sw%DVj0Tt0A2N)bq5 zf|(GN@pjcIWEfrtddpuw1qpa`9DMM8-KBaxdc+^uLoQ1eGCd6np60z@J}%mytQtb92JH2&0~Rf4B&*XFnwCBtO2%!A?Z!f&hY+h@H{^dcI5 zvkj#@87!tl+SXlG&ga<*&%+gN%duyXcW+YjSu>L+d~bw-_HL7}HSB++XEj!Ns;)-f z%hf*HdRdiC8jXB^)jamXfPIwZ;?Vi!i6vlw<-8m90>~%}fPKLS*-k3x{WAR^of$aNF=bsxit3sTxD|v^-)T{6E!^T36*|0Op zBo-RMhUiRduhbukjfwwu+!@x9KvSJx8ha~>AyHXO!9BJyy%b0BqW&P@Vjegy`Aw0W z0x)nrJe=rQC2%~(ux28@aloAD+T!LxR1t6r*u=vAW_;c-My za6U`Hv=pK~f?C*(KfZP}-){!>;-9!lL!nzDXk-l1l_<=%=@jjh53@$c~ghRQ~d9KHhJ{%ek&+hu=C5AMx{B z!pQD72216?Q@}t#xxOt30Z9y2|NRXmk3!z0OW`5!)-8E{oxsB_l^q}Q*eg19>|cAO zORpNBk+^mbZH4=zUg2XDL$>`Dt^R*FbiOiJkO zi6=s(w%a^n#uTW#$1CsKqA9#RY+XwlY#r!>0-%3(D=Eav0~HACIYQc6M8*r=C^)EC?p^!EpIE1dBjg;Hl3k1joZ0;2u@{3{IM~Vs)?<>wJokg3-ukROPA$UhmId| zrXrG;G;_vaXmdlJ?Z6x~b&dL`B^7J+1TA)jMY zwOwK{5w~AfVt7HCQw(!7-bfDjOS8*%yYXl_?95F)_*ns3OGuCTnptZ{K`}kU}{OB0# zNm)Cu)VAO&DUz!;5Ggp^S#CX^?2iP2o+v--C?nuF(gcmn z?6rUQw_ZA{wJPRukCI_0?tJmca~*D&;861p*o(@mIz$I*lK5uia>4yLKg-iMpBb%^8#L`jXO8v5Z3w3*I_l?`8tNOeS2Mbf7=eb9{V2?DK5)f4o`z1DIS& z@3ETO%Xnw+0j(*tyblz3`tq+3N-_jt19>AlP#Pb!NB1c3y%l%U3)P6f3Dx zHW??qt7ys35HU^69nbicU?i~vikM{UQG!bC)#|UHUGC`tf#D_ceRCv=0psj0#!G(5 zZlr~Gg()&Ke8ZS^c=HxJ9u9o{_lecpNLjs)yB2?&p$@|`qu2o9BMRGJ5ZYWE2oIO@+-tum;(8p~YETN{$TfP%n zRyC}I7T|iFo$Q$5o_yf~m`?*zO($2+fvCOL9_J6J7TPbse>~z;kcM_skM7#8WjAUlhV`(OF5c8Z+4JXMVw{eHS>fh3hyzeQKakr7qx= z&IWXW1W3=;H0R0<6%cS`A0DzeOW{1;Zq2Fba%sZ3>07tAK5P1u^esAg!!;$lYJ_Qk zUp-(j_;Pp{F9qrq4 zAG?#IV8F%eA&%*@f3m4pZ`Y_Zsl<3ly9T+&K9B0)l*|5KY}bPy#6z+h zaiqbjY{#3OO!2sxP1{1ZhT-WhjSo5fi*^FSmz`72o3rwJE`ZM{JUQng&Q(j)~sj}0t=fs~$eEEUgO5-Uy2c1)|PxbbAW`Hi58TOHk zLobYCuE<|UK-2&%qSG6Px&}s)T$rHu!G=8g)|O#In0`-@U-;w3C0|}v&z*628<9)3 zNT)|Od*F_Oho&BhlYt8#pzB^6wF6JK-Hc6OmFW3q8_%t6RZ#E5UpsSoGH1*A`az2B zo5hG_9nkmsb9i?izP;nL_0S;noASNjWVlBjIQsik!itEhN>cnPbZeUxQbc5taAZar z1-u~nDV>bxswo#2MoiBtlHJx=4=t!aOTp&hvP-EFLCoE(zq-z}iH}a12N}ez+sElV zX5UoNDHBdiP3k;jrVcJo$qeW4afW!9qWg30?$ta8^Bq&~2*3;DwJwq_W39^XW{%jM zKU6%WQd^sAB@Cs?^*EUtif;CQx^v$Ayf&q3{ypc(o_QCSPde|&t`^ax1#$jQ3y@Z?qZc;LRmeATU|1ZM%Pv)c7x2r^kt4XsEln~BTp&{*;OgTHlHB1V+yp}a`^H-i|65ue1-YqR|b7K#l zaF2kK2>wO*%RGC{q=7G$mrA2nUy`fKBIiC1x_*_Lpj4`DCrrcMPyZKN2#_>d;-j<+03aW85)|W+hcDOs)(1K$(@UL-X0M zKZ%sC-}*z&;3toKcX(wGGK|>bQg;Ek_&EFL`d1stQTVqp6gAOK!<{dA zl=XcqMN~%be?pWLrZJ-tE4xxtb0%|2wgO*;J`izhB@g7h(g+1Z^CDiXmG8;!T+h;9 zRi0LJ+gNmVAy3$Z492NNtGcbt@Lpk*9U=sa!d?0otocMISAcTRbf$$7hg5FR^w zQKpZhwdQTBzZ#D-8`{=SJ@2pC07nzeO>DD$Qd3q6w-tzVqenSWS320w^o9kA$RNd0H@}1S&>ch^4GwVbrzKs zm`L~kNDbkg%an;!f_+aJB$IT&2ELBuEoPajkV2y>C_DS`Yj$X(!NoC2-Md^MCEgoR zV=_cY><0;qejy)9XD(1x;bie;iYp&nn&3=DIPcxs$Uy0(716vCbaG|edQ8$~l*C3d zdle*YSoe-qkCl{_bgb~K`eUt-BK??#S$&IRL?q_`N&}nk%$6?#qKFI{WFHn*WwYO= zwZa~Wlwz@8CN;5vF6 zwOw-9T>98CDs19a!k)r*M}YuMv)^UY&X*SC0-9-9$OCn+Wn-bf>i5*>$vLJ>!SZA#WHaQ1}g`C3BETXq-i6U;0O zcNGsR{qgfY1RFO~@`l5oU4ZJ{UE`*c`;cGLw#OnjHnKh?NjdS0_y3Qlw~UMWftH5_ zMG)zd?rspI8>B>F>25)~I|Pw#5RmQ;C8edig(ak$1(sfx*nPgg`~2^H0lZ@QEU>fZ z%*>f76r!kV*tBfyy`_5ElJ*EtEq9^&IEl?IBFal}K2`XT*Ga=#E0;e(^@3K8es3^f zKQ!dMc7-LQi(%889hA=?L7Rqlum4bXM}k#hf?rmLpoB3PrI#t37HC^F7%#_!w^y-^ zO*hse)1Z0v$^3#u@9F8Ia1GyvU{b~JEnG5H|YNXn29co(3&;CUvTR;Qa1#E3t z-n1~dnDzZIQF{p5;B}(p*~T23G=_3RrVteGGAZwQSwx(0RbBijpD0U8-LFNQCDPDD zq2Y;vK+~eMq0F2@m!tcLZWl87d`p)+R~6RFZ62vJr2XCBE7!gg<6rt3Co$^o5qD|K zbN}znTX@F|ebEqrTrn`1CC`$84A_Rg_~p6jPK21`D8t_dn|@%2&sNQeDcWKgH)^a6F9CSM7b(4)OF8bBuz&-p6g7im%|79*HkQ3eo~?s60}2UeXNtccA{S-_f}RL z=r^3%THX+4WDsTO5oNsD&BktL<+};HG@yMM2?=P=rr3pm2g-VtqbJ>s)3=&GZXfWn z2YsWBDoJWtpI=4Ul8}7gjwiel+U>;WrC^}@*GmnE?X3K-FQ-<&7R;HhdhDP4cTPtE zgL=a#VkdcL65B`C^(P6K#o?BfvDYsLg!S-zZA*HiB~2le2=&L_NYNK@mSe0!;)c4} zShT7tydgZffo7_;VD*63VhPH_RUEOUrXVN95XZwrMaOx|8V0Qx8=YU=s=A^(w8XkE zTl{(zy3BQSc86%?l*YTe_U`TlPqV?lpMtg5jG~UVYOs=R(tlO4lh}O6cp^Q@j_7E0 zX@j2%ts|zTd>?v{&;QreB>MX%v-uy@v?(zVbX!bWu3M?Pv!OHSiu15 zFV+G`Z|U?mJdnrW#mLq@7q|yGHA&OsL7Gi?RWx8`lKf4nPS8LHWK9O~m+3K_<jD8pnIeQls~Q&ArA@Gm`VphTk0KVxGu$m>dNeoT`^I1pSCmVGKdA{Uq({{nqK5i-KIX|&ap z3<;2;$*YQxVzCNv_I>&z@yQSoNz^X2!nUbM4RbjnN;=!aWKtaWx52Z#WM~Ufr!U9m zE5mqYg&8**8l?r3MLRfU;n*+Lwv#|q3#d>uO=$%6&$N0hJ|5kIf!k23aseC=AUxIHM!=MyMBXL zNWH${hJ$J@>tf7NqETui3XHtN2bVkvDdL99$F2S=?SV}9Wn_Z&=I27%@IPy7CLlL^ z1s&baKzPa<9#cl9olG;W^wGYqItShAg__G%DD3LtrI@%zZdd9Xu2c!2B9h4Og0?4! z9cbkN^*T;S=4wmy^SX9)*!Xm)l0oKM&ILkY-5XNth{UsMLU&{U2btuD_o_(|74CSL zvSa-SLkD4(#=kFgwzT8>il6Yw&<6;QH$(hB3?EM$^AA}8w~i#&EGAzqY5nuFmTGK% z;s~*ueJ8S3N#XeRJq3keboc40>SgG;aw)s4Qu-vzu<%;l-oF|C_(tJ6vz#l?aOY(7 zh`(c7P<#E57v2;@p#Lad5?w)%;l9-f9^N|P$(K|Ai0)x*5_xx&k*2~C{xMDlJxm5A z_9n$aZM0&A+i2`A4|6UMMagXisRrtG1!r!1axw0m#h+%Av3D*;qy)XWw+n=}7IAOk zJkNMum@0Lq2$x3DB|&j_hZ%GoK6KF<)sM8kNz2gF<}qt{Ohgt0!(W$i@{Kcn^TCQ_ z*bjL(QbcP_h7+oT$@9Vuq?TXzQn~HSYT(;0h%iT0#e@E<*V2B}IR8E8LFSv2*c=ms zU&ggdjyy|}9oyT-WS7UlLT#We=)B-od^T{QWCw@lx zyZB2ZOLUy=604YKHsJm#Z>L(15(%d`l?v%cAjB^2$!B2|m3#~@!kf+4#7S(FUi{*A z*YzGW#2{JGAeSrCrmweRgypT^)Zq9S8~1#ZQ`|wtm(kp>DJo?Zytj-#6b)D1pzBn` z0iLA>)MeSYXa9H-s_mp`AyBQO{26umQz&(-PPnvd<#KV)s@vlZaR>6A#~JZ}-0=;_ z&UzqGy}nT5BGyT#+d)%tI2J#!Y@>HW)M)Qa8F{w=w5cqLq#S%Vv2s}L!yXs zQ}>pIG)H7uEGh46+e(kw_xBPZ`5C=etVS~9_p$em#I^Sn1_ByRp za#>$eV=TWWV@~|rmnrlpj;7UC9lh<9=DEC10s%8L6+Yk4;xWs88X_S5&12d5nMLfK~ru20e% zH=a*ls2ZEGH85D^t!Zc4P};a*ge?Na1wAeZ{8ae& zxxog*3J#bNb+OLBiO-IXwfWQcy_&|j?`cgtK7J7D97VFveN8(;KBR4}w>{8zD;do4LTWXGfwqJbJB&yP z+O`Vidyp8$V4vpmQtLL=GBs`Zw?wXl zRMnAUdyVSkEGbf=-6{Di(@@k=fHqjxgOL(X32Emy|Qt_W~FU;T!L z$;O{E9NS3G8m$AB25G6!X&8KAi`KFY3t83TwkF@T{XUjqOB%YP=)~20Js7(U?=CzP z70nN0<0mt~r7{xx>6-q}Pa9+8LjQp7=VgMev$;!v<;LtSmBEZLR?O=IeLr<7)Md}w zi@X`HyC)RnE!SB-a^PtLsk(GZVDZy%N6wrTC`zK$iV19{7b2@(Acxlsds4v>(q64Q zO9D%U>dE9gw*k;fs}j0F#c*{`IsB4{tVsXA>X8^ITa@G#-;2micqNIy!mjCD@4}!F z0k-+0->h0_z+?)h8blkJNi?~bIUdpCDXgXk=M>GsA5V4hjjW( zX=2vC&7pAJY0QM3eI0{e2W@v-xErJMwVyYgCI{Q4rpCjt`lUBuN1aGYVp#s4O2hwv z203trch=fA^7@!xWa35+*?Z+|KLIktmwRLeum9g3bI@0kDMg6`1Q0c>o&u?Ib*1?P zSGI$X;IHq79z9bR0HPAF?8HY5iw&&n5K~3Zqgn!b0XLl}GXW7xd`(DZmcExW?r!)jmx##(Y*G6} z2j0ddQ7x+h65SsUyVSXiKHo@}=B@kZqby-lA(#zj)fXpq3@maLj?%#5#BUlofgt2O ziIAZgTr6)TG^Pwp8M=tHElEL?C_;rlgsX1$CS2iPMgr9X**oAyRxSD3_fLzDWYiBw-Nu zp}qf5;uplcN3pZ(eV4ylut$6Y4jt2qb;U$M(@VN2y0$lW!GD&U)Y!}dC|@%y*XJ-$ z<6uQTpA85H9Rhg6`4cQOgZmf4bp|$z&d3<4>PursqgZ2t-`YFUr1Tu#K z!tW~jLr+})&`@}Sry1+XITbc6R!H20@e&nx{neZW#v68vIPq=JhAti3%sY%h2WXhd zl%@&TfTnBNqezK!B&>Fji>JNV5S?7Aon~nD9xdmbdbVYxL#$yf;rJ}UR~XbnwJzaL znn%enR7~?-_LGR8L4yJ3Z)0wQh1X*ZvJ_vjsh_9)p?}}fOW0M6ktc~+ghy)r$}v>o zLkwbcoeFd{O7NS=6>l>%p+vxpVF_atQ%0g&@8jh2{%20FAH)W31TSwKuGdV+GZsTZ zOZ4TF?)+9W@2!R^oH^?KW$uF9Dsuo6j#2CD89nsC#nH=ED+VKQZ zWA{dq)A9|Yi3YC8w(rENCP>$8&Zl^nsAqk`H-~M%{H46@l^~vfhsnmrOtbU!@?|!? z^+&4Bxg5k*R&qB{NQNU^T>_UyiH$9mC=rY+;q566fC{Alf&AD1F|8qLzEBbB#Ll1x z?_krMef|F+DAKeZd@vR97GWASniWh>Qqo-M&;bQ*%cfNTRs92|KOoH)gs#djW)n1_ z?B+KmDlwS5rqs+Gd6k;Y2}+I8-ZUgV!>fba zmplptm*9;YCePBJZ^UQjQ*!K2oVx`6vxy_6NzoC|P*!GUoD&@=C*hG(vWK%QdNr6J zGW+HO@`-wf8OlywX*8EUu%?ySlmA70=~2Di^zNe96Ko^mjO(-ihL+V0G$TY0GsIOH zQlS~u@#1MSx7IB9i<2rZR0_;S4!r}8DH-A?& zTDbf+ta4NruNYp{$N=6~qAJ_*q7*94*{xZ4ft>&#=oP~m}@kKlI(e*Q}Qr_!8|A-o*J>+ zULadQ%IP;xuLv^Lk7ZM>Dl#_#|1>7(vg$I_;>oZ!NGF%+;7-0%lUsznaF`GD5`~tO z#3d8RFz=Dt@~#tF%In9T1bA*F<38^dxmF~ql*P18FRYGnZ2r`|{!`zDHG`v};X`B%wa&&P82|q}p2R#7|uk2^A2{1w2})FF`f?zg*@`iPU(>r`&X)H~eDT z(^7`lhq;M=)Fk5{@(d0^?ba>~!4zRPD9@xW#?~$hh=P{`lq_-i7n;&c#QpMdGO2i8 z+Ve!;C3m)GY(yY3?KF%ZX(xOM)4FuxWYY}cAJjZ$8GB_n=3v;1IN|E96)F*GC{WI+ zHKFg3c)-7G{}wMtbvJkkDP}z$GUbOcYE#3h3WVzq?~nWv*}hZavhe>Tg+7u0Kb#Hl ziRFCV!^a0^e&*)q_akddQS9MA&PE1#InJZRcGUiGws;h3f6VzLX2_m@QU6uMV|``T zAD)ATnh9&t@oun~Oqd}eVL@Pg}{3mlN&Ghr z+SEi($YUI`WRgBCvN|_d_p&>)NG*oy&?)f>r&jQNwx3wa%1+_E9XqO#E!n>>uJmj3 zAKk6WmI zs~neTU1y6Q5EnJ7D>z-5wl(-^oCk>r(MPWKXmX|xklML8`x4R*-eB9rQ9gv4bFBo7 zbrziY$IvbJR^#E*(K8(4vB{cmiLaUCKS}fLueB!=1y$MA2GQ47@8J6d#P+oHO05!R zsPdQU>k>P6^*Xiw9wbOUpiJw-lp%E*V8BNs;;W3}u`D48L(ymb#;uwT5nR2AICWS4 zexRge?F6RFil`B3uruP0$Wy?m;AE+0k2#G9Y#ihyQ7S#}|MPQo)?V!m!(u>KJk&A! zr9EB6w?7|V{D3JrB%3JCzDqNK6||v9tIE_7y)Kqv!z`7ql)p7KO))Vp7~`+JjYRSB zQRHFjYQ7_lS|?O0IefO1T#%?lK&1$}9*lBLsDZNGOD^AwC1Sw9&RhjVDc{rdOAkvK z?#UEpjWKk`<{o zubKPA=(l|lc@^uWc&sRf7)?s@elaY*QKMuibV)clZM{sWD%A*Xkgsc*={BXi>d=t zT41As9uxn#hTq4QWsNT1XbH-Tpv2ba-H?kQ`$IyDxMuiAmA&$$vs$+Vw>$ip&$Ty> zGOXcBSCcNC-Z=`r)u+pO6-5V0MpO_|I@Rb`j3_`9=a7V_@EEd(VBOS zce5W~g^-xJQ9!0z-|Bt_k-|8y=oaM8x22vUO^#ch+ zh=qS?PT#q>)0%8UV9p@n`N&Zq4z0g}oH`=34s!UA*Wx5XiSwTqWg#0Nng!jMH>ZCq ze$c&6Y##xj=P^m?f!ELzMkY%(a0$NnAz1n57Z)(*p1K*Y&u2QD0s>J>!SheD2w!n` zacZE9^J}gRRHsP_)S${X+7LHkjjQC%cJ{il9QOt^W{p-oDF+;Q>rdFf$v(qR-Fwig z`oWg{G%c+Z`mXZ1i@mvU^B*k9e+Tpln7p-uhNa+=l+4RZ=5LEf{E}q_A$T?yxg5mh zt2YL_C&e}xbQ+fba4(Z(k9P6Y1_EjKMnh)k%o%-Y87&dn)?KfQG+q=&Z$Fr{s>jA` zSP@hz*&hL`yUfq?ygtJZFW8WQTkiC?0yHdpMv#ge^_Hpp-%mp#Bu=W`t8{hs7hv$+ z!L&sqApDx7|1_pwbO4&PV$q!PwLSX+a<1fA@VHa_#tGCv5iw7XrgM;FWQd2{=2Y8G z>zhdQYZK3k#Wi0W&fkA&#j)Y)T`3{DOb}(vwj-f+Y3R9!_~=;# zm5KO3D8xVUP+6G1@mY^E0rgLd(|L_6&ZFZ5mIH#={iirU0@?-?-y~bL%TPS|XmIRaMOPcFJ*v8LMe`31aWf|X|u)t#A z$_i3XObP2OTb@6(=sH_EL}6-%vrtn2`;JFr7xk4%;w@B)~Sq-A8>wWyT@ zg153rHhh+nvGVsZgL4Q2p_Vec!Op!tj#$DvAF_X;6w?rB9(N(RJt&K@>0YL3A5qiN zcsUL1ZeDREjLJ`aGPqqMo|m#}x!2Zq$cpGkNayXnrMn~jkF_DrK@Bdkybt|7=oj`X zWQ>hA9z1NNo8-R31hP*PP^#4W`W+9$4T&hvO4jm78aRw=s6YwTCbx2LuPdZ6jOZSO zC$1Jsy~o(<=G)2PLN4FsT)D;^RgA?bbQRRucfz34=~AE9^Z#CMJQ%?K&oSm;nbqIw zG!BdxUwb4tzVIz^GP-?`0FqLHmhcHNU;m&O z?3MokDD|%*0l`uno5ii84c);BH9YvDG^4K+DGluel4|q_^^O!9E)ng*#PmQFr$&-+ zvryAwndO7_PXbuX^>VOrY2Wr&$J=>y$VHb*r3lY;(=%_wG>M>!Hy}pYhh&gsM9KN* zm5BbWXT#RbNd2wgn0ie|zf7*+o?5~ml5a?df&|_etG%BY-8PL$8?7tpV@>5hP$ZBX zit@TOm60NVhLi>@{|&rgLhID(xMv&I#Ds7DR%Vo4;h60Lf^!?2J|CGdwRbJ`5`{Mra$^5~C`B3!!IGV4p|iacqo_knT_@Bm3M6Sii5dh^N6ZEDccK3{b5xfOybk8 z%wm6xP*deVFn$ij_XpZ8#keZ#LhTjYp#qZE*WRkP+i0IU6m*$nE3I<@%RwEJr%3}D zO+HF^+DPXg#}=ZVM-^|cZvqiBu*@5BrK%7*CQIgG2^EJlzNplP*$-l@(cBy{v9DuJ z(;eI7iA7|iF`^q-GPr;lq%Fd!VJNp?a(GAr~mDel~GAi;o+#_f< zWM~v;d!GHWb#)7dE-O{?^2;zRk~Dge88xJb<=-iWn%p%??i-@)(|^($H9|^Ot|qY( z)MRI8q_+XaV9BGYByW92{p^vwmO)$zc2&kEZjOeVtiVQ#-yQu_siKr3?>Ilid#IG@ zhZfNq)mEByf54{XF$0-O$k~tq&0fGyk0YJ?rEL(wjp>R`Vl|F7f&@<+goIVmyUPa%JX*7IKjed7;oW`#*bkO5KPLf$yvZ@> zeAtBNJV+G(NLl74DKihFj&ppUV)Ht$a*03r@?41xsf3SA0|hsPhSdCltce>0)+dKSWAMyw z!nc2dt_D84O~eLpJkV_8eUY!A{LJ3;g37SuXEDhYG*WpqkB^}FAK}4arq(C7V{$CS1s!I&eWs_zVzSvQP>637^v zP#TlwrR?S=1Ajyt4?+5nOy{TakSNvm`Weq}-Uj^JlD12jfnh*3_>#}&Ax&gkg|iTe zSM}6g>w0Cxbc__YJIQDJ5&JhB3H4^P#ytbtOa@(lh|m@W(I93aHorUMFnMicd_2Zo z#R+N@BK`{eBnmTR8>45b1BaUhm)_s#k@P&u0<%DiK5glMm&tv%UcH@JS5Z$_Z!<%* zSk>sa4<*%=?^C?Hm?OUYWnP|4IQB95zT_ssylv>OuA81&Cnpw3f~rGwcth^tr+^4S z;O-B;);9S{6dwGC26t%qLGM zoG3vFULbQ6cLHa5i;XAYgR};mMfbk31hNjMctlH-zrV@>N&SPd8gTQv`nFMPOZT#&;3AA~4h zMKG^^@xPeh8$KKZkG5rvv26L7k63eV#ocEE zW(a_ZWsyaKL!JQJNoS_ccP+)w2I<;5gP$6eanGGp!CsA72%x}LT1CX?V-E54e})+| zDjLp_xG{)NFbVz%b>M4Rde2azY5WCZB0){Ia20kB5u&J%VKhTw(FK4GSVG?tbpp%!B+7-)b6y>vE=Hq`0izc$a)CgGJ#YhO?OaAzN;0)AYg_1Bc$ zn}V;k0v^@b3Ub*Gzjg3*0}&kcXJYqQ5#}k)MP4KpgU|N@+5buX!tLSvNWs;emLxTq zh@6omk`>pO;Hb}IJRe4RCCkF}P-7=_gvO>P*`1i@caS~2CsCBAgY)UtryrPKf5{D% z*nW)u7pFWBqMm|?-0>jJq1!zDGt<=M<6{jLIx*`h>|QF0D>SZ6`3fi$fpCJT!}cP8 ztXN;OSV>qCx%~FS_nLpF7fK;Pau550Pm_YTz5}?= zXCKg2AoU5eVe2hiYtF+LHx#!$$oGI8P{xT5Vs<#c$=d6AqF6Wd{E;?ydb6s@wZYI? z{(?lML4eFghpxrwZjWgXd4&WaFF6LiW7#poU`zd>x04iEQo-eZH!)|-Y$K> z{~Vn@#wm;B99YRnCWvecu1yMh_vF{^6vJSCr~O~ZD875@6bn&IED$f(_oO`CbGZNd z@MJ&C(7)P>Rc~tL;tc%dDV2je)!#w9mEZ~?Paf@iEDx(e{gP+ z!MT&D2>3k$pIOaR6Z4HH*+jFC|83f&M7S!IJZ?#o-aiB(?2P3PqMTHhXwH3n!plN8 zHT@#^$+dK!RnE$CbT(f{J_i~ePPvmWw<>L(&$3iM1h*FVbTJv#@_FTw^OC$CtL6x6 z#$y0EOjz>0bBb%bGAzEtGD*+eO9||vGph$oKz*6JysqN(;Y#7nDTlK-Qf9Rk+&q=} z62)sYKQ(t?RKHqr*F1gkypTAI1q$+#&KLJ#M)o;Foz1}5X6gBi*DKzDn@>l=aOD8- zEG}HV8MP>YUOatq5c|g)rxq_2k(Pgw+Po@+xrZ{$btzf+n|CQm}2R zPGducHz2E4GWinPSb!kO+(~NkpTRo+wIgY3*s9pxojp9Jg`Ed1Bf+PRH`9X|&PZ@y zrPiOn#!rIe{Bs_lv1E02IAtZ)Wm;1HItRfr_d=IZe?W$q&`)ckd7)Q)JjJIt!eVig zGc<{!qLbsR_GPJ?s60RG|4ID6J7a-R**=`zfw-NHLkHwf1`KE8KTG( z;+Sx9=It3IWLv2YF^?;(VqdHlj2*P>-pZ|mW)S?&$2_3?A62MKtG}LBg$7N%z#kgr12LthU`Q{-Y?`1GyPAx$^4s^oX)2k+I$ z=Rxx+KIv2F{7e;?a@`f9dK?XtO0QUG3@od8qf&6E*nVU9i%aJ%o2LMI=&}AotDTAZnLkF%LIyM#f?6 z>s`BO7ay_qjo{*^{E(TR;BR7@>*x*_YG1qB%0g~1yYvgjQffHo`QM{;cXg?$JoHn8 zo3IuwSTV&@)M=;UG_~vO9NeHf zN32&e55YM0=;-BhOgOf`_M9)1+|EnlPHh45bVu!*O4$F&E4G0cTB%O+0-eE6{@&)OpDaxs)C|%+1n$EDnPq3D zV=ZB)B0bYoN9SUDFqVb*dWdwap@bE)W%blRCIqn626~CZ3+}>Gg2tv0Gwx+JuYO=E zCN|E~@HmWpk}^powH#ZEW6U}L`lr%YjomERkS4MrR&0Ub#P-BxK(Tqbh zY#-%M=IMd(1I<|@M4oHKl-#_Q41AmYP?-rL8e~bm^q3D#%2yi6--iRb{y;Jxz9F5b zv|X%##GLSp=lE&@9IV{EoKftGhXf5?^pIkP6)XDHVw%we7NtZ|{MqLz6%hH$@dw9& z%Nh?Eje z$y>BsP51U0K1WAGxV-~#O|LY4VG}9laDAa=(gz>w7#i0eQA(JYqOFO`F!n0Ffs(e^WVqt zMo4+UL%M}_yZSKe@8qVS2NILAr|JgEQbN8TTq*v)mrTu9U;2ozb41pn9cV0CSjv;d zvtw%O6dt45w@IfH%R2P&ZhDK|1CR3r4Vgjg&|uY@?XZB>MNm@Z<4Gs5`&rGk5HYpa&9&H&$*P2TVEOn6^dN_T4JLBO zrDwLQYbe3`E@0RW!{c3tLx;684MW37GP9uWz=aIo_0xy3j{Z>Lk|4yC0lwCh-(i5A zVc*sl7egR(aLg;Od51E0W^-K!SECp3ta*X!)>Z+X?{z#1q1^7; zpJr?n5XeTKvQsCD&yC#yz3)Nkjw~+gKdz7=OCpVo2~NsH$~9d%xbZLPVp3S6=}%t> zW(@uM5N79iQVyxC8Xu?YE@(5EGd7F7+7PI?dtx6@9(BWIVc9{)G8^AcLwyPmc4!e5 zyBZ@*)pRqp&&7@}zDw=kEmgkXc0BFfDsUcYeAMLk(m3QM*&Pq82klEVF68$+3?p^p zatX3Tm&%9XPY%O0`;VBV{7qAu>~dp~;g5GWR&VO$_B$?a_#7maJuYi#rw?ktt&ZKH87f2U)jI#k5U1T%7d!kFWqQLQ@)x!d4zWolCy+4)hR~w z6rW?%xMn`0+VW_4%P^CWHSmx%~#3}gbI=9=`EQ_X&DDgABf1Rc+PUTzaeqrT=Yvzv8xU1 zGmRDS<9oFQ7bd;z$dl-k%DvP)T8r+k zqf0Pe1n_4Uri7ntqprS;^<$IfP^coDU^tZZ(jv=nr@A!2QzIX3_16BAeEU-VXPC%Hv>)OQJuIEj9;W{Tonn_vI0A# ztfNUQMQ2SWeU35YRH_*qf@UB(Oq9N9U>3^t%f)g3^iu0E)C_tUJ2pdF-qa%%;d`$q z-J|1iP}OtA9DX^ia_oJHu@3eV$7gw2cbpe6AwfRVg7W(v3KbmwJ};RnZmulCHiA>MgfTLcpKYZ zR!MQ(VC~Ub=Hz`KQJjw-j^TG%d2Z*nu{sbtLwQTyEFKpPpD{0(BU%t*J+zF_5S16Y zeus<=L8Jl|qE1HbEeaV-DiGJxt`hts?DH>>H!Rd$x*KG(#D{6@dr=;?)eIQ;*oOJ> zY0&nB_PR)sbvC+E#>u%iwhoDJdmA|e{`!YRDUS3zcqc*wK2_6%ffJCVQQ+XUzb@1v znJ|a6F%5Qwsu#b+z`?sg9a52aS6kw@23JArffcy~o+%(*j;!{;cMgc0gOHkZiA!Z_%0gy#GH0h=0|et^qrA2f|T*>ha|thyZ19z$O7~b^tAL@b8p{ zI-t653FTLH!E{4hB8}7~&?*fio&vY@@IXnnLzWMB*;}+s4<0>Gq|-*rcisMN1LLMx zd-K8p4eJ9x$=`k_^ee}h zaaIWr%O`#V($3||F*%XbJeQVsQ$STAeJLe5xTaZAYbr4tKhIErWGiB&Iw9myA5C^W zijw8+cKpGNe&K}@Cv~cD;5#`Ues_aS2)XT_DAWvNTI~oxj==8o+FX&Yfrv={km2u# zU|I8nPJQvnJNxy(QO5x;UeL4Uwbv}Oo+W(+DA8Stbpdp)^u5t9wHmcf4Sw9FM|{xYH6Q0-nBV@*3}izW%zsxzLiDZ+TOorJpXk0;5+cKA`UGd$%Qpi;WeV@FI3`c|t!)$c<1eaUnq7`z?8}RS%ty8T z5G8#>*N3LAX>5TB11IoY9e9h}6F6Q8T71+aL0(ZbPUkD{dw8Z}Gx`(}{$U8Lr)0*9 z1&(ka#7+hvo(zjlvmVW$Ct3In2cUYjpjhCtIj*KVQzf*uGM}t|>OaXa888xPhO~(r zoMrfRS_^?XuG`n<}&~KpeDktluCXT)pien<~Fd(RJWp zDYl-+(fw7uv22R54zV222xIB*cG&|m)RFqSK3hzgl!KD1Fve-k==Ze#6lZwY=BqgK z0-5daJps>OADovYo`Ep$g*y0QZ8$<|{>OQD6=oi*7x6kpE@55(PC%rS;Yvrx`BS;z zs3kr<&;2K~XFu%b#&Lo6bCsZg*zPtmrNCtlX7$T~#5!!-`#dtsz^TmIr?&t~yoP?~ z3T6#o`s9!So%j{qLw<%3+PACf(FRnu=WO|mY=$h3B}Fwa${g+wj{2?c8BCCX zX8U+2$r)oACF6T?CvjkmvO07&+86x4a|HoqQ6^7J7!a#mS6BDDt&Ob6H#ofw%=RlI zEs+YZqv|%3%Q&4$K{LsQ%r8$J^Zpef;=Qo;XfX8V0kh}M|JT8dO3I=2$QRWVM!aKX zT28CH`+~HPfsbxAX>W>HOkgLlZpYg?NJUjl9Yl5qZ`#1=zTo8$?Xx|Bwu-hHL609r zNfiHi_8lY&bxwPW;@@3f|+nL-_*?7TL2 z&})Jeg`Yh_#C^ImwSVHfVS`xzh*4t)=uEzy7w@n$%6cl{r#)drd$Qx*@DE0Z>jwRa zdEunT=pBT7N-R9E{R(>AY!sxUPgxk+uJ)(RJ2bS`p%>!#cbsrGuQ)eI&l)^WR4DkK zy#{@Ya?bm%g=O~v>+t?Ts7k5_WD-)|)>hcnQM{V=yRJ+9p8|jPY1npPTM6P8yOQX1 z4HN98z0vc{__m=h`%LF}>AdqN-RplMoy|+{SnnZwDaZF&aDcEhGfkebJrq|gWdnVC z&wKP7KTkiliR6G&4XjxY23}y=VDR6Kp2+;wY;#3PW_BM~=`=Xuf#Cb&=^7RMl;yIT zBPAA>u}jp%K3;=>uHUD?6URpMurCps{l?M2LXV>zy73>T+(Pu)A<)cKqeuIAJMxm| zJGwcvaL0nm=ReHAKbJRMT-*S(0lLet;BW2SLOB6{C*2%TKC^J{W+_%{Axx&$*@-qi zn|Ud1gX^=iOUp2`>1!LZC}W5GF0bOt&h9pwt3BKjP@$VSpW@BCr?vc$ImCgK=SH_B zH2wF|<3%_o&B6JQ`FP6xs?bCaQth?2P%EQCLXr_E7;qW=gx|*d`zadfGWvFcen#d* zm$b5}W_1^$;If6rt*QsmMd{w~0EQjJBX$hzzc~ zPj{fN{C*VJ#OSht?8BpOwk%ZqN*SlRdf%C`r!aE1*q17MsuTsd2YV>ar|H9HDvuT0 z5Fv|>a9qT5EqHP zbf-WoT$5A4lnIjVf*vX0z-2>rl8$~;mBs^_$*`e)o8uv%_LlV!=w$wTHP!Y%y9>p+ zb#h0w@tZ{3M%+4*VkT&XwcdR&AE`%2X$o#I&n~s4Deq%&D=(33(qZ`EU>NQjnvvK* zjjqJlnb0IaO74-~dhF^|PKm9Hr-_pW( zvaIQdj0p1oW9qGgqI{$NVWhjemtI0dx&=f+I;6X$yBkSmX^`%c?nW9>8tFz@VTGla z=Dokq^Lu9Anf+`3*qNRCy3T#h`P5&LWc_4|KcCge!&`jtbLDTb55*ZdMpTVvf3r?_ z=~KMk-z(2czp49Vi*+UZwj0&;ECl_Dm@s@BZuqwS-9r1!I;vL4b^p!nGZxi(7v|!1 zn{3u=LMBt;q!Z@IxsaDOoK{i#I*(o!%=1Sv8a%VM&DoF(pP;77-*Z}9=G#hu+Hy++rQ z7{RuII=`hX3+Q!slhfK&?TPJOU90Z75tLMfivFLHUh5yyB%Fx7oo8Gn-x2_6_i{JF z$PNzBJ%i%0CRz5 zi7{&`HLx*U;#Fl_w+rKbH}DT#l)BgHX-M)2EccfAq5NVbI$M3{Be%AZkMLZf_p@3% z-S~jp$3?;O%+nKwZR=p`dbG!92kvIXh?}keI&A(V)pOst9Dn#oikmf zb`Fh2OFdtKt-jfpuI}DnPG5>}1wsVrfDUqV-J^nKg8J8$Fbk--u(P-5?v8x}aNV!o z`LQR5Lqm9!0c^n|30r;|T{@A|64v0U@-HoU!N}^Ii8e8``a%!#yC%G*ER16zgzCS% zdkFo&`K{$4SWzPCZ9c=(*|kp}9%|HH0P#+37TV60NAXi$)-MBFhy=Rcn*h4mmdPX= z$wc12UB_^>sx&E}oiQ5Y{R{IdLZRY~l%Tm#Rtj?=3AN5^TEbU_gktFE znHXS<_82*5jNT*}R$jYpkT*@sx7ogTS0DW`RY7x$ibgvo4IvbqdGkU1CE^&8 z=gYYxRsGlI*4GOYkc$L2#ho^0YV`p0IjiFJcmbW8pQRrFvhW9)wy$VxZ8qgUHtLSE zgSEcxth2p2p`}<%4vf*vRt8f$9A-N ztX|%K_5rcR7Otw-fSe7zOiHr5^nS*SQtJtKRO6xso5VC;vxq#M3Ak;odCq&^G!4JZ z%&IqQw+>2S^omd?=_)P+V}Dk2)7q9q;e(qnW}2+wqc&H;wrOYDb`1S~eRxWKJQAY0 zxlsRQD|c}ZZ$UnoDhlr3^8VD>JrwjzUjwrmxLL6CW1vM}nt0T%eyJ)^&PoWo?c-bD^K2hF|r7 zuF2VLKN=7h=#tGDl>UXL1`mJwEB0Xf5I4{9M>J%W zP7D5=Pl4)HZvOyZhV-3HxbB4}IP?g^#pwyw%(ZreI^q5L51wDsUwNLc&th;! z?@u4?cb;f(k)k{ew1rh;an4Uv-+?U5j2l|iwY*Yxdq!4cmUNBfYH|W5GD6XIgY`35 zVZXDvgQbk5W|iDHdwT{&5#LvM>YyC8vf8(#JO8(86(Nk_H~==O-@k*N5&h43q!;2M z%7Q_a5mM8ha{_eOvbBN*(xC_Q73y-MZ`Rs?oy@sJ0qG^l)A_Q|XSin5SUs+dplJDd)@%lal;pCNdMu)H!UY)PR`6HcsAa!c8r0F)XrP z@RZN-jyX*X#<`;pr=aE)NHoXc=HplbVMb+K(rr3QP(xAp7}^hedovq@IjIa<))MfH zq2rwwQSv2|wnOJGae^7#KRdd5b}uTXgKkbiBH#a7-$-?LbWoCWeXB06Q3j%xJ(y#b zQS3IFS1$Gr(oK9ZSR=a*Uv=MY@L|;`zG9NU&mOLwt&_q13Uql64dS|3?+z$)WSs|e zMYgsH{l22^2kP{<3l?{VyP!<%mZ5(QOWN)_RT7J_M(_Imlf^jo2W@ij8*tn;O&ZDL z6&8d%mtK^?BpiGOIA6awvyp)FB#$)BPc#CatNhFdefA7M^#lqNy9+!Qwi zsvWB(>tWjR%QrYOP_%ZnrndYAp>i;~NQHIf+495g-0M%Gt|)EOuVbTFaHvb;5J_xR@a+Bs2Ud`X*UTVrpt9 z8@+MGyfo@&J~ios8z?tja{8Z3)w=3B?=-j{N#>eJ$#YQx6N{Y^Sqso zBPIfyPmcfHd#)+?<9gQQ?IE`5k01r8rG$QtF`w_x*V^46_}1Pcpee&#jgALoqaY+` zLwU(cnvSxTgHo0GOUbY8m=q^`c64*%EXX?&b^I-(yVcmusLb504IIXdzD}W&D})wq z%W=o>q4M&+6Z_1c+vt2_q~DV%q<&D==dKP!w6rm%O|f&`W@? zfmgQhilV2xJI8N>UIDaEpgW@=D@7bFuj%IPJ+i-VGwwej>jSrJ1j4+5*<^?JivroP zxbk(QbE}#_oZ3n9vDW&uTIfITd(&qfp>DqD{S9L1hQUdDc-m60%_A1p?K0yfwIdmL z@GO_C*FVoR zAo+a0<^=)(9XFf%q-RdgDp zwY-x(-auRm4_Jz-UA!H*k9vdsNzG%fG_3rM4OXqL*W#{m3|uJICyoL+>E=OuJV_yJ zrf@F2gJM%A7{{COkm-Xj;D;~HfS$ko>M?^fT=K?EgOPTP?b)KmcU5~y> zo@S}8=sq!c)NhFF-QqZnC!mW}XS8mXM#d6>&u-2Go&eaH(B-VLP@(O&6Vak{QgfZ9wN83#YSm<40YTD zBO1th62i+P6xemZEBTwC6{^_Qf$(z`wVh6)G`a6%k1L?a`fzZogD$k`OQyOduiBuHL^OeR%1H{dt3jUi=^*2$%eG z&m?9Du8Q^_1)r5zC-e&#J?h^W9-Hb^;4OljID6A@=1-INfu4VlGD9G{mXH$<|qXYmj^kA4~ zPd?deHtS(tcnNiD4U~&Xji<1Hrak7kdzUsCjxl3`_`owq?qv@z;~3icUQS3zRsPAj zs>(LYw~@pN<^FQ7DpY?hH?H{i@9l*Mz9P^f%p2xLvI{kyd{ z>nzFLa+Xc*?L9dqx!5y%AcH3L$#umhx*v|nVQ18#7fuii+&&?F}Z`x@m*}K zPr7s;qW5@%#_PP84CgQ+2IElKwR05*FXjX}^ir0+?S)QFLS1{Fder@BEa$_IpC5?q zY%RS)^L8EfK-LwA(9F$}T)6Nl%(c*@-B74_bL9;ZeBo^2Qk zbUEZ=LqtPzQD=>1Bu>n)Xg6OoFigkfdCK*ADl3AO=8{@zN02HE#ba5Va$Sf0x85g0 zwNI?3L7eMy=zduVKF$=hAM=lX9KwDqcThS43<)|KJYdyqzlsh*g-udhsbsBTi*~q; ztX{L68tJjXA0_$5r#+w0Wc}#J^9X|5FYS-94q2k77F$ecsB`H3)g?@)C7aRP!2^X+ z0jIZ*B47BjUe>IQa71ZKVw9%&!M{%0wm2ssq(qQUMBcp}>tVo>YYS>EaygROe_p=g zuTiiDxu`mR`S<75OTIg^2bUWVJM2G*{lDA5K(EOM?`2ojK9^wd+xk28@RPS6_kzNa z2X=MmI=$D&1%A$okSeZo%=HA^6E#T*NG|~#?w4&dC{&8`Z+%_evXc<7$4a^el!!+y zS#CN#0y&bLs|=(Hmfe^)=J)E>&0MwP=Sjij6a;euc-S|yZN*pm-2Y-84%x2*8JVt0 zJsJtWSczWAy0b_@FK%Z{yeEQBqt3)(eyZgG+!3h){)NM*n^rx;2L)~nQah^ZO+xS8 z@QS&Ti{+qbRY}1A-;0F3qKER={5qAjw0R*(Rd3vDCfe`1)Qh&0B+JZ)$zp1)|Fy)J zjQrPqWm4)(#n}6Vedza&S;z5g1ijT{p$BB*w%h^zT!NFRI3lEH+3vH2P!8V8#s4hW zuWj$aWixT_*aI}0zQE^~j3MTlZ7lBikRv4*RfT9GELqB2ik407s$69|{kHpkUA1pg zGlw`qn>%)_9k@Cq3k_O8`Ysyd0QKMbm+t62Silte%)=t}6;YZP=9O6ROwe}|^+Q1Q zqkB_@V~>1*c$CmvU~Ruxhz^YIVajinp zI{Vg89}KM>geub+nq@=PIm%w?p@Yy=H*$Xsij5|a`B%c?d;DhXAOGAJe1qr9)VQve zmyP2bT--KfoG;v1nF!@fk0<2zjDyd2HOt!h*xr)ag5IC|_yhd$NE#hLgF=oYWgNt) zbRT{0`@pvTC3&LBsnU}fbkCprYy|{8XR~7NBp)5ZLMuZPd-SVY-&Ma!RPgQ8rjMlD z;B!G|sMmex+oBJDRE)jy|L-T)tY9qel1$Scwj=+-J<%ct;`p%n%c<@E4+ElpJM!?c zbr-P}s(=~ZngO&!&avyA9UUD@H#hq~Gy5eWfreWxbi-=#KuV*!5(C-gGe9!9y*XoU zHfS)(o`#aj4?w32z&}04BdTH9(!dTZth&1V-)%pUX|*+EWK6prvPP@uDL8@3K*puH z1Nz;T755d6xPIR-8L_nwLy&0(k9ic6kSCx4w}}ArsMiN!)%vLY!P@dZyZ01VXcIaP zxbBA9@;7mdCs^JIem!z;KU8jGsti=K*@&Fr|vHCu{37ccI6*CLF$R6K|J z<=uNo`HQ8iNf?KoXk5!KX-F7 z5psWZ*W(#ONUr)tVf)kI57Bp1r@_Bupe$dmbVfDS@EzNy71bjev6;yRD=a4GDZ2rkN=aP!9z;zGZYs_OR>W>6zH(V~SCqgfQ1t(NKu9EXHtfT~*fNS4PK3Nl z-tJm=PoL4p^iZ&X{ne&YV$0Fuq%=x^^@nH5W_S#+4xt} z=S4yRcquGct-<6vq!liG-it-Lj4`mTaz}NAKKTR$6K`}m%w(*kVv~mXi)mnwB~J>= z51)tWBuJx@TS2w|CX1pX zAtms)b8e{g^!dQM$Fwit&3i)d*Qmhy>S~2Ccy0+lT{*vNr3^ij5dYY_KN3G@e;j78 z^dbhp%y?r`vsig6FVV$el{o?S`l2T>7d8ANp0QtO8%-gy3Bj>-Xn<^V!5i=U$7XED z(kTM`1oz-yD{lEQhBuh8FivU1$f5rwW4+qB0sJ?BoJ0aVNaNy{n>s&DQaEWx zw1(#rd1&Gg!wg0<-~698lGCmq{@nh^-0fqv2a}@L4WTy&wSrLW^VruzCz)sP&#={To@i=5$Ew5 z2y&wy-(Ef)JuY{c7#TrR%1$aR8h}>av#SnuW$J*sm`%z-ZN=HHo4e*JRkEXZUYZ3wb!=<@K86aF#Z4L*r)&j zEM6wQ=YecO!fzd)5iJ7i^4xE8%Bh%M=Sx7TCwq!n5{8h)sA?Y$rU zyiV@8{kd>H8=70=E2h=YUgO(j+|&(wRWzT|S_x}Era|f2j*8lx&8|$&^sgVF>IJu_ zJ178=;;*$mC$L>Btb-LL{}Q8l{j8&3*k7?K&B<*_$)daN{&s$QiKc7KDEo?2CHk#8 z-yv1s;prjztntu6f4Cp~cdh1a45rUQcoGA=dD$i5z8^i@$<8{?N+|VLOX;bg^5@t4 z_o$ZdCW!fFazfFZerG{FVzXZD&=T@hEJFJB)G)WYQE7+7q=YCW2)qbZcsvtGeHMlJ(dRdi zj-;WSyf5mYne^GCFXoX1xr9uL01xUTR3gsgVE69>*hKd?U?ynAUe*3fHSNP%v;#<8 zP5Ip*&tibdk|cF2g5GUvwvESmEqZmHJrK5R;sG}zoM412XEn0Usx-`D<7d}7k1z}E7Ijy7;1-xPeNp z;2I+8lSkX`{qNr0gZ_VJ53Eq(wLjukER7nT-W^FT_mdQw=|pJwoM9ilCwX|YXzs&GPR0R zkNe@44|n>P_{z6*-w*?tGbAb7Qi!p)Kj+ z)!@?}z*K(Ee1+{dw|6+tM{oRQVsfo9)P(x`JuG)(Dc@9+YvG$y# ztLWcJ_6Re98EPfW#GU{T@a{S*|Ms3tQHEMEyZ_x>8JpKoWot5lUGqlntO{_pxTa8| zn$0$Zj0z=xEV1yGFsH<6TR$+-V~?nAN@s+u81X<7 z5&Q)V4T~}Ft`RF=^;Nn$L0cC(pa=)E6lfY#{z34Rb-yD zL>vdaZkkv$v3pC>5|wYO$5-@!PGpsE?w8P*IKA0$62eHH8`BDiE|2XlYNB5houwJ+6ouU}e#5RYj9I>}di@(he zA2%s+&{pf{a%t4!MDVdKe4UHHh@(At;h)d&MUlQ9M(?TWprXbAI2rCH zy%Ht(-yysobb>|V>T2*ZQ>HS51tnA*d=RRk6++Sd-z~t6ve1#Fkay<|3;~u^u=@U{ z6{n8AK6;%i8-q=4Mm6lauuR)#=}f)8?&G5Q0F~%w=~PKWJ+9j5j)>((TG#EY@Uq`~ z%C{!O3~j@ACw|v-F|1CjvES!(p9M^Q&0JIUiw~cSeae{n+?dRECiSZKGC&Y2nzuy=5 zQQs#>r*Vr^3Wl89s4g}ULfbrXbg9=M$l7gT-(gpNnzY5LGYe}v_H>-*2zie@xIbYm z?Lse8uT)8_lIC2Zf&)8>wrcMz((2PIOAXiItpZfp-79Y6oB$tE!NVyG)T=TT6e?R9 zx32bK>2rn0?IcZy0Cd?WSE;M7r}>oNAz#oPv^Rs8l}w8>NPV1M4(nn-6Y|K0YtZAh{#Ej?I8DP^abs#IQM8L_odm12!ee5mw^ftsYaBJL6yin@vA^c+j@ z(f|DsUKRhg%6N0|klc?zNVAYYhGcU1zn(E8oV)>Vo;rRRNrv`4+9|K)sVKj2W;s8I zK=i8k+$Kmd@raV0l}*)P8rx+e1vV0K5L;Syfj^ISwR?3XDBLa#Fp8FQAW3oDx>+PV z#;f_ttXi_ir*_G7xd_lApLALtw0)O zU+A+`$LOeFloH=_YSMZ4#BGP0hAtT}Q>CtFNj{(LDUc_~XWd*2A^h_R{%6_qtqzEJ zZ-)&pkGyYQ@g+MZFm1oMZzQ{|+qmyjxwdC6*zdg<2;xgRw@Q&*otJLiY81a=l^^jt zU-zb4%=;ktK-n1x2x-n5<71Z0YiK3OB#J0urd6a6D34Mq29$?9VCstMYzm3ZxU~)q zRaQv{InyLYms(+yEi z%;0iElLq5Ioca7}c0&q0`W&)%{4>hI0NaXyLCUSMW7(E7{xqcaYKFzq**;rj-GF-3onY3cR{WJ6E`Cbi{MfW0iCp7JpeTu;b2D(oR1`I_MT z6vTd|7y2()uq^Ii+{=mktNYD2ob2&_)*4HE{}z{Xz3X_juy_{Nte9LH}iD zi>kN?x`3`e!v>W5jC{DY!>VAZQ6H*5iP8w#S-v64!!X?wIHd;8cpfqvM%aJg-Hqd* z;m?f?Izw2I?ajk2|HW-k*8O81*@ZM3P&^wwq{!!GV?lvW1|V|E53a_FUU$8lLBMqS^EwRFInm`Edaxf{8eIZQ>e#k)mnlx|EqzX`ft{2a5 zSSdDt#XzAjRhHH^)z?7<5{fBxP|mQGE74egmI>eB^^wr`^CIsei@;A8DlKOf<}t`D zDUAvY=w?Thw*OIW{1~1tIwxq~O{H_jmm_ZNy~VKCn7$jcyFNwe_Mp-g96NE_RTX2G zN17rreS4K@_Tt9vES!51y*()kHS=p}xU~N#a;S!$is(6F;abk}u$e_qci=Y<{JaaM9 z1e^DEK63V7IBa7LG@{{yIB%4D7XNayE6tw<`?9ch1ijl~MLOi};{RJN(|&BKW%^dj zbUYHj7s*!EJgN{qda?bu%#X^zj4x!eQ2J1~K9FE%tb6cD*ApeJZ2%D!Pb3Ds*cZD@=T=W+cc|h0m}d7S*ZOPk&W}JMi-pQ>E{{3C9?kRjrsW1BoKsgAet; zFpN?HK+>;xD&RmiUsX-}E&@{nA?zxEkW1GFh_BJNYKKKCNMOL-)zY;h#gF)Qd4U;W z+0j+H>EiqQTy#?yi(94kcOzOP)7Q~w1!J2bLC2*x|04+EscDV0x}}^&3ofvfn)oq)O{h3VjNIj0N*Zl0-Oi*xx;3NBnzfPv;W=xFLWKaa)`0q z1-ESuggSHsT48`q<~TTPuQ%JLPQ?3XjeSEF+l%;L2e4y}AJGPxnxTmLGmW@Kk$NzK z)jJjW=@E{vTesqGUL~puRG88NFzR|yH61J2fBe^<-)1mN;S`=zqC)%8Yx_Jo9wh$^ z;Gvu%Bu@LEKubx=3FY!P6r1nqOJDVJ_Q5<4=94yHk(N(Yjs2|JkF7VFxuD$OEo4qk zs4qoNO*3guge4st%T$b$QmugD;Wm28cu}Qvn@7m{fK>jepX|wN*|2uZwJ_MS^MT(L zl<8D!&nBKi(wnS=TrGBN^x60OwSn-?pVKG#uSc@VZ&Mh(J(85~L`OQ2(mYESQ`&eO z){5}`pXjP-GnuTD5EG}tYsp$n#Ge2bS<3FHDu%0WgwZ_rQBOfas z6Wv)Ij8&m;sM7p1hCOPL8k>|+e2TQn0a2HXl6xO;p#uhS&B!phz{2l)J@TE=!>u>W z!R@rzaLGZho4TQE{EzJSPM}k*=yJTwTvi2^De%;>8tFPU_e*#7jZAm#=T7SIJe*1R z=B@Mdah%T{&mIt%@SE&sw~c*ae@90}2vz926c*q_Cfr8cIwiIOj~(4EqN@rn%8*a2 zNtDY5t&%PlyEop0DDPSH%H&p@NI|^`9cLt_zfME_;9I&?fxnKkr!;q5X`yJ7v-U{xYsp1BC#L}$)Z=JMI znEMQ*PevP`XKm4RTLSo4$;w4zpqsvc$oBgOK;8DDAHsRLQG6>SbgxLpfORG^C30XQ zkvVzdG`?);x+t?^u!LYEQ{Q)@D?_>btn4mQU`hE72NfvKHtclIopi`PO1GXoNzTp( z1c3$rKPuMHU;ww&YMV{3sb_Z&ULq|-KPiz6$5j+QD6Zpb;JQG|{yGU27O?6(`jFqa z<@in%1ZHr?ftX-2pb|`VH77T1#;{caVVQBGdvc?;DZ4E=Q$(`(ERT)p7c%}-=Qi+U z;s|pK0&}CkLgp~NDt?4a6oJA`;i6=#EXVHbnflF7*~@8rkj=Qyq8LXvB6&&1B_yl( z5)93!r-q!4V3Z1GVjlK|Ke;e}>=Hyl})Nd4mu=1O{$@3I&9s(rAtr6AhG}3}~ z4ipz?nG7#c4lUbGFq6}!nhAydKFVGLA_>0-1M;_+6)q}q%4Y(qG1ULKy=SN(aylQs zl;CVdssvtl1Vk`0KHaYSNTlVY=(g=zy7LK)N%*Xfs&X`2j@D$k58*j)Jb6V)yuxhk zsuN#rJ*VH2k*)@+bKd{2I^zR}xqVK0S1|rLQ%tB&=S&*>$PP%hnav9^UF2yr`Y)*!UQ?>vfuobYpZb2!#Y=9?Ew0tK z{&6^p0ur=Z`dEm8g+AFg&9KVJY;c;;}|d5k|lmC z))urRQpjGm9jbGUYcmd&5S1!LOnF)-mo#&8j4(VSB^_-$T||;X=^M~poi#ETn*6*P zJl11^+@ROQd8U}TAH0-gbM^%cqL23s6N^w0qq_xuAFvn{{k!l@bpLjZ!fER`{vCF*0zIE0&JIt$X&CrY#>VGRk7K6F2#Y?99dI6wlH zp=TJGx*2(|W56=$0N)5!92xQ<+WBxF-CCC_D4_VEbofDk=eIB{7u)?`Bh@ACnX`0+ zmft$6$YG9?3jvHRk;ToI(X$mOBqli zJ_7-Z@7LN|oW-rDr=dV>7-iZ;a;#bHhoI-Dyquhz0oeh=`>+Q>SqYsclC*skgZ_*A z;FW*MU|>0QF_J6sQ)w>hExR1X4-qa&H4h)0Sdk)s9YB*4wh>rM+50^Fc11LOw;``% z*l`b@RvWAqgS0%#r1)EXT)mP!4hncfg3OL*;{IA)!`zdL>W*giuTW(g)<8bE5<0)2 z;e}`TN)(q4o008yy77>`SO42>J0@;x`@ITb;6Bdt#N?lN465?Tcb2;I#J;oOvwxrl zypIi{#r#ZqcB&t zmCqJBRWOHpkkb|`xksRAOsWMe`$G{fejgZQsp)G(;J6=~WokcEqQvJ?fX5zBLkXUh zFmtuM9F!$S4>Znk3O1tkb&t z3?eQzD{WbH$-&N#vP*i{dOl8tf3YQzy&Ma@q>mXUNgu2j`8gJ9><4!bp<(qn%H~p) zE%(Vq$y*rhH|t4UIf7~^7l>;=tSg_1Jatu@)yPuW{hYRKRv^oiYkRO9cy@(PcF~Nr zvhFM+i8wTQR%#>43c8-3;kTy!F@Y{iKRCsm9k)^cg&+yP{n*Bn?89co!(*pRs-!`S zG@KZF2|gy}{n??7iQBk*LLz5^G51vT`ZpTGj?@go-TvF;i|_XJNG^~)h$%+5@-_3s z^|cUfx3kJf_&#l5(?}!KEfqucG*OVjLl+j{n)$a46a_E2&>2oH>BU-)g!!x$>^OBRD&K-pE>vOSA;$(Te`Jt~3Yot!2541^k+#6bXK{Un(fV?OD>lhJ>_MRHypq71q@=AV2B<7f};)}@SND8;v*M3mGabT&@G8x}73$@G2q&Q`*Q>@oXWI(%BajxU6Z$LK>WGSIkEf^Ekheq7p_Y!JJ4N_^* zV=5mK@Ku(+hxeK4611r{jxAPfhHErG^C0p|{x~Azy{I+-C|t|_-$ISopI~xR^0s|F zn1{+5${;lfDm~JCTo_5w^W#JaqIIUtlU__a2(!%3NHC`~|5xCbVzs7yGgDJHUtix# zVO*iZ!;r?{d)kK9PYK3w7Y8|042yq~8s%cI9)gknB1F6tX-@ihLm}WbaVz;z3!D4I z;@-zzD}t_TDLSLXoxL`ngvtwvv7bM2^7Hcn@2M55C2)$;{ANP(yCB*J>_7Wu@y|wF zk8AfA*|)dv)1QtX{cCrh`GIfNI!i-eb3Q73zPU+~+6w3$1zZ~n)3BGm5nhZ^S{p>W zZuNQh-E(msNOOZjPmA6zw||lr{xWCUquIn&+wep91~z6kLm(CUXcqc_qkHT*#g>Zo zS!iG`L@W>Rnu`jb0Df|BTHzt+DXy4X)&@3P^Ou?GUpM^yh-2<>mI`~;G_)w|{ zEUTY_dNz0 z74rY%0*osLWv2D}bj$M*_%yJ|mf30KB5ORoFz2bUTDWRRElzew+(OdcbJpr}wcR$p z|D@CZR?;7fJDVx_WQEoZh#kUyRYc#$-g}*n2iT_D#Ne7nbZ&;fS&<1g0V%L8U2{&S@Ab6*GZYj@WJ zkn=EGJ!cYSFz(${Ep)x_R=!US{3dhK4aE7!TsfearD=$f#+qB(7-#iI$s<24q&DIq zVqevy#PsD(#`~EvP5F9_#DZ1fecH5E4a=fU{w&Ny%%G8C$_QzM>IGtMZNF=4jfU_Qo=oJ!A*#pv=3#9vw z-WPLq+RXpTVMEfZ{3c1+-Jze4Z8^IC9hk0ZUzqEUJpHIf_x;uhG@iOs^2HK8ue`g! zXRQai#24@pJ71L!^3^er_0M^W!Hzwo(GAOk4VzWy*9W}Pq_vRxYECDioHvTcoNMy4 zFSpJT-@2%;^nJ5;J)SwdZol}W&fR_At?$@qSbKVU8nyx`1K&Vo(t3(ts->X%=RbQ) zG!yk>n3ml1x6VEDtaa)f^7;YiyBRp&TitKZo~g^88-x3FeuP#}mRN=k$6gTHd3Ju- z@AFjQ<3&J!}o)&Ph0$J zbc|IB%XkyF#Eo47RUdc1dGiYJ*|xcDs>luHiOS8Hv>k7%K?HTSX&I|sN-?l7$bhA+ z%e$CdNzE+%JfHZU2!Aiddjps|{c+CAo)j(NSoHsSVhoS7Hw1$M>Xn9{r#z`BI|xLKt1p zx)VO+q;%ta;P3UCAXhP5rG!P=eOjbW#7-Yds4J+W3HTq^v=$Y-J!-*8auSx2O_Sa3p;;5lcnUO!j^M z3Vn-j4eh1d+lBWpEtL&izOn!j|H*VI{pmBEEcnTEEDW*REY4<()4g); zkWJ6MKtAHvebdo)MUUl@hlko7#8!Y2llV@b*{Wo6bsF}m4K5%}cp`G9m|@uy*b~BZcZzn>rF@bAM9 ze*AlZ$tjQP_mg%pi@{1l_l+voQ$9J<>QxhDU{c-iQ2OVA>52lyl;O3NtqtZx38k!3 ztfmDcSyeU?>r`B`6G^}p>VZ~qp_rp*FdKn^2W2en(f^BZX1@~W8VT2qpIx(3EbB-L zlsCXlWtDD_i@+T=Gm0v18FUgGTH-b1%b5}*GuArpH-33`amc<1yHaBRvK{R{)J9_T z)(7jDb0Gk|;nc>a8{D*!rP|}hUPls&-%CfHc$+c(}Ro!{i8EdtZ4}Kl@ zcKmLsRR}Vz8oW4<5izo@=HK16F?Mz6K##lavYx?;KN93@4%rQNTYn_E6?d&OoKvmvhAp6 zDu0yxIYi16yZQ(SK}qMj(`ZF+e6^-2QH1Q|2tJ0=#nvxo z$Ho`vwZKpGV^JFGc@&DNm-YuL`C$)6l8|VE7FcN%V!U_G*{* zME)W)(a17%a8n{HiCybW%qF0`1>iHXH4ZYpX(Juj+{%gXXVF)3FKC*?;ki!uztTpbs{Y_HacZRi%8u0Sbx)J-5>0p z5LwH);GZbAbt!Z^^=tFBiDRLHaB1Yd9BKt=?xNe2%n#AioNe;srAe5UrBuhlD>EHT zPgO$yvYyZ0Q!f8sQ*Rv=W&3>()7=apB_Yz1f^;J-4Iz2EQz(}~-B74^P$LL3It@=}K zGEdJK(1S>1v)y(j?l94Ghi%ch-H?0tu_XZFC`t|JT)2AQTj!2)q#*q?q z_~=v?au<-nj^x$9WzhZG`+77)wIhUZuxCqh>_NLhdPi_eXYk%jY_K2%89Ql*UIs!U z_6z#9gYBL$^|%$;xb=o;{S1~F-PjmH)_U1{B-pkT7*7M!1=pJkX5v+?((rKP>XIAq zc#Hs^?-`2+&;q9SM=t1Ww_o&)R}KK+Y>e6MnI}6?6hzNyZ1fao_Unl;KWC{;GRuQK z*!qrI3VOzIC%Q6{z)xkR>D$jluw5~QJ(ZE)y z%EB%(^hq!^_q#R*WKjRbcp^Lw$OnytE5umD zM;XxQ8!>6<*pSy%*3Z;`B%<96)8AQuhzk#%I19-@$){UCdC;;iGUmHvv@660A6}3L zp(D6W>_7A2a!1s&sB}TqPBb~Ob5_~0egXX`yn*~o#`v8^KWblX6yFjo4{WVS`rTsk87ro+ z_UXuvaAE0I1&30%M1&Y&t&)vV&UC^pT#5Rl_RZw~Ci>C0GnK8ptM}~2x5ItXOtO^? zr%LOx1lqvBea9l93bs}N+EFquUjdBaG)!~1{k;{tS0aAIR$*U{*XhAWx2Ub)*&~Ct z(>9R}WT#T(=x`Vy8q6j(OmP`duN^(fe4q2R+pG?o1CK#KS3-o99gj$@PL#O1X+!jM zkJ>05QzxjcpgdJByF7E!KC?@mL{h2Z@X%V6l_2ox8kE0Cd+clKu(ARi1;m}lSRToFt@o#Iy9t3=CTw+T1tmFL4 zlx0~eZ?X|Lfaggpqm2BYp1uD3x2wHnw)Y|Ldh@3CG4uPQ&VP&{fZ{IvhVw=mY}Na) zV$UN-?QWc_J3(tLr;vD=Rgj-A)oryg;1DSIJmBuZ`ltf{S+>j|VG5sPW1T;G`V{&3 z1=o%H6ddY}xU4G}q0(PjQ&hBO3dZv@MsItX(tL6K{p+v2txllVHyRUItKGzquTmh6 z7YhsWdOual?Lmr43t!p>oL1{n<;d7F-;`(Cke7}kMY-rJ)Rd9Px;xjQu2!LCqj|cL zMZphx!ki3mCf8K4tfBC5Y-OvI4LA;T zPTkG0$z#yU_4Lfw^N#mODdF~bdt_#hP8_O1xX59FcVa|;ouJJHsF;?%L!}9*_PA35 zBk3P%(XQyS1dB1hX|&$1OrkN`v0o$3CFcFMz;NOLiBKFFOzB*a=3w{gQ&mgsOLa6{ z9_d3^T(h(HTF+DCyIXoep_l#a{VIhTTf`nnA)9+GRe!84AJ(-s6op+#)?uFyUHZQN z0r^#|7B>~)90R?WF5U7Q1+~vmCxO8{&*fcO2}x;7U>=t$V9@)nLVC-RVO3Pke8TbN0&(0l%3$(=H{=XrMiB+kmd#keyf49zn@u-_@f@nRFR$++9&$3 zwzi9>dq^d1Slbdm=ZzBG57EIc(A2*>Z7y|@z{cT_kAq#Kz;!68u>B3`*8D^~?HMXX z(wN6Nep)1}w*aq7!Tp9kbMG&Jp!eg}-2uKTrLJ85^pK z?UYF3NeHE{LDmJ}+b+#`6IEt2qotvpb#JzTCHO=1(=I9H#T8KYx#Zkpg*igtBVeCl zXfh#>@X(V1Z326`&%!9E4m$;gz8B&EJCLYTJnep6 z=HK=%Ra6}}&5A}>)&>Ueh1th85&0)Y#G%m+^Oe@m(CC(FjUxqo=Tnrw%|gv9+(*ZWX8w&_H)+GlqkqHY~f?no?|S)y?%@P zsQA~ku%UesTzheRZ{yBo9Q=MbvS=E;gD9Eh?B{#0c4ehh_+*Hf0^(Repq4NpzSZf1 z=R1MZgL|E7!I4?|^Fv3qsbfxPw{^;D<)ZO;Y;m_IY|2}o81`6K?c6Jz>uH8^c^*D# zM^49SIZ00Y*{B7!uI1Mgp-^>uhr56(`~Wq z4F7)wwAFkJSVL%L-Bp+N6e@qW~iHf zc#qhiol?4N!t23kij7n)i%jx*oL(jD;VRq}>X3PkF(~Q+o}&R8ZM4+|%-WR3>VC!s zcpg8#of^Ob6#76nUfH!^Wtff_< zxx+zD>dwT5P1brb%Z!QgNJ@|zLGoz zUT~@URZ;4Wyf{`fKAN<3dHbac&;`jo~hiRYkZ#6f{r|arht$1(r4x$C1gIL`oaos8x+CP!*mNkPO9Rt#j_Ys3uVRv_T zO;MX3l2iK^{KmipL)uFrg~kz}-oWcu=kZv=evP^RU)f;P*JZjTYVS%EsJ9;P_U#)0 zt#yL8#O8$dWHNu#S-6L+L;KL7B+1r@k@Yqgr{b{EclBc!C`y?{ZgVujCF(m#)@(72 za&oD8S>P`SpEA>HbpLkqK_)r9Z}2*7CX^G+`ksb|Qg+bhfcu*ENZgoZhsnjuX)l(@01cYYm}Jsgq1(WApz6A-WyYo-^-=X_EW~b61Slm3QkHHocm7K z=+IJHeMbcWBZ{r$*A}%SXD}~rIrbWw)<1mu(A8Q2-wr^yV!9Esi=l zOd*!%z5O@zmx;IQ0Ia4m4UJw~?kcRU;EIr=j#dXreobLsM$$uu=76g?meQg%byfSB zzCm#$)v(g7ZMQ}TDk|dMb3pB;0~VCv--KKspU&iNuD!jEdp?jq_fCF{JUie;zfhf} zs$lkm<88^}J7s@`f>Rr+n-HSnRR;KK1O5{;4xYa_38-yTAZg6v8{5iWG2>ui`PjBlt6iimk4mEmT`Hp~j6 zAfqms8dgR_Sz~m#&a&gD3V62i z!<>pvuo9COj=f4ir}yy4E75*WaM|BzNnP7kpQnB(Y6FF_5Lw8N$2qr4hx{uE~teZ^N zoOR{Dt<^DMT@Nn1kV%DiKFn!N#FjI-{5ME?SQh;l^KtJxyo~cV=aA-vhPaFb8fb(3 z{QdhcE(BRqMpptxGhaws0TA(H`x&IM%>W=ho~j+voYzXtOuch}GlSd@L1HUlIK4pL zUudecrW9sAUc-TOy^>KnW3h$pqtQ$+@3LFylFhWe(WkH3Xv;(++yTWgj!*+UdhOkA zDi^trI67vPwWZ0v6+l8Vkz`W=U4vwXM-ZAvU#+vY+rGsIwKNXFq8+wzL$m4IMH z?Y1MD+E5eZ3g%)>P4JCTTuThk1Kyf;E|8V#c8|WTmG5PrVZ5>;|A1UvaltHV3Jp3N z^Fzsf*p5ZOhLb5|qzz*y)>($q;;{192+f+-%t zZF_!RFOGpa)~6Gni<2&#nMvkv!dNgcGRy5%zv`G5A#z2{Q|0VJjv}wFeCxR>qm;z9 z+i{!*vA%9yF{Yi{bdxh6jk-ggd^WbJ?8Vxx0%3_`E6xOI%uF2#ZY`*~+tnqXfW*;= zR%1Sy$_JwrZmalDuHJ|S8ip|$%}O$hED`9jEN3_K4_!)&xV_OMqm2kVCH=3XVCaac zOmmvl#q+HohSaZ??8cQ?@vIrk^rH2+JvIwc&wjRq#0mSa`}b16ax4>9oXfMWU&WT3 zWm^|_?eeZX49x5N|HijK^%b51IO#*N-@eNkyyE@i70_QCTfYDJA+Ln+Q;ia}8&CX4 zN>1XWKzA9{_IfY|v*7^H9rj&xfqId-KE*#>VTLWqQy%O)_j2&&WK%vVasUxXIe4!; zwuw?)D4ioIon_JR)`H*I%N1`*^oezN^7K2m!2p-Nt~C}Y{Yek5zqTr|ta{t3bfm`8 zjOw2vdNP?+?BAXGB=L=LdFWi992Yr+tDOmQTY`@>SE_zj;Z-;SCNFuvf_90FNZ^Hm zDpM@EdJ{+Eypj$~YGjXTD_30P?59hxAP0qF0Aeku$farWgBh-QUAMr~Q&j{l$M0yL z5tMK6jL~Iz>P(lB;9gPPyw)U&xhzAnsDLfZec9Dd!M(Cyn&wyGweZ#_M|*piIg>-0 za(4JL646=6Fh#vz8_s;OLHu}6_@JTBq#LNHLyj9S$U|(6c7XrY4=NPUR+M=eEl6YA zjn!E&(;&|;6eDDAa`jQ@CHG9NM}_oDbh5HgK}?CZaQ4;^B{{RxoQtzplX|@v7=K~j zzh$}avt}F~g*0&p86AfR!NLE0SiYP|z#pcnEzz|Z|37f)<&{EH5$C+Vkq$|;dd$>$Y~r{qdyn|@2lo+q z(~J5y97}sb?NKp-3g!N4$-Lk-zjX4spQJ7eqBe(L1XC-$;mB2N{Pn4*|>4rcof1sisJir*7FN-SC6Ja;>m13b7V&V2*o%*&=YO7P#4T^4o@J3# z9*O%t44tFgkTK-&;EBGYT-L{nUiYS~aIMRvBD0esK54ynsOq9~(FNPnvXT6w$Vrzt(diJ2*(fiAYOfc2D2@Jvm$7`fQ$#{1)B+4lCETbbVn0xb-k`8#)2p=>c58DEjv&WQgL z>J?)yoW!vro&BNIo-O;**=XbPM*DEwZ>`zvmnEig7H$b4E>0pxT4@x*NAbS1Rfm#_ z;+}CV!@(gEZ--8HDsbnK$i%U0(z+;svPeno0Pz)ILCi=a%(-7*+}JGr-^d={nI{Q|oE(z<{QIJhw8I#=X(tBK-YML4*xn{iX3kRxf zc~h=%%C}C)B?N*L`Nqf@z@QQ5st*dHn>~CrO>PD=g6+DaK?w?7VzpmWgVA?cDV&c2 zrY`kM#e`#nh=X@oSK8#mx1g$jUhr>LXi~^3Vd!8fIEr&j5h&qhQ-72J{d=ZqDFzpNP{f(V7}5JbyklM zoySbM$5esGXYA*;`TqZ=l<5M$k00gIZMUDa#3H6kGZ|D6sQq1&mm9mZp`pt|G4a!R zRN*Slm(29u&af54Ny%$AUf3+^mUfx5=3g9OE>b=S*!k*W8KjbM*}~NOpp}Bz<`}~G zdwh1aN_dsIrNtl$(ljJPjZQzT97FO2H}?X#5>KGo73Y@b13?L)ozbU1UQp_4Fs7Hj zK2R)vAN_||H|a(fHd>|irm`%-I#XiL>9i-F-TmN-i9zi|UG`x;iK^dtKKtWpy<#Ed z<(cSVgJD0+>~V*sA;6WS`-N_|#u&N3oC!xAjFnl>fdWrpDrsjCTA1y?FkM-zWq75s zL}*Wc&WtTS1RN1M{C2%~HkLBYjIueI>$87@##4fqn7B&; zSOGacu;pe3X#0t0Gd@bR>>Qi+82McLmek}L$+;5eZ{k2Xct*@Qt<<<&5i=(GLdD*l zBxTVFpls6yLjDItg_2T9hUO2}f7tLi7>3Un&+J_GYuFQbbTCcH6(U8h_xnF~2YdhY z1Lo=Ovo~S0hR$vB949m)In#XpS$z_;sruB){wPd4FG#?I?mS>0AG+L=%F4saZKt@d z(^4DL1^PDGQDb6i_$+ZMQmAbJAKUpDn4n@3iT3G$rA`1|1C4GgbOfiV$FGF%fA(?EEFF*+R$+2tI!_CaODhJ>)?(f@A*a?<8(ELV7mska} z>|rac@{sImQhqf!OR?U7e#?8sQ%b(2soXJA-LyJ(iw`7x(i$Hu4%8j8E+Ke3Jv=i$ z>49{^_FUDq@vZVQ1#rr>Zx0hh^#n?x6bpvGL;xm0@~2T+)d_{>o4@(16h7^eVhcNk z*Vg$Oe1OMI%x`X@`;1pD70^Ird7XPjSO|(I#Ew!wyye&YiIIdrcTbl|o0jQD^Q+3t zxK@$+MsTj!|I~wJ4s>IFe71*F^Mkay$E;=CJV+CroPQmSxMp$F*Z+&SV0+5Ipbb(y zcyA&%=9?;1^gPcG6I$J?`T=R}B8GX=L@@jt=e@_L?IE}7{%+=*!DiTZw|N?T75-Pm zOuwRa#?TM)v0<$S=#o1?PrE5L<$i%V7u5N+2CxY4SKLdDq86kV7?G69fTOd(oK~R?^0(??T6*rg z@h)!UwbW*&KFG` zGv}jCv6Zu@I1Q|WI6+kkckiVIe;DCcI=tgb#y`Md)s=pr)?HGBW>up)hSuOpfAjX%fLpM}M;+g3e6ZxrMzM(n8HlfU zr=zAimF&X`>s`H@=4=z*Qk(0KN9+Bd=G%s5)7H7Vb#EuJoejXQ0(1ocRk{Qh--tuU*8bRl z5nc&bj`6lF3i-Po8^wG06TbBdqAez7{fR{Yi)0I5(C%DF#YiJ9cg^aOkjZRKvTv{eeu zVudt(g{Dt)L{R6Z{hAi~&VaDoiQ;fT8x>hVO3k=FlC(y;lwFdP1{!nlV%QcOR6QWe z&Cn@YJ-dcbCJEQ_>v3JA`*1K6BSpaBo`Xf$_zqDbYW&7)OsdHxE0^y$28I|r&O0`1 zBgOSOzNF$&*u@Q^f#>_d4W?1zsi-@+kb#*|45$L5IO-UO)(g}ebZ26_+HnP%h=|o_ ziTT}r;G{8}k>e4Vh)o5gr#=4#_Fmq^x9a||DD~3K)LUv{llMYX5R~~cDOW4FZDj05 zg|}t3*L81d___F zAZo%0*I-l(j1(g@H=>d9rH%Up1+IUXt62uw#m?5R(R$06KZY)8E7H$$(MLVA@85m* zp8`O#t!PG4ifDH|Ugn@f4Jyk%HV-vVoVrq-Xp4J2+Obif+SA(^uR+`VcE(>$NRRNU zoh!M9Tk)5F{!N>^SK9g9pUXq*`Ki)b)V=o0y76KKeFLTd)1K9=s`tt#rpX(k(YYSW zW8W8Qf0fUF`i#q#f(wMLfylu96Uj}=@#Evo3g>^3ESnzt{{n%LqII4`QSY39?iBcN zOOcqE=;!Bm;9jQ$^t6946)r^q(Cq(#lN;BCdDTdUcbs@eV7@JNGmxs-9?#(Ymj?q* z$R8{LzjOWl^ZPIyznYe!w`bYCqsn8%C`@H+DY1rMpZ<9gm&|*=74IRmyROL3{EJHp zgt#FfFxjQqbH%KDuPMr_F!8bbwNZL^6^5@0qKAUS%F_@S_BzOt(_W-W$a84l`rwc> zH+^?|m)b|*L)m)RnwU*{*??F5K#$d|6Vv=js+{pz?*_XHKNDjuTfoZY)a_RXMZ6>f z#K*93K@&Tr+J4=PBcXdFHyyQa+|NdYShId4)1ZO50w#UU154z z&u*h2Y5Esb6IxTU;@C%YxjN`17fXg<^B#9|NMRm+6mCS3DArOtWt5-r1Yfg$WXLX; zgh)o$Z?(_me&Z<@T4IndQ%e*9$wAS2&;42g6@sbl+)PihsfbI{vAe887oj(#KQG)C zFSDv!v=Z(@SYMh-o`7af%2y$0b>6}xJ#`X-oBtD>so=;gkjzuA!ebD{`5X6;BN$;6 z(E+D66pUD}zOJmUe^=Y}&~^EzqcdM7xviA~&;5n<6|A@SE%#|%$OFDZ_VLwCs!qR| zxB#iMt#;bNe}#revL6qmvC{X9_6a+lQpI5c)tJoE5g!u;Dzt_qJoHY7plVebT@PHy zfY+yA>{o%i<`SDWu7)W?Uj!A{{Tugyq(J-!)vOQ=#U2a8tVc@49#10weCrMqtORc$ zxP68t813@U*p+@nXvWl~xlfDQ_QYf!eH#J--Ht6{BLySA38eS%UYF0M_auemE@wX2 zt0=A1eS{rr22-?f{b(SyM+M`twWyeS7Jnj>pE4vQa%cyvPgHZ$e3^^CSJE9n%v^D(^Uetoh zQHSAXKUbnXs+1&KO}O)$PMJ(|tm;@b>{IhbOR~%Ak@fzA+S7D0Z>Dr!0o1k-7?EKD zKgV0}_9X`0I;tI-4~?EvA$$LxpozZM{0Y3;+xm0C2iNLVTY);>VQ?Wy$J*+4KyGrf~8b?KC0l|7dr zu6-A@Lz8uQ5_S1gp{Qs zI~v=b&ziOy0aS3r)%vt1$9X(NP~PYOnLrY-4|#q+_O+ljJpZuPV}sg_^oufPa9bDrpb*5dTQN zL=_kxgxGmQ@2M-6EDWPp{$59@gZXE<6#;?ZMR#5_Y?XCTRi527;o(!z_6N*@e`jW5 z3t%4>s$#xdk0I(d9Vd>N2j&RIP*UDnBE3<)86tq2lR%utQKP2X77t?>FOV!SuBtaldwM$+8`%VDg_l!y-mZcbZk`)mm4K7d?<=n`t}mDbIc zguq>=j#uq4p1F#hqp`%3!Ph;tM>XGin8txjrQ70i^{e_RpGBrSPxdNFPy<7KhxFCs zx=+6D;c-HI3QNCT6LobWP;6iNqEtPpp1(DUh}MrE9b(F((eetfXAO-lYQkx9qcr!3 zh<{fY7#PW=2_kuQCY14Y0~KtqwTUF2UwR}QXqv+pL|2tB!`J$T@|8U59W-<&HYDj> z^{@O5Dbrru^R+|NUn-a z{=d+5`uJY|n6I`ZLls5@XXtF$1sUD6EGL>Xh6Ry_kQPPgs(GExm}WD1m`u0vXdGv6 zWtD7g*maNv4(1~N7Zj{_i<6W#_WB^Zv3_V6` zm1c-W!F%4_i?nR94j;{d5X@XqCVAccPoH>If68X(W*#y|fnT%V=DE>fgVKc*9@uEj zcd@?tcJo?ka%b1(a~OT$2hAyTCnt7$Y)fu+J~xNjK8i*9zHS+(El)?OuTQO^Z_Y$=4OZ|7<9H?!u`V=Pk$lh zh5xoqIrb`i z=U^vCXZ(N+7t0DaN75djJf7V5{O9Qab+-}k#Ch>N+t{S&@u(Mx4;=W5vCN`YNwyHq zu>^=>w;A@EQ@z}}&qk5IM2B+5+uaTQXu;iypv*_ + + + + + + diff --git a/common/traffic_light_recognition_marker_publisher/package.xml b/common/traffic_light_recognition_marker_publisher/package.xml new file mode 100644 index 0000000000000..d12022c01684e --- /dev/null +++ b/common/traffic_light_recognition_marker_publisher/package.xml @@ -0,0 +1,30 @@ + + + + traffic_light_recognition_marker_publisher + 0.0.0 + The traffic_light_recognition_marker_publisher package + Tomoya Kimura + Takeshi Miura + Shumpei Wakabayashi + Apache License 2.0 + + ament_cmake + autoware_cmake + + autoware_auto_mapping_msgs + autoware_auto_perception_msgs + geometry_msgs + lanelet2_extension + rclcpp + rclcpp_components + tier4_autoware_utils + visualization_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp b/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp new file mode 100644 index 0000000000000..6076d3fa32f26 --- /dev/null +++ b/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp @@ -0,0 +1,164 @@ +// Copyright 2021 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 "traffic_light_recognition_marker_publisher.hpp" + +#include +#include +#include +#include +#include + +TrafficLightRecognitionMarkerPublisher::TrafficLightRecognitionMarkerPublisher( + const rclcpp::NodeOptions & options) +: Node("traffic_light_recognition_marker_publisher", options) +{ + using std::placeholders::_1; + + sub_map_ptr_ = this->create_subscription( + "~/input/lanelet2_map", rclcpp::QoS{1}.transient_local(), + std::bind(&TrafficLightRecognitionMarkerPublisher::onMap, this, _1)); + sub_tlr_ptr_ = this->create_subscription( + "~/input/traffic_signals", rclcpp::QoS{1}, + std::bind(&TrafficLightRecognitionMarkerPublisher::onTrafficSignalArray, this, _1)); + pub_marker_ptr_ = + this->create_publisher("~/output/marker", rclcpp::QoS{1}); +} + +void TrafficLightRecognitionMarkerPublisher::onMap(const HADMapBin::ConstSharedPtr msg_ptr) +{ + is_map_ready_ = false; + lanelet::LaneletMapPtr viz_lanelet_map(new lanelet::LaneletMap); + lanelet::utils::conversion::fromBinMsg(*msg_ptr, viz_lanelet_map); + lanelet::ConstLanelets lanelets = lanelet::utils::query::laneletLayer(viz_lanelet_map); + std::vector tl_regulatory_elements = + lanelet::utils::query::autowareTrafficLights(lanelets); + for (const auto & tl : tl_regulatory_elements) { + const auto tl_lights = tl->trafficLights(); + for (const auto & tl_light : tl_lights) { + if (tl_light.isLineString()) { + lanelet::ConstLineString3d tl_linestring = + static_cast(tl_light); + int32_t tl_id = static_cast(tl_light.id()); + Pose tl_pose; + tl_pose.position.x = (tl_linestring.front().x() + tl_linestring.back().x()) / 2; + tl_pose.position.y = (tl_linestring.front().y() + tl_linestring.back().y()) / 2; + tl_pose.position.z = tl_linestring.front().z() + 1.0; + tl_position_map_[tl_id] = tl_pose; + } + } + } + is_map_ready_ = true; +} + +void TrafficLightRecognitionMarkerPublisher::onTrafficSignalArray( + const TrafficSignalArray::ConstSharedPtr msg_ptr) +{ + if (!is_map_ready_) { + return; + } + MarkerArray markers; + marker_id = 0; + for (const auto & tl : msg_ptr->signals) { + if (tl_position_map_.count(tl.map_primitive_id) == 0) continue; + auto tl_position = tl_position_map_[tl.map_primitive_id]; + for (const auto tl_light : tl.lights) { + const auto marker = getTrafficLightMarker(tl_position, tl_light.color, tl_light.shape); + markers.markers.emplace_back(marker); + marker_id++; + tl_position.position.z += 0.5; + } + } + pub_marker_ptr_->publish(markers); +} + +visualization_msgs::msg::Marker TrafficLightRecognitionMarkerPublisher::getTrafficLightMarker( + const Pose & tl_pose, const uint8_t tl_color, const uint8_t tl_shape) +{ + visualization_msgs::msg::Marker marker; + marker.header.frame_id = "map"; + marker.header.stamp = rclcpp::Time(); + marker.ns = "traffic_light_color"; + marker.id = marker_id; + marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + marker.lifetime = rclcpp::Duration::from_seconds(1.0); + marker.action = visualization_msgs::msg::Marker::ADD; + marker.pose = tl_pose; + marker.color = getTrafficLightColor(tl_color, tl_shape); + marker.scale.z = 0.5; + marker.frame_locked = false; + marker.text = getTrafficLightString(tl_color, tl_shape); + + return marker; +} + +std::string TrafficLightRecognitionMarkerPublisher::getTrafficLightString( + const uint8_t tl_color, const uint8_t tl_shape) +{ + if (tl_shape == TrafficLight::LEFT_ARROW) return "LEFT_ARROW"; + if (tl_shape == TrafficLight::RIGHT_ARROW) return "RIGHT_ARROW"; + if (tl_shape == TrafficLight::UP_ARROW) return "UP_ARROW"; + if (tl_shape == TrafficLight::DOWN_ARROW) return "DOWN_ARROW"; + if (tl_shape == TrafficLight::DOWN_LEFT_ARROW) return "DOWN_LEFT_ARROW"; + if (tl_shape == TrafficLight::DOWN_RIGHT_ARROW) return "DOWN_RIGHT_ARROW"; + + if (tl_color == TrafficLight::RED) return "RED"; + if (tl_color == TrafficLight::GREEN) return "GREEN"; + if (tl_color == TrafficLight::AMBER) return "AMBER"; + + if (tl_shape == TrafficLight::UNKNOWN) return "UNKNOWN"; + + return "UNKNOWN"; +} + +std_msgs::msg::ColorRGBA TrafficLightRecognitionMarkerPublisher::getTrafficLightColor( + const uint8_t tl_color, const uint8_t tl_shape) +{ + std_msgs::msg::ColorRGBA c; + c.r = 1.0f; + c.g = 1.0f; + c.b = 1.0f; + c.a = 0.999; + + if ( + tl_shape == TrafficLight::LEFT_ARROW || tl_shape == TrafficLight::RIGHT_ARROW || + tl_shape == TrafficLight::UP_ARROW || tl_shape == TrafficLight::DOWN_ARROW || + tl_shape == TrafficLight::DOWN_LEFT_ARROW || tl_shape == TrafficLight::DOWN_RIGHT_ARROW) { + return c; // white + } + + if (tl_color == TrafficLight::RED) { + c.r = 1.0f; + c.g = 0.0f; + c.b = 0.0f; + return c; // red + } + if (tl_color == TrafficLight::GREEN) { + c.r = 0.0f; + c.g = 1.0f; + c.b = 0.0f; + return c; // green + } + if (tl_color == TrafficLight::AMBER) { + c.r = 1.0f; + c.g = 1.0f; + c.b = 0.0f; + return c; // amber + } + + return c; // white +} + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(TrafficLightRecognitionMarkerPublisher) diff --git a/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp b/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp new file mode 100644 index 0000000000000..de9aea14b7e5a --- /dev/null +++ b/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp @@ -0,0 +1,62 @@ +// Copyright 2021 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 TRAFFIC_LIGHT_RECOGNITION_MARKER_PUBLISHER_HPP_ +#define TRAFFIC_LIGHT_RECOGNITION_MARKER_PUBLISHER_HPP_ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +class TrafficLightRecognitionMarkerPublisher : public rclcpp::Node +{ +public: + using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using TrafficSignalArray = autoware_auto_perception_msgs::msg::TrafficSignalArray; + using TrafficLight = autoware_auto_perception_msgs::msg::TrafficLight; + using MarkerArray = visualization_msgs::msg::MarkerArray; + using Pose = geometry_msgs::msg::Pose; + + explicit TrafficLightRecognitionMarkerPublisher(const rclcpp::NodeOptions & options); + +private: + rclcpp::Subscription::SharedPtr sub_map_ptr_; + rclcpp::Subscription::SharedPtr + sub_tlr_ptr_; + rclcpp::Publisher::SharedPtr pub_marker_ptr_; + + void onMap(const HADMapBin::ConstSharedPtr msg_ptr); + void onTrafficSignalArray(const TrafficSignalArray::ConstSharedPtr msg_ptr); + visualization_msgs::msg::Marker getTrafficLightMarker( + const Pose & tl_pose, const uint8_t tl_color, const uint8_t tl_shape); + + std::string getTrafficLightString(const uint8_t tl_color, const uint8_t tl_shape); + std_msgs::msg::ColorRGBA getTrafficLightColor(const uint8_t tl_color, const uint8_t tl_shape); + + std::map tl_position_map_; + bool is_map_ready_ = false; + int32_t marker_id = 0; +}; + +#endif // TRAFFIC_LIGHT_RECOGNITION_MARKER_PUBLISHER_HPP_ From 1b697794356ec6deb7a27b107ebd348b905b1a8c Mon Sep 17 00:00:00 2001 From: Tao Zhong <55872497+tzhong518@users.noreply.github.com> Date: Wed, 28 Jun 2023 17:25:29 +0900 Subject: [PATCH 046/118] fix(replace motorbike with motorcycle): fix yolox's labelmap (#4102) fix:replace motorbike with motorcycle Signed-off-by: tzhong518 --- perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp b/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp index 65307ff28acde..e450ba6b5817e 100644 --- a/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp +++ b/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp @@ -199,6 +199,8 @@ void TrtYoloXNode::replaceLabelMap() auto & label = label_map_[i]; if (label == "PERSON") { label = "PEDESTRIAN"; + } else if (label == "MOTORBIKE") { + label = "MOTORCYCLE"; } else if ( label != "CAR" && label != "PEDESTRIAN" && label != "BUS" && label != "TRUCK" && label != "BICYCLE" && label != "MOTORCYCLE") { From 2919364143357807f2cfef9ff2264cb5eb9bb137 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 28 Jun 2023 23:58:25 +0900 Subject: [PATCH 047/118] feat(behavior_path_planner): add getCurrentLanes with length args (#4108) Signed-off-by: kosuke55 --- .../behavior_path_planner/utils/utils.hpp | 3 +++ .../behavior_path_planner/src/utils/utils.cpp | 21 +++++++++++++------ 2 files changed, 18 insertions(+), 6 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 cc2d109f0cf1c..a8be9cdbe1c3e 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 @@ -350,6 +350,9 @@ BehaviorModuleOutput getReferencePath( // object label std::uint8_t getHighestProbLabel(const std::vector & classification); +lanelet::ConstLanelets getCurrentLanes( + const std::shared_ptr & planner_data, const double backward_path_length, + const double forward_path_length); lanelet::ConstLanelets getCurrentLanes(const std::shared_ptr & planner_data); lanelet::ConstLanelets getCurrentLanesFromPath( diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 5b89b352d9574..fabf857aa0b40 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -2573,23 +2573,32 @@ std::uint8_t getHighestProbLabel(const std::vector & class return label; } -lanelet::ConstLanelets getCurrentLanes(const std::shared_ptr & planner_data) +lanelet::ConstLanelets getCurrentLanes( + const std::shared_ptr & planner_data, const double backward_path_length, + const double forward_path_length) { 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; lanelet::ConstLanelet current_lane; if (!route_handler->getClosestLaneletWithinRoute(current_pose, ¤t_lane)) { - // RCLCPP_ERROR(getLogger(), "failed to find closest lanelet within route!!!"); - std::cerr << "failed to find closest lanelet within route!!!" << std::endl; + auto clock{rclcpp::Clock{RCL_ROS_TIME}}; + RCLCPP_ERROR_STREAM_THROTTLE( + rclcpp::get_logger("behavior_path_planner").get_child("utils"), clock, 1000, + "failed to find closest lanelet within route!!!"); return {}; // TODO(Horibe) what should be returned? } // For current_lanes with desired length return route_handler->getLaneletSequence( - current_lane, current_pose, common_parameters.backward_path_length, - common_parameters.forward_path_length); + current_lane, current_pose, backward_path_length, forward_path_length); +} + +lanelet::ConstLanelets getCurrentLanes(const std::shared_ptr & planner_data) +{ + const auto & common_parameters = planner_data->parameters; + return getCurrentLanes( + planner_data, common_parameters.backward_path_length, common_parameters.forward_path_length); } lanelet::ConstLanelets getCurrentLanesFromPath( From df3f7b885aaeaa949ffff601c4ef65511c435103 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 29 Jun 2023 07:37:59 +0900 Subject: [PATCH 048/118] feat(behavior_path_planner)!: remove macro (#4106) * refactor(avoidance): remove macro Signed-off-by: satoshi-ota * refactor(behavior_path_planner): remove macro Signed-off-by: satoshi-ota * refactor(start_planner): remove macro Signed-off-by: satoshi-ota * refactor(goal_planner): remove macro Signed-off-by: satoshi-ota * refactor(side_shift): remove macro Signed-off-by: satoshi-ota * refactor(lane_change): remove macro Signed-off-by: satoshi-ota * refactor(dynamic_avoidance): remove macro Signed-off-by: satoshi-ota * refactor(behavior_path_planner): remove files Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- planning/behavior_path_planner/CMakeLists.txt | 38 +--- .../behavior_path_planner_node.hpp | 34 +--- .../behavior_tree_manager.hpp | 90 --------- .../behavior_path_planner/module_status.hpp | 10 - .../avoidance/avoidance_module.hpp | 7 - .../dynamic_avoidance_module.hpp | 6 - .../goal_planner/goal_planner_module.hpp | 11 +- .../lane_following/lane_following_module.hpp | 58 ------ .../scene_module_bt_node_interface.hpp | 63 ------- .../scene_module/scene_module_interface.hpp | 100 ---------- .../side_shift/side_shift_module.hpp | 10 - .../start_planner/start_planner_module.hpp | 11 -- .../default_fixed_goal_planner.hpp | 4 - .../src/behavior_path_planner_node.cpp | 138 -------------- .../src/behavior_tree_manager.cpp | 175 ------------------ .../avoidance/avoidance_module.cpp | 56 ------ .../dynamic_avoidance_module.cpp | 14 -- .../goal_planner/goal_planner_module.cpp | 24 +-- .../scene_module/lane_change/interface.cpp | 12 -- .../lane_following/lane_following_module.cpp | 94 ---------- .../scene_module_bt_node_interface.cpp | 138 -------------- .../side_shift/side_shift_module.cpp | 48 ----- .../start_planner/start_planner_module.cpp | 62 ------- .../default_fixed_goal_planner.cpp | 34 ---- .../behavior_path_planner/src/utils/utils.cpp | 22 --- 25 files changed, 12 insertions(+), 1247 deletions(-) delete mode 100644 planning/behavior_path_planner/include/behavior_path_planner/behavior_tree_manager.hpp delete mode 100644 planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_following/lane_following_module.hpp delete mode 100644 planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_bt_node_interface.hpp delete mode 100644 planning/behavior_path_planner/src/behavior_tree_manager.cpp delete mode 100644 planning/behavior_path_planner/src/scene_module/lane_following/lane_following_module.cpp delete mode 100644 planning/behavior_path_planner/src/scene_module/scene_module_bt_node_interface.cpp diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 4463620dcc4a9..bf135003fd353 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -7,21 +7,26 @@ autoware_package() find_package(OpenCV REQUIRED) find_package(magic_enum CONFIG REQUIRED) -set(COMPILE_WITH_OLD_ARCHITECTURE FALSE) - -set(common_src +ament_auto_add_library(behavior_path_planner_node SHARED + src/planner_manager.cpp src/steering_factor_interface.cpp src/behavior_path_planner_node.cpp src/scene_module/scene_module_visitor.cpp src/scene_module/avoidance/avoidance_module.cpp + src/scene_module/avoidance/manager.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp + src/scene_module/dynamic_avoidance/manager.cpp src/scene_module/start_planner/start_planner_module.cpp + src/scene_module/start_planner/manager.cpp src/scene_module/goal_planner/goal_planner_module.cpp + src/scene_module/goal_planner/manager.cpp src/scene_module/side_shift/side_shift_module.cpp + src/scene_module/side_shift/manager.cpp src/scene_module/lane_change/interface.cpp src/scene_module/lane_change/normal.cpp src/scene_module/lane_change/external_request.cpp src/scene_module/lane_change/avoidance_by_lane_change.cpp + src/scene_module/lane_change/manager.cpp src/turn_signal_decider.cpp src/utils/utils.cpp src/utils/path_utils.cpp @@ -50,33 +55,6 @@ set(common_src src/marker_util/lane_change/debug.cpp ) -if(COMPILE_WITH_OLD_ARCHITECTURE) - ament_auto_add_library(behavior_path_planner_node SHARED - src/behavior_tree_manager.cpp - src/scene_module/scene_module_bt_node_interface.cpp - src/scene_module/lane_following/lane_following_module.cpp - ${common_src} - ) - - target_compile_definitions(behavior_path_planner_node PRIVATE USE_OLD_ARCHITECTURE) - - message(WARNING "Build behavior_path_planner with OLD framework...") - -else() - ament_auto_add_library(behavior_path_planner_node SHARED - src/planner_manager.cpp - src/scene_module/avoidance/manager.cpp - src/scene_module/dynamic_avoidance/manager.cpp - src/scene_module/start_planner/manager.cpp - src/scene_module/goal_planner/manager.cpp - src/scene_module/side_shift/manager.cpp - src/scene_module/lane_change/manager.cpp - ${common_src} - ) - - message(WARNING "Build behavior_path_planner with NEW framework...") -endif() - target_include_directories(behavior_path_planner_node SYSTEM PUBLIC ${EIGEN3_INCLUDE_DIR} ) 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 d06a3aae68e4f..454106e4e6811 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 @@ -16,26 +16,14 @@ #define BEHAVIOR_PATH_PLANNER__BEHAVIOR_PATH_PLANNER_NODE_HPP_ #include "behavior_path_planner/data_manager.hpp" -#include "behavior_path_planner/scene_module/scene_module_interface.hpp" - -#ifdef USE_OLD_ARCHITECTURE -#include "behavior_path_planner/behavior_tree_manager.hpp" -#include "behavior_path_planner/scene_module/avoidance/avoidance_module.hpp" -#include "behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp" -#include "behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp" -#include "behavior_path_planner/scene_module/lane_following/lane_following_module.hpp" -#include "behavior_path_planner/scene_module/side_shift/side_shift_module.hpp" -#include "behavior_path_planner/scene_module/start_planner/start_planner_module.hpp" -#else #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" -#endif - #include "behavior_path_planner/steering_factor_interface.hpp" #include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" #include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" @@ -127,11 +115,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node std::shared_ptr planner_data_; -#ifdef USE_OLD_ARCHITECTURE - std::shared_ptr bt_manager_; -#else std::shared_ptr planner_manager_; -#endif std::unique_ptr steering_factor_interface_ptr_; Scenario::SharedPtr current_scenario_{nullptr}; @@ -160,10 +144,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node BehaviorPathPlannerParameters getCommonParam(); -#ifdef USE_OLD_ARCHITECTURE - BehaviorTreeManagerParam getBehaviorTreeManagerParam(); -#endif - AvoidanceParameters getAvoidanceParam(); DynamicAvoidanceParameters getDynamicAvoidanceParam(); LaneChangeParameters getLaneChangeParam(); @@ -196,15 +176,9 @@ class BehaviorPathPlannerNode : public rclcpp::Node /** * @brief extract path from behavior tree output */ -#ifdef USE_OLD_ARCHITECTURE - PathWithLaneId::SharedPtr getPath( - const BehaviorModuleOutput & bt_out, const std::shared_ptr & planner_data, - const std::shared_ptr & bt_manager); -#else PathWithLaneId::SharedPtr getPath( const BehaviorModuleOutput & bt_out, const std::shared_ptr & planner_data, const std::shared_ptr & planner_manager); -#endif bool keepInputPoints(const std::vector> & statuses) const; @@ -246,11 +220,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node /** * @brief publish path candidate */ -#ifdef USE_OLD_ARCHITECTURE - void publishPathCandidate( - const std::vector> & scene_modules, - const std::shared_ptr & planner_data); -#else void publishPathCandidate( const std::vector> & managers, const std::shared_ptr & planner_data); @@ -258,7 +227,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node void publishPathReference( const std::vector> & managers, const std::shared_ptr & planner_data); -#endif /** * @brief convert path with lane id to path for publish path candidate diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_tree_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_tree_manager.hpp deleted file mode 100644 index f179b90139705..0000000000000 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_tree_manager.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// Copyright 2021 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__BEHAVIOR_TREE_MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__BEHAVIOR_TREE_MANAGER_HPP_ - -#include "behavior_path_planner/data_manager.hpp" -#include "behavior_path_planner/scene_module/scene_module_bt_node_interface.hpp" -#include "behavior_path_planner/scene_module/scene_module_visitor.hpp" - -#include -#include - -#include - -#include -#include -#include -#include - -#include -#include -#include - -namespace behavior_path_planner -{ -struct BehaviorTreeManagerParam -{ - std::string bt_tree_config_path; - int groot_zmq_publisher_port; - int groot_zmq_server_port; -}; - -class BehaviorTreeManager -{ -public: - BehaviorTreeManager(rclcpp::Node & node, const BehaviorTreeManagerParam & param); - void createBehaviorTree(); - void registerSceneModule(const std::shared_ptr & p); - - void resetBehaviorTree(); - - BehaviorModuleOutput run(const std::shared_ptr & data); - std::vector> getModulesStatus(); - std::shared_ptr getAllSceneModuleDebugMsgData(); - std::vector> getSceneModules() const - { - return scene_modules_; - } - - AvoidanceDebugMsgArray getAvoidanceDebugMsgArray(); - -private: - BehaviorTreeManagerParam bt_manager_param_; - std::shared_ptr current_planner_data_; - std::vector> scene_modules_; - std::vector> modules_status_; - rclcpp::Logger logger_; - rclcpp::Clock clock_; - std::shared_ptr scene_module_visitor_ptr_; - - BT::BehaviorTreeFactory bt_factory_; - BT::Tree bt_tree_; - BT::Blackboard::Ptr blackboard_; - - void resetNotRunningModulePathCandidate(); - - // For Groot monitoring - std::unique_ptr groot_monitor_; - - void addGrootMonitoring( - BT::Tree * tree, uint16_t publisher_port, uint16_t server_port, - uint16_t max_msg_per_second = 25); - - void resetGrootMonitor(); -}; -} // namespace behavior_path_planner - -#endif // BEHAVIOR_PATH_PLANNER__BEHAVIOR_TREE_MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/module_status.hpp b/planning/behavior_path_planner/include/behavior_path_planner/module_status.hpp index cfb5209ff795c..f6a7a10b21db1 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/module_status.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/module_status.hpp @@ -15,16 +15,8 @@ #ifndef BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_ #define BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_ -#ifdef USE_OLD_ARCHITECTURE -#include -#endif - namespace behavior_path_planner { - -#ifdef USE_OLD_ARCHITECTURE -using ModuleStatus = BT::NodeStatus; -#else enum class ModuleStatus { IDLE = 0, RUNNING = 1, @@ -32,8 +24,6 @@ enum class ModuleStatus { FAILURE = 3, // SKIPPED = 4, }; -#endif - } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__MODULE_STATUS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 28357af3cda84..5751e1873a579 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -46,14 +46,9 @@ using tier4_planning_msgs::msg::AvoidanceDebugMsg; class AvoidanceModule : public SceneModuleInterface { public: -#ifdef USE_OLD_ARCHITECTURE - AvoidanceModule( - const std::string & name, rclcpp::Node & node, std::shared_ptr parameters); -#else AvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map > & rtc_interface_ptr_map); -#endif ModuleStatus updateState() override; ModuleStatus getNodeStatusWhileWaitingApproval() const override { return ModuleStatus::SUCCESS; } @@ -67,12 +62,10 @@ class AvoidanceModule : public SceneModuleInterface void updateData() override; void acceptVisitor(const std::shared_ptr & visitor) const override; -#ifndef USE_OLD_ARCHITECTURE void updateModuleParams(const std::shared_ptr & parameters) { parameters_ = parameters; } -#endif std::shared_ptr get_debug_msg_array() const; private: 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 4898188c71319..32735b72913fa 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 @@ -109,11 +109,6 @@ class DynamicAvoidanceModule : public SceneModuleInterface } }; -#ifdef USE_OLD_ARCHITECTURE - DynamicAvoidanceModule( - const std::string & name, rclcpp::Node & node, - std::shared_ptr parameters); -#else DynamicAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, @@ -123,7 +118,6 @@ class DynamicAvoidanceModule : public SceneModuleInterface { parameters_ = parameters; } -#endif bool isExecutionRequested() const override; bool isExecutionReady() const override; 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 da2665723ae90..1e4a1370ac867 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 @@ -87,11 +87,6 @@ struct PUllOverStatus class GoalPlannerModule : public SceneModuleInterface { public: -#ifdef USE_OLD_ARCHITECTURE - GoalPlannerModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters); -#else GoalPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, @@ -101,7 +96,6 @@ class GoalPlannerModule : public SceneModuleInterface { parameters_ = parameters; } -#endif BehaviorModuleOutput run() override; bool isExecutionRequested() const override; @@ -152,10 +146,7 @@ class GoalPlannerModule : public SceneModuleInterface tier4_autoware_utils::LinearRing2d vehicle_footprint_; -// save last time and pose -#ifdef USE_OLD_ARCHITECTURE - std::unique_ptr last_received_time_; -#endif + // save last time and pose std::unique_ptr last_approved_time_; std::unique_ptr last_increment_time_; std::unique_ptr last_path_update_time_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_following/lane_following_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_following/lane_following_module.hpp deleted file mode 100644 index d908dea155180..0000000000000 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_following/lane_following_module.hpp +++ /dev/null @@ -1,58 +0,0 @@ -// Copyright 2021 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__SCENE_MODULE__LANE_FOLLOWING__LANE_FOLLOWING_MODULE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_FOLLOWING__LANE_FOLLOWING_MODULE_HPP_ - -#include "behavior_path_planner/scene_module/scene_module_interface.hpp" -#include "behavior_path_planner/utils/lane_following/module_data.hpp" - -#include - -#include - -#include -#include -#include - -namespace behavior_path_planner -{ -using autoware_auto_planning_msgs::msg::PathWithLaneId; - -class LaneFollowingModule : public SceneModuleInterface -{ -public: - LaneFollowingModule(const std::string & name, rclcpp::Node & node); - - bool isExecutionRequested() const override; - bool isExecutionReady() const override; - BT::NodeStatus updateState() override; - BehaviorModuleOutput plan() override; - CandidateOutput planCandidate() const override; - void processOnEntry() override; - void processOnExit() override; - - void setParameters(const std::shared_ptr & parameters); - void acceptVisitor( - [[maybe_unused]] const std::shared_ptr & visitor) const override - { - } - -private: - BehaviorModuleOutput getReferencePath() const; - void initParam(); -}; -} // namespace behavior_path_planner - -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_FOLLOWING__LANE_FOLLOWING_MODULE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_bt_node_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_bt_node_interface.hpp deleted file mode 100644 index e3578928782f3..0000000000000 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_bt_node_interface.hpp +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright 2021 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__SCENE_MODULE__SCENE_MODULE_BT_NODE_INTERFACE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SCENE_MODULE_BT_NODE_INTERFACE_HPP_ - -#include "behavior_path_planner/scene_module/scene_module_interface.hpp" - -#include - -#include -#include - -namespace behavior_path_planner -{ -struct SceneModuleStatus -{ - explicit SceneModuleStatus(const std::string & n) : module_name(n) {} - std::string module_name; // TODO(Horibe) should be const - bool is_requested{false}; - bool is_execution_ready{false}; - bool is_waiting_approval{false}; - BT::NodeStatus status{BT::NodeStatus::SUCCESS}; -}; - -class SceneModuleBTNodeInterface : public BT::CoroActionNode -{ -public: - SceneModuleBTNodeInterface( - const std::string & name, const BT::NodeConfiguration & config, - const std::shared_ptr & scene_module, - const std::shared_ptr & module_status); - -protected: - std::shared_ptr scene_module_; - std::shared_ptr module_status_; - -public: - BT::NodeStatus tick() override; - void halt() override; - static BT::PortsList providedPorts(); - - BT::NodeStatus planCandidate(BT::TreeNode & self); -}; - -BT::NodeStatus isExecutionRequested( - const std::shared_ptr p, - const std::shared_ptr & status); - -} // namespace behavior_path_planner - -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SCENE_MODULE_BT_NODE_INTERFACE_HPP_ 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 68db46e68b1d3..f068bff5e8caa 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 @@ -76,37 +76,11 @@ class SceneModuleInterface clock_{node.get_clock()}, is_waiting_approval_{false}, is_locked_new_module_launch_{false}, -#ifdef USE_OLD_ARCHITECTURE - current_state_{ModuleStatus::SUCCESS}, -#else current_state_{ModuleStatus::IDLE}, -#endif rtc_interface_ptr_map_(rtc_interface_ptr_map), steering_factor_interface_ptr_( std::make_unique(&node, utils::convertToSnakeCase(name))) { -#ifdef USE_OLD_ARCHITECTURE - { - const auto ns = std::string("~/debug/") + utils::convertToSnakeCase(name); - pub_debug_marker_ = node.create_publisher(ns, 20); - } - - { - const auto ns = std::string("~/info/") + utils::convertToSnakeCase(name); - pub_info_marker_ = node.create_publisher(ns, 20); - } - - { - const auto ns = std::string("~/virtual_wall/") + utils::convertToSnakeCase(name); - pub_virtual_wall_ = node.create_publisher(ns, 20); - } - - { - const auto ns = std::string("~/output/stop_reasons"); - pub_stop_reasons_ = node.create_publisher(ns, 20); - } -#endif - for (auto itr = rtc_interface_ptr_map_.begin(); itr != rtc_interface_ptr_map_.end(); ++itr) { uuid_map_.emplace(itr->first, generateUUID()); } @@ -185,10 +159,6 @@ class SceneModuleInterface */ virtual BehaviorModuleOutput run() { -#ifdef USE_OLD_ARCHITECTURE - current_state_ = ModuleStatus::RUNNING; -#endif - updateData(); if (!isWaitingApproval()) { @@ -212,11 +182,7 @@ class SceneModuleInterface { RCLCPP_DEBUG(getLogger(), "%s %s", name_.c_str(), __func__); -#ifdef USE_OLD_ARCHITECTURE - current_state_ = ModuleStatus::SUCCESS; -#else current_state_ = ModuleStatus::IDLE; -#endif stop_reason_ = StopReason(); @@ -314,61 +280,6 @@ class SceneModuleInterface */ virtual void setData(const std::shared_ptr & data) { planner_data_ = data; } -#ifdef USE_OLD_ARCHITECTURE - void publishInfoMarker() { pub_info_marker_->publish(info_marker_); } - - void publishDebugMarker() { pub_debug_marker_->publish(debug_marker_); } - - void publishStopReasons() - { - StopReasonArray stop_reason_array; - stop_reason_array.header.frame_id = "map"; - stop_reason_array.header.stamp = clock_->now(); - - const auto reason = getStopReason(); - if (reason.reason == "") { - return; - } - - stop_reason_array.stop_reasons.push_back(reason); - - pub_stop_reasons_->publish(stop_reason_array); - } - - void publishVirtualWall() - { - MarkerArray markers{}; - - const auto opt_stop_pose = getStopPose(); - if (!!opt_stop_pose) { - const auto virtual_wall = createStopVirtualWallMarker( - opt_stop_pose.get(), utils::convertToSnakeCase(name()), rclcpp::Clock().now(), 0); - appendMarkerArray(virtual_wall, &markers); - } - - const auto opt_slow_pose = getSlowPose(); - if (!!opt_slow_pose) { - const auto virtual_wall = createSlowDownVirtualWallMarker( - opt_slow_pose.get(), utils::convertToSnakeCase(name()), rclcpp::Clock().now(), 0); - appendMarkerArray(virtual_wall, &markers); - } - - const auto opt_dead_pose = getDeadPose(); - if (!!opt_dead_pose) { - const auto virtual_wall = createDeadLineVirtualWallMarker( - opt_dead_pose.get(), utils::convertToSnakeCase(name()), rclcpp::Clock().now(), 0); - appendMarkerArray(virtual_wall, &markers); - } - - const auto module_specific_wall = getModuleVirtualWall(); - appendMarkerArray(module_specific_wall, &markers); - - pub_virtual_wall_->publish(markers); - - resetWallPoses(); - } -#endif - bool isWaitingApproval() const { return is_waiting_approval_; } bool isLockedNewModuleLaunch() const { return is_locked_new_module_launch_; } @@ -459,13 +370,6 @@ class SceneModuleInterface rclcpp::Logger logger_; -#ifdef USE_OLD_ARCHITECTURE - rclcpp::Publisher::SharedPtr pub_info_marker_; - rclcpp::Publisher::SharedPtr pub_debug_marker_; - rclcpp::Publisher::SharedPtr pub_virtual_wall_; - rclcpp::Publisher::SharedPtr pub_stop_reasons_; -#endif - BehaviorModuleOutput previous_module_output_; protected: @@ -575,11 +479,7 @@ class SceneModuleInterface PlanResult path_candidate_; PlanResult path_reference_; -#ifdef USE_OLD_ARCHITECTURE - ModuleStatus current_state_{ModuleStatus::SUCCESS}; -#else ModuleStatus current_state_{ModuleStatus::IDLE}; -#endif StopReason stop_reason_; 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 250ece8190e37..8118d05ef225d 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 @@ -40,16 +40,10 @@ using tier4_planning_msgs::msg::LateralOffset; class SideShiftModule : public SceneModuleInterface { public: -#ifdef USE_OLD_ARCHITECTURE - SideShiftModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters); -#else SideShiftModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, const std::unordered_map > & rtc_interface_ptr_map); -#endif bool isExecutionRequested() const override; bool isExecutionReady() const override; @@ -81,10 +75,6 @@ class SideShiftModule : public SceneModuleInterface void initVariables(); -#ifdef USE_OLD_ARCHITECTURE - void onLateralOffset(const LateralOffset::ConstSharedPtr lateral_offset_msg); -#endif - // non-const methods BehaviorModuleOutput adjustDrivableArea(const ShiftedPath & path) const; 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 a48c24b183111..6aa3ca9ac2239 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 @@ -66,11 +66,6 @@ struct PullOutStatus class StartPlannerModule : public SceneModuleInterface { public: -#ifdef USE_OLD_ARCHITECTURE - StartPlannerModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters); -#else StartPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, @@ -80,7 +75,6 @@ class StartPlannerModule : public SceneModuleInterface { parameters_ = parameters; } -#endif BehaviorModuleOutput run() override; @@ -156,11 +150,6 @@ class StartPlannerModule : public SceneModuleInterface bool hasFinishedCurrentPath(); void setDebugData() const; - -// temporary for old architecture -#ifdef USE_OLD_ARCHITECTURE - mutable bool is_executed_{false}; -#endif }; } // namespace behavior_path_planner 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 568ecdc98c705..40c339e507683 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 @@ -32,10 +32,6 @@ class DefaultFixedGoalPlanner : public FixedGoalPlannerBase BehaviorModuleOutput plan(const std::shared_ptr & planner_data) const override; protected: -#ifdef USE_OLD_ARCHITECTURE - boost::optional getReferencePath( - const std::shared_ptr & planner_data) const; -#endif PathWithLaneId modifyPathForSmoothGoalConnection( const PathWithLaneId & path, const std::shared_ptr & planner_data) const; }; 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 4ed96ebe463ae..410c443b94ed9 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -137,66 +137,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod m_set_param_res = this->add_on_set_parameters_callback( std::bind(&BehaviorPathPlannerNode::onSetParam, this, std::placeholders::_1)); -#ifdef USE_OLD_ARCHITECTURE - // behavior tree manager - { - RCLCPP_INFO(get_logger(), "use behavior tree."); - - const std::string path_candidate_name_space = "/planning/path_candidate/"; - const std::lock_guard lock(mutex_manager_); // for bt_manager_ - - bt_manager_ = std::make_shared(*this, getBehaviorTreeManagerParam()); - - auto side_shift_module = - std::make_shared("SideShift", *this, side_shift_param_ptr_); - bt_manager_->registerSceneModule(side_shift_module); - - auto avoidance_module = - std::make_shared("Avoidance", *this, avoidance_param_ptr_); - path_candidate_publishers_.emplace( - "Avoidance", create_publisher(path_candidate_name_space + "avoidance", 1)); - bt_manager_->registerSceneModule(avoidance_module); - - auto lane_following_module = std::make_shared("LaneFollowing", *this); - bt_manager_->registerSceneModule(lane_following_module); - - auto ext_request_lane_change_right_module = - std::make_shared( - "ExternalRequestLaneChangeRight", *this, lane_change_param_ptr_); - path_candidate_publishers_.emplace( - "ExternalRequestLaneChangeRight", - create_publisher(path_candidate_name_space + "external_request_lane_change_right", 1)); - bt_manager_->registerSceneModule(ext_request_lane_change_right_module); - - auto ext_request_lane_change_left_module = - std::make_shared( - "ExternalRequestLaneChangeLeft", *this, lane_change_param_ptr_); - path_candidate_publishers_.emplace( - "ExternalRequestLaneChangeLeft", - create_publisher(path_candidate_name_space + "external_request_lane_change_left", 1)); - bt_manager_->registerSceneModule(ext_request_lane_change_left_module); - - auto lane_change_module = - std::make_shared("LaneChange", *this, lane_change_param_ptr_); - path_candidate_publishers_.emplace( - "LaneChange", create_publisher(path_candidate_name_space + "lane_change", 1)); - bt_manager_->registerSceneModule(lane_change_module); - - auto goal_planner = - std::make_shared("GoalPlanner", *this, goal_planner_param_ptr_); - path_candidate_publishers_.emplace( - "GoalPlanner", create_publisher(path_candidate_name_space + "goal_planner", 1)); - bt_manager_->registerSceneModule(goal_planner); - - auto start_planner_module = - std::make_shared("StartPlanner", *this, start_planner_param_ptr_); - path_candidate_publishers_.emplace( - "StartPlanner", create_publisher(path_candidate_name_space + "start_planner", 1)); - bt_manager_->registerSceneModule(start_planner_module); - - bt_manager_->createBehaviorTree(); - } -#else { RCLCPP_INFO(get_logger(), "not use behavior tree."); @@ -308,7 +248,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod planner_manager_->registerSceneModuleManager(manager); } } -#endif // turn signal decider { @@ -335,19 +274,11 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod std::vector BehaviorPathPlannerNode::getWaitingApprovalModules() { -#ifdef USE_OLD_ARCHITECTURE - auto registered_modules_ptr = bt_manager_->getSceneModules(); - std::vector waiting_approval_modules; - for (const auto & module : registered_modules_ptr) { - if (module->isWaitingApproval() == true) { - waiting_approval_modules.push_back(module->name()); -#else auto all_scene_module_ptr = planner_manager_->getSceneModuleStatus(); std::vector waiting_approval_modules; for (const auto & module : all_scene_module_ptr) { if (module->is_waiting_approval == true) { waiting_approval_modules.push_back(module->module_name); -#endif } } return waiting_approval_modules; @@ -1126,17 +1057,6 @@ StartPlannerParameters BehaviorPathPlannerNode::getStartPlannerParam() return p; } -#ifdef USE_OLD_ARCHITECTURE -BehaviorTreeManagerParam BehaviorPathPlannerNode::getBehaviorTreeManagerParam() -{ - BehaviorTreeManagerParam p{}; - p.bt_tree_config_path = declare_parameter("bt_tree_config_path"); - p.groot_zmq_publisher_port = declare_parameter("groot_zmq_publisher_port"); - p.groot_zmq_server_port = declare_parameter("groot_zmq_server_port"); - return p; -} -#endif - // wait until mandatory data is ready bool BehaviorPathPlannerNode::isDataReady() { @@ -1232,9 +1152,7 @@ void BehaviorPathPlannerNode::run() const bool is_first_time = !(planner_data_->route_handler->isHandlerReady()); if (route_ptr) { planner_data_->route_handler->setRoute(*route_ptr); -#ifndef USE_OLD_ARCHITECTURE planner_manager_->resetRootLanelet(planner_data_); -#endif // uuid is not changed when rerouting with modified goal, // in this case do not need to rest modules. @@ -1244,36 +1162,22 @@ void BehaviorPathPlannerNode::run() // so that the each modules do not have to care about the "route jump". if (!is_first_time && !has_same_route_id) { RCLCPP_DEBUG(get_logger(), "new route is received. reset behavior tree."); -#ifdef USE_OLD_ARCHITECTURE - bt_manager_->resetBehaviorTree(); -#else planner_manager_->reset(); -#endif } } -#ifndef USE_OLD_ARCHITECTURE const auto controlled_by_autoware_autonomously = planner_data_->operation_mode->mode == OperationModeState::AUTONOMOUS && planner_data_->operation_mode->is_autoware_control_enabled; if (!controlled_by_autoware_autonomously) { planner_manager_->resetRootLanelet(planner_data_); } -#endif // run behavior planner -#ifdef USE_OLD_ARCHITECTURE - const auto output = bt_manager_->run(planner_data_); -#else const auto output = planner_manager_->run(planner_data_); -#endif // path handling -#ifdef USE_OLD_ARCHITECTURE - const auto path = getPath(output, planner_data_, bt_manager_); -#else const auto path = getPath(output, planner_data_, planner_manager_); -#endif // update planner data planner_data_->prev_output_path = path; @@ -1305,19 +1209,10 @@ void BehaviorPathPlannerNode::run() get_logger(), *get_clock(), 5000, "behavior path output is empty! Stop publish."); } -#ifdef USE_OLD_ARCHITECTURE - publishPathCandidate(bt_manager_->getSceneModules(), planner_data_); - publishSceneModuleDebugMsg(bt_manager_->getAllSceneModuleDebugMsgData()); -#else publishSceneModuleDebugMsg(planner_manager_->getDebugMsg()); publishPathCandidate(planner_manager_->getSceneModuleManagers(), planner_data_); publishPathReference(planner_manager_->getSceneModuleManagers(), planner_data_); stop_reason_publisher_->publish(planner_manager_->getStopReasons()); -#endif - -#ifdef USE_OLD_ARCHITECTURE - lk_manager.unlock(); // release bt_manager_ -#endif if (output.modified_goal) { PoseWithUuidStamped modified_goal = *(output.modified_goal); @@ -1336,12 +1231,10 @@ void BehaviorPathPlannerNode::run() lk_pd.unlock(); // release planner_data_ -#ifndef USE_OLD_ARCHITECTURE planner_manager_->print(); planner_manager_->publishMarker(); planner_manager_->publishVirtualWall(); lk_manager.unlock(); // release planner_manager_ -#endif RCLCPP_DEBUG(get_logger(), "----- behavior path planner end -----\n\n"); } @@ -1518,20 +1411,6 @@ void BehaviorPathPlannerNode::publishSceneModuleDebugMsg( } } -#ifdef USE_OLD_ARCHITECTURE -void BehaviorPathPlannerNode::publishPathCandidate( - const std::vector> & scene_modules, - const std::shared_ptr & planner_data) -{ - for (auto & module : scene_modules) { - if (path_candidate_publishers_.count(module->name()) != 0) { - path_candidate_publishers_.at(module->name()) - ->publish( - convertToPath(module->getPathCandidate(), module->isExecutionReady(), planner_data)); - } - } -} -#else void BehaviorPathPlannerNode::publishPathCandidate( const std::vector> & managers, const std::shared_ptr & planner_data) @@ -1583,7 +1462,6 @@ void BehaviorPathPlannerNode::publishPathReference( } } } -#endif Path BehaviorPathPlannerNode::convertToPath( const std::shared_ptr & path_candidate_ptr, const bool is_ready, @@ -1611,15 +1489,9 @@ Path BehaviorPathPlannerNode::convertToPath( return output; } -#ifdef USE_OLD_ARCHITECTURE -PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath( - const BehaviorModuleOutput & bt_output, const std::shared_ptr & planner_data, - const std::shared_ptr & bt_manager) -#else PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath( const BehaviorModuleOutput & bt_output, const std::shared_ptr & planner_data, const std::shared_ptr & planner_manager) -#endif { // TODO(Horibe) do some error handling when path is not available. @@ -1630,11 +1502,7 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath( get_logger(), "BehaviorTreeManager: output is %s.", bt_output.path ? "FOUND" : "NOT FOUND"); PathWithLaneId connected_path; -#ifdef USE_OLD_ARCHITECTURE - const auto module_status_ptr_vec = bt_manager->getModulesStatus(); -#else const auto module_status_ptr_vec = planner_manager->getSceneModuleStatus(); -#endif const auto resampled_path = utils::resamplePathWithSpline( *path, planner_data->parameters.output_path_interval, keepInputPoints(module_status_ptr_vec)); @@ -1645,11 +1513,7 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath( bool BehaviorPathPlannerNode::keepInputPoints( const std::vector> & statuses) const { -#ifdef USE_OLD_ARCHITECTURE - const std::vector target_modules = {"GoalPlanner", "Avoidance"}; -#else const std::vector target_modules = {"goal_planner", "avoidance"}; -#endif const auto target_status = ModuleStatus::RUNNING; @@ -1745,12 +1609,10 @@ SetParametersResult BehaviorPathPlannerNode::onSetParam( return result; } -#ifndef USE_OLD_ARCHITECTURE { const std::lock_guard lock(mutex_manager_); // for planner_manager_ planner_manager_->updateModuleParams(parameters); } -#endif result.successful = true; result.reason = "success"; diff --git a/planning/behavior_path_planner/src/behavior_tree_manager.cpp b/planning/behavior_path_planner/src/behavior_tree_manager.cpp deleted file mode 100644 index 2e8627b745db8..0000000000000 --- a/planning/behavior_path_planner/src/behavior_tree_manager.cpp +++ /dev/null @@ -1,175 +0,0 @@ -// Copyright 2021 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 "behavior_path_planner/behavior_tree_manager.hpp" - -#include "behavior_path_planner/scene_module/scene_module_bt_node_interface.hpp" -#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/utils.hpp" - -#include -#include -#include -#include -#include - -namespace behavior_path_planner -{ -BehaviorTreeManager::BehaviorTreeManager( - rclcpp::Node & node, const BehaviorTreeManagerParam & param) -: bt_manager_param_(param), - logger_(node.get_logger().get_child("behavior_tree_manager")), - clock_(*node.get_clock()) -{ -} - -void BehaviorTreeManager::createBehaviorTree() -{ - blackboard_ = BT::Blackboard::create(); - try { - bt_tree_ = bt_factory_.createTreeFromFile(bt_manager_param_.bt_tree_config_path, blackboard_); - } catch (...) { - RCLCPP_ERROR( - logger_, "Failed to create BT from: %s", bt_manager_param_.bt_tree_config_path.c_str()); - exit(EXIT_FAILURE); - } - addGrootMonitoring( - &bt_tree_, bt_manager_param_.groot_zmq_publisher_port, bt_manager_param_.groot_zmq_server_port); -} - -void BehaviorTreeManager::registerSceneModule(const std::shared_ptr & module) -{ - const std::string & name = module->name(); - const auto status = std::make_shared(name); - - // simple condition node for "isRequested" - bt_factory_.registerSimpleCondition(name + "_Request", [module, status](BT::TreeNode &) { - return isExecutionRequested(module, status); - }); - - // simple action node for "planCandidate" - auto bt_node = - std::make_shared("", BT::NodeConfiguration{}, module, status); - bt_factory_.registerSimpleAction( - name + "_PlanCandidate", - [bt_node](BT::TreeNode & tree_node) { return bt_node->planCandidate(tree_node); }, - SceneModuleBTNodeInterface::providedPorts()); - - // register builder with default tick functor for "plan" - auto builder = [module, status]( - const std::string & _name, const BT::NodeConfiguration & _config) { - return std::make_unique(_name, _config, module, status); - }; - bt_factory_.registerBuilder(name + "_Plan", builder); - - scene_modules_.push_back(module); - modules_status_.push_back(status); -} - -BehaviorModuleOutput BehaviorTreeManager::run(const std::shared_ptr & data) -{ - current_planner_data_ = data; - - // set planner_data & reset status - std::for_each( - scene_modules_.begin(), scene_modules_.end(), [&data](const auto & m) { m->setData(data); }); - std::for_each(modules_status_.begin(), modules_status_.end(), [](const auto & s) { - *s = SceneModuleStatus{s->module_name}; - }); - - const bool is_any_module_running = std::any_of( - scene_modules_.begin(), scene_modules_.end(), - [](const auto & module) { return module->getCurrentStatus() == BT::NodeStatus::RUNNING; }); - - if ( - !is_any_module_running && - utils::isEgoOutOfRoute( - data->self_odometry->pose.pose, data->prev_modified_goal, data->route_handler)) { - BehaviorModuleOutput output = utils::createGoalAroundPath(data); - return output; - } - - // reset blackboard - blackboard_->set("output", BehaviorModuleOutput{}); - - const auto res = bt_tree_.tickRoot(); - - const auto output = blackboard_->get("output"); - - RCLCPP_DEBUG(logger_, "BehaviorPathPlanner::run end status = %s", BT::toStr(res).c_str()); - - resetNotRunningModulePathCandidate(); - - std::for_each(scene_modules_.begin(), scene_modules_.end(), [](const auto & m) { - m->publishInfoMarker(); - m->publishDebugMarker(); - m->publishStopReasons(); - m->publishVirtualWall(); - if (!m->isExecutionRequested()) { - m->onExit(); - } - m->publishRTCStatus(); - m->publishSteeringFactor(); - }); - return output; -} - -std::vector> -BehaviorTreeManager::getModulesStatus() -{ - return modules_status_; -} - -void BehaviorTreeManager::resetNotRunningModulePathCandidate() -{ - const bool is_any_module_running = std::any_of( - scene_modules_.begin(), scene_modules_.end(), - [](const auto & module) { return module->getCurrentStatus() == BT::NodeStatus::RUNNING; }); - - for (auto & module : scene_modules_) { - if (is_any_module_running && (module->getCurrentStatus() != BT::NodeStatus::RUNNING)) { - module->resetPathCandidate(); - } - } -} - -void BehaviorTreeManager::resetBehaviorTree() -{ - bt_tree_.haltTree(); -} - -void BehaviorTreeManager::addGrootMonitoring( - BT::Tree * tree, uint16_t publisher_port, uint16_t server_port, uint16_t max_msg_per_second) -{ - groot_monitor_ = - std::make_unique(*tree, max_msg_per_second, publisher_port, server_port); -} - -void BehaviorTreeManager::resetGrootMonitor() -{ - if (groot_monitor_) { - groot_monitor_.reset(); - } -} - -std::shared_ptr BehaviorTreeManager::getAllSceneModuleDebugMsgData() -{ - scene_module_visitor_ptr_ = std::make_shared(); - for (const auto & module : scene_modules_) { - module->acceptVisitor(scene_module_visitor_ptr_); - } - return scene_module_visitor_ptr_; -} -} // namespace behavior_path_planner 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 91f1c23c3008d..587afb1fdee57 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 @@ -96,20 +96,12 @@ bool isDrivingSameLane( } } // namespace -#ifdef USE_OLD_ARCHITECTURE -AvoidanceModule::AvoidanceModule( - const std::string & name, rclcpp::Node & node, std::shared_ptr parameters) -: SceneModuleInterface{name, node, createRTCInterfaceMap(node, name, {"left", "right"})}, - parameters_{parameters}, - helper_{parameters} -#else AvoidanceModule::AvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{parameters}, helper_{parameters} -#endif { } @@ -122,26 +114,11 @@ bool AvoidanceModule::isExecutionRequested() const } // Check ego is in preferred lane -#ifdef USE_OLD_ARCHITECTURE - const auto avoid_data = calcAvoidancePlanningData(debug_data_); - - const auto current_lanes = utils::getCurrentLanes(planner_data_); - lanelet::ConstLanelet current_lane; - lanelet::utils::query::getClosestLanelet( - current_lanes, planner_data_->self_odometry->pose.pose, ¤t_lane); - const auto num = planner_data_->route_handler->getNumLaneToPreferredLane(current_lane); - - if (num != 0) { - return false; - } -#else const auto avoid_data = avoidance_data_; -#endif updateInfoMarker(avoid_data); updateDebugMarker(avoid_data, path_shifter_, debug_data_); -#ifndef USE_OLD_ARCHITECTURE // there is object that should be avoid. return true. if (!!avoid_data.stop_target_object) { return true; @@ -150,7 +127,6 @@ bool AvoidanceModule::isExecutionRequested() const if (avoid_data.unapproved_new_sl.empty()) { return false; } -#endif return !avoid_data.target_objects.empty(); } @@ -201,14 +177,10 @@ ModuleStatus AvoidanceModule::updateState() helper_.setPreviousDrivingLanes(data.current_lanelets); -#ifdef USE_OLD_ARCHITECTURE - return ModuleStatus::RUNNING; -#else if (is_plan_running || current_state_ == ModuleStatus::RUNNING) { return ModuleStatus::RUNNING; } return ModuleStatus::IDLE; -#endif } bool AvoidanceModule::isAvoidancePlanRunning() const @@ -253,14 +225,9 @@ AvoidancePlanningData AvoidanceModule::calcAvoidancePlanningData(DebugData & deb }(); // center line path (output of this function must have size > 1) -#ifdef USE_OLD_ARCHITECTURE - const auto center_path = - utils::calcCenterLinePath(planner_data_, reference_pose, longest_dist_to_shift_line); -#else const auto center_path = utils::calcCenterLinePath( planner_data_, reference_pose, longest_dist_to_shift_line, *getPreviousModuleOutput().reference_path); -#endif debug.center_line = center_path; if (center_path.points.size() < 2) { @@ -270,11 +237,7 @@ AvoidancePlanningData AvoidanceModule::calcAvoidancePlanningData(DebugData & deb } // reference path -#ifdef USE_OLD_ARCHITECTURE - data.reference_path_rough = center_path; -#else data.reference_path_rough = extendBackwardLength(*getPreviousModuleOutput().path); -#endif data.reference_path = utils::resamplePathWithSpline( data.reference_path_rough, parameters_->resample_interval_for_planning); @@ -295,14 +258,8 @@ AvoidancePlanningData AvoidanceModule::calcAvoidancePlanningData(DebugData & deb calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0)); // lanelet info -#ifdef USE_OLD_ARCHITECTURE - data.current_lanelets = utils::calcLaneAroundPose( - planner_data_->route_handler, reference_pose, planner_data_->parameters.forward_path_length, - planner_data_->parameters.backward_path_length); -#else data.current_lanelets = utils::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_); -#endif // keep avoidance state data.state = avoidance_data_.state; @@ -2676,11 +2633,9 @@ BehaviorModuleOutput AvoidanceModule::planWaitingApproval() // we can execute the plan() since it handles the approval appropriately. BehaviorModuleOutput out = plan(); -#ifndef USE_OLD_ARCHITECTURE if (path_shifter_.getShiftLines().empty()) { out.turn_signal_info = getPreviousModuleOutput().turn_signal_info; } -#endif const auto all_unavoidable = std::all_of( data.target_objects.begin(), data.target_objects.end(), @@ -2932,7 +2887,6 @@ void AvoidanceModule::updateData() helper_.setData(planner_data_); -#ifndef USE_OLD_ARCHITECTURE if (!helper_.isInitialized()) { helper_.setPreviousSplineShiftPath(toShiftedPath(*getPreviousModuleOutput().path)); helper_.setPreviousLinearShiftPath(toShiftedPath(*getPreviousModuleOutput().path)); @@ -2940,7 +2894,6 @@ void AvoidanceModule::updateData() helper_.setPreviousDrivingLanes( utils::getCurrentLanesFromPath(*getPreviousModuleOutput().reference_path, planner_data_)); } -#endif debug_data_ = DebugData(); avoidance_data_ = calcAvoidancePlanningData(debug_data_); @@ -2959,15 +2912,6 @@ void AvoidanceModule::updateData() // update registered shift point for new reference path & remove past objects updateRegisteredRawShiftLines(); -#ifdef USE_OLD_ARCHITECTURE - if (!helper_.isInitialized()) { - helper_.setPreviousSplineShiftPath(toShiftedPath(avoidance_data_.reference_path)); - helper_.setPreviousLinearShiftPath(toShiftedPath(avoidance_data_.reference_path)); - helper_.setPreviousReferencePath(avoidance_data_.reference_path); - helper_.setPreviousDrivingLanes(avoidance_data_.current_lanelets); - } -#endif - fillShiftLine(avoidance_data_, debug_data_); fillEgoStatus(avoidance_data_, debug_data_); fillDebugData(avoidance_data_, debug_data_); 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 a8a7f89c54021..262fbb55301ba 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 @@ -145,19 +145,11 @@ std::pair projectObstacleVelocityToTrajectory( } } // namespace -#ifdef USE_OLD_ARCHITECTURE -DynamicAvoidanceModule::DynamicAvoidanceModule( - const std::string & name, rclcpp::Node & node, - std::shared_ptr parameters) -: SceneModuleInterface{name, node, createRTCInterfaceMap(node, name, {""})}, - parameters_{std::move(parameters)} -#else DynamicAvoidanceModule::DynamicAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{std::move(parameters)} -#endif { } @@ -216,12 +208,6 @@ ModuleStatus DynamicAvoidanceModule::updateState() return ModuleStatus::SUCCESS; } -#ifndef USE_OLD_ARCHITECTURE - if (!isActivated() || isWaitingApproval()) { - return ModuleStatus::IDLE; - } -#endif - return ModuleStatus::RUNNING; } 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 09eeb0697c698..c7725b0ccf0f0 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 @@ -47,20 +47,12 @@ using tier4_autoware_utils::inverseTransformPose; namespace behavior_path_planner { -#ifdef USE_OLD_ARCHITECTURE -GoalPlannerModule::GoalPlannerModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters) -: SceneModuleInterface{name, node, createRTCInterfaceMap(node, name, {""})}, parameters_{parameters} -{ -#else 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} { -#endif LaneDepartureChecker lane_departure_checker{}; lane_departure_checker.setVehicleInfo(vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()); @@ -232,11 +224,9 @@ BehaviorModuleOutput GoalPlannerModule::run() current_state_ = ModuleStatus::RUNNING; updateOccupancyGrid(); -#ifndef USE_OLD_ARCHITECTURE if (!isActivated()) { return planWaitingApproval(); } -#endif return plan(); } @@ -490,22 +480,12 @@ 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. -#ifdef USE_OLD_ARCHITECTURE - // initialize when receiving new route - if (!last_received_time_ || *last_received_time_ != route_handler->getRouteHeader().stamp) { - // this process causes twice reset when receiving first route. - resetStatus(); - } - last_received_time_ = std::make_unique(route_handler->getRouteHeader().stamp); - -#else + // 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()) { return; } -#endif // calculate goal candidates const Pose goal_pose = route_handler->getGoalPose(); 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 26051c4d78f3e..ab2c87c7e1ff9 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 @@ -82,22 +82,14 @@ ModuleStatus LaneChangeInterface::updateState() } if (!module_type_->isValidPath()) { -#ifdef USE_OLD_ARCHITECTURE - return ModuleStatus::FAILURE; -#else return ModuleStatus::RUNNING; -#endif } if (module_type_->isAbortState()) { -#ifdef USE_OLD_ARCHITECTURE - return module_type_->hasFinishedAbort() ? ModuleStatus::FAILURE : ModuleStatus::RUNNING; -#else if (module_type_->hasFinishedAbort()) { resetLaneChangeModule(); } return ModuleStatus::RUNNING; -#endif } if (module_type_->hasFinishedLaneChange()) { @@ -153,14 +145,10 @@ ModuleStatus LaneChangeInterface::updateState() getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, "Lane change path is unsafe. Cancel lane change."); module_type_->toCancelState(); -#ifdef USE_OLD_ARCHITECTURE - return isWaitingApproval() ? ModuleStatus::RUNNING : ModuleStatus::FAILURE; -#else if (!isWaitingApproval()) { resetLaneChangeModule(); } return ModuleStatus::RUNNING; -#endif } if (!module_type_->isAbortEnabled()) { diff --git a/planning/behavior_path_planner/src/scene_module/lane_following/lane_following_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_following/lane_following_module.cpp deleted file mode 100644 index 2c0985251b845..0000000000000 --- a/planning/behavior_path_planner/src/scene_module/lane_following/lane_following_module.cpp +++ /dev/null @@ -1,94 +0,0 @@ -// Copyright 2021-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 "behavior_path_planner/scene_module/lane_following/lane_following_module.hpp" - -#include "behavior_path_planner/utils/path_utils.hpp" -#include "behavior_path_planner/utils/utils.hpp" - -#include - -#include -#include - -namespace behavior_path_planner -{ -LaneFollowingModule::LaneFollowingModule(const std::string & name, rclcpp::Node & node) -// RTCInterface is temporarily registered, but not used. -: SceneModuleInterface{name, node, {}} -{ - initParam(); -} - -void LaneFollowingModule::initParam() -{ - clearWaitingApproval(); // no need approval -} - -bool LaneFollowingModule::isExecutionRequested() const -{ - return true; -} - -bool LaneFollowingModule::isExecutionReady() const -{ - return true; -} - -BT::NodeStatus LaneFollowingModule::updateState() -{ - return BT::NodeStatus::SUCCESS; -} - -BehaviorModuleOutput LaneFollowingModule::plan() -{ - return getReferencePath(); -} -CandidateOutput LaneFollowingModule::planCandidate() const -{ - const auto path = getReferencePath().path; - if (!path) { - return {}; - } - return CandidateOutput(*path); -} -void LaneFollowingModule::processOnEntry() -{ - initParam(); - current_state_ = BT::NodeStatus::RUNNING; -} -void LaneFollowingModule::processOnExit() -{ - initParam(); - current_state_ = BT::NodeStatus::SUCCESS; -} - -BehaviorModuleOutput LaneFollowingModule::getReferencePath() const -{ - const auto & route_handler = planner_data_->route_handler; - const auto current_pose = planner_data_->self_odometry->pose.pose; - const double dist_threshold = planner_data_->parameters.ego_nearest_dist_threshold; - const double yaw_threshold = planner_data_->parameters.ego_nearest_yaw_threshold; - - lanelet::ConstLanelet current_lane; - if (!route_handler->getClosestLaneletWithConstrainsWithinRoute( - current_pose, ¤t_lane, dist_threshold, yaw_threshold)) { - RCLCPP_ERROR_THROTTLE( - getLogger(), *clock_, 5000, "failed to find closest lanelet within route!!!"); - return {}; // TODO(Horibe) - } - - return utils::getReferencePath(current_lane, planner_data_); -} -} // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/scene_module_bt_node_interface.cpp b/planning/behavior_path_planner/src/scene_module/scene_module_bt_node_interface.cpp deleted file mode 100644 index 855e099c1ce21..0000000000000 --- a/planning/behavior_path_planner/src/scene_module/scene_module_bt_node_interface.cpp +++ /dev/null @@ -1,138 +0,0 @@ -// Copyright 2021 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 "behavior_path_planner/scene_module/scene_module_bt_node_interface.hpp" - -#include -#include - -namespace behavior_path_planner -{ -BT::NodeStatus isExecutionRequested( - const std::shared_ptr p, - const std::shared_ptr & status) -{ - const auto ret = p->isExecutionRequested(); - status->is_requested = ret; - RCLCPP_DEBUG_STREAM(p->getLogger(), "name = " << p->name() << ", result = " << ret); - return ret ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE; -} - -SceneModuleBTNodeInterface::SceneModuleBTNodeInterface( - const std::string & name, const BT::NodeConfiguration & config, - const std::shared_ptr & scene_module, - const std::shared_ptr & module_status) -: BT::CoroActionNode(name, config), scene_module_(scene_module), module_status_(module_status) -{ -} - -BT::NodeStatus SceneModuleBTNodeInterface::tick() -{ - RCLCPP_DEBUG_STREAM( - scene_module_->getLogger(), "bt::tick is called. module name: " << scene_module_->name()); - auto current_status = BT::NodeStatus::RUNNING; - - scene_module_->onEntry(); - module_status_->is_waiting_approval = scene_module_->isWaitingApproval(); - module_status_->is_execution_ready = scene_module_->isExecutionReady(); - - const bool is_lane_following = scene_module_->name() == "LaneFollowing"; - - const bool is_waiting_approval = !scene_module_->isActivated(); - if (is_waiting_approval && !is_lane_following) { - scene_module_->lockRTCCommand(); - try { - // NOTE: Since BehaviorTreeCpp has an issue to shadow the exception reason thrown - // in the TreeNode, catch and display it here until the issue is fixed. - scene_module_->updateData(); - auto res = setOutput("output", scene_module_->planWaitingApproval()); - if (!res) { - RCLCPP_ERROR_STREAM(scene_module_->getLogger(), "setOutput() failed : " << res.error()); - } - module_status_->is_waiting_approval = scene_module_->isWaitingApproval(); - module_status_->is_execution_ready = scene_module_->isExecutionReady(); - } catch (const std::exception & e) { - RCLCPP_ERROR_STREAM( - scene_module_->getLogger(), "behavior module has failed with exception: " << e.what()); - // std::exit(EXIT_FAILURE); // TODO(Horibe) do appropriate handing - } - scene_module_->unlockRTCCommand(); - return scene_module_->getNodeStatusWhileWaitingApproval(); - } - - while (rclcpp::ok()) { - // NOTE: Since BehaviorTreeCpp has an issue to shadow the exception reason thrown - // in the TreeNode, catch and display it here until the issue is fixed. - scene_module_->lockRTCCommand(); - try { - auto res = setOutput("output", scene_module_->run()); - if (!res) { - RCLCPP_ERROR_STREAM(scene_module_->getLogger(), "setOutput() failed : " << res.error()); - } - - scene_module_->updateCurrentState(); - current_status = scene_module_->getCurrentStatus(); - - // for data output - module_status_->status = current_status; - module_status_->is_waiting_approval = scene_module_->isWaitingApproval(); - module_status_->is_execution_ready = scene_module_->isExecutionReady(); - } catch (const std::exception & e) { - RCLCPP_ERROR_STREAM( - scene_module_->getLogger(), "behavior module has failed with exception: " << e.what()); - // std::exit(EXIT_FAILURE); // TODO(Horibe) do appropriate handing - } - - RCLCPP_DEBUG_STREAM( - scene_module_->getLogger(), "on tick: current status = " << BT::toStr(current_status)); - if (current_status != BT::NodeStatus::RUNNING) { - RCLCPP_DEBUG(scene_module_->getLogger(), "on tick: module ended."); - break; - } - - scene_module_->unlockRTCCommand(); - setStatusRunningAndYield(); - } - - scene_module_->onExit(); - RCLCPP_DEBUG_STREAM( - scene_module_->getLogger(), "on tick: return current status = " << BT::toStr(current_status)); - - return current_status; -} - -void SceneModuleBTNodeInterface::halt() -{ - scene_module_->onExit(); - BT::CoroActionNode::halt(); -} - -BT::NodeStatus SceneModuleBTNodeInterface::planCandidate(BT::TreeNode & self) -{ - RCLCPP_DEBUG_STREAM( - scene_module_->getLogger(), "bt::planCandidate module name: " << scene_module_->name()); - auto res = self.setOutput("output", scene_module_->planWaitingApproval()); - if (!res) { - RCLCPP_ERROR_STREAM(scene_module_->getLogger(), "setOutput() failed : " << res.error()); - } - - return BT::NodeStatus::SUCCESS; -} - -BT::PortsList SceneModuleBTNodeInterface::providedPorts() -{ - return {BT::OutputPort("output", "desc")}; -} - -} // namespace behavior_path_planner 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 fe2a03460b013..d235cd1866181 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 @@ -35,23 +35,12 @@ using tier4_autoware_utils::calcDistance2d; using tier4_autoware_utils::calcOffsetPose; using tier4_autoware_utils::getPoint; -#ifdef USE_OLD_ARCHITECTURE -SideShiftModule::SideShiftModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters) -: SceneModuleInterface{name, node, {}}, parameters_{parameters} -{ - using std::placeholders::_1; - lateral_offset_subscriber_ = node.create_subscription( - "~/input/lateral_offset", 1, std::bind(&SideShiftModule::onLateralOffset, this, _1)); -#else SideShiftModule::SideShiftModule( 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} { -#endif // If lateral offset is subscribed, it approves side shift module automatically clearWaitingApproval(); } @@ -186,7 +175,6 @@ ModuleStatus SideShiftModule::updateState() void SideShiftModule::updateData() { -#ifndef USE_OLD_ARCHITECTURE if ( planner_data_->lateral_offset != nullptr && planner_data_->lateral_offset->stamp != latest_lateral_offset_stamp_) { @@ -196,7 +184,6 @@ void SideShiftModule::updateData() latest_lateral_offset_stamp_ = planner_data_->lateral_offset->stamp; } } -#endif if (current_state_ != ModuleStatus::RUNNING) { return; @@ -214,10 +201,6 @@ void SideShiftModule::updateData() const auto reference_pose = prev_output_.shift_length.empty() ? planner_data_->self_odometry->pose.pose : utils::getUnshiftedEgoPose(getEgoPose(), prev_output_); -#ifdef USE_OLD_ARCHITECTURE - const auto centerline_path = - utils::calcCenterLinePath(planner_data_, reference_pose, longest_dist_to_shift_line); -#else if (prev_reference_.points.empty()) { prev_reference_ = *getPreviousModuleOutput().path; } @@ -227,15 +210,10 @@ void SideShiftModule::updateData() const auto centerline_path = utils::calcCenterLinePath( planner_data_, reference_pose, longest_dist_to_shift_line, *getPreviousModuleOutput().reference_path); -#endif constexpr double resample_interval = 1.0; -#ifdef USE_OLD_ARCHITECTURE - reference_path_ = utils::resamplePathWithSpline(centerline_path, resample_interval); -#else const auto backward_extened_path = extendBackwardLength(*getPreviousModuleOutput().path); reference_path_ = utils::resamplePathWithSpline(backward_extened_path, resample_interval); -#endif path_shifter_.setPath(reference_path_); @@ -359,32 +337,6 @@ BehaviorModuleOutput SideShiftModule::planWaitingApproval() return output; } -#ifdef USE_OLD_ARCHITECTURE -void SideShiftModule::onLateralOffset(const LateralOffset::ConstSharedPtr lateral_offset_msg) -{ - const double new_lateral_offset = lateral_offset_msg->lateral_offset; - - RCLCPP_DEBUG( - getLogger(), "onLateralOffset start : lateral offset current = %f, new = &%f", - requested_lateral_offset_, new_lateral_offset); - - // offset is not changed. - if (std::abs(inserted_lateral_offset_ - new_lateral_offset) < 1e-4) { - return; - } - - if (parameters_->shift_request_time_limit < parameters_->time_to_start_shifting) { - RCLCPP_DEBUG( - getLogger(), "Shift request time might be too low. Generated trajectory might be wavy"); - } - // new offset is requested. - if (isReadyForNextRequest(parameters_->shift_request_time_limit)) { - lateral_offset_change_request_ = true; - requested_lateral_offset_ = new_lateral_offset; - } -} -#endif - ShiftLine SideShiftModule::calcShiftLine() const { const auto & p = parameters_; 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 b2cf74893666b..533076be8012a 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 @@ -36,30 +36,6 @@ using tier4_autoware_utils::inverseTransformPoint; namespace behavior_path_planner { -#ifdef USE_OLD_ARCHITECTURE -StartPlannerModule::StartPlannerModule( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters) -: SceneModuleInterface{name, node, createRTCInterfaceMap(node, name, {""})}, - parameters_{parameters}, - vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()} -{ - lane_departure_checker_ = std::make_shared(); - lane_departure_checker_->setVehicleInfo(vehicle_info_); - - // set enabled planner - if (parameters_->enable_shift_pull_out) { - start_planner_planners_.push_back( - std::make_shared(node, *parameters, lane_departure_checker_)); - } - if (parameters_->enable_geometric_pull_out) { - start_planner_planners_.push_back(std::make_shared(node, *parameters)); - } - if (start_planner_planners_.empty()) { - RCLCPP_ERROR(getLogger(), "Not found enabled planner"); - } -} -#else StartPlannerModule::StartPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, @@ -83,19 +59,12 @@ StartPlannerModule::StartPlannerModule( RCLCPP_ERROR(getLogger(), "Not found enabled planner"); } } -#endif BehaviorModuleOutput StartPlannerModule::run() { -#ifdef USE_OLD_ARCHITECTURE - current_state_ = ModuleStatus::RUNNING; -#endif - -#ifndef USE_OLD_ARCHITECTURE if (!isActivated()) { return planWaitingApproval(); } -#endif return plan(); } @@ -115,9 +84,6 @@ bool StartPlannerModule::isExecutionRequested() const if ( tier4_autoware_utils::calcDistance2d(goal_pose.position, current_pose.position) < parameters_->th_arrived_distance) { -#ifdef USE_OLD_ARCHITECTURE - is_executed_ = false; -#endif return false; } @@ -125,29 +91,17 @@ bool StartPlannerModule::isExecutionRequested() const !planner_data_->prev_route_id || *planner_data_->prev_route_id != planner_data_->route_handler->getRouteUuid(); -#ifdef USE_OLD_ARCHITECTURE - if (is_executed_) { - return true; - } -#endif - if (current_state_ == ModuleStatus::RUNNING) { return true; } if (!has_received_new_route_) { -#ifdef USE_OLD_ARCHITECTURE - is_executed_ = false; -#endif return false; } const bool is_stopped = utils::l2Norm(planner_data_->self_odometry->twist.twist.linear) < parameters_->th_stopped_velocity; if (!is_stopped) { -#ifdef USE_OLD_ARCHITECTURE - is_executed_ = false; -#endif return false; } @@ -163,15 +117,9 @@ bool StartPlannerModule::isExecutionRequested() const auto lanes = current_lanes; lanes.insert(lanes.end(), pull_out_lanes.begin(), pull_out_lanes.end()); if (LaneDepartureChecker::isOutOfLane(lanes, vehicle_footprint)) { -#ifdef USE_OLD_ARCHITECTURE - is_executed_ = false; -#endif return false; } -#ifdef USE_OLD_ARCHITECTURE - is_executed_ = true; -#endif return true; } @@ -184,17 +132,11 @@ ModuleStatus StartPlannerModule::updateState() { RCLCPP_DEBUG(getLogger(), "START_PLANNER updateState"); -#ifdef USE_OLD_ARCHITECTURE - if (isActivated() && !isWaitingApproval()) { - current_state_ = ModuleStatus::RUNNING; - } -#else if (isActivated() && !isWaitingApproval()) { current_state_ = ModuleStatus::RUNNING; } else { current_state_ = ModuleStatus::IDLE; } -#endif if (hasFinishedPullOut()) { return ModuleStatus::SUCCESS; @@ -729,10 +671,6 @@ bool StartPlannerModule::hasFinishedPullOut() const const bool has_finished = arclength_current.length - arclength_pull_out_end.length > 0.0; -#ifdef USE_OLD_ARCHITECTURE - is_executed_ = !has_finished; -#endif - return has_finished; } 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 085f72b59d31e..5d77027efa5d0 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 @@ -30,19 +30,8 @@ BehaviorModuleOutput DefaultFixedGoalPlanner::plan( const std::shared_ptr & planner_data) const { BehaviorModuleOutput output = -#ifdef USE_OLD_ARCHITECTURE - // generate reference path in this planner - std::invoke([this, &planner_data]() { - auto path = getReferencePath(planner_data); - if (!path) { - return BehaviorModuleOutput{}; - } - return *path; - }); -#else // use planner previous module reference path getPreviousModuleOutput(); -#endif const PathWithLaneId smoothed_path = modifyPathForSmoothGoalConnection(*(output.path), planner_data); output.path = std::make_shared(smoothed_path); @@ -50,29 +39,6 @@ BehaviorModuleOutput DefaultFixedGoalPlanner::plan( return output; } -#ifdef USE_OLD_ARCHITECTURE -boost::optional DefaultFixedGoalPlanner::getReferencePath( - const std::shared_ptr & planner_data) const -{ - const auto & route_handler = planner_data->route_handler; - const auto current_pose = planner_data->self_odometry->pose.pose; - const double dist_threshold = planner_data->parameters.ego_nearest_dist_threshold; - const double yaw_threshold = planner_data->parameters.ego_nearest_yaw_threshold; - - lanelet::ConstLanelet current_lane{}; - if (route_handler->getClosestLaneletWithConstrainsWithinRoute( - current_pose, ¤t_lane, dist_threshold, yaw_threshold)) { - return utils::getReferencePath(current_lane, planner_data); - } - - if (route_handler->getClosestLaneletWithinRoute(current_pose, ¤t_lane)) { - return utils::getReferencePath(current_lane, planner_data); - } - - return {}; // something wrong -} -#endif - PathWithLaneId DefaultFixedGoalPlanner::modifyPathForSmoothGoalConnection( const PathWithLaneId & path, const std::shared_ptr & planner_data) const { diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index fabf857aa0b40..708f4b6f4823f 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -2409,25 +2409,6 @@ PathWithLaneId getCenterLinePath( const double s_backward = std::max(0., s - backward_path_length); double s_forward = s + forward_path_length; -#ifdef USE_OLD_ARCHITECTURE - const double lane_length = lanelet::utils::getLaneletLength2d(lanelet_sequence); - const auto shift_intervals = - route_handler.getLateralIntervalsToPreferredLane(lanelet_sequence.back()); - const double lane_change_buffer = - utils::calcMinimumLaneChangeLength(parameter, shift_intervals, 0.0); - - if (route_handler.isDeadEndLanelet(lanelet_sequence.back())) { - const double forward_length = std::max(lane_length - lane_change_buffer, 0.0); - s_forward = std::min(s_forward, forward_length); - } - - if (route_handler.isInGoalRouteSection(lanelet_sequence.back())) { - const auto goal_arc_coordinates = - lanelet::utils::getArcCoordinates(lanelet_sequence, route_handler.getGoalPose()); - const double forward_length = std::max(goal_arc_coordinates.length - lane_change_buffer, 0.0); - s_forward = std::min(s_forward, forward_length); - } -#else if (route_handler.isDeadEndLanelet(lanelet_sequence.back())) { const auto lane_length = lanelet::utils::getLaneletLength2d(lanelet_sequence); s_forward = std::clamp(s_forward, 0.0, lane_length); @@ -2438,7 +2419,6 @@ PathWithLaneId getCenterLinePath( lanelet::utils::getArcCoordinates(lanelet_sequence, route_handler.getGoalPose()); s_forward = std::clamp(s_forward, 0.0, goal_arc_coordinates.length); } -#endif const auto raw_path_with_lane_id = route_handler.getCenterLinePath(lanelet_sequence, s_backward, s_forward, true); @@ -2904,10 +2884,8 @@ DrivableAreaInfo combineDrivableAreaInfo( DrivableAreaInfo combined_drivable_area_info; // drivable lanes -#ifndef USE_OLD_ARCHITECTURE combined_drivable_area_info.drivable_lanes = combineDrivableLanes(drivable_area_info1.drivable_lanes, drivable_area_info2.drivable_lanes); -#endif // obstacles for (const auto & obstacle : drivable_area_info1.obstacles) { From ac29eb5df8191ebad303094d8a6d757054eca513 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 29 Jun 2023 11:08:24 +0900 Subject: [PATCH 049/118] fix(start_planner): fix path cut by U turn goal (#4109) * fix(start_planner): fix path cut by U turn goal Signed-off-by: kosuke55 * cut path Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../start_planner/start_planner_module.cpp | 19 ++++++++++++++--- .../start_planner/geometric_pull_out.cpp | 6 +++++- .../utils/start_planner/shift_pull_out.cpp | 21 ++++++++++++------- 3 files changed, 34 insertions(+), 12 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 533076be8012a..e9e28b8e62f9b 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 @@ -112,7 +112,12 @@ bool StartPlannerModule::isExecutionRequested() const tier4_autoware_utils::pose2transform(planner_data_->self_odometry->pose.pose)); // Check if ego is not out of lanes - const auto current_lanes = utils::getExtendedCurrentLanes(planner_data_); + // const auto current_lanes = utils::getExtendedCurrentLanes(planner_data_); + const double backward_path_length = + planner_data_->parameters.backward_path_length + parameters_->max_back_distance; + const auto current_lanes = + utils::getCurrentLanes(planner_data_, backward_path_length, std::numeric_limits::max()); + const auto pull_out_lanes = start_planner_utils::getPullOutLanes(planner_data_); auto lanes = current_lanes; lanes.insert(lanes.end(), pull_out_lanes.begin(), pull_out_lanes.end()); @@ -305,7 +310,12 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() return output; } - const auto current_lanes = utils::getExtendedCurrentLanes(planner_data_); + // const auto current_lanes = utils::getExtendedCurrentLanes(planner_data_); + const double backward_path_length = + planner_data_->parameters.backward_path_length + parameters_->max_back_distance; + const auto current_lanes = + utils::getCurrentLanes(planner_data_, backward_path_length, std::numeric_limits::max()); + const auto pull_out_lanes = start_planner_utils::getPullOutLanes(planner_data_); auto stop_path = status_.back_finished ? getCurrentPath() : status_.backward_path; const auto drivable_lanes = @@ -542,7 +552,10 @@ void StartPlannerModule::updatePullOutStatus() const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto & goal_pose = planner_data_->route_handler->getGoalPose(); - status_.current_lanes = utils::getExtendedCurrentLanes(planner_data_); + const double backward_path_length = + planner_data_->parameters.backward_path_length + parameters_->max_back_distance; + status_.current_lanes = + utils::getCurrentLanes(planner_data_, backward_path_length, std::numeric_limits::max()); status_.pull_out_lanes = start_planner_utils::getPullOutLanes(planner_data_); // combine road and shoulder lanes diff --git a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp index 261a297f859bf..e4f0e13953924 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp @@ -40,7 +40,11 @@ boost::optional GeometricPullOut::plan(Pose start_pose, Pose goal_p PullOutPath output; // combine road lane and shoulder lane - const auto road_lanes = utils::getExtendedCurrentLanes(planner_data_); + const double backward_path_length = + planner_data_->parameters.backward_path_length + parameters_.max_back_distance; + const auto road_lanes = + utils::getCurrentLanes(planner_data_, backward_path_length, std::numeric_limits::max()); + const auto shoulder_lanes = getPullOutLanes(planner_data_); auto lanes = road_lanes; lanes.insert(lanes.end(), shoulder_lanes.begin(), shoulder_lanes.end()); diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp index 7d8448802b847..b11bb7731b826 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp @@ -44,12 +44,16 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) const auto & route_handler = planner_data_->route_handler; const auto & common_parameters = planner_data_->parameters; const auto & dynamic_objects = planner_data_->dynamic_object; - const auto & road_lanes = utils::getExtendedCurrentLanes(planner_data_); - const auto & shoulder_lanes = getPullOutLanes(planner_data_); + const auto shoulder_lanes = getPullOutLanes(planner_data_); if (shoulder_lanes.empty()) { return boost::none; } + const double backward_path_length = + planner_data_->parameters.backward_path_length + parameters_.max_back_distance; + const auto road_lanes = + utils::getCurrentLanes(planner_data_, backward_path_length, std::numeric_limits::max()); + // find candidate paths auto pull_out_paths = calcPullOutPaths( *route_handler, road_lanes, shoulder_lanes, start_pose, goal_pose, common_parameters, @@ -135,6 +139,7 @@ std::vector ShiftPullOut::calcPullOutPaths( } // rename parameter + const double forward_path_length = common_parameter.forward_path_length; const double backward_path_length = common_parameter.backward_path_length; const double minimum_shift_pull_out_distance = parameter.minimum_shift_pull_out_distance; const double lateral_jerk = parameter.lateral_jerk; @@ -150,13 +155,13 @@ std::vector ShiftPullOut::calcPullOutPaths( const auto arc_position_start = getArcCoordinates(road_lanes, start_pose); const double s_start = std::max(arc_position_start.length - backward_path_length, 0.0); const auto arc_position_goal = getArcCoordinates(road_lanes, goal_pose); - const double road_lanes_length = std::accumulate( - road_lanes.begin(), road_lanes.end(), 0.0, [](const double sum, const auto & lane) { - return sum + lanelet::utils::getLaneletLength2d(lane); - }); - // if goal is behind start pose, + + // if goal is behind start pose, use path with forward_path_length const bool goal_is_behind = arc_position_goal.length < s_start; - const double s_end = goal_is_behind ? road_lanes_length : arc_position_goal.length; + const double s_forward_length = s_start + forward_path_length; + const double s_end = + goal_is_behind ? s_forward_length : std::min(arc_position_goal.length, s_forward_length); + constexpr double RESAMPLE_INTERVAL = 1.0; PathWithLaneId road_lane_reference_path = utils::resamplePathWithSpline( route_handler.getCenterLinePath(road_lanes, s_start, s_end), RESAMPLE_INTERVAL); From 5bc699b535e94c167e088597ddd58df48eae8fbc Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 29 Jun 2023 12:47:18 +0900 Subject: [PATCH 050/118] fix(lane_change): safety check chattering (#4105) * fix(lane_change): safety check chattering Signed-off-by: Takamasa Horibe * remove unused default value Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../lane_change/lane_change_module_data.hpp | 5 ++++ .../utils/lane_change/lane_change_path.hpp | 9 ++++--- .../utils/lane_change/utils.hpp | 12 ++++----- .../src/scene_module/lane_change/normal.cpp | 27 +++++++++++-------- .../src/utils/lane_change/utils.cpp | 12 ++++----- 5 files changed, 39 insertions(+), 26 deletions(-) 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 67a23f23d5827..006040d8eaa4a 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 @@ -94,6 +94,11 @@ struct LaneChangePhaseInfo double lane_changing{0.0}; [[nodiscard]] double sum() const { return prepare + lane_changing; } + + LaneChangePhaseInfo(const double _prepare, const double _lane_changing) + : prepare(_prepare), lane_changing(_lane_changing) + { + } }; struct LaneChangeTargetObjectIndices diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp index 41c2b62ba31e5..7e78ab9045c64 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp @@ -36,9 +36,12 @@ struct LaneChangePath Pose lane_changing_end{}; ShiftedPath shifted_path{}; ShiftLine shift_line{}; - double acceleration{0.0}; - LaneChangePhaseInfo length{}; - LaneChangePhaseInfo duration{}; + + // longitudinal acceleration applied on the prepare and lane-changing phase + LaneChangePhaseInfo longitudinal_acceleration{0.0, 0.0}; + + LaneChangePhaseInfo length{0.0, 0.0}; + LaneChangePhaseInfo duration{0.0, 0.0}; PathWithLaneId prev_path{}; }; using LaneChangePaths = std::vector; 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 9570ffec56576..872520b4b81e2 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 @@ -90,10 +90,10 @@ std::optional constructCandidatePath( const PathWithLaneId & prepare_segment, const PathWithLaneId & target_segment, const PathWithLaneId & target_lane_reference_path, const ShiftLine & shift_line, const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, - const std::vector> & sorted_lane_ids, const double longitudinal_acceleration, - const double lateral_acceleration, const LaneChangePhaseInfo lane_change_length, - const LaneChangePhaseInfo lane_change_velocity, const double terminal_lane_changing_velocity, - const LaneChangePhaseInfo lane_change_time); + const std::vector> & sorted_lane_ids, + const LaneChangePhaseInfo longitudinal_acceleration, const double lateral_acceleration, + const LaneChangePhaseInfo lane_change_length, const LaneChangePhaseInfo lane_change_velocity, + const double terminal_lane_changing_velocity, const LaneChangePhaseInfo lane_change_time); PathSafetyStatus isLaneChangePathSafe( const LaneChangePath & lane_change_path, const PredictedObjects::ConstSharedPtr dynamic_objects, @@ -101,8 +101,8 @@ PathSafetyStatus isLaneChangePathSafe( const Twist & current_twist, const BehaviorPathPlannerParameters & common_parameter, const behavior_path_planner::LaneChangeParameters & lane_change_parameter, const double front_decel, const double rear_decel, - std::unordered_map & debug_data, const double prepare_acc = 0.0, - const double lane_changing_acc = 0.0); + std::unordered_map & debug_data, const double prepare_acc, + const double lane_changing_acc); bool isObjectIndexIncluded( const size_t & index, const std::vector & dynamic_objects_indices); 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 c004a0b3aec26..20f6aee241115 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 @@ -578,11 +578,13 @@ bool NormalLaneChange::getLaneChangePaths( minimum_lane_changing_velocity); // compute actual longitudinal acceleration - const double longitudinal_acc = (prepare_velocity - current_velocity) / prepare_duration; + const double longitudinal_acc_on_prepare = + (prepare_velocity - current_velocity) / prepare_duration; // get path on original lanes const double prepare_length = std::max( - current_velocity * prepare_duration + 0.5 * longitudinal_acc * std::pow(prepare_duration, 2), + current_velocity * prepare_duration + + 0.5 * longitudinal_acc_on_prepare * std::pow(prepare_duration, 2), minimum_prepare_length); if (prepare_length < target_length) { @@ -629,14 +631,15 @@ bool NormalLaneChange::getLaneChangePaths( lateral_acc += lateral_acc_resolution) { const auto lane_changing_time = PathShifter::calcShiftTimeFromJerk( shift_length, common_parameter.lane_changing_lateral_jerk, lateral_acc); - const double lane_changing_lon_acc = utils::lane_change::calcLaneChangingAcceleration( - initial_lane_changing_velocity, max_path_velocity, lane_changing_time, - sampled_longitudinal_acc); + const double longitudinal_acc_on_lane_changing = + utils::lane_change::calcLaneChangingAcceleration( + initial_lane_changing_velocity, max_path_velocity, lane_changing_time, + sampled_longitudinal_acc); const auto lane_changing_length = initial_lane_changing_velocity * lane_changing_time + - 0.5 * lane_changing_lon_acc * lane_changing_time * lane_changing_time; + 0.5 * longitudinal_acc_on_lane_changing * lane_changing_time * lane_changing_time; const auto terminal_lane_changing_velocity = - initial_lane_changing_velocity + lane_changing_lon_acc * lane_changing_time; + initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time; utils::lane_change::setPrepareVelocity( prepare_segment, current_velocity, terminal_lane_changing_velocity); @@ -701,7 +704,8 @@ bool NormalLaneChange::getLaneChangePaths( const auto candidate_path = utils::lane_change::constructCandidatePath( prepare_segment, target_segment, target_lane_reference_path, shift_line, original_lanelets, - target_lanelets, sorted_lane_ids, lane_changing_lon_acc, lateral_acc, lc_length, + target_lanelets, sorted_lane_ids, + {longitudinal_acc_on_prepare, longitudinal_acc_on_lane_changing}, lateral_acc, lc_length, lc_velocity, terminal_lane_changing_velocity, lc_time); if (!candidate_path) { @@ -752,8 +756,8 @@ bool NormalLaneChange::getLaneChangePaths( const auto [is_safe, is_object_coming_from_rear] = utils::lane_change::isLaneChangePathSafe( *candidate_path, dynamic_objects, dynamic_object_indices, getEgoPose(), getEgoTwist(), common_parameter, *lane_change_parameters_, common_parameter.expected_front_deceleration, - common_parameter.expected_rear_deceleration, object_debug_, longitudinal_acc, - lane_changing_lon_acc); + common_parameter.expected_rear_deceleration, object_debug_, longitudinal_acc_on_prepare, + longitudinal_acc_on_lane_changing); if (is_safe) { return true; @@ -790,7 +794,8 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const path, dynamic_objects, dynamic_object_indices, current_pose, current_twist, common_parameters, *lane_change_parameters_, common_parameters.expected_front_deceleration_for_abort, common_parameters.expected_rear_deceleration_for_abort, debug_data, - status_.lane_change_path.acceleration); + status_.lane_change_path.longitudinal_acceleration.prepare, + status_.lane_change_path.longitudinal_acceleration.lane_changing); return safety_status; } 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 04224b380414e..25ad04874994f 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -210,15 +210,15 @@ std::optional constructCandidatePath( const PathWithLaneId & prepare_segment, const PathWithLaneId & target_segment, const PathWithLaneId & target_lane_reference_path, const ShiftLine & shift_line, const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, - const std::vector> & sorted_lane_ids, const double longitudinal_acceleration, - const double lateral_acceleration, const LaneChangePhaseInfo lane_change_length, - const LaneChangePhaseInfo lane_change_velocity, const double terminal_lane_changing_velocity, - const LaneChangePhaseInfo lane_change_time) + const std::vector> & sorted_lane_ids, + const LaneChangePhaseInfo longitudinal_acceleration, const double lateral_acceleration, + const LaneChangePhaseInfo lane_change_length, const LaneChangePhaseInfo lane_change_velocity, + const double terminal_lane_changing_velocity, const LaneChangePhaseInfo lane_change_time) { PathShifter path_shifter; path_shifter.setPath(target_lane_reference_path); path_shifter.addShiftLine(shift_line); - path_shifter.setLongitudinalAcceleration(longitudinal_acceleration); + path_shifter.setLongitudinalAcceleration(longitudinal_acceleration.lane_changing); ShiftedPath shifted_path; // offset front side @@ -238,7 +238,7 @@ std::optional constructCandidatePath( const auto & lane_changing_length = lane_change_length.lane_changing; LaneChangePath candidate_path; - candidate_path.acceleration = longitudinal_acceleration; + candidate_path.longitudinal_acceleration = longitudinal_acceleration; candidate_path.length.prepare = prepare_length; candidate_path.length.lane_changing = lane_changing_length; candidate_path.duration.prepare = lane_change_time.prepare; From d295c8178f73609b33e69fd954c8b7ac216144f3 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 29 Jun 2023 14:10:12 +0900 Subject: [PATCH 051/118] fix(obstacle_velocity_limiter): remove hardcoded parameter (#4098) Signed-off-by: Maxime CLEMENT --- .../lane_driving/motion_planning/motion_planning.launch.py | 1 - 1 file changed, 1 deletion(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py index d491e14bcf3e4..94461c1748439 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.py @@ -108,7 +108,6 @@ def launch_setup(context, *args, **kwargs): parameters=[ obstacle_velocity_limiter_param, vehicle_info_param, - {"obstacles.dynamic_source": "static_only"}, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) From b86d3d8bc59502fbfa5b4bd14e30e0550bf939e0 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 29 Jun 2023 14:39:50 +0900 Subject: [PATCH 052/118] fix(behavior_path_planner): use previous path for get current lane (#4094) Signed-off-by: Fumiya Watanabe --- .../src/scene_module/lane_change/normal.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 20f6aee241115..77f2b9b842166 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 @@ -284,7 +284,7 @@ TurnSignalInfo NormalLaneChange::updateOutputTurnSignal() lanelet::ConstLanelets NormalLaneChange::getCurrentLanes() const { - return utils::getCurrentLanesFromPath(prev_module_reference_path_, planner_data_); + return utils::getCurrentLanesFromPath(prev_module_path_, planner_data_); } lanelet::ConstLanelets NormalLaneChange::getLaneChangeLanes( From 53b1347dc8fb292fa9362a6dc38da15b00bf18bd Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 29 Jun 2023 17:57:45 +0900 Subject: [PATCH 053/118] docs(ad_api_adaptors): fix readme to remove unused service (#4117) Signed-off-by: Takagi, Isamu --- system/default_ad_api_helpers/ad_api_adaptors/README.md | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/README.md b/system/default_ad_api_helpers/ad_api_adaptors/README.md index 6cb43c5475828..121befb68c88a 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/README.md +++ b/system/default_ad_api_helpers/ad_api_adaptors/README.md @@ -7,11 +7,10 @@ When a initial pose topic is received, call the localization initialize API. This node depends on the map height fitter library. [See here for more details.](../../../map/map_height_fitter/README.md) -| Interface | Local Name | Global Name | Description | -| ------------ | -------------- | --------------------------------- | ----------------------------------------- | -| Subscription | initialpose | /initialpose | The pose for localization initialization. | -| Client | fit_map_height | /localization/util/fit_map_height | To fix initial pose to map height | -| Client | - | /api/localization/initialize | The localization initialize API. | +| Interface | Local Name | Global Name | Description | +| ------------ | ----------- | ---------------------------- | ----------------------------------------- | +| Subscription | initialpose | /initialpose | The pose for localization initialization. | +| Client | - | /api/localization/initialize | The localization initialize API. | ## routing_adaptor From 8ef04a7594e2bedfcdcf3a928cb267f162c31e75 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 29 Jun 2023 20:05:02 +0900 Subject: [PATCH 054/118] feat(lane_change): update object filtering for lane change (#4103) --- .../utils/lane_change/utils.hpp | 15 +- .../src/scene_module/lane_change/normal.cpp | 38 ++-- .../src/utils/lane_change/utils.cpp | 163 +++++++++--------- 3 files changed, 108 insertions(+), 108 deletions(-) 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 872520b4b81e2..a724410192b59 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 @@ -150,12 +150,6 @@ lanelet::ConstLanelets getBackwardLanelets( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const double backward_length); -LaneChangeTargetObjectIndices filterObjectIndices( - const LaneChangePaths & lane_change_paths, const PredictedObjects & objects, - const lanelet::ConstLanelets & target_backward_lanes, const Pose & current_pose, - const double forward_path_length, const LaneChangeParameters & lane_change_parameter, - const double filter_width); - bool isTargetObjectType(const PredictedObject & object, const LaneChangeParameters & parameter); double calcLateralBufferForFiltering(const double vehicle_width, const double lateral_buffer = 0.0); @@ -186,5 +180,14 @@ boost::optional getLeadingStaticObjectIdx( const RouteHandler & route_handler, const LaneChangePath & lane_change_path, const PredictedObjects & objects, const std::vector & obj_indices, const double object_check_min_road_shoulder_width, const double object_shiftable_ratio_threshold); + +std::optional createPolygon( + const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist); + +LaneChangeTargetObjectIndices filterObject( + const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelets & target_backward_lanes, + const Pose & current_pose, const RouteHandler & route_handler, + const LaneChangeParameters & lane_change_parameter); } // namespace behavior_path_planner::utils::lane_change #endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_ 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 77f2b9b842166..41561493e08d6 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 @@ -506,6 +506,7 @@ bool NormalLaneChange::getLaneChangePaths( const auto & route_handler = *getRouteHandler(); const auto & dynamic_objects = planner_data_->dynamic_object; const auto & common_parameter = planner_data_->parameters; + const auto & current_pose = getEgoPose(); const auto backward_path_length = common_parameter.backward_path_length; const auto forward_path_length = common_parameter.forward_path_length; @@ -559,8 +560,6 @@ bool NormalLaneChange::getLaneChangePaths( const auto sorted_lane_ids = utils::lane_change::getSortedLaneIds( route_handler, original_lanelets, target_lanelets, arc_position_from_target.distance); - const auto lateral_buffer = - utils::lane_change::calcLateralBufferForFiltering(common_parameter.vehicle_width, 0.5); const auto target_preferred_lanelets = utils::lane_change::getTargetPreferredLanes( route_handler, original_lanelets, target_lanelets, direction, type_); @@ -569,7 +568,13 @@ bool NormalLaneChange::getLaneChangePaths( const auto target_preferred_lane_poly_2d = lanelet::utils::to2D(target_preferred_lane_poly).basicPolygon(); - LaneChangeTargetObjectIndices dynamic_object_indices; + const auto backward_length = lane_change_parameters_->backward_lane_length; + const auto backward_target_lanes_for_object_filtering = utils::lane_change::getBackwardLanelets( + route_handler, target_lanelets, getEgoPose(), backward_length); + const auto dynamic_object_indices = utils::lane_change::filterObject( + *dynamic_objects, original_lanelets, target_lanelets, + backward_target_lanes_for_object_filtering, current_pose, route_handler, + *lane_change_parameters_); candidate_paths->reserve(longitudinal_acc_sampling_values.size() * lateral_acc_sampling_num); for (const auto & sampled_longitudinal_acc : longitudinal_acc_sampling_values) { @@ -723,16 +728,6 @@ bool NormalLaneChange::getLaneChangePaths( } if (candidate_paths->empty()) { - // only compute dynamic object indices once - const auto backward_length = lane_change_parameters_->backward_lane_length; - const auto backward_target_lanes_for_object_filtering = - utils::lane_change::getBackwardLanelets( - route_handler, target_lanelets, getEgoPose(), backward_length); - dynamic_object_indices = utils::lane_change::filterObjectIndices( - {*candidate_path}, *dynamic_objects, backward_target_lanes_for_object_filtering, - getEgoPose(), common_parameter.forward_path_length, *lane_change_parameters_, - lateral_buffer); - const double object_check_min_road_shoulder_width = lane_change_parameters_->object_check_min_road_shoulder_width; const double object_shiftable_ratio_threshold = @@ -775,21 +770,20 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const const auto & dynamic_objects = planner_data_->dynamic_object; const auto & common_parameters = getCommonParam(); const auto & lane_change_parameters = *lane_change_parameters_; - const auto & route_handler = getRouteHandler(); + const auto & route_handler = *getRouteHandler(); const auto & path = status_.lane_change_path; + const auto & current_lanes = status_.current_lanes; + const auto & target_lanes = status_.lane_change_lanes; // get lanes used for detection const auto backward_target_lanes_for_object_filtering = utils::lane_change::getBackwardLanelets( - *route_handler, path.target_lanelets, current_pose, - lane_change_parameters.backward_lane_length); + route_handler, path.target_lanelets, current_pose, lane_change_parameters.backward_lane_length); - CollisionCheckDebugMap debug_data; - const auto lateral_buffer = - utils::lane_change::calcLateralBufferForFiltering(common_parameters.vehicle_width); - const auto dynamic_object_indices = utils::lane_change::filterObjectIndices( - {path}, *dynamic_objects, backward_target_lanes_for_object_filtering, current_pose, - common_parameters.forward_path_length, lane_change_parameters, lateral_buffer); + const auto dynamic_object_indices = utils::lane_change::filterObject( + *dynamic_objects, current_lanes, target_lanes, backward_target_lanes_for_object_filtering, + current_pose, route_handler, *lane_change_parameters_); + CollisionCheckDebugMap debug_data; const auto safety_status = utils::lane_change::isLaneChangePathSafe( path, dynamic_objects, dynamic_object_indices, current_pose, current_twist, common_parameters, *lane_change_parameters_, common_parameters.expected_front_deceleration_for_abort, 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 25ad04874994f..6d1b4486856e1 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -822,86 +822,6 @@ lanelet::ConstLanelets getBackwardLanelets( return backward_lanes; } -LaneChangeTargetObjectIndices filterObjectIndices( - const LaneChangePaths & lane_change_paths, const PredictedObjects & objects, - const lanelet::ConstLanelets & target_backward_lanes, const Pose & current_pose, - const double forward_path_length, const LaneChangeParameters & lane_change_parameter, - const double filter_width) -{ - // Reserve maximum amount possible - - std::vector current_lane_obj_indices{}; - std::vector target_lane_obj_indices{}; - std::vector others_obj_indices{}; - current_lane_obj_indices.reserve(objects.objects.size()); - target_lane_obj_indices.reserve(objects.objects.size()); - others_obj_indices.reserve(objects.objects.size()); - - const auto & longest_path = lane_change_paths.front(); - const auto & current_lanes = longest_path.reference_lanelets; - const auto & target_lanes = longest_path.target_lanelets; - const auto & ego_path = longest_path.path; - - const auto get_basic_polygon = - [](const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist) { - const auto polygon_3d = lanelet::utils::getPolygonFromArcLength(lanes, start_dist, end_dist); - return lanelet::utils::to2D(polygon_3d).basicPolygon(); - }; - const auto arc = lanelet::utils::getArcCoordinates(current_lanes, current_pose); - const auto current_polygon = - get_basic_polygon(current_lanes, arc.length, arc.length + forward_path_length); - const auto target_polygon = - get_basic_polygon(target_lanes, 0.0, std::numeric_limits::max()); - LineString2d ego_path_linestring; - ego_path_linestring.reserve(ego_path.points.size()); - for (const auto & pt : ego_path.points) { - const auto & position = pt.point.pose.position; - boost::geometry::append(ego_path_linestring, Point2d(position.x, position.y)); - } - - for (size_t i = 0; i < objects.objects.size(); ++i) { - const auto & obj = objects.objects.at(i); - - if (!isTargetObjectType(obj, lane_change_parameter)) { - continue; - } - - const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj); - if (boost::geometry::intersects(current_polygon, obj_polygon)) { - const double distance = boost::geometry::distance(obj_polygon, ego_path_linestring); - - if (distance < filter_width) { - current_lane_obj_indices.push_back(i); - continue; - } - } - - const bool is_intersect_with_target = boost::geometry::intersects(target_polygon, obj_polygon); - if (is_intersect_with_target) { - target_lane_obj_indices.push_back(i); - continue; - } - - const bool is_intersect_with_backward = std::invoke([&]() { - for (const auto & ll : target_backward_lanes) { - const bool is_intersect_with_backward = - boost::geometry::intersects(ll.polygon2d().basicPolygon(), obj_polygon); - if (is_intersect_with_backward) { - target_lane_obj_indices.push_back(i); - return true; - } - } - return false; - }); - - if (!is_intersect_with_backward) { - others_obj_indices.push_back(i); - } - } - - return {current_lane_obj_indices, target_lane_obj_indices, others_obj_indices}; -} - bool isTargetObjectType(const PredictedObject & object, const LaneChangeParameters & parameter) { using autoware_auto_perception_msgs::msg::ObjectClassification; @@ -1163,4 +1083,87 @@ boost::optional getLeadingStaticObjectIdx( return leading_obj_idx; } + +std::optional createPolygon( + const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist) +{ + if (lanes.empty()) { + return {}; + } + const auto polygon_3d = lanelet::utils::getPolygonFromArcLength(lanes, start_dist, end_dist); + return lanelet::utils::to2D(polygon_3d).basicPolygon(); +} + +LaneChangeTargetObjectIndices filterObject( + const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelets & target_backward_lanes, + const Pose & current_pose, const RouteHandler & route_handler, + const LaneChangeParameters & lane_change_parameter) +{ + // Guard + if (objects.objects.empty()) { + return {}; + } + + // Get path + const auto path = + route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + + const auto current_polygon = + createPolygon(current_lanes, 0.0, std::numeric_limits::max()); + const auto target_polygon = createPolygon(target_lanes, 0.0, std::numeric_limits::max()); + const auto target_backward_polygon = + createPolygon(target_backward_lanes, 0.0, std::numeric_limits::max()); + + LaneChangeTargetObjectIndices filtered_obj_indices; + for (size_t i = 0; i < objects.objects.size(); ++i) { + const auto & object = objects.objects.at(i); + const auto & obj_velocity = object.kinematics.initial_twist_with_covariance.twist.linear.x; + + // ignore specific object types + if (!isTargetObjectType(object, lane_change_parameter)) { + continue; + } + + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); + + // calc distance from the current ego position + double max_dist_ego_to_obj = std::numeric_limits::lowest(); + for (const auto & polygon_p : obj_polygon.outer()) { + const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + const double dist_ego_to_obj = + motion_utils::calcSignedArcLength(path.points, current_pose.position, obj_p); + max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); + } + + // ignore static object that are behind the ego vehicle + if (obj_velocity < 1.0 && max_dist_ego_to_obj < 0.0) { + continue; + } + + // check if the object intersects with target lanes + if (target_polygon && boost::geometry::intersects(target_polygon.value(), obj_polygon)) { + filtered_obj_indices.target_lane.push_back(i); + continue; + } + + // check if the object intersects with target backward lanes + if ( + target_backward_polygon && + boost::geometry::intersects(target_backward_polygon.value(), obj_polygon)) { + filtered_obj_indices.target_lane.push_back(i); + continue; + } + + // check if the object intersects with current lanes + if (current_polygon && boost::geometry::intersects(current_polygon.value(), obj_polygon)) { + filtered_obj_indices.current_lane.push_back(i); + continue; + } + + filtered_obj_indices.other_lane.push_back(i); + } + + return filtered_obj_indices; +} } // namespace behavior_path_planner::utils::lane_change From 9c30691e6b6f6b6dbdb9d54427b8f4e6e3f44df3 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 29 Jun 2023 20:05:20 +0900 Subject: [PATCH 055/118] fix(lane_change): fix termianl lane chagne turn signal (#4115) --- .../src/scene_module/lane_change/interface.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 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 ab2c87c7e1ff9..713188afb7f0b 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 @@ -402,13 +402,13 @@ void LaneChangeInterface::acceptVisitor(const std::shared_ptrgetLaneChangeStatus().lane_change_lanes; + const auto & current_lanes = module_type_->getLaneChangeStatus().current_lanes; const auto & is_valid = module_type_->getLaneChangeStatus().is_valid_path; const auto & lane_change_path = module_type_->getLaneChangeStatus().lane_change_path; const auto & lane_change_param = module_type_->getLaneChangeParam(); if ( - module_type_->getModuleType() != LaneChangeModuleType::NORMAL || target_lanes.empty() || + module_type_->getModuleType() != LaneChangeModuleType::NORMAL || current_lanes.empty() || !is_valid) { return original_turn_signal_info; } @@ -436,13 +436,15 @@ TurnSignalInfo LaneChangeInterface::getCurrentTurnSignalInfo( const auto & route_handler = module_type_->getRouteHandler(); const auto & common_parameter = module_type_->getCommonParam(); const auto shift_intervals = - route_handler->getLateralIntervalsToPreferredLane(target_lanes.back()); + route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); const double next_lane_change_buffer = utils::calcMinimumLaneChangeLength(common_parameter, shift_intervals); 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; - const double buffer = next_lane_change_buffer + min_length_for_turn_signal_activation; + const double buffer = + next_lane_change_buffer + min_length_for_turn_signal_activation + base_to_front; const double path_length = motion_utils::calcArcLength(path.points); const auto & front_point = path.points.front().point.pose.position; const size_t & current_nearest_seg_idx = From 3bef61753c2c2b9c1f90ba73a33c330779f8debb Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Fri, 30 Jun 2023 09:30:55 +0900 Subject: [PATCH 056/118] docs(yabloc): update yabloc readme (#4100) * add yabloc documentation Signed-off-by: Kento Yabuuchi * reflected review Signed-off-by: Kento Yabuuchi * Modify image size Signed-off-by: Kento Yabuuchi * add sample data link Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- localization/yabloc/README.md | 59 +++++++++++++++++- .../yabloc/docs/yabloc_image_description.png | Bin 0 -> 677694 bytes localization/yabloc/docs/yabloc_principle.png | Bin 0 -> 959680 bytes .../yabloc/docs/yabloc_rviz_description.png | Bin 0 -> 475695 bytes 4 files changed, 56 insertions(+), 3 deletions(-) create mode 100644 localization/yabloc/docs/yabloc_image_description.png create mode 100644 localization/yabloc/docs/yabloc_principle.png create mode 100644 localization/yabloc/docs/yabloc_rviz_description.png diff --git a/localization/yabloc/README.md b/localization/yabloc/README.md index 34d6c70453c6c..f80dcfc88cf2e 100644 --- a/localization/yabloc/README.md +++ b/localization/yabloc/README.md @@ -4,6 +4,10 @@ [![thumbnail](docs/yabloc_thumbnail.jpg)](https://youtu.be/Eaf6r_BNFfk) +It estimates position by matching road surface markings extracted from images with a vector map. +Point cloud maps and LiDAR are not required. +YabLoc enables users localize vehicles that are not equipped with LiDAR and in environments where point cloud maps are not available. + ## Packages - [yabloc_common](yabloc_common/README.md) @@ -13,8 +17,8 @@ ## How to launch YabLoc instead of NDT -When launching autoware, if you set `localization_mode:=yabloc` as an argument, YabLoc will be launched instead of NDT. -By default, `localization_mode` is `ndt`. +When launching autoware, if you set `localization_mode:=camera` as an argument, YabLoc will be launched instead of NDT. +By default, `localization_mode` is `lidar`. A sample command to run YabLoc is as follows @@ -23,9 +27,58 @@ ros2 launch autoware_launch logging_simulator.launch.xml \ map_path:=$HOME/autoware_map/sample-map-rosbag\ vehicle_model:=sample_vehicle \ sensor_model:=sample_sensor_kit \ - localization_mode:=yabloc + localization_mode:=camera ``` ## Architecture ![node_diagram](docs/yabloc_architecture.drawio.svg) + +## Principle + +The diagram below illustrates the basic principle of YabLoc. +It extracts road surface markings by extracting the line segments using the road area obtained from graph-based segmentation. +The red line at the center-top of the diagram represents the line segments identified as road surface markings. +YabLoc transforms these segments for each particle and determines the particle's weight by comparing them with the cost map generated from Lanelet2. + +![principle](docs/yabloc_principle.png) + +## Visualization + +### Core visualization topics + +These topics are not visualized by default. + + + +| index | topic name | description | +| ----- | -------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| 1 | `/localization/yabloc/pf/predicted_particle_marker` | particle distribution of particle filter. Red particles are probable candidate. | +| 2 | `/localization/yabloc/pf/scored_cloud` | 3D projected line segments. the color indicates how well they match the map. | +| 3 | `/localization/yabloc/image_processing/lanelet2_overlay_image` | overlay of lanelet2 (yellow lines) onto image based on estimated pose. If they match well with the actual road markings, it means that the localization performs well. | + +### Image topics for debug + +These topics are not visualized by default. + + + +| index | topic name | description | +| ----- | ----------------------------------------------------------------------- | ----------------------------------------------------------------------------- | +| 1 | `/localization/yabloc/pf/cost_map_image` | cost map made from lanelet2 | +| 2 | `/localization/yabloc/pf/match_image` | projected line segments | +| 3 | `/localization/yabloc/image_processing/image_with_colored_line_segment` | classified line segments. green line segments are used in particle correction | +| 4 | `/localization/yabloc/image_processing/lanelet2_overlay_image` | overlay of lanelet2 | +| 5 | `/localization/yabloc/image_processing/segmented_image` | graph based segmentation result | + +## Limitation + +- Running YabLoc and NDT simultaneously is not supported. + - This is because running both at the same time may be computationally too expensive. + - Also, in most cases, NDT is superior to YabLoc, so there is less benefit to running them at the same time. +- It does not estimate roll and pitch, therefore some of the perception nodes may not work well. +- It does not support multiple cameras now. But it will in the future. +- In places where there are few road surface markings, such as intersections, the estimation heavily relies on GNSS, IMU, and vehicle's wheel odometry. +- If the road boundary or road surface markings are not included in the Lanelet2, the estimation is likely to fail. +- The sample rosbag provided in the autoware tutorial does not include images, so it is not possible to run YabLoc with it. + - If you want to test the functionality of YabLoc, the sample test data provided in this [PR](https://github.com/autowarefoundation/autoware.universe/pull/3946) is useful. diff --git a/localization/yabloc/docs/yabloc_image_description.png b/localization/yabloc/docs/yabloc_image_description.png new file mode 100644 index 0000000000000000000000000000000000000000..d76977535d306911a7355ef2341447b9219799ae GIT binary patch literal 677694 zcmbrl1yCGJ*Dg4aAR)L0cemid2^QSl-6gm~f(8%n?(XjH?(QywJIqel2;ySG3IG7qG63*C85R=!Nguy>75MGLcQJJb z006P~&l4h!77-T!AOeUBe^qi#JzaBBL)XLwT)3EgjL+lFl|(`Q`0o8_xut;%xasU1 z*X=CZS&N{*dq?*k0}2IMt~o)we&5sQ$1lic{|9X^pNxs?qgjvf(^ZG@c5a8jY^vea zRUSGzDVjJ)L0Dpc`1t42&AxCN-RRh$&-lW!c}Gv?wVlF-7Dm?TP!B+Ao8k|1*6;F>z*2|t^Rf#_(dmXXruq3CN5i#A@1s&JW4ENBJ#OJG>a+(8Xzd(3;d?<){U^vN5mYW4K@nmJ#v-a2InyT zEc7H>(uq%nv3O}JqMxWB%1DkCj}d^Z5C?SoD`lXscx$uCR;MMeJ5jP(t%%Ir-Vm+bAHO{|Pf#JYdAy-nw?2zm!fnfN-ALkLYd zLhTe;w35#%Uy=MR|ARbL@t)0w#mB!CB*a-J$0@j|QphW)#8xmf%85qgcgve4JG;2> zJ0AYlVz|G%gZ|-he~!=PIJmITuuEG$65@OG>Ca&0Pb2vY$;xZe#Qe8Tom(AP&@fzw{Y@??W>7fG zwl)WvPppah1FPX&4fooxrY&CmYWJ8AtSdX&c~&%K4ZMd$q&cU6oxqp<0O@% z+>C{Xu?(^LEl`@!+?7VmP_#WDpyegAL`_#=+>9nR%l!i4D)LRASTXa@KNjc@SUg#% z04*8+CAi`Taz2siSBTF{QNUdP-@kk)?%xh(pdB^rao#nP-y2N}McAx3J&GjfUch#a zPhh=^<-k{@c--NKsc0u90RUo~Csy0gj^pftKKE@^?p4W8F$zXb z9es*psqM=V1*$|_J_CZ>cH8glZ$S;IAIB6O%(yelax6ycc(HUx0063F19?E06vgv; zTQ9mCAgPelSBc zAwIT$7#AO*UmX+O2R}K#&b#bpKEkF;(5&=30-`*gA|o($_t&6Qzrx8#B3-fw1nkUo zZ|~Q%?aN0kxGTjSRN-DJfn9sOnowSeUYpNH87wieWk}XWCZoQGr&wKEf~KlJ1@GLT z+ksGjoiP9q)PoY*r%O+lx9h( z_|Qx~Ku}v=7l(--^|n2Es*WTzceO2&an7@~$WdH@|DA=`alt>U;5`|~^))>;ogoWa zatJcti^H+ZdOeeqwKkqIkawi1!F-gKK0>(9<1O$fA_o5cq)9q`>Uf{OcWb@p>^u5$ zGTLt{tR@D^#((11p=zH=&5~8U7DL5FJ4Qsd(R2Yb*xRM^xLv85V<90$Qb;Fz)?MJr zUmW25(T_4fbwohc?;Bc^RR1JRGKI5~=3QE~`_AbdrWOE@$%+%E!QPM|OONIh&#Fqb zcdW5^?2wzsx837(m&P|cF!du1?V9=2xK(Xzu)aPf2?ubo7C4GCH9aJTAe^*>8j&C6 zbmo4?MF+?XUx~n3%Fd7a(YG*Z@UHBH&E8<4nT^#<+&Mq2qCYCZm8=-gtcN|u^xo2< zWF%%UcnMlGIRi#Y8TYRnbGm$dvG^0S9%;@L=DTf$!J$w>TwJ~#`Onva9T?(WDRHGw zrMe3vcs@ga)Epb1kU$v~Yb)c4ff09QqV|>}|6S@oR{Lig7lXrkTxv!hAZ1KNS@~7^ z-;ncnI_1c0s-FU#JD0IbY9b;c+S+Z9!1A|9(XOC4@Yp{K!V=%S8``sv5>uKVZMR}i znK+>3tU6~zgPLLb=X-FZ-P*NplA=(g0>^SdCRIqEf!&wX;Q}#ma_|}7@4pi%m3=?| z8*l#3n`II3pXl>{*z1G-QCV4;p$-3+*gr2>8&D$hN}{6u6AaM*GT}c7gd|k?Zx6Xx zB{Aabe;N4S>9LB)Z>$7HiC=}r(0sD;9MS&2xX?j$2hBl2E#tMkS#M2=$K^e-31<<*z~gi9;qX3`gfJOTrAuM z=SBPfG?o2`b9_-c{yRElL<}yzm^-tL)4YWB5TD+LqY2ZV;ngDX32bf~;R9t6Jc_Kt z*f&^_KKAO$iUs%0R_!{MahIoJfCGKv;nG8g`Dl z!M(PkB0&0=Iy&KvTYQi1FDieHnxTsE|pBvgqdkoapHZ_ww5 zVo1|m<9H}W%6+z|U-em^&)b`_^CGko@$9X(3e{JyVV+m2eY6@CK4UY=p1a!47BrE= zP+3<%K{Wgvd6myV{g=KQP)J#Cj|8AoVQzA2ZswVF20q5qV`X2iVF<1DCd8I}0+zeO z1-KMs?jG(DhBvh&UeekG6(5oum>-Xmm$%Zccw$T{Xn3_^;iWM^25q%|Rs9xwIRx;mpz(Vb0U9#`ZzpDrf7QlTeziO_|WX*gsxU+#2oW*zcwb<4tSX(0o2^&8xACJWN%AWFlrxrFk-{E#Qv&3Z^{4;x^GG*JOA!X0nzO_Y^ zx4}R=Eu%4}H1`emWLuX0d>XxGwpHt57S^kv!&nLu9!KwhRsf`){f5p;$4T$m7w$>#J`deJ@7pc8H@d@rXA%IUlPB5!3`)=;(ST;#6jKwS>1Q zu8d(T$ofIb_3G%fakurXLO6XH(!~ffsP35nF1uanWCu!y+Pr(JuU{xlPKuPEeWaYe z*pV!sOji+aV1#N{bvR)+xFIa(;{R+M_>YAhHVB|)kM@wj*~y5yYy4^M@nR6aGf>?* z=|mJf(Ma6g^j>zkpV}}>br&U9Y`5(}yCM9pq_V*tluR7c4BjXHWP6W$SVhymw@Fb6 zeyGji%y(@!sK5x@4vn=sY)N>v06!6}Lb$>K2Mh6HJ z0?(6KcfJQY0E^I4@@>*xSm`=4FF*`<4J2YEdxJ+_2=Df-;KWQqGNz~RNV-j1D9fG> ztMm@aq392Th%LgoTaJ}kal4GjTP0_i=av0RgHpcHx$S&*d~8;?-V5q~c_d2t!NYR3 z0Y#d?&wR>dZoqQsbD4LO0<>EfWrGd8K`=jG zi+v1seNN~*+;vX}7!uFtoAmU9#wW~vI>m~7-;vnzGCq!y2MU@oQ@Zr&xeyTx6Zi5B zg0x=N8j3JM3e*wh@DtbjGVSy$FPi<^xgPh^EdO9zLpS<;t8>Lrm@Q-Lk|nS4Zuv8K zv;JCZKm4~UY$<$0fF7r`8f!trM;Nlr8Y|CT7|u_g9*hU8ST5VE10IVhW@xg&=96<+ zi`hvkQ$Z5`)0gq^ipS~N1P+FRdR|G7rEM3jk;eg~~_(o~|!yLlN<}XR5U(^R0yiuEC|9 zE=kc-94ctFRNb=10Ar~Zg;g_4b!d1k$dQ@c{tgtOUeUceU@9p{$%*5^nDV z-a=8yWe?5Y`n;iE^JUJ?%OT|?^EQrb5`59P9a;J~qW_bg_#+p;C!b+TeuucOyE6X+ z8j#$VMO@yCDW&0Qq|u3qG=m-R@y25|CU)_dTWy&_h20tQYtMe$!EF89j{HVSN+9ZD zGn+)y3sI?Gmi}lPk#gh|1$jHw^&%Y{_&Bij^Rq5ur`^q~gZ6sy(RvH~vs5Zmy{Y!A zJzq)g^!Luxr1PVK{LvZ$4od-i`X|l4-RdQ%ttOtq1kCkl2rzU54bZDq` zj6EX>2k4w;n^w*N{9p&RI(qCk$Kfa2t%RrWRr#PPB6c1ulyZ1 zR(|FgTbyi8o9*6kYpa|!9n>vqVwtfcp@+yGeBZo0}bvIfgA% z_y`SPYZ>QVb$%F;OreNe&Gpi+N|4DbfXJV%m59X?kbfGJkus6Mn>8y7h(RL#Csi%R zYp&L%r%rwc7vMYTj==2{#_PDLp%kw~Jmh)L%9AIt-h6ZPAYh)NR@D9h0rWfV_U$~Y zEuk6$AaHp;Uv+PtZ^P$m1uVYA$BRo^jobB4=O*|R^G<`^#>pz_CKaw7IfdPV$vyk_ z2;p1$hYxwC#{kBj_1xXuZ#ul+FI2n(A|4RPPLARnF#Y0zJnpV1t8d}buF6rUdg`t> zX7(T-E=q-Z;#tVAK_*}y>o?yue9{sk>C`uFCeg08g1Xx({cL( zLvsT&f`=`kzCD%nd7@n+fy#)}j+l{8OnqOvh3x~cE&2Y-QCfyvDJ9)ayDWt?NO-+%5d6OCfzL+jJ-8foET6KkH)EpOo!6s?aG}N zzXKq*dEfC6Q!*Hw(syFD&6&Ens-n1+4tA5R2r#E@99*FU) zj^L;=SEt{Kgpe%-SBzCC7-#+W1l;flI3WK zkQBskzMCxFL>Un_Uz~GltSdF9G9`R0WP|}cqJgDKywx;#Jac1uVAHY ze41G-4itI)xne77%4{`KPV0O>{8SSYQ`B}J8!FE!2sKi?SID1Tu)yI=;7qX}>M0eT zpQf$D7wvRaG*%$Nn5a}d=v7;9x~73Rt}UCykhGX>QB9H;*Se?-14jPfm)8fD%AFIe zqr15GYrC!f1$ncEv-8cc8Nwd#JexMU#Oxg~ig8|ihhzkzGDwXcL_npj+XIwvQJ*tN z<#x~sQpLY;c#D}$MvIj0?i?l(Cny zk9(=XqD4XnystGADrrud9zd(0 zA@$ZX@aB))gGRWyEkk!{j&;38!;}(fcPt7qJV-I4_Vy$=k2A2SdzYHvb!!e;=v2Et ziQAN?-i!PwzH}P;Si$vllq{NasNFTAMP?vDRM=heFY-NU8@8Svqp>7(G0PU}MQd7Q zW~QReuwSyHNZ0Ou3A`j@+!4~zajy5@zcdrSS{W1`5M{fK`ygWnm8_f;3IPboxf8Ny z0sx{@ka%h@p3zlOwW*|3;7|Zk*%5crLcia9owPI8e zMJ4zD<*c32@dqjV4{^mRwb-Xh@Q^WoRU&;yC{&26m$yBrGsYB4ZD-kBV>>%05=CZ?u7 zhPcww()9H7+}thMIsmf>Ha>RxET-tXEw*<1?Ho}BR%udTSE(#vdR1Ha&)FI$W4 zy4y{-w5BUtD!-dvU2HKI6TIR)+jY1yn9z*aloU%tLm~NCEe24(3HXAkyL)@B#RY(z zK%(WsTw4FfOfGPBi@8$H5X zQ@9_Ye?P(fNA1QQLV$%jZmorpi~jW{l+PoArn@(=n*mhzR!w%wHPQt4XY+JW;OVPK z>2n2U7d}VoE?CS)*FtSLRlK9^7$S#p(2r@kxF6Kg)YBmIYl z7UNAnR8f;s2aLIsEj^mmn-^G_XB0L0vmTFDY=c~wQf?Q@d>OVn`wpPFjwSnR)0?*x zMC;Agf9*3k_mfoJjMpUgBnXwmh?FHSdXLAKz%cL;E-#&Zn~#e!%G;aNXvSH!C4*tm zZhzQaiZLM=OMb2e-yvP^hj+sKL^$EF+9>bgfYe(kx-X&$W7UPjBS?^Fi_oV0v&UAt zQ1(@0@$@kXej<09$a5uI)SVq339({@)mqQ_ADR^&nH8F2y>0pM)o-8id*O^Dy^=@+B#e=Zajh}66=a9B!AKwl@!$3 z5f?xVWCwfuv5O8MZA=s@y$2(L9erfl83%i(r&=pRW#R=Xma#DFd1c@M-otfDX5xu7h36UPCy&|UJw4#z zvS)8UZq;^m@>L~P)>sOM2O5g^7|^0C`s8h)n^foV!L{8L`!4Nshu4C7BN4Z&AxDsV zsI4gqPKyk9{~dA!kxI$A`#*AK3C+|t<5c`aQ^WPJ{CLb(QczJaHicejR#fumQBv}j zNaKZ+w{<+n2YTw^i1zhi`9R!2f>T!t+-xJ-yc4ud8-5uaB;);Z-&>%~ivagaEivap z&4Xq8Y^A|=gYT)Og*U)Xs`22V%*s{=!8QC8^{c zO}1x}R{5vdd69sgtMBad@&|J@3maVR<{wparcPe?az7X=6UZ&l2-AZ{EhHi z50^9mK)^ozT(|1>tBk(UKkkN9YELxrrr;8N5ThB>*6Gck&UJ^8ReHXd|&`CSN+GiHRtRc)M}MV;>2)w@?z6{B71}Ebh_bJZ1VPRinEi>Y;6`N=gIrV zxr&Lpa-VyF;)0<1@%X^wCmbG3X%s=K5O>tKstCWK@J%YfrrnaA_)_qZ8x4;P*y{tt zCQ$9ZShdqI?pjx;8lq{#-t-5+fV_)j2}w{G%ye0}aNi1{bF zMSPCK)t}B7umM0S+Zcqrg=cbfF}};_m`Ax#W}S82zA=;j84{m4%S66g;Gdq#bPGhP zdy>LG!>P0S-trZOdG$&9*!E3tovQ;09$CM)Od!hez%CT)mZg==I8K-39og%6za0#E zn(FDJrNrxMN>%@uCUPw*2LbhLMMETTtJu+DJ;YDTgQU$?MDyuXKAhTjBb|6VP2OfabL*9+DTdumot74 zT@nPv<6~Y;Q!+G72C7`h!$RcQ>6j8VfM|Oae(UX44+bV?+Bt~I{nQVFq9j8?R_hr)pS z#X)RW#aqjYE)Uc8E3^_aTm%5)Xy`QiH+Uw zcDrNW*N49YWneLFk3Urrt5zq!?CD#N)|u^_H?Vx2>HmB=OV%Mu`l>NMo!eRKQShpG z{w@5w9Ydm7;5_>R0_GrGPR#!s6t^_pR5aq7se07rxX$A~ zWvsB^@pVf*?GZ&beb$0UvcpVA$WA73uv1dXfxS`O<**SG{8rQ_3Wk`9;XHGVxPiP(o|<(u@!^#P z!Yf#S+%a3K)$JE!8|q={cS6#21~8@{YQu;~RHXpJu;TLQPy#coA~XKPfZ_G!OHG$F z;hW>ZVMRoT$cE48X;jWK|54Q><(KZ4e%P2Ykhv`QdTm_%5f2d-Sq~QC$3VlxFxfWq zNvHk{IslN8Gi-pBN)s}+<)=hJ2|lzvyA1SuAyE~G1_m?tOVL5Z2S{3WMR-J_TAeZz ztjk)hPWjS$W8tFI zF5<2|+X2^8nY@Fp=WIOEKNU;RV3n>3){?*JCI@E-PEnrv`C^$lSx?GA*?NOb%4+~B z!CxCOjSdYPqbCOxa<8kJd*X>wSyqe9KO7`i7Uw42P~wyprf$5|@Pc}_?H7}eX{v&k z?1ng9gwT|f8?D&E1y84Ax7n!7r}Q_m3|iwgX8(Q}v+=tIypDe#fxj=u#H0#NIGmXF}z0!(#Q&0onpnGZOVQX`X= z-Ee*yUvWr@)xg&1(D^t4<&6YMXN%LYq_6(+ni|_25#?Th&vAeMXi$|~9yuRHxo~r? z*>rFJeY|@4a!~ew_>6bu$svGR*@>P;l8PkrRzxZ!|FHW76XhcdXR>ca1^8b4>GpSO z!aeZHYhTT-L*uKwfV`5UJwXr!_XJYCqIC5n%<_%s1S$P0pq5P}E)K3JDqW*CTJQggZ`JZf>8*UtxI~Xf*)>bE| zC@FL>L`U}vvg$yrB!>81az0LnmuBhveihaqbktnabNz?7K(ueLSs-?CXLkt&K}WOB zc4Jydt^WI>ibtme!FNyq%qLGp-n!eJlnkFw97h!}w%gT!PLMfdN`B-<2poL)ft|V) z=GxTE)?}V(xHdfw*PLFBniXalxm?=nikH^CyQeZkumm7WQao|l7U3Zmh2zO7E{nfpUfZS6y)ByRkv3O-Az+mZESPbQ3wleRA*A2VCo zRK8QoeA)8i3TLY)%DKkCqs=CLp2QvaB9w;~_~r)(|BzGE)LCSlk&Xaw{@V zr%HU&YI;sE#yLGPR~@JvV+Z4hX8!@u=i+FKxTK-uM5oqS?|hA!%fyFZ2^XUKzE;0X zw7H9MW8~+wqt%+Qy`!rTE@_Ks48hz|qnn(yGTd$zqc1$}7o5#RRN|YG==bHPYt7ml z;~BvS-26;M^s&V~qM&-cNA&O*I9Yf{M_;;9Z=+h7>r_&I=Nxel zgqkZ>*G&4}VZERZ{Z|WF8w7uIIfZ^!HuKvn>=_eAwVLPsv~L@*8{H*aFGKGdtX5bp zdKc~EQlfU@Fgy{w^{a!8RyAgKJlp(eHO*PzM57(8?H0Vo3m76x`yh#`TT?yjo4G1p zdcKHwNBrKhyja?6sWIpw5j@lYMtvV0L2 zIpz1={c41xTfRmKK*YN|Q2|XU^P7D4MhmFBye778(dkbiR0km#et=(*O8E#t7a7ao z`Tn;1b7MVuV8_eDPhpD3Dck@=mOZ))Z|7W}$gE&`K-M1WX}fi1sUU|Hl9R8#Z`8lh zuP`-9ch47Z4b2J9{aASd$!HDtBQHBk`9?t@+8eYea?k}s_gx?u91hLQ&D(rH>)qYH zVDE@*KXtOpq+*Fww#gSoK>z35GZsC%L&%U|+^VP6$UNJ(q{wvMXs{QUg* z`1rImd_XDZo2Lno3raghtBVI-w*88Vk6k^HKK9VOc(!_yU~+m~Nw#eFs{vXK1C%I_ zN6Za7A3gw&?&f$A*XgDf^ws6JN=-_Gjow1=UzEciZWFc!5?tHN%*^cV%=ACdp*Pl- zIf8#HKm6tDx*h+8u8IGbUbZ<73-f=`O2N4xlTZ7m2@wCnmtYvcx1s-kil&umr3U{0 z_U>F7euab#kBv#o%2otU6ZyYY93CHokvEsaU z2`Wn`B_(tbd8d>4vTob5kD5LVjvGUv2U`>xiy=Rb6LXeIxakYpQe@YES`5s5|@1^~EkDf{|90Ev)fo zr<3(2hXYE{%gf86Vk&>n8s%4|Xs~UoDEC4tYl0_F`p@LK1qHNVC2gUASIrM<#&<&OY znH4DRUe^jdSj=rBV;GCrUqX3akBU>M7C2mT08~({>D7S5kR-j8kuK%YmRc(9R&Bz+ z@>m<25lx#YQ;SVqO>F?K@9uq|F1~T;LFtB_owc^cW1VG-Etih#0&WeL>^41FxPXEh zSjZva7O9gsyS9Las56gR%fc|r9QMac)gpTmA;?dV^&n&6fjeFGMX-F3sbV6!%Atsr z;-k-m^cI8iUDGyen($`EBNG~Pz2j?Wcn!f==fg>V_fL1>6O_< zJ}5O=&{%1*lTMoq*mTf%Sae6*)EJ|kPpKGj~ z&7EL5X&oz)r6H#x(?Dx&cWR0*+oi<41+Ei31Jm1AXDR$KG+5CtcZmNZ|}izm?Z-?Y9SE^lIDns)gz5?mYe_ zmbw(#lQ$n;6jT6UX+`m)GsfF%M*%Y-(-YDcuLEsq%N{Uz`8>h5Iq zjPX=#Qu=c9CEvV>duX6r;rAtsH)@GQ%H8WZBj%(Rw7vv5%wZ#DK3(a=`&V5YpH$yV zP_;s^fb-MI>bgJarzTkSM{!_#$X%LW->y}MbchDu;dgs#{S%5&qA zz0=q?>E!2wd}}Bl6$afMpPq_gOL;tMs2FeClWNJS58fjKWsPt0^2-#%BS^fTZB~DN z{y-dd`1-EnxynrnDuP7Z)BaV($XUdhzEq~v{#MSDs%-wMp};g^<%y`||J zfaEY-!krPYmS3Y5zi~&LK?s(3dT{2W3)Wkk1yd4IeME{Ig~Z#dG_6Cu56)hNn-wUu z=T6tHL+3dXS#UUKthVF&!G=1GB?iO(sJb~gi|#B=*Hy!tyv1Gglgo~1tK8RLFKwXW zOWN`Q8m2;G|IbMivcUE?8SwS5aMX+5K&~689Yt9$@w$jB);>j2qJ)i9!u=2{j-J-X z@lq0mR$KL<<)*G$mC~df<@NF)LL}|%K>#+Yt;LJ3XHu$ew(8A=DVrm~CBx^DR5W*( zdgEKzn=IAFmsMAsdoGIG%aZpDK?E~PkGV5y7QJ%ZqKSUY(uAQ-@M01!o!xii!)R z>WZw~dhYH|$!wP3KCN8zFtNRO`)TM6Q%puuGy?-INNZVxWK2eUBnI@OTlrke>vrpE z5l&HPWOP)D{%6+D9}46O09VYo+}|V7EcUt`q2q&tql2U12a$lpxz6p}b93X;M1__j z2U~PrkgiXfjtZjAQO;i9Mk5NN5g@TK#gd}D8Kq!V7LJVe=5!r*iWvaVQ}A<^)^_C+ z)cU#XQ!I0Y<{C>xUpN0a^mQSphW5MpUeE^55Hr(GY`e0ZYNwAEnCiy)V@&z{0}Tc5&EdY<&Rbb2C!iJ#QA}`8Ysowg zXk?UJvxu$pz!vVXX|;uY%M1{ox(t+IU@No!C=;^nHHn~|f$$^|;UkI1NO?8ApOV(> zY>%o`+Zm_W9{K4tgO>Bx5SpZ$*4<=;lkA%3)aabjx3q#CJ-LmpO^b_XFtA=PWiCS1 z97sU;L+Qcf*4Jlv&mOR8-{b>)lhhV6Tu%+aLo_`LR2C`8T+}OpWE*j_`@Y->^_G-* z-ga@ZukTble3_y3wfEPrUto;dyN-s0L{L?=;bpJr6UF0Dk>a1MD}#@#(b9!9dWaO6pd)?=wec}wUnjz?A3tKA+O zIgsj8{!Hs@AIHatq1Yje6IrM-evJ2k1Qqz7vbwM(*{Bk62yo9h6%p5syG~Pc>P-Lu zI{5D=cYZQ~cZLq;d5DE#NZj@0^Mefm7`Q)}kE+kaJ(5SLK|>E(_<46^eeD3RHl?Hf zO_rgQXNdB2p*aagjv?u=U=~OFa&zMzNFskK13%kC_p-Sh8pm;r;IAup4yj%#pAwwU z&;)1>GUQ=0v1(yQZl`BUfiI| zNF&brBYqPzTulflK**?S!rd7kHnIq3{V}(N7`LU!ZrSz0%Q>HClKvsD(bL2Dov#5s zcg&|s^R*gxmV(D!U7hAB#ClZE$`GnuX9@5M@v$mVY*Zq{A6W1TpVu$K^Ne%9`PAC0->St}NRt-U+9 zd^UF@s_=QA#EN}Zmv>&>cH-Z3RA!0$Xh z-Wtn|C67xB8+@1uoK5R235Y=w!Y6RmWChex7k51GtY!K2-EiKsxO@65WyINOA*Pqj z-nixw5Q>(v4ajb%%m~Ad20Emucw{!j5%cbD%V|N>c2BjLEL{05-?kQ>X;k(V)yHEa z!$;SZxaR7VS+BC-VK=!0NZ~D($h%dnJdotDoE-Pb;Bzp?f~}O{>D`HBOY;EZ5^bn>p@3PFq_gmxca z7ac;8BvxwCAJ6!og;h)kOFx7&kAvFoyCrpMF0UzTnGaCxx^rmBW!iaek1o$vA~#-% zDywF8AX-#9L=0EeqY|8L`R#YwG+xhh`k$L|<1am^X(;IFt;dqtu(5S{q|0)0SS;u1 z_9&-mjVmSPNxA0l?AZ<{D={(#Xw*vd2IDsGUst#^af&})@6k11(8~7(?ifTRB6okb z2mgD4A*hFd-Bq}YhK(;HJ5x`&D*_6aRy}P3MP$NRdeyM;+&q@!q^peN5U9no%PFaY*hD zeh!`rZm;TuhvN|b3M{9zyS4-P&)yDuFLm5V>6FDBhb-m>j0L47w5o5{bWASSwXup3 zZTk^ruQn4`wEc!yj`d*6p?>Hse?1_~JK;EIw-TOs0$Wb6mYTELe16^Te3Zji^LXuo zalF;c$`iW6amULZ{EshE{i7#VW6(rRvUl{?EZ7`FVw zNFsL+!-ek56JnB)c|S@-OZ_a3o3G%H|J3fAP84;z-g2cuM_k=L%sTOLw;Xgf!CYE6 zaorG3O^mcwp0ujZjHvnNZ97rv_vktv0=9(d zPW7bs_42n5U27N!GpTpAs066Fu(&yGABKPNbB-~&nfA6fn+Wb?Jt1H*y>Xbz-c3T$ zO}DsijFFtrhzQv#O@CP~T>nk}?&PAn{KS!cI90EPvXZ41PXh=gpV4hJo<7OZOrvV=dvgUK-P z>Jjq)>3FH*t|)bpJK$Sa24}?UGO1}Fl*Le;tUMdWh7bnIw3v!*x|hopWd?>}W9|*^ zFKoD{*S<08@-?H-(rbS0oocA?VYTHjIXVs=XEYh(K_MpZ6E!5`r{47xv*&{-(>U|E zJzr}nXz-rxKvH9$f5{C}-7xb&&~7xTS6zM*_ec+6#nWJ~BDbj1yg6L!8BvH6o7qT3 zl0ru9&V?yI=jIYPh=j7-cgE1dp7&AwjwvLj(|u;0Lvb$ca+$_C$6|bT<42s$SlqKv zT^Bgx^Vk-TESQ-3J9I_&Nd1#hfR;yZ`G(6~a)7oPC~V1*G7Wsd9z<$=N^}j=X?Fb~ zzS)?yk^zfN)qER;5_pa`{roF?E^IFJS)C_o$uP>N+V?Xy()=y<_hbuBlrB=T$AqI@g4CuRZ)9`vt_(ImX?J} z>?g}5s+KU}3K=fLvT&SS`ls;^%daM~-#uC~BV8)iu$^FJ35~G7c=hdlfzr3{d9^*5 zJ7ss<3;8O_(a+Enn@N<1*&cR~#pl%vl`)uD^i5bgXaYxJ=iL9CFXt_<_1nZ@mb3eG z{E9ied~O2I$8R^-&u5<%%*KjPDkFN^Ibod20QI~U?E|X!;Bcb7L zrj%M=el&H^C61lm{L$5 zUZqj+E-zo3W1Oh0@e*petDQoGP0!QV3zcWE9Itmthwdl3x>(|V{Z!+*^oxsd{yx#0T}3ppHNoTC-2->d)?l8bXw!`Ol08X8(@BO}&RC%cZU3A% zo6C5Sn0XZ(T66}U{gzvG;t%JsdS3Ut)5mWtZG{d<>g*~nyPKA_wY)GBx|}mC);qIa z6TQiI^f)VkjiCaM3I1gDVpMa{-T)8qy`(<#dD#j7TfFmq6RoL>d<(n9MMh*bw%`@& z`3sxP@S9^o`wXQ=erd+-gu@ipocvsET_6j0MMo6avQ~dfa_b%?;TrMZdyJMZnC=fh zrm26Uv}#J}LWcDJ1=RKsOb*kkom}|xeft7mHUJ(%!PNnt6n=$m_5RC@{c%Wu*I35* zQO%7g*tC+6IPM5N<87GCAG0A4r*B$iwM{1xLQTpw1ah%aOcP4K#Bc9%dkp>3uuXv1 zaNtI$#rMKlx^i0608RCYM3M+!Zi)XGEolEB@{5&pdvvwRQc$WzCTX6>bR@H0dtPMu zCXpxKW;WWbKu7X};Naj-D9&&8R&4S>?f1t&27QE_X3xW2X91UDmkWiEH@cd z_f7Mob1NkcMr?$EdBFtErq(F?H(-0h^btYJm2SwOD^FA(Xq)VvUtu{ zTTv36f^7IIof55A>l|AUbyQ9hV`82O3zjFA8twhhYSd?B+ZD56W~Zi-_`IG}&p@h@ z?avz`L-bXzjJLJ1#dzOJiL5|ACV!8+kU#|q$D@q$(E58sJ!Rqw?me!pc#pT(9U zM5u9!8DHFrriaQx}W`?B__u5VG6JNrRs<0!RFB`gJ^5Gp_>b6UETUam6vLOZd z#-95;Tb(vDmk&Q0F3)ZQzKln-FQ3V6W%FTjE7;Pr3Qe|?|XvF!&%6-{3x=w6qs+QUsfC(t9P5)x5g!>Wa z*JB~K&qU*+MJjH`XTBjsu4a0>$)DnBxW)3DtPb60DlHX}H#TpcK%M!-8pY=3LO|m@ z^{N^Q+OF+kP1D5`sY=>Z4W&!@807a){}*9z9o1GBeT#;+6pA~=i%W|Y*H9>>cyWi~ z?(S|yixzixcQ5YlP+S58f`njs`F{7^`|f`)VK^V z!nDe8T3`ivaW|VIaY!q^s@GO%Het@Mwh^-BV*QC=zYzt<>irbW)Kafsa?K(^rX5Rk zz#tcXTzCa2Ra#cpk<=aEEGW}o1>Tl6rggbEnOmobSHx^?hb0ol+1ksEd)TJj_~Nr8 zIaAbFf;z?6vfr9GbFcFTpYV6nqQX6_#bQ^? zSMx{Wz^2FwV4Bf8l;{)+5Vu4!p)I$F1b zr^7Bn1o%<@mS@7KKopf^AVf!pSXWlR&Syb46}@5DRY0X?{^rEkd|6o3bvLIPo40Yc zs@gp)MKGEOE%fc%w}4the!2B)@Xe0zTu8!X_%zH*%hi5qq_D_~YU$XEVp)QLJWePqj78~dJo(Pe|nkuVX*nTFMT<*v^t zf4bc}sH{f6-R3wyWZ;q&*#aNl(nH~OY(@h3DjgcA~`Q^UBM06x($`%WG z@)1K$kHF2}Bu;Qq20&~oMSMN z^Vv=uMM00d#9ssn46B5tH^w7#c|Cs4R7n-gu#+nKt&Iii5IldrkO#F!7G8X*(q1(D zetH6i*it0C5kv9oG}(!Ncr`*tL8RzIVEks;Xqp%1L?vylInVQ?5!9Ns4b-^5LY zFI(~{XM69kQ|rpy;1}sUTRF`in}H7Z2(Gz#d8qI5s+Yw0B3J)NEns86)EaI6=7y*6 zEU<{o9;5!o7e_T!k3J#H!RfYoDdRPGB02qvtAG8paHv)Rm2Bgwki~N;J1G`AIn=Mt z>f+ehEwBrK1I*_w>nj_~Jv=!7KtVLiA0hrSz~Gu(Z;Bu?=&}D&1<)!mTzo=?E1~%*>q< z3$06x1$~YsuhTUYDN(JwJNEavQgkpkw;vx$_G^gTEoja-Z7(K%+ioBaKI4d?0#G#t zD{|;C#%B=0OwL!<`SWBRG~e6WpdANf@H|knOYEZaMf!yJNBbQokZ{KP08@((Asm(Q z$gd^v#hJng6S%Xo8UMad?YaJPx?XDfWMEzcb#e0aI_zvcPqLyr&^4Ke$qA+)Hc$Rw z|CmMOf6T<}?frbJo8BDH7GE3bJBN}hzUba%pTrUk*L2^5CJH2JGrkYDF;16& zT1}e#7M2;Y*g@1pDW*$u1+xz1<})Cq5Arpsru`RMhdv3O>&RJ}~X7bg^O5(Wn^w5U(TW z7JQAM49*N1D4d;s1?BE-Y^DnsM8EqTEVJ%+6(q%}YyOBgeVyuUa3!4c`!^Cm;eTGB zl86#`E8l!?%!#hGYMcVMe1&RxbTmeqoO<^Gk?IE*eSWo)$;-?cX;g$wPN)>=bXk2? z0j{W4>=0ak;^pDIFf{88@X5QL-HEAqaaTQ9?ibQC{U^U?r@(wzbN^SxTJ*8wcGvej zi>co_|7EM*Y!a-5n2(T1tvs$4uXr6YHqldtd#Ljm8jV6W&kmG0QkYsy><=NHW+0Bs zY93dKzz57z(LY&UyGtlM7$w*p(6z&Xgozbdq2=l|H>ugeGH&gR)9P`otkuP2rnA8^ zN9L1Ge$dT(wyOi$V6YhRN0nn27ihT7^d8q<&i20btt;U^dX`2%eV+mULD*DfQ@s<4 z#!I*IAU^Y`C@2gd-TnftxHIlLK4ZhHEvA1T7*F&^oSfqo?(yea;TLK$o9>@Z#R64XLEC)4qy#1M24L3u%>CRc*LjKyYn@jt{G%Oa&eGm=?r6{F)P z{xN$q^2?fTZ|uQwd>;7tY$9dO;I+Nd^TN_dE-GrXXihAidV%d&h=hUdE|(2)SeP|_ z7Oqkr5Z!E1#BsbAKwT7~ zpWsg54Qz#`E%$rSn)1c=L5HFPES0hRuV$45PsfILhSFzm4UZzZJ%9y3KZ_h&|MoyU zEsIfCLG|iqPDa2bCp??x{HTL469I=c&OzTGCnWf@xs_eGaWC}QC8P$xMC0zjEv!`T zi8CwNtbM#>whNEN_Vu#6-oR!+$2up|vItMbQ3_)xYuLOEe`ZWy?H|agreyQrJK7lQ zA$mD5Ko-hzv|Z`$gLKg-=GAD6+GEaS3_94xLvuv>IO&Rmdzb5X4PC~S&~p>pI8eEm1pl-vXuAB%D#-Fzf%d!&s7lbEX6>?-um z;Av?pkmf7=a@lg8GKSy7p($KV`~GQLW1m1VU^+XNQ_mUWv$x`lLD4V9W^O=g$_?6v zj&xwDoO>yCaSpIPqlnKMD?sghDp>DZ4!=Q;$lIui^dPQK!wiY$ zy>zY?iFz<{W?6I$o~ml(if3$0&$!5B_-Pc;LGd<>!Vfl6VH#`{lx|;NPf;8ivLo@+h@q!;LXG2JRY7+ zCqh4O3x~rGYVA6wvzcl z%HMV(1tbXFUux_ouVEnL9tblQ%Z~>yeI*; zC;W|e%g8x(JPhD#vw+g%*|#X>LV=>Nt2BIK)tOHq?}t**GNo&+`~3E5+d(e;@ezc& zLo)fwd>{3Ep;OV|HoppGZ5q5=+;#<8x*QrXyGQH#`&!$-$?(6&!qW8BBZVw)?+u8*gSl)K!t1IQX&qI*`+SFu7DvxKIZ=6b@& z@%@{XPnfT-H*SfS-^t&!lD8!^EO6~lZlc5_%_8ON<~@pbOos3ClH=djVx3-zKF%t7 z2NB;^RLw|j`wcBrf%W~|(N%ci;`q z-Ar8$OEX)li!&UB#WE16EnpeH$j5wpO;Br-T?g7PD-fu02Ih+u%qDdvWqw=nTypYz z5>`Oj!kZbE6lq4kY-GPpho~iUwWr&2t=xVNM8Qs1jP~p2 z18K!DLsSA)zESMlm3m;2YbH=Wo|#Sp+^x&s#NDt`s~G5YdT<^wmk6AlpQCpS8u#(+ zTg-M6;=CdN{3t#_`#|vHXL`rw^=(Xa^an8|09?OI`N6lq#c6q3q{C;d=$u997a~%U zZ^=Q*k41Oe-VGLZT;IA7efAmI6VdU9QeMeY)CEgH?U)U0Ub-fqD7RE64#rQtCgMi-;v7IT^>xBuV}OK~=SX4XF4XDVoX z=dKuPFbPl;NBw?o?EoKQZX$8ol1UdC7WZx>!Rd4wui24jY-&__xdzoJ3i>T{l1k2f zI4Wg?c9Ir&Is*c(?0`(Q%e&KB;K&YP%l-<4!Fo&SsOLQ0pN-10SS0W){`7F%dnmx^ zuzK+B@DteQvvCgy5H3Of@6yKdET=_J>DRHsCQi=E+v=>>w`0QODyT1UZf)Cqu2YO- zijg}`b257*o6am?mP%&c%}VjqC6Y z>*ZmMc&>~j_tW4%&*3-;mU$I@GIs2Wu`!B^>cj!Qdp{k)APMk|g_eN${HGCT8w!>i1X)1!au0Ktdpz6{RUqIhqQN&eRtI13#UF3~h?M}~%iRmAu z&)vI+XDQMWuR$99ZX_r0_7P5$1lKfDsjxejd&b?|wYSPZm7g&)znb5KP+9!b32A+4Va; zOb!R5h?DP=Q~>$~(Y}QE8JT^i#SDMDf631(V@-OwbTxsXA0tV|GW^fmH}W)`&C?4v zVYZ7v}H+2;K?)urQpvDNMkZ4S;70j#X9udgHCt2(-!K@RLM zBJ|jH$4R#mVaDg`fvG+B1|E1Lq>7qwwV2vEd8-8r!IK=pishIx#ypFo*lWLRt1fGc zEK(lQm^DA3fZm+V{ih>?j^)y=-GNOKN-d}kt_RO4HT>lI92z4qC@k9QHhey;1GKmR zBl4Wf4rkP>-q+fhlv)j51JuB;0!ywX0Kgy8Jp2b>+U!i(-5=j+Cq(b0QQ!B593GDZiTI&Pp9RLZo!!n z=4Hgrd)Ep`e)5djH7$qhN`Xed+$yL}uO6S|HMo-`MoKb7Q=Zme(NH=gC�C^Tv$VTBnbdux2R+(NM-8pEkB6$kkICN-O#R3(iQ&Q=W4 zJ&)5(ysXxTp1JlrOk}cptd*PAX6rpt3lJMY=+_|Q?y3T|$>dM;W_8$>&|cn+maHz_ z%*@Pk?C1Q75-6Np7UH=ohv0Ek4Ro}pouc$bWPN+S7_EY(P5(re@aVi@Tz!9Q3G8_@r`TJf+a$jZ^<6@05Q zHiebTVw{xA<>|5%MnG21loY>RlzxCoS6Y52=QSysTYcX$9WJM@Nl6gte># zd(^TSgF%Z{1)AA9DCkuT-(pyT6UGMR>?GA#g5xJ6yi(%RpkIy4bi^VS+jSZT?TSWWmr$dum>%PF^EuVW0V9_KN7=DBj!9Ef)Ao zpgxtP5(*YMDkkP6)K61W^Jpr|Q&jO{+jMFNz#fhfgT>@!0(~3HYt*z9U(Ho)_I@|% z1fjjbLiFVNu;rep<0*L5=8;i+vNs%;T9_1*;di#yRuLXvaxzL9x~RoO(CvZidUHRE zJ*>ba&5U6A^LYnb(D)f}`yD=v>kc@6^wSn(>TNH4T78r zh+1q`KOga;aLZGPcs2f%uh#2W%998;l6{AbZIAFyXRAI~8s;p3TR*cr!ndNPHVrmp z;ytb&EvfvjmSvAF(EW6wj%4O3-Vo4CY{j!5)+5bI3i~B9KxuPJ(0k*F!d=qV%&*7L zk5BRAUY4t^_qR{2&CMAircY3i;OozR?Jb2>JVmghhTeB`T`i)Ps`c}1laDfGs@2*} zV+7H1EsY}rF3goRXcuHTtl2$olhENhI&?n{5XOB^B=Bf%I44y216B^Qhui+KEKd4m|ce`sJ%61B__ldWc^E{kWqX{ z|0@VL;r-_YuZqsWeU(}PfbK+2qBr@u%W*igp1tS5g#}X+E$f?nyQt#vgla`wCcnDo z@x%`h@@H#m$t1?ZSZ_feXo#4~v1;~x;ieV5EBu?c)n{a6TG7$gPNSJJ-kwQIrCp%m zxSlOq(N9}_#fGZH9DNwwZZgC4zwc35zCM{>iz0u(9^&I(oaaU|Uc39R$=U4l>+Nq@ z(oWq9JY9<^k_If7RA7p?xq3>8r5DFh2!-wW|ISK6ANK#B=whRca~&R)H;?Y}PU5NA zDhhql+Mj0|v8YcQR8dCsXj<8l1TcTgpMTNNu_KvUNi752N$UECAj`6@NxtYpc6)#_Ct{K1f%at_AnXv1N)}F!2v#vXQU1hxa-$ zXJB&ItB+}+lgTZRuY_8Mw?|{kFgiVwtlz)WiwkV4VEadLR6`4PTI-{Y-LHHD%Y%N? z`c=PtQ*(BQYd4F21eGU?*lzX3J`~+phCnsomMq z=YeF^XX{`VT&-T0bhteuB&jby6N*beJyfBB>zH2C&56ghprs~WMh@;0v1;pfdf)=I z8!f1bqMSup&cwvoQp3Z;iFHB{66tqBNi;5l&h<3#^;p*8^G*SUEaoI>xvb%PjPoXrb=FeYgacoXu*6SR;(gwj`UDwt-Xz@d ziETp7@i(w;6STHL7aZCYE#l6~uXGv#gOXa2(X38c|MLu8ueO?cmbyrV84ToGRqzda}EvrYz2r@_n70Q6B$h@U?kHBRMYVE6*}{^-Q>M@m8BfZq zOEs};0LuK4>Xu0PMv_%1|I6!Gc+nMB930_8I~94=CrAv}@S>i{Jb3i;>2DogmQ7Dl z0kcSN4#N6kObGp>*rn&SdYXS|nx;x(PZ0ekv7l(_ppsge^un+40yZd_<>8 z%6lW5%szd4lxvNp|2VirbqLjR(%75JHGLEX@!pkbj0uw^7X+2uhw-{(tTgaa7s~6U z5;bM9ZN&kd4i4JLPApH-u+Wrj71wX)wL1hfi8o9Jvn#W&w@(*E!Z0Y?-ND%!bv3{4 zT^Fj-*K-3U$~B-IaD@{$!g)@oleAPCqNof$dpj?sg!FqDEV*bz*@*6QBn*zMt}f|= z1`vxfSt3-zzxJzbXvh%tZ9kEG*P`9+OWUgVXgSYFthBKZ$9UjFjrdv*CZqpJDY)+c z(sfCJmgSi~P$H?v@5xZrw+lw$u8f{pz2B>vBoM%6rmNJ;>b@d%B>LZ2fWE2FFa_S9 z3(e_sGNl@#kcVKig_g?~>&4(ZvRbFvJ4BLF)6HN{w?@*TW)b9#tnTpU6U=}Lv7hG> zki(5DLQ^JKN5?#zvgr-E4R)(~4lhzo_Ha(sGt0m`UTb)>sdfgP+%pEB9?|h)$TwlRSW+A-J1|F8uy`_OXX|qnPqP?e z%4*68jA{JR{8U|@-U)-;24`jI_3_Cj#)iLXL1)%EA#9c0x|%teG3qBC+;(c{L@jhX zWHeWXe4`~k>aiKXpslO(d3CN6negD2-r70;x4b(1T`ZiQnP3=B^TashkI=xu(m8wW z;1Dl<+*4VL+q<-ch}Hedhir=GVpyafdTuQ(^(Pr0Bn54Kv%l|Fy5zviYr%?zA5Vrn zz7;>t>Lbcx)y}N=hWhOOgTRy&1){`6fK4fkii+y-%=i@|4FA{nI=>-Gz3mlh)CYsx8qb$c5V5z*?n_f1A-%$ms1+PdNglaH@&ML9vJxa0X+ zQ_yrdQ-)E4MD`JQyT{;S)Bx6;@AUuIp}4^80H*j9q@lBQa3r`9qVWn?O6ZUAE+BO zM0(1rU;iKC)Qmr>q!NMXU()|WhAN$_C2YToh(Jx2Nlr*m&MV4Qu4`&iLmYIvyVdk? zLw@0rkd&!cB+HnpX%v#LtgnA0_(jTNrRpjzvYa)hpJUtff$yQQptZTc>(r6Y^tSQuF zw3kuUcN6B2KA*SLs=S2W;P)Z%0xGI(+k`25YciTf2i$o+vj6E%|M2Yd8QMi-?T&+C zh?k-c$_)#9-7txWbgeXfFPcM80a8?walBHyUMs;UEMAEdq9N}3I17qJ_ZlpQk0Wm1 zVN`59H$P9tXQz9nU9I1xt#JEA?Hx8Xi&Wjt_8-y=7n|g}gY$`2)L*!o%Qhb|EvzYK z6n=s&Ul1q&milzb(d9S6pIP>H(r&`dxhS*fGyBE{6?MC^B~sHWW2|RE%M%Gs)+ zWaw(57+I)ltP|!eh|w0{$oYbrEPqA(k(uC^Oeu;N{y*xk^c;F_I>#l#sXk76bF+kZ z=R>V-Im|AX1S{>Y!3pT`mclcVqTDV`|$5b^^nz4+s$T{mH{MgA0(5OEP~I@Ttw#g7vB za-@?M>TBn53r)Y$TX!XC*$eD$1gR&9<)J&bFNEBiP-v`)%d%cy#GcH%Z?L+8eu>Yq z!8v^U3={PfCiq*1@?ltfY<0buDyjXwYw)W{R(X42We%V1??@+18DWN+(SJp2W0z=H(f5Z>bQmskQpB$cOY zD1goeChz)pKsR?ndHu?y6XqN_eLlrONmW!h;zYB;1`y6u%)Tzv$I}A#I4L!sBp-?2 zH^hvJ-4jeE+;k*xyX@{sv;H`E#(ZCJtl;hZMa9@JD*njRm#xs(=}XllIGQB~xzldj zswvlp)RyiqYhI^qeK$GL$MYq|XrRE)pNmD%d$Mz1e`p^WFqn8bF%l1bvLwLWx?!#{ z!uH)0fMgs4Q$*LH$%U&9Epd1EY;703UIp?MxRqT}FsZNkzHSbN(+qv*I=p0c7s_}j zy~8=W?fXAmc6&fXXVJBpRK%5Ut-*%#Rw3)hG2OD&9r7#8mY@tMSWa={Y-cVH#(5<{hwb+L-q+ znEpUWm9D)tYB;Abg*xo`B5P%`wGI7~zg1_;W1?v~5{TDltD`vS6<{xsOGrhxTqpJ9 zuea#M?p+o9F98t)hUM?!n!m}p=msS%+nDycGQlu8X+zOq#B@Hs?Q$(aU{c694yVIW zh8O!w#I?RA6wuB+oi0_J?Cr6P`uJJhQYBwD=p1HIH1zzqgP-do6n=|X!9ollxyIY% zL}3@%RMmeqhRDh3vC@6+=iGfaJ|ciU5n?Z=mn@IPB2Dae#ot8A+m7>X8vNwH0k$Q@PqkC}af!nL=aQfx(D@&dH#l1&+@GEJB#*-(L~#f2Naalm1ti@dD}}nD*TZA(w_Vu`=6z&Y~w+ zhGe{FT?r)IW_^|2JVmNz{ge1Ta97A#5lWiqCgVgl&M9-yf-LY;+t2Mj(cQ~HXGg5_ zZ$83h?yPNt_kF`*HQIhvSDCAMvC}X2HWl5n!_meWPy?PfF=;|gl8_vr%>yV_t%Di8 z#PzO`CjEF^>W&KS@o4+V=I3@Af6+35>*If6 z;FfTa7P}4q-37zRELJykDzdxDvDC@85!26|*Oi0CNG3!28%=)m;M9an?OQ7N>^}yD zS2LRrrc*=+2`fX_H@zY-pXo}Cu*WyTi$UsX*oD|xtH7FU^Vb=#Kq*-C??RvZG zyvH9MN3C(gA*#fL8M&t2f<1eWG5)&am#6$zYaw=aip}inP67guMRS$xo8vQ|m!p9? zD4XxyEb`HvN-B1xR*I~?Y>)+Bfq^!{)mw=ONh)=NGB+UsZlLb$0?c47=whBhoG?KP zC7*F2c)lycJrvji7Is}aHdDX=yiWvEu0gK5uV?EYHpAj5Hs<8NA_a)PZ2M+3Q*@TQ z*erQ3p!kxl4U+4rdZU$LH&!*TChY0-x->}xc7bAcc!7L z$D6qIj+9U9%rpr_Qkz#co6Lt3b|sWK0NT>~fMJmykAF(Xg>Dz(>E#q_1J?h_bhv`a zT&?OJJJ<_C9sBKa1hjN3zxMsX<-fhBJG@!5l3$b5>rx79?j)o(K*T~c>u3Z76tm6E z&H23VY!JAV@^V72^{aBJaK5T-$6Z{#3Q$DckjrhN5}>zeL#Wkq;NlXsT>Z!pf5_!} zhcfG7Z`#;=YFpaz9SN7W3^@Jp8b=_ozUyvgS8X_ETxdsK}l=P z>vK3k?W%(1+r6J^U3aRcg6~(sWip%8j!Q;NRmtlrokJR36fq74yV#&Z6%H@*nNP|i1nmFFsv5v^%guNDYa2NX@lclDaQX6Fu9iq zoDlNAX)pekiftAR-lw0MC;oO&waxcb`#2%1^#jbAxMgqs>sMGvg*Ttgn*T+S>yK$A z{B7*3q#uB=;UmQbEYIz?%IsC_@d}zi*xopm0zEL5EsJ~+x_1!#O7rF5fTQA0wqlm< zb`IM>_xc3vW`1=7$~PmCRhLJRfBPHk&KcJZQ}6fA$) z^LOgYB=P}IE*M#P3piQq&-8j;TAU+etHR~dHhQWTH)Rwp|Jybhfd6fuUrK3a2?fPE zf%e)3!`E*cPkO$rdQ6lUcTP<`?Ow`Ket&qzFX3^0nACl_wOCHvBc}MZgM=}PeaEKT zNh^B!9BSaJ3Y`tglT{>i6EA0b8Oq_?bp?FI_x0Mmk8`)siOb;|+M6icIv;wTYJ^)% ziGjLQmS3vqdKtI*y|iXr?w<&AdWLPNdLHCHBV7zq<-`i_bND@1W8y#M$1+*po&Nji z(QXaN%~GA7?l$0=g`Y-ScGOR;Hmlymj^ZzMm+ENFC%|D||H60fUK3U6u4uS8Z6 z^hRTkcjMDVy?=s}9jsOWdMc+2d(O`ulBex~N$t&XG`6J{dPQZw?pUf>t@NcOmcAtt z3CB2D&yDT@q@bG4-*<6VubV6C)g9@6m2um?Iz0+cQG`K~=v?|Iw$vXP?#|mT6MUB= zRn|*ta$26f-XbM9LXRTBU}}nD_B7zi-eEtkL6*XPV4B(Fj z0+w8;lFIBg6wf<3s*lV$?C%e26qj%kUXE{o=>htQMC_!8K3)&?dv%`vI}4o;N0)m9 z#_IS(?7|qVQj-rH9UtGx(TDgMt&1*zlSzMarET*RCn zniYYU*oa!L)=RU#FZzYDIo}gE?B$Zt=`uL%3ZBS*UN7i0{3!H8+0E4pgYvV1er@4&VGWzkRRRTz z_G^wlbZ1|F>@Dr#loc`jcEZ5ULf+I0{Nmg!x!%6i{L)~AGZ(Y?YrOaxVoxuhce=Md|)Q- zCgHZB+Vot4uuCn^FRW>$~^Rs))h4s=kJSbucT~dOR(m7JITzjb0Oj0@zBWG#XZuLs0=wXF z42z2)t804-G(c;`wtc(ByeZ@fsu%04`(a{#3DzWkZqzeYSO>Lg;FJZP-tW@nVV2AoP4 zVaRh`q_(xEkkx=kc9(yKR8OO)KRL?x@-?@$mon^yXK$Qe0~n4AJh>hgOp#tOV8JbC zX04qCUFuocKCNKrJste5R%pZ$oZ75PyB_?5BT(9SPR#B>FyPwk4u-+dK0GvPOk?uA zR$kuz_1W#x&jn^*5}ziI5dXNyvo-Y(D#&^2E4K$@-n;2J$m0f#$JQn*+h0A0qki>dB8N9qh)XS@ z0QL$7Kv*r=PTkhIuX=qQwqx+8gtG}2awAkGVHzd8wytodO8a;+O#Rm=4>wpH@RMBz zB!&J*B>6S&+hR{GTl3k?00vuaZ;dlk%cT6#1zVKYEj2nq-J3_Ew1=P4MGAi-5S0Ue z+OESIlf;~~*X>`bcpnpyFhe>OZ7N(JbLf8$@xm`)oPH}|aqT<_KYmz0gfxh>gvD9T z-!0u43>rhDF)?uf_tPGJMkCcx1L`45*GZZur@Yp)a&L0I-~HpT+sXf3RmrTdR5x@t z%swA!ua5Qwb((}*yI`g1%VoS6K=iJcef_vjsN@E<@l~k~HUOZlsJBKMee!O$Qc-?1 zR%p7h3(YskFfd3sXPZA^&B+%;S}i`^Z2ROFt$wfi5$1V_OuJf98^exW|eE*fO)!ZpIx1G=gH*oF-|02WQ}jkKIzSO zJNN^K(+U)IPxEZmMqVor_P}NOVPV)|F}5?KOS4P3fDzPu4b{>wT%{QQ(GONI-A9=s)t*#(3fPgYUaP?OCoj ze3M7=A`mvTSC! zk>I7wnCTvvi~({czNEwSeR0Ktb1T`&a`c6FHvF?zRy}yW#0ed__9k91Y;3kbyqp?Vc-Q# zn$*CO?P)z7kBw<}l>{ErpZ11SRuWvg0J%BKzCYo!-%1%i+07Ft{|pE(d{RlLA=CfZ zaK?;D)d2MOb9$U_wvB34!j|s12SL*c{K>X9Qjxcjf_0jO9C)g{q5tnWV+iArOHGeC zWXqS(+YJLSh*m|S-kYwkBTYU3ldhN9{!Evjqj0#9r$^7D{Aiv>%Y9|cGoh<@sE(Al z;?pd0|EGZ;fL^qaS2!F99!O;`+MLTLk~;N`KCj(;XgCNeU*t-H1<<~to;k>Z^e#x<+1{e78q? zIhzsNoC{Jkc#&U?atwu(=bJ)BGjsE2=MYK!>JPS%dz|^L2FWP%j z08?Nu8h6^;env^D_r6`aavCO_v5U|D?xNoK?nbTu1MireN(4591BD|LSXu=vkj4?! zdnE$RvR$p*XYE-LWCe7N!V*Yz{| z7j@SB3YjzeR#2Kfy8|za+#kFPTOo24F#wCco5uD(+6QGh+13QoCb3D|@6S_FI#)9I zyZyYiu4?g6H?kIFeXLQenFQ!qE6vI#O-Z|ygEU`OBLmGiXF1%#a~r}1Kj|A?}Gun?c_ zt*d;Ib6QT8qS&+;-m{4*-YW|9l1$EXguOhaMO zlF4cDoeUG^IORTsA{55&q|tO9Uf3ZdDEaYn!?Ba>%2i!y+wp!i70bg_s>paq>2PxtLAUTUL#dp*0!K> zt@&C0K;4oXB~C`+m^^hP1gwVdHpXx+Tx&YmIZGkq9VN8JTdSsWyGmv5$8kG+{LeMV zwMspmkRaNs8MB?GAe;AW>&wpRtF^CfQN}-phom_CKn&anU4f2~P~ z1Q6vE6vsJMOTh1qs!FyEu9oJU{X#)Hl4bKHgUMZ$+vX^TAl0Z&(vnL1*FoqAUI@8zJ9mYbBmPF}kE}chvutvG|a3HZgj9J5Iltv>kMlLzd#ZQKF73 zMd`B9LpPOeKeqrG3<$>CSJMJwWo#n9CGTE_D>&5MNe)7KQ^V+{-8}G?LgO z4CeIT>qa<7Q^$J4VQ*zf7n~da9btCZGoD7jUA(T~GdPXXa;AP?^N*Us&K7pC&y~z@ zK6+)~7kNC_(|04X;|q@?tXw4WxkfOc)uNC4@MZu9jMM$4a|5rHTE)$Ve-!8K3$eHP<= z47r94@T%?zeqXZsR}Bb$Fuk2X!X%f;Iy{WBdKpNq+oC4+1J1M>&m3*E{41wXyz+~S<_>F z@g%YZZmR0j#u^3y9*&l4MCDW~^4Tv|o-`(v^iEL&&EE7nlILY<-<{X2-CgHkCvYvW zPus!;Do-Bs{M5J3-!`|s%qxad(VLg<*-;2M>B!%&_zx^nWOyIy#;Ldnewnj-@hy?4 zNT(OZ{V*@Cp<+ZP6$(-FNmr;^5+Yg=By=LY*GZl`7Ks{FbV4Y5B^gI`gGHV#_xhxm zy^PJA{w52-azs=~m@yBziW1r93`JF%|JMlOh&@3{2 z)A%`Xd_D9XT#3O@w>9=H!G@SgkSO$b)vEPW#Bid|nXu5Ob{b3@I)nsO`7-)Wx8>f4 z`2i~EP_4rl9O0taqk*&*qR(}%YhJl)^mllIG%%ZpI z8cWD9(lYN}pwHGFZS6d|cDk*NJyf*iT&LlaRd$mW zXQj1QXN||u$9E~+3lGt``>Yq(8G~VqQaq z{kz}me7XSk73u$t1@Ow-&Bm0LevL9k#`b6qi*R%80=XN&%0Xf5j~+zuiPvM)9(O}! z30bc}_YdK0UUP;6kQY($pXJaeqrHG6`wrw*^ zi1;14A-0S5b7(D!WaBYUM!-ym`Pg)YPaJm5`M#?8#7R5+(b6ZLN3z4^+2`mJ$kw+r zGxOD3`|gY+yG^GXpVTVqspi|Q?cW!RBQ7bjb}l3OsaHExADcIP?&oX0>=0L4%@Yo% zCcE^^s13Ym=6UpiZj=R{+`JxY8DHr8O|_WhfwgMtMyoWAJ4wTKIw$QJ&cN12HE&1# zx}#8X*{`OGSmiq+#2LT%vwF%}Z#eXG~eWs<#kxvU;(>^9Z!VqQ9Z^tkht4I!vz{fJ9Y;r7F$ z%=e5n`plR-8y&4@1RwGHuO7t2a+&ud7KgPmU!Q5$3y7`YOIv@sqjCo0aNu zPB=4TzWg&&nQl@t9fTbkOX6U=5;(2>D~7xzY6WK4!}VGLOnNB)`ZCQbxle|gP#JNu z;w-GVRsU=q2s4)AT0H4&(#>Q{rT218S71ujne`-6m`B@p`j{^3>BjCa*uVC;;FbzW zZ*&>crsj2};!)g4%%eDO5hZfv4|91QB?wOexpY2Y!bM0`f6#F@IHeumT zrGjrMqC2iEJnX+^SCr)oasLNGs%*HGIEqPP)s;N4=A)O%D?ceq;Q7!L?|M3~mi8)b zqS82$TB3@0q_W``0ty3KBba&& z|6y(aWPbT|yvP##J=^^IKIALPcm$_Jk?Fzb3SkN65^1%oCEmGLuPcipQn0C-uAc>- zh0Oj=rn^grlj72#3}S7gwCt2!d0MHB;*8yxU?n+H*w z@Qg&}8ia`Jj1nSm(}x&U9n77<%V-p+o`g83QHLJxAk~HjKKEmT5eJ7FW!I;L$I;PA z3vxs1;z`q#q7h~D<*{7JYRqXdYMuo0?+PJL(pa|i{|{|n{ncjMY@Jd{@#0b_#kDO2 zE$*}gclY30+@URQEfQP`#R=~2R@@zmySsmP->1(x@A(71wfG@xWrZY@nQLbD-q#G1 zYb75|%*>k4I0DW0*?0oZ4qd^!sYbq>p5c&KD$80a;@~#;ExoFtQ974HU&-5xPnf_- z8`sy~-Y#`gDI$ zyf%oIMnEGeHaklj3TM3NU8NuTot{-UKWiV(PHOqvK_!`b)O;4H0$fZpn*b@84a{%Py%I}3Dc~)6IsZ zT^a3uxY%(FY^wz^icO1Q&jLos$FTt1D$;4fiT2wKHj~AyD)KYhTwmdWFh9(5Bqztn z#25AzQggv*v#}1`R)x!tx9+Ep8;*L8bnP6uGTq*SHUM$r zPqJZ(QE-#XZ_T?8pNwPt7sX?8-IGSrs)_I25@O$V=iaGiGIti`YfpZ~%7?_j=3Dn< z-&80inKR8PYinoMDsuY zD8#L7bT=q0ER#O}yVm5-e8=-070}W7dErjT9bp1lZB$g$N#gE5N-UK!Y^HRS$jC_d z#wP8kOs*#sYpq|OtE#GAeFzNk2Xr-2?Vj1F1_IGff!;g~*qVf&W)BMxWM3h8X-mqB1{5MA`oy zj?I`H@kizK&-3}p|5uM@$Ak3mQ$T`S{_hFhS#8@ye_thnoDT8-@3(}Z{0Jbcgb^q}QV%&Wlf&fa)mSH9e0N=+M5QSuz1z;m1;>obRu^bpimq8_Kzw)iP5=c-#gMjVbL5;UU!+bwnTeZ(p<1>ew9 z(9kJ2GsqV!YJpy{Bn3I4cVS8&Sl+vvL~c! zp2!w)7P$gB?3vz{?=xRRz43>Ov@hq~!+)F#pMr)aE5E>Zm?XS#2ldAzupnl8D+Wts zOvBV%!7+8L5~P?Ca%J9@BwUh|+02COyoB#?p|S>)lq zM5m1`k3B-ApAbH9#~J)ke``&%$*LSy8B)sG2m*oA^0Er0nO6`axS7#gP+M{h;g$L{ z0n#9rMi!7IBJC1yRTp9ak=bI8Jx_>T3(03Y{qZNDWpuwyhD0Px*NC5HFW*x=i*buf zykWe2CjM1HPE0Xm(=QP!YbJBrMg2WKTX|GC{!pATNLq<)n;iO?tC6L!_BYx;!SoAT zw)+PJ=J3VWT;l6sDq?S9;<8(aforO%S>h4j&?$N!PMZ>5l7V%BG0`OC4VI+Y=kM53 z45jGm6xfo2$a99KEJ0yi39FM&d^>WVfC9K)KBG(r2J|B{Wjb#AtzF}sS zF~esO+x|pnnpiJC6MSw(4#PGha6SDMzu4=xbVm8P65Qz8Ih(L3r*B=>Gz9gDPS^OY z@jEOG160yN{Mq0$E+`Jfnf;4ep7V{JVFs5E1=4+KZV^LFC8j#nFmu>so`gi7LN|HP zlqK>qis>49Lb7n$oDsW>QbnX4d;2h7_b2T^R}lp~FjUbmXEd6DGld|8I5KRwpGj7G zI@^H3kXm))&`t;})UWr?#sFn(;Luaahl|pdD;c4BcRQA$i;uC(;EI@q(E4Ge{zOC& zaUBZ_uEpTbK1N^)ulyQ`&;L?y&P%GIQddPk3%!%Y?+C9?(Ql~E(2oVwa+A2Td$?;r6ZJ zaJgUKrT-%U?JP&ZCK?}I3NIHt)KW^HC)(6Kc_uE3#PLf%208d8u7YqB(a7D(cX~`o zQk=78T6cvaaEPu5&d5AES0YjG>NvT(B&A_8LP&=4;WOj~uk8F;kLE+o%Wu^d zX8M3DC73V)#iYz6&WCgjZxgX~3x-z@-$?E!p}%X>rHoS@)qba}gv?bURPZ zq=lTY;i9MFSW6B>*9`+2N~ih)`5{y?X>>c;174U{7VO}^-yHs~loXdc|BbaOs*V8Otkylpec#5EL=$T#Cro;4K7pK z3oi#9dIzhhMz0KJ#cFDj5C#y=QbGFJFD7B-XK~~r&VckEi&)9Hdt4OyWowm!E#Ze& zD+-g>N-1-lWf3=c7P#}!*iDd98c6ohcU5is5H6xF%DzenO1M=qpaHoz%kbvN-hUJ9>w~CgGq(x)0S~JsHBLBQ;Bm8b=uELgi(wX zm4}hc*Y!|`VKFqs#b(POu4eor^!m)HW8CzuKP0VGRYlxCMnzn_1<5xbOQ;KnB)27V z4eg>~t9IaqZR?q~*j;vB z^VJseC)=zDFW2hV-WhXg!MHwNfZ97i_>l7h_+7aO@2 z9LGKgoJ8^-)EEIndVrxZ!2!Si6Q7ikkD49!(rZNJ9nh?%fgm$*`DmHG>aqT0TOK2} z<@t8jB{%ol^U%xlp2gN)NMsL$*eblWjRdY`Cgf87yOo0SxN-6=J_zf@Iq2i7P$Q>= zip_qpP>Dg0enNrLeK#+f7a$otHnV`09`rB-kumczHs5U1c>Ct)d^s9Qa zO`F-$KJ0{?#}(XE$H_6lqt7q+b`-wN0{dCcr}TVo_p7Vt_7f5ks6OTWbK+4(s%*x? zj0~kN+N1Mdfhw`antCAyefSA5Q0BE&YDBt;Do)j;jFJnPGxuxKr&y7Mf_nGcUdlxt zF-Y8+a*At@!bql!6TnptoO~1(c>W@<6bk4t#rUaE!_yy4)X^>Y9}_{-n^8r_(85?M zGq3GHxu?St&KYFL7|bxD4+Y^?+H)w{C|aGns+7Y65s|vi{UX>1hC7^D7GDKImG~hh zC9FXF!h>fY{-zYwl%JXr!Ea|G0lP}En5pK|GL=dq zRWp~B3Y6o7?k2*l>RRApVg7@WJF_=p3u^wF%%YXu6nsx3ktc)(Fg}Q(s$lO=n(^U2 zVO%UNjZsHj#UVi~Na=+i5;;Xg5rq3Ge*8FExVf!r$Ra@~qyvh7lhY1SM<3c`F&7+Zrwy*ggN_5(7XD*GM9$cS6qu%z2&K{Hyv9|p{X2ByWPh< zO0gc_kHLHg(!ihg`NjqRWuHPl3Y4j&x9kw;>B;{;YmMe$I{pe8wsNywcw zV6n2`2P@I1^3m$#_7=zMDob2mOGC1k1@r`TtGysAED(RDqv$a^Zb zVClA%t8rVV*lobF>8g`i;Hc$kf&KdbglRX~_9yI88eRm@uzaLOgvR!FI;JdR5+*Jt zf5CF2$j=ZdWM9Lt(ok;ns;??c6KY22U=pK38IicaZB(hQl2YWv_&^fv*bqK8?qHQ)L=D6Z0O5zs?xnduq^Hc+%-9i`B9Lpc3 zji&ryubf}`lGn|VRAHel3A4U_r^KspAI9Z*H-kC<+3EM~{MHlGs?;-Sl}K4B?YzZn zO2SR$jyV7Pki!5wwIL{0(HkM^MYqjqB9ou_Z140k;uX_UGV}K{Zrh5*bjt|A{r1!N z)9f-S4r#aZo3ymFx(}nFE>@2_6Sn3lE(Zo=PESmeBjmht&;94B?iUNvKJ8Eqc`e-* zF9C@r!8A3&SR-}w`H~<|%KZsHdq-}{W53T5KS#{i|9EfN8#&(n@jt$+V(ax_P9osC z+x^0GH}+y~$*=n!n%ntC+^n~0XW;5$bGF*^tc7Y4$nXzWD}P==Y?^$K?9s`jJ7UEt zdg!v&jOf%nWaym*gtgdwI0r^FjKCCJj?>{X0I@4C)+G&gY#9|F; z*QN%gTST`68pZ`|=ifk!3>DSpL0Zg(93z&fJl;4aslq6;g08aVOiZ%8Rn3COo?P`)M5qSjw5u zq}Iff51X29{RmM~m|=Eg8SVapVJ&6AJw!db)@QG8r@J5SfOOqXSJb%v^FzDIt>sW_ zG5=;0+Pm7dXK@e9Rn~Lwnyyxuy|$%F6WIUp+_jpvCR_JIEw%F?AmUlW9=xMlYnzvi zRP>Cg@yxy$KjkQos$*4#_TcZ?$Ay>GP?}fm^#oaJFj&t#(GRJ$d1F>eJ{lDSbRe5t zLMdqNu>4UH?L3b9d4I_)#%ZzF=Drl|&}-T?$ros3m8^d1cQY*b4x>NzTS@J+{bK`wcv(KJ)7{~87=2DTY=;*o1`fpLzbd`8>dhCzhTl5{#Z7zoLzctM^Cu$)44ogshI|Y!D%I|KEp?qXCkwTfjsmzm zPomTAj=%YMvNMzajq)H~j^h*4k9~?hr(z zF1l^%&bgTRZ@(>`aOJyq5u1{}xBK1t{579qP8ccA!e0E263{5*CHdA(W|lbNk5hg* zB0Nmg2$m5sM@kZEm{qpwTJf{itoo|d`)MUgLbLzIaeO)kRD-auVfZvsUlld_YdeF; z8+u=xSeb=iyNGIn# ze^K9bJDr|`Ec0$ld`A^rM`NWvV?D_csrCX^VvvPXFY_^Q8>tC>rAPgInW?`H;@AK3 ztj)57WojcT)V6<&*7r2^(Z9m%o2=mbx=Vp~XsP_ZfzAa?6EHgK$Lv#q(qzrK$kCU$ zjBh666=4+Q=fgIbc#%QRgT$1nY4mUcFJedCOv{n9w?%Hz{R0S1@{9ers1-15L8z}{ zMVhoHi}hYxfC(RdMZa_Js@A(sdj9&Mai`%hrSn$sYI{@fY)x*_js)9lOZ0UJKkMI| z)s0fXt-(+Q{Xk$kG9uoW3|Hm?5_>qcQ@J9C27_bw*&&}*8BY1J@l1W4xS+jwxgu1B z$m)3kL3_auUKtdQeSTsRP2&x{mn-RHpgf~b@ORM{K~J<5*`jVToqQAG)q8QDrHgIBT%PrTj`4jwD#Y26IQmFKx&Qa=x7~)#(#DzrEFvFkPmfh zEpNV#A|zG4>0dtDiL2@G-p|-fb!g9Na=%<~>DG(3VV<+}cr(0(Nr8CB|G#7L^Oq>8dwqtbCqgb-hk zD=%tG!ZYCwwsBHEBl^S&hW#{$Oo155Xx%v}EQ}bLx3e*v3hL*ut&4{7Z+s=A{H&hw z^D!+LGNmXhV`<)tW8SM$25}~)5@9fEwv^b}m>?Ct8AP-Kp!>i(lzK{smCXYC78F*x zoPh2hf7EZmx+3ZnfB`a*oe9k0A&OxX7K^oJdH0M9mn}iJwd>_irv81|u`}SzznbnA zaGqgG^%!Am@1TUyD*4{v1w^KsFft z;loecjP=}YKx)CV_^RK@$88qebZ5|xS^Ol8hM&|Nicd# zXQ1d?(Dl_<)kNjgM`9ypGFC`{wLxh#pjMD%I371&ol1|pkRsOnZh!vQ9eiQDQBREW zklf1>dHf(MHq>L#N4~t`I3tl~P!|z3?Lg|EH`R=@qBB&_+u^$Gc zO!y4u4Jk9|GiQ6bV&2AS5UZq95gA^UGnQc;is|veTevu!pqA&kP-mzEsKW!5LkZi^ z#02Ftb3dY?Wt&4HHHuJ2GPOAixU|$NjA0J8-@_8f6Kaq-i8sg=$)WxJbz6m0Nx5-%Ie-#=a--fyQ}U)LYh?IsL)nvi}V`dimol}^d* zU%w74^|9)Wc=PR{7or~jqjVaYCA0+1!g}%)yXK4UFSxRCH?*knOD|-Zl>p2nPWd5b z2j3vIO9U zf4P9Mvkl`)Ftc%5zl?KgaD1#MJDB6tI2V0}I~Mke!C(iaDWcyyY(hL~l;hT=t|HRe zL?$8H6*z#)m`rH-7TGI+IdFYa$R3h8nj5GM*~8j-Uw36^**&BC-^#XSxevr>hs z=7+G30RBRH!}u*X;kSG_GZ+j+b(f}zQ8`k1skup1SXku@asuK?WJC+$ngcbJIXAB) zZ;JU{kBu-2$Rmow%kV=PrZKaD8e$_maY2)4u)iaYrPOxl_I|)^{tGvD6=!LL=D8$t|dSAB2K%+8Aw)*-x6|k#fqm{*F2VG_*R>TTU zLX1(D?Dq-9_Z6HerJ)JQdaVTyb-P6#*HX+6DTHJ>*T&8FZMWW+9C5mrpM9FPvy&pu zEB_Xud~j~Kz4RYnN`lF#zJ&jr7=Yx9w8F=K+LkG9%-)+C;?goQ}To)9?uH)#jlZv}fkiWe!OGS?fN9mW*PPI?*Yw_^y;#J;ti8W_Hd~iazK@t{NOR57IgSB5wdNLyD$@iB* z8Trkb*>em}$-&z0Pref=xr3z>DzoA`?8^9x|6m@>KqqwQb;!$G<#Qf|rsil#%CCFG zr|q@iGw(3;&HK{D=koC3;E>GosMW|z{BMSOp@i8;iVK{@fi0|bOar!pR%KBkhq9`g z0HSgD-b{7WaIs1?0Vbjs7J{hNVNc7{xfkEFtW?=MJ_f}@rKH4^F%ZK$=(vf9iSP}l z9bnaBqTS83G>NWsFrkdTkf?sqp5gfwfVp!65T_JBx=N1A=oihBCmWiBSG3-;DHZ|* z6pZNjEy(GKep&p%T=tFgFInj%h37Uc#Pq%~En>d30r9{bY2i)dStl`ewJF-rVJ<@5 z)D@wQu4#5ElQ|+3FFw3{mM)yYI_aph6FnT!tf>wxT>G4a6rZ79cpf6I*obr(1>-`Q z?un9;(xGcNFR*pNRQo=b0;RkAg<5l^)Aj4S$->8nua^y*{M|R2fAJl%CQ?UIEPfOy^lrQz%y?uCRV!g$I{P-etVtK6sh5HYCiHO2$sazPycI!Ogl@h8^C zjc5vyOF$w^kSYYBQz2Kj(DX zu2sqI+-XkmG(oO$SLe|Ec5X?4jm-gGO#ipJS?-~T1rSGPsQ(*d)tAXX$8{76>x=@D zU<9(N7N)E1a%6X}`k`<0upEZq$^cvnUH%xibAm(%9N~dN_#%G(D6A7d&wC*{f)SU= znXNr|8}(0pC4cD71of&XpT8DL?dBa%K0e+Lzct!frxxQAGAJpM&FALy|O= z0l0&!J4*-UL$-|h(l2ka0x_jf99rs5WdNnJk)7~0eh`RXzD^u&hxY&_Fbd(6zJo{iPbnIv_9$d2Pq^BnKSq{cD zBIQStq3KKiwjbv86S3K!De%6Gw_(ka1rSW?;ROt{H=248Ge9+B0rat$cULk;@3CpM zj)V3{u-K|`4a2r(zd-P2Oz?ip$m{L@h9N-I{0YOZ9~vmkvJV6dmowTL*KY*=*XuSpEwuL|}TB0eO}WZX%?DR9MU zCgS1guKHI{z!LYT&rLxo8jWv{0dKDM)L6*jtfvnzjrM5cjhz^ z?V7F-?zh5$uu^81a)9*56E!z~LnM(jXD+4BV8@&!6Ke%5ZY<4}U-CXoM9ViQK70rr`!8R90~Fh?8k*Y$GUwxzbp6*$A}~CmosH&%MnK_0ceDwLvrCCv76HkcC{w zMKH|iC(&*AdIB&=-Zh?$l2mygWthsm8g#H{uic8vww=Cdm11r@`vXe@^N=FW*Z<9M zd+%fZli}dWK&7mrRpeNvm^ihPQs z{QULHd88IUX^po@HU@>s7}(JRJ?bh7kq6MMMKo1$5xQ5zq5vX^_wWHd$uFCTt4`HQ zV#SlwJ)`&4d$v*E-Ij=`^6!{dR|LNP@hp!d2xS=WK@rm;FZ=8mfpK1k8KLj$RtAcj z&R3r=UA+w*VS4hh&)HZN$H>31?3w!l7>$^nNuij} zZ#FaMrt&=aBQy(uIS4A+$G5VG!TD7QEQ~>KOSd`wufL3!4;3C}HZ`hV?p5sukQI`x zYw4jFvdp{KB?*9yK0xBL3D_jn_R3cy`fDn_=03k1lxO3^J2CrGvV(hd&qvUKvE)_t zw0Y(1QfrCAi8|Hu$uT2Y-4FM7E5XyDK&ugOne(u=8jPVO)t?MyA+Q=I8mnNK`6y7g zNP}T;yIkDN{@Ir5l_*(iAZ-YzA^@AFrf2)xS{N|M{I({FDQrSTdd-Y^GQ`8ldGUvw z3@DuX!}thu>W~4(Ts%_sJRiJ6(#`SHf^*Xrs)26@t;G$l3tUZZ zhrx8I)7y@iO`_2AgyK#=K}(0j!?}La3UEL;MFzFxG!ZAQ3|lmHe^<8oEUB@PbX2xc zbT;=d$*yQReW;?fCVWAWoi5bM%EYn#B6v(f+p;2Fz+k5-vi5mx|JeNtc}vuy?+IQ_ z{7lBnn&sk_s*TL2&WkpAK}>y=hq?JKgC5L_1^Jh{?r+(I`{f$9adufFzp@_6=ARh0 z@xN#x!nN^Eq85X~jaMp0N;oMttf2k0#3a!XVM$hg))pV86pctZC%Q5%Q-4P**p}sO z^jh;C&|lA159;11id;f;NMl;x-XfSG{e)sNBJnz2Bm_6|Eq-q7{UuI{VN0~%+PL#yKEje~v8Do+hu0J4AnfF>}b!=pYLrZg@ z(%;(iviyD`6x+Pg6)GS05lx7u&Jm=4Q5?{}f!53e4AVVXXZE>1Z+>j6Zd|VFPN_}a zbW%`0=6c=5^ms&`qWQBv|3AyBkReQNpGCF}?+mtZaxGtbrM{=rt zV#6vUIf?V9QRrj&0kBr7Jpd!E5m?=1H?TtT_S=w;vGCiCdAb#iW>EXpiP~}Tqd@aR zpxR2ni;R)?^J6K_j5gQvDRjwpZHtW_FD}*p&9?Z4rm82k_7hrVr=&}d*avrVcYT|m z?k82a*X#f*m6~Xn(7fsA$r7I@Jq@B$gZIEQ7tfvdxtQ`U|8$?f#&x9fHNO?p8i`B< zgk#J|Ae&^d9Mnm~JL$mmkyh<*$@25rzSff}J2K&^&^bhmBe3Pni+Eae;DF)8u zlGDVm$#+%vx^V(WQ56YH!PYM(+rVKJpW;GAkM@a@M%2?b*O{mW33d>zw9ygJ5m@bC z>uC5(8f4~h@jXHMHz=k=xFQljSu^~cSX$>MIMKp1rDBZWm6QlQ(_4Q`gO>W`vJtnq z5dkD{MtBt-8c7TK&HwO_cFb$LXLC{f7?C9SE!5}QPOjPn$4!@3(*8(>>aTTx#eya9 zp&lJtIy&ZtqqeEX2ehS&fC=vV=Evu$=WP?*`)lgt$Czs;qoXpy6+N5I4}udq*WY+m(@CG|_eoxSeoi(G+_Ut$T&PA3{Fj6R z+J5otBEVr40Qls!8af9PHnwu0b4LkyJc*UfR@Hu87$_jN(%_i@Bh`^@qsp@d&4P5) zNw3*$#Uc=L>N+*6(9nV?4a1*A2FXRm#D8V_;3e6FNP=^?Pwz`f+*gaDFQzpC-@>FJ zz_9>>OloGv+gf9`Ce1_;ZAr`#mSQqwbinNcpUeYwzL+V^j%U0R!Op?i*S)j$Fu=6& z>Jt{Z?G0aQUL*9`Pz7;wp^a6HK51zJxqAt9K;bnAVh-DhtcR}e#2eYf7TF?0uu6Gy z7{%a>h=}E*@+KTkTTSi#l=}iY7L8F9DWmovfAK4Vem~?uckv9)?(>zddgRD-%;U9O&Tm_o;R7qly*< zoe=LKr8Ku!Im|LYS(z|W;E4KmWl`9K{g6~^7AB`^QlbJsSQ2b!%1vF+bj?7raVfuP z(Q+Kec+yQwTqH%JK`qjTc!YWZiTFI7x9cWiV$@=r{<`{52l&;VI%qgr@XT^cf7*6=;_J1z0nc+QVHiML>bu!T8Q*}qRBx|8@i|SBn{~ZN#qf@! z+pS5rf}u;#PE|_wgRt4kkBgM?!Fi|tl8PXxwF`Q*YYk;Qtl|=rB~DhI0g$@Y?u^*F zuU0*x=*#xg-$K@Y$@WC?WYsPr=aX+V9FvzrZ7zH1(i#A(3?xNd@wRtdH3;Ow91^S+ zssE^&%8dJVNZVXU zi<^8Zk1{3che#xs7=IFY#nB3n;f&>E3ceIuYkZLw@Kb}KZ0Ajn_|C%Pc#_FNX!bc} zYC@yyVG0G#VF%0#UL&F-ODjAgF^bqC5a%evn8M9Ak`akDSk`-pLBZUI9Vju1rjH5; zA!K!en=<2t6`~3|B-igj5`FiRE+3Q2mNP&?v=gh0LvjeK;PMFT!Z|ESSz| z(uHqELGXT`*N3Mf&9B%iBa!9RjUl5#loN~7NH)3<)>j=)QI~Dp1yb!K6-sRh9mjB4 z&hn!?$FLZ9!~`){w{d8PsAp~`==%{4lD`Og(latqd}0fL)PsTiG^Jl#f2+!gQ9w3% zm4#k>genS>M^-#QaeU3Qfk*RjY;?LLuug6?@bAIj&3my{xqVVCVDWb5!cNbT)=jTeyh)5Wb5yqrL!Ni;__6cjD4Y*N_aTZ2tobspMFE&&$?!X{N!% zEf$7awRNF#CuN(J(LUqAeJ>|q$_ck=m}Y{`#rQWYGS*a+t?%~iZI*ujO=52#l3h$S zmW?-x4@lUK;>b6~Oj(#oYtq-znXw2It#O+QLxoAF68_?736TvAHq`(g9r1EA---PJ1H0yIHzi z(d$me$@)(T;rKCK$}8&iECT^*WQSE0q8K#HI_!HT6nF4t2}+lePPDn9HEW=gCNApbDlya)N|EHWC0u@~MGt$XXon0x%*ZwM1l8ghQV$|?7M{H&M5*wo+GP)J$S z-+sh^XN^x`VkiKli8_s5Jcq<^tR&{}dw6W8oXmX={V#(B=5$i3d|h_16iuboQj-@T zf#h|5B{8n|R+Ew|GnHbO@94L7i? zZ&L>)kMj`E(341(8A8iA>L$y9_T*Dz5(3NTT78*Bp=w?@4oJeY01}>OD__X07j`vC zjipK(x?Q5k&%UB{&Zhc8hG1;M-AQH4WZZCEgf)r){sbpGHs4@YaWA1S<&?GH`iUe~ zol!pFb`$_HJm^egfx{988gVP7L8#1m1`6-DQ4Zgh=Ms4535x8^R_ieHt3%jeJR1{@}nW&&{xghuy&XTD_=8yeKSPr_8u3) zhWPypD3Oav<+3@5URjJDU0GB8mMRG(RQwK?5i_-rO_FJ!KqLR;xi3T+T>wu^<)=nd zd>L-A^H0zAUqz0hTR|w4%KiZdTKs4Kw=!Kic=#DM&PD_!2C+pNAWXA-yPg-ekNK_` zG#zhIhJ!uSOy>$DNfqaQGjMpKM&96pQI73wbK%y&s`H9CEI8S9bAlCrk-IogC!g2k z@?ZfNf4^9|`|&*7`)=$i+H$kmYsjbjqr(JdlTprGgWD;fL{{7Xr;`DYpY_r*`+fzp zUIBZ+JVqgtNeBo4&~q(-ht0yItYWUdZ?p)9Dh1IU#$$v^^<4y6a?9G!;TcV+V{p7w z^HY7vfCgGgzQPh&{-TlRfi0FULQUzl+*C?MTb4+l_oe1!D-TSLvjf8u)hOY;*A#1@ zvZTmZbYWseOR$s%(f3wyqow}P*$z08UrOHINhiOd^e*j5-ZM72sbaAFgB$%KZ26H( zbUwx#tt3%vK8`XYICrJFsyWZ?JM;Xt%kPUSWDqTmA}&r1%KW}L$%!R>Jgf&lD%|fQ z19VmOm%i%D^#czC7~3+x@M&yJ=hK0=Bqj&Xe~XDQhvjOT&?&xWiOj7tbVZhJ@sJY} zGclPA|MqqjNgbuy>s9l4{pnKEC4}#OQ*HnE^X%`&k{Yr9 zlV3`E%`>~Ne`^w+YIaYmd0xCU zQNh4q%?Md<9G2rd?r8M56u2i$vm3gv7Ch)*U&4OAIp?xG<@3DI`Eu^@aO&8jxiPW3 z`Bs4Mp3uh`5O)7jgab=(EXa8NR!8^OXDc3Q4FFRwA|G~aF!tgx*jhEaYR;gi%MLur08-J>a~+e$UP3DsFF8%V*V?*<+@^zn}5-|MeJq zz+(~tj{!y=YveK2Bw>Qb;T>Jh0}xK}p?DzM0Q~l-;ti6{PZL#}i9U)vc9y3}WlFXXKMFSZ)bB->h3%Y-UCNgTmvbuM`5xlKiT7*+H}LV-HW;I zs`}--9zbo}bY5ut%5(SMv}jQdocq`oy#lCz(&G0lI;M0}rJW==^&*%}xsIQC(Z3f$ zL5I-C$%M_eogNRPjGV||6jl`{MqEXAI6M^u#Lp}GVjwdO`6yvNSZ#!CiOcGk2QWy8 z=+oh2KNHZ7ldSQSfSgYfH8MeOpcp(L(rFQ-PV_{~`Cc<)n@~}~5e%-?j8Nto;MT)zrKM56=3h9I;$Z>%HJU&N zRs=c7O@ieYgg7Pi?2Nh$T?+CnF&K$Nc2T1w6d{4IgM^+L3$N7n1KTS{iP9FCx;TI5 zzw9OovCBmw^_4v=6c`ugDFH;#uS69HpXZMFl89p4JByatCXGVEb}gFr1E1R5x1wE~ z)I1%cydUFWR^l8_fO%pvHnA}or!&5@4Fvzr&tO!CgFkqtY4mbUA(cnL6sPk`K`q(8 zA^_361U<2cIBDk~E#Rvrec07&`K-BHaMt^8XM!j+De$x%d z3q$FU773M6&CgyWP1>Y9d3^U3P>?1K5aBij$O2Nh@MkSn(oyzNUlK;cNT`4+oA$n^ zhFSy6!`*n0Nog(}UicWi@{mragVj2Ri`zsvwz~=P3!Vab$Jh|Z{fFzfH{I!FWimc` zFI>?dRO!tu2Xeg@ePpM~-ZyvoJR@SyeA`#1^M2FV)TV(+6osRKu0IJTR(FW9ELoHQ z3#(z#=nXRZ^s=k;t&M8pa75`I_cMa`Fw7epa?0uj=ecKu+DCzf=W_?C0;^}Dp0U~A zCYR6-ZYUtl%MGW4x3g1Cv`_Cp{0m|JYzgTD7feSrZVKPcJSILmFMWRYP4{-{{jpz> zz~kl-T(5-!U|b(9OV6NLfSb0`G1X>xAL*+qPKYMK@q*z5r*4vBl!kB>6>I}e#tceL z%Zz1e8lZS&9@C6M_ch&>9)%DV!q8==3%_{WhERR8v_)G<-CJwirt+@40{a35l6+-C z8E(3T63jOL%OH+2iCVqdN{53BFJux{ue9{g_qqXHNP-6qN2SjUW|4p%O<$NUi>a2& z)Hvmc;8c#|5D(96qCN(GG6a_Q8j|kkKyS_O^j#e^dGx#KdDhsrw!;92TGM?Zm+p0j zoY&UyuIh(C!5aIuU)6fI2QJOLLxD*=|K^OsP_48> zY2GZhu}md{Sd8grlVz@IqpYwdTFl3HXoX{-qLDN~*=yE=BDd055n)e#7`)(5pZd1q z-g{B3SAVN|Ri^$8QCB4FW;>;qAsWh07nkNe@LysEA`wG%)NV1#9q|pVO(a<^fU+7W z>xZDBn9#KMi%r@sd(wb1ClO28+1S|P^t@{w4t89uuiLEWQZLrN9)SJ+A6ah|7U#Bf zjWz^_;2wgzJHZm%T^btK#)3NpNpN>)+}$lWA-FUU+&#F3pg~V(@3r>#KhL@24ybp| zQB`A%s#*FX;rRKkKX_4ZHn0nsgTbinUl^s(-ZdIh zz}^;JIin~W@HJ=Sit?PNUwwV9bPrW1QwDNx|E-e0z~~$%5u6CGi}#R}@L^vHm}8wr z%1=g>Z$oJHBehvH%(wLQL4uN+zruDgm}#MG+kXrm1RGOsdt4Gkm~?}j=|G9*7M(yiwCRN4W#t3 zjrGUlm#6$Oj&Gly?ys@l-)+`+XZ@3a!kAdthbUoAv{?3!O2Y|TyqY-fnDpxB@*=kW z!7%mxfCTTp460xnso>b3DATC%vrL_CSgYN30Iiq=P$e^9M^K(o69o^Y&;$&&2RyFW+j?rnZGp^ z2=!w-(qIUL@qlc8TQ)^YSwY;eK^)}cu;i=IVG{NE+oelXa=CL ztYBC^kx*aS(&B0c;Kh5Dccl>l<;F|#Z_7@pxX)PV-19sC_6)PtA1~zah#34?{4GGS z^m~%xWw_Glnt6ZqdrRy;4g@kTOu9Pk=G2q1jrR@hL{04m&o_H>=clk71XJu;6`mTc z&vzIjJi^GtQ({gB@AbyI<^$QcM}%);2P|t|Q+nZ59hcS9cI!ux$VDB{K>pSZ;V`c` z4bruk->9$S4_s_QtxlqIZK;7EUF}V>C0gE)kd+m>7!mu>zEJCR<$-nagt9jm)$#&w z`75QG%?*RQ2=T66^V84_hyX|1QvaDj@IyVh+VPNwZ+ zOkZ74(wpNb6b}O8e_T#i>cVXrO=t=1dr_6#e%)M}$V^!bRAxMJ$;bws$zjli4rwHj zjAG15&$wWZJr13^2^l|b6Wzj|bvrC7nUvTx$d!IpRKa5 zYpn7Q`t)T;9>$8pOo>&@*Q%vZC1{0hStk7}>I;=l0n~m$caqqnR}4NC$jX~JE9#4>a-skV6@N&U_Y*Rfot`=23i|#NB z)mMO81c?I@mKL@o*7k6;qHuV(6UhS0eOx|q;kNK04M0~;w3k@5$0(_LAD+cz|sK#;FPxxOlH-rU)JLKHpvgp(&W` zg4mB&kDGgZ#;5!$@bhdB3xJrEI(70DmWb0{x>dyyI{Q=5g3-mqU$gMtd)bgNcGZC6 zV#oKlBm0&h!lc=MU^6mzg*?jq)1YNK$JhoQHzfou%CS-21d|vi*M)$B;OLb{YXv%A8CT*U;pM z)3qYvXVHUQkO5G&nF>z}aM_9{Pan+oiW{r+#^y^#AZiGN#5R?4XF6w#K9CY=CLmKU zSd#A7R{povhgLE%6;7QFbU=Odh}x0i#u$V za@XNIoycZb1VMu35^OB39_9vF=se0if7vWGeo8cd5kBB}o(Jztdhb>~-!;v^J}zx& zx%7X7LFNkcaW>Y`JtR&BY~R^_5IirahdHFaTD&aeIYJU5%fd6xK9K;%xLGbVz;xHe zceq`VO4+te%AToCbqW#vFjr><4+P-Jvlsr1ey%yMCu>T$gueNHgIC`#qxYD z$bO{uzWZG7cww#M)_Yah6CBS=gNh*DiOM9Q#+Y&vzik@+qp(L8_(z-*l}iehN^3NQ zD1Wp>thZbX_cIGBdoYtz{13Ta1Y~3hs--@fvL3mw;&k~5GMDY1XI=aCzMi*^)hQqR zyB@BVd~;nVp;>J_GT&5{v-L_hd~?_LRRSjO{TH-%f9;)ny}Vop_`BjNhXT`3nMOS? zhj)InX_lSNCIZ-4bCM1-e_Pwy4^d}Rvn@3u2G+}sX>t{^OOWrdzya$iu33X?9bT-b z9@I;b?O#aR89*(Y4i4aC+&IxEm)1ZKQ>t`Em4!6jT74rny2rWrNlh{%>JhfY_`Dz- z?=2&KnA!gM5LmExV{+z5zSc92Nqj8@@y@d*^=R9RY`;wE<7Z zSXfw%gh?Y7-04d6mu8zwV_d^*OX*|gGgVUWNCXlwkcyw)@$%l{{R%N6DNmAi;uYsX1~H(KcHnbVqJ(%qWDdK&;N-Suz-1nKlhge> zQCbl8dKAN?kRsZ+=sq_gcR>03>*z@QXKq4$NsIZ#_M=_ni$lBneh$Brl~fe?4T6qp zj6hWFP3~WQr|uyXnhRHc2(-b5M_+~_d*O9Tz;w)DlM6MWFx~@FE0_oP&ppG-NRBQ@ zS9)IPysiYkXMP*=!|>}G<8ROTSbhh{{+r0_58WI7eaA1^H7~z59*;Sc;-D{&0l^!O zUA5k~98WVXU8nX~A0B_fRxTLDj}8APBuOJx7g;}vf2N*5EjdToiEQMY1>!`x9Qjzr zceZ1bQZ#N~bNP~)1x@DeCXW~pX0|LXC(cj=&z8a7i*(2yJFPSJLWsZDu2!}{YHEQUY%+h?lyE=9X}RiZ_ObY~wTHiP`o^_ZBRCASfCuZhvqt@kVWC`? z)BJP(GsiQ{Ei8(50XGW6PWB-ueJBU)TJ}ZSN*K_-X{Uk5oMjJG z_*z1*C0XLA@atL=wR?t5bIN@9IEK}Co-EXR`8fV4nQ}&Q`X(U>ucBk5V}`nw+~sLr z=gGiwoahS>C2Sz#?f4y#G4%a$!^_=Fh=q70zUD71}BVr~{r9 z_!@O z^L;IBVF;j#iGu--%leHLoE~KfHCy>qY^AN6O;D5ha)S(do-8AMg_IuTj;v$JNn2mv zO9VyOJi*5mvv(rsepau(cIewvX+U@BuSA^>Z9ze?$K2%gUpE1o)~Xs_8}MEQUJ=eG z+ol_AeCv4y025MB|60|#6g*%dhtv0E~h7~gmgnde+%QsoFYgD|ZZb{F5@ea9-{pXPXpT=1VUh7AckE5XXMC#_e$ z>JX-ZT;Atislw(3FfBzhU`r=P6e6l&ybO&&EQraDH{ELRiac}llX9e zq8VVaSAxF>5J}D)dg=2FxX#Fkj}#|M$o3OmA98NMRE}zTcptm}RreQJk8W1;r)tQ` zb|f{yPU0Wt=G!bYkthvLG@!?^*Iy?SIWx>v9< zR_6ZVDvam{9}&Ni7pnIdZ%gPzacT(2jh97Jw%s+_$D4YXz4zO$npRW@eOp?MV9VE`U5_v^-?$9M+l~=8xJY+W21F z7}C7{8$;c@u)p$l(VQeMa*rwYbvunCmZ7g9xhY*f?%0f~e>p#qn|P+kJ}hpC03f$$&fz)vm2K zSnI#W?*xplKgRxHpcs1aCpdrjcI(^q5*F|?;C|2Xd7k1vpW?ne_r9EX$EB?^x^m*5 zQzybWQU4ode?T^qa;~XOfBrA?<>_%~WbWfVcO|=VU z6ScnB!DSORdwzF6xw36tZKN0T#eE0gw1pc=+IQw_J>QgBk8&EXHse!!mB`%)h7K6>C@$<-=Q7o^&OdSq7fV_SoxLo zX+oLIWLYgn>t8={6E=43lw#TtewWok)MW+~)t2j0Bj`?>6%_K2$(H5oMD6W88~eN6 zD5kk#(MJ3%4Y)7exQO+9T#S2K?E7|Ezj0r^;jt;JL89)56?Rrzu9WP-LCt_#hw{?+WrRu z)0Os?oJU+RTogU_mbjZ)W6(9@ps;~FDgb4IX_@^-B9p#F)OR0%eOX7rdYmGFOxW!; zJ-FEY06`UNu#{uxV>*3i3il+WIk~{*6LimlE_LQxZu)oVE=GROr-cf^^o(HezOByu z#ywHMY3}pMw~iJAzyZ?<8<7pft?Q#^@M+F##TzG$BGwdMS5mR+N;C5jK2hsdg@Je} zyf`?rVU=q8jPx%4c_FUXwIIcMd1?F8nT7zVISln-;ax|e=NN`G|3%Q7Q{%0SO87cn z?U5M!yZ8)S=BD#6BoNUXeBnAL*KpFgimKkYgDUpc=(&Fd>71740_sskSEy0=8Jo{Etv zKK;rMBfl38*gt=S21eqb|W{9&?dW40pDX%BLi z*Mq#XOFLX{HX}{TyvidvLa7kjoE_@C2n;I$_IJh)76cG_Y z_*MDszVh44!?zdFjZ0DEYi;A})RxZOp^XcyvySub0!DJbtEtH+e#8 zPn(~S@4Ewz%1htFc1V3%@bp`tc>GQQn-CO*NxxDzI^e%uO47*V@xUeB5ar)ULQ6nQ zH9sqh7k`1R$lAq7&j{VRnTm=UNO2V8-9rR9s#HngH8!xv1AD1E-f_34+%4ZqB-*T>OPkN|93W z^E$4%9fDcP-RWReJVS5u@(M#QAHb7UV?l}82MtHV*O$g1A|9ZuuM+iBU9XXks(3CK zv*)<`chFG7w?gC;KAqIKQ*zPXWd+w)vI||t{@<&yc+{DuWgmW;tHPOh#Ewxq?8Xj+ zH@NVin3UMl1PX*%6VW1ag)MqBQk*JM(dzH$Dyf%FP>GozU;t95;)M8QiK-6^+FG7= zE!HJuuW|qN0yqvp$papp0e{<>zgx{(zCE3)ieBRfrgi?LgUOp?e+Mmfx__s@4959b zqW1@daiTYic&Z|Bo6isD-~1jtaNWpZ)x!Sy@BfC}f_oBgvXCt4Z*v&M$%kyOE%_Ca zBH^71vZ?hJ$}$C#wws5Cd*4lpiemfXnl*r!E=B70)D<@FY1`$brWY)L%Rgr==rqst z(|(M5%vcnAw|Mcc63O3G31VD^j*8lmGS4L9YYVfQl0+plx#9`)oYRa@9pUf#hMR&P zbyxdU0^b&>_~(vOe}OA98z;g4{#hlm$&%LlxH7=ule@bJFD89Te~4mwsD8l5TSeiH zGh7YIB5B6@x68~Gm&s0G;lZ&@U_e)&&4^wlu(-AsFO z^2B^j7cOFav)=Y);B*BCkTLgps6hXTCy|yI5LTW3sz<$as!G$&SG$qjcEK@#>K~X( zhc@o9k8nk-Cc<7o1AarA;A1KN7MeL&4vMJo=4SCGo~AJ4%FIYPx`}5?9BdX}*w0KE ztRxwG`A0>;mLxv^R&N8^l* zns4eUzdD(t5%2z)E1p+DHWDoCf{ zt#`cF9nA$w5(-I|6>!&a=hJL-8~ktA1S=VEy}$p2K&|jRy%Gg&B%D>hlV~>LDz^Ex zyl&JW$SmFCcss5@MJ__qh|4uo!LbJqF3x(J)TX52i;QEMLT_GyYyELk;@-MdUA^F3 zE`>MLpNZ5nBWP&sVa6HL!m3fOuT*o-;qX(opuyhU(->4rfG*QTmWUz$qc6j}EqbqKO6?6ryt{>y!CEJPxS> z|FlMx6P0MbL8n)cP%=52EdVjMmwj&2Je~XEv@*ml+fsAZ~Fe}?lJC)Gp!w7O5l{-=N~x3TL@+)vwhUi#zF>ET8W{{$$Da}Wq*9* zL9@t=(vZFNN_aU`zA<)gO+x}n6XoYttAEZcdnW6Ug%L479VDvG2Kd{y+Xm=^l#~Kg z?b~63LCm;9`hHO3b`pSAI#eeqB~jQh81fwhjD{$|b@NGZ?BdxE(B9xLmTP3E1v=J+ za~j8-Nz_6($YC3#e%m;IlU4Bb>()`xuO#Z`#o6T&u9bx=6Z>_KqXzjQ`AUr`8Utxp zsgxeLWCW^DOBWx`#~u6GD+Hj@@mCY&?ZYNOYEr3G%FdFnC#*SDQ4*hld?@DHQhcr) zK}BZF_+vkB1AjSL(4+MVjtcz4TDl%u2-3R}Ef#btSv{G}(Z>_w;;agy*!!}Jnp#@D z8>@25A5pN0oM9H;ONVNW25?Opz;|;Wq?43Jh_fhD@r6{wWMs8uY-b#n3f&1_d_%5| zF5mNR@^kZHD-eqe$Mjx>&F3h(34=q-k^uuE9s0vg^mOAx%=yUX){SO+a*lHjIT~H@ z&uR@sN=n!T8m%+KN|y0OU-7wz*)8MQnenuHX9_Uj^P+?vxAV6I)KD<;P_ouHD)9Lj z0@G*70y&k_Q1CdV=1#N*EFYVA{)JJz2C}3!bPRBD^H%rHk$T#ebDjn_cKYW5t%zZ* zVp@S9lDWRz)$@0t2ql4Wg=No?D&8zJOQ6DnlS1AIxEOi~^$IH9B-VfZhm@Wr#H56< zP>ToB#-#15yY>gD1xW5YUGpW{6|p>kmpf&iX`J;)B;sMWX$I6X~%?*LYLk?IDV>HZwjQ|rV`Mmh4mwzF*dS`x=M~b zo@o)F2)fpeIwus#3H6Mseu)xxI5B}0`!UjlA{lTi#aXQtouH_Cn zmn6^IDtW}fO`qZGCV*48&t!&V4VL=C`gOeId!{dTwDOgt%rstmeza{7*;-`VKi`!T z&)9#t0W3G1jb;o@HlPGd>4=rR%VL#7rUt~64jr1G7gemG}7+LzV0|J>80wvYcg(jU24l-mkn z-wc~4Tn-+<%mUC=2AV|;=AUFrw;@xy)URwrn-1<`0@&^PV~Z#WAqfcQdIE@?S=0nX zJS@uX<}iLnFzgyt0WzGhQyn`JMm@p>23J7MD$Wk~q6uk;iiZwhRGk`P)Px71--WO^ zTmx|TYck*zk;8$Mu5m>1tm#271FFXk9iAVC9P*>52b>rhyPSUTBNgis!B|V=ZAak{ z0^mp1c3p=F;Q_i{7er%2$^_W&`oj@=vb=wHNE3Gn;SofyQ$~NOk7gw9)s=z51Fra4 zH(0)lIksv@cI=fm+4&$1n8*m$2;fyUJE`+jDTjO*Wz3hRUV&#Ioh;p2woHidHHEJnqC}Yv#Zyrxig+(&_VD4Yd%H#Z zLS7>RinoG%pgs)TVq|vV4MkOx@Bi*W8`e^=u63++| z3e@A7gq6)CHk-lZ5r+}dkt;TeKj~t+oa0MyQnHlEO7avq5>~W7>Ad$5OeVVPlBgp% z01Cgwth1Sg1XYCgK0#b#1Uup@XPOw7gv_b%eowSoy!vr1nedPFGh#q(I<;=YsZ8%G zAFa+hW05*OqEN1~jEt8n)dImyS>$9XZZ^Z|d3PYxUmT*)j%XI9mS+r4iFzPx_FdsZ zKB&fz&(LeUu*su&C(%vN^STSB?k+jV!hgL>Qy@*zUfYSKt~?$28&4}%wZ^wh*w`<3yQ?U|i+lk@BL?~ct=g z%A>z(>7r!7%Q$_h;)Bu}RCU9J77>ulr<+w=TSJ1pTd)HvGBb|5b>IH2Hi3fz{SDz@!wFX1+(329C#4i-(V}kvxN>0E1d`qqrK!82G1&r9z z25_P~-_8;G9S8^(`>no#2fY(5w@zy>3dLAsl-K?&BbSHgXW{lidHq6jpe)m%*mBuF zE!5A7m&{3~US=V0RXUU2BThPoy_H;}YyWkLd7B^cSoZ(jjK3*elz&_S+6e|K82qS0 z=#e1ltE%+qC~%O3DNc*qCP3~rUKTFJ4A861ZE*2SfzrI$`;K%spDigT5S_+O@^eE; z?=KtU^$7OEoEsi(Q+jHilma&%&P*9+8nb>(>DPhH&1O1G2RD8)(| z!>nFNT_&*;mtwOAsEAA%k2HNZi6Car78qKYA73FOY@{3WRUA=Pfk@?4#Qf1|>q5-K zCm0?FrgKT7(biOpT1DR`)2hcv1;G`4>3T(Ubn32lHj__$CM!-z&Mv z0tT!aA}$v76WE9tlQ5E4osr-sOx%P8%RCOMr>O+1a*$N420q$Fk}!mP2Ks4f63`PI zuG1G_ODt2!4Qx=nxfFU?s)_fpTfQd%E^o1_yRrl}Lwa?8$+K%(<)%M{ zKfDm>)yyOck(aEE6gC>H>1Z=6qHni`D6rPO!v5Vu$gGHq5xCa%72CeOVUJzx4Ts%P zD1WK~dTdw7laqnki75VB1UIIB?gaD_RLpHHfnPXuPD1B>mTU-gz>qfce`H- z1f>7>zf=9Uc?qhS6ksuJMj$4)Si@i~8N~&_*e1DZI9kL}(!gvOlidniE($A!Ma=0H z)|yt1tK1+=EK4Eba#8@!MmbwJa~ytjR%+ZjTeL>vbi^}4;e^21woyT$wlemE6u??IraEsZV<$o-J16^;F-B62~n__^? zO%Jyew}fc1mo9K7Q{$hLR=$ayFp>RGIkh*}c7*G}TWdbRwMG2lL_*~|kAWyqURrX& zEn$06HufyEFqCWV1lII--p%GwjyRWFy$ z2Z-%lEoT3cM($A@wMi%O{}4usu%A6Yv;8Ttqw#M!{|e&_Jz^Y=43G0EXReGfcmT@H zY5bMjoU6AIu;%+f5@C}yZrZK%Bk=yjGE>|}IcmvFHUlLVD(S2cMP*ik9ULyD1fR}> zBhLsy43e@gNif?l`H>SzVj!>2vG=ilR)z`c=d6G8rba^(HPB{C)2p-fgLI|V{K=KT z(sos(_(x!|#4(6S3O$0a1yLIC;3ATSI4b@H&l6S(-%W#tvPc`Y2>r=vuP+hJtzOiKaIF3?ID_1 z^wP!+LiT)9#dxZe!NrSzKBg&28n7Q%nsL2u2V&a%xTe>qXQ9&`W)&4&vHdaKBnz&# z1b0TRQeJ}k5t|@3ni%wJT##X2YBO+YrWrzDcpb*dEDxesQDeKVhi_#e7u0~Jz6ak> zvN@5-j)h!N-{?5^-DWn5jfI*}iS!YRV6wLpTl1fhg-@!{pZHjhK?}DHEi)(QX8?1VzOVYN;iWQh%B~ zd2v3Bw35aNPe-Aq?!`?c>&qvOY)}Bx)mWKYm0ITe)bvnsrR-`hbZ|8Lk7)F0Z+{Uv z<9KgR_IzXYyrTNUZw4Hn@at`;r}@qNyG&`oi}me_gc{&>^z;xs;BaDoCw2K-Z<(Rp zu6(X|>i5BgEwJB`A~w|$TmOb?aEn!5#wG@C6B`iwApZ3rS&;{^TvL8PekxHY#lUTF z3J2wY3%{q=dV>6Ib`tj0d#K}UiYDjG1ZR2X0!eWK@8hCa!G~THG5Ph^k{$V&?#xSb zQzR)TJ$h6}MX~weeMbKaTk(HWQ)8w{`Sd)<`c2;fmvHQ33bD>*S}dq^ zO8FD(DyJmqY)H`MM%GE#D2u(Vn$+MpQ7HDZaRBZp`8-D-vBgJ^0W{TbEfY)$uzX{r z_13HW!8TNZgYt}Q;v;H9>P1?-J{lNrSc=E2lZ7NBiZ=6Bsa-Aq?eZog{zDfI4nyiK z_u4X3meop`7GP{dI&Pz^YLNY`s3>RU(Y&VPY4*sco4P|e(r=<;g}k<0J14X_DzQZc zC^qH^;vw?eijj#-3JE<>EiGJl98JC?HEbSjzP9{~i?ox+i8BmKRKmwS&448YRXaFJ z+>1BvlRF;?CF>}^`a0_4FW%JH=$uNWz|Bp#8fvVzG0g~i)3?^5xP$rMQcOj)6Sgy1H{2o2NmI*c@TU+ zDo!JS?<(|5!YqjI>W^gZKUJSM`7jKz*f)=t-nP?0!NEgXd?q>d9Ok~tiki%V18CDD8|Qc@gHK@tWJkcjAF;gnXtZwc7#@W03n zAPT%!77fHcIr@ZZ!XM?^@j4Lu%Joc`J@Q>G5jvD;yz{)TG{+y*$)>)$_nkekP@05> zV+A`V?tz*V?%jdJwV+2GiY@Jly{e&wX&EL`?u4A?c|^e>azb$wcIbLfg84^9dACzF zUKYF`&T+jaJ>0#k>DF8C%b0NxHNWdJqscg`>8B~CUKC-6l0v(%HTsA*vN7$>4gP{DG;JW_7GT)MpM`F8ZF@h4 zMnOOwWwJ#@zEV=kU@T;+N{WyQj+L`mO%3HI|64b|Sdh(e-f?~QzPDEtHwQgX;G{&{ z#!eWcb~bHpxF~5!J|E>QC$-AQRKo%zjFJ*RL~gSH4T_J(f4L+gM+xv1rYh&WKFjMp zF%-w81w9^Vzy1#TbgS^g%pq1G?P2CqwA#_Wilv9I zH{QPXv?F2eLd%x%=lhn*Mp!|(>c*-gql8wSaKo}_ zEW>G-*$-o~JqML3GC&ZtOVjBL@~;!lfd4;C>;w->_D5bm=C*_>Yv8tq3{3X=%nM>l z9;xallx@^tjj9IISqDs9O2Y<2PBc zTMBzG8Pu962iJ6YVy?4Ia^vn_FMt}ita)nm2g!5!^Ddu6p7!-G@#S#}vZX;EXPS}n zq6qD+Kg&OHXPXrlQC1-5mk}oSq*^4<<^kk<-C5k}Yfd7w2a6z5&6K?CT(|7hDAL#L z%W43nS?Rtaxk{)gr{@$>#84<*>W9036YGD-&W@h8w$7w8c-SfAp0fb{CRX-6+uUW1 z(Qb#WjMb&y`T{N4Yren>pR^+9@RyQ7det^OUO3QyU~BswDboR*rE> zG0|P)YJx)4oESmyig^Xw1!jQ8HCn;#92OHebdMV5sI>35HST0eU!3b6&ORjO;kv!7 zuK>W8(w$utkzU7x1gm9^aI&&xxSK8CNza3MaQm8Qo0<=TqdkCXR5Mq*7Ey z7+jdqmL@K=kZ5sIOAbWo5g&L8F0BYrQKId0+XN@T|Oic$ps-}pf35@9_t zdf(lmYk@;+98dKmH%r@_X^UbW7&qF0yOKI<1dAFqwXvxAPISJCU16;;G}VwJ{UP^v8@11+AxODQNP13 zzgUXH8W^y=Weo?Yuog!CaZOHO>k#`sgR|Us@j88LQ(>$Sz9kF*ri zbh(6jq!f=U$6@lj0&p*eEc0rYj&fzjgj#+kZ&Qqme4;d@OeY)mUaz*9)6CL{GXOA^ z;GbB*&dooSg(7su$%CWe9>(xQ*IvA#u5N!^8}h$ype-I2F~dzv7*8;OIYc=_`#IEd ztqK9-g6kd37M_$6{feKS1+)QI7xPC!Dw&?8_~b8xK8c+6oF$t?&B8qiTXlNIYK*JW zL>&FSOFl||i3^w3J`2q7nNobPT)wg!LPalwR-F-S5XE zm#+)D$!Qbqlima7V*_M8Nx42CMzblc7A!l!m}NYFQ7mL9q=}7#u*q7NpkmhDnzSt6 zF%Qkvn0*by*5NIHw;B^KR!{lmy<1nhAdh>O&j;R$rV0jorWCg>dTr@(EyJt~ZDD!y zR3Fm}2gU-)aTI*Mk~h2+#cSh0TRFRetb0q&t5U|qS|_?Rlj)Yk)VL2rNjo2_Vk-I5 z>bIorui*I(nznrw9{a93JN37PAdk{_ec|IDC zFd&`v{KZ}z@&qzSPlk3*6)d9d(h<_JBIDHeZCzpa72a`!NHDco5d9^PFp=8MChO{Uv7ZOyPB|{7`zr=JD5qItOnQ>*{S?Po;s?Y`I1wdu{w1m(}FO zDcC%#TnsZ+I(}SDXlHZ<`5ZFVCsC+$M09vqRRuvCZ-`hi}D}$uBt@zgCPClA}@| z-;&qnx-9Z9SsRye%u8=W$pqaK-<;XGM5O01rB$IB7kAMj@|~gtqErTxlu@IKnd8i@ zWk<}^X3uIS;cwa0J1_iCKbVYw8EL$?^5!f$%8_fF) zoa+h_&laO1B_bT;^TmA5cop|AldJ^wSth2;zS@!z1*Cf#{1)Ldx@>&EL5R9@qD{2A z$zHqM?onY>yo|atTr_f0MD-R-R=_)7$j5|utFVb(#26AX20|IAcw6!lA5T+DYa$)7 zoQWQlYrsIhvwiv%qeq91fj!{lgO_0>ir53d#Cd1*`?w*h&!@_-!{gj!YwSwpc5T8I z+DF1=W=lQ#WoB(n#K@@hf{BTDxP?O#P{X+gqw&?Z^MZgd&n|eUTiT3Pnn7{osrC7@ z08a+`Mk-y)JA^;BbGAVBM7>XZYKIoXQwm)26|xk_e`x&PiYnk~TXv}U{66lDiC9}} zi3l!Cv1tT>?b|9)8()DL2HHG<|FVyl(SNz4kgYFCDZ2e@Ve?3h->VR^V6XN#x9uiF z`<0;Kheg42OC0P`BASNg#|bm&#+L&hk>;yjZ*(PZf8n^49utgFJbtcnHGbF|v^$kH z7slY!wnF+0*6k&eAdR7w&yY9e0%+)B@TBmV(xWD4m`$G)CF3W78R$H5BZ!2V8;8F~ zuATX;ssHee%y+LBU5psh@I8zh^(SF%ka570Sl|u}(*J@9h>fc=kU$vEzwU}sThVLO zqCfIE7J6l}=jSLFTf|Rqm)LRJC6s4-mb0u&pBtASGw`~w*n>>HUE~r7CC(XX&b82Q|2jhR9~EZJ7ABFSfI@)Hzqp6T#41nKx%N+3BzGT zRJwVzc{sGVv!{_zCHG}=`T0w1k!$3*7>U7MvHh8Ug0{Z#SVU+uTiSjV@>*kZLvvbV zo2~M`(DAIk4o-rjS2AZ)-;dcmgg|S^$87$j9%=)8cp)yv7Ir9^w`ee5#QeE#{5Th2@H zmPPnfCb)@)B(UagPo;laQz3XLxDUDQU_@+vK_Z*YjJg0I}N(s1__h2~^4bXyaCeHZd zOL(a&xFm=@i5wUqr(HU^Wo5M22FJQDa%22+r5brvOZzLK)pbyG-1ki6RgpEV39k~p zK|zkK2B19}`+il10)VKkH=iPOXaZuB3H8y%z!`0zq$b4tOotL!K-O+P${hR!E;zAL zh$I_{4g6Kunrkj6WOT3_V%AcaXIh)^v@=WV@e;$LoP1N~5T_7RCA<4uSE<|(C2C00 z;Z5D<9m@Kvo{NNXA!**25>xrH;u=<;ZUY%=4L$*gcXS34)j*jL?OlfOs-g0XFxY`5 zdq67&VCdcqb30MHU?_8aCAAin2Q4K_%bc3e#Wc7ur00A*I17w^lgR=oF`d7D$6=#) za3Ct8&o5Z%3|*TGTbp&Ct8Qdw^&I*a0CR|7+JUzzBqL?8t(O7uH7YlF(BUi#$xweI z{pQON*RY6ooF9`u>ic7a zL|Q`palfi|AzS%A#R4%gAFQ%PtA$DpcR^L{_!BzzUvskQ)ur@xwyso7v5kRKoI%`u zN>bENXg_N&_5a7zR|mD-E^P;jLvb%H?iySR#Y%7uZUKT7cZcF$+zJ$TcPLh%loF)4 z6nA$h{-x)9&-0#{{FBKflY4)AuUvcWE{ujoQG!X*CW*Nsp9xvI!K+u1jW-Jwkhgj3 zKgZHf=)&&K3xnW8z8Oiqi}rCC_Qi8J84P|MKS41Qt>55Jwy=S#-<-OLoRx2f7WgL5 z5K*F`c1}33_*YkhM59hWX>3L&1Kb#Pwe%(=Bat+fAr*8M-!H=^-pyLweNogUn=KF*7>aS?X?L|^tMOL`68 zkNGd>M*6?fY<`2KB2qCZqzIEAv#*~Jf)=eERsd9>vck;2%A{i�ZcvMlY|!0{73 zJn#vk?T^UOu4Nks-tJZOlWC%U1pM0BS5c#0gB%=ZAN)qe51Qgva%g8N#dd05JJJtU znr8z01+0P6_#x?nToDq01Ug&w-aK>kw-AwSfp}T?{O1*fRvv}ogfnUbYxi6i-A}}7}O}q z{l#-5lRNdC6=1_{Qd*pXa_~{p%<_(F^uAR6&P^@QV??i^d`7Qh=r;H4S*m$!V385P zdv?u@NR@ZQhoJhdU6#BGw2)QKr+-$sd|-!21+inLVc{-iw##w{0=J<>yoau0pow=BznHIO9+%{VGlH)PzA&^T%#Y&@*_)q1Ft(QN^)FKVX3&l^xEspipw~jj zzOoyz@f>RdFXPJ3i|~Q!ByCO?;Vb)#Z@B(>gty**OX>nx?;DiA2h@u{C5ni!4s1^d z;-WeNP#PwZU-JmCdKDaa+5K2U$wBWq!yuusLh{M{VL;NV#61^qD$bST->yyWGT42+ zlBY}IHzAT7*D;XUS++>{xv#A3VCGkcnD?uvaxdh;*TUFs^m`1;8rDposBweRCDCAn z!=#A8s%)45gMr#OJd-z#>8hV*2ON9OeXT5x^b~ap_l-7WfLj%>SQ4jL56qtbz|^gB zIEo@=*4+sfgg?~igf{kFle5T)Mg7V&kAfy?=GnMqr-S+z+*Qppi*IO+@RBA}Z`ZpQ zbns|Fuup}k?y2;zY|Dxfpef)6fAb{Vh7}Kxc_U(Mu=W1w=B=eUQvPEN2b2Zf-oI$a zd1%ce`dIpDW0@h3|>5ug{B<#WJ zUT+#EUKas_!jJA6`8xH#3KAM$Yvy#86*$Az#1~fJz?IvRi$kB6rds<(o4ts0)^`1k zVECcZYoqnuOrMjnJUQNgsJ=zPWY6uLnEhcB@Hsvyc2I=mD(MSUZ0Zow^vHBctm%mc zvr+?M4I2jo6v(;@N?_C_1;*}#xkX8dwMvAON8(h))33IoPt~c9Zu7=zM>3|8GxeCj zCE_C;?8&KA?`Vlm5J2pFf+TmWLhxpSIi z-A%TTup6qoM(v`0R76M|#UOhCxlcRnm&27B-j0_&-@p1KMe|oSSW0A+9#5>7c2Iid zCAEf$+CS{sDG~GP0ajq)1>H!TbBKKs50`C}Xc|^=u8()@`=mo=!Hc59FI^k_51(&^ zyUyT*$~A1fP1T=XPq7CNqd1|7eMz}qo4ZqMFP7cUbGF^G9$W?ap3`^b92Hl4U`RA4 zAC#o?R&|iDHQ7)y!e~Q3MliGCrmf)-~DM~mqC^&(f4z_eFOw<4?8#}Oib7N zv?Glhr;TjjOBkctgF@BA-QiBn(5y^AtKz+_`eH;>ncge|Ua;OQ`u9MiH0x`+^yL0- zoHv7*zi}bI?KW#Nk+5UjfPz0FGU6zdm)Jj2JgS$mc+QymY@TY3@$>}gxn6Rv^IM>f zoo$W%BGBSs^gdbJ%&O)|3 zG$;;toT6z0vzoZNh6a^eg=jipGoloS-EIxNuHsTU-_6099jVvHjwjnYEy9$)^OBWV zhAuw)dhUsgem=J3=!X^ME;f(6Phqeu?^)3Q6w$-G$Eo374;d{AFBds)buw|0G#Hr!~y=q>ZjM_qJ?y=*nlYIZYqlkFdqWn5l zh$6)doA1l5{cXloR0BZd{7K5RU`nD~IUu+BQ=(x-D3~vC6RrA<0g~fYACQw5GK27;2 zx9ht!WH%?Xm zN)YESQ-CwDuk-A8vy11`lx}2tBx&(!CJ6{!-M+usjH#x-0%r`o5@yX9CJ>Mz=DGMv zO0kRhUf?{7uo~e z_OtOFS)@=8A8Qg2yt7w?@50G=J9CSEQPxr8R%)ZfI7Y-uo?*)?(5<OM5aSzoZcCH5kx>%m2eVQpYt1_!^QmlNQGN^{#D9 ze^+jf(Q~_kGuugyrsH8mLw&Ra;ix6uaXXhtOW$2b?gD@+M)uyjw4VRmcfg zQO+PLesjaEy(3~g*se)!NIW<9Cco!L>kU^&c^a0Q?5nX_G-4h2u0?g<@{No-NKG@e z%<_ij)&3|hIa3+a##;N{RP6KSAo7EA>@QLR0<%+YKQozxar>F5?ALvA*bp z4G6tJBTCr;;HDCT<$FEZ8|7Rls4QMGYgIXQfFe8lYG=j&Cchzkk&x zBjx3PWOjFDmH6xPZ2)eZyqib&L#K0#PJ_TdLr~1SjQ-{~>lq3FK`0o*%qFJnO=gOY zMpX0{W~aJij!;@#8W6bx3RCJXc@#2<#l8q6wMz?+Mjel+x3VFz93_m*3t<>;X(!+K z+X(b2`e;DW1o+~-gkvZvF)a)ponC*8kW<1zRpe+A^>Nhk{**pasRBwtpaV^!)9~IX zD&>BwMflz&!K2uV#+&A5uee0mz~K8VJ_&YjU=bz>-ezKs^=Q2*%>S6-+~0rU(KnV$ zq2Gc0J`zD7*2F*jcom%jcV0}sF2V>+Bl*_>z{kOp^`qJztwU)moK}9Z3|9MO)U_U7^%|zBX+2O>G#gU6=JDZciMBo&8=Y5XQ>5cNEJ;Iqe zZh8juy}t;AkPUKK(O^sFh~AeR!FB8?HURxuknuLNuarEXO{BI~qs9bqLy-RD7E&cug%oMKu+<;lg zC(_6XqAb<@uqaZEiW((vjiw{;o$|f?ZX6w4l2r-PyjSZMoXZSDFm-%_hPte#m+o|A zTPfMJ)|{`Q!t-AKuQyfA+oWi`RQ88v>kchAG?sxs)|LN%X1*QF_&3^tEsIa#2>;*_ zVI6_V{{$9q!#SC&*bVq2>`G!}G%0mO zB7|0ADaC&j#2`o%u56jY%(N|> zx%;k3-PxoMR8$_O85mE8ztF7`EbJeBABC_^0V zXZRX4R>u1Hj^kej_*e12$tA)e(Kpx<5WW>8#h!;1ArOP1K|R7FJw+ZRbhpDhgsWy= zZHbw-YvAe|F%RY{?p!Q2R5k(7j|)L_v7O);@u>WIiV*0vJ?u**Y>uuH-070Yl-4gD zZrS`+_t?0QYH*)*~JF5RB!kgK9O{{ZvHCa zjrB4*UiZis*+XrpR);dYD}m&DDaU5euL0wBzT3*sIerOtG{z#LNq>J0>-PCPp{j-- znE}BwSMi8GsxW58(EezH2+@^UR10$&y7`yoG*No^Kxr+4l)U?O|O`4eBhL z=L6d}!qIPRG$>I6bnHjuIFV>cvjtRtlE@kAz7s?|!hR)42hF>E&Wj44N9KfHGi$L! zkf>u4I@2vW;xOa1vlCMyv7o|Vf6A`Re6srh<;hB~;W94^`6MlAV*2d<@(um=JLQd@ zIxLuG^|}s;lvA(47g5wSVlXine-t0kHM{DHDPi0W=(&ob%w4lV@A;ljYB%3RN?^b% zmtB@WFAuZWe&Rm(Zmjlr3uKsIqW9J0-cmF=nB~ zX%Ai%(XgaXdYW@1DnQZfw}Qfnbj*>9(FP)?Nrr7)JS<@kOU$9>nGgt8+#C0K8r*b) zi?iu4zD|C6t}I=OSaA<5_((4pu$H8xAGahZ7gzQ~%f$X3i3wLa1+mQqwICFgN5~AH z(_oZ}w%bSS6A!=>7YiVc(BmlCs^-03#MJThdn1b?dhazRl&eWFwayXE$h@E0vzyi9 z!)*s|l_1$9Roo1;0UF%C1BfJu(EVi@O3xqhwl#|UREON%&e63kzgasc_1MsrH&ec ziBcuARr!RwMh^P>tx}nyI&;vb8}DwU&g80(b9`ch2{jA@h!MerH-NjXB^sowgjxsX zT~*Y8GL)NErbPyIdefsYd`cL={b+f|O$4O-#U0i|=k4nwD6<+D%AaIhxVVVnS(-7?EhO3vGa>gaAb(Ja)(> zO){xFkqSr0?wqAJ#?96JUQ$1)wsGWdKbS;p7!Ty8YA zD%;LgYml=$h_IIZYN?42FVc;m5PBphQpm1oVpIHS8P?}5B2xnznYt@1BT?B;DJ)Ng zV==&o>Bc$}C2 zV2zWd?)*PS4TH!Yd7B(tI0RS~3Opwpz(Cs2(4xls!ELfvB3dofP?Ek1$715_> z|1mN;tB4#`k%;N72@M0C7C+W&~N?FJt}0hoB`0 zIkK6tNwGl98od_)_EHvW7zK$i1)cM=)k zWhq3KY_3o*(@hoyDQxj)ohU1JbKB4Cw@Ku6<37nY&mp8`p`j5*CK@tPB1iNavM=Rw zL5Gg*H!=Q%;T$KVB>ZcUaN_^g{19Lj%8nPtds1i=h+#bmmTqA0w+$0&UmMiFP|x)9 zVRGV=4YPimY8~Xmq=_@*0AYzL-BzqCj^c8%o3fap1qtF4cy-E}lTXE-z1)=^?z!mA z`;m{rki7PzCj%uRVTy(nxlkL4trb^GedFWz(@eoM9+Vd4`uYftXg~xEL?l53(u^j3 zKnp@lQelshl#3=6HS!?7{@C-|Rg7R@ZIX^ALI-VAiz}!V>)pt@=GeCn61gF?O2~Ys zykhL~`-w=ajx1arxcpJ591T6c=`-vYP1qg2p?^|*q)T3Ak4sRJ;LYlvX3V5{)5s*zKEq{ z$|OUvfRCrfn=?#iVU8GuJ0qiL4pgQ1Dii@zL~Ec*f=rPV_m)#JG(uz~h)RiAJw=^e zR`am}!Icq? z(N_{h69PL3ic5~iGu}64)qhVU=y{$ z;i7lLc^oK#9O}>KC=wpc2{c4+eq*lMl&O%&v8C1d2q1o9&*(v#(6d2dmlbwnm-Xi3 z)3|6S1?|H7n^Tz^wV#MZvb zei#+arx9{PpU#-96eeN@$?2aEbcvr$9$=dd{2rIg6yBnH8Oqj=n79SliPB~!Z`{J` zknv&TMbvqH0*4zTeIL-GrP>cv0*(8ZdwJQ+Y6jhNhkbr=>S4fC2f_@#? zt9t$!?v-$jD9nzVip=a^EVNktE;*@ym!7d;BwI3Ol1?tFs%VH0_>9)W^y(#;8BnG= z%l#l{E^h;vs*IurOL?i0Wn?7wlcEIU6SP?~p@198(Vq0QHlz)33DV(%pMPrhRYINC zlw!HOD&cGQB2BsNlr$#&7=W%u9R2=2lYYgdM8uYNY2ET8sl);>&@`+W0T9K4uff!+ zBNL}t8Qz}mNxA6;U64UK)a)X#b|uWsL4biW=|S*ksJXIZ2z^*ZWXu$!2Qxw_F; zrWX?Cvm~xjN@@*UA%C!IGK(W{t#P@z`037#XDyiElcBVFjZ*5-M7H4Qtj>i!E?PDX zZmKEiXK7aq69Ir~JB3sq%`lgha0DF&M=QNTRnC6p1wQlyVZ zR!5aWe-gh)OBfWP=*E#&;`Gtba8jMLZR|yCwp_JI96fQAe5sUZftO^HRai>1+L;7t zi|W^8lk)ocT^hNRLQFn|rko@3vnz3t$l_&1yZ3!cZBZ%f-BNjH!wr`<+A91e{rC5GK*c;)w^K!j+e$3ei=AfdokjQNC!L z2a&RGJW-7wKkg+1l6!@VBtFSiA!1Q|@Uf7@`hA%nr4zD-hjHR14cJ$PoNTeY-;7b_ z#qKOrMM0tgUYus;IWl}A$6)Y4A);;sX^j|>z{-?^bK zGw=snJIKJ%dSJ>`OGb+|-P3nxX{gAigxF{1<9z%dTR&V3d>yKC#GCf4^DcQ1J2&me z;0)cm2#Sn!LHzfK8cevT@rm+9-plheL!c71W==x@)4tXm__L%Vd$C312kq+AcQ!Am znyeir%3U+35;Mu#`Foqv3z^Hb`%6p7irdq@P71vU4*b|9t2q+6ws==CicL1e!`PSIjt_0j`zP7do5bm)-k0nz3|Xg$kRiCTpKe)1VMfS#H7dT=a?xTUbEurr($C5-NxAcwJVSxR&J z(jnb|>}-%7Q3-)nYja%nvR3~jlviE`QY>Tg1+M(aN#bS|VHObxhey5gFRxkyEG0-N`&OJ zg8}Wag!C*q90fF8rE^k-+BfQ1jlyWa*!0ZH%!NWonSwBHBY$=!DCewzB|ixWn$}E- z*hVRO)eF4-5I^C#DfU$M54VszL!9nE>Hlv#u<&6eFGc(>MfNKLu$)*~I-T;-@_INt zi3+$}bFlfsg2XokDv!dvSw%w1H-c@U2Vxe3-uIAV48yX(6{HB7rZH5eNcsF3>BuUQ z2<3I-#g1OVsxd^s8z~GfKy@Akjckxzxo_l$w~p*ka!u0*H~xrmB>x^isfTL9onOrf znIV&jFV@QY+SkQ|%my~U^)ol14zh`ceeaPtapEsP+IVkpa*AaF$U`D%>p?KVW8#ul zXiqd;t$XFdyAXAUP&1uP{|b8Z`%sqxAO zH1BD<-EIjmA>S}j0}W+6AZYW%4C6D6@Su@5qs;oGw{x8Z3(GGJP`W!V!u;}A-^N%r zaWJrV)}H%e8m5{0Kl;By*w5pA4a$H~zWIv{!sD1Q*;#vVl;313qgr?%Df$3BmM`SY zfU|4~=5+Cr)sW5+Nf`8`@ug~qBBdz8Y48~KiEt}f!2|hoTUDO7VV0wE;UBGgtz5_1 z$dLnS^09QzzYJ9B63YQ-T!UO=&%Xz%2a|$m2_WmYAs0 z*28>S0SJT(GofvR@qYsv9^8v(r7_=AQ58#iZ%$}Y*)U%q9IffTy?-v{Nv21bV{wy3 zKx6C+TRA)GBz5~JLFg%nmJ)$mg*Z4)J~x%UZd z(`IDkOsy5B*G#P018;!4%sHy}$*Dc{*m>r!UVYrK9%HPIL3)AvWBpIykfXm$o?%|N^{*%6fl>J4tDG?hP%~3IcO$zN*g~^%(jm~#m zVsKrg+E6=oeL^iZ;wtw5Kel^$;GQ+$^K})lYD~|JB#$DVaL|`;_%FYhMqg z$UQX+?F9XL+X-7MoCBp6Bf^45H+4ROgGIXRLL=U?!JBqmTAE|c1vgdlBnZ5p%ufya zHs_-m!*yf&gYlpLajTvw&nw>BFLvO=!{4-Iq(s~bjmV4NhK{*^A!r^AJ08}55omz` z2>L)&spagoZarqv1LCduS~{m!6lF(r$n42BC^1C*qu*U)ivTkQ1H}Z{Wdwr!LX{_l zcXQxtjIgAN-MxDIE;DiJXsr;%pONm_UitlK&#=I-C?po$6IAOIRxn@)1CTVaR^!}B zOIjr-;)rf2#gE2e^8pvhH6A`W;z$WuRR&R(%0(Bc$4fEjkXt6e0ip881Io-hmKm^6 zqSiQ)URGm2fJK8+S_eb3PPWCW4!lwImgz2=ANS5MOf_#LvYgUM->6C%s> z$=2%9NVyN}`bxMH?1czZcdSZqRCiC)n=egaN?o8e_KqLn6CE=;AmPz|M#JXBz`c#S zm*T!}Nb(7v^Yrn`a9DKf;uM&(hVMSY|4L?2{Wz7R17k{jTM zrVWZ3as%jbzV&w^YVd^{TM<=4mgEG<4rIaafV}(@dsDM)}irW*vNQn>cx8+Sq?;R&%C4 zBPOEHrvlO?Y>-Vb_6P%AGY!1-&jiO`B{xGlY}pB%Ebx^Ko2{%qDO9&9u42@WzZ)pFOtE6brd9cq6LXdbXVPH+QWxynkWRVxZ8?Gm67vHQ^I~Swf{B9x zVp>&-1@4S~9uq}0hB?MH`!aGAceS4F5lU2fHPb}X(uf8dgfsP zG!XJZ_0>f>R9CBj|CHR3BwmH<=m@Yr9*W;_5@+HA0V}sJW~JFf>~#1;;Q1~ZWPF;dQ8wJss3#|!Fv`lAFHeBM+1rXukMX;}E_gjT6K#H( z^Ihw={hM4-xz!{eyI@qzONIS6i`MV(sk?7BExKFojVlV4cY7~SX-oR13WPHOa)iab z+T9x;-tC1fXz#K};(xWqs`|S$nDe z%D8&i!sBs2DSYR#+(^`O=jm2^3_@T=ux=4^g0dfo?Fm_!lc{%QPE|}QR!UTcQ4Ogt zCh6_VBm(68&co!37jF6_q)YVDrLqz!2iYZIg|<+l|HFS6{)7JnMsr^vWtf@?J$X+R zxCZMBv&tON6ISj?w->ppS-kpLc7qWKq|#&7ob z65BOCU>4p^vEJ0YdAhdd^>e%LFN$h#f3aGx*L_Z8;AftZb6zo$WLF9J?3Oj`{PIf) zDade?>C@;3o=zsHHvqsZ^^ zF0X?0ZIj}WHkkAMF8I3Q!iN)`TCO?eEhEUtu9C-(>a*H0WOCiywKA7;hd z_YX{);lFcLB7W^5Fnn)k;D7skYo){*FundhORM~OsOG6B_wgy$r``VwGxxbGWty)F z3>N>hxzXakHS$qi^3SI6!?cpy^^CEf3%&t>FcUvq<*ChhNz>A;&ikPO$9KQi*z-YO z{3aVyX||4VJh73d7}*M)B`8I=s9l-3Nn{D}6HT_^X8;;=KZA3=Ct2I;D9Cs(;Y>L_ z51&Sotl|jPM5OD`)E!60!Y8~9H)C!VwvMmquYf>7hAxVkABX;a-zoofUP-s#Y2Mn- zW)1m@%~ynGT#{&8e#Px^@6gy%MO?*YY?xTfOwvV{Sf_DRkGttOXs~aHoesX9ka_7* zX+ShA{lJp*L5=+vajK|POUWGV@10}X>(j)UmLW2u-8Giros+i@>wA)u!N)%_#UALZ zy}vei13uakvsNIq#sOAYFXaofKLbHnfH%KxbDuAtzfg!jw>)i@*X(2tq>U~A*%Lo& z;p-oJJ`(rpYWp1bqP2ANX?^hN80z(`{k+F$JR9Dnr&NKO>;3SDgp!Tv@ej^(r}1M+ zuITLWo@CPJGmU`lo!p$S-kPI-hI0QHcR4?c9JG2r7>lJBV}KO)CLF@!pD$~~3_73S z-~V%4^YlX`ZR<8G%~-EldvX8rY`+Qq(3HAkwV#_j)R_Rjn-#`LwajD7Z@soEmoBOO z2aWHtg{zIqR=QelGga9A8@+bYjF$4-3wvYXcli>>?{rlozNAdJdigg|5$)ivA ztvE_x>KDLg7WpRmtwIIHY}xs*uD`1H1NM&G>Z*RS?@K#v=wX>+x(0r;X)>S5a^Kfe zw2?{j9;S0BGKW?VM3ly8anXDPw$7foaEwq8S$uxg4yy{V`=_9xxc!Rc?vKLs^W#9v z$x8Qg{t4X$J51T7w{!p(k7q0(j5I?i1a~+w(oBtT`lD2Y#Q?SD!K4m5^Y`-y3%$zH z(!=EgaMj)P2&jIFklM-z{%xxA?|nZ?s3%ec}L}W zDjvQO_c&ljzx$jaP(kmxr^KH&6ap89&qI@)+uh8(hv?G)s@MQ~Ipv>z2ZPj|3eAAc zA(GDGjlb8*bYG*}sZG%M>gxR)_;i-+=7ICIp@Z%VWB)Aiz4y-(Y1(B*9%)(&Z;d*^ zgVPSr6CR#QBR7vfNb;{OM>Z^cw&Vv-9wu7a_%F}IuWhr=58pj1&pXf)cKe)kfXkk) zy3guV9&e3LuU34|i%j>6PV}y>YMyT>?>AK*&j;4&(|Fz(Jo;;7zZJceoAO^WeEKH- zG)4K`FAg%0K3efSf4|4DD+H4vx=1T%13*m9w8$i(1{ts~R;1-G*Yz%}%$Dw|80E#(LM<6?aSZZA|-& zQ`3Kbtmx-ngUdvB7iMeteqQ%Z4;wedyy=Z(z~ko zD9o_lRgCI0U%BmofPRw)Cerm?NAT1MsZYJ#Xq2SKP)|;iQmu$Y%@O1R_l114h+71I?&fVxUS~_tKHd) z6^{8{8sARP&jgd8M=Ufj0J6?MWa_oRCjn`*1s5|tme=^iEvi07ir-^SVuluUl#(ZF zH$Nm$-fg*gWVD_ZW|cm&Ot0L~8n@PO#XtRe9>!^Q(k*0=>z3yWRCx%`Wxcn1l~&PZ zA6*neBX<(YlKTg?^O3ao4UplG4w?PJ~8oe~4b zPyd4=*4#fCV}5rf;;#yEGWQ`VlGGFxjaLHKgU?6Z8{G^X9~riG5AJDiD{IMk5G=d|$YJbxOw+z((YyEQ@q> z*g&ChMA!NP=L>6UilLe7*~47-^Ubh7E5$*p-k`Oz$_T#emTx^y?rf=#W@;v8 zNNxrEcPU%dS6hFp79DNv`=;#Y-aX~wWR^E7Ss+LVjZVj!vJg&g6_;FeTm?D*)~AH) z&*b9y=iGz}#;&LH{r$7YSwLmSZ~^1}oz{YK)Lii0>lpbc<2$Cwj~pYvo1fOUu4h(a z_=Q~m;R1+R*9j+^z^~+RAAMj+f9H1SNrUH z&?%=3m{*25>`7{_nYcI)L!1h=6Hn;x~j;-nO zkGOd;of*i#UA7L+e`Ho9w)+Nr720+TGsoH^&B)WEGSnkfktOodi4&Z&qh!W;-N2ce z@ysuZSW_c0(@@}gB|lh5*jS*v7W%4HhBOUm$up2s~W-vqe5J!o-iYkBhh=`hV2 z);wM27&CFd)ehM^nQ(NAda_4V>Q#@zESmvr=KR!auHjn(d7ORU+L+Cms@P6xG2ZvT z894~QIcPbVHWq2C9zGIDdCTC1)>(h4d9MJ{2f5k6cNc>EmOR{QAcm7SN)9$<2lv$; z8tVH=+5?4eL5b)ppU!@ec9I?VkRD?KQvXMN^@ILm;#e0;+x>RgDPJ=IaJ9OiKB_oU#ITCjvGra(A zR%E3vxI2Jf_e^{6xzoHu$uOLTU}*vcXJ$oiPmB4tl}V!&=%NQ^ zDD&z zEoJcIAd<1LmQr1*u1$s7Z)j0h%X==N4&!d)7wtf`dDaqH*k$7-F?68rQNS)snyT1m!3 zM+)#PTxJ>^tt6`+v=(D&mXVymo&No_T-0BJs5#tD*x(=#3 z4t|okp9n!%(1~a|vU7;0jHZm@w3z&RTO+P!b;N60pZMJr-ROTYhpy1SEVIzMl5Utl z?ifF73T8AtfO)n$rSCxma)S z0K8c8QCWTu&Ke_VIg6FNmSc*%8GhI!^2_;ub)W%1rvOTCynQ&6v|zrDl=cYp~H0fd=h#yI<3h z^4);oho*qmDaNBOs<{=38Ru(45xg~|qK1B4{xN(Ju2Z;8r` z`0C=Pn=vBI2!!y^ziEU4FgkHdhropiKt6Z|s71PG@nfCnidaF)C?<0+R&aSJJ0z=K z;eUJy4$*(f(suh)-f11jfvo7dGHi;Mm@NtF*pZ5_Ng( z#Ic8)j$Y-mI$e3?0Awomi7VDuk?J*>4be$9`q^*a3VHdAM6NS<`*I3PU}4zWjT;N6 z@LQ`ZWiHTlmbTNp0Ig$-+|ZaFrtt;^Qyg@j9fRQG%ZGdq&NIe*w|R1JVbNXD|9y6x ziEvB)R`nRZrHBmgb~!o1S4Bi|X=2x#oAoHe0L}t3teiPYcr&fRHvGFXL^u49nSHC) z(TsFV7~V?r>&jryanCfxMy1hd&18c1IKnTZUi+(7lKAMaL(-T?mM;IPWi7@xBjEIb zuAbMR%xihiZD?u7D?`d^aT34c4{7x)%JUooF!_xVc!v1ka@OK%-@I@?dKf7mJ`bF{ z128mbB`pw0K22|#D+9FnAJjdBf-r6TYh!_{K7gAb9?8-mHJ^HcvQL3W>v{y zjIjSf>8by-9pU@3tm{G?HxPhrdg%Nb%1M@}ng^+K75Z+0=y0$h771BVj4dtUpR+R< z#gqd4NEbY)L zx>3P_zJg~?Jp6p31KXcO;MR|sdGhY*ASdTaF{iETz-scY15)ab`DN!%QSRfee!$g8 zne6sizf4E}n*$hZ)WT~fx zZO`Nvr`~OfRUyENGCH)WizT#io)g(QaL9 z48XS_-J#idvmbRU;(>DlI28>mVqQnt)4`nC@V>2*n(hYg)9iq?mgC2sfDrK~?VPTK zB1vtxv(@aadF|-)%(N57Ia1@LlEIQzqk|1~&U}L~%_QFB=9yVP8x3ubMCqhr4iG+Q z!lN@52(-RrIuc63ZZNxs$|bQ^h54i1$haS-ZHH1wrplj8PV>SbtY%!xvMO!dBJ5OJLLl{ zTAc=&)lDR*z!607xd*&^lOBDLNeYoR&BS!nc07q=>;G2^ zD7pWu1h;%BhGAY~mAoRxTKI~2AE(|;h`xm`d>@?pW5Qh`=wm^W#9yaSrv$WeeuOL+ zct=?{wb5BQk6294E??fsHV@BT|A-cZ-)oJ6gSL6gvB6CWXiaO^sx$i6)501JriJye z1I8G7{;|nhD-KJnCYgbsBdW)p=Z7hMBwg{N@{@NL9w-fm<~1&Du{&xu_U41FP(qA= z&(DV{k2@z}(|l>O26tZ$t2>H{zp3Zd?by7M%%7t&^0u_?Ymyl8?i+s(QdCMRFZrHs zjqgGvtC(2IgcYs_%cHq?Zn$Z#YqprzT^9NN+4d;@!l}kVTPy9z-i%RVBMuVr`co_c zqmHX0{s7|padC=gF3k{CnmoDy2t|K<1l>nzI(#rhjrtpkd34ARcd7((yr3ATme}dN zW+h?%M)3th%9i6&eXo0!nsNMmuy4A? z>t4q>_tHs`GpBo7uR(n&K&`#pSaXZU>ep6^=&J3Ayw4i53Lh&nJ3VibL1N}~o-Vq` zB(eKbcKdDPC2~dz%XDQ()`;q)dX~tV;K0ox@}&uXCGQBuG?acuy&$5*rJ`c;>B7OL zi`T(^fwldcRs;Ud8s|fo_?4HDUykI}mrTId(^nPKUOL@G zi}z^ym^g&l`6PacS0I)hP|{{}atkPWlVj^Gh(m~oS>1Vvc{VTob9BW1XaSv@Gt^Rb z;Z^KB8$2~+giKZepKpq190h)wZTMjxiZ|ek)1&G#Qxwn5!S%QYg0Ldp$UDwm$4QePN6;b`OW0NP5Eh@n zOTTx}qQ6Vpa?`weM#|q*j~I@~_L@d13Hw|>;$%oV-qdSj4`g!Y>slvtupCd3<+pU| zqWAoAY_^+8>R^$tHm-1PRDJ$`Onr4&({KCs2tg#IyQRB9l#o(Jj}arK28@!FkWjj% zOPUd*gaHx~N(pR$bgLjBt%4x^e)vAW=li_Ju|LNC*!bM{73X!H*L~gL>H=D6PLysP zqaa$#1O;y#B9Oi#c`vNtk+zNu>uZ80cgq5nPHZ_3A?ncYOpvQ8OUAFWQ;Q9f+?43HboyCfP~upFDhdd21$Q`sM-1DrEg8u zR95BWerKGomacy%AOz{dl-&`REdQLXu)ZFcocd2}0m93Hn?;i6iW|@Tdal<_0Gd)V z`YF866;+Nvn)375Hd|~F07uWPfYy&J$$LN*Hbr8IObj?4w%R3j@4PO|ZnT7;C-P4! zz)TX}T;CA8BUUXV_QtqxP1G!n^3H}ew<^yC2YZtcyWbNKBOiqp9o(bZXKJMM9w;UR zf55^^wj**IEjR9|*vQ%*YJZsm#)?Pq1uWLMd^S>8dN|hlCRgL=`TFh(=xN8OI2GNh z3h3hu9|OKjCHHjQ6YCnMt;Q-%3ab9fK0Xq=7nm}p(TCvKzN7tC3A&r-yP*A^VPX}q zQt=h|;|1(jx*E}7z@j)>pl^zBvKvmTLazYsQ2x>ei?x+9%%&8FI?Zvmyoojq6w=); zBY?w^ZsEu{aY=tFL;O)sscFBkN28&bsJd3rcj;lwQ%Gw5=Sh!b-u=DLSdJd_s>|T zTHaQgd)}Y;-W_i=1Yta~9I)bUoIAFG(aPUuGV!zW(;Q06sqVU^eEKsvW8LfU71GEs z_pRkfe7)#?*GwPl2%*zHaIJwzAFJbt0Ns2XB6Y%nMp$)*lRM*0TveupeHLB#0&WYH z?NJo7b;rWSzF7j0RXm)JsdG%MgZ~8N#{z40=n$qiC^rV&$*O5oK?sk^f9$+!1}Js~ z(UL5Yc~!#|ilJ_32sWw8h7W)rXQ>r~IY(!r5ai$o?zbjC^N!NWx`EaWMaO)&33pe*bV6ZFP zU~nzty$wD1-Y}&zlCl;d4s5tk0SJVQA&ycT;iAKBHmihU!8|DS?PoJi#tY8kL3rY= zA|12MfTO+<weL9K2$wv_qd9sa_9&^Vx+dk85|~j9 ziMm(S2XQzLC$MFpsVOUq#I5Q118?j2n>-k@Bgrq}4NM;1?UlFz2Xy$?eS@K=0fpg* zE2}>V{?NYM@ETX%S$dUw+tv_mSEhgx?eKG2hlsQVURytYN@m?{vi+hKwso9re4bE# zxp_~DNxX*{36=*)N4eY|nZfWz(T`m?uyRVE#BQ@&FTIICvf%(n-p zRaNren>v4rYUt`HafwS&Q66$K0jVrFp)2zh(`NKtnG5#xKGCU|8 zNoNVqNd-P&W9y8-Lq6T@aTh%qoZihaQrZtqADzJ9b1~;l=p~i;wx{k%0CpOdhcE`N zXneTrhNewApXZB{SCjNGMzKsB0<~!7`gjf0+CoM0OE<0hNL|m5h09HrxgDQ^)!*fF zSyk#C5%3IArml{DO`5kYo|e4s+ho4ke7kCudB8u09M2lNG-1o0dN+2}{{`o3`1NT$ zG<@zfUZUpcY6LGV$fJq(M0J-!hITX~wU|m_OkXh1UL84>+pp$bxRDPQfW#%lVd^H& z%4N7u`0ghiLal=TOb71lA5wQC=g-ejv}>pT7=h%fLDy(UpH1t~`C+#1%p($nKKfA+Pw-4hYFU{rf_okH zDLV&c!_zfo2h2k_6-o$7zX5vaC0hqCgB#p;zi*v>)6&)hAAW^7x^O6-*niY{&fNnY z9B`p9t2qJcVQ+w8kbd)g5Bao}b5bpA75Bc;&Q z33I+)+ikR4Sjry^YAxnF<6+r;cHPE+pnN1YlGKK5+nPVAha(rQLrv9uPjxIey%6H<()L zsDqyHcf`^!_7DEB37`1G%AMtK^H@R9U;T$S@7^qW0tl*Np6z9uaTd@d!O7VrbdgJE zxdum5`Uxww*8MmG0>Q@x(UrIYXJCtKWS=Yj|i7`|H(I0VUdC#f{0DIl<5!ByH9nsnGOg31C*<=91r9F@k+75`bRQ($4!|U zN?Pa%gdCv_K!r=Q0U&~r#saH5Z;nIP_n zfUQco08AUuI7iEko3lGT=`FCo`fXm-|MRe;WcBu5z*CZatLX0YT;VycVUFgI@YUGZ zE_#`>WoqyJngu;u<5TNM_%1hNLzFnR`Zh#84%kiE;GW*g3aaXX!qXTmm%>B9jd>#0 zgt6dg`6FerLQjDI6P?Qg(Tfz1-r3-i?!_{r z*Z%6~@p;<){&~O3!Yhwq(Im=~e_TedACRlw*Ndxot_Ui(e^8sQPIk!rHtsG_;vo$tL zH`tmR_|v(^6co;z&Ce3;w)CmhHHvZ6LqZUHLYG9D+YTi)US73dS%RL_YvCF1ykC~t zDTVts2FS%K9&S`EaQFgHWZe&)8u?f0y5Qi_uJEFm?XtI9^ozOE_oh3JC$`Q%`e#Q< zCIRSuOequjE+lp+z;Uzs3-MD=6b!16ooA;a}wZW1iq zpF0g$5?k^k204IG)n6g}1@B1f*ZRQ>?o?kdyRY7!V)=ob_fL z%+JG&dr#l9-tK|+zRyaOQ0faor&`Gf?&ZZ&dkA9T2>IjO>Zb%8_*M>P^C@rj3t^GX&KQtvnS_Kg7PR>lJM#~gh&0c+anL+~(+fCh-7@z3 zQqx4`ppiWB?dXHZgAEv9u?4v<7&Q}QG{P8_RK~agkxsb;DxdrA0Dpbfnn{bLGUvHp z3REh0WPPvs7m?*X%&fMpFc}i($_Dy}8+qc5-(?KY#NM=hqJKGP2>+<81!mb(t;=0~UQ)@Ua5e$J`N$Y)4ta4>iYv6lhc* zJx(_Dl16HQJ?{qBi1qfX!Qo%x|BTBqyy0(Y4fax#FgDu7j4MVI;<1EdNn zr?SiSw-wG0THc}^tbR~~#Nmk1gR&caD+*4N3z2P`RLa)-g~94mT_0Tjw-;bCY-~mB z^NVX|UB~Up)vW83TbZ{!tZxUzMjyP}ThJ}M*#3NP&30r^MVh#1%vxOz2v{BQiQ$^V2^~>(ew#W+Xa*5AkYh6oG5pp0Girg62hTfHn%pmcc-Vk|G zcb+xg)Rwoa>sz&N-J0{D02LzsMM=84{kp^_2rvalg`pw`fjHK~Fre5;i;>*3Ue=?` zbq4Y+%8GLaqUSYPp!@2H!*44aSr%{Ss0GVSj=JruwRhq>J$2_MK;5AZ(xx=%NMRv^NN5&%i+%|KyNS$i-eo!45B#TQki4mVoeM(N+8vEQ?z8%n z{As-}&a_e#hP(`(SVHA#I*<_9BqKdfapc?8yQ)mODjh~QA$up-lVf2I*aT9dg21i z+U0e?kVt%<_(k+F2Mbz_L=Yq=U;5{MYnc7XIYnfp8`_TnksB9_JI)CKyXiHeh_?Se zJy4$29R|X*+~|YEf0B)L$W1EM!YHsDYUXIh=X84^-q%Hf)ztd*xyg8bPucm#r**>D zokty#1LF1yQYADWw(ehrhF^Lm#nBA6|N#mXn=yZ+Hb`m1b_aa5+283Ab1_^TQ7LCW~$WzAaC=dJ#|6 zlmJqof3EI>nbF{v-A7h8spX&7XjamQ_~-*{h&&*YV~(CGJs@D;SPlmjwOHici42>X z4OUrrYW&h7Uue=vGu?t$8uf`%dKQziUHYgNlH1><4IXTs=zX||G<&ms<+dLs*B;#} zYG_5m<9x4fM^iUrae7(OgmVL_+x)3*-|)Imq=U|6F$VGOsNfzEA-wXGGOS2lZst;U zZ)@dhO-*mbxEKLc*md5W765e!LFe+g%j`J^ivLEw=8{@*aAi z%-;YihO=`!S@VzfrGQ6ko$p^`AP<4W$x0);@Gn>&iFB4na-qdc!Xr~qO7@lnd; z9-zA1FFh@sTm!P)3wZ*&Vq2IUTZ*=EiDp_t*JnmDiVA6;|XH*D27FE%a@sN6na<7ZTH%E9%-9 zg7i(;31VkHaGAcOb)qorbZsdh(S&oFXgvK1UGH~b_%99HMgEWf*JW8AD}XV8EhyWg zcy5J(TM(iGLvp4u!=7VQ&|FWy4JZ1?k|>9A-CT^Y%;5*}`MvNQDKX!NcJ9UtTf|xC zqPjS0LrYnm6ik@(qBcr{yRykTImg}QG4gc-mq_j0q-Sa$%N1&|Gl#nwE+>Vf_VqD= z66VvF6-v?YNGYp`_Uj|hZDiho(mN-tV|-LAxFr{3k@lQql6ewCl96j9yge{V;_LQ# z+J=zUMf3T>9`Q)ycdRpr9NnBR#KtQ!tohe7S;S8AM}JY9Q(8_!$+e7#8*PQ}b?LX7z)~NE@b3U(tt@k@n^2{B zgjhc==x|)H{y4WIg}Pe|OLt#V>eD(favEQ43Cxap_<@;<+e1n2;z9B;csI)4!{`-q-`5LJV zdH%sh5>R`ZsT;WB?#OS?4clKrzfRwtb3RT^twM;D^YCj8i%oK(Or$bYFCDHXegDUJ zT66wmqwjJuL@c$`;C?VqOEzE}F^`n6tT2cS`^`N_w@}~(G?>GQVLhtVDqYvHfhR+N zwC3>m=M~$7*b0GLfJ<#(0X+1v{M+gneLI&8ei=gwX@KILcjze6{jjuDBjskwojO9D zr+{2T(ESx&sZ>CxKC3~EA8GP#oa=p@e0aQGuDZ+OUf`HuF8|hDOf|7k)(iIgZTp3i zl*q7p6@B09J2I-mx)UK&Ysb;nM_!x+gj-@OH8&{zpA4`_9D1}EGJB{kI25ZNZP9Vv z3`Z`&rQKqdne{ub0M^o1Nk^-7G{vVi)Doo*?P-6|M*ODcUB$_YY0W5IL)ON(9!>VR z_z#Vyg-9)+fKc5hpvp+s8a6A7lYqoAK-JW=eaA{8fD0h^p*Jb|=C!HyGIVvV`{MoB zhk&sLAeExUdZd9kEI*))r3OK_LoI-Do?>adeA3k@ejq@fW@`p}PFWmW-?tFBg>C8P zKXwo(VSRvd6Y>I*uhDb8DT`$Vovm(mU}iZF!h3S52I^bb2CK@HFYcfE)(QN;4TXzp zDFSNYv>c~1xkH_|JCz|CXb8*kyrkfCJJQ+q_M}hp_fj93oKbg1Ah!c`_90ysWq|hr zbG`$pfsU22=$0ARD@HXpzVWjM3m&LUPD7x8=;$;0Jnjbm&&DOKy-)n<=RX6c8$2!X zkApeC_^g`_e7}wdATQXVC*0-BXUy~pigFDf&=`yzTvxnJRo~ja>;}J|FbI}DzSVJl zT@@3!U0INx4g^UnnPD`LG~kuM`#vi)#K;K1mVk5JFtHXc#tT8SKs{!NhUD+huf2si z18p@AqOoATm09;$4mfdtYeF~k0#6yP%?N0YdV)7Q2T%<5eR}eiHKXH5UP%2fQ8A3& z;3RjUCe|!LKWe*ivs+&d2}=hzop zV^s8_i*fr(joR}1RYz}P@}z%_XeF$wV7mGII}PWb0iyb)o~XKmYwGP20*Rf=OG)rR>V&`GxU8fonnHC@~By#r{lwX9w_TX3kBmo zNqs^Aj7AXQ&T^I-z^JL+9dO*37q9F8KaWW|MBb=4%&qXFqGPMWzu^x7DRHKzFQAgA zC@`8$`tddni7W=Dom3onef{owhAqD=I-v8j6`E4a>@~pNkJq3WP`bHl3|jf27j#`N z?okM^Qod;hD-W8|IzO}xTf?Q3ZgJNnzOwW?cGbtpIP~1(^0P}`M#Nh3*APes zt3Fl^5Qn~;e+wm+&C3YcsJ~c2M4={zs9PF8{*2WN*{Q!Mt!KjOGXo6AM6bOuB*_~+ zQE(*ooZvE??esXHMJq87=ci=o=}Fg=LVF9W>e(UW#EHAtUk8rW*=Y>!R?%l;A*^ax&>TAWeWJL?k+ZN$E`2ti7sA!v*?P9|k=jXk`vmf23^`Xql({dYH zp?lYV3+fqJyWY3meY#i^df9!wupat(w)e6y^v~V=?|UP39mwvZ=8=PgS%(h3<>c!h z&ui`dPgg^lt(UjP%3Xfn_@s5oU`0#SW=qRn<_vH!sw(ui&Yu8~nCn&};>=FzB&B|G z44c*B8SHUR5XN>L2~2dmT^mRzf>+H~9QC%haONiD5p^cND-?eTvrWxzr~SF*n@$v_M(}op_AB+<>T-Fo*mi zRP z`S^2N?Nwp-iKsLmX!OVJ9wwiImE%O2=SqLK4ldc1mdwvS$%gEf1<`BW{Yn@5TNT7Q zo=>ojvwVv8tc&hf8BXRfM2hrxX^ADlF zJ2#uoghHQ2a@?cE2eHYW?;_-`Kj1+wv~mXCEBF7FRtLSAD^X zwM+$z+Yue33-vFK#*VBnslyI~9)oOW{sbUI2|zZIKo^2Wy?*9iQGb~zQcJ)r$^v3c z!Ow|&Dtk}TS=<*vV1fmU^!*#gWma!OlpK)Lo#Az#nQhC9b2FelALO2~HYpUmGKgx0 zB!zCPD*f!e{vzn1-HsROYLh>jEPGYnym_z8Ondyi*)*ymaOWwmcQZ9Gp z!SzKe_3X&Fu9nu&b6JmpiLBNaS~FTAMpr+CMXIQO{@PFkWqMgBC-YAupO_^ii|(V- ziQS0B={HSvw0QH*Yt~g3St)QfO=+G*9MkH_oB-EZ58ie9qv&&zM+N$Pq<0Y%y8d^y z%gdhMW9ZEN$GxU^>;8B)bHCQsahcS8;pXnkHKfO= zHFGn1GCKGZ<@rZd4uh#{5ECUxuym!YgRt4yncCc)ET+vM($n*Qm;mRdcx8sZ9H4_P zc^9Eb2Md8dP>C}~-5IV+)tSmz!)98$&kJz`gJkeGd}SPKQzmaVEo=3NQ;4{tVkk>b zWDCf4d_~vKYrv~BfLK}R63=YuQHWq2j!^9dZ|G0afeCba_BpZpy`~EPnkw=W>Othh z3H6So@0O=&%hoGoQ*XaU9`640>!5CBCe5s6JIJYI_t}>t>YzUEEGs*l>-qZYL$^?h zXdUscw=MK+-rK^*j9Jjk<+XNb53r)yhBzmT_naSCOjQ*Y{KYYToW4`x9!;D{IjjsJ zSRXXit>DloCh?pD(WkS`ZO0s5#GAXbg65vQo}Wksdl;-;iQc1DXGyFw(=HT>uX0wJ z6RA1*nN=YG!e~2ar_B=|`TigJ1=@yDC%POJ^ox$- zf;fM#>dz#(^V=SG{Y5 zh1?lqf8vXmt<4kzYDLsPj*EpQMm#Z2$lUaZYKlzvjyI10J>U#T%dCD}NT@6jx?6am zuK>&~Z(U}8f0kI!taKqQf>*UGjFX+YUm^4QR%0nU6Ok?TCt5wLiia=itZP*9iVDK% zYgvN}p#F0+X|8RtO*LBABZOCdzlU6+wLn&v+a@!~A^A}DbzwK$c}9w`Fymy!G44lq z!p^H=BQmA8oU~oox(BMzb6tu}#4Wtc{gnmZtb1;6k_FtFUQ|qb$B(6 zf7%pfC9U?qUjJiqb*9d@V8z9H2ed%;gHlbHZi~P$Ekx|I1Q!jzYAVnKrN%?FF`m*i zTkqpAZN&I5XCMV|1_gK1@WTbLyIk4N^gRx!=ms0yS{g35o(tQELt%Vi(Bw|-DHcs4qA z;gOtZ-Y5-|5CLVW1r(*G8sOd<&vhlHCC|d2H@?5t;7M$j#{Cmy)}!)VM#RB=e&$2V z#}s`MrL(Tk!Vd4sheOOnpq8j7^ywcr#50aqJT8`bzh-(;Hb`?Jl`FMC1@>eS9i%M; z;%09nv33xgpM;@Xyai!N3`97}J^Pl-`Vd}=`hmYRe4e2=86Kf~ybx8}x&5hWyEXt+vX^k&%Ox<-4KzCI>w~SbnB@K*^R{4Aa5MfF#wINMTrx&t! z*J{@GUq4_1{NNP(3iaDv9`0_udK~y}VyXs!*AwuR^mq<_LR?aF0U`mtbX-1iv)5r} zjhg)aCDb4eSD-LQMw?aC{#M({#(5e~4#M$2^tTv(e}{mb|DCI5RordO*Z41QhtXSa z6NA9*pG?&$iEXETyT{@|PSnOJL0}DGn8fNKq0xvxpBx;&#J=e{R#f*y`qe96FvQi9JmWUs8^oO;(GywI$o z)Ed@T#w4Jj0n!vIxrds!)v9CaimV)63zdCF*q+A`-eO~NA z!2Woox;wHS-*$Jb75^(m;dAmxlsh34B^1e~UC3E7_i%g`9mMi~<{1!u6E;k8?)EbS z{tDAnS24660PQkhz@V!$lPkja0SQyVJLcE23Lz{g{QyZAdkr2A)Z=RF^G@@%e+$$X zXM8?5odlkK!EP>Ve)gE{!uVkz9`jX3G+QX;k5{*qjm1(JcR#y;SbYfChps3iH<(yM zE^ywu^Nss6!f-iPjq=x|mg1?MUga_&6V?RD(-DH(v**VPm@=gQj5++Jwm>TQ-t-9M`mAMY#lTlMjQVw)wNS* zN8mb$ixaEG$-4deUa|jzH2ZXgr75wN_Eb>U=d-J|+@5Zx<4F=u%{yn`6}*_>)hUpc z57Q25Om5myKegDfrEG2nMC5)RYM7o6xY`K|=)Jr+Y>EFc6gMQr-iMnO1qW7!@bEZf zMW+eQuC!prwBDG ztx+96%uNDbsnS6Vf(i3JaED>eTrqD`ZNkfK_;NF7i|;&g!VUKNV{^2)Wmz4CYa=*= zPbs-4(&Nfq$PF7TvS%2;m;SLq)IR`TA!$d@_vnj>xQSw>puj{&kyjt1Y+P12_F~Yd>Z>Od7W9VRv8|pplknU!AmeTg2_Bayd+Xy4HzF=F7gA7RZ5e>!0 z87@`QqL^?n;+LpdH;$OFB}wiy?Mnjjby5l!Rv8%W%N(cIp0?^Tj(s1Xjob7usKlTw zkK;BzKxJUY;v`wUOvhR$A{ zxGC8*;)yWtz|&O|@b~x#XJ@{@8GpLNQfrTFnn9G~cD^t6Jf42$7NI=vQ`Mk|QO56x za{=+(Q68}ZgKN{rMX*!a{4IZm z@-W~x(c%wU{OGe>1+JyK4ytA9B@OH$;koMNM?Y%ieY{h^mbg7?d9J6sHq*9Nffp{8 z-|L;qhX)Y<7Vu1w4N&N{C>eNafvuI^81C~ zL#(HGGUvLi21==N7hIkx%SI>+ZApR3cs+7Zn)jK!+8M3#Wc3D+ilU34B7_L)nCTaH zyMM|3eA4?g4&|J*cr*>^Y+f$%8lX`Ep>K{A4 zGh{}W=d*-MMBlPA9Vi&@zG#IHvY9+okA}Y8I9`_z)gp$Sd}bY^}taNg{Gk1NfpnuBTO}|*x z;HAWpsBd4_b5ZcLcZYnAB2(@Zs+Peem*&haCSeKVG{ZM?W^BAwE^G4G<})5C2*C-$ zZ|R|}6taU2?3oD3RtSfcqUCW9Uq`djhY3H^IrcWPLd{his&La;{F~2N|M794x!Gua z*%0Ipbd(U-w>sk}-*PHaF?$l{^`_Ad=uA^cs_9p$F;WYP4hsH7bFjmTU%~}fW*10< zydL2s0BH_PElMPueQbg@r=IW7)h^=tRdjsGsa>diU_BDP5iIXhZl)H`M%Q z_B(MSTh>PV33V!nxFkN0rm8}sVpb1xjym!Vt%t~g*-&|4dq8h4ADmMq42RQJK%n1i zq5M69DaD|WGG)nayI?I9Op*A~Fr|bgOp%7OW&!>QhFzdv=_AUh;e_Wxvz;IU1Qc$F z3pb;;aIO2*IelfEVpP*2V_c}NYVfCDKTUCgRn{EE6i8XyaGH4;aI0j2nN(5gQ-b3! z1sr!g1yDkzY72F}fr8>Le5y5xg8%IWF!_`2LuSwJvWEA)U9cP z_;*R8ZwQVn%%(&6=`D!3(Y^MKOnR=hOvDu|5Tc&IsJ>-z<^P36!( zU^eQ5_FZ*+5T!;i$A}#6WYlXl@D~bn`cefY{0uith($c_(`zjfl8wFBJE@h3d*z7x zu~ihlTaa6Po?=FZLnS4dnz-nks+=-tz9I}NjCUJTa_8%dV7-pooC1^6l^%sh52;spc5#CpZx@9jhNer)P+523hZ3@}qE^-alTL2L=tKLl8YxmWXg5T- zy~XlP^hRGX!=RNP9N8qtx{3h$y+@A0eweo`XglruQrx_tO2Z2$PIio+*Mz!U z%X@J{!)4A{(!nu@On-}o@5NvN@wd5EW+k-G8<2mRpgu`WKOe~6`D&$dT{(*38 zZjSimt=c9Fa&JkCBTUIz*JmTiq0 z(RR-g0kT_C(YqQ}#fX4%^&92M+#)g}K*^72^YdjsE$22&{40D5MCGCCa)0`;jFZD+ zn;60KX0XS!GDn<3vKkd5Ft|Vy2@xX5A7U;slbe-{jS8$8O5x&@_G#gc2a+2wqjg7-a}JB+a|)nysMp!K^I&2l9s7<3(&6IOF(?8&zgoOtxfhy>6=7OMT*l zCwHtBYW8t=)ZZzD9A%Hxi?E$wONHa~v&J`FLhaV-KLJAl)6c|>rv27u#(t~*kMQV- zSuB2dV=$__G?rhcfPwXxZ$Ov8q&skIEwbEbOAbHVjY686!6n)IJ;E4l-yu@Kob7BP zny(oPQ*R~7(M+#4uQ&^ncw}Uw!S!ctO3q4hM9Q5vQ{A_n>*Ov=B;t;++^v!zz$)2MsotdDxhGC% z8y*aqoeJ4Jy#A#^?QRqpjswv#{X?=tJR!nj!X^C+qC7-mC~Z3aaLS|YH3Nw;IjMs9 z!g^!KL2)b~eP*f@(f1-W<7r23?K9uQhl%2ptrb|?qtOuzo@g7xCUo6-kYm= z2`1A<-=t?&=5txMYPNk>^SSe28o%?Mq|en83I89q^Y-^kIIOcZiLa{aU5|zQ+kkDS}~YEP&bmBHBhqx4Ae0o({wgXPg6z(`y?kqqL!YAaXwQ zS1_?5d^j0qZJfxU!Qu}^3~qL6pi7WJgSJ|EuF=QQL40KnaTyK`^7VD1Oc$QGcq3Dx zSbB__wm2oBAyK?^HnQVuf2xsIcjDehs21Y_4}Li(7@u;=xXfa}t_m@29LGSB@|~n8 zcJiGaT-}>StTD4ZR!or7m;WAlY}{MgThp<5o~m_Uva^XKsdBUn__546&w@1$uEu!Y ziY)kSRtlNN+IY9ujSXJq*3U)Z_oVB9@Fi1)P$&t4la&J8wGTIK#{bb^i2nmGPC8MH z*?Tidc_~a7a3s*-KLHdDz#$Xht_j9?U$v>Iz1DXWMqR+k+F-u z9V_K;;}gDdOtuh)r3*V^Aa-zaWdQ^M1x1SdT}i#4k$V5*$=z?Hyt>~|G^O}#Y(j3+ zM~=!Tl_wjhCMR+x5Usg$GH41I3Vx0Sb0@;Nzm5a`1_wV-N{TCMP`VA*hfL*A7{a5T zdJJKTxS_R!>9IR_k=YD6YMovt)>$BB;;>WU?py)Cdjk4AWG`bYpCvR9WzefmdfhH| zR_!PvZ?pVqtG<_-dkgv@!S5DGfRCt8tT~lmEe)dNyx$SxY2sDV^o{%#NpQwJF)hQW znL|f7#9@`+LZcsQR1EEAVo;I*-7>i!Zcx7{_p_w0S*u;KyQ05Oj6i163F0Cr5~ln< zOx;v#PrRQ1YgsfGSQSs83~TX~+W6tx5#qCA<+GQjGv|{oQDDJNSGo1N2!(tyEMSK{ z{tk2{i5>ClC zJRQ5{nD6wZPf?YJj~X~i$k%@8ul8^}yIpF>uV%Z^pE^7EHO$X>@Z?FqtqU_b=Wpc^ zyGrHA`;`LVa`M=mgzD`_^vKFB&iELH1pf*{dgaFWs46Y`dm$dCjLjs{rGYRg*6GBp z23UyVv|6U4~^)kJo1lF`%sjf(k@P zI|Q6*Jd@`6ueQOwx%|(`ll3Y<(*Q=B&MpDNBe0FR86ak)3scX@zxfvV=vcwIk z_B6l!yavZXpQGx^+!Rf5@}fU9a2cIv3A}dfoY1r+t6_0Cyy#5CqPcxH6CtMc$L8}i zX)W2usd#cbRZN3(t{+axoCshOa|pi%Xx$j_rzi z52$*KoyQbCm83$9XQ0@XOs=@%z>EvXp$&gL|BdVH&L6*yAMMAhxW~4w{qZSaHN;BAV0 z4Pk+jqO<0u-;wjUW?GEfE;+2O1Zunn>X+~Ch~+!$D@Msxq)&xcCJcxf-u7(%R=z&| z6JZBSaJ4c_>OE_wHUV*|jXL|DxA-t+Y8wmnCp@Z|irsyMNzKUCdPjYWeO|Qo@SfdU z&b8oS{|@<#x1gzW(d7F9zH54FkJ!u4wg<+%6}x;`wCq7k4?`^Kp2>lV_Kuf&!^`l+ z(v5Uy2DN|P{;%!5$@;@eR10Dt^24^_(%RQ7}VnFy{Om-=O**O(w7&|`#)L@qjHmMRWW^j>&lor+??j> zB%H{iwGd`4o9)5kwQ}ZJInxBB2q z%3AABp4)u+85uuTfWxB3z+-0irSeq-4TA@nrXi**cKFKr#74WLIU^$3@~5^9{r=Uw z(OWwTLD`m%jc{<(4V~p0W6~8w*A%l#KTi6oCCm+DA9J;+2BA9xyk`|Iwl}Ei_rADK zUVYdz0kNx%*!uiv+fwO(%tw`Hq{rOvE4Prrr{J&G?HhhSBHGAwuSG%5!88i@$TYdO z$g@J5fegjgfD)h%bAXttc{$j4-^SqJmXoUx<3!Uk&@1N=gtgQ*xplQ|u{{JmGp(0h z6b}27#_QQl*b@xfaiN(7*y3Q<=&x-7+TM!1;GY(y(dq=imgCD& zBEAInJfsXGaAavsdSI$+<3#fppM@G9O=Ed7wV3pTu=Glwr;?K2xO6I`#dN=D-@U_4 ze)~k;iAV@)M5`(ef=0IDu=9IPLR_UB&6FOVdr`^0OnZjeBh_sA#(w7!*@O5JXvDUE z(hxW>p|?pxojJRRPbH}_fvZ0BTmP`dZDcQ!wCJmj{njTy8Zx*YqF69VIlf(v~wnx$w6*fmw2aSLhldKc7z6aM`@v*m{$2=SC)ZH%i9SZZsJwYKn= zWWJQym{q-W?j*f0_D)8fcSnHFVKVDl*x%8D?iW2|>0|r9BFpfVA*{T%UY$AfAO2M} z`qw-Y4mq<&v$Y+N>-+RtgsyV8!fKNZhH|NLX*pY{%lDJEItYEACs^<7}63^F%ap+1iwFoJ=abFJb)5JJ^6mLy= zqmlsPLXOv=YRVdJyfU*xH5d89b>cCtXxNYp3KSzi8%l2Q zmVi?~W)LT*y;;_=L8^)sWMQ^%ez)K9&N_Jsw}kxzpPc(*ubymd{7vQU{A^^*2`p?y z_+>S+rmspVfH+$drY@&OW$ZlrdHeeCzM{g3}G zl;qgNSb+|3n*7@293AZDR#&M)vF0PuCT8$+;It%V=8&PZ(aGFWQ@|@`z zNcKVY$%Je}_I*ha$})C_v5V5!n!*U7?AzFqElZL;A;}iP@1^JSJm25;#hYhr>QXWedc09K!{Xs}Jn|ei1jVH+6mBz8AH{Pc zip`$GOoMYcd2Nf56GCYZZ%ri~{T7S#q4qC}oOpbZjznDb5{glGZ<@}e;k`Xx_|xKy zj^;p`B<=;&2R&^Y*bqckurapEXFWe#!1;4<-jZM<@G!XQ1_>+8e~%~1m}H-OxrGN= z`lmhM&1Y)_=AsSK&;7Q&4!z>y4Gi5?7sWO5^Oa0i852-C+K%z@i`vDc3=C)EZ1had z_sN{lpP?v9i$sgCLc~%^&UABy0|_J+ednRk0AgERJ|jHumVaOd9wize03(ru!Bz$> zo*JK!a0sej$|*vj)b)e}In{GQ#h(z_%FANN>BGy!mN9-P-#pV8O-Uz(Z&In)Z*NQP z(;dALhIp{Ju=qLXBopDB#ie*|PWW)-G$JP*;=-a&Doa)C-nhPgd*matB2>#p-Bd`^ zxYwyi#e6CHzeoLW7Ch>5&!Icw4&s6;S><&Y%zx$1i8!4FnaPH#Ms|&~Zb_wZy}Eds z&J{&5ldD&I_0Mc!)tER9+tM_$X@9qpgk5Joe}2)CtExo82sQ9L{M?P?Hf1G2Us-Vx z2OJE{250I_lr_3fItaodnb)sTa+XnwYn_)-WKfeA+bTGp!km*vZnh}?^($>rs>F`h zukfcHl=Y%7tEGg)MqUNvL_=y`_V@2@{;@sGqbAiv5*_h20!d}BdRyvViD!zWDj#>E{_Sfye zxyg$}p)%czN8x{?p)gUfP%lW({?9q4tlt0-7n7ck;h0nVLihIV&oT&oM(b4Vh$y zA6MZl;?enbg!F6Bw(*PncnlmK@(2jgHt?mm&nD?RYXmh<3B;uw>1z{ z2W*1_&*8_-2Jctb2~w&O(g|fZBGgRShF^O>L$1W)O_vl+-DC9P6JC{BNvFiH`RQNn zGn(VACK8H-QdueLvo1KYjpUEvJK z7_htUo(tk}fBb^mmMYY~;R`JV0JP&y-Oe zBZ+QhuEo+kG);HA5v68hXBPPw%^4PE9|5`Y!v5RXD}X7Wc1^XH92+LhMN;d{hTqsW zb+{xvqo|5CFGxLt2=hSF;Dn!Ba$fOZ$7m|l-2b~707SBv8M>A zs1_*W3i`?>bM+>M#Jrn}cE17x0{9 zIgPU)jRXx^P^cw%(+~t2CQSQm5`iS%c`bXm{@`$-uSy*)zf8vQ=G9t_U~Bv1;H8%T z0$B9wX_MH-(zJvDa#lcO+_ifM79*rZhX>@tP}3xd+~nS4(K*LiWwi*9J9 zTfQ#JB@(dTj-%@FL7Ry=%-|W>n(oP2sd|wp4Vg(o(`n^J0AOsHB>y z$Imov{GP|*x!c6{eL3SIDsuZ+ZWDh${*N=b%k>xcydssz;IE6nKFQ7NIPRt)_QY{h zcsjipQuLkMqt6un`Gw=?t^xL%97oMt!+bsUB-BiMv-(S3&7$U!vvw$bPpmck6H9@3ta_!pnj2c~wd^G>P_ot9ZHmTkM4)+S%IJd%<#ldVuJ_${ zslVlueixl})~-Vj!eH?P6Ot(Xgp`h9Dw~D&)v(7Pwrt^95|{c-s7;KHh32C~NyC%- zRXP^$NV&iE5tdr@5DH96!ZMmypZ5M|qn_K8>kN9GOSCJ)w`*NnS$If@Owj$Ld`QSbd`iEQMQJ^LufFJzDq@Wf1chN&zo(>5o#l92q4SwYE3s?-#1-vS?o$ z#6Zw5betb_7eMmZ9xUEqDcDm8BOx2Y2cpb0Sx%xK7!t1LFj-OPm?2!E^Ssi=BOkr2 z%)1*>qeu>k9`}Qt=X_)J4FR3H4-la-WrZBCj7(gFRK@w|Kpq-(}$oG&dAXv0bm2UQH#H@XLSm0rVcm9>R8u@UlCBpU1=c{Gva)q zj^KNll!KSD7`I#*5~=Rzbr<$I6P63Vb15e^Lof`YaJ;-0@|FV@)Kon$$4>v{!K(0m zuD^Am9CCVcPHVzQQI7Y`*{1~h#dhdg&b}$)`|bu4k_Z$U)d-Q!=Jp5?g7BjI1eAwr z@RJjSmXpSG_fk33g9Eb5a*ar}aF;?IBCCDwVu9K@%GXc`w3C9pSvKvY&H8sG*+GiR z@BHdEktEI$O9ULi8Jgawo-YZ!&&OZYImcu*NSAvwlf0ymNk2n9^t$e1_cs0vaokgy zr(b}5Hz3dUTUJ)4G_GEVT>Y6d2@iG6j|_S9V0#ODbY1^5gifg6$!^2yRW2j!gms@A z`S;(VH%+PANuVX`UJp6!VD|}`CkX+1Kbzbh1=%Vy2<%*%B? zcM*g?i^>H0=*(#40N1OfVcJ(FAYQ5nW9rk!qB4?d1Ox-5Ms}uRp7v9Y!IEfTxJ-(* z=b(f#{V%G;B)g`e?RvMuFSQwbMimqrZ>^S(4`yTVg-g}j2CXd3cMe!GQ%Y(YH?l9M$G!RYI<+UXC(^~yB79Y zX)$!oY9W2<5=ERewI>U;cMprJcQtnuuO`PhH(7_aqj3CB64W=vCX(zW4g1Q@m{D^s zl7-2m=%~YarkHZl=;^W=B6Q|=w#6R3I3=^TBsM?(&A0pYUErN*NV*~j?9&r?(Q-x9|%gbH@L7&;0$WbhT?M-tS0$ z@=xDY7>RzL!e*_2U$jZG-ir>mzvi4r(=e#fPcs~FSpl-k05Q9f%_g)RkqtF8C z#+-y-YXvN&e0Gjpy>@m}-to_zU3~*q++6PHjy10Ae)^cUR{DWH>(#~~Ka7M~MJOFb zFrL$tJFn$jpM`(ntV|+x_nJL{S5v(V7ID)5ZIaV!OC^lS*c-$9 z)#6bnLdm&2#mqT`A^*=x&!?AsXMTC^!Do6i|$FJSH z(YE$`?-Fvf)JiF{S%u0;e!i`%%-5q?4Zbh+d2;sNNoUjB3)A-+PcD0_A{4ghGR52V zI6Ft98l*d->ZvBH6FT|3ru(%_ERmBPn8~Sfa!6&zF%zVtwoth ziU~LG`gMBeX2jn6tHy4X%>oi>Nbb>tm@ErgAMkbjpH?g;D?Op*A?k)8I!UU5C+1#pKFU&vbZ3_JQ8#j7& zHMp5OD9g^dcTLRebL8tKY3Y_y1M40*^Dcx#!X3eKnOjo!m44UY0jC{oHM(ud-&tYy z_x6(ghMV#i+;rRYZBLI-K0n!KR=(dW>z}nTHH7ELNagj2v}Yc;x!S@jji=}+&U3z& z`TWM)-=0+NQqJVW_R=xCBq#0emGD6?d9hi=nWM=3kl$7rC>$8sJwowBW*0?xCv2M{ z2&?y*=0E3u2tD4)KU%wYc$~-;)D^`0@App&zW)SN{o*`r&<(><&CH34)$0^1G`^Zd1`QIU_QjO8df2gvp{VmEO}W``G)Ma- z15ak@f~e<$S=BGk%qHN34eG4eAYdb^fHE!sw<1s-GfoYAL3Zma;}FfGJ!?XBgY40K z=+VRDv4furU7-gQyPLLWw7Qkkg~bCZ^xyCFRJEm6)Np^(F|Q?NXVW@}AqBQ;D~KtN zl6?E&Tv-|%#*T?SvpsA4VsnW9EPFGwxl6T>*1=p|tnJxdbp|X<@I^tm?0IQBJZdM08T1QbgyczIM z)E%al2%j&c%9rPZD?oIdBCv8HP)bEvve(RBsSuvKLI71s;Yh6Of%hLosc}>DDAZM$ zp#)*hZeV*3I5@^t^ogqULSMf!4^38Cch-m+-mQq z?W6@)Td9_t0Ga$6zh|o>W$*cp|iLfwxqivQShIim0jn*9Wy^}uhlm2(N6A!d`$L5M6C&I%BL*B(<^_a1eC4amH(ypIpKNzrY0 z7A|Q7e zq>43^)hBg71cJ~)VIzg*-tsza*2v>ig=A!n*s=yrn#%PNf^;9`k1lIiJ@Bk+y3ccu=W36?S|6ovObLeQw|?@eP%D4OC_*6| z{mAD&KAhWEp%1ZaiNP*ygrQg+c!+I0Naw4f;})0}JjTpH!dG2gozwhKI#L^YBYr%y zkh?N7s3IJqfk4yR}^{?tmf8G@*7v~ z?>-L^F3j+`UzWD>XV&x4Fnhz+_2+H7)9R~XcayPWB#HtC8(0Dt?Sb*xyVRjuIgQcW zx@!^kifeicSpe2$lG>3nLbBbZ9CI(SIPkE{Tz-k48-e8`liv{@6e;*h#oR|{qSMfs zYQyw&UER~MnRHy9Y>%JRxVkGW7I1oaevz8`X1~9Z*o)w>h_DL%^?QU2;Tovht zw+&{f6nmd>b>YL({>&|0Fp(U{J3R&eSJL=^Rg9u`?1z`JpkpZ2!Q+m=izPHS7JZcLJ>GJ&Z z9`BUN#)mG;BS8!14|x1pD?a9dNYsSv^|Lg~c({G*Jm%{!Ef=AwW?e75c-^~V?=yP8eR83 zrD*EQyM4c-1NXykw@>C|$1+SFHWo+D?EC=`z&|BnnkKCAA?@%nyvlfjNADuajK>iz zwk1&@9vlwml7qN!~W1n!r~qxcx|nqptY`fz($<>0U-+_)(X`@;=E_@-_K9yU#ik8p*H z==AAc4mRD8(ne&MA3&jcB-;bVS=uC@3AB}r_tx8xSI1tdHRU@=_b3#nZ1ZSTjwMx4 zG>yf0zY|B?Jj@44tdkXi{m)d&PI+2IvL!Dl@)9s5Y3Vqa@A(TzqA4q^KE22!(F9rg z`ch^2V!IpIH^(oNy(Oer64b7TVDU^Bh_HU}God!5etkIEL3Uw+By1@@09Sd|W_R$9 zhAD;MPO@IR_3v-BciOk!elUo3Bi_3HxoBSB#jTh?4|zx-v`Adn?-v+o4AnvksADa2 zurBTP0!bb0S@wWh=i4BsGKlkD8eX*ur^5KpY49gDI7TrWh4D`Uk-kM*ny_p6Q6fOcV;r*(U)_g?{ zX!FMNSJ8nVzi>6i?e?0ltmtNXBM@8wiya>+rQ#Rr;(hr}pXA?}zk4x&1v-sE@1q9> zs1+Ty2OwNX-hRQ8-H^Y8bk=j%%Wrwx^=V)XkDBN)LY#@klR@6Pvribr;-xBMh31S> z0_O??e=qgc9kJqt&kO?IC50UR-p4Sp6iHI?stw{cdjSX|QzGSwuhI@)u7e9f_L}l? z$~&W7Y!fK;z|LDin7{MA)N8Fqa`3e`D^fKziop5cb~{m@5HG1UhBw7OAGgfF_ULyq zVZi*SNp=r>xOb9&*b>2#rJw~lj;XOu+l?DKF7gZb{rpXn@cL!kQDx|of#m}`?=Cr; zH}74(IZ7IG*d4y>%mCJt?Q)Npt9qw(X#4w5RR{imyef&lOs9=Z=jO|e$c^St4m=n) zUno=d=VG8W7^y4*W#H++M--2Hy&WSR!=@kd9E7@3=w9ji$C^4#37xrIi7pZBr6SL< zc@Bf-NRni}N+Ad@b(x)mW`KT9;;dh$@)u}{+}ej8c)R6Nk`IEY@d-mTAH4pTnl_5Z z3>zWnIUR}TQva+9NiKgY5AEGMN@`k8+JSF4ey{#hWpa>zTpBvx!w{$F_{_qMUj{k{ ztS0GMaWoxrdtIOyAS*9*R{g^WJD#eIQf_%=jNDV49Up zV07Wy8tAuoH136dz$0U*Exalmc?h#Cj)b$7T!ycPhV>9V>-sK;S-%f)UN3U{Oj$0| z#3gj<;h%49JXudn89&vBZG(^Zi+wAEqHd-sK|gg_7Oc4-rC<~F>AxP8m7xV}Y7{li z#1em6vN)7w9F-b8+Pn4BL-6F!2;VU+w`*-3NHluD2RQPMj6?kQ=ae2_7lqr%}bQ6u_w#H!HID20|ypMLhx|!Jv$8n;G zcX=}$I%`NfSW0_!nd6ev3C0-#t>V-VF=PyJ08U)8&ypu7@$Upkj*ixIQ#b>=K>S9t zC4x|Tg^PDip`g93MW~|8werOXUfT!hn|e^r)_xo$;WS|$JpRk;?bahl0w#n@+BS$6 zN%a2F?tr^Z@+s~w`VAua`z?ut@PLiF*pVmZ!-j+>!HzBNK?e`hvDwr&pu1|oIl|ixl=Axlq9HNv6Hr!9V+xVqoa7T+|^69Skgt?MO+wun(|J9u)K~j(%V+On8N2_I^@x!@AloJ@h3lL zRSs$Hp7d?U1kQXY#Yc4Hr-RZ&f$oJ{@BOdC8;ENG-7QXh%)<4$bqY3dQAadDYus50tE^1>D0ch~7k?z(_*qS8H&`HtOs>wDYoW#w7W z5S6}F5gc`!8*xRqipNj+0$7p#j!lq2@125OBLs>!lC~^xB+?ZU{L--MZfWP5^$_)x z6c##Ly6pRoL{fBb>k{$e2=)+QSWGGrF8x^kP#yFa|Fjm+<;B+HMPS*?#bU)oY^y{4 z?;>0joZ%FPbL2PXicrve4VVD9K4Wn(ZNxbZTU0C6#D2)gfFvrr+AYy$l1dg1SOir8eJ*hJfBnEav0#PH z{hxL-2^#`1BzJfuUcFsLoGv?E?XARdMH*IUPRHBd09gv6WhK-8oM~*EvhN#JHc%gL zFIWMaFwU(zo$He> z;pX!i>C93+5|cTJm&(8bo1r9OC|;uqL-p$`kedyvfDZnAwi)qS3Vf4@@+Q(q99~KW zW)*wCXDgjRPbV%(k&68_IEB5Js@40xm#@ht4GRI4$+Ys2#O7m8Y+Ao!2HQqI*e;hl zhx}&^rzrDrIa}!BsVM#3xR_p#L!!O0?`4_xM?JeY;c;1bU@FrkgkQ)(+3F1WNs&Xd zDTr-uT6+6dh|bUKQW;m6Aa(Cc5h?Q0t8J;0d)I&PSN2Xs*_as-YXUBFJ&>j@$#?}m zSPq`dQ3yfJ-un!+E==0Ew}KjycD_=I*hf`v5#$ z-qXn9Fn->G@17lC0 z|E2EK%m3OalrMVy66G7vwX5%blJzP#GiKsWY>XQp45FiB@|a2$e8Iip7ucwKS~_9; zQqXLL(iYB<^2M4cCP*ZtL5TLiqAIq`q-vGz%pk1}A)(%hjg&eSi(b2`3^=ZIZzmRh zvh9ag`AWeP8qeSX`I1dBB_~PUP3clcUmzgtfD;%aJzH?eYHA^IVe)E+IQ$k*yy2@u zCpjsextLcPN;Mo4Up}emAssKuIEJh?LT@m<>Xe}4`1}XvZ2MzKo^eUGS1tRtlFV(NC+9=b-SaA@R663t%oA0~clq zz_7%W3Ec~o3)BqAQp^4C$Jz6`7Ts_eo_46Iy4kYEC-9q>^9pI>@RxK0it1iSg7%@Y zbMc6S3cx^sHYI~m|Ct~!pITLWUj%&CbKsFocVq0mf+Qwi1iu6K7E?5AYzndv>Kk}_ zyfDU>{4&zAS!Nu04fjO);b35>%HO73)nKx`xK9N1V~JHt?zcrA(IAPMx6F+d*Fa4{ zMph+bxtEdcg@vUNBNpwFAS>}|WqhHEyRS}&WcB|;w~&U>|?*5QFdkS7P(H> zB(2q!By{HHIo3zxO+74h2?*uO8CYmno$UW`)fVBa%E8b6zp11Z*Aii`Zk&+>;2gJg z23F(?7zmNpK-9Z2>gP+l0yrL{_Tu3s$tedOP=yyr!lqqj@V(4&?}wzCSxSA+co`sx zyjnl+I`G8ZcO(q$@D{rE!|yrZ=$sV*`_og8^El{|d14a#x_`V(R_$FH_VqiWx@A%9 z-?xV>`Cl>_h>Jd14Q%>D*k}pT5V-0UQ}zrsFtjZmC<7zD4G08wB}blS6winb6C_Mq zgkXG21CcE!4gPgPHk26ScI78v$Mp`X)(JI=MHi>VGEx{Cjvs?!&`B&%v%JtXghy@m z0H*5KaefN+hlfPAxC~6+fd_4<sg*OYGES&WjLJB24mTZj0A<4Q zZPDM^nt|R900=s~mu-L?Z#-J~>e_Q>eqRPC{@Wxk5(3JF;@WFjm|2yh0E~5G*0KuI z{<<5!JEh@rb_jXB*iuG@#p2XHt+-bIMo|=&*MkHs1Qe#PGhDDsJ#HnPhg1Rw_H(lx zCNi^k(n|NOj{6eKo0@{M1mLGx{td{XQ)uZ7&iRNBPwu{5pZH{kdu+n`Hx0BB6ps|>sYu9C zvs@m8Dux*+fe#=91OEN=emK*nkOxmDUY*l8o`Z0}#szvu4@P}T40!+G?c08Ss@4v) z|F9UP;a_f$DyA18!9eGjE#m2tPF5X73Wi68ls12;vkU*69BtKyaB zgN|nTOA|7N7m#Cew>tg@LWbTi?+}oqA+9+Krr13#f}8yVG={? zR`H~L-DDIOO;}++>d;#QvS6z$^+FKJ5_f-Xbkhq$JN#wI5HQd(VQQF^)EEt>&F(?a zHcLJcN`1U?=ZJ0o*dF8dFhg8KvJ;g~apV#FzHM`fmoT&j5U(-vvE-O%-Tzta8_j;I z5q4F{z(%`XqKWWq@|R|A)14|?^gE|SbiRRGj8f3 z?hy2Xz^hJZ(gm|R`dw~AyUK*2j}up}J zMG9Ak*q+|Ht5ZV2Ecm&(o{=Ndy?#q93&uCa>N~9RrBfe^g}0|ZXc%Q6b<%r#bNJ3_ zxsuzdHlJj3LwuY-7x%y&hAXNOrA(eBDjYI3X?(S^=4)1+rU=16nMZo_t&UTyRc~?~ z_p0uD-a_&4*5p#gsc3+y5b1wOFB+Ot*F|2TuW7LjB=^w6ZRR@(Z32nbdvwT_L0d=; z7EcQ3=0d?s_D**Wt$1OjiT!Yld)tMu!I_%q;(Kwgv7|at{ze9PE+TPv{+8&4r*8IF zx@0G9@2SZGTVOV0F=^+t_zt1njX`!-h&W+P!zH6j33YSt!8ziL&oEk?r|PKu{*dbz z6jxz_)Uk6tbb8IG3l5>bszh`*=cNmMzY3+se=u95*y{#C#;@kg!R1`g>Cgnx0AoKY zr{Szc?s*1bV)l#y@-c(i!rO{EIV7^@{DS>Ug<#E2@4GtxXrs_&wMYOebmx!z;ml35 zqNjAu86eL5xh;g^F$05LH$ln*tO}#H36dBK9?H)C3I&}B+Pn{G>4_jnk=y_r{b;y5 zZ{xkHAqV8SJtqXA`LS9>$zyc!1x&F}4%V$>oYLZfFAvU=_JHO#68* zD323|NC|)h;fn$L#gF*sTTTP~f69v~NGwW$WrcoYv~?zk=e<3^9q)*{b31Jgo_$N+ zhQJZPZ z9>JK(@~IA@>|>0Eqyj>D^ttP;_fh=NC)`)%iBS8={7Y7Q4|7woodsP{c8RJV7?Cxio&(Cf$mBpZuIJyG((r~~I!k-bpR+ZA@tp)n@H3r8Fj z>`@DA!=EW_wCB%il_Sz$)z-WvIbj8>$wpmz>@;E>nBM=hES+^ncY~qOeRxy z=a(q7n)h2xa&xvGd@TF&z2e6{;e^& ze?!4BTsOhWMam@H#p;i3ueY}uBDSrOHGr9lBNYot^ZY&U)(slTG5q$$axI?}tZ9#W zJbJ-WDNlT^w86d%k8=L_1{|blTHPKsC953c)$lUB-{&M)7I*Yb}L z@%0Ix*hk<}2$ax%=LogEh_7rhVJM`+N?6eNUZPOCF=OtM<%dc9izC&pPxrxi*h3W? z-lh4Amn1uH;^wU<7hSeYlnDPhviIkJALDbDe!HbJ;!Mf}Ple`pBe2B$-e{+SOSAVa z#2Ldsm#I%(pZC_)XHD1vp#y zpt=+taH&l%dkMyLX=tyq?omB2ma`%!b|jaxq06ge|Moj-r?$H-`{TTT{n0=Li7G%3 z=-z9=I~UM4x4h$gNlSR!-W@lac+VYiCOLa_#}Su>_tUDvpkmgI5$7?91p1#B!IAH} z&Ic2=?)}YMMb#Qn6e;LivAuvXi@4Aa*Pte3G$mt~n*0D1trdi-u|eGCdA+YeO)R|? z(xhd9(cSRreU&e9c+<;AxrZ-(lZf7p13&+bV#(9woRlh%Sw$EM)^0)ZID&K3bJ?Hh zNT_&G3f@9=XHDA~ISWD4P)~QnV_@2HWYm`Y{(R`NqF_j%A>cG z-U6_*Isl|Ipy7mTb>$v)DkhBE&-6)p?zj}QaP6B=b zPB8a$TK@cL*o)p1;lZj1!I|Bc_>ngdDVhkgti^L59fQDgK5N3Yr5h(n8B+R;lYC|N z%?FHbmFzACKhiD(t>J|^hn8>}<;$gGLa=6)l=4Uz$96=0#MUQ>9By`}2s8FPYdm}i zh6^uf&1!RgI?VcTgDwk5L){Z!Iu-6Ygof`WW0g|8b5CaG)&7x|gEKc*04}fm!vb2M z?{^sVqFCfQVFY6<0YVzqriG+x=>?a=;L>aHbm#UeHy~QN$2-(>-Un{BQ`-9!kOOyZ zyMHX~oRNIGlQSm_`>Swo2H);RpbrBHu15!8R4V37jK#4lduiE8+_#8KnJk%p~&a*r_2>d<{HAz9aqOy+Hl{*t)JD+rL=| zBy{6ZU4rqfDG2nntB=w^^jSbJP}jhj!k#`-xlF_%1&YBZU=`&f6Ei{c!o(?ZzHu&9 z;XY<$W9KUPbU;<=xq@8rsiF@9D$H^YmIkYJa<9g^mq=DvjooeKsQLpj3lh)T`J;(A6)}p-ZfCz?XGfVH@q*~ zaT|1ipvU_8xg z;sTnU$^Z($=Qcmi^!97TbGayVA}_upqIYfG2pab$$;{X0*y!mv`9wc|0|i$A$=xr{iA#w?p*H z&!(N|#=iuj{{Y2jFoj&@Z#Ow(g2*{z#mq zjU{&=(PE*sSTsEUf_MCTE(pF&RhdxKg}{3oeOCQ|TOm|;Eu(OXGvO@S$dA&xJ?jbX z3rDYOLjxE~E^JpkQ~9}j67s9jDs#-pV)0N2$WMe`mF^YS_gmHf`qt;)vHuR;Km1Eb z>_1pc+;{_MANmZ--%&tqU%Pq?TqHFMSh*XcLu4>ELh!x)IG1ZXMhJz3`{;2LkFEh4 zj8?YO9K0gJ1o( zVMO%e7dDaFWVr!~7C#x=$@>YBDrdra!bkyy3L@!Koe+%V+t3d{jeCDB!qJwl_XQYH zE4_{?C18SXgzOcVYe4%16$I*^0?)$WZ6CoUqwmggUfkD$)==W5U<5ykjXo}S; zV}}ZkRDTu7mo5NjH+4l;o{lO8@bWi9509D-RQ{BT9`*5E-AARWOrVdp_(Fl(?u+$4 z@gT;sDgRev!i5~&Z<>GbgdwsIr7l;7M8Zxu4w*ThNjI^Gei$` zWB8P1fM44|G1=dFsdW63n$txX5=%w*sr(?Igi*WrLtg+gJxzY{t$uRaTr5uts#^6a z^5MvW2PhrgD`14wdpIGDSOALrB$G?#jqqyX#s-AFZP?l3CQB z{>z*NJC#HIOM$9<*pNn;c&(>=_-AqGrl^4mT`IQEC;JPHT$&hqps)4R$|}T=tK64( zPlftl*q=)i>-%0fajT_ZFH6GEjEyu~qD%~NVj0{M>45*b6qPVWBw=?CGO9rY8Ldl z7H+Tm=I8~l#IFAxpE+7n2_uWK6t5Bsjdbe~*Xlu#dJZY+)RKn%3QajCv^)4=W~ANt z=W3SaGzJGhT4JyLszE`4+aIIXrwbY~dje*{tX16iojd#NV?4@1&v7`S2>TB9skZlS zI<{tAEuKKHYo|j$ z#gWZv3ow-V<=X^xVTWP-|0LpnYx7g~4J$^3zjy!-Bab{`m6Nd{jaGi-Ls&>RxxNHFM1F(jCFp#7Ve}N#~ zuB}`t!;=+wj=7(V45Zz9Ee5<8*I?7BMhJ;h5fzt9n##|YBJ(rZpB8_OFx0f?d$M@- zo67UUBplz&?`_$c-+_$>aiNQnHJcR8zkWKstv-Ru9dD}q`cyH#R0!n`=n1#GaAU8Q zwlb`5P6iMeH+t)+e;su3a(VFm7wpDA%^C-`=22?jLGM`FrLOL8uBpk1MvD^RAyu#Y z!N@OwxT$o#H<9O!PE>ZksF)Ij8#WGKSMSLefB*91k>?ku&e(hOI*IMwOxof;6@8Rv z&z>+`i8hbmSJ!DK^7GTGH9rn}Vy|~>=qAQX*GZ;gOOGex>%2vKj*j1)`2ttlSN6(F zSCfRVXbx#_ZTauLH}fC(;<}tv{o%FMa&DQ$-uoYig%3l%1(^(oy!`Rn*E6tbD{lvB zO*buQTr-rs$6gP(vsl%eB@R4RP_;gZZT~8INZz71{Xhox7pH%~e7qx12)$~VitOV*4ZJ|EXo9_kpn3-Qf)2WR5KK$f#`Zbjf~t&Du;(cV z^p!pEod&g0e7k+-8E7{=`&^3)6Y)%EzED}00~wG7_CZucFy%KXG_Dt+@lmM zMco~deWmv>je(Gj3VBF>WlM%px;HX5`@K9&fDba3}3X;-s) z$<B@AA$eN>Km4)MfjYeFE*{}>v752x-=sLv*2Gt&ndp2uEsvLLHV#c_T9yl z5TVhJJHFsE#^Td%YKz+m%ozcLZSymr*tW@Y@ovbUqtfd-^B8cf?OfMge!fI>z!C%x zrvF?>QTGdsZ*S2_&8Z!uMGCCF-fq&8=AtseeP4tnYR?7 z@#Nq}4A;7y^griqFVGY`g4o0ziH@di^*QiRb)&C1>YMKFj8@eja>@9@dD?d|YWcys>w@ns!ImzD>jE(%kHgg`t=ejp z)`G{MKP&@%*w@=H`(+9EHz8Sb$)EZm^k)>=qt~uD>lHd^1})*NTv>1*V?^H8QGQyT zz5r2n)1g4$qzRj(&T&!a$2|zV81_z)cN>>dzwvbB0_O0C&ak!jcuG6*M`k@zAnL2d zo_}B+^?SKpAw``hFQSNa@`kO(gM6^291aLo+?2G`2t3cY4Z1J;A*=XZ^y!f zq+SMWsXkJC7VUvxyDak(QzWTq6p=Mi$9zUInzqxm!rJl8@8SB`JuDCIJaZ-wYLrI z^J6NSd{cH!vJSr-f%ns9g*r7qOBK5G;5YBi6fxo87}(xc9@qrf1UBN|gr>j|7-ky5 zcTP8Vq|9r0f^NhHh zn;Xr&AeswaNxS8PQeMGaV-${o82A5#^wr(p1JRef67lUK`!bacSo{mdZhBI>m2dhh zDhiyivmUt-gZNwBa5$VOA7~gJQTc5W#OStzw8BSho3a~Hc78YKKtZS*KJXHsmNfag zqqg$>#YdymIjg$@VR2rsG(IUvrCrDYW2dt3(pay*cJ}0fRg$qk6=kxzEU&GeU8Ey$ z#H6x0-6OsJ>65|d1B_pG6l>km!=~*(<&%{Ut+n|_qfILit^4vt?6=QRku+~X)C*<` ztbD&M6EGFaww7py2isGZ$c5|2EQQ){tnCu$eVH9_F-4}00jU)Ko?qtjoRvo=ZTDZL z9nPNVjE6vyE(FHm-xv~wQbxv7AU8ZmNYr=r$8R~RG0|{{)BDofF7qKiMilnLZ3jCl zIqU*f#^vHYO@>L5i-w=&H0!_jm95lW`)c9-B3-U~5QsS)kR@*M4iekJ6=rHhhz4Q^ z=H<5T!N$hpGb~TC=N$vV?TJ+B4?GJh-L1*V zP;*txNcIW6MIVJ?&dgITrql%fx}&TZ-#a=2feJv zhS>{U3vO*mG!~;SwM)ki{>kSar44Xk+shQ%;j9(>1}!@fSU+|C+{Z=3B^HVg1>!{h z?}VfunHRy=JG#Z9F-%vksD7#U^Q+;pnRF|-cVY4gG2F+~nLvslt~|OYPTfgXI=jj* z0`K)JIjCu$hXP!bL+9Q#Z$MC}`k2RJ;gFdP4FQ2goh5bXM&!}>2qI#I71&9n*!|}! z7#r^}Dj7(GfAh@t6FD3;?McrxQ>EfgvwPcCFyf=P41)W`eZB~TaAJ>ScYcd_mIdB} zELbP@)iFYFFm#^l%Ndl2eWb^*^}e|Duppi1087~1H}=t^+kfKZwu1N1dB$&5>|<#z zBhG~!kO(2>EwTMagu~ssSq_&O&5ivxC)2EeK|J$Mcn14@LT~W-`h);>iC)bk0 zaFi0PZ8H~`oUsHxOXpC1}7Hy5u#Z@}I@*P*d zUa`5HfyqB|3VG_rwU9-(1$^o)A*qdkmwD|8WKD6*Yx8QeIjR`Wze07boDD+3Vpfyu zdC%xaawp|ZN_mJy^}2NDXU*vqa}E8SM$R2Adp)mjg{#QEkvIK|M>Ux?=dDpA$G4L! zx=R_S5GA9hue1LQKQ6zyE&q!1i?aA{r9;KxhpH4@$Nd@;$&kMDzZVqQQ*{3=y|7JR z6VosU#;LPm7YHn3;*#7L;(*A@=LmL_P{hO^UHG}j#h(SpcZ7+KF0ms<-6Dv7z`HR4 zfb;g+@MDqqr^FDm z?D;WcTYtHpiC7vkd$yD9?&4nTb{XK##RMQy*}{j&pHNNxne~zzS2I5(&nJ3p`Ty4b zwOagZekwBFb=t6K@2Kaa;*5y_lB~_cAtgkP&A@03N;D&hLJ$nP&=NOxy(_+20cFyp z{j(N?DgX6`G!^@^LT-PA2G=hH6!_l4``7FYKgj#Q#fkb)3xIU;z~C){tbU=*{XwKS zXGY2eX_5sS;^RPR6O$?$V_`=?eYk3*+`GY{LrUO3BHY%GV8ioA&PF)6R>0Le*kFZO!}Vlv~BS&;2OT zc3(37dieQ(-sH&4`0&{*1bvIR2x4P;i~U+~7G`jBwWGOvZ47^nWG6I`C4GIFn3GostUY`ops$yjuuru<#AtYZ_s1$GrUGo z;YNFy>Lg77K0x*>OV&`YY&R|Ekn7(Lxos1Hgk!9iisoZJGyWQtQEqZ^9r>6oQ2G7K zc|?))?R|@4lmA}L@jNi%Bda!9WQB_pjo9mh{OXO^?*?Y1PCF2Chzj!Aio+kn6rqoM zp#Vo3t6Q^jUV9WposhcQD_(~!Q<>#GY#}7VFXP3^b3ruYiw7N%_(ez~U^FKG*QDCZ z7l*W1azPfxJ;XgBa#;O+z5FR>pS^r?xRAxKDYlb#k_@f$2J?M9`aQ0j!!dH;MaG`F zy5C{A`=@JK-)&fGji&J1{8Y|?k2B9!Dm-?4_uEHhz7N)BR56s@D!8nMwQEZSDTa-_yS zy8JcRc$SIkesX|;a4kaHX)0Ahwcn>Gve2=>=U+|Cu`#uA7<7wAXXoPu)?o-K05 z(VSwk>MPVj&0gGY+;bYN8P+b8Dk^6A;r4K>_3PXBJh!^tI5KQ@nLUxW^|p`k$Sb-? zK>2W})ojL+BF|lC+d6en+Hg8{CUK?=KQns7F0CO)Wp<@>lK1#$eW!|W!o9`RgP&fv zDkYk5i_SXsfV44S#_MKY-@4Z8Vcvg?f8yWEJP%hd6xdR3Yzno1__^}7bRmuSTuxi} zX4=ADQu&9zA*JT*6r6{vf00n)_G;(e=E7buVrAf@CZ*kZefXh)a$?!*aG#nU!5AyP zvDfl^z4I*pEm4kh)DLm9?KW@iA#qpCPYUw2K@71WZu1pc6r^2w$ReXdTzo#KOssHH zkOKn3b{*ly^U9HaUmk^ zk9&)T^fh9O>c0k@Vo!|d-K3}+g{7))Tu-H4{g{2!kAZcje~X^u-3M$Y{fw*nHdwv_rj*=3 z3AFv*`~Sx6#4n0rmZ@_~^DJ}b=WN5c zFmsaO#1i_VYl=Obb=ZXNq?Ekxo1`; zcbu=s|CO(zWn!(kjkx~Ebtk9mQeF36;xX2NSFy1_DDBGA2!@fXhGEbOI=VgJGNB%@ z;32qDj24;qhf_!0c=(Ci-PDC;G{X}*dE>=5_v*34npb&d=w=B3;IMhfTxktld+oMg z3W1nE>D(k8%b{i5nluk|4&^T3FXQWl18M_zr_89&ZhhjZM;`0?cRgHt@s`O?WHGlYC8uL5 zSSO>cBJ5-*L@2W_fx`ewHEykQu0^~7t7Dh>&ib?&dQP*wBCIciAd!qJe9BsPu#FcJ z2Vn(8BZmR>g1@A4dlj<~6A(Va`U?DwOaUF3;a^E3SBbWV{EOf3LHfnLmJ9S-91{@c zYeI(hWsP@=kt-liSeW{J;xyYyja1}f@YKfZ-BPQ5T3fvGe$q*{&t%PL;u7lEQpCwP z-L~!Jl8ZmHMI~Aj0!%98U%mk;`nzWA?2d$G(p+Z&K!qqOu$Y7e7=AT<$u2-4=c2!J z=Mo;4h4dR=ec2}x&%>uN+4vuO={Smd>3PX=m9@>-B57_0B<-`yZ;K)yfw)anHB>2K zqSZ3_#a$f#&WJ7A`{diI3gX!7Q1Q`Ch9w>z!@gI%pN6wWV#VY&6b@)vvx$>m*2O8`BfrI`GOLlTm-OvgJV zX6-1qW2h2R;&8;r3i;n)4LphG zyF@zd6qPX_#H4Ig_v?YNQeMR5SQuw0QPwq2eX?F`G)4e3^(YN4Y{03f9YubgbmqcL zz2kJ$(#lhp}l~LyvN`AGoDYV6(rljS1|)RxM{{SD*;~N?nK)1_H2-7 zf%PZwavv||kMN%KuE2j4IY9awbUS(eoxIT;T6ouUIwOZFX**8CnA^v715;c`G%t)=|aS9Tu$d6DWszy0R-RU8P z@E>rtUZ=9ZPcbUtxF?EPY_CmSGkmA3< z<%mc{{N4kXWyP~K8RnNWKSCeZg%+sCIuZT>(H*#P*{%rINCDU6@<@Z_qY!Il6@T=7 zag0UVOQelT%v^f->5i!ALb6>e*$!Yl&yNxCTSA8PK$i&|!(zH$VI8(MNE^b{Pnn}tv?!X)&etBfbqYR(@37X7!py}GzrPBO_;E9tqCTbhs#@^B&O?S}L$`ce zdLG6|-3Hg%C-TO3kuMvSqnmTs!id5+#gtDSSo0H>&p(!@i%)+BBd?LC0%39s!(lH_ z(fHe}XY+H|`PrGH$*&zM^suk(hTk;kgxOyz`{%^Y^yJecAu&XLe7#ua8b&4U#nHE$ zb2F$ru>YfD<45loNq;JFyObrBdcDZMkgPB`)7m^-+f5TLW=DGFEj&Lyf>lH|H)r`0`q*tV z%&E=&R6ieZ^%+XLPBZ@s1TVg$5avH$yDj}xR2)$Mxg4go-XSC3)|BCG&6^@G!Fv$` z`%ehMvmKn1@o9&2S7jRW@o7`YVjYI|vhBPJe&Q zd_Z06@fkcH!!^llih9=eS&#q*fYZxa3hBLeAn@6cufO;BDNw3j!T|2(Qz`)r)~EQz zWU^+Xe7fhDKP%B2_2eHygM6)QwFub0iT~g&Wd17P(qRvD!`2aX&HxRvHY@QgR2%{F z|Ik0dT#1^moZ}S2__?OLh4VVo5JsfqMJ|}nEfpX(o%vIge?CqKGj>g=OukqODB%=d!C^zTT8ATpKa7D;mK;MY?KOy{I2pxOYZm-xGN1i6vBHj_odyUpU%k z5_QMjm`-B&#$3ydy!NltV|ID!tH?wOvJ;hVik6+n#6bg>|9BDUpR-&wa@BY>y=O{I zEF{{X0G~&o-#t#n>OvHVL@pP0lLI-tn5pL>^t%{KTsq8ITUz6-GunmZfyK)!&CYvO z6#EHJe4ct-`G0HBsGmwYI#dild!8Bixa~6v-0M8eOmTaEEA9Vcc;pM-PO_IBrk%Ra z#9wRzEoNoQs&+K{U9JyM>i!DyL(@SEFbD~+d?muqS(nD#bT zogOi5PAZ&zQ+f96zx^-oBxn7aZwU1`DKVoq?*A;i3;?#|@9*a)j}qzU#T2IFElOPu zcp9Jge}WjhYub;07rxRl)#?9*fIIpJL zJyh`iFxD!6kz;}f)O^}66YF^y2LfgsQ4Hs3{?r-ks|4ksFlxUB?%|?uDl~1C=ByBr5!aasevO% zoH{Ul7jLl{7a&5rX|9Irv#!4e_M=HuqXMph?+0>L1}qq&q28V^s%4F#dr2`DK~@Ca z%%%{+o_ER8oan6`nK;B?iZ)sp{-_+`PGsbd`i?liS`1Umkp4B7mvxRh#~xE3ie`Ra z$a`DPi&}{kslQj6)mL50RItX`x&%&9)>R!`(QJH1O=3j_9p3*A@=uMz$0s=0*<9TA z=WfReVbW}p;{Uqhrxfzq6UkM`2|FR^jAHrc%vBWoCDSo=Xr})q*Pm83>h!|F5YJk;;O)vX zpQ<fZ`SD(i6E^2XGf}|8PnoYog)`$@v@M{$zzRH9X(u7g0=eX?hX0`7`t2Dc{%_ z6zdL2H4zXDGM}9PpkDKni6;$S`D9cfS+th&zlnUF1y)w^ zL-*ns{sz@c-NKw+CM-MHf>=AFq>2N+15@UtaHMofA^l26+JRFvz7~d*!5whpZqi2+ z{mzpT>vJqy!2D}Z>F*(je@8GWCAZr4q-m4Ni(1K@)}JC9H&GM;Okg41o!>0nDz|MV zkC=qD#j={A12rKKA*c1;HEWzYJ}s7KfxDT@F=fpixUhp_$qSM4T^XRveHtwCZfU(~OBa;I{x-B=%AVZ&poJCBG4@ zefa@}NPToO(GoiqJ=g4K%vSn*)%S*LYbInEVMVR61D! z$$K~`;aE)LUg2%#itMGnf%F4KC`B{EE%AZ7&L8i1GDmkMXFn05-NeOYc6K!sg^j+H z!RtNI;b70DjNkUP(qn^`z>D?TlNYkNiu6aW^^k;TFQwcJ`k?rtv#w}h6nc;p7^DO2+2SlW56CAer-sshn+mvB6 zJnXA`Z>0;~)c@g|c~QRQ^9m!AhaTZA0vtOL{LD&bS5XT=q3<1P5mi=$E3?rNCEbH0 z8Ef^qAPZj=N&Y)Wn%|<@LtH+6#w%asaBEE550JbS-H2_sJI6fb-VblhsHYJ0k$j!30QQqnVUJEw+cN3B!M27MP=MOdr{_~FVT!H>`1+#%kL)N}{1;Vu zM`?FwF?GEj_QH($U2JzISJ)+y8Y8U0%n z2eWr7*{AKGbi>yiylV;^EOx(ZlmWw8HYb%BIweOCpGz=-_RmP>0f!6MvQqGFYOY)@ zAguwluVE4D3r}T7(O*oS^{cQ?hE)kza4v0WK?P_aL`xUxg6&u+m$Y2StWGo&@bnP+6 z^M${Zd{mF!erE#(^j7y3eA=lOs-~nOyfW~uJ*nj6O7IVBB6qxoHybvRMU*qHX?!iT3t zDYke%k8fW&3$m{NR0RP-Cj)DsBOpSkHv*W~Wf8>b024J_yZD1}u1iG`Eb_^Uq%R#w z5$5Q)AmAS?y4LCNeCSPH3SlPuMVpva1W}#PPZoXgiJZT0Ul>SMXdwxQyIt#>Zf+T~ zbX36cYfE_ipz=SAgj(72ww8mhrh*E7U!vlrHHH5k)ufhB{5peS9xs$}(a6IprsK?Y zZh7W(&PfI!Bxgv7x01&ZzVc$2L1)Au+jSTBcD4&~@cislNPQ2Ih%X1T=X?;}d6Nb|^*%{cq6@B(A0K~N$WJ?^1*t4Ge;*5C z2EG7Ym$tm|DRzRTw*55gTaf_YVDx3{E7_<}r?K1?lNF-CFQ|czp0RqV5H;^7`s8x@ z#kj|~7qB<9@&0|p!9m5LCwc8C3B>s_+ufJ#x+_L^o+;`ECuoBUtI1Z1$BYCD3p*PD z+Gn^Yt~2&9C6nCY)&R$=d9q5f#}wZq4?Atv7voX@^nPjR@3H>CbPk4ruIlQCu7u zA^M=sY0k@d0uAxut_3(KXd1{T-D$-Va1Zbh!FqU{bTe}J`UAB|vt97AZ-Kd+k3Qu6 z_m2}7?43Wb!k{|KRJk;>Uh%KQ%I$~us*CVmu%t2&`=auE@Ww|9;r4c#Kzh~u8 zTR&Tz46Xm(g5$!mv&Rk=d1pZ}kCih3!&7@_lsbP|Gwd4Y5jejzW=nGP}Dh)fPP%AH6z(Z6Dc)BLeMV(aE=3@H(`Kl=njQjV5?fhF10@FP}|;1(F;p)Io7@^PI+duFr0uEfq3YzU0%E6 zQ|L-Zh>KFU4|8;THjPNlDOT^zx-KiNnTgR?e!WOtV&PlvUk!d;;4+JAS~>~Y5=B~2 ziJ-m5nz#QRzY6~!eE14}>WyDYe?341(13ggxF8R1S>bN;kv}t3w1@4UcRni$@eEi{ zN73N@k9g|b(x~zCMSqp(Yz#PHno(C!d#*}V6#CYRY-rs|@cxgY370|SG5dsy&mbNX z#9VY0V~D4y5399U^hj$wdmrb+UV~)h!8m4=(_Q)ubJa%O-{75Z4uk7w1H|Kt@M!|- znMr5Oe`Y=2jhEs$c)gUx?|Sl6=1`HT$(U6=Tmw9~swqUF%`QE1NJ?{{;Q2%|c7L^+ zqeBHS#3Lj3VRxSLHEG5g93~PSdsL!{sKaw|#uGseSfm!NJv8iFV40hkr{=Ntq=P_5 z4Y%_6Z$+mKdBN@pdT9#ay$O{HkKh1neu<{mD7EX zln2mkG2~iRI+9A}(?Y5h#xu(}W#h#sRljQPE+>`L(HuX?F&ss0HM;-#myj;|@vvkQ zQ08UH*DrWVpu;g%QdVbCXFGAYeJNRK!KBpeFG7Fm{lu$fVAyp!e^{3bQX%UjCZ0760X{dii>1`VJrB4$h`_}DCQ(VaTM zDW9n?Rb8V0A?RQ5tVYo@+aYDk?fA&c`;FKx`Z{%W=&P0jiChZ~Gl`aWqUI;?Yc8iC;@K;`c4)NtPBs_Z~UDhbacM zt1t#10A6%$;#6B)eKmjIe)L;8&wKrBL?VgaLfK?}%_8VoU~U3SrQ=x1PlfSkhC`Mf z#@AQ|*Q{?<3QHU;OZ`s^01NYBF|}z0EL8R9#Vcm71NPbjDe6y!Zsw`yPIBqZ1Qz9J z|KZ)lF{7SHbG0b@9OdIH{51Aypb=XJP2;dM=NJBK`aYKWY`+{-Um5ymsVrXVu}DBN zox%IRe`!gNm}Bi@EK$1Kl96c(qsjALx$eM1nc1bMN*1`cUhjK1b?dP#l^0_#V7hQ> zdv(iZB$)SmDecMdIdg!EF};ga@7QgP^jP#Q+jEc|Z0C{QVrO^%YZ<>^A+&3J?SS31 z4B<>|fZ>spiTVcJRRm8A@nK*>7<5>);xa(KlS&Pq>I$7=u%r;@kxBzgImiQ7J2IJk_`S*DHlZ^ zTEy~P`9$Z>UQM2cQA}(5ZqK`AWt!LZ%R%B8d4)S4$K#(R;6c#?5u=wd2YMFl0q3HE ziZEmXwBh$BA0+RjPIc$nl!%XvgNsw|VPG1M(72%7xg5TsN{Efhqn_izM~+E@gww{H zYt@`q8;)@YYMT`If{dpdNlH=`pr~tkk;SJGKy>%A+m?|bLl&yfii}B7s6qr_wc??l zI;P%V?oTK-f&Ss+t!_U5dlhUKUoWO6Oi&&9!EZ;X19)^DHjI&<(w=5cVg$)Y9${R; z7C$w#ujnzRAGGkITI8PvSmfnDw>)`#GoA4SUPVvQ2 z@6oq8q!ZQ@*@tA6AJVbiJaZKQC%BsHLuHVtINeRjC#$o(BFU)H9a(XUZUlUkJ$xBB zGv6|C6}^05Ea27I#<2)(3EU=UO4{Gq-#x~e^ar_!%ys`Lx7Q=L*SJM?LTktdTmNA_ z5oV1g+)|*#_lMSdOP+3KshO$#xmD)XZyxj)cg2@6e`1n(=}q}HY9m-l9q1imQ_r?A zz7Hk%J+4WZQTkXZ5G|n8bnPd?oVgBY76|OxcmD8u_LD3Mw_TfF{o?vOK z_wlbYROvY9(g=L6_ZI#poNN3O5$2SKthvO)nFZ|{&?#So z-^3NG;l4|7K>sJjL4kSx2uZ7X^YWA$Fg32*?<}qE>CfTerml?8iDv9p2MArfQ0Dll z`wZz$ZL+)5(<57yc&A0nq17(KJvYN$S_l>r#oSs`9T`9Qr<(tD3Z;uy)ii|>$LFe1 z(!e;XV@87ctN~k*-6E;FM_>xIx?#?tEg1tl(E1d(S}Q80gBPEO7*faP4PI&^eZ|S# z=qU~v>Q5HU4B{|D8)Y|Rfmn{qx-NSG<8)RNrxO4>5w@02I5D~YB0oF;$Jl*bJ11;a zmyC4J=)0U1U9s8Kx)-!H2X~fSdG_dEc77*3iVZ^D))p#V5c{J83map> z9^Dgio27`oI=OAu`0cUv{h9LR6g4r-Zt4D}i%0F6<;>S@)BQlz`LZm=K~{s&_^I;T z2m?+T;w6wN_EUL~sd*M^_i^AwZC5wr+~7t+TrHJs37~ydPSv+CtC^o<7&neEMK6># zV9RtHTemM;d=El3NP?6;^ZKXE+E&YdC{^!K-wO+=bnI{s2m4p2%dYy@E+Xm+I;}tE z)^%k8_-ftiLT!5^h<#$3xF_)nYqxOD3)R*+hX{@^PgI6Lh9>w6fGDDAba&Q`rX=E!@pZe5+PNZ#|L15dcsV!`EZh=&XN}_u~HS}hh_-+$w#NW zGgH2;SX~g~;QlC-Shmp-fB0`nq3cz>11vo=-qF^BuK4wnCe#*^LCpF4^DPj>b;P4T-*+P%~kcTvwuCtO1w9nRGzGQnPw9bDsN=s4GP? z^@*8aMMd&KC#ian5jRwV`(8OQD>+SW1QQNaXT9=+2%_DbU~ZKW09)|$6)#Z;+-LNA z1R}1Z{dMe)UuP^4wms#X$=L1B8pqhTxhkK#lGE`_qSicU#jM`N{x~7T@>|dwePhmO z=3w>*LtBa-t4_9sHUrj~gD!)5vetqVjAi+IKC(Sutpus8lxMX$=_zS!;S!g*`OgKZ zz=O}YYJ}%scb}<{**OqZTuT^N^ma?5&RE9O11_k3Jjhu`ehxKoEMvwb!kY#REK`9+ z4Opj)BgGxMx1gPw6%9rRTR=`IwY9$FUISZlE^9S)l&yGt+?*s#h0aD;duP;ux#y2l zRQOCK*HCIuoKE!4XuU-Gl#1#<6*^hmu1&mw_y}n{GZ}{5{wOb#hjjWqkJFcS_t%ED z#62dn!BI41HMC3d_{8X5>{cMt^L4)9mxD)=n|0+SPzsA=kn>%Au(;?Srh$=FiDxSv zPv$6m8ehXW1O_+!+SxS+ILGxd^_`BFo)qjjYB9Up7USx#7TNct<^WT`_n-i89+vgcO50@H4khFA8G4dl$R#vO#~MBXTppxgjO6G1(s-4!{%z##dr zc)m`&Xu=HszPguYGutHsv#|XUn$0&Qv_Q+%+)-0fw!0$Y*{P2J9&|HjmrHIN{+rmD zeV50%pS)RhX0tbYxnqBHegCYR1~?B+I`zzrr3pWV3fC;g;xK>Ll;l+2?x<62Boa_O z@=Q?287_+6`POP(QoOz}uW>oAToUjQ112gFQ0r=|cnKpiwWlM_r;SzqMsLpkwe|OT zNx8JsZ(W}-0W`~pjys`zA!j)(u9!tU<@a5@e~M!DqB#kACy;2aSG$IT#Li05l(cJi z7mZOll>_4+#nEy9N);Y=5L$Q-Eg~8r2L;5Kw(QmRxoGwc$r9Nfukttcw0pKgt0Skp zWz}k**t_e)Q&ZhpH6~!gN-ghwN?mTm?xJ3YSLn+%><^1WsFj4#mwM2P6dnh=u}QHy zgC&%}vdZq+^KZCLAMl%v$$tkvbm@d*#k|q z_yQZS;jTwF%>^+=ceN0(;)ZtTf9UhfpY*sU_9Lu=R{Od1-|miA9{H{0d=%!=RZJAM zy3<(i>F27TWq1cmglc2fgWxSVu2MgJbMpNub38~je9v7kQyI9$^iC9RUe~=R8mwfp zBVU&A<)ZO3`G!g+U<0jBO218DFtm4{L(MwWK0bxK=y~c@i}7d@_AZwaU-kK$@p2Cy zDffg`fm-+~5b0ajNvwVPG$|nM!Qqv8@GGeyEWhsj-^ao9wr;4;@| z%rA|S>eYhedeRPFjU?L9o5|}*31Zaf{Ra$pzi{p~dwJOYX5^aj9tzqMr(M@B8yWiN zyo$KTuzX(ooEe&}vXi8=f6p@xVF^K1A4pK72mEU&RY;~_h=l5kk5hL(oxPS;u^3kj{^f?TUVz!A zSdRHMu-wUwSP}>Z?n~*0ajl3DrF89#4kK!IdH#KySNrorNn{_J$GrR6Y%Nc5eG6I@ zd>}{un^?l_YrtbQZH_kb2m&3|t9cXi7S0jYoSXEyrL)C6siGu0w;S<)S1-tI$jR-w z$?Z$aW-NsI4(!N`=r*3&X);GQ4aW zNgIHuhFViV00aGw0&eLtNEB9X@8*+NtV)&yJt|XJzQw-FO1P(TH|a?-jwxt1NsUGc zU|b=746~wnP`cD-GHRCZO>CdiA(7mScUkD$?Ca+zM5PkG+^qZD4<9Hhp%`|%GBL;srV{=Sd01w$hF+kyDE{G zs9L+56WlrrY|Ac-uPys5oYn+}+Y&7Y6mKGJt2FSpR`b9+A9VK!z(}92dRlq16M+0U zo#p*ux|!w>8F&4zzRL|jDJmGsGLw$Nq;HpLBp1!QR zDhQyho8br%p&$99 z(a?SBjw!%LBmc6+4as*;D?_>{?}4cSvGm!SJa}MKR#A6~U81zu{fo2|Jp4=d;}%&t zi)TM%^`&I2bxhHysQL{gPfBeNZ_9utZ#Jo(Sqb3^3ZkzTFF9389VNeTmDGq;Hf@L7G?W5CipOsUlXJ!Cw-?0pIZPn#&iBUzN`!G+>28_I9p-yZ z4tGluJH5T0pT|sb5MQ6^9uP@To%JbY{8eYbEPOn9X(HM}J|&tM3qe^q&}Qp=0!I5{ zNd!?T5zZ6A@JGy+0wjghhD?ofXQY0WGqKiGen&R?*Q?5CoFYYPUROF{l-&S{E3O4{>evhFP1q z&;dX$AV_Hj#@srBc=VZ9FmP45uM`m?PXFm1f zLi;@GDTHM_ZmGF^X-7Mn$jU|Ym~D!t*6$!1f-(;5E^t+b1fPnA0;XT;0RAO{lmz0dfYa0qa#GTD{T>;^ zQd_BhsG@k3jm~$Q;_C}gYM{r_o`YP$@uhHXJpWyQ zYutH6a%@HD&E!O>8&$Cy?x~d2-CI)oD8Be*hgn^)#Ji;Dn zM}E@~JsQ@GEu1VO0Lv5x450V0*Z{uQ696FPo*YocTO+9|>3R{of24g<_<)Fi+}m3S z>anhNW1jio;38bhRq*$B>DuoD&%ptPPCX!MjpMhpw1hhd6kg=1qcH;rX<=0$mYKW1 z)DhHtj@$@totb9|0+U6?{8`V&0o&4pAZu{1P=zQ{h=yI96M7;)%BrtSGocKwB)7b^ z%Z_L5-P!duqzWUK!%1gTcXb~ES&(~i#}#j}WBm)pX~t6;5wi50B1T`vglbGGkG_Y} zY4YIflvsfDZy(46+vZLpkM?zm;Q5{>=>*OPU7$;w+N%`W6UtI{Gghqs)9Gz#B;&-0 zRILN%@fMD2DA~QXWd>Cj1vbs@(37zsd^Vv=z&rHkyTJMY>q*faxu-%7KeA)qWz6Hn zpFVgcsB2S3YQD4a#x?AV)2Ul1Rm$)CxJ2`pII43?VbB(79~Ael^0^KWf$8j5yXQ1^ zjV)UKxlScNB=|5>cJv4#@37|>{8S|b`KtIE_46#0@0ShgmFk$Kl|21(TrIKXjHafM z)WpR=mkIas+XcI`>z%AG1wx%px*M{-S^W7BhOgb{Epw1hk2;KMV|`ggRqmlVzkJ`T zE&m${@XUVW!s7G#MH8#{a+6Bav_JHA9Nb4dROilh4fjwn#79nk17-L$eRkKchj@$t zbE&SZdY@U>mB8qKAv+!PQJnx$+8p~fm&LpC&{sG)#2ZQH<+mQC7I+n-tch11VPrQ^ z!&|sA0%AW7N=2acm=8qSyYxGt*sC2LZ&tYUt8%zDz5eQ+zWw+C z!!S*tqhrt5(PTg%%Z~Z;k-`sg(aOnLQpJ}YJb4}FX!~ZkieqTqi=6z+7W65(>zYCw zAH*?Y?1*Q{g4OMC>D!7eJYfS!aQ4#cu!s_Rx4c2aiOTSaSO}fOwVR`hkoG>(;#<=f+5Wl)9I^yrp{;u3! zv*RZF6lUmx;U2f1hvnARu(x$sb_8vFVr2YqhTP(hy;t)|ZAK^Dn+WhJ zAC-5goxJ8D`-S`R^=XGA-t)C%Ibm(hg==RJqLFO^bciiAZU7<=nZu32pygzSi`<}n zddv$d?!X(O2|YqiY2*GYe@A0ZU1aF41(}f%+(@Be7iDvr9Gmim25JdA!_ofy%G=p_ zlS`2{m=iUhQXn0vk9?|k2rhT)r^&n`O~+?Q3+dMZwKclYbu7W>wpqsyO$lcG*uKb8 zYdX9B)rf`hEa*0*jjjB`g(*g z93?zLKP?LG6)*ihxpdIe_n|Vb&zE~7s*akM;Ey+MJq2j`fsv<2t|K2DtZjYWeCuo3 z+Lc8_gOXam+rX_w)8de;Y^aDvbErr7M88m1)HEHUYvjyww?BB+wQLQfqI_y53x zbh-3HFt8Ii5YcJg3uvx4M-=Xz;g}0{g4^P%M13jknbAaEMK^`9;tZ^*K)49-=~Nj& z|IwIm=)%;fu%zN$D^HDEn_YxPfvf+Qn9)US;#m4n;&?hc`czrr{?f4bqs8f%ZJ`+x zw-a@lCvZmqH$~p2dCY~WZ{-Q?mn-$S(yIx|GhqEiYDdkg9sJo{Go&3pPf95t3fYhH zDOF9Zl(^aMr^r<^3jgQ;kV<|JVBVA-2eI%e;h+lNXJ@WDYi*l@9bNKj`iqli8x9-m zbB?Thb8-k!7+??U0h`Y!m$x>uyi3ijRnS12nZk6g&el+ZYzZOWH$I2ahTq+{xXe*k z6$i^L%9jV7j$^U=9(=AFV#UGx`(JoXF0Z+?{=cSw7p#Bb1i#6_zStJcionCP{rO>; zTv+}3our}tD>P%A{YgoM&vToBxxseAt zacXWdrRf4jS)LX#~-;lpla=ftoWbGHSx^>q5SwQ#kukg%Vu%7 zlj_DcpWEN<{Z+$_CeA(LyXU3LGn~77@tY$<>l$0pQtU~(_lk0ipfMR2KG>RQ`B=v8 z22i_2_b2r|{`tnJ8yILObLa|Wgj@@m4^rk6ndtkJM((upkCPBGNk-~T~~SU9aSB*|1G!z_?j$8T0W< z$GRS5l*`DoVjJ-mBLZWuxIZW#6sb!5Ac+f@Id&2WeHo!nC>c}WIxc)IU@A79mx98g(Jp1dz5#LU$RSwtP!tXgQ_))w}FZt9SBw zI0WJqUtPsa2^>bmRX?PA2Z}||{sL`!3vU4yAS|+ip3B(W-pNkMp>{MVS>6m?g}Bax zw^Fb@xn_XLkBY0Ba*uu0fR(BTwS4d_Ug+KYPq0I*9L-q<4v7oZVg^b(#cm&SVh{L( z-H(B~P`zGMt|xhlFSk)eHLF4*QWLj!?~Ng~;S~3#o;V5u@2EQBfP%x+aytw>z86_E z$oID&IT?^fqy0x7-5y)jt!{jFhDQe?O{AUvPV9|w?$htaC0gv zyvx$S&c@2NCcIDgmstqRIs?}E#RsV;qqLC?GW`e6j>vBO)wLd?H<;P>knk9ijSU05 zl6sn+1s&Gt1e7!>_A8-8>}GTy*N`J;pWR8f{wWbo zta1RMICwM;Q2iDGG*9@`$fLR&rPo=^F_Fkg(|aEz z2^$Gi@K0g3#R4RNQ$0@Hr>M;$)#Q2-uk29!kQ+0WIFpX8mjXB2`@fSX&u(9A7H;9u z+82d(1@Z6Ezp4)rOcr;=#yMSs$jN7Y2TAL6hODWoJ#~9t43>39S!&OByAsK#qPyVS zvHOP}m8kzi?nNQqKkh0fbonz(I4FN4jY7zh&RMrJU)69&uX)ORzd74?nvY5C8S^E* z3Amsxuo>G>f>(B(@XZVZgNG?FC{p5}3LU7@#36fy)IQj>k`)eJ=P^qSXo7{G>d21f z!<87bSf5#oEQgZ!e=7$N+x_~xJwq3UdZ1O==xWJ^wB0H$rJYUH{njDpwbJrZWy66_ zh7a7jf5>ePmTxZpP@j}sk(q`5Y18PA2-r1NLg0b5zvbL4FC>ytNe)*ciQi(shnR%t zR`fCcx@JVZ8P*PmtYJgea9*7!{W(C zEWxkVhdc~v!nH{PMiF%--?gvOj~E$wY{Kda$pPi!MUXjwTUwUQUIOlElLb}2X9?%} z!nN&dLbUQ@C&uhx=hzMZtu;lLZpv*%zy;+~Z+?UE$hb!w!`^_k6_sqStq=>fUHH6l zHT!+rhWS%xS;s8?heqco&L=W4`m*0?#i;UNegD$}&^(;zw#|5~26lN15Bv7Lr=j7d zlzK-4v(NECQE(^w!H>-Vh!B?j^`nr{!XT2vveX*gug89ot`X*twr(^x1Pq&b&7ll_ zQH-#~w-cJU0Rs2D^{+bkw>DI&h%l-P`5YU)+DD6)Mb?cSe;}KF7ApHYE-9|WZ045)deb#Wxl5J_CQlrECVKFdi~?R3Yfpn(5l=m%9)B0 zyYpMPLEZ?F6K^EB;bY)X8?yZHr?B6R>|5P0pC7)yot}YtZVOLB$%!(qn`je>4Fhgi zKN>*N8s)oqs83M^Zfbe(*r)bFIX7CiWxW@1&#B>Ry+v=M$cI2$a{z*EE{lpp5`XKi znz_#n{6L&HRwC1iP$z||tS@iv?kQ}?s5?MlOpJy)av&C2OUGm!so=-bbh#xM@c6jb zinU z**XfD2Vg(rTk(_U!3$@Y4mM)N7cYR1LFq=7&IN@gCFO;E{VS}cp^y(VuHeNg2BMq< z{6FQ`S&^0{w%rm%@CxPl*!LXjMzsD+ST;jn@&ZLy=5=GbC(L{>TyXtNzDPR6#Z^Wm zYnGl=Y)OzE-O!5=reZoIf^y1B?!0^AV54bt{3+3twB3ET($OW2CcGeVD|)u9oyuGe zvTZn@vD)LUbnF6F1w=}`#HO+??0A(RMGo9*2HrGrT4`n^P(Xo;q+|JtG$WV48Zj}A zoZm^-{A+|MV}0Zlt%tq#lbK1)zCeLnHMS9ZrgC+*`7TU8C-D}BUMMC6%!6s{SEJt} zQXxHSKz;M6FBot_t40~RU`~_D!`IiZF!GjK0q1mSH9XQB-5jvOqe4CB{0p#`DG`I> zzKT-jODuflMzc@g8~=q1muuK|O&F?zB-|x@wd%L;y`s4NL_Bzh<@qAp@b-(W8 zN%N03x|gbn^`YS4dAszyZxcxx$}a{DJCAyFwU2cb(=rbhr)(r1IjmG@@1RHZKYQ_p zJ=aO9>XJD~&iOSrzEpPX61rr#l#q~cz05|gNicl2$vZjh>XovM>v_6i+^{ zh_Tu|cmUBa4IgkZ^kPV}k5?;%-CZ$&QXG{F@*}Uf3#x1jcLb;AX=_5DE0Er*%sCO< zrkP52qObL<7hU@`kgI2#7tl$ZsYW{o%UgscZJ!Bf;xlk19`*saMxm$InL5`^DS_%} z_NN^MUisixi&^M3&s;futC&X4?Y_*D#~0dM~Bh_#xFhqpFQ}?>lJdqjORteCWw7Q3 zb);bW&NLE~U47R|EpA|Pp7x3vAvTjus0<}Tc^5N~-`7;`p@%&_#jr80eO8usrw@uj zl@mbwHWnf{&tw$-!iDC*rS&R%L3Wdq6?3{K5*J&!Cf5bG*MFx2x^k)!57T0;K^@QlLxDL@X2!as zUB!^e9Je#EY9pienc0Vr+n`cN(um(QXizi#wqucL2wnvE`EA_r+rQ%+-9v+|>PR5mNk*SAo<|~X1M7`%% zm~-w3lQIKn$2DWg1Z)nrKhGLPR%e-qEB@V(PUWZ#bkDCck-IeFk6uj}z9U7Lc@90L z<|ph)I33UdrU^7RJuf*E$M=}Fl}VtO)ZPUjN4^s%;fneVoX|BaMqbvP6Df>SQX z9Ts#=?RZbUkTfo&A>cj;Mf`G-fAOG4J28pfLC$svCj!N{kcd$L$s<*%8Tx6HHtUZl z(*86;omu1oiPo9i&4tIFr;>1|&)ZrGqbK6zQ~Y>%qnI4%f@V2GI5>LV?X5E5eqLx z(r62#Ra4Fp504#F&aS8Tfcbj9>tko&rdg(~%bmAae~in|v(3~PD`@Q&mn9M9vut*i zU)@l)RN>fCm7_qyocp%S3hl2)0D$@VHYfHr6Egd)T46DVbN84h7i<_=bx;|m0)C1`ka%hyoeew~p_mu5DMNy?J1odkmftLJTNS=pmMe&GLLYgo5 zp}mv->^7aDRzwr2EIHf_pF`6!JQf?lNR?TEJ$i4W)cby^`f*?t#g~dxIfu4P@Vmx= zBj&4HL$Ay@ucT1__MWXdnM=8OvMjrPT(E>)QUk(HZa}A;o2|26cGXqlX0U8YB06t( z3%{P6nNkjUoBz#UDsb*fg6^G-3kIwALiJ@P9bS#GmL1*&k%1Hb3L!c5p^hq&iprlz z_JT7lG`~vy=9xXk>Y~Ui5!lxPEA6P7=$*wx0g(OGn|aUihl(McVetx*!FW{yuYFi>=;v$nO`mirK`&%~5h{#r;`R6*r>iQ$Gk?gPgvk~Y4E%8Y6}(co zNPwcn;K4=}e7&l*aSb`M(fnyUrDiCzh(?&ko_x6VrYX1t74_!F4C~D2T_5SWF|o*i z_>c=LHx$?k+ysq2!pCId(+9R?>owSE{;^J5CdgDwh6EqZiEg z%%86CS2E$Zm3N8Hple~#rK+AyRsKMIynD%uv{K`W88?zurG~@l;-E07sjWh0F*9F& zn`aWd?WAkE{k1)|<;N?7hH}Obe>i40;NeK0YooYc1(CXj+rO(-8ucb=%$W4I)KM6o zq+92Gvn|n!bZw|gg0dLwW+bw%e^e;84V9zO;&w&0HNng$eOK?5{mT>^y0ov9i2GHe zHt4hPHi4{O1X2IAI2xO)_kwR)L6q2M>kr5dFgm^>G1zVohvXJ3J*OO8MuDCvf0(Su zB(+1O1Km;_k*R8Ui?gE8!r_OLCEkg5XA_1$&I;^(UgA6YKJGnt;Jq4E=Pni_UjVAUP|X|D;q5bZrl*ZTTbJY}=yj zcM6%=1*i`0@j}bMgKrs#Jst=i*myb{kxLF$=B{m(#z#6%k6iv0Qr5|QRLgbF#o{*! zBXoBNMq4zBd3XnqON^E47h==QhsBz!WG+QClH?Rk_0yg|=4U5D_PscmbN4#q7E5~< zx1(=cUS4+HUcTz$0CLgS@;g17bWdUW=CLxERyNC2^#TcQQq6ctYu5Zb? zjGMl@S4G_a5|!A=Rr$M~T2qnTiQP0-#PAGq&6ITBN4F^o<&1gMHQBgWY>!8S+;-DI z$6a&w`rDTOXxjSWkyaxz5K<3#X0DIE{88LT%q+dTdr4+}z_yk{$8(X{Yvq^BNqfq% zx3^GAakjGj^pf8Y@TEu87pj z7g?*8d2+l|cf8uk`JJ=6spHOLmwMsf#J%(Oy46{4Qev<#0`A@v5VtPbGRypu@!h|` zbOE+>S_bJBo1HgS=YQG;SDDhe1kXu|m=c17dxZMm^UK7Y9-aH`@J2wmm|yBQHzTzM zF+UaQyHCkS>#HZz0>^1~2YD%nA_tW>-KY*<+`Qpga`?_#H2c!Iv}mjn**l4>QEt^A z>Nrz)cUN0c-4tKvJ4dlb*3I|-I-b?<=lhyA5Tx?B8$%vW5S+TJbOD%;EXOnQKdr z{&oyB6jZwIETtT#d#|_GZRfan&**#2*&VeS9br5(Z(`h3s3j$70t@!r7#bpuok_0uP|FyzD!HiVFCm zxbn0LwTUt)i|dU!eIC7pHhRi9y)ND>TpSwTMVfX}%1-wviv4LN7xNGZbyLKI>A`7) zh=vq`MlBSBe(#IpI7kS!Fuu~-m7RcjG)^)Yj&0m@ z>U~l%+0JavLW8~#K8J48M(yc~@gdVZ!LeWp^OHOI7d8L9RO( z8brj77ChVTK2UJ!rpOK9V(y8q`)A^m?(R(OKcD&)HdXjU=Th-OrPeJIh9_n5%4(LP zldT;nwCNN&u|n`v5}QryJ&ntm+V$OqMVhv zh41TjkN2@$LIuI2pZRZ>7ne6)?M)nSPabb8oRcYacVZY!HYvDyc01b{E}2&I%=eY; zpigu?Q?czv8}f*Jiq=@R23mVRd|hUFB}#Sl0E<;pg4+KoE!e>(ATKVE+BX;806OZ! z#Jso&LZcl&Kll6uvtKipD>2Z4El@sU7K>lEw0&<)j`+hH(e%)7kgJ&Y*1kt=Z?1V9 zUq$>ErS7Ttkdhlv=h=)0eN0MXE0s3VRl&oi**EEugZ*>1for#<{nQ)w&N@En?<;?F zKe=Q2!QpQkmMA)VDyHDSuWVb{d@F)+!FQ0U1;%6-BJ`Y$9#*fJK3`v{5toJAf_Qbz z!%>@0HgViY`?e=*`}0g<#C>~`X)XGM$J|I#$Ki8^T0C2I)<$?QlY!r}H1weT899A* z9PY^K5fD*~uqcYE!GLI7cKMc)Ql%E#>0E140)sQP@ljaXU&0q(ei+TVS!+d?fl4q? zAlp)C(fA=2GPG&K%s>7xPDa*+5^D^M1+w z>h}?`XgD_wVE?HPIFVB-p}vp*8awt%WA-wW zM_z?VykU&ijwx_lb?aTBb7Bg1@D(WqKf%YT`DNUf&heBR!l(RpWI^5OqWnTVjR3*d zHF$ouh}W|>((dsPjOeFSO_dR}!ED#4wk}PawInRLHJs`_&exUWHO|-PYgD@$dwFxg z=dj`D!ofgm;9Sc;}(Z&DXE|vu#SI+z+Tb&==Te2#tN) zP!#1Q#t-eQ7D$1tpe?Xhg;X*ES=|ZEY zPf@NFQAGZ*1Tu^ZZQby;ERvzg*`5;=q)Pq~MdeP_xEQ8_i>g&$rxeifUr;kTmP1fv|7i{1hQbhW-(jzh?sHJES+L8=UkR4XOO&E=2&+}GOm$2 zl1k0L$3tg;aj2y3z?>UN{VENYL48i@TcOx{7(YcWPVw^u? z{ho;NG?F5t<=}^s@ms_At4~9*dAif@!?>^>BSne^H>&4a2ohNd-Xjp#G!TzC zKM*4(jf`7>s;Kg%QDpw$f}w$ymH6k3ASMEltdPAePD!24beh80-ESW%a6VC7#=N0L(_!z zV&}-G3?@B~*&X7O<;rmWi3PJ{9CMf2M}hKU8T$aP%gk-F%uOjSgY0lk^h>(Ny~J;S zM)RMOf#7{RfL$Xwe4!Q9Vy}fBF0Q}IPaeGaYbT@jRgeZpp(R_fnbj?{#vr*(;5m9( z(ka(itMxeH`;YdbYfXX=C7)0i z{L?3PF$2fd17LbL%u`4W!Eg^`RN#Zl_!uwS6w$L*o;1ycDrdnMhSsiFeEl!Ci5mB~r@hwB{! zRdCfNJ(TXpiY#D=VFsX*RGOw*r@Nh89v6iTB5d*z`h)(y%d5WRRMcy$$8lQe6bCht zL&ZnZvluJdK|yej9yemkULy{AM!tG`i~svrp3%wVpRjR#=wM{_DN;^aWNX7lUO!=z zwcfLD_g)28y)%+zMaH|S*mHW4WbcXJ_#JK$kMD*UZSZyDob{Stg-xZV-%0+JrAPJ3 zu!FIY1v1u=$pe2uaD>W8hn!_nj&ZX@zplIEOTVq5!hNdvu>1`AF`@N` z?_3_o6o^>8E{pwdRE#0{B|1koHklBoi}R7I659%n%9&4XnBv8K8@4s=`UC54V^+g9D#)oIWauS#zZ_Tgu?#l^z&skBm;?$gQjDbt(PvjeR)lZtp~T86{+TU7zVJ| zyYXBL)<@E!$Qhy!^2M5+8C0!%XQ?6+6FNjg(!Slyohz647Cn@f+;GUWTdAx|)&I^* zd-O}-q z+u$p#mruQ>3ARQBT_5JO2uTo81WI=)Sdwt8tGAT8W^<*~Cne62&+|U=5qmB1B;Dw# zgnJojp0y;|63*aLfm!LF{o>%nuB4IgYd(N~%~}&d9hEB2Xt)tHzf>9D(RyJ03HNrV zWys4772+|0EI-k3J9>(#Z7QhiD5%-GS$9z9JpvQG*T|>ied`p;F{kyc=+*t+@#EyK z6RakBcs~FZ&;6EAF<7aCB5qIJ9tM{SjZ1%*YkqEzCjtfH8R7EKy^fFkuidT^wz=jT zY+SZ-t-N$_w`Sl(7AOT0v~Xk0ebJUB%>Efir$iUTQNobJ(tKT0LnM?=40-fr!0zaG zhaKUj8RsHCa^eBsI?dZOT*(m5$sZS!WfI{tav!}ul1tE^C&$~f%yl%5vp^uW3>MEw zFwgEJ{Hzgiax5Kgx<#IBf-)@}Rj@1x4K|TWDxj9HZz!U10N3Fx5a5rh69(nywz{!6 z6rah}6Rjhzo&9+|87vpa9vRgUEMM;K^w~-!sy(N1?qTz;R1>`_#UWwJ0lnwzN<$mL z7^0AEVEqn83f2b4nfS92kAyu28EvS&2mYY*H+v;t4z%CF)9K~i6@}=r*lihBBVMGv ze|P=y@umBi9Aw_}jx$b_?c#=qO;+lk8}51TR=l80!Wpjv71EibyQ6UP2e<;8ay~^f zw4rLqpvys!Xh~A$5TGbn5TZU#tz@qXFF)!jWtmG$pj%9-^|)AE_?+>b^c49o?n#7H zB-fDaYPK{OEAb+4tplC`Q0T2wFIBCC!fef-GX?pOEJ{Y4clh+MY2QC@Z+r7&+}}I9 zd}H%p2(9k1%=(=VI+r?NBB6j*FfzWW_?`#vMl^*QIaX?t@ns0?u%HiI>wPva>v_59 zGe8PKL2=Gkt_hznW;rWt+TQBcy%yn#u_`~gHFx#!C$Ss=9J`rK1c*e}C*cQL`6k!& zd`rmlFuFF;CAmU3-C;lEw}XvGyEb}ZSYydqj1-FrI2>e}iEm^ppMDph8_zfBXn2nC z1~JOMe!CP=i326`MnC6BJB;-1i$Z}Y=vWuWOQqYZ-Vthgu6h53Co=4 zO~AajwApf$FZgO{*At@O6mB5?_Pi@SHSR}*=*+3T)c3`pp3JVr<9CJ6 z9~B2oa(oQ-WrX8s0*NZcykH*5fg@gh0owe&kY}b z7jBTIT>kth{4|r3#%=A}#R1)451Aaig>5iS6bJ=?5Dx417|@}juT^w~yoRFdmZ^`c z-n=fZQE($sgUODoOR@8L0;L>hz z=bJ~CsSm*chluLTM)8mTaRC@303-i=4dKAwm^!EAz;>t82{_pwpx{l1`$8@f1nwZNlp#Vq-%HmQS~&sEycF^3A2#Al~G{ zv5qzRET2^KFHsn$KLxudEy}S*C3N_bEYWwooj_u0uNIqCy)bb;G5OM!l2}cOFsgF* zrY^OS?Gr8-eL`L4jzBzoTpvSsv{$z`UE0h_+Y3Bhox#c>S#&H5KM+g0&P%=$O?e=J7E?#^z9w(g+GmfG(WMHR?3N0wlCL^ZDrz-$+2 z?-MJl`02thes^w5fG?KvCq|p$R_Mp(#?;xGpf?KdAqlPCTiZ zy|q$&(@p)(rnfelms#*E4fq2vIg(p>wwB@GG90zzuWn2^4q#sN{2he5pr?8{VDvs(p^*n;WkoCxKBTJhSelg+9dwpnWR9 z;*^Mb_ve*dNUQPt#aO3+$g27PlWD5nz(*aHC6_NhLZKBX>EaEX_&R8%z)AC+!4Lm2 z8{_kA1S%u>sbp`895?SB>en6be~b0ro;%iJaT(4hV8R*J1X0w(Qn7K_qaEfM&g8vY za)39rK0l);#H7HhBCCgP!@EH=ac6$sT<>b96G*IL5(z!NRx@_VdB_gDLz@r@u(60} z=s-P#ex(H9J+py*F7?m5t#um>JE?ApXy&=*>}r{rt%Mh1&VOZ3QpVwGjYz*rozBj6 zfuZ}TeBXE6?aC|Yb!nu&JAgMef*cUKX+W@*UwpG!_S;o7O};^WJn0H``^sHr8jxs-W&(Z#@0P^F(Si|ZpG%W zi{huTr6zOJ&{*bn2{?%l8Sy9a%XImd`{>8Boi1uAi*FHfL~q9g&9W^5Q$HQih-&Su&w zuA>b5^+vr2TJ7t2Gcdmx230#Fa;IWJCI1f&q`|6D*vj7b8NbL)GuJV+zlxa;XH(W` zQp%%IU(dT-cYh}PP}-gg0sknOC#ZM4&4^z_S~B(l(F&pNtu+uAgN0Hi<)AW7A!75J134o*8#sv81aC3Lf zZvT_}QQEo7d=b3@r+v(y-)m7MS3{o#N==k0Cp8a4)xMwJEH{0iy|%40n@ROE+oN}_ zeMS?@ZdPT#8Q|gO(>WGy+ZTc5oiMwm-8)eT(#ZaX6Mi{Fu@+5 zE9ytr@h`hWai$P`QW@GET?0ZVq6L;wA=y>T-L35x1sGDWY|=`eq!VRFnsLr5(qiEa z%Zv#zxfUt(@LCxcof|>*dx2kqp|NO?5*xdo?BHxoo5Rw07jp`ZRO5IoE>*OqwV@sMohrb-e-i*Pl1oCTfU2e<()D>v(Udq#QN6c(wdM zi1{!JemrxzzS&`Z6)%c@eBHO1#v z8?K)vs;6J~B}Du6M56>GOLRL35Whb5x8Ls&z+y9^ zv8wM9r?Rcl?jI%Zb)euRJViTfF@l|o(|}M>)UPZl>wk;0Qhmdi+nrXleo7-^Ir_XJ zKWqmCOx7c-X~nF{V#dyoGVFSo0%*->HL-A?@n1e7@Jen3$xFN81Qw5 zSmc8efspEWVd^(HISGcEaEH8|kR%cjptnrH*~vDOr!h)qI`WOL>bSGDz~f~6fAGIC zSA{kMB3No9kRv{vV*e_~!N^%crPn>e@x-HxrgiB!R^`)v#L<~5l~0va;?94$(cZsz zPM$fheUS2)AG9cuF)@OPtEkaJ;_uGSAF%j13a}$o%}i2r~2bs2zGSNo@3rgTjgrjzg-8jg6J@CoV(h z*UhCFuv`S)%}i{MHcSfD;{~v{vaJSk|AUMha(7n|(?=4cPsL#Q!p?K!ofy@&J{XVLX^SylSK`mdco3>o=;cL=_1t>Php|8Q0p4HsjiP?i_ z1j9AtTJdsz&1I0~hc^OQ=_=jcC!RA4@-;j})ZdwtsZD-8(|_@o@*_W6TH&(i{jQ=Y z8-B0fc``>j>!m+kHHg3G*E-yNWad!RQ<-h+qNt zZug(liFwxROf^G;)?0oeHjmaNJ-ek}w%QbHt~9*uUPN|W)(tG8sXY6Fv-0(~u6Nb8 z-wAv^8c9&5#V=*PF8HE@K`-*YI^`4a^jh>rn}ocH*!r%PWcgr7bF% z{XT+nG<9d*lfQEChTJl`E8QwahRmM3DpS+w^XuCkl{i`Az_*yh^c-znqy z(xh28q5?ZmqpzkTo93e+lkRi;7)QH+?Cx~#jCT9em|}C6Ze^=<5si$e93}M{J3Z6k zb5Ps`kY+G?KSj6Yy*MY1^lcKFj_}he#x1h+8e6`BbMdfOCm0Q>1YsJbhu`3&l8HidivewxOpcKTlHg?}qUwjj9(} zKAXsU8uK(}<88a&#@jA^O7iLjg}2=>u2H|4ieO_}_r&D^Hf{d ztmGL;pyJ-1dSr=^W9L#&LQn^bI8Ux{u$Ii|FV$ax`N7qC<)MgUvtoGclerawZZ?==Eaw(6?Jt&*0%DkgL# z3&dM%T(6A>{ICAa3UmMaW<6-oF=y#bAo)6WpsYtoDtI6+ZwhQo_OtssP*t~Y zD!`yYMP$xbnN_$v>aWV=^j1YQ(>w{E$torN3*9Sx0iv;p!hZDh%^!SjITi>H;FXKNGR-_3 zCV~@n64QY)Dbg%sb!9z#k+|m*)h%h4&GR+E%}kw3g|Y1j)%TO@5C)Y z^wBSU^0{_@CpMs2{FPJPiipeZ+=z4RJwU@o^za<5m#rx&nU{+axZ~bpse(<&5OR0H z^3Od_l?O@SBPIHV*3L8T?s&F`(d%M?zMN-DbCH1VogFYxQJ`!^eFw}ev;r1B$ts`+ z*wvf!Lrg$7HUXOj`yczaQhDE8$&?6W-_BA0^j^f$upFMh^Z||8Z38x?B|p`{+}65*F8{ zuprwk>6s&vk130!R0`seO+GV?Ypnr1pE{td!4+Pe&cNADPU4C>*e4U0<{ew)xF{66?jr&)63r45(p zqcF=6raz;WbWM5qs08(A;E|qi{}BsX00EZyYH@2q!3k!ImB*xqHf(WrI?!~)qRBd96@lRcq8wT7-J%{G zT^-)~2js%dK*eyjMtjkJa4@8aM82YILEXdiN29jSVu8P$fdDuF#3nEs-P@ov7enYWO(>J?!If$kVFe&!_!~0*3vH5STUp;wOKQycfPW>YODoNx9 z2-}$n-m`_eAi+G{49D|n)J7p2)(ERg`(EjuFSJ)A>D|Vlw8by`nsaiqGu_HI2@(kg zG_MuG5RG-uUKT|Xz!_*1vX8|@^7r4v{X*#A5K2kqtX;L}Ig%E&VjvmE<+Y(^W)|dOn!6T+ z*BU-#*=BEn(uF|a%hT_2@1FU={jV@{6r?@0WQv@-y6Gnsy|b*mGj$5_!GKUsoA3L+ z{1xhG9LGp3R$|+f69K@!#9f%klfu=0w#lJ;)uKc8Yo+c_z9`TM`gOG+jmM0$U+rz@ zOpjw$yH($hAa}X6crv%{8nNk&zRwbWnjHP7umCnCF!CU0K1%8NIYW-(G>b@(|JEN@ zj2c-2iwMo|ZL`eCGrgk+6rh!a4;`xSrydP}_*wk^E^(gkPk9k8W3)*qXamt54TW0E zLUFUt_4T6&O}N6^P`z6gv7sVBsO<$SMf`X<1WCRXcQLP%>>Ko?Guqt?Al4w>I#S>w z;zgA_^m&yR%SrfslTr|FCs?DpI0z)lUgY82-kMn0KyX4!9<164yq zMUUm_cQY(}=EX`p*Sp3%lZKqapVp8ef_1h1{gRB19s1=;6RfQ-Q1-{b&9!tr!u>f$ z?UGo!V}v-ji}3vefqXF4SSrDfa<)R-L(%x9cQqTH+;kd}YJ=swXF4OZ0e=NYO>(;1&B-87aI zowAwcp5BZ;aetmm-Ia`+mWE)G`Mei*yPf>{&SGoKIm7EUw3FODRvMI}*=r^y<_tRI zo@T)vVMj)@^*Y}-J)+O7X@A&xAcVixw=<&mJv_CxQK7E#=`#|G$0pQGwz}poT<-jq z6WTL4b*7K9e?>H^kDhyeu$epD&s=|@NOF-y(+I68L=pK++*)J?xrJ_phcI$6{GRT$ zkcukZc<|?2>ovh2R=P;+W-8o6ZyEJh@^959PGzBhJQA_t?)>lRv zcr0sk;67R^7n7r}mj0&yThrHTmCs#RkXLF8flVSbe+yi7uhdMNE&fzCsD?-4C=f8g z!tSRkH!B$@a#nJ@Dy3>9W9*l_6P`7Ec@#vymTP3*HfCfA8AQuoWC z836>rd_8L^R$mGq?NohzBp6)Ez_0u(Omt23PfOJJdPY@M-(t1IsAqqOHMgU-wiAax z+VDdo3tUSl=gwPrn{pf0%IPbd%Rky5QFhG!Rg!-zCz z>RTdV>PDeo6I9yr^nVXx?d9?{0sk9Th7k*v$ae~HcBu+c9KvaOU{F$Wx$h*32)UTa{aAg(0DRlzR}Y|xm2R_CcP{^nMr z-!ht=>7(4sqsVB}B|$>D;VVqMRCAd^4liqDIp{ArW?x)&vaZTMeQ1y8q|b6yqbOm9*~ROoy#kjC9h15}tz zgcCVan)R@lh6TF#FF&GUzrhaZJn=O5XkZctQpn{lrk?>f1AI}G72C`Mrw z$YMp2R+RruLmDA{k^noE0{r9dN`NXf%3gEHSP3=7ir}SPUREPO_|)7gg)v16&+`UN zX_ILtHMeKW5IwDN=S7YA>a2@1UIvpB+guo6%djv6SaLUns?JRQE`ruH8aKTJ>H=Qa zYKK!BJJrTuvmBzYA-C?!l2F^%*)G&~1CjWqO>xwQ8oHPM1GIYZ9hRLxLViC^{!c{B zX{gzA9YWB(SoHji2<=oqEepP82yj4t@gry>N-=H$Z9XrGjBMy8srVm@ptT*qX2UlO z%501;8xh}W(v_v3!Td)Vsa3XsiaAXUUuHOge~&g5gL-;|$=DTPP9#=G0?Y|}X0HCR zcmTAmZ{|{0xQ-y zlic%C55cXOo$>(?aok!g2g)iH(x4YE4u(O|zW@+TF00&cP}%r=p}`BxKBM|sWn$^Y zu){nNVsUw|u#g8a z+m*N2NAEFeb%&sayoSsi(v`T6h`8GxsgRz{w<^bxQis_qxq)e2rBK8U5%xhip`zeu z3>;JFd;j}-G=<=AKsT6Jf>eQu!IA!CY4biN_%R(88(~uPx-v4F3CbCy6P&C;ViH_) z@-Ctcpq>5(_h76TlCRXl;}UFU=U=?FZHrAYHch>)29p1%zYw@; z-I#%ZS`Fg1Z?uR_N(st8(hk?4(`rXCW}9aA*m299Z2|7tniFxw$0*qR(tip_542bO zaZ&+w<02qQt^}Y=Ggp?QHVz*~aH+3isuM zO&HHnE}nVTZ_YU>7=wN6$+o!lC)UCOYL+>mTK9i!GbR3t=Q$VX)T+S{!9&~pXH=-; z%~_0EIy92Ug97iQmlhL`LJ7}eNU7zOe#HmQrRc2}MPnM4Vjp9F|-KFbRZm;ge7 z3;*K+6a&au@5a}qY-Hso=2nmvd{sqHu*3$vj*TFki}c$U1^2-RnGp&*xd5QfoP8?6 zjT9YFNRP(o3cHQlM)+AS&}4rTGURfZpwrH!nXP%+NPIbGCmw!9>-z#Z25&>TzgJ2G znk1ac>L!u2Kd!d|3RwY4K*HN2RX-@bjQ@USL1Z4rJ*-yQC|FQ1?=`k;uQ0!Yz;yQd zF5&-5R;WJVQRBVC#*kW~sewrp@bzG>%mV-7H@6RvcPR_;-Dt~#S~$GvVTn|v#m`1; z(2Eie(KNpsiZlx_JSlKG7S;{`J&eCB%jr!4%1%v>qTW6cWDeoQXu>nZW|^|C+xp(~ zYj&2?r$@h<)7hYh18nzCX>TpQtQN`jYXM}z&>`~wN`U~$ekAi=DbqynFanVt0q?*%qTRKaM&*j+!p#8!JW2$+I;b-LA=YnX zB~-u8Jn!bZCk&#lfe5r&lAp_?&bs{1@LLzX-%p%!6Od0qCG9_jV%k!ztzzgfLSxSLHiR>BeW}FWD@;5Is z5!OGmeF-eOX#nRmdzs=&B>~*)6Ixs#2M$p+QzTYm_NW}tIvPdH4{2C$;OFM#*y!2d z=NEGbVw93?lRv~@*Ch-3Rg-F!?7UXq@|$wr{8$>rPScF`?~A*Ub@xEP^SJnAy~=ya zM0i)1qQGr;Q|EXroB5b#mm#s4E)`ixgy5?j9O5rFtF%*TaAu!Ck|v3J0z)vfXvZ2lllDWe1Bfpj2)84h?}BN<#s3VOX; zdozUfzMKN7=_0YqGYjpg(e5x>!>+IHpiqbu*K)K!CidE}STVsx+DyNAhO!SnB&^#L zuA%=hT3qrAzJs=E>eh-39%^5T|4XT~4~aW07!R~JWPFR2voL*k>vW~nnQ#r+{@WxH z`lwK=0TKiPltj_DAHveM1e#06p~|@d?RwVx+Kx}Id{-)$Uj6`s?|qmuuR>%EFY;Td zL`)c@}rbqTsYu#GIoUX@2h5tGNA^i+-%7^)+?j-u;@0;W1{Tki9 znOmMG&awq%bG-2X1F9S)YpHtCr^$Su)U`O?TcjKJrXqs_$+|#F zz@lXZmsP3P?~0DxPOV}ZnlvIcMoFI~pbca)u>*k9a8ZpF=}dWn(8r%e=so|PxQTb> znWHiczc-b@@`6YbJgXJ?yWk7PuNLbqwNn;lYid1Tyv{S5@>=}@vcKSAzDNPH%#+^* zM>Yt-SSlZppr5HJx4Q`i{`eA15Z7&SIT>%5&O=}+yB<>z_mmC zG&L4P!YQieRV|GEH{$DASVO_sNBE~tEkD4^OvW4=gVHI zpA*ZVYE}PfE2M9Wotq|ZQyb3z%;TxU^#|;t6~KBhjTrNVRcaUJefG_&ox$1Z3rRcq z_`5IRhHFPdm-qAm!l#uB6PznIpx7@nTy6-AN6!uECa-(%HyFUwo_ZuZ}-o`AOvXsUoM5Zmc%7POS@s5I1QYikba z<*Tbx0id8#ELPTu%qxHTAvcmlfxAHd-7SfBd27U%5}XpeypG6&B2AYg*wj2hgZ$`l z9~Xn=IQ{zrpK1`W7$jcGMp_3l`ZGqS1Z;tbh;~r@^E1YmDLRPj`j0J@=pvMKk*|tc zqH*tkvhn3qyvJpn(mLjU9rSGag`T;N2leqxnG9+B!F_>simvR@!$yMx?ASxu{&9My z`3EO{9!47v>UJ%>{@(Cf1no|>;J@B5H2dnS>rJ1ZX+OZTFbBT;8%wcRcjC4f0K0Eu za&|7jABo|tbL^!IPcs~?qa*q6u@VcZ)<~~^-i*h>MHP5C=nc$hX$c^D7->6v0_qE^ zF*xbP3xgbU9$u>GHW1W;2S@7+V4~&|+@HSXFD6t?K6MTsGpx=z+0Bru7=I|8bJv}i z&&@NmvxO0oSDD{p1N(&Vd*J`fQ)^!VN}6(u?u#3h@4<=a+1EhLHqBI(=~B;t0N-Mq zmIL@yJn-vIwQZodJbJ}ZV_XNrgSEIfba8>^F_k<=FhTjRH)Qo*sb?-4fGxtRB6O7G z3J+sPL3r-LbH0a^EpkKEDHQ`PbQgfvvGD-eF1}*?tgl@!UDjT>-z0mK_a?VbV5p#A z^bc8xIJ0*4%omRhVx#1mPtS`%inDYgbq@t(r13|zpIuZs*=TapHg|$)Xk!DR)4ZEIn%SOxG>!COs|logH{XbGc;sQ zH_2@HpkQ`H6(&6I2~wH!ql{q4X$D;ORBIlNqn5~lhJ7EU(CsP0m>&N3kC@Q8OMQs> zm(#$S_1kqhAv>8OI#Tp@SKe@pU%pcQjlN@Rg3)H&Hpp*|7Oti*{T-_jmpcNX%q$q1 zrh$~`KhLNPPxZN+o#N+|t11IUQbShg{o+5ODtNW;s%iuqhI>f8}6N(*`3ZjG>QfD!$U2RN1?42@>WZi!WC;> z5vr9`#oSxd#E!MtFAR{G;#!Q46(Y4JAfDK^r~lU&;z{ z9O29POAM(N7jqc3?7I5O?uZJ_ag@w^wgo5l&0d9RjiM~fzy1^UN0uF|F?#!s=gST& z1SV?6(+-U4J@7xNz=XP4Sx~okV{3d1j(bXnMkf#4fOFab)BPh1b0)9!u1zQ8sy6avBo~ zDooq=#dMHV`^oscGcFlS+2{R&yWPU&JKld04dg%um}{Xm8(Lmbgmr|HI09t0+ULp7 zkmJmLkBPE3TG-9Htl?_<@8S=HfGTGw@~6e0?0N5x@4ePCid;N3qL?F4Z|LJevM@od z)sQ_e3_+c8W}H;ehL(baDD;N^Q2+!I!~A~=+NYtr`$H`ySh0d^KFWO~7PjwI#&N*8 zR;6b|K;$C)9VrJ*8L|siCeMpBMg92uAf*~sX`&`Z*)d#~49}Tzc2fv|EFixEaYfSV z`J|?v;K(SW1Aw;#p=~Jj&l7h)E&^ng)c6U(Idc^;VY4j?s(NSkH)FmNb7}FnEqJj; z31*oua?;1M4m$ue0NWJ`onk~G&5Q50$lZ7UA5&if4|V&sKPXb!mt@T{wvjD+M3ykN zY?HA>4B3~lWmlA43}csdh(9Y1&Fiu*JeB)>3{m-JK|cOnE=tmGh)8WI2=O$MJOXU zi7Q-VFNqqE7Lkde?AKwGnm)IlPXQucC+9whMh z0HmgVX;56M1aR-_Mu0G|t0`wU8Ovh83FDe9JBljRSsJ?YL5l9NJ{WqE_jmnk=<>ta z(*u8t;PJUu=2^Fuu)yOf<>R-rlmp(Q)1#BlTma302s3Znu-DCX}?1u`t#NAK<0=2f3iba-3USh$Fo>j1&%sM)8VNNfG~>Ms)Ccj+Z$Lybo4 z^EUY+@I*RR6v9>3Lgl2!RF!c-?)%=yV4(UN;zX#!nxcOAkSX9joMI!R3m;H{jAd_n z5J+AHo~fIuCcO(f%yfk~P2ZTr184PB-p*-Yew#YpsL4{1Ndct zSvi3I?OT!ehs*3$Ge+ZSJcD1vY&~3bt2t$0Sm@oE!^&a2REKXjJg|&@k`Lx(f)r97 zipJL%OmalL)c6`umatACWt;MUL6wzQWsC(f@IPH3UuTsc66S$Gz~~h3l)txg<=*5K zBnJ7&$Cb$Qkn&8Ffem0Ag0Y8=djO%ZHUiBAiT1q6(GV`=c5M?(q~V5f0MJ?P@!*?j z2&hX-+bJ`kbwioIK*TStm6$_Re(g#~VifJ3+bb*o*fWIfzXr(@|H$BgyzxJ~9{lW1P269L;l$P` zV8%SWd5HpaMBnA=f#+Y<8$UqdctJNSti|M&;GX~?SQ&|r3WBr{IH=zM6~<^2#3!C3 zZ7Y3{ho*DY>fRTywXsIP8|{edk=d!Ybq!qfli~KjJazy^lpAv{N6g?q*&*R zCpe+76@EKqUTWXQTY!L_k+5343)-k|ZVU+TY}~2fp(>76!$e43-IhLrM@ml{%4>mg zFmCUWHJQrlg1c;B8Sj8$)93r1bRB_y=Rs@Tv+`>kFql1{oOq5viYwn&LZf z;y-~BzkkQGEl@@nM!5^B$ch{(=LPpT8x~+q!OPNrNq_QiZh9PY2uRVJH|amvR25wB zhTGpZGC;6K<=ht*SH|HPBLwEk|GWZC2M)DGrhpc(A*bk-js~)} za`R?0Skk24i3JQo=>4|uf&ZC>rr)&{sm(CCcKuu8_)*4=E;S#rHN!C;^&)I>oyQcx z+MaiVOiS_(nc(w&IONE|CC&rR>MO4#-!u^zBycgK8*Vje(PeL}RjX85BJ%}x?i$U> z0lJ{XG0wYx0+Zao7zP4yjv(L-4_g^Pq;QVZvWkZ7*>{iKGtsNI`jrI2Ay?BQSso;(~`ILeT(1pe~Z?!vDx=*3-0e;)|4^88fUe#j zmbXQ8FDh1rh#|Z0-_OQIccGwt<@hW8@R19kkjLJ6=<|zPiMU-44?hwg@$NS;7;y)9 z$Et%S!5c`Sc0Hkn`zcsq9c0;nZ3YQS$Y8FdMDZ2Ds6vG_p9iWyHzf7)qTFaQL!7?r z!h(VhpuKy-pQGaR<@O6&9%_#)y!5DbfXq<0Zxdwpc_~%csSTg`$_tM9%6lWrWV~O& z0aw~+=ZrSd%zVwEgTCqxY&uwgkMW2E2z@4FC>-JT60mK>v3XC8{3on{pF_FIiT2hK99r}f%ZFa-PvI{Me3dti5Io&LNYIahx*+CgO9}MtJQ8#ge8#IJ zzdUQ=ruRKoD}FX!vG1p%@VuJv@jMu~-%jH!n|3FY#N_&mHocqcZb1W-)a{TgAGCEc z*7>~A9KV;H|9&jH$@!P%=W`Pzy~1Z|x)tMQ#)QpC^1Y1XPee+vx(AUUwhM8Zr(joU zzUtdsq>*_1XBj__Ia5{uSN@t95!gp7B=#Tof3gf43zCNA%6TBn%V7dwA*2DTWx1ew zAs_wDC+azyg$b?;zNiOYT#tn7&u3(Bt*UZF(Jy%s;NkzHBzX~KOKxi zo+=|4!Lz)9_=aP^9?F)4bhj&@jW#otyOSfF1j1OrmMww4bl%lhf62@q%34t^=~UI&J1;s;!l$LM-W(-J`C}c{JNpbLE>B7Aua_ zuSvze|F^Lok|~AZUknhBOKTW-{V!rNf$3k17(ed~<~unob*)B@uHWY{_+s{+uI^%U zM^glkZGZQz!>|N;$EiIbH2Lt=h;pQP}=W+%O&$7g_>5 z%w5T2`KJ75IcL8Za_IWAOc_i#-0xW3UXkGnYAvn0mJYU=S15Bqciz>&{r^1Ziy#Oq zQhc??jRAoOV_}wmO4QNq6Q$-AK^XXE?rvcu!3*Ka+fFY66=3#`9)fV8 zgIWA5d+`^W*JWR@;+ZCU#AZkGTpdGYv09gT>az6yQ3zAd^fymh`{}BK43$OS3pGP@Muz+yTX2n~4p3?kQ}Ff36zo8A zJMJAfwnD0wCkhGM*-G>42@^_E{VqJuTmQb|6XCEjC4%}<5>TFZ&%AS||_ zrtY^{?O{%le3?AlZ=|C><9Da`RdDrrbU$I|rGB09dxCp;K}Wome11}3CL*1B_3Y>2 z^5Kqf3bw-mnuZ#IeL2U+j$1(oMde((S~Vo)2#4_DhCXxK-g2`;CS@g*DZB-CUE1q> zwX7E6Q|uJ3s;D*;l&Q+CS%I9rOZ)4R%W81cgzg*p+>tRJE2M{FGFFvSyaygqt=E4C zzZ^8ZYvkW)f^@QMX45AfU3YE$xEbzt!9kn3l>}0Plo(cN~7y z{j+;1xVCes%D0Qn^fw!QqZ67mFB)pppaSYo@0PUq3TU{qUU>Z%9cTpL*75ey{@T|{ z>#%iWxvhS*pF`H@qv-EoX)DtFy>b?Ec5Y5l9)PKo6OP{1JYiU_s6;Zh@5=-(%5GX8 zM5#nAr2$R-fkX)xL~H^Y@B?5Xx73fF$0(ff2Ra_PyN<5j7oTeN1^iS7<#Re~S44vq zg7xq&!RY5!+~fAglbg&)r+o^AQ!}0Vw;SXHB+DiHHcZy}W-wbi$AJ0l-f(I786$CX zJq$k^&-5p0ZH;ltp&;WD08saU+ZBR`DELO=$Bu*c~vcW=xRncbWakhk~DOdHNM_ML0LP^-f6N1 zLJFLqO5^Vm5+ol0Za9C`BEufQ&J61MrZ^oWZ6kq3XAPbQ*^1bs=<&MlzjApkGGwVb=dz#iDA&V;k)_AcH2ILIf?|5&=HI;QzL~W(Q}tb4t}Cpb|rFOzaw2 zKhmilF6$P|WM{M&m+xxs&14_tO56Gr>M5++rj8fRM;FyhX^)U-dD*$dFZeY*ut&ehZTGQ3H1dN2IHY3zKk?XSGUPs_Wx5AFG3baV{L!}wy` zHLdlhzPHzb?I9l%QhNtfud@7mIwpR*0=av)78#%MR6l@v8;vh7W(cK@KS`u1Xpsed zO!1P_b$RD6$?4m%c&b+$9#Pa*8=oV>?+(DcsUBnD!pC7j5nUX1$|4&(Y{P8O^vW2VoWp+1wXBtpDjE&E%CVcZH_X)b4%e(g;>lH@JA%VR#%3bIj#sWLp{j*S|F zH`1w3PUJfnyshoWCA4`Ex!|9FKQ%~~fA z?7e}eQ;C+2w5(j~wUq`x%qx14;a0fU!a2LQpIzMn5<~^vhdyj9nS60YhYIfNL+MyT zz$l3$%hUz9MeL!;mrZSNJtcJ#42VqFh_9!F7<(sqID8&I6*y)~%T}{i$ z#QU&znIG?yS%L&$+2zB%uA47*pU<28ZGnSy*1Z$tT1fejJ*yN=5Lp&XZvB|*)6uVX z=6(eu1=e!&WC$=TJ?&3gGJ_74$irkjx4Gxt^a1_2*FyWXbW8kT%yX=(@+PgU^z=%0 zMM92l=_3RZq$!VlZlTd-#3OoB@BhwZ)!`M^l=K) zMv(4`daCVdhW={NbHnQphQVKa%?#|-orBz>i|-i9?!oH+AwweO9@w1+nF~Hg!M%e5 zEJ5T3NqnQ7Q6+n1(MIQan`1BIYQs2b>Fev~qO6Z|&mOcsy1HV|XW?PlPzN15Y1{wOKRa27jLFbL z*j{ps&Zu`i+;@QfTQbDJ3MGP~>`Xo$yX%P|-R5}@a9S=w_t%XBS(INrOqB6_JS0rG zFz?!WDW3;3;w1ZKqliS@(C(;YfnSELke$!(f}!0dhyF}kGL>N=esQF>hE%DMPe{Oz z&4WM8%LID5sW+7E(G8m@sqpoUJaGOYuL~^{=o~w5r>Y2-8jYutL%w|RS)}m7A)SON zu(w~Bxu-9I;I)9NFl8@{b%bN0&=jxTIbL@URi4eBZKQ1r=R<2E!#4e!!2ovV#EmzV zX(^G92sy6@n3<4H@iri6jC&*My8lGJCGKqEXRu?QO@(8b%$6&n0$EnBZCS*?GiG>0 zTiaOG5#q?HMdo9Vz|<< z3U`+mO}Jg(Nk)967JF>DoyJ$EH|GTlTGC6Zp<*(egsuC{tFse6@xE374I13Mi(aDL z{oI)6kN(qTSzr?*R@6&Ju+#ivu-+^f|oa}dwPLy z%CNM~CkFk7fLcDslGv6&>O+q?N{m)HvnWb2%%pd`ADJnzdJJ%*vo3pfn45)O((%bP%16^ zLX_m&k6!7ViC%2>TKy$6XXniB#e%I4lC;bDcGK?9Jv5OkA7A4;qhMQWv3Q?@nL9{r zI~Q`g1-TTgLq9wca4BxqfNY{OSaLL-{W?$!Movm*xTQXW=ywWJ=*`pQY&j!ku9_la zaD4;#9(eVxVAP@PV&vQyNF~3PcL&#TP<>% zkGGRh;0I$=gp}3KEi9QH3RhNcN1!)g#KH(h0hAOmR$$%h^j!leLKtc4e13R!3g2j_ zi^u{#P4>9vF8IMc@GrVTYf~A#F9f{l&TmU_8(g7QuIGb|HJ3B-xwu08_$f#-dTxL6 zGNlIAgKiHA^r}VjBVY*ZX5!)Vvo+SwB5&19;D^90}iJM z%#6{H<$-J*Fkj5(WgfHzH&`41Tte?35?`E82=N;)_J>R$$$Mzu&=S%4i5Hx}$ybwe z)WEqYMK$XB;kKPiUI$?5y7sPO0jolJm$lGpxA|oKb=U~*B!OUb)wNqY6H0SAUl|k# zef>kK6C@SeW?r>!9rXKEpH*!n7L0-g{uP`VpF1RZq#W)H`)omB+D|s-K+FvXCF0z~ z2io+FICfNuUf+Y=U#+4Y;_sVWvaOD`tr%*PmCxu}F8--d{?iFqOAn6O&`XeCwG(%` zr>0vtjNhmO4Ehp0!g@Bl>fr>!u#p~Gvm2zaZq2F}=IUdJZ%Gtu33Ed*w|S{f}=#^>)Y3kIHZsO(_@rHuAP7WsoTavBJe+q;;qOf zQa@dACzaKhh;DfGl^zzYimuz>9ISgVWqWswk3N$i91cOXxBQ(tTihC%zcV5`(yDwc zaHa`4+X~w|UTvTC@t?B%_D*R$>h&$iuk^E{yyJUk?Psn5FR-$5J#ZwU8!mZx{-)9f zp=hB#9srdqilYA*)4YG7n#uI-Lc8i!Fhv|Q=|cvg-o68j(&jp3N`XD^Q|tgon9yse=cVkLuYvpu(B4n=Jp3werEgu*oO)5Dr+M-X1(n~FSGU#g zJOQ>%@Mjmi%&^$?thDeP(z0H{aMEwmejXl?a)|v{(a*G%+|No;H;etJPxHji9$Wvs zm3_iLF4FhgKQFHXHSEQ86GGOh=I9CPD(_tpJUm3?94)wPsgqi=_~lmt%l{sy!o)S% zKgyg5Le&b(cteWRxIO~Xr9EZkER)gaHBBnP091gk3J(0RriozpD`D2il{Qt71%lkL zdBRV&3+}7%EF+zO8Dn|?ERbdi*C`#S^)BtDSkQg21P!reU;E>5c%PSZj=DN{GklU*3W{-)y9LSrY{q$;8*@QICy!*I;Q0)~ zcy9d3_}^;``S{ltfE6E`e7z_P$;1e`8c5DZlS6?auQH{E7)`G?rpr~T2><5Z|M@$~ zwHj0bw9!V%pA*lnC^#WvTR)+DAW2 z9B@_1t9Ovy!~z8|B7m6BNTjCSOSql^?QAL#^UBt3rq0=0Sh0o6L>6 zpFk}XYgUa}cx(!ewOc=It1)gkFry^?fFT;cnjHI9t7fqf2=snt2J*G0IZ{k8N7wR)qR#ONO5_BgB14pmMI=10sB&e*96Yv`dQ3@W*m}-}_ALd3 zm4}32dn0u5X3L(-coU({NjZ^tbJw~-2}F;)Tyg(CVR+AfIO6}p3NtaReB5b$^RX{I z3oF-=f=?v}EsZn#GnW9#klrjLF;$pCta{83d-759!zNz2%J7x6G65#sK9gB%s*CcQ z1wz5#>?V@(>dp>KIB&(Eeq4}U4 z#iL^2D*HZ-fcaMiA}+_o-4$Y%NB4Ou%N?Yp(y;6HxXN)n-&IE&sHXh3oV#&guzM1= zoJ7h4!3t&>yeV7*85%BIZSk?$HG4W58L?De?OK%{kZFRuUp>g#J}SfzGkey=v^z7R zAVn9(Z2VQn+%TDS-BcYxUpQ_|Z>c%M#9$mzipA67WPdid4%KW<$!3o&9Qb2w^UkYW zaqK#(YuTsqR-&OuGa)0`P5S}U*cV;~pLaAtY~+#Trj|WxCUThnK8kGM1sHUpc^oFY z>>BM%BC}qWmw);(N1xWigpAQU`~m5yt^RV~_FL=%qa9gz_7~w-5*P2jn&$?-e7iQG zBNGhjAJ+1IRVdzU*PC@E0WfePS~I%m<2v7sa98#cR+W*xwr}B3O}-d3!2xwonsp!MY~@T_VA?1?_D2~1WN*Um%iuK7y*;33p=W@{ZC=bcGH+;3joz8CsyYWC!S zt7QDzvhvR2>_w`FjStUNr?M6nkVC89hKsZ(w1fJ}8#Jd4bJ9dbN=`Yb!Y5}+2mJ3X z2LCG_agWfncDVXqzF~1j_f)0LuG4#hqe#fGE}O|}5C!OXH#bD#JQ-hhe339C?=w!j zh6gt|ASl6IUa0}wBov!?y@#>|m?{2b@UZcf##in(BcB8+z7!NkW18ziTTk_1?CT94 zrw;+=>FFjoz-z{k=*7OSIM*Zd-X;|*SUSN-BU|B%wiuI*a-8yZ0GYy$Tr9fDEGt`P z8Ko1v;jr^ky}kC59^0ho=KZ^_@1}MRpc!YC>3O?L)a+V2Vy7AAs>%*xO-2yXf_q1$ zp?_P#mdBJ60IBkMqhohmpPi!^QA(DSW2)Z4qC?C#*@rQ9ZOFve1RoRLQJVc1xfIMadsJi2TQGA!2CW0O zOXGK=ZTM{g5kW>BeO)d*qT_(ch1^Y>WH0|ZZTRJk>HWd8rnA$^vmP#>_LQjx81=z> zLj+Ep)$!9_+9w83n_^!cnI95a>RA3@%tjOkaR2>d%)Z=es7!D1)i)Un-`{s?r`#U? z@>qsLdoBlmugkAI8sdOE?uVNqBr7%5M#t|@YTmE|gJS-AeQiOe zM=%qNl$@ifqEyt`*`_@E3VzI7^8B#$wD}MF2Ewm$r`LMay^i;Ue34@%agUA9V)%Nu ztd_asrI7ZWPT*()s%rC(h5#9{43JXIQf?q>lY_EVru3qCG zf!o75n+cd#y$Tp9P_Ef))8E8^d|i7;TGov-FhjguF$Mc_!mKBsUAoQO$E}(r9R+2` z2eBe7HOB)KNPa4KPlJ?AsDb)6N$e1wXU(M0%%{S*+Nd#r1}RkgC9etOyay|e0pEb5XY>HM? z76;g4ZZZXlpN4)P{Ci-1{ukHjk#&YNpj%bs0k}dvcOm^*0Fsr&UCOx_@aw?fbr5m5 z9$PHXO=U`Av8ZDpWeWLCxK+^ux2&tuML}T={0`kn^xW{C$Ol_xcZK{QCjw^wPb%_q z_DH=RLU=@iT{j#k81xiC)^F^3_a$h{i!LESyl(sGpmwy`F5ylxZZDC76$Q;q(I?4@ zcLz`*rVOssICqXvFo0R=I$cx=cM3KuO--$Be44xVf}uS1)IA}0zBZ2~qpPQ+O5y&~ zp=xlcYD0EGcPWxLm3^r-i$Qp0+aT*#1S5_gpxgXE7z?~GDgYw|iU)W{DL@1JOCy`( zm+z;486{l~2mJCVbr8gQvpM8ziv&`rM7HNKz`!Fosb`nyaJOxBOy{*m_>e2^IhM5JKgr})HA-7yNA~P(Ma==Wpmyf z@JRyFo1+u#F7O8Ama_N1OaW`q?{_d4;jn*4AEx{KA`f+Pw2(Tr9`Y)Kg=f-u$;QJ^ z+ozk^w}1@77@vTLpk*cb7 zMt15!o_w>yU-zWZgDoI%T8uQUfXCQbtmbrNnx??-K^Ebh_rtggW<* zncm6mENm=(l<^YC2lO5;PJG(_4fIDsUxa^--`Yzzz@zU@6C!vtA?*c71PG%mB%(#tIb+738%O1bID%bP!xl-Fq z9cT0J(0;hDpo1%-JmD*>rRaZ7Mma7r>%}!i`E--yqwPn&g3s*ERhK+g1w^KY3!>Zv z+1=dew)-|!(|fo;Y)loRo!DBiHv4u3?9mXfGw3qo(eaxwmpcZTMwz*9L^%_yBBcwe zTreoid*^AOsEK|EAb*BN55}gSlE?nrxzFQEelIL79|*xRQN=>qoKopAZ1LTOvDs^Y zDYe7Dt(D}xDI8@+s2+D5@Ee_Y;JUTrF4#Qm{^-v^qgZy%`p3H2ki&`XW+HJAwl-_l zZl`8H;wD5hc~ zQ9Jt{#MK{g0$XxfUeygTQwu8ANqp=&n|2}N&$n*_y4T0b zq8lopPbOi(ijz-XXbyTXIE#ytow4GG3>cXS@q5pu`uG0t>%GIe_TpxT&EUfA+>HjU|*&VL)YnsopwEMM2BfL#?BNE$3i7~Z~X55072-4x83ji<$` zfl_a7QP`Zp$)MHb8Mfs}Y+_e7+k%Y}ud$NEU1zGAbm<9og#?X~r zT?9{IPIYe||8e90XaR`TMT4Fz*1_9V&wrK8&uD{x9uO9V$qzmbajZnfhio5p+L;=5 zXOU~Y08Atk7;Ul@v+vNLDx!Qu0;_zi88%Px;CJE_SKG|*xl2L6 zBHrEf#M3x49BA;5D5O2eOp;E)uDkxL`z{M@<9{fGh7nIqoj*SDyOFv&sp1k?2ZNi^ zcV<810YAGj9TMFL%7)YlKvyHUZ)T!t@H$y-q&ymWsr-qQBPV>;+qHhyc(t3k$4sBQ zFd!+)KOjs@9(S5_RHQY~dR_o1|336ozXAvdQ*>1pXd6J@dsPMSJgy*#c^Xn}uWhd_ zPGRYWkOb80k|}cRch50fAcWnP^O=)?ztXBMqFk)Tu*7e?(?^b;t1RL3IR&GsGKgIK z*4m5gmOlok@{RWbjxRwrrv?izf1wLKsQ`Y(kN%~*BfAe6q6|>e9d`fNin49Fj>8M1 z86BsF8mW#AqIH{z1+`@1em7FE&XsqU1lgf}d@;5L z)Q1sd9iK{cWXmlPl5@FCR@r7Kx*+?=$<3DJ+awpizxc$l zLzkoC-_>&XDy%`&m3sb>A&XKaT2}65Y?EfarPBSdexT?WLwzQ48R5Y^AA9c2r?m#5 zh{*P@6cNXAj})#ohygurf*<9eUneB|f?R6!kN1_On~7BuNrcX?FZy)3dpqV4QQRFHE+Gv993N0I(s>Jn|sE6Sl zUqpK`Mk1w6AZkBi+&x*dKH)iCI6JnRJ#jhs%gh}i`RnUxf%3=BsP`xMt^0j`o%ub+ z?AJ1*H>g5(+4+S!C#za}V&h{y`ngvo%2c_8%jp zS~5@hP6TFJ(hr9g+W@z6x&5AG=)T?xQ>^6pCd-tZ&b(HyFvi=|Rqh$w^8?6s)lAhc zEM|QHxqQtO4sRj`R5tlN@K-4!^ZVyN>^tDtKxu&8F0y=v3TQ8kHJv8$k=lL^fBDE% zbjBkHJhVM#38_^;Q?hYXCsR>v{$deKdYYHxdJ42k)`PswUxr$*N1d5JKO^R_TpR#{ zE!(WbOc8XgHJPM4;<6H*i@xNZ&9mr*Vqs7|eRT*o!?%F(<#M0w5Qa%8^1HLH5yc08 z^g%W-{3BOs1MZGi?U|fm0(f#s#jwj){9%s~0`Qxe_%?ZoQXtF$`$asiq8|JwaOlk) z2UCb6>$?qF3wV>OwK>`E)o=FtN=GODp(|fct6Gk8$=*D;9DBBs9(LlR4B7@11MkyY zgmNLll*>%^PUmc> zQ3mQi+w~tRZkkci1r&7NU9FI7rQBs5Iky>YFALEbI!=!J`Ak4$>kf@PMd5TS+=7LZc7Dm;T$@%5B3 zTc!7M(v++ADeP&4J8M^zJJDC@Rulpq6~YjUjU^ka0dV>7aTcBrY3I^z^vNqIIBsU^ zZBs9h`gx5|YsOr!v)DUs+1>~PGODoC4*#%0F4bs}2@!$D$qfR1N0+vSF5=VA;IY}( zqr7HG;%x`WgbvIL6O%%Pf3!snvYXt-9UwOXhTr8DP?CHqRtW@?p-$yE!*2sQL$sE< z5o<o!iI#CKWG-FFnw5y2i8gVVO$PzNQmiruixw zI(BDO2a(Jzq_-A}KtXNZB83M1c7fu}foF*}CSt)Pl>W<@m4^t$LgZ6ZpBO;I6&DME z67$AWSX`)UX4S&k{I2z5Q%UXGec8!P-4_ZS71Byg(`Ub!2VbQsjR~>z#wZ4ZyZQG4 z>8&j;ZeEdN*8yrecX(%NN0;p#NT(s}^L{+A^WPUnf%alIo^LtF8y>NcV@#NH?w9BI zjd?c871av9hzgZkcbn1W3^eT)n$Re@KL+sLl5t0&%Rre<5a3|M)#bAACWA0dE2&=FI9= z{AN)%8UIe|zYN>VDE)xnV87pw-@r=wx#7~A0e`JyM`D8a?~_M*ivz^wI#B0SS;TK0 zG9$Y|J=Zn}NJQ1FBH=EIODcD_a|a?#%SfRHe=oa8B;qWb(&NX*IM9V&F9WJw`oB$ z+si(PFB~;?gzK3`2Ryo@f=+acvWFcC!i1s}hC#<6DaD*hRTamF5rthwSs9BOVFTny z%4KjMa0aH7uFJyJJ7x>FAOBNlSySBVDPj5@Lj)MlpAt74x(Hvh^9fl^51z|}!pP$| z(Tz%3qF$bdXDR2IO6s%6nKANIN_0_z_Q7}Bn17Qd)oW0(NWgbO4ePp&r888(mgh?hC|Ts5rfxjlc$25M)<<2!(}vfUa6{}M0k4`<$@Cl{t#tl* zsOF#x@#+OW0cgzoCKb!+gdlbO{t1NxI+MN!X93O#QlNXniff%y7oy@;C)pAAywFx2 zLF+|n3l}W9%V8w!1}`rho`iHk`FOvPh`$1W2m<<%g_8hc1R^@?poqC_`ZrbF1mnLLcU6q-B1*}?pKm{L3?`n(kSmJo4;1!pO0 z9BdokQLIi6Quz0UAhBwgGzDb!mYD$fN39Wt-y>HfkYyNSdODur@w)@+jJ6`j_Rha$ zMma|fcI;L7&n4qA6{Ka32%Z|Ns#s5;1w+so8PU0$Tc`zLuy-inw)bS)N2}=8Qpmrl zArxFdn>ZW-lGk!lI*#5_AdAv)8ud$xA9ZP59PRW0eGwaPW^oiL*n^o~t7+E*k63S? zcVe<%0D#QGqJtjl864Ds9Rc<3Mrte(j0}Ht0ZV33vNj0qfwcFQ0~N)8-V&w!6!ncz zmKUKR9eAWR)PUIFKo4k)37o_ZW;8XJ!mhK42SAru*tK=p1nc6P6ECGlpP)$goWza*k1|(-6 zbQ?rrR)N?t8$HkY-0Al6GC`)`w1RZ2G@5IspTY~l84{% z@i?)#j`EbIde^4BM(`8I1}2ebFH)W~T~+yF8o9gQYMe$Gu2G#L6=I_!V5NMSOS(W4 zsi#D#+|6ZO#KnS0&DJ5|q!Pj~KoN?2AU=E%8z5N}82hrF2D?l39hAJev+$|%=GDZu zt3x4cH-vdIb~S=B-8*wXng}NU6Lf`$)iLy{df#4zSEjX~j$Kb7Gt&=R)e+L~C2u$0 z)Qr=y@smjckF6%fzN{PVRq&ARwm=-D5Ryo{W2`)vt$m zsMZI$Xy;>VtSICz$KkZz+Uz$X2V~?Bz8Kuz!)%gKSqn--z)Kpfek5^vqt}#`lC^+k zsMN2F2Te>bl-d$Fq`iP;)-$t(eCcwe3`niiBul^Xyl9>E=IBuZLELC5mYSimNu zIjM1&m`CParZfmnbp5=-B^zbD;3h5x~D{@~LN&#lhn6b|0p?KgJO*0~nL< z`BfE-b_X*$K{jz{2`m<9mK<3H)f1EXnY2t18cNT5X2n z^+sr`P1WfnBzk|UWwM;lU*KnV_1B$k0<~cJo4M=L6;IU*oD5fUdgyKY%UlPO?P2t6+#@pD^-OFnkoPf9_*=YwILII`Ec5m?D| z6Fu2uI%`KnLst8{|4)AR0~BT!fXw+Q52$$BeOmu4R5?0XcG+%peUi`uN3x!UrMVCq zh|4hLNg6lgA7%$j+}1W-GoRIr5*oNzFdROfg+~c#rvg%Oi7*Uo7$GTG=GisAe;RIQ zrhXJ|ESX`7gUkZQP71LluPz}8M{0DzZm92f0BLrh6X+ug_}ROf6Ua4r9U||6_{4Yf zrWzsP7dXyc5Ryots16kL`$Ex-Anb=?`v1=<5<5u*9`eIX-HKDMOsrbQX@STyuV9hJ zxC1&{h;3DQhge>;WE2iXRhL^{ZiK1U5WjJoa^!Cpr{`fymM@tjTAz4|f|W0tQ_ZSE zEUc9Zs@1zX>LQF1L1jIzm=irQQO|OJ?)ZR8&s-N3#p25p2gcm8G1E zm%~*>G`?14GFe%tV2z%S1GbUXmo4*jBX!i3Ue<2{jE~hu5c+z*NsEHPz!T$77OVon z;;{D)5~zAxz;rPo(^yI-IWJMk;i3H&dKF8iU3-|dv0Xu_=?AkR80q_sR!x_LcCo{F{@duU)wa6B$fO|xE#mB&NnL= z*m;oI-zblk7U))+;4t=1@p1t95@chW1Kh~c`uj?JWK~L#FsuyaiA+^vH$e%(3>`rn z>={!NDeIBC3Fd}pu1cr>r?KnbCeNuNok`ZK#FgQdgZ1T zW{oe@+_FGoKbZ~=(UvBRLi*-}2J2QZr$9L$<1p*P14Ew2gvj@JmZcr9Kk5Uej1T2_ zDPVL`glFtP<7l9;ALh*e0|gUz@x~Nz$8=k*L)hX&bNAW3c;9Yj@$X+68-0hs*ZB!Qh&aa1s#wgK^Mx{_VoTTS_+U z*M-PGm*W{Nv`TVNeb#+*l$gFXq4e{g-34W6%eJzjiKpikWH-Jr29E;G!{eYoYJYsP zrWZ7{D!GBa43fQuV5%z6)psNf<+T9b_pFaW{Qc;C1Hq?6sIVyj7Y zBzp0E({1BzETo;ZB2Qwt$*CVdNV#!WR*}#=s)yZ-F(oPwSS-ChV1pH zW`R#Z$K?-4@YhqYp6*N};ax%9a9`JjLSlZv6kT_Lf0$txenLKyY{0 z1lJIPySs^a+ z<)Y^1c#H2Fo+hy+Yei~e^;!c5T{ANFLz65&W0K$?PHb~95N-8>+e`baj>0^E$;=y- z19|$K1M%LD({dr#Kmp_%U;?GthpO)vUn)Q7Bqhlwa>peV&jFpqKv+d`ph>8FU+xkA z`N!VQ-zwgJUV@Z>@|YTM2^nr|lx0_>U4P9?zH?ovgA5q-?$|Sb>`lzB2irdV-B=(w29*QhJFT+0y!Y$LgC;_mm-}5 zpqv*yQZQ_cApu@}=i=iDcyU*7qtbO#g)~K;vO@ zB=6HYv^paqMS3Iiwn^aeNF>f_{VokDAp z5Q+y$I8E&&b@{D2896JiDUVfa+2%`aG7Z-ZG7U34P*n9L>PuYo_g7KI}UAX12@M%s*-jozmJRyxJGtFJ4`J`wNi& zzA~ZxfCrYAO29PJ%8-&8S^2>#Kr-nPh)im@!t!fUV_b_Fq)!U}+-%8NP`MQ(lkis= zM*MF%`Bus-W?JcHBM3Md@I8`>vibQ|dEd$@zDly{FwAjBtuBS&rE8!hEK=w>8^?vp zOCvRpG~*cHx!}X8snCMXjB9s`BX!chVOTY%=D=dh zz$Ksv13P@=eR?3~{~hPS@fVNN9m;Ip2l532zUmW`y^ms9&{ye>_w zyf?{<|G9pa{p`ih#yE#o*Sj$v9TY2>R*Jsg5C+S7?YsKk@guN1+j^%?MTh2Vk0et* z^#lT&^1>1jPAKk8PYUb*0DcElc>`@&z=D?4Fqe6&vC~v6)>x(k3BWKp^n=rZWV?*c zsIs+8Q&uYwrC5W%fha_J0IjoghK&&*R4+wv1O)Kx@-ud2*2ohOGK}+^nI9Z!8meN5 z{l~Ozz1p`uXOPKX4!$N^gMPhw_dha63iLJJ@s^e&%a^!PlrITS#Y9SJtM4uUg>XocWEG>X4amZnIRjajvmqeb<2L*;(=*P-5>KH%IiDe@D*oqB?QBaiOe%?P zr@r$H0zQVTu|S|RIjo;r7H9wnZ5=0bwn*k9q^pn5)Kk#V8I6AvIb{ZD7TN0hcn37k zTEp@IrM=W`X+8qaa%p?M6$nt+2Q=2{%v_oNPcobgdiNVBTS#kVW5$jH-cDI(V`fA| z!6svP|8jfwTmv$}wY?jsLd*R`A_)U04h9iPW{3{csLAbs+VS%9Ew;kg33&-c{ES^K;+*b=`cAS^7%#H_>vm-biJJoT$*zs3L>AtX*Nh4nVQD=PmfxBd?&|FQp^K+zr>sx(|DU!B@RxkZfS&Vx-tTYYlECRn0NnbFim?`; zgi_`Sp6OD2S^&xj8IC_|hYp(1c1R~u7xx1NH)UTIRtO1!k}vD}*>}&i{$$2) zl;kwuLsxv}>U9oW=65{-Kzvebl$11N47A{yLf-XE%(Wja3|aqYEW}@h3N6^0!H>kDbbi=RSv+-_NhtGjJ_v}^KzKp>Aw)% zMFjqS7hxU9wUEn6n&EQ1-+(S`SpUaG2aJOGU!$M{jLBimaV`S7*CqN|X_rh0K>pA6 zFGX;$(_+zE2SEZ%y}jhS-oXOD1jg*KdS`J=izqx+esh?sMJZ0q(>K8o1`}8z(IOw59G*@*3>!u(?BY=63vMn=ow=`XoK7B}2s!hlnM)Vv4|P?m+R;m$ zU({3%q_xATcbU-2geD5<$XPQ8>x`D^CyD@=$<+m|$f_O(9}b}>ElG6@Pe*;YnU|Ki z?4pVl9`r3D6D1Qxe-?+yVGwB`8(Ne+%z;?TIb6s&So7zXELeT1)G528rPPG>I8qFW zIv7hF=}Dtj0O5&qz85u7eTW#o7dT4!BUbhC8C;w)JB)922wW3Xe#`};f%w@n!b@La z1&)d?2oiIK9fCQ-?5HApCaAo=u;9icH9_%!wylu#zoY#0jraiiyGh~^i znx2^t3~raHkC(2YW9DGuk5BquT8e~&H{@wbE6!;C&8kr`895K2glZt~4|0vSItQn9 zrJ_jiP_A+l=C~@VFi>u?%!#8$sdlaTaGPKV(0wtTFqc}{AwUpc`S;=fQot0k z!+5%X_mPxHUjb_IQbKi z2U=a(dUb3aDcA&4xsp0FW)dE;c`Rq{FdS@JyE@FLTBrnL1eN76GqW5CldNQ-=zJoT zPFZbI()@R(Nu6xk*o*4Q!sswZ8s@-uxcJp>4Jw_{y88GhTUS1v@V6lvam)2&qw?4* zOH+qOzZAeu6Ig|A?Yn2AV|o;>c0@AIiMo!6is1h|I+D;AfcZlD(Nb}FwPGl2$M!0) zuel@JvFh(7$ej|B{8l;M^~BS0@M$>BF%w+DfIL>6<`KOHKjSnWz9Pk^r8~k`DE~#R zVMUjZq>B#!kqQg8M@oKSw+>#Offlv|#q`^&y!ozZ*HaaD*BNVN*=*qWe%V;B%=dXe z$;_+%F>k96)o~}14?|ZnMj%Q zDbCO-MyKO8aE@Qn{DCdeqw-dU_`K+*V=eVKruD`y-{h6RuNB>Bn7NesO0Z_B?(|JQ zKKYDl42~*gZ)al5i|qxYL=$^c-%vRJ8UIC!y5kYx%kdvE$n!_3t_&W-m>PdZTR*AE z`|=d(dp;@;n*gayJB&@pgZRg#+Qdc$7Sjv|iE6~(_sk`~;n4BjvK%kV#H|sIZOu1h zg$V%VI;irNz%jtYsXwSs1~Yu)TZAG2dpEu(Imv@Rql|!Mz;Vv?>d%$0p>G)K`Q6cs z<*AvO%R*UMbVgqvMgl1bl+S?Fd#f>OMvggqw_cdyGu}xT-~sCwl`zx^+rj4TjK}ER z%$qiQ<4AS^pl2z3z}DJ zrazhhreW&?=rme&OOZMsDH=bKui!8MRZT;&UOj)3u!j&NSxs~3lh+fLDw$PdSO*f# z>Ww4j7b&nn8vDK%mrz(|a>QwO6KPmU7^a*HQrrv1iG^cg{)UquCmE?pP?}2{k%sjU z<0H;c6zzvgn2?m&5aBU1Dxb+wj-C54^uwqYc)R|Xw-Q)w3i6Ckl0=WIQnXfWi1-6S zSSh`xJYdz?k_AW=hSQRMf|zLfz_C!sDfa7I86vbksuZzBr*()*fq%@zwah-U^yY0* zxpx_|s_%{)lPFx=s{l=^Lr(ut5d+{^)J8R|WB-*@+=)Oz@&16IgNQ%J0m-G%zEQKi{ zV<6N5ijGFUUH5;XDu)mZ(lGPYR2B*wpKa&Cj&Q$50uH{~Wm4ib=aT0)_RB81lWw&+;!cxy~w3&Cq zdNOG_Y#YjyeB0spmpn zlNl~L05_xBbJe+LN)=dO0t8yjP)RtkA#JV}Et?B4glP!uM#&?k4675Mo-)x=P(B<1 zC_wKt$s{3;b1>h;GVy)2gFG@d6^B%wdRJ0XDb*ML{+iEkBE%!K<5qv9rz_!5nS6}YGt!iBQ9)-gXi{ht4P1*4^h%}Ij z^!Grbj7^O7KrVgUiKCMhVBUW$#C^%uI!CD@A3Zb25E6BwYO;WWU9XO8*c*WEu%Lv- z!^+pXD>NE%F{ZV`m&o{eFn3dcdeiI?2X$-BTCk#$e1*fMV06(v4ve< zjDSH~^-7&Cifksj#IOT*%FI8=X8)rmssFtFxli=L?c#|E?3~C8jYh+rB+kR(Wpy#I z05W#-P*R?AsVptTES*A!d|EPK^QimvY&*LEW`$Zp5<|j*32pqERG%p+2uq&N_yZQX z1U&;jLlO6Dhso6ZQd9#0aN*uJWd4VX+3U*Ja^q#WZi(y8@q|oaPIfV9)RJ+gT!`{` zw62x0m!HxK@omj2h75}1)!rv^(!FI;rz3RLmO80b#bXMK_`zg#1!$K{0$?h9MWH(l z^R5o89C?N@JGJIqQzoEDL*Fg5I!_uD;?UBs=WOW)ef)uKYZf`Q@uq;yrSp0UN(L-V zfr~P%gB49KLWxk?}I=ITxoV7MhsEoTvk(m!z00=BkvSLP?$i$7Rk@yAG zfKXqjY}y+KafIqW$7hTJC?=}c_)tF!kuw1h22R=!J|N>>YV-7_(7#5(KaCg0wT=b^ zn#Ou|zbZKyHmT>YERHpyEiRQ%Oa08OZ8L;7d|VrCLaPdmqlQDNls)-w-(^zdL(Fq6 zXE+ZZz@TXZmcd9g&Q;|AYVcHn7##HnH52hNDoar1WP$hvun%ppE?x~N41B#I=Bk_{ z-u{;D?yGu`z-ZR2$G~U^e%h!Jw=kyzD`-8FGO^6{vhf#4w0IF6KxBjmxe-cVrl+0Do=gYDHo#t1KM03kXPhuOf3 z;h8otWWdYSR9DixBQ3~ZRnmCN$FSK8kN)!;ws^QSDkyiRY*b#Pk;r_(n;7y4(<7*W z2tvr1VIW51F6cFb0~MJ3erH~e3F@H>i+}w}G-5-cMmvi=%h>9Zs@4eGYn^b$`Zqk` zI4HrY^2El2Xi@(HXaG4(k_U|`tBuMhs>@s2)#JdIY%c3J2QriyOW;Li+!wBP0EI#X z%J8mj`37B4XWH83Aw}AEY@0(=dJFnARt;~Nm_B^CX}Z}_#l8S0)QAI8A~vfkwv|}{ zVFUF9a!$@~5Oe9sWqtn2S$yrtYmSdC1)d9=?Tpnv zP?w2GCtOVppk~=XDMKVbo#nz+-bu{|%<R$1uksX^DzE^7Tt8VV z!(SC1axDDHU56jZicjLDPjs4WU4R9BVhyRrh3bAE?b{JErDBpAdb15l_Y?1*eU~T6MT3}ta0n-Nq{#C2(2-ek>XsMrZ zyN7F-=@~+RBlBgQ0&&cw4-X*ft=xGCy(mK-fGEo}Ca~n&SU3lV@ZkaYs;{FHjwO!- zFCWfOF2@s1lj{SV;_bHYfQTgS(gCo`)eDu#Ji?bsXDqjZcaw<<+Vo;@xOn2f()}ZQ$snM4I8r zlSI9RECIS1)6miPcv>D#{DejdIo+7|Q5jExCL;vz@7N3|;Nz3#l{v&2@!_CFi9MF8 zXl`TwL zE7I_zT{HXxMICcMS)FowD3Qwjz@}y=lfJ~wVgs81^URKG#CKqt$>^eFFmskZRdRljPWg>9xhGk~PZ;y}TZ^Oiglaaw^ zcl@bWRiT~KL>24V6;KJhK=ea@AfAK&tmX|&NkN)Q;aZ{8I?0-K6i%H`(h>YLoEz^Btq=4kS^>n>d zMW_x<@U;I*2r6NHef_(4?;<>-Qc_Y{THGxxN_Wx54MGuQ&GYLcHIj zTj_LsXIOqnOgU?x?U2HE@BFn)%Ps8t)RnpewKHmuLjmO_`DV;lFL&7fD98U!sr+LM zZ^$-SRi|(IN%Z5sG}2S(Cj~W>V61oElQIb#>Brj`ITIOAha)qXO^Qf)FXgC&Y^jRH zTU#IHBT3VTi8}nA+A}irw6%#qWP%xQ%{@&zYf-q$Z^6G^5hoL7qtpm@YStBfcMiPB z54DyZXihJ?^R@h^AxiYHpdFvl_PK8RaFY3gPeJMUZ~B-(qVt2dbA zF|I82E>2ZK%9|Y-8$&@xrVbvd*Pj@N6GOtl=yKXc0S!P#vpZg2j7Gcqe7|~4ed-mJ zpQt!Gi`)2b%*Ds|J7xY_wQNW`Zpb{;!ScuwH?RH>h1vm3ByPqlGCqr@4kqJu z>vD_CPE?mu{o_T;B@v5H$E>JE1R6ovtTWfLTkEkQU?yxL$wNCFHHp;3ey_`M^T4H5 zNkED;H2$D+d4FsG|N;~n+@~y6J?Hg9g)w!=y(-))Fc6GPj6bi;ko!Zp^1d! zdxXl`SIvwi6toNXj2r0^5qBe!^AFPko2TkKGx4q^uY80y{HxZ2RhCN3h)SZ5@vwD! zE$UDCJWo>4OPVRV1ig=O6S~(MO&|v;IX1U%kH%OIM$_ikrZhAZp*{ELN6|Tg8`Vl3 z%H#q9+3R)24_!eI>0FlAl2e9*nV_9!5tyyTZ-p+uFK%Ylds?HW`vda?DA6E*Q-j%z zch|bCz8urTM+m=tvkY#&cjCW($aevy`EybTJsR|q08a(x_2`V{$*{#W~R(kC5ao)rC6%@8tQ^tgR?cshb8`bXD-DyDx0tT zC?ls@0MAwE{c^YKQ+Z3myDR>KyVI*-Ogra2tJzRg_bIQ=;WNE_;2!`%^>CY5)nRWe zGw3kW_IOf$1GSIg!pE1%&wnG}YUNJ7x4y@kF>l^%x8}pPXEPjaTQDUF*?Ax1xlY$S z@CJ3*&3?8~DI<)#UwAEr>J=bN6#QtAfIL#_;D``b_||px^^@tmM6XuMjK#o1eE!>3 z9=oO1%<%`@UaI!$;oRyIsy#rxF;X&mX__g`N_V z`|8 zy*{fF_OiJtzw5W&ymuT(#3w}k`o3U=ZhUN-0-ImXLZjwOO=z>Dc3X|1J*3TVtF%qe zj@Ep5V^oa@aVxmz-j{=2aK_@L%sRAS8??20(%6NY-1XLXcmJgdKEN%i+|z5HU0)^o zd*W}WO|zq$LBVhQbpy7P=r5a57?*CDZJuwuAQN6C^ij{-s=7bx+C3Wx%=4$XY!`36 z)|-Claoa+g`S#QmpYC0!By+46>aT>RuC#}3$FDlA?HkitIPd$~a4)Ux(;lA!-veW= z^6CMiO7Msy;bZEdEa{?@oDzu(qOVTa^uFE%YkTQRCue}qPO2}}UM{Ec4GSSTDi5}s zb=`Z>l(&B(HT?O~QazjoGwXs7zTbDdra19}v=j1q*t0JuN1j!>Z?D}u>{9tapmE-A zx98iy&U-XJ+rEKtT>2lI#8a(|b~k;NZ|-j>Ic$G!WSGfRg=qz0Kr~v&IxXNqACXJk zbL>`|`o1kK?=u^I)>=>m4YIfI6OJU!U7_c_1zPrKMSRCoufU0Z{8a(X*w z!h+=}Lhh{3f&yD1{pv>AjYkwst|Lm`+E z?vEk5|0(XzY4(O6zC^}N2Jh}&aL71D3BfJ7(#W`wbyLmJ&CbAeVAnN!8On}c^rlaq zOlSG7(3qzcygV;7I2N#0Jf%904{_t5+=VblWa4v1KK`otTr(+SCwkl;|&H+mE8_KOQ-B6me#O<&0Rla-6l6=bH}h`^>>%>q#js%&5t9GoqTzmTta zxrWSBGiX?4)NSW7zw-O{s_j~12XvI;sI{tU#((kQ)$7Nm4}U6_Djl!OD%^!_L-%2^$|1h2Bm8?19U9!ELOevs+= zEoC&c3~+8Sdhf;P=L1MRyrUA$t9GE+%p*Q_-XcN2SInX%|0t`~;$9mnlL(LQvT9lA)(zJe9S4^$_vUNuP?haNzA@_^ccovq-X>V{QHa((YdBNGO|dIntiUGnkfi;|wTqOAg3=`&kA=7KXXDVH+m zj~cx?uic#7s;poLcho6-gtYtG-lSMJmQntaty@~OSRQ)X505;Ma=~&rT7APp{qR9;8xv_ZW)4E3MQ zU{)zd){uPB#Ke3as&cb`^M4K?8hE3BiW zc8xMFVCaqpMU1w!{mR0JnnORa)Nsbh1;^y9=5eSA4_Iy>O}hBRXnxLgQ-tJtfsFOjUP2ueE2%Hoqv=_oZT? zRyh>iv1AU%qWu_`Yr4{uow0|$R{kLvL8sSdFbTF)s>9uuqR_H#*KC{bU6$7h_C7|> zF~~|n0qSw%5$Yxj*y5NdJmw|D5MQCoC~r{6`9ebu0#)WE>+lZvtn00-gM|ANL^aL$ zljTbDPiOb)=Ui_K)6M;H<}r{X8#u(b^bD!pCJc`$dqW@MVc#XJ*jO-kRzv)-MUClzlK>|I-FKGEB@ z)3=8-FU-6dt|YKN;r|&|QUH_dTvC0*vSduz0wb!temCf?N7CK#y{N@2gv0L5hp%s4 zjQ8EB|8mIszZ@E!7&H8{rt95}fjFeyJd>DZ8&L`eso4#$;t>{=#Sa~`q-5mEn ze^@Qvz-qYtwMPWRdR+B*#&v%`4RmsM7yEXn&ot!sBs`5TcpN=IG<5NGiFK~fkb8! zf+HmsFDZVI$H_x0hX*HCfK9802SPZdQ3A(vjRH-6^0x~8kH!LlA%E5WwC+lrbhfNh#tBt(1XCGCI#)79yM>wxY=OYEl zS>;yUY|l6ldyOetU=kCJH96g#*kNV41kjNUIz3jx;R;xw12Q?$TzkaB60b!GkM)*U_eS1bIL=sInR>1ixmv;QjOTj6L*L5p~ZQ+&_i%3Fz7mi z;nnXyZ*rpUw$Ank$SU|wW;e2A)=5K>OF+%R6@*8jaNF7n!4w1v(qmb{8Cq}L+3p<{ zC&QLomU=Zz)3DTuss7k1P0+zsKr5%Ac*MV#e`T9l(0tlVXqd((k_>O#e8$^Vzs&bM(_+ZHM|- z+odr4l_iN~_11ayU*Qepy3*^)BRnTcr8_exr4}jHNs-{gx1Vp*m)1V`mpDD7d|j~r zD2oWvtp;D_%1wp%ql3JBKUNvODVgx-yv$YUPJ}8RXzwU~6>jZU;528n5y}5=Ex=MW z$?<%k^ea+#OY=2{4)gI?pRAMl?*2mf6{Aj(*5?sY?wT;a1YwLa{4FK4pFae8Z$ejj zkO)L8H)?~tFLw8SSnZ}c1SHo$`s@eOj-2{cr+#Nc+^4(?PEto`O4olDxp$MV4W$H- zk@~j!%n8HXHc{k-4%DCRK-+zZwYl=8N(?pp_vZu|{9E`y)HHJzYmOJvHG7&tu!3}$ zww>%3i|a`R&6rfO!2?HAN+b6;@%t@ z5@HW&Z;)yrFyLR4VFg$gr2ez#xxdMJ!FAUq#&*3r&Uq_iY0s|x(-)q0AV(RnC6|Gr zWQP+90Q^vN37)T~@gaa;zk~P>#urCQ6M`1B(02*=PJSWxjwW!vpFGJ>B7NCTG4j6# zf+w_0JPjtM%m^wHr?MCG2AmI7mXDXi2EM6%EXWy~M;)abW9T*W1fW({`Z*Ra4-187 zC0!14GtQtAF&42~t!h?Mj={&tDfSTSw#`B_!=FNlW(1A zkNt@ojWm}&NnbuszQg9ZQ4i)Me5~El`?eNh0|2dQiGaKZF;5@B3)=6-(2JO@yYa>q zFOKqeT)icX^lt*|rN@PSIQn_;N5xK2L6OVUBvm#yG?mzYcl&A!BZ#Tol{!8{D=vYU zP-WWFE6F3L91^-n*0rs=d2r&36p(xQ$FXvBSObGaPs@He{^O%^%=D|BlM~;k`zs(Y zrN+WmmdQatN_up1f)1+hlVEO*@hrdFD7~HX6VcDh^!8}F@Y_IOLQ0HH{F8YSY8T~Q zoJ|7s?ciL@eJe?>6o4E>4c1)SujGA7s%7#Ej6U)yzft%a6miXH4 zhMrAP{SBK=OzPdM%xt~U$?g>|Bij8-Lk;9Qk{IB@EHo;LqwV%LYS`rfDR+sSeh`40DA_Xh3jDdKh=1_bbJ z_-z>F1F^)_H8frhKK~m_2V#{%Y!1y5|9=EIfdKS>(s4li^h5FgimJM!{eMPPX*VwM zQ`n6r$HwI4uWwPQ1pqe1r116kq4nZ%Lg zl$2PlE_cUMkg20cxR}P@QU7wd_$3EILPln6JrMJ?X6zEWb+jRJp^BFpsH6{FTEM(-iJ%B8K5QM&nSxaEL zBV41ovQAnQ5y!m7Fg*D`;w#Wg}T~X9311yb_M}a;D;=$+5GBz5& zV`e^r@w2v^FP+I2@_z1Za5-K+7t0z(ViFXpkG^fA5h!gmuujFS*Y(MqI)142XeKC`tJ$<7h-ha%T(q z(lRnaew|cTknGQtXf`!tCrS2pMK8~?LUZg$w?9oMp0cFrq@`5rkBpAe75)wx&^^78U%*Uvyi=$>dh1&GrHX(37MO3_UqR&#hD2@*vo0Ub!>71TXIn4QUukvg;a<6{VL^QjL=?=xW)nruSBLZN z?w1T!?312u%HTgMBk6ffSwXJn=ANn-2DnXgOPiaUNxsIPKi4-joZY>1cfU#JvQDn{ zh)H~C1BZ}_mFF&5lq1}JsQrzhM7ldN)^=N&AaldEO19FZ^M)Ps>~r+x+f#IaO_afT z9fkj86FR^qynormM$7zZEr3D{{%m47cp}D+Z?#0imeRgcHmt*Nrx@27&ePqB$b}yA zXCcDa8bd!^VS)fI|I{F&LBGwb&JXexA&AttGPQFZB6zrD>v8Sl5)?L6RAErYm%`1* zcbA|d3=<%iK*xueo4+mY=H`|_r*!HWu`?XA>CQok44k9fp3b;z7vr1ilXoS^5iN3h z%2-8W5IvzyX!z92s)*0MmL`{{nc~@Mk#|cqgwn(`f|XP}2H;Fc-}DI(X+(O00)UhO z2%X%pTQSNnk@st0`dr$2)ua?|np4_yUqPzzQ7ET&NfhR%aQ%a|pqN$kY196&F+iVEWH~h*3%i2OyowtOtbUxq;O(E zU`p4f9{gqz<=S?Rs@1cqhswXDt;YS)`KBnvi^l`HW>8cu>!#e?yJgm}LPiV)`bl^ar_pYmG!2_k4Qo?Kp8+le@eb6I5vEu6y8g5cZzF>3{;WG&*TBPt<9jmd-L;(5faheW2Ub@v zuKKm4FQlffKAXwsOol5{R9HBX#!1h}ScXU2CZgY*YU^odWv1Mb@R{jQnB9iC#cW+} zl5sHfC_AL1+dAp&$3ldB(S_#R?Cf{QIASZVPz!9&=s0qOje_D2e*ax7D=S?qUEsxp zXy|Z*Xw>;QIN18cJ7}w5S#kaQ(>_~q4^g`T6JQx;DbXcv3dq|jL%N8PJ$~I3A=-7g zIJUArQ76IbMSMp2#u}m!@^I6LS42$S-;jTuX|?HH{x!!v^CUZz@fr>k>^y0?JdGb0 zB!%vJ5Fjr_OD9Eem9$TrdqI*w{@Oy#ucN%H zD&pxvv!3ENOENzo7rPk-e0fPv=%DZOJ46fqWA$htlBm5<_)RYlFXb#jiTFYl;jEKo zIOUvv^?4S~duTYj@@6su1-aSd#ocd&4O)ww1G``Atvjr8wQ(-c%R!N4hblEo#>Xv zWwM_j)x-(RbJfdVeSf3X3}deUsd8$5aFSiXiS-8^^Cg%fyXE37s50jY=a-+B2Ue0p znN5HrDMdr8ZP2V{723yrw(_2UyfrSO_Ol~6qISyN=_dv}*>I7^tIuT{xnTU$r?Sp7 zfqFQZp=8+FB8G5(H3hYZQzBqP_l@k4vc2_PRtI@(Pd%HR;p0yI38AG&i&zcD5y7@H zNK{Uw<;X;;Q;rZ2hOypZ8W&P&0(cpz~9gPL_r zA=4SOQ*+Uox83y)uX2lwTe}jcYW7X#$RPOSE0$m)P&nq!0h1`}l zf~{t2p5Th9kvjH9l=C*yjG19vax_Y&x_vqZKJv5;!uimXdc`^hGL|XsE zykew&qEp^S79f0XJOt*PPrDBZ;qNI|y5~1n8MHXR)DbB(QM}n8n<v*-E5?{GImdh33GwIF zv7fyUW!*v6-YMHK{na;Cy=E3O>y=ua-VUoK(cZd7(vHqgd!*2N`)FeD)%96Hc6xL1 zozG# zt{>+(>UbvhGEpcR)gz0k#R3&x^mz(3(2HwvAb|iFeQ=Cf#Y<%{$Ob;T;fKFDVb% zioE#tEq>fzE66CR)~hvv=qRl%(Zw97OQH5CExEHkokEoeslG!MYA|gn3wMwOL>?Z& z4KSy}eh=2}nf6N@XWv(QUoI%mrXDUYxDNbxrVzRP4xR`}E!4BtLQ0OjPM|wS|ien*q#hyg>S}#U+<8JhMMzt`1@aSH@R9(HMT>XJnxqMj5aLq zS7j)pZ5*r(yIa76tGwfUmvhWdezLaLV~A(ntC@7>BkL}E;*?Xsp4TqQCetE>H`ZvPkawL2q2Us4d5bIPz7dMiC#gJ$!vqj%zk_d;~MO627-iqTVv4U9)7 zbawbtlZ9^%3&a8+2n zFQe@3=E?tD?<1s`VVny7E}55RSN5nI>vA`EA9wo!25+N6QT2A~cSeF>yI(nXH7m zKgT_pY;wco?=R)wXgtOkKv}AfwSJj0en5`amVaNm;2iYeUU`62$@25}SD~u=DSWs(_VpvLr)*(UWrFB&H*0ZcZ<2g-dy&3?P@068hdx`E`?<-JFeryapp577-TA{S z%SQdqXr&60M-n&h=9f7oW~3pXlfFFh(*VFYl* zNKr`jWvxDMYlqqz_9@&c#VT3n{m~mCz!~f=!VGN3rzf-Kbbo3y4AMyUB^KBZ4SCY@ z#44qn!2#v|3|m1LE0Mo-_4(-0?&;%hq0>upwf$rL`L?;OPaAkDdVL@KVxX*Nf3kN2k#@rk~;rvvfs(4 zXY4mFnf3k_i2ktXhg?lsZCSY&cxgt^$W=KK?d#H+V9js+uhT(ZNq^zsL0_HrlHl2G+xZxc)UQAI7yC!{ndkLS8^EDK07MRp28q$xH~Yq694*B}xacLy3i{Z>^ZaOC zq_rrrkQ)!u%=UG=a~7D2zU)?&j6+b&;;7dHHN`4(f>Y@xiB>mWy;CAL^L60Mc9maw zd@2SPxVcpADCMfZl=zW!oXu8TeFwQ1Y}`3)b1uLe(sw>(vRBi@V*LDZ_+hpUk;?|s z9^EtN?wi(Pu$t?JeubefJ~j%SKm4 ztP6+f<@%(lkF!I@Yaxk}>C7fi@>Z`h)A{rRxr6=kk*DMF;>gbh+YVrpY}*<1Ro%C4*}YFacPHt#x6}9RaN4}OXl%tUZ8~r?%;Q6xwoYJjwx9qxV>)0bzxp;E zNuV7G=dZPqfx!3<7b&(TG^uZ4redBAuYlhUqt(YLIJY+#F31r>&Ub7F6!3-Ceq3A; zeoF9CE~eg~Uh93S23WUW|C+dM>38W#SJr_R`kD$ee`mTB6sDXtKxOi0CED>wy&D3` zU^DWvj!?<3?c|M;C)MEiZ6oSLL=go zIr;4RG{Bh9b9=NXUv4*%wC!MZ-8V|SG^@+ZqZb2&E32#MeFi)C9|nBK?j8OpU>YDqI<4ReTy1eX4h(t3RkXg7N(}A za&l3@!GnPUcEZ5udC_#D^P6H#P#71{lL6vCWUU;x#q`PMrNX_L>tv8V`AGlJ7638scmaVs=kN^_}Y9lH_ zS^@RIz*mmI5#=mCJyh+mw_Qnqg(KkG5{Xf(mz&vD<5OEk)*kUn+f!j*0Xy3^68uU^ zR>GFz_{fGWt-Kv&;j){_gYKYXlnPRxq=zB$6GCA(ez(|X)cFFwK1O`5<>GvV9)uo+m_^jo`H!jtyW?OOYB z;q6`09G!p9nhjd`9Jl@RTo7ifC1fLFm==20Iz#QSy@-IUUH_rnu|qEg40Hdmv}}>o zb`c-jiR9DZCCWw`a(CEQM6i)@i#tbx0P5)Iz@d`yQ}Q-_(+C#?BHytzj1s%MDVK}z zr0S8SE~{qMP86OAki->)Xo;Xg?{+d9%;zI&BS%IdveEYDr(J2n%>95=%OMs{o9=b&O- z5UOmL(J4Ll@UK3PLO$AMUSI-g$Pc*FhNkjFSbZhWrULAuxIzC}-ZjtmJKcl~H+cNRi-hNJyWc@?qrSJqv(&y}9Ge{)p<2rP@;nH^tRq{VJ}?J0P@ z%86t(k7Dz^E3>ujKHPq-qciAB$^2n+i+smThsH^RNq0hBMM64f=MTX=j;pOTn_#xw zQUSxoExF8y!vpOp50}LWs3;J(5=ykhU zE>5pTB1e@osZI&ZSdPnwb8&ruA^qBn zda-?OEH@vUlLEXD(L0xSSKJVu9+j$%= zJ>N1tH@wp^$?EWg=ZgOlTu;Jt4`LMn!2293UeDEbH zy#lQgI|@rqby=Ao_5uz9j{*TWR|KIrZFT8hVvTpZwh3q+f3sx%c~cfCNdE zM!LoQC&#I>B8^KqZj7?z#mJS|t4HxH65kVvvA<+ohCT+AO4W0@qQS(d8$7pncX%8R z>fIl?>#e5x<92me# zO0Lj(*8i5{WaeR89^b~AKUdq?TkbgZHfEp!bxob=U$Y?+bv-mV@B#eoY`QD;bd4U- z*WXns2!B01X2v3@E?wFQ*iB7%Lfe+g@=|>6thEgC74*bn&-EOO2QwU5D=uPw3ky9h zwcn$nKiy`czGEauFFQP+U8o_8ou8Rt;}B$BRndfBe>@404AkP#5+vdNu~-J@{18m@ z4s2`jC{nGoezKrsAPx9jn?5I2vr)npd?pZ-O3;B+RM~!?}pDa=&pC< zOD(t8vQXDvb~B8I9Co)_n0+E!nvC7Te@_A*iI4N1`~ro$RkXBMJr?q!3Qr5U4h)hBiGVe z%cGuriLLds%%9unomZ&UYWdp{Bf3711->CjeP!~#k28*k**9-6(Jc6UPIgC$wa*WA zUuUMhO7>zQIYYBrF&IffN*qQ;OhA2O!*Tn>@h*}W)J4#4>=u9Youo+jzkJ?pYs0{O(rn>eZ5j zThgsIQswMfB6d=9Wk9)WT76;=$0P!1((f%~lA{eI^0jEH@p^+pb59uVLwsdj0cqgBe@I-fRQ|DW>XT&Bpi9wD(;0>H%D?mNr$~kBW-Q=k|BQgBlt00~#u7>weU$ zbsfM#aZsnIXqE?Ti4f0>j1a`Z^XB|~FSC=%ruf|91KNP@@9zU&sQLj6^YwtuoDm+F zM3v3`-SstISQ7LW)-#o+k33(gQ}gWtf=|liK&cy;+e!da zHmhv4FaG0?l(r-3?4gK!!>3S_-t;? zQg^Kw04QmsY|JywOJikN{Xz}-OLN2h)mnN>52HkaJN82qdXSx?1 zpQd`7x~Q=eafB2;U5*ySyLz7)K;zbajyB&^D%wdhxS1IX6woN`jlb&6;%I+ZjtT6A zao_FOF|X6`rsn=BE6@uLJYu|WD^`degOdo4@^jh=oFav2U*C6?D2?4KRIla|F#PKJ zadUY>ljmyj79N<^oE6EY1CjKSPj8bLwUN*WVpiEykp$aw-2-WgM-Wh=iB_0+W$av~ zF`_dL6POBlyaX2u-a+hy9RE)uQxtjYxjP*X5>t+)CRj8FVq|;{jOk?*Mq!7 zvibXRWwdYq$sp=W&^_gMd1<@aH$)NwJDtsDu?GCuy5M_YwmzRqau40C@2UokUf)o& zQ3&LlHr)ZQ%HEdQ@tJux^cmgvl@{} z=~sc8G@oTXSnV9V-eJIa+gzWv!d*L;ie2R1*US?a$bi0FQhCEjV+M?eOui{N)>Y=E zBKt}od3y$ESa(%`M&sRg!?gd{PyUJxV7{8|9J~tM-V%4g^85UYy=bfKtwn^eoUoQJ z(I4s;a04vT?pN}4W~&#zf*CIc^V6kbXhaO&d_kkd`6N^4Q|9AdnUIxadKyooA z2#bhC>NsO76F+C0tY9h=Hi8{tz2Rp$8lEIL^>Q} z^B)h7mEcjAfNqtHL543b0CmK@?P|-(QUfZe#Ti-zf!6ubRj4uIkIYwUhmZ9b*5G<# z)Ly6irj1Sbar!R)3hNS*inVCS9>IV zM!+lkR1mJJoaWWzDdT=K9ZV|7{Wmv!iHgJnE#>wwV~zE|x?Qlh0lVP%SH4H@T52(- z~|&%DW(U_v*qdlD1r}CrR&IgXZT&6JZS5vZHYqrJll zQguX{t1(?56+dmP2|!IU_J6)sEN9$O2Z1Wsi0FIbR<5wHvCnR|qsx7R7A)`XB@C+t zqXnM7VlT?3^71?c_33$kTjvt-gSz~*A3Jba-26}T3C2i%+Y{AUA$Ie&7XFV6O9M|#wjS2X18s(91F^`98K{yN{!$C>`h)5C<;HDhG_Phq;F^N++Ebf(n|E1)mnR;Nx};R<^_n2^sw zEGI>qhpb&WUrhJ$V$9 zTFNpy6nO!SEyMqhg1R2qAMV*(f>x9h;9;~P#f0u*hCQsi=IFu7N?`}xuV23&j3Qa? z^!1gHka+L-8WR(&RS8^FO$?v21p08hZkthQ$r>>n z=@^SGfl7SS$FhObcBN@WxoQ;17EfIr4;_#SUQb~w#l|!VuTBe3MmZ^rmhRuP z?;oAv_6Hkr6JrGTZrcCPVfU+4r|bCt^ZVbwv^f04|Hm!BCFRn;_GtfSGN5*PdRhP9 zStY)~9Q@yW|MQm$-Tyx$6uh+i8lypLPHjMBKlhX_Q2tkFHYmZ$xP#H8;N=qw3ky}7 zuRK`q-&-_j5ph_m%>7ak&;d&$1FzQrGyvJ3(yoUa(_^Lh_J>v7WI+lZ9v8?t{m8cK|K;S+G@j4wS3@}uExIS4%21OEaRauIb zy{%d{@rSzL^*HkpRV_ovbXrE>lVNm#s&eYIRBO`NJ4cL}LV<}{f1!R|Xh_IHi?fxg zwgY3{H@#}T_F>8fV06ypcF2p{E&35=0ABXII_f8&Pu8hIS_0d>K&v~|8t_!nASbn5 z&aGt|Et!}=A%y=eq%1(%Rj|oPKV4;Gjn%8$`28lH2Ia!ZHSl=J>XszDPQMqecN4Wj zROGOyr>8X{^Gz$@8BujyhEb}!=zwPyY_iq2vfris*alyY$h3O5G3{-mRO1QM#2kj| z`7l@a4;jWjV)|l~-E>r-1`{xa=t>7C$(==g_YyWx#bsZ?!sSC&V9lHq!2xH8u(%cpjqey&Vp9U;lwvo82f{a zh%qFKKHoUy3H0{lFe!FhVH`F9~;w|=*cjv_$__4TCK`N17vD3pm@YtS3=aMM7l#E zX1ON^ALHuR4ao8{V*TNp4RA)oEWK&vV)Ur^!VwXer>sop17}?&2`=-lcTG=!8n^5C zB+%2ar(P6;q?&hn0712Qt9CoLzTIfiJ<{P;#{|@ZuE|LqUZ+Jm6Sa7t>n5s{Kx2>8 zPUuQ@B?2P(39)@YeV?dWm}8diWkPr3-3%xeS#&FW%=U;8>^){Z<#wvQVI(p=EkRn#zVGr{&z3! zwRbiXyEqB{H5QmgGg(D@?R_P;Tk$kJVe|r`pCz;!ELl?Bm7_jz!%An0Yy^};G6$1? zES;TJkH7f1K7$c(gx|$u%|WyNFs)~538un{p{HoQDQ~hXiESbvs2Y<(ty@w)q+=X9AiazbsC-J181Zpb2o^Fy9RXT6)pT|jW_fLpY! zoA1+i$)CwFi%}Js9Ow5*V`*U9xu>Z8PVShZ1V<#z;CbKLllp?^UU#2|Yt->`#>5O~ zOK1oE2hbi*$M>}eOc&kU-L#Huibl8_6CIi7&8u67>g<>6LS_AS>w_QaE4@~4_h8{f zFFp(CuBfqBsCr7KRx8CF*&GFqhS@M(nBJpV8T=RKm&fT9((&TQhTCSaTIv3@x^s$9u@upkVgnlT}AVxOhTK1<(lS#}n#UR6hQj?d-LT zl~z?`2-@sEk6JZuwp#>qk;+}+UDtWthEwZ1MC!C1|IC%$4b*RcnR#6*GPXHQLiZn` zRo&a8U1Y2^{$0**Oq&x(oOP5e*t1!tVz9!-QO)et#F0!1#Uqz|~$L z{v|-|9fYoJq{Ot&)g((`Pw>Xo_@OVH2tOeYMO;Tome$B<4o&N?czid|G9~_rp$cnw zL4)I0^2^f0x6VISjuu8WEQ5vdW`^2eo5dz6UFG}kL_1iUN^ag@A)j$rQ$w>;aEdfX zVML^Ae93~tP3w%Luj@k0?Vr(5+2~4-(-~Rn{NPbH*fWtKBFOUL=E3B&V&TWqf<>RG z@_Z zwmo0XhH6r;{esqePIi1J{^3x&?3X^S-<^&#!TP7MOY&}}-@up7r;Pf(Uzed%n$hSX z5O@|ys!evs!w@F&D!NCs`(OX>Ha)LL7VcoELi3(LwW71SVR~QBN*Yf?jkIG&MXla3 z-#Dc}zEQVEm_|9ARl-sV?7bK7;m_FAc;U>}M_K^v`) z5cLtE2OoJYr{vt5HLf<%zMrJ}p59mf(oy~L#a=Vkeabh6pd-P$?V0S(Rkz6*k6E1P zNOOxJTgE;9y9-Ha!DSaE>uIY4T_ZaSBFe9&4-ntBtybNAbO?HjW6wbrYm{%}({G1| zae)_iq7`W z>#KR3CZBi>1PX^h(rjR5W}c`WB*Q&U9Cqq3^HaaG#CatCOJA5e&hBN^Y1DQ4N_iDh ze$tbz1&if!w?!z4-O+XbGIJJ0XL{w)t1>6~XMvMg1(4=lBXikIGbB~uL0U1%GPf9* zZCvb6$jeV`i+!Y^Fda?7e*a!mRZVwHClAZJj2o};I=<8QW^CYu?^>6|wb^Q^p7o@M zmF4tqT}ZQjr(B3FKaK0nJK>pKfAztJA29t^PAe z(#m^A#_yLi@)*AuN0KU6Pi%xXn-6=_Q?Vd6Rm=Uec#xAxV3bk5dmN&k@~&QA zUAo%$ytwB4fbD8N7dB>QXq$RHni8@~%BXu~^=*5KExWl`mphIvuF<>IcBa~wco+yH z`h6f@G(8oYWj}O`l)>YrHL#;;?`jND^Iq_I`XsX5-T1ewfbMVe=$lD1HZCnYJJ;v* zXjIY*($(KyL&MooTlj%6AGe+yDpN7$=gTE1ax1?;r96Xas&5CEnbGRt-pUe|=Y);^ z^WOC7a}wbSx6_KZt5f(4tpz!EEdS2C$C8=#j@z}y%bB9&4?L^+mER}SJ>ySMi*)X4 z=Ta7xJ=DYy!-3Tw>=BqpOzU#vwek*dn;(tFwg6VABQ_(+*-GVXVguicP|O?d_g|^i zgnkUtvG3fu;`7fsP2faV3X;P)W&%Y#OC}XJv_7OBwlj6|p3FSi>b654oFX`8p`6B} zDVxCL0o=j+EIlJ&*Zy+h9-Dkb%;PjzlJyYIt)8Fl~u6q-TM;dME3IFWUH zxsz@u)7qT0JcKp!2t-i4sTTGA;Jw*gBkO(0G(ao~et}u~KzDfR1_!Kt9}~xh+}}yH zFg+>&OPe`%h8ZampkD>6 zxGYYR$B(wP)FdvGo8#r5)XQxd0kAnS_OgN$Z+Z{I33dC~R^W|boxN%2Qg<*V`BG7| zl|`qQo*7xx&UPV6=J7eXX8(l5O4#Q;|Hd1wML_qKn{Naj zlyi-I*3VQi*YEdsnW8(ck9tWa+FhWt4aFv)2>{oAt*^Mw6gM3YsO(13mx(IRz2|iz zq3iKlcOx9*)`;%+c{oG4IU4|b`ThFjEY{-L-W1sNgg-|Tho%0I%W|}&@7J$$+gEu1 zCUmGhg?yy{BrD!u74;qhrY|tLOl>WPRV*6uS(?wFa*e;7-{Q?PU6q3|qP?sf4B1G& z9H*qeV_I==vE~N_t)BJJE89kP*RRD?0Rta}?#x-sIHQr%3;XFxouuffQWX8{$={8T z0bM&gJ(Yp)uH)`!xxx*?ZsAuykq7_%V9vanUrT;) z=gUU*K9$h4V0YPB18gbZn_WpG-afO{8ImQCNADC#TkDc_zIaoq&Y*YsrTQJ=`qSm{ zdm~;6IFOjEo9SK(4C(7c%h^@u(Wu)GV?K1746oj;YWc!ix$nM}njY@QwZV2U^DmQI zXUM)p=R@2nwj7`OIB*^~-od2_I@}ktmb*q~u2d|w3~F*uuK_cf&L}F^Wl<>-(fBvTt5$AZ-EK|2^6)> zA{Y-QUWja){z?p%Yqn#&ys&@uIZUYC*U0pSQh;!7zHfb@ZfN>qe!y7-P|X|}ot5+F zW>Wlt6_%w`7sc}Y###D(uFhl!H_ugJ<)h2iPWCZuI>Blp8QzyYi#$0@PVhTWjCm;S zk(GNtU8YuEiJYj7g#~Zqj!diDaoyn|vQNeBTUEH&*jS(;`ff*Z0c+LSPWPA&w=ktC zxY(s4BYjWo66&X((o1~VaT`9bSeIGS`=?V*u1;^=_Le_O)y10vqBff2IPRSLZ%ekayFP{E<-<$sCTV;1;GE69QNK4$+%UoDe zL5Frg7}f%--X5p;&L1^SJ2Lle**HSDh+kMb(Vn@Qy<0aX(5Eol zSzK2l2YLn`?O?=@=UJ=*6j=3B1Z< z3J6gVA>b0Q&nfd!St4=JP*T zfUfNkF8|OxI}h7_w~1CR@S*p5K;&Tfl9(b{Uv@JJ1v$tMQ4v-1L+HOgm!7k-+LGt< zyv6LS`>~hDWPMEOa)NwT`0f2Tv?V$fe64^~_)}XCWz_pjZ2An0Gp^bxF8Sv#S~GQs{723?u>qj1Zp^Y(}h++ z5T6A-`;&iM+nH;1CLJa8r`*euA9`7KdvxV>^8EA~qvh;$oO(?1m6JbayZ$-%pk(Z^ zJG%ZYe8BmK-C|Y2%hR0n&6>xc@~O{5r}A6pra-$KJpPYw*RQE&sz_QViuDECpwTzhp#@RQt6h@2H^6mRo_QS-)<+xfe7x25UI?HPgt&L9(6j#Gj>%Ke- zWuiFr315+F$Z!=3GFV?i>pfmO&n25FxUEvL?#ojx2ZD)g?H?Ya?Ra^L)r0+&*B-7i zBxz%D;6OCZ8|qkqeFGJ+Evpn=Cjsh7S@^B-T)gP7)}E~$$=_FmpBx`VE5o#k<5vwu zoQgf)S@ZvfMnW;=TW?kcx|3z`^9VC%#{9I|#lqmN@DSnzQbRpTRvAO9>_ z?yOY1p1%B@ujhh!m}s}u1SOR(a(Khk`L6Ug`LA^#WW1_pnQ?b3Wgqc+-oB-lY14f) zdI>cYLJb(ju8GMoRTf}zF3|VCkHwz?;?#XAe#oS4D5Mr$4T*TDr3!JB{QxpeGaY!2%miWmg4 zn{Mxfe|p`raKEDb*tVKe&qmFM2D7RpL51N;TRS~GXDTu4guq-RYsyqUk6idWIlQi{ z&X8+l1?AB0M~7At;d0QcxM9CZqPgn1yY^nzwEP*!*ZDDNnf@~;d9 zF~&A9_6i9wA=BNSmrY$sZ#(~6Z!<*&fY~4?)4MxBBmV>LcuZL&9 zGdh7le^%N&^Pa1BX9gqE!QiEfPjB(; z?nrl^*su~mbD7JjaM^o6fpIX!FOMc6l+iYA(rav5{>62QQhFQ}`8w;*4JEH}Xhb0D zP$^ULs-{Ess!`OF^l6*--Z05ami&kePqWd3oZY?}dcbi|Mm50{1oOS+i{b9Cm(My; zsJ=cm=gAoPI7Aj(o)HJmw-!jR-mQpfrWf6MBX#vhw)25B2i zv8c!ZI;mqunfRC6>l-Fa##{5NV$|YD>vyVK$>--%5;LuO*o4<>cVn)Z_h2&^eWoXP zl5z|TD$oOylQdSZrX(D;J?`JE7p*OUZ9?>#%zM+;uEG}FHmV|9 zd2eiyW+Bb;;kw#!eMO>gl1dnwRhWlYG$2?%)Q)(Rts`EwRzE&n$hT&KKpTAZn+RU} z;iNvTusR6ohsi%7AW2supXDLUwU=k}U-H*Qq|4qV_1XR#Eo08DZs)60fSo>B`YLZU z()na_tnCLSLs3#F&-m$`#fUH_z;?LM?jzePg(|51GA8MG3e{8(SD9l}LJ~zxUBYZ; zz8;BIBW>Dp(pv+2+@%fRAT>ioVH_C7FT|I z?Y20Y(DQBI} z+PTtnu=yeP6gQDbx7;(?E6L5=a&SQ_GPp7<>|q1m?W{)bWll_2|;`^prvkISJj^QowRgcW+(4wN*X+7X;mBdn?C;86%w8 z#nt1BVkp~MwxI?`nX1T)Po4aw?)6g003q4cuTf85;{k0hu4pTt5x%OLkt`w&A_R+t zQ~zaoxl@(aF>n2Bx?vs#QfJa9104wdm^M{M;b;m+eNAKc?_@!O#AfraWPH;a^-WGty|r9yX>kt zxy%Y&BIg5FCyxjFeBo-$XbYZ$8u{zxya%C|JC(7)Ucz76AGM-=U!v<8m0YO*vv32v z8h}fQCg(5FfDqAx)M?7!#+wQ!_5*W7;I&LM`K(hG`YhQGuD&-^6A4~GeKVH~jahbx z8FfEAnG5&qwQ9|m%~|$bbDsMA{o?siWRGck?-Q)4)g%yl`ciXU>Dq4u0%acy)L9x9 zw=`IBc|KmY+pW#W>C>}Q2N-FsFSzVG+C3$}_rDgDBH%W;JPS^LzcpAPs7QWB@P8Z9 zzkx(hb{{^d+D4J^0bB)Pvi*iN>=x6X*1Lf{r4ak#n9M*7bIHi&y z!^9))w1ZK4qYv}A)BWr=gyqT^sZ5472eW-CJAZzJGX%uO~hnQL=S@x}Hsd!EVD;HDv82d9#ijm3{ z892T792eU1cwBARhAeJEP4k6_jvDxI1N&o^e-4c^BpWal5Z28|tqXeg-A842tO#Y$ z&3anQWPB%W&}`j&PU`0qU8pq~@q`(Ek42lw~M{8 zSIad8EQ`Ad&Q!Wzbz4IycH}vO-r}hR0dhkl=4MIIDMKaLmQCkOY_BQHcr$+jl5tsD z3Fxo5T8Ao4KY-%jCNw}b&un2pOk60A<1@Ww$BG$$3&Mg+DM5J%E1?s zqCtNK7@=t*N>oQRJYB{^-l8mvCO2VwUemqCW=S~d4EH*8cmX&y!`BSe^OobWc@!U5 zan*|=343MyGXMw6;rLLRv}?a|d_n6mZe3nQ&Q>zLh7|_tuDD78Yp|IekN9O03kZ}` z`eJ<#t8V*fIp&<79?V@asO9KyvsyE5i18z@&@XW@iS1@lSIC;1asN4X_R!TgUL(^0 zZ6p!yt?YNh&4B}kO>&!eCN&z3wyT807C-lm(JAxW$hr+!@%ZTo8Sh5KF6Vz^&CI4$ zq40waY~- z=5qh~f%qCp`IQ$^Wdvo}cmGF1<)nW#@s&l(@sKjURw;fJhL+ASJ4Kfq|NO*Nr~Oj& zoLWe%YXI0>cq{*AG}$HtzS}#%J2$5!1=N5a`yM}6E%o*=Wpc`9j%*&s_-wq?Alef( z=Ow*)6xz3;2hIwi46{(QMi){DMV~#|JYEd@j z$Qjx+!v9H{X~MYKX+MuDvG7>sIJk-)f5m?CQZuk@0R?ydEGt#mXbVr2(gSLV7S(#! z+^;#Z-U2@DnEj0pxgq9vy!*@a-Q@O2&-UoD2|;8&wk$6FZK(^uB1S<1BjV;E>%GEc z^0i)!8+t1KkVxbN5_U`sa@YJZ6F>R;#apJa=r?*l8OR8>=|r1UzY_npGmZAtmm=dj+$rb@(UeKt>F-v{L1BdfQwi z|8>g0*=)%K5Gqz!OsgjT(yjo4f{%!46~cf=5C!K4zy{1rOcL7z^{iBKi|n~`mGwRx zSo*CyEdpi+k~UO_vR67_E5L&%jeIJeVF{NEBb4d?_5Vd$+?C8?Haq?g?&81DiQDAF ze;2j~ZNd62PKW0JxfPQxaPk(^H}IcNUmtLiHnvyB8S_7gj8gLdVli}Ptk*ldw+AAJ zhK2xS!aKxVmy@NMni>F*+h7Gj@&iyW0KdOZixVvmkEUV*kW*7rlW-ssB^8xg!{&d> z=O&ipC?dX&+N>)DE-1I#H|wNx+T5QFl5$xu*!QAyt+*`P1R`TbMMV`Q=(V}A0`x*# z{Q!-b9-<$w^U*8-u>cAMPJ~ea0++|Xy_nGX%4MK9U7mlsS!ci51JU>Oetx`*7Q8%micnA>_p(oTZlyC?4;* zm;LQiHwOz#VY?aAwtdg*xHnoTojjh-We0#gcWng!iSNzNQ=%?FU~>suz5kOvb6B2C z8apiog&_dTl#+TGO>wac+T99RtP1+I8~`ms10%N-1kDZWy!_>#gl<pYwH@Ki3O=(gxc;_2I~)kqWjM*6jdK zX9eo80|9S7`!yiQ=+>GJI8|{4#2ufM)M(fr23}8Vcup7BhAh!DLi;w06pf069{(J( z8V&UI_Y2&tI3^}>{7cP$+X44axs|)`p4&~w(j-Z}Rg!iu_T}W7ilGbSoyYgNB8IFW zdn5JRbqNRwmtCio%>GF7IO_nFY}(}**SgAAQy{(L*l(}9A9aguK+(uls~%f_po#Cp z;r#SF9EjI$&U-O2wA(!z$WTaqA015g{)w047aqMDyZNM_($SgQ);84TXwrP`0?ZNd z?DPOhMFzL*3%<6|#>WYV1J%7=YV>oL?_OVC(T11~Ncx=jIQH^7o6j~mAY@PMU)&LL zSYF=kXRCkn|JPr{2lJQzpAs?ROy3_%=W(lx?k;-Ov z?a?VSURc7^Zu|H zAVC|5CeSfKH2x``13y zI?(@Bl{XL21;kNGt5s;6brq0{K0N6H?lMpccM`@yjqkZAxKghj*xLP5N=i!A3KOVg zou~i1tR)~~OcKzAnn33{^nKh_$BHmIpROH;G^rdv8AT`!gV+YdC={qZ1`+r%jD+Qx zBQg#U06d%UAfz|>C`K~=QgQD`=aK*_HO2T{tl5o-D2(+gGfyEX<&)IW5MiW5l1cUsHXR2})lQfVUuc z9rsC*s(d#NuZW8f)V1$y6k(z{AVyEI@X$FnrsWDby7Wttq1-c)h}TpjFbZ2uaz8)N zM}T>#8H)8;vV9LyAS3)b_m;eGR)T>z;?d;QFS3Op|Eh2r5fqK*%Gj=KyTu{jXj~cg zuM)z?rD9lL&P*h`!{RWJx_-d82WCHt?}o*A$mLXTeF=ZJ7C`C$DsD(l;e^_KTCz~) zJ;Iy(QWRsl5#CBQwJ%8cczFE;&ZZ`&g~j9|N3#}xzPPk}W@F1BjHE&NRHkP0t^3f) zv`C*S#R9EJrd3+$U@@MW*Y(Jpo$y5S{YY|0;ofwU_+Uv%h-oAdccvV8xpL0(bvF<- z&&hOgi-jK^O6GWL;16?XsxBJTnrKi}&rCIFp>Gth!n->PB`@0hVy z^73E&{RmJ;L!4ovr4(<`MF?KO43QF8yHJ!3x>73ssdmre=tLktXX$#H$KpQI94Dn2=GWx# zpXmf^JZN?EV78# zc{v7Mc{#BrufI=ypTKP})X7)Fg%V&D&>{3J)^Yz~9<1k96mPbj(s>yp*A{@6dKLRk z<-;_ISgA-1Oy^qt)lcr$fFQC}OCtE;=7z91+b@0~_#1N3oM&e9;X;aJC*)@oiq%4? z44@9E(n7y{56i>mc=PI&1`uw@X!hhcpS31R{J{aQ-cTWpVC$F-i)AVNcWlLofaUE* zv%>Fad2)8H9>&8=y4>q!;*RZlr%nJ!(h1%kwq?>fgM)7xTCGh@Pan=&ge@*(|Kt1> zxL31P4v1X9Tl)UJkk^HY@I}&^;ICRgQL(c0KG2u-3`ynu4tEhb#8Ax1gH0spa~O!GFk$L=@Xeg{Pr4)BKx`yL%Z?*#sdL(}3JB4x zPDu}e5#S2K2Nu2G@ZNyX2)YqLpB9TT4&NgLv517wz3KTv+e?7J@{N`}NbwhIEFSGX zKG36#(x^%YVilpG_*HyOP@)Jy1DXLYm1TVbs{zAqwH|Na6xIi*JP{eozy+k7_p@kM z7zuG+SNpKSq@yEL%03a(1Vl*Kk1Ar{U7_?I)54yl=RGJ!cZjB#DXau1A=8#=ae{|{ z;q0xlJr;%!C9~r&DAa}vhsvURga84N0Ob`K{FJ#^8O?`e=~$D>@ti43T=BS1p>z=_ zC`O9qb9bMl&fQHkr$hSa*}j#IZN_+aH1RgDl85bFG-cN2Eu6?jtA8fARKx~Iyiq|Y z-DK#yLOKpToYPC;ryu*eUWw#Q)Tbz=ON71>oLeW zr_Hn%vWa4N*IO2KN2q2ENK$=3t2Z10$7I=`jqTlB)UlkLM_f_ZUci0d>kBWE< z1Y@S+*HX2}iop1w_{mwN?3cBdV75fQzYa|7Nju4e!(?vPAOamJ9|A@1%fcE+QCfsv z!S(uwr{vKbO=c*S{XsK&143l`h9@2irzmb}i4y9cM-xVdl9!|U6i-1Pp@gJ?h4@oZ z0#7rE|3mfEC)nx}8;G0OB~mRIBppZ5EMObGY>ZK?a_+GT`t80e?L8eAW3%hX*{jY!`wcJtUO7Qd@NsvO-w~_ZKyL|Nejyuo= zcjXcHieW*<$t{zzy0+~r3SUOmo+A(@mLH&rwG`yTSRlhVMYFH+(pUFh05ScNbNdHL z3DdBdL-y3G2Fw1Cyp-MFg~fW;9{ef7VwD7ya;J@EQdzjeIS#$|Q5BaFv$$f9(f6`i z&c|z&$if=2I!J+Va18jWD#o0i2PI zmFe@o7xVKC>e38Ipf&G)2(x~)EqsNIQC zg;AysdDRpIB2cD|FcBb(F))Ux8VbY+0|o$$5v7bOK!Gt}vcd#`K%o0FpnwpgOpSB{ z05GPCC1q4SgmOLeV?rcJA_B?RyVa)-0MHwZ#4EU6GNqs>j4G4?#Rw~uB8-_NQARNZ zsz#LpIRb#JC?7Mr}OmXCA?4JK6O z2t8=kmCnL!>CU+#sB~xlrG`NZk?vp>p4Y>co;-yvPw58ae@@Ph5&$resT`1QS*O)y zWo4>!T47N!KCjDW&+vF%dc8g(B9aj7bh~VsX+ED1Gq6NNYBXA}%OU$R7=yZXVqFfK zEi)4lAv`?F>99Fnp6jk_hY_N($7nFf3Kd1c?Q%v&Mn@#HP^j#%WtlX=KOl_>LBOb@ z$^!!gjQMYl|EPTZkXv4U?NxQ(fJ#>KU%qine&*$eAKd@-+I7>OoOUqjfT5*6J5;0& zH8Dc|z7-Hh^@tj|@Q+n?1fq$rB|IN&b}^XoBX zRMinRL4=SfifRD?a^z5!6@df^SWIQ$?FxhTD{Roh~Ul2P-MlZ(-MQ;=W#0vMVJ_j=5y!HN;0iizdi;;sidxH zAcT0l9+Sypj4?@)&+Bn(1pyE;S|i}-;Zm2a2n0!z4jee}_FJ=b=%=dM@i89{-z!gk zX5*4~=KOc`C_<=v@7oYUl=^MM3St4dlw}z-z!*Xd03!f(@XHjLQJ}kiU0-%%y7d~0 z2?0d>v+D>1g#8f^geYT#5Owwv00c~EAd;en;ngWkN`Wzkv43emb{GO<%oqY7CTnH}NFbC_#t5ZUjSUe(vM*Qv zD+q!*z04RRL;#>f5G0?XF55v!@PU^qKrsb?Bl~}A)xNh{E`$&$3;>So{~Z9@cN^HI zL!U$Ywp}=V=(?yr3Z()OWx?Zdxg(=uT^_GS?|+yS5U^~2fc?fJzrPH6?`BWK5&!_8 z{*wYL9fE{K{AY$vPW%ytKHe;+buPIdPD(ut^$$RbGu*!lAu#SKJiB6NO$(-+Gw8{6 zuwc_n88TVJOlGUYZntM-$Uc|k^~sb;9$!>cM7TNZ z{UvVzKwNyID1$aR`Jzsv6%eynOjc`{&*zJatM7KZU2YFTII4DhT1IN{`VufOCSVO? zG&A+`^_@CeES5K3dvNPoNAUBjj$glZ47hW`$}je`Z`Wq`-XqqC=)AfO2vMp40|tmn zvcwog$Uk5O$R46FLWrU$z$jCnumC_|2w?<3DFcK77zRW!#ux*_etkh8V4_eO&~3n& zV1(7MKEZ@hHCW>hnq!0sAp{f3SfF=dRdx^pj4%LVjA^xc28vJeVS)is_3=Pm^8LidbCIA4G0RoT5Z8lp(fyk0Vu)r|&y1kTY z2@;q9K8M3>GAlqut;Xl|%958#J`{MWM2M-2HIV=5B`DeVnmUonP@bDA=y0$Ui(m44 zfe@|_x@596l#6t$SBG$lztUKtwdXggz#qlt9Yi_{rl0Fb@RWn;cA=T(mF}W{51x9V z6&_5w2_}Mo6{@)0Zb6o@s4*E#TD{KUa4515K(Jb^ilQiroRMYMikLBEFq!oRliTHV z*=@4qk$tklnCz3aVHS%~4+!ty|CimK6&4Wfi<)dwi>H(-p_ zmxT;Qlh^B2Cpdv^yi!zPqB|rRF7FY1 zNuD1{Mv)6oSiaNBJ>Mb-jL-5OEbvGZidm@mmm`Y2ykyrh#+WFIm?@GZApnEXBr^yL z3)5<~Sy@>wTb3va)-bC^qp>^EGcz+7Mp}WGtYJF6!R7Wi9S)z@rPGR{&L99&WM++s zdUxSG0O-`E8@ZC~aM(|P2D8~>Fj=mor35t&BMb;p zMiHR%r;qL4`RjyxhfN%Prqq>Fq1-q6>?044S+exY1`QfoBck)^Hl+*`0#soXWXb3A z%6=uy*3z7LAOyfhrj@8dG*V2ByXf zSH+xRKl0C^=N{1KJ2$@;s{XMk>CSGZLJi1Hs+6uz{dE4ot&Rrl{}x_=7kB0r$s5k!n${ zKon(Iz@WYWo4AR@*X1Fhb`06bo|Kro|<&*#->eX@*VqN8P5LI|mQddRYZ1<_zMA&i}Fmn_S; zkhcNKj&SwQrnYUJ?;JmSvwtqeK3&G|S$S0sz#lUI3teqo)4& zMS+_?`@TU)2&@WJ`=h$j8y)}m(EoO9?Ad3iD2j|S03hmq1dy|`6aXYi3cTf{zO4!v z696VtsxCZX{^gqLJD=)M9{~U%f`7dF@g zJRzu|88x;NSeQfA1u|;bg%AN_njKV9rworc@6dIiTGFJ0zvfh9uAqj^o@FvyL{Y>dl4Z%~^s0S!7i7j)D`gPoxIw(Q14MO@-PGuxkKQ}$4cx^guHc`03x83l$GIa3lvi6+bS z->U(CE2x`vWcOR@!v~k9q?N#^TVei^U8hbRfB4~tHg4K(G)IHlC6F4?MT`LgfilJJP+ZQ8 zVs#sGW@&T47*jw379t{R34)-m6j!?+1l|ZxUl34ag$P7l2djoeP(a%mV+0e%!2f2a zq99DN2QQeAY+r$~U^H43S;54w+v>V{j4>vdDpZ}qMF=Qmh!AzSO&C-BYkB;I5eQKz zQy1xAgaIRl5M}D?460TO0HB_LFeZ#Clp+9x!R2!5^+qHJ7-3)xBO(ZhDpXb^m&1Vo zOy)3*kSxm#6G|BXlYL&$>#;yQZjVOPNU{W=AWR6>Xti3G%V8FET8$n9QoL>-5ww;_ zb!HkN6xeW}0C|S+>fd>FJ6A*IxXB~0B{;D4Qcm@Uq}##HD|lfjD_=?_-RjahS(Xt~WZ7pl7=ef;jn3=wIBa%Vmd$39 z&*zh6+2e6(w8UgG5e;&=Bt~ggR)*wu=?x~MIa2cZOju-qWy#AJO-)I0IUP=?Q=`>4 zN@y->G_vG#dpsC}BukiJSyuFVgU%Y^^Lnpbx~Rd0G-%+-9Q;99dd2P8mz8#C*Y8)` zz5!pa{kB<)X1f1#_vYc29MzrRSt6IaysfHKyLO3v6Oxbs_vd!ANH%8Vaofl}o@p=L z!$5l)@OT>A)6)jyp>4C;U}J;F>-h7y?Vd5cZMGnA-B?y{7{>nc;MuZ-+Ya1#Bt9ywRUCj#6d^!SoQloszFeNCIxuZ*8branzdU?1@MvoW_@+O;z#jc}=HQ{0<<1 zgtdwjVPawmdP*dspbT)czEEK9`TIcTkm<0NWz zhS|WDr9ma;PIqBPu4}rOpLy-Sc=BsgFTebXJ^L=H3>Cxt1%QZ*8dRO$hQn#F@(>q{ zJW)ZbNLqdmO{r)EN0veLQ&tjBQfw406fGCQ5Bo{=km<~_`M!^tP#v8T- zEvPX@)d$K&@Jl{63d#&3!pMrFNHM+`W4ue0k1Gs8;pnH3rcHzo4dYZj=R)3=Q$)UW z=f|G+f}1^k6HMi+SY_UF2LK-U>YV^^?F+wOM69(<$EdygFMs^_L-%~{_UFCeW>xo` z>t6chyFYRGl4l%w~6nQ5?r<9L24c*#2OBVeukVP2+YL{0SR( zrP1VEO%IKGGYZWMK$WD%TXDD*1u$K$ilHL&bsst0Gu`{qgqo@EQs7Pc?WN0`T z6vfIgNdTiLNtgCqG|Yxt=EK2ylEeUzwp#uE(73#}+>4UVo&%Qk zU%mIOU%cy|y!h(3|A)ba8jGDMZ~vvizx%m=`KiDC#yj4@*WGwC2FFS8NJhOG6fMk%63C;Mk;U#-f6=E`KoCv5G6AK6hCcZ*U6#(?ng^e*zl$pUP z5`|?HAR-DPDS#nyY78rQ8Ne@9l$i-g)h}S2H&IbVBxcac&N1-rjOv^V%NjI@$cW;V zzzQIMgx-V6kDIkt8C0}C=sD-+x{KgFz5o!AnH3P#W`ka*-31f*`NALE@Aui5DD83- z8I#1ZDT_Q#+klj$twC=cRG3WMnH%QiaIik_$A_qj7D0`-PAbce@u7zL<)unjy*Yt0 zx|zK?{>-cH}`S-3q(s{u4P zh*7nj>GX`Eo=8%|Y&gxctSr~_I0iH(isu)X@*-DTWZ57|V^xilq~GruDF^EV6SWri z>_@_~C|p^bK6wfd5)-ZDgUCd?cJI3UiYwRF*0NlXsU5e}Ste%U$e7Z)VNncE93jGm zg{76%)lK^7mou6l4hAS8Gs76$h_$#g5t9VN zffeyM?qH#Tdx1&^^P-O;VnY=@;$+kb{@qJLA`7exTLO(jh$7w_3PYSPRaGJn&UH5w ztC+NeEGoevRI$0(#1L)_Lj+%_VhPkXEPIj_tX=~XUFC;{atpr9K;Zz;P`j*UOsGg){yq8`b zU8zMkV@tPeYKyzF!#AuByC&EsX)QA)X$pYDL0?74P!z>PY^~U$aLxi^ zlBUK)-bC7oAfPxm6z5m#d-ojx;v`7{(XbT}s)q;>2=i=E76l?IpoyZ|Q)kBuJ;}AH z4?ghOhaP(1wXc26%Be@NDgc1N$V7oqQISzVTxB6CBGiZ>()8j1Kml|L%}r&-)(BgG zO$A;EmR@5gowOWoWBGB01!ka0w82& zaSj1gQGtL|z$uE~fRqRj36T-m^N8NQ{Y!U#?7lDkR{#)o00IyMdPS0PvyOciKNSE( zt+%N`Z%*s4uzCa$Q4xT{@(BR$`P@ehan%soqGUow6Gv_DQtU+8gzzyUh-82m02B#; z5v1BSe#?;o{qn?fF*C*bQ9Bf3KTj2<=B7YEJiRGWbDP}= zb?E>ENPwtNZ=>^$BJa@nwo{m>{+Zcit1r2+sUnOvASA9y!)g?^!NmX|@Z`3gF+`c% zwsWZy_np{3pK%lsv4}XuwAB`M-MP7ig~dEC`u%l9PP=ohP8XF{mroD-tGTu5++t^8 zi76Sb_4BoLTNeJgMZhF&=dPSzoF5E&uE>XLr~9j?ieg9%ahz~4q$pJ#5OdU;o13p4 z11AcB62Qr$55N8GZ~yRz|7zF#u?v(5b*IWdeG#mr4f<5eC#88f_g59Y&H~iit6VAL{K1w zptQvb8S*?+btsB+$VB?LfDJhwiD(%TJ?i^M|o|AW)#XBLTVt zZo$~|x1Gj(i=(5eu1w)JjG&vQww)@v<)%2j!8mjy*51ma`D^RJK%g1h69(Nuw9v>H zte`tiQ&HDyx4YfBqAZ8Qz9J{Bb{wUs*jryM@?l|J+@5Q7=ZWIHH!S;oXUqDM<0LJ_ zcDkJ`8@RH}`>R=R#g;iSL{UuMxkW9g01=s_-RbfM&|R^K;R*Th(MRgI0Z*QccmVL* zzgqmKKYQoj{p}t1-FM$ZANn?cf0Tp7F|s9r@J!XWxWUDYD3GxYW`0GF;od$y7~g~l zR36T;0ux{|2vm`LKwZycxfIh91nIP!C|Zp&lKchR3!2t0xAlU z0xyidr=hQ&uihKw@m$p0w<@=kXFn0C(}8VrUjE6aJd)-ovx6}PXUO{T&rURI_++e4VKrA zBWs)_F5^RoFLt6Qjy!tj=kJZ<=+Ps`=I0j-b2jY9QDjhB@j_XaD(b1u-McR;^UOI} zU0$i}*CvVpigSbY<=4Od_19f{#h?H7lN!u@dDoi6a`?)(Gc-!0Fv1{+8#G^Zf zl`$=1h{L%}^MP8P^6wc{%KXZuRO`1=Lq^oG2o(cJjNY9p%lc_LS6`jaLBM20b!GWXyE_*}Eo36(cB@_H!@*$Co-3IM z5ZmqU+Ug2|ssNiPO;RFe;%aFGuFOml1Na3&y?C1ax&|h!A^%ln@@^vH4BUpzpu2I# zvq8MNy{Rq)>`|Dq`tW-4P0un5y3Z27o+zJ`4WN62FHc_Rp1DH9sbBq?&snP~PKs8m z3rq{0y;+v6_tuKMpKuHW5mTOJ0!qZ~_PhYL(pFhyYs;sQA&MeV+Pin36Fu|ziGO_P z-Y7CB9zWUXbeX8gv&a}mO`>j5l%m4Q0JyNQXv@Mm>8-7cn|*(qmLd0?ICk~(pZDaC z8}Q6apLzei-`w}yi!j6^AIHg2I9{lP%yfZn_>tRsjB5LBhgwS)*jOyV4QchL&`5Q9lhV*n5tz2J?( z$4c`eYe&JbMJf{@?{n&V;@z#pxw0&xIPvePRu@r4fppfE%n|r#jB#8Rc~KM!n5G>- zAY$*$iXoZ-Q>C5_zGMUd;@8p`?#+gPH8KX7QKms;BiouyFueYAR#NMRAReB&>O;f8 zX`2vM{nzHcvqG~cMEr)TtFtwi{@*!*@Fe{2K-r>^*(_LnFGlmc`dPs`tDr1MQ3MKc z+{&_{wFMy<Ev5{1))ev`PpHD3$uKViZOSMNqG#7|Xs;t5Stf z{f0hb+En^hda~kp-2x8&G;62(zqk4 zs_H-m5jyQoZ@t%FSv~pKk>xWdopXEkUSc{O>ttnRB`*qQURv5^k~l90j~{<@W#!cT ze0Sgei$CyN@3PkY!SB4|kKg~!I5wADdinlChxZ>ioOI?)+UYFq<~X%hRJAAyZsMD!iciQPK6I^A?|*X@y!9iY3ZkG;xd}m2D5>R_G5kgt zfjkpADbYTwxh4+Q)@T&kISN!9(5!aAtE7r(cJ|VtFp%f32UaAY~nV6 zmNxgXb&&k~1_%n`fRGIX00A;mo(=sq)w2mgXw=%$+7dvVbHvPSn2ds|3NfmPU)xAX z9;i_q`!#^5AR!Wo*eV4KR%jCjxuN;On%&rd9-e}3kZIiBK#s4qK(u8cVxhvEkv0N- zBVN$=w)f0rRMm+K6)TNj_!wdYk8+O$qeIndpaO3(b$>Po@DaQ;Fl2`8y&)Gf?Ok%?K8)X!t?$q|m#N8T z##1vnV{6UGs#amSowWdv=fk2X05M5hCXT$>i*qhAk%?m@D$AnCGh1XFaTLcUj#bsE zI1wj~nT;{tM@bQp4PuBWQmyXM=T=bF)z#It)m0)+(gY?=p?9oYsCIX-yz9+_x4ijh zf9~ggZsp8z=bR@ps$|TeG`Nr8@-xAw=r&5T+O$F8cvZ`xLKQ(#eycJA+YE@T*;K4&z z0Kix7{uKCEMO8tccm2x%fXN)V_)4gJ!J0$lW6eDO#+#pY&G#Z1=E%8HRpU4Y@G9SO zOv6v!>XMtP(Fu`m=K36=ws__V&m)*B*eKJ#&aAf0%9~V}cP(<)k>{($8hM z&Ii1Aq79g^r9>ZnX)D=aqs}z<_`4a!ab%3O77>#qan3HyFDxxC0#H$wg*c9rR(H-Y z4+p)qH$h$Yo(lR`L6*nt&37da805H9;GK#w>6YKEs^v4-y+=03fgr zh_ze|2(_Ul05Xw?cPa+oK2l{b86p&r5AuaRM3?8^k$|Ykht3t=Qm%>QUI1|7gR+Y; z2CD$VDo(`qdu!RC=R@9vepC;th>8j`A%e5kizxu$#5rdXu+{0taf+nbpsyeZWUV8l zC{B=#6IYal6UR|xOd3TAF^DP>6CyD=>%4oID~90tacT;^eppA+6@=x=v|Ea2VbJ>< zZjRdkFwObS5D{l_x|=+8m2^H^p55fY9W7haDBId_mXp)?HiN;K?L2hW2s}ZcpC5WR zd%VH6oi0t^L{$JWCQ9NM0j;&9u(oo#lO`AK+0*JQ4Xw+ZLz6^t6dB`eS!9DE>y@sI zTIrsB2P2c(%%ZdXwbiWOUs_sv+S8tSfsj0=de_cckVb_{ z-4PyGo!TmeTlGY%)~-q8cQP#g!%@}qJUSOr1%}>nGEg2cQLRG$z;}329K3P4C!<4l z>IUEA%@{+;^UTvF03(hb0K6SdAhkh#MBXqTsHnIi9~MOxM!}b=dlDR*6amD!Jj=p0 zBZxQ!;V3d3F>~pioaTFi!x5pk*-MKOT4{j{JU&f2o@UDp|y zH?~5raB`y5iJu68wwA7@L1|k!u{nlsv`sxV7q;vmjBnwtH5+DUUH`Te7UQKFv}uaw z9LfYiHcNT29kG1sGHUV57-NV%bhxrqDdy(7bKM0eP&%;!Nvp%gFw?N#vt^#;eJ3vM zbknrM6uI2mA}@wRQ0;U&`wtwNUs#%(Tj;2xs z(&9z?E<#X3U0>NOlH>W5Et&i8e5tjm*I$3#qsNZz*>^DjIOnXjp0MywYE5=b@F{2* z>b*fY9_20ab+qQ*eG3&W_LQeR_nTk8*JmbTq^6tF7>Qn;9V^Ei5wW)PhUgW|2H|rR zrq`!E0zd+sU{dNd-p)B@_B4$L_xhw?`0U?Y`@$ap@GedWP+zjvIkJh&Xvu+a;LsJ1 z9ewcLyFPy1i@v|Gf`F<5sC5UR5hDhC080Wbl?(%bF|md$AynoTefuiVZrrx zJI{<)d~B!Y_Nw6qpP!hrfuh2f>5)6zwns6lObG-Jn(k;wkF9DSd< zG#`w~S*I!rGB-bmQM8!sD~obC=&!Avj!k=hZm!j8MT6x&S4eI&;de(wWdX*GiIzjUjm7Z@t}D{=pym=MOyiV7uMHkNwTnPq|`t z|5YA-@cvtFx#bss{Q^uBximZv8fb22Vq=h5 zy~4Coiq`NxjoTri1^|F}_9sLTuLG$94OB%dG95(%)*~V^s;Y=MXPFHmY6yisdIA;v zWR0St;!`gvNazyQ2K#Z+$=N61fmC%(AnUkc20JhAnv!WsvVm1QMotvWp z5gG+>)&WS`ZULfm;%s4}#9B+t0D{OwRAzmY!f+xAwdgy8A(^!sYsb*-6xvyU#j$@+ zblE;`pM4LXaOmD@uEb5gZNB#$%cjr`NC4!VQ&0fublPalT(rwtn`gs*f7Ni>ZMTy& z$+KaWXCju+wA=ITZr3`yvbr|xtrDn+EX*&G;WKAWb-P`#w6eBBh=4?d;#?BPhKzs~ zW#$C>{Wa^{k)uaXoji_$mt1;igWf9wl%ltN`HO#b_vgQhqOddb58m(t$iXfGD)0sc zKx8Ij4qFU{&N((5!sRN|Ig)e~ zS_FV9qjf-^_D*3mxe$_sjCCO*m_o2QDT>UwqSc=B#??W|>NWb^ zB{FfaNe>>h62>ItVr6SfDGN<3afC!F}gF?ui3RVBc3)X)cqYm4ay#X$$mj62fUTiIdS3irYh>Ms_l89&$rA0AxcHo>PGOcdMS*wD>;m{Zs(QaoE35&8A4tnA& zfFyCs#yF8Y&(bt0^0KrJ5q*YxRW*hQNdc@aMPNAWA<^>k@}Sofk=?tO27R}-wzh+p z-z?t+bPUwm)K|UgSAYFoL7Pg*%p`S)lMx{@L6;y>MIr=Fq-muxVF)uKaZqbM@*h6+ zp_hFBk3$`KtEy8wE7d#e3PeD;9%&F6nsg5U={Nz~{Ax53EImamgZk()iY(L_RX=7%oLd|Scd8A(6sD)WSo&WT5 zUI7B8S>#Rnza5dgUI1^4i#iV>{_GW}^$S=%t5Xe}Hysp8l__D<-XH*gb5c5+#FXbb zI!R2@>#dhX7DcIvB2ZmhIpee4x7%H2{>^v2b-Jn7zTw}mFE690K_ZdC`WikN+SPSL#)e({t z=R~T>RcZyVE%E{4oJonK#sm?qf-a1Di-10ntH*5-De|mkn21VIAF%+T%8|!LUCGSO zmbNH}V^l&ULUyQzBSM4VDu-4;AW(^-#OrI35EP;)K_n3i5Ym5$bCsY1uFT8fK)Hxp za{%OBL1&d29Qrn%h=#}bhE?h;dmAnEXY1OwbM{Tkx#P_&+&-_b2i=tj@q{dw za68Zq001It#YF~-qCh7R$AiJZmbnjX2cZ4+HUCniY1=xDk~qtTwk)##niJ~?TkUR? zChKeKDBz(x8}!LA3aUsFbKDB+-m)mZ_N}jFS!S&*igK{Jdg*0XYy{m!p2bn}@kbu~ zE{ekb_V*pR?Y6&u+uPsvM}PB&SKf3*0Br=UBjDDg_(rr#KS_3?c ztT(C#n@wqRR7cp0Kt#@2@*!QYVu|W50o3eCKzJQ{r+gtKQ8z{$h4ZMh);Y(-*mwlB zy6jr4f(o2RP8q7smJ|~ri3*1NOLc%j^s5FCan>Rk^phI--Hbq}qZiD#$!tVwTOI!f zl0s$msi3G@<yx!IrUf;E|B5S{s7!GGCexGgG7K}d; zCz-5YA9LX(aM&J_SKUG9Lf&L+ZDdSQ=0#C}N|K~bRIDws%oxMWY$9-?ptdY+kvmtY zDiKFXf<)`f%Z88u#adBCB992hknv%jK%KM49(yd$b5OO;iFFGL3#v+l^9zeRHvnVh zyM&GzX;c5F{TDxjD!$C;6s@@xsHOoQMa3VRB(bebxUsTntf`g;r!evwB_a`E9(O5% zVBS*mKHg>oDyxg8W#08&*(a?TlJM69X+Ff)hX z!2m?2EDIu^zB;@X2M%8i>K;4#;60za{dq5VDS#njL=1s=E8`$U1Y%QP0sd%d;!Hk^3u zNNaA_{H}#GiF&J#_tsaFC~n6|(rLf*ZNEI-?7#i_w-}D?%1RnVQJR1)#oC3%C2O6k z7^V;Y#UIs`uej>zPkYLh2mAdaj~%`0>MQo{-Pdln$)qzoY=^xcyY)36`rx16a?|ka zhiL2akxz_qF*{gpxheb52mk!mTW|f%_xvs_?g?r}^a*wZk)k+KRUZg5;I_($cG(EG zK`HnTkw@&H1Pm-sP*^fE0QoFkp|$FPGbR$1qRb-&PzA;+YP#2l2meh%bmCOiRB(-i zBq6dR5~~v@LWs5c7*$nWnGFVP+U;&|t3p)teo0a%u?7H+VsTbPk;un}?DbZixbFNS zDEP}1A3$BW)1A+BkLSO;NBuShW)}pF)))*7Tsfr*ffhwRl zAs-c5B=pHR+rcS1?E$H6*jMLD)&Ccyqsi3G%pM+z_;^gAh>IdvjwFLV~VNn{4SGlPCFHW4v)I$Z%RUB140#+Fu8 z3`O1f`MA|G91YgjV`EGbfwSUVw>#&Ys0uTc*-%A_BD?Rt`?5U0?2^OTaCqX>;}>6Y zXxFaYX__L(vpekEnZfb{tIMzZE{wwdj(5M~@|RvlrkYf-vY&wP9C{(vAB7{zyQ)(2 zC)oUq9#^5RSN-!x*UbmZMqeMQV7eZ82uaw9dn&@WMC)KNSmmomUta+cMa8?vDkv&> zR=Pqk66eG}REo7h3#ep+o{8c(NkSx#>Kas4Wkli=v-cwcL{$OREE|ew(rN{>9Y5s} zfdUbei9|$Eiz1JbB#f6IEd-8?6=O`K3f^T234QKf06;nf3N!;Av7x*e`wsvcU}b}e)h(!-$=@zChC`4LX6)R!t*OeRqZ+lg zVb!v|GI74`wly(y8wlas+BdW81n1HqI>QsPjnj{&wy}v)osHwji-ZhP4hMpqv^vHZ zvAJlO4YSx7Ky0U&BYQDp$_-ITn+AmV7{j^koI zGm9&mPlK1&oARQFV3iZZ8@ANA-)!ouU-%>dT>ru!^ujzePJ~tQfqR)fk%Tq5Q_)7@ zqL`!ls_XW@bmu3Yd;QB04K!?XYGO!KQ1zM{Z~EfrK6>QaUq5`=Q}!Rc6o8H&d+46e z-TtiS|Fb$?ud0CJbFY8Ny?5QgYz`j2>e!J7thI=S01eYMH{A5a&wupT!}nc!)ip?@ zY7q%Q%d$+JhSGznktA@Jp|WyN$v1w>kcS zG-(L67*i@V?R&cMR_#83YWsQ&REzR!Ps!!NwW=7kIg?|siN`8}_Dq z?!uq_-n;59U-#ngeeBVP=jXaFzV5~(NqhbNp^L8s!h;7de#fu<(kp-XzngjCtycPq zSG?j4uluoI{@HUFwk^u?3cT?xJKwA?Kl)02>-#?Ows-vL`+nyG0N`mC1+O&pi6M;Y zD7+pv-@*`+AS~7Dmyv@5Qm}jpEJ>ww^*d|1zBam%Du8W`4}>Jn<}!?v7#w?vxt3Eg zNZdd~qT*x}YXAumLP9+z7UzK3Tj(HycPSN>L4Tc%F(zUNcnISjSO_TMe3ywMK(VD& zwf+8DtJPLT!%R$SEvSkr0=Cjlk>}o<$%#WWh``LEib&l~cR0+fvp)U;v$57jaV((5 z7(!!h!EBrrBoc7|K!{~ofI<`}L{!?++R{kmtOaAHqqBt(2v^b2f`%Q{8hZvlR~q(B zAQZ4(oR1&4RT*DY%sgO2dIbQ_#&c?$RnG~!XD(xQf;5>8-A`oM5V{+;dm6f@tXxOX zUH?Rc2v)2W=4gIlAuG$Jz55Wr=H=<-Q-)1vZZVCc;h@*+^{llj&RT~=X}8?NcWnyXvZ|mKJwKaWWhZFWP??5HGrD zU!Ir8PaK_j*-4sw^~|Xk+;GEpV-)u5uf6{9uN~k2to?p}Z5{#u7!spXjhds?H8*)xD7RG23c-qmkO=;0r2*PnTIj_;k^UDzn%rQdMRWah~u~ zL?w#jBr@#8l|>0EYz!OY#N~Nj76k>1F*Q+~v{FKH&e|fg&LI&KDL|a0$Shv*rsAAa zm6g?XK)7h{MXe+)t!uTR)#`TV7Ob^dmi7AUr%s*R(Qz7;^YX$Ffe(KazURMzn|=)5 z_FHiKC*j*i;Py|#yWbE0<`>{;FNU|g6W04X)6q(s`l{aANeWq9!VSbmfhzS%)ItoEvKny|{sx1>Kx=9YKt(J95}Bty`+EW4Qy=_&0KkzeK_gCkgB-=NWf;`S zl7JAW-tg+!=2rhS>gV>MdGt`#J*xvyHTL)qGc!w z+wn=srna+=qj2;lZ~Wz=Ec%1q``+_wzQXI?_!bkzD$bU9lZ)AR$>onc z{4GZ9cG|tQwe|JBIM{#S@Spw3@4e&KehC29S7-C_4?Xy;i!Qq86L;Km#U(pGs_*@M z`1%7o->ff}Ujlc0@{4=+?0Mwd4+hN%R$*TNRn_O(NwlXrqJoh09h|n;n zaT>)*r`0KKIn0LHU?5gI-MLnGj*U@u&X&XV^=y58I9NM*^4P-vIC+`S6OesPb1-{!JJt<65fo4F#UP zZc4%1=^zDo^d(eK6}8!L;N$9shcH~_$dSq$sS~n~g$9VKBF^P`?&S^*G?rA)Gg0vR z2T#@1*MdNZ6h%hCuONVswKB0GBxbJcfD{RR!V>^cANkjn0LWxcfAJ;GiC0cnY77mW zP(!i{qdUUzFiMT((m0|_mT3&1+-6lCI|QKdv}_gZ)+ZYbH?+~%x#8mlD9z@#3c$W? zU?0cvu{Ud`1pY(|;ocrSjA@PA(_1wW%@{1gYKBGxaZa3d;)qZY({`5-`@OYcZ(URc zDNYmXoT?T@p(3D4$ZVokrz6g0*&y%t03dC(I&%wYr>g(}>p&F0c|ObrgJL+$hW+*R zwPTMRdFbJ9EuTKQFxMeK>tt!yMF;j@9LFgk+tRJCuAMr0a&E4BfyVIMtz)tbe(^uT zZ+u|G3WFiM>Fuzx2Jd(i(0S2501a*G`#;8cSpB!|~t znb>FX@Mh?)608x#M*yq+gS<#y8?690Dw$tLulT+@3{7bH#_IoA=of@QBdcv z$CpPQ{MzA5u2LHkSAXRTcU<@4SExEsiyGLg=U)G^d+++VXMDbL=O>?i{ma=f0*K6(svRDZgO@L5o#%Bcpo;YUO5lI_q4z}iHstPlcqfb?)iDzJztJD)&wlleG zSf?>Klhb5nwtGPeHar@(Pn^vzxp>Z8v^1a?JlNTW|KRuDL4$bf(-K7qCOgQ={UnAqnd z47fc)T95yR*%R;p03ZNKL_t*O^F#;kCPXguQnE6$U-5;7ZR4F)Q6NxJBm|W_>lOL1 zyReufogf>425$%?sGO(RusEv#q7w3qK*%!!07ztQ5t$efkqrQQ?R{Acoh_3j6+s^| z#_RGMe7yn!GIhG$esA4~TFq5lueZ8rVjw~$Da+cV9g#Ynxpixafe4*b1Y{;}p-;+b z+AT{<%uH(7KQ`z@jbWd0L%{)nb9Q}g#Vi>_ij!EtIqQ%hPEuyhvRr$sorSil;EXqP zGu#IM4(cdF_Qs`Jh%}1Uc2e6xg|mTfq!1~;arAciUL-&O&V^hglacAL> zorLbNY*w*`4MzqD*Vb0M?at}rCrp~g?YT}jU0qpTSw6`M#zaWWQQS(~wipchgZ}zz zmfIvv;#Rx6Fkco@mich)42e}+7UeL@2EE?e^2({XPKU8;qUf97d~n~seOF!mRO_sD zc6D|6*wIIZc|T2OLo+Je{lIr~6!zD=`ifgFs|=ZIq^;;fK+%v63A}(kGB~XvR|!c* z@16JG89lRJCJt0fU^%KZc9l6yb!gxw0>O=_>W0Jq#mtX(=BkHN>#Cy;dokaW9Mu

SSt>Mt!9Z|p*5nUP zd_zvX;g^9lAPa3CWTDTn8Fe_aL9N!1o{A z8~`xH_=zoCD)ZDDQ9)X@Nq&D7e zUEHXWs*{{@#kq>&FL_c2%9HN)7Wil&N~eMHB<22mxSb=*UmH%GE3wy(2Be>`I5{N{ z5Px+Z90nH(&Xrf$8=`9Lm@#fl$KGNid_C`6dO(h}-;{ym(y}%m=C6Q4ZN}>Oi9d>A z-@iI|qx-S!mj{;+^UxrxQ+;MqXWVY?+AVtsb-BTSn5}6qVB`=P7InB)t%%XyjZP3E z=jLoSYUrrnRn#A6P_ubrLF*(UV16A7_7hk3G!H$Lf9$*KLi7W67QA8sVxCRSi#asF zz&)JtCFr-Dh?Xvzh#4uO!oWIa3?Y}<%qq@F_nTJL$3ux8KM3)+qWle1`{W6K*kuS% zQNF!j`=mcWPDR*PR(F;J#kT$p(R!_IkP(u^$b`nV*R1)Nx34gCq&_CH5JQG`}kr&Dk;rS|^XM_b8 zk`WDmseSH&+DE4^RtDoEv{3DX+GkgfS{GLL^wdjctDBZKM*)VEcrAS1kU;{GJvwif=*jzs%9VG zz#FP$s2;9#BD+4F{CiSTc#=4>`a)*J9>LwE!xMzSFDcA?Ja_Sj3gA!gKK}er1hgXO z-O#)vt4Km}8tXfqFoUyPEl1OiS=8uH8`6Y-h7nnw;Fdwa7L}xq6peVkd}2 zEl^*kR#5RNLae413Jtjk{7Hd%aB8c_iARYgs#Riadh}W>>#zUo&~754cOE8|o|~8S zom4d`t_GPEOf{SY*&}q3ncTf!Cz9!NO`79W5(Jns8X7h>i<{lZT{E!VhfymaD83uz ziua`anl%w#MQ#2;HQ4%L0pAF`T9C+kEgm1+py0Wt;WCwq}A^NK|2A-J-oQ21p50myU5F=^bZ`A| z`@Vl!7H&IY(HEV&txL?6RuHWT6|7FCGfAKG2T?hb+2{78Ma?s0C6ft>Mn$H9)dHP% z8IOoU2@fHVIAP*khN!#4&x^r~qb3E{?5qa3|7}A2aUM1r>*cvfClDMr>?$K-c=sn5 z-P%`3D_Ad{H!6@@2s5vYxDcwG9(8DBaR5X4*n~iCq2&pj?ADE~7Wf7Kqq=Ro3^_F! zP}A#`{|lq!fXHtpKMxN2&K~lGGb@B4QPS~hxQqEsaJe?SF@e_3Lx$P>hD-El7>c6=W)7nY8JbpVj zN$9nSqrr^p=k-^tN;k8mEB11|C}ASGsi3>lN@k5vvB9S^`Geamf28XqlEkzkvy=S4 z;A2MS&KoknQ!^g^h31}zM3oED3UA*D4!Y|QAy{sxrt zpXC@EGpvq@SW;kJb0x(f`+atw*_ma#74Uquy_v+kX_y>IV4~ff5oB$ZD<}4> z!6B?ZQnVCPusRS-5Vkpuh|R4z>Jc1zR#y*M8|}hE?(R4#8rq|yL6w7M6pm>J2^&`| z7ry>pBgWw?o}N|&5aLrl3zf@A#*fDDT^wQ;Y^Pw7TqqCUI<0~H1?=uhKh5I99|I6V z1_Rx~YOFt>7?KCe>Va0tyEND5x~IdrkyMY8pf)x>DF(j=^3;WX6MJQd=+6A`c_pOv%p`?ZKt~yo|ebxQBZXik&80Ws8rGBTJy^bb;$#H~QdZTar51RY_^ge^M zogN4(_$%~=kkyIs!PhZ$n1Oc4vjHN4qFHa zFN=-VSF`<`e;_9SN&->)a6lv|sgLjux=x+u)f~vN-`S1@3G*+C@Bd{+!bGDS#ghnU z$5xTT+rN0^g~T9jpm!j7K}%T^Bewjt*k&IK@BU^J}sV-vPY+*0$^Dq+*ha6Rdx-ijROn3J82OanKl>EjTT}_YQPG{Ab3_Dg`dMQhJXLlfr)j z21y}VJ-8P*9PlWItp#b+kK=w4J%ueoKK4J5ai65d@!L7OsGyaIV2%&@F60+3TzqH5 zcasyfk~`KR@3HI7%`vc8o$zx3+pCgOEY7_~Et#`9e*$@Y*#v1RSwLQ3q35>p}jc{;#LF z1XqmKvhe*{$OnO9b)UL1%94O_~P{|d+n>%@&0krCU{nB;((qS{sg0)zuO|tyO z+L4^X-L-{3%;wl|m*aG6Zr(BfijL6DqavK!pa9`U!UxOF7xxUY1F+*Nmxe=eAcM z0b!4|f-*s!0h?iSmNZr;GTb)#t91!+|K?oizaJ$NB#4mNZ7swRlK=)fVb^325`__y zcb&(n3eJcN%FY8zA$H!CQbJ(Wdp&Y1?ocYUcn7y^;@224K#1O!Xv*moLgn=Sp`*Qb zhg){4YK%-Hnu_kDDlf+B1gZXo_WXBvjCzUl5ooa0+~YLi>AOoD0D1Uv7=$lzue5h< zFeKktKJwZi%>xkdv&MPRhsPMRhtIyA@>@NfG1C$=`~jmPuxIFEDg=YH&rI``3GvRHLBlw>?L{5UO9dWox$^T?tK>PCXT2s`|YGCBoe+Ej@%as zq39fP2-oWqdy6!mE~?=7XVro7#*2bJJ64B@%!nUFo)mt4OYIH+nIv>+Lw3Ev6S2Yaq3N?$vhcgNq#+fgF5Cb4DUSIzkQTXmsLi7We_U3!|v0h)YVSniaxy_~w z5UgdGWxID5Md=3497i=2^(roj7sWsPSb^}65Fh9I?nUpklrEtb*M2gkeBhYEG{`Uv zqd4+AcO?$@Ss<VaLE@dA# z&Wc#mUyHiu6BBLI{G9N%rpq{IHz;mQ=gWqjR!V^6OOEL(zQXmhnuukYBCxhK<3Im_ zFVwoYV(UVU)1~CO_m<52@%1GIozYL?3EQP323cQA`s|+BuMYep%# z-@eTm_?n^=sjjhCK}OK?1}O-}EZz=$hw4F&&&d#=M4lyi^g85#MlnB<5e zSNk8=+6=kYj?TqUW=#oI^M`BAfj(}W!3uS4&{$n6 zi~GE}28k>bUXnVLf0c)IJ^@j!>=TDcAw4{1*S`@DrNX}uu0Bw(^Yuspt6kM{ro`+7 zl%fCk(+&`D{BlDNB-KH(O6!{=35#)f01ZN81RRG#5GaF0O1vdy{?JVabaQ^ zQ`O(shJ<&aG3E4qfk2V%5q|%e%tAm-`$HjRdgW*`A5q9k`DJ4!NxJA0iE>VC|MQ)R zrvBJXCdWS~A`%y{Ci0Zd)%uLn!{O%w78s|5b3)3?Q!2h;$XvMjX1*TW5C6KtKJQ4$ zV(ZccA#xVaIlNQ>NImg^?ta-nL!nMQN`b}yX=vxB3eQs8=z1mQzhDKTsOwuvw%_$$ zECg`V2^DfZP+*_xS9zLCW!No2ZQu`Bj&jmg``dZaer(tb-=<87eq@)jwKIq!)tc>4(hDTS3=dTaz-tZ z(&++27tFjRot@j-)s59BHaCXXH12r=k^AYPdB!h+m%zqR1Vf5t6*H_+_Lj^{iz@~$ zp`%hIFx&7H0fU__J*e{27H`H*VE1oZTh3HC{{xZtA&7iq+j39DMoSHdoLaIS^%z_t zI?!4b-$!EEw8{WXn&nKMTuty$>v_;J(A8Uvh=H$9&TGtDZti~|j?@=sm$HACxM9ay znOV$-LKFa+zZ7~(Av+esPWKlV;Ek;Wsxq;QWtQ;`J4IQu?IwC^#cmXSaUSiyu^7St=A@%*v&d8Dfp=S_yB(Q*fYA5q5oO&IG zeL+9pd|_YYUu^C}6!UIYYS6N7zunB8VAOEoUzEUqH_n4-LqW2q$TFmDm$LF?2gz;E zo?~Da-BqVRf>S5AC}~RbThcI2Z2r>;0m3@V;_&X60wjw;Tqsq=UuH>2fP^pB&DL01 z{W13T!R-;}_?02%mVY2h4ZuS7{jt-#MpG#Qh*DOh?$l2>Ab^R5vomR=paBX@y1Jdk z!>^M8m&ad>x{!=)O>t_IN+l7xiEnExIHmC{`rRlK1eMQ}(d9@j-=0oQ24WYa zo?l7MG?lyjA`}I>kK*iXjwoo@PrbA_(Zb_3+;$G71z;~8ZkGAef$H$MtXsqo3Ri6O zK5U5DTDi+%c%ks-^7CJxhw?q`$aPv@zx4AuLHXEPNSYYsi@P*lu-;bVo2z~)yl9et zV-VC1=NW@FU$8db1SxX83#K8S9IZmCFQjN5dKS)W4f@uB=THR1Z3~xr?tapQrxel> z4og{O)`Os_WWDfH7P^ON&mDc~l#_3h7~-%!)wEv&3@*tqTwr_zD=$>d&_m+t#a)iz zwl)Hi>}|ME891oHekza%wRZd;7ePVH#_brm;M}8aD%y@f{Ds(*(%3%?^!}cj?04+L z@O39E=fM2;zfMkFQD@WzGroMjUZN@F@ZosN&AGpb7GFA+#jkn_5P0W8c_(JdCNc<% z#L53r8R=3%lAgZkJ#|y12*6HRrFt%uiADj3r%L5PZbzTG@g0hb9jqS!XwuTkJAZnD zT=x-P!lTjyX&^)fWu=URv-B;-f?wMA+pI408+|8-{GE9+)01QU5WEi(honF0-dE@@ zarV>R>r&d0ohe2OO*GCey#Jz7v4KkMFKOM=Du<_l{zWYyQ189z)RkAfyf6R710|Gdi zyTyw+{-R@pL5T8gAL3LEL@A!wXqF~REe3&(`bU8O^SlW`?aQrjeggG5rVPKJR`1C6 zeAuYwoy5kgE)UR)i)%b|5hdUVPjc$b#|;d=JU>L)|ey zw8ug`Th)XFWn~d1%v$CWmS@bb0j>HSgJH(e3@MwGS7FN-An^(k-i3x$nHwr7a{A*o z+7gk9FI0L1@jgR&Q-Npd^<$vEwdU?=9k`yg| ze%TBg_moO4yY8qGF1HDk>6X5z#BLgrS|hp)BpBVF$|t@4D^9IZ zE8pBcl?-_Nb%~f{bru&}6U=AdM!0Nx$r-ZkUgtfiftbbrQ7D;WWZ`mlQUYFo>_8b~ z_UR)2ovY^=U(3HR|0uZI6u~udDdg-U*A{MT>MXX#`qkU_1(7CMe)m>bZ%h6cj{EQD?13h{(oX^OWK)mrz(&9SH1A5| zb3#>mdB@hM_#P79-iJSu0wMbY%mPGc z{d<1|poeAXhu@QV=WQdy=ifKiK3VlV_}{NKyGz$_)Q4HCj&oMMR+Bjjo8M0c<+5K@ zf};lrtZ}bX$zxa00F=f^O!q!Y1FI3or3SA8r{7X>{#FSd4-0nxy7FIixY5S@iel)7Sprtwrh0?p z=|KmJSH99+sufS>gBKP0nLKRy8YfA3>N?kM41gn z%LBUskR=PE%mZ&Glu5si6&OlM&|QSUaB8OWmS-)1Hi=GIyf5uq+z4@gb@kgYdA>5) zUUg*U13zbB0gBFmN8G*`upXS`d|< zjtC_*(>u1O<(F1MD51m*)bm3GL+R;lp4$&T8`U(5ZY+|;gSwdME}|&U8xy|}W8L*t zQO}}c%k;Md5kSqiehiQ73O?w93Po20Qhk(bFyJpfXq)QeYNOL=`39TYC8tNZHeYW1 z?=giIZD}aXKkfs$)Of+ecC}Adi=SZoaK7wn8J0wC&xfCAxoQLwNmq>MYZKDH4#$*1 z9$H{XcsC{or|q@Y>TBs7p79pFpxn2IXXsE|{NzZQvR=D+gF%Y~D#7{{dJ*e0&6fSK z`^h?0i1kSuP@$}k7m5PYWQbPldS36wB;n)qY}tBirQ4kbA7V(lSG6r|E-&4F|Ky?% zVDZ73qU3!{IaI9`Tn3=Ot&3|y+H#G(eN7?eEGHETs>3&I%TO*gWR@}8DGbKg`OxiK zI-`!Ysq+d zl3j}{m^<5NSPl|5KBONbvyd|{L;cqtqO&29kx6W%sp0vC_=^=#;PfQ;|D}aSK%+$L zkBt?t72H2p7_J7JWz_D-eF6FRMrl9`>^k2qU;=!n-Eixl zPXr4L_0H_-v$gLeCXuJkmd%I)_`<&2x1V{2MB2CVW405~(hX&aE<_j|%(pr4m-(GS zgJu*_fXBS-VlC-fL?9yhm!FnHpth}9G3_p%SA&Gh@KbIm3e$YwRke!&d7s*lWmCrJ zGZGyZY&s%8G-ZYqCYcDqKxTy;iOVfmN+@eV)yx{F$# z?(Mg(2<-h_kO;_IGIs6nj>@0nuO^&N(EcP2Egb(s4Uh+R$E+k7@0xIcD6Eu1-X6N9l8ocZ-GQR=>Cx5HN5xM6{)p@dTL+!5Dv8Ug1q*v z$B3SW#=Pj|bNaT@dmq>2n^!IV~l!=O`TwWe!kRqF*28*ZZbPZ1e-3&L$pmmkV8jVR%+(3(?&N^ zYlv?D|S{!H@W}Ivc-JuzjJQ4ouAIRaq z-xG_Ls=Z9^M2W!F&>|FF;YPmiwyQ$_rnar>lvNGlDPv+0R-;g_6Hjc3GhM-Ax_2AD;H5sMxz3yg9La%*4E5Y{ z@(elhpH`gXJ*daY1y_i*V6%s_)R-5OZ<^u!GYf;Gr@lcMSx+q z5n?8 z#&Gk&dr*UbgdxJ<%P)e5@}n}^mtN~9&!m`Trs3yv&um?`$&I1>g&bTW&dEF1N$Em+ zGdl&>iYLFw%-!^VWd-K}m+{WXbnKoGQ zk{#~(j0Lu+izNCtl<(YKtIF>XgN_yK4( z^I)=q<2{_M<-$%p&D83Q5x&dzvU>_mRLq7}2PuftrnaV$d&nXJK^EV0!%@gW9Szjf zPoDu`yqh*rHuDq+F*<`NqO{T}Q>Ytu+{{xu_hEd{tlSn({;^1R5@$L}+Xb8sOb%#_ zAWRr}9@L}I0?p}s1Lx)IF!nd8-PSm$ec!Y@z4gkkz1{skw<905;6;jM?$JN0cOlk< zohqwBImNo8!Tf7=^c0SkpFy~qeFh|OQuVSnDY-M{y95NI7He-}OpY^qe%km6q&1?XQD z0eZF%YC<~>^PlWG)acCpc>@2)M0E_YR$V6=-xwwDs~;jO3xe^jZ}k`T_h6Sj1Y%Qv z`_JcoZYU!92OXz}^Lp#qh|eGRh!cb4Wb0+cQ`VuS7&_w8y61MWW=@G^gz0+4p z53Kv2yVVK>^9p{T+aoO-KacQJB;q;J|AiO`W-&SvoCs1H zT7AsyThhL#H{JX6+@nbA$Gilc0UqaZ8k*hd6`-?!U3y}lEwKw#p1f&P&B1+k-#>yG zg$ILy(Y~kKE4+0H!P+!#2GRan8!^dt-%5PJ7v+dM<{-={gE1&qFNe5vF=~@OWo}gI zU#&^)vF<4|cV3eM60XKWFX1|=O&P{-PmFaIdvUquqbr62%v%WJq>p~68_c(q`X~Bl z7e-cB!^@32t)KfB?u)E0fo{(&cL^iFx+m!3uhrqFWWV|THLOWd>%F4f(=5==o#Psl z1_+I?GN4n8UDS%;BsrtGTK(0Xz zNB4=98?oSCMiX>Q2JCwqI1QcaXng$PCt_K4ck}j9#CJT9i9}f>k0R1cT?5@Z=W;A( za>P$S*Z29TQ)w+RXNI7{Te>xss&RJ2XJN!2$bXnLVv8sE6GR~X2C4**FhAy>RHWC( z6ZhSECHDi<>5n-3iXN7=RQ`A7Q9}qf;FnnOPr1`UGMa)7v-Dt;K9hq{A3)}mD(eBRJDO0rN_k)fkrjO!hqk&hJcO_qU0bD zw&@Ki)#!L8E;iR=5%fpDs%6$A<~P>Uyy7^C~kTh!~`IXHVBKB*H0rRD&Jm0)DAOm^wJ7m!|zl6 zvJ^#1mi0ttQ7A=Abe;dHXZ@4;JjiNh&u-h7ZG3Y}fG$hLR$tA1uK<}YoM(8tCI0WnLDs@zikv5>I@z8; zBot}vW>bkH`1z{JYG^lqNIA}!&6D$fCpT@jf9FiE{Zz=+%UUl$pMnhH8BfpT?E8Fv z%YFcpA7LWlYTT1t$wzHEa`6?R+P%G|;P`_qh_kuh!D4apwc;NoT9;-baJ0>38g%>Y zVE3KpzAd<=2L3#S+nR7KGwm<`l5g=yy@1|WR)?v42{z3cs9{5M@yp40Ay5#IBYEvq zezHl6w@L8MC;wd;;(Wa~Qz1$afe--1pz_|M7we)gIZYu%uH+6m~bpKS6Lw)wFJl}vjJ%xqzXK(usZGO06!NFS{@=Hx-et^i^ID77Ywm0ac zgbq=F8Wr11Osv21bU2gS1TN1SnEl6%wWHc(21@#$PM59xDO~v&fmZ&lD`I6_>6dBl z{vRC%h)XOXk;{8{FB1W295bRSKVRh{ij8z+E7-qhWSbZS*ge{5H_=$+d<-Paj^HrT zwRuw=b3GQI(Rf!3&}XZb(7rE+|0sm^MbqZ#Gl|V_GA+j1WXNQW$FeVp_E}VD671JS z8OQv6t^~GBz#eOL^9Ap;MA+Us*#KnFp`rjhalC*jlulNmbixn{u>^@J*9+D`=?uLe zY21?m!E(ot(MNDA5iO?G(X0EuQe9eSwRj@FU~O1JljvgErQ-hOf%G=h4fZIWg8 z&)9)$oupnlf~k1nF8}VQeYAr`Y0Su4qF$x?QecR8#`}|;GnYiN(Z&>wGpJE>K|703 zCWt0!h_>VkkUjp;PkPCDTfZ<6RW3$&g7@es5wFdcg)|k>?UNPP{>c7do(mk}uR$rl z0ESL6Ivk>A?($wzl8Fqav6>d5LmlEdY?!QIpj6n;mv{Y#LCe9ko8SFjhDID!=6#70`=?qxvd7&RzA z{!I3`5Pb2wFAMd(SklRepH=MW+ubeD1cINf;T=Wg2Co2&Zf|@TRWmww-l}3uMgfG$ z?+qtla1KH-nSZ?{u^~sR1PUvVVD`*7U5+r_1E0H3iGQ2jC2nK-$@<;&b5@!#tVQy} znLoRNUs#|!yv_eLMQHC`VE&bsh`%V-pW1^x>Ih(*=y@!Q^3TxreRZWLWjasJIu1mr zpnIyKwpfD14$0s9Hu@$vWZ4vWHYR~m!sESE7hS#YcHI_tL88PO{M@&(qva)pnnOB% zLc@ONd;%|Mkahib9nP%@FDcSd_ZyMvGdP6bPuld#5m$m>4EiT`ni+ zHM4DCH-~CB9n?eC1ZG?I1*Zw<#H-H}%#BoUUDtbR)K5-E5S4h35+yo7T+xRk4wtC;VjiZQ6sb0& zi7(<`3;LSzJGTQakvc%C=S!I0@qud8M(o`^0W#RG7sr@o8g~DiQi0M)fKx#hRYPZK zLYwjSQY19qEXzy`!RaH@9jo2bsQe7QWhIL<0+>IS>|%7p zfr(o7_Mxz2JA5Se0%VJ6qWi;x)C<;ccGkL5WFpnkf9)~?)_#lpejRos6YAX@`FO9dHpguh_N@k} z9r(&$dr$BnYD|D76yl2@l`LWo3%N^{-j#i5@o zg}PNa2|*_3qjd^r3SZuK&3#WNpo5KZ>QGj$o+KtvDfDW}a3=MgGJO{F`qwB2xUfcu$z)6L zT&L+K30&Ie)^vtIJTcQBZeS{Lmg!66?!rNOPOZ0&~WLNgi9af{*^-jU|Q zjz|pl^qct=TSpF3QKGv)!pBE@jOD=L{;G*Y&q4reAOOFryXMVlyE6ELkN_6e zuUF;aqT%110ewRuF4fJ>A9;4t`~HZ$(q%wc05|KMiV;K3-|yZ1^CvNZ5zK_AZ~Ex= zzE((Q5+7gCdh%6A)MI2Bd*8-Fh{o-SU(O@;M%qD?)%p{wU4<6o&o`i!QZCTF7*Bg@NtFN4}+FK^-iv+NI1s?I%3G?a-RmLvZ zJ1G1A-q)WGbQ7!gt<{@xsl>k*x%)UQ#8{)7I!y8%+^9|PJ%&bI>vwG0F8$Z0P@)?O zeM`cx>PqlxFodP3oO*9Fe&g?zV7aiNQ@)w*#N?^Kp{VZl!6KaNNMIU)r)hQxiJ zy=w%>hq>g4z!B+rm-k)xxobL>1aL%_bM4)~UUZO3-ly^{m3xan8sCH`KJF2!3|8!! z&y4$C@N;uy@E?6!pPg1&R8 zC7B>gGMVe>Mr|0_XaLP@A%2w=mHSxs=8DY)y}WfspB%E+&$Dw0(f;11*N-dDQ@P8X zGb|9oy0wE}<>x&X@*lQ5=kn z$iqRSdwyT&%I565g_*4h?VVG@k;Yjr8{1}%6B@UEJiXl909}DA?syL04mpM`;5n}f zhntnJ%{$2QF16kN=7PB#oy|s~jn%V^t+s4T<^Ew~^)-<;Rn5IVadNxY{OH>g72AwG zkbtStPC(`y&Z;NoOgcVRj<0G~wp6v$p&dIkx4lxq-(x>h<~Wq>xr67@0V(4E#m=hu zG9D&{!~NBs5k9(y`ws0RmP?or)=>}qZKb(3^=$f@dtLNK=ZOE>KAloZO3aSA>p|_t)s1Gm#gO>e^;%nX>$rn-|>gi@)m$ zb$U!vA`G@sid;fdidHA{6M_X4i)pb$f(6_rA$dOy!$s|gOM)<#A~qk15R*@iakHe( zsK!1c*fqQGBL}a(NmKZ}BGf|mJ?icY@zFeBDR+1yf( z`cVUkZNI)yfECRdi;C%l(CP>y|I8{jt2M?!+Mia8a%GS3v8cQ#(+z(v>DPOIJH+3A zApyUTc46V;yCBRq6GBr&$8MbNK7{5h~Q8UXZxB31Klm#$P^4#Y7eGpL>i8 zr~l>jfByS_KB%w&x>`QQ-Y1g~q8nPdPKH0~o0FoGi#hFgbvS(T0$iAz;YKi<(C)`j zm^Qif*IS;O{V-~N=W-)wx5=3>lTH1dGW;q`AHI>Ikt$=DP&@12;>3y7^fto`Y%m?h zew%7hpqsy0Xy(q-!Cis&g*%7g=sqaR{a17OhyxGt$I1Tdbap?Yh8^+UBVAt#cf-J8 z62$o5nAkh9mam8t2pMI(XM!-2=-{hSkg1$tNmxhi}+ z9LyD`wfLsr;LGw|ZQO2gJ{;_A;N}g+=5~V_)|>7hre$}&bWFyqzJ>%=b}RX}&HZa- zuMs<)(n~x2_gz87T-0d_VBs*r`f-h$QhSgCa-k9zK<}i=u1r~_e=8KjR%J{oxSSMq z58F7q%zAlI0~+yX8`)cYnJL8vjLEU7m zReC6J5<0qM;p$Ij!ucIvJA^Ennv!tIoH(z1Hby~>g_+Av2pK*!43yM_dmC2Cf)u4Ljjob8rg1T=C@;a zn^ia>H|_4iILE=6?Hb79%XhYBJhefSOKP|?v$It(8BItlU3;R}8b)%?#=zXec_JRq zs$^2h7~`xW!{rW73a2YK@4v+u7>+W-m4lkgDn!A^FGu^|j3q@Gt|1RBw~k(KKllEm zCwv|6yU8yw^HTM8+~cZw7<*{lXFD?c3}!&4CuAMT<=>w3&$E7ed279+0@r!-2Sr}4 zybV5khpOJwS5pPuh9t_Jh2=|`ujXpVMkFX7X1)F_Ibi0zq0zpa_2#?JEbM||KepIW z=FTjna^sMFTh}ATxiTu zY4?|RbzF$*KMj=1ilL)7C(BIfLbFnNVcC?aT2v~VT+d4_oG`9HqBmMjYeQ-gPV23) z9{f9NExW-s9Cib3W@zmxXBWK*eAR$ew!P-{jSR`f1{geTOlG*~+{L)sbN}73f%qpE zu@RpH-KELz8kj4dpa13r-E=tIldpt56bOxtP0rKQZg0&vx2&JhBVKlaGFOj93vZoh z=}MpdJ8YPInan>Nu2+=|6G|gulFeAH9X7iAapidCL{{O;0-v4<5VYyKll*EZRKsxV z%;Q^K2Y23IES;^&khwu>fxhGnu*4&FbC6Dr!f7lqESImbFtecRZs+Rj@w9Z@>aQx8 zS#-6ZwJLEyy6TzB8pPUJqg``&z0VNTq)($#r#51DHjUc-$6D}sW(Ab#U{cNwq1HxM zhv8Bc4-A-C24i;Ce74YURx(xK5R(}Dm1hwQi#5vZ4xYF>2S{e>nRV z^W6+|;bu55OwEA7=9L#Vadx}EC)Qx%XfU}~I$zJ2$M3+e*9jXCoquxJxV*b27VN~d zNiZXdZ~c@1FbT^tOBn0LPnSu;oK|6)xvA&2Xc=M*Y9*bp*+DsslGhHniJsJa&FK%r z7cMu3v(m_YxOq)e*Au!FIQ#YZH#%FYu8uq>M4a~QV33^Ql$WhX&hw>yh_QjC?UWT1 z5E(mpOx9S%3~_(w zit9DNAD=#08*M+8uOfCao&6ds1ahasHx@`I~oB6WOlcj+pBvhjG#(^lmBGbHr@-q7K{YgA>3h?6WhzUSJQpj@7D@<@kNG z9+yufd0s(Jt-<+xtXl4x*#`<|2eE?l?ALB|XxeB#QoU&yV7&}K|1g`#?3kKc+Q#f2 z3TAkjra4@&{_*P9Y{8EktMG#a1leij-YWu;ou-Ao3=f_h$;CIPln`!or&l%{JXV08 z_ax)IV8IhUks?ZR*S9O>D`k?SR8@lC&t(=Sp{rqqJYmYc7W&?kZ!zxv2z2EyYF!Ih z?0~?{OjG)WbZQ<9+MLGRQ6UDOjjAkC@D-y`H`NK2MJ7+w}?QUOL8w|?Zi8U?gWD6|9AbW+=%r%j5zn03={iL=-&Luf7 zi*HyD@LZEV5YL-D`()`VI@!6TH9l%Gl|6AvF556j7|k8BnW2#K&rAI9#pfqP|Wiiu_%!s^FX z7^kIv@+Fml%mKA1K8x?(bcTZpH0LY8&*BACb-yYYp{$K1Zgia&WEkQe<+u8A-1zLZ z;Z*dA)s1e-T5_v4g-)K@*cO;p7NTcYukOb7`5uIf*x4pCr@VrCO4Yo+)mcyen^DR~ z{ww+-AxDB_O!0Mz{~H}xJ_R75Nt3Y&FRjHoP0wR@oCy07eY0S(TkzqrkA!iQy>Uq@ zNvAOnVwh`6n~Rd->f+vw+4OKF9lVI8j?Y7-aBIfCf1}FZX)&Ry%jN#j^SJqv>|R%c zPtKnna#tc@{3tZ)_M*!}aQo4#A0bz%3We^mf8ob6-kdv3K$5Rk%PxAjv-ZSkg|DD{ z7dOA5S({3KaGv~{Ldu%0a4PY+mfTV**?9etW4b2|Jb0d%pZ0k{B0|LC;cnD^STMA} z-Hy@6*D%-y?sG#I#@W}}TjMGb>T#F5J|p=OfwmslDE)GrIi?s%TH2tDhVa12Az8Bk ze>$1SON!+(@Z^hB*di2v;u|~07E8ye=n0yVShhy0xk$lj z&g;bEAx5!|*2{!GNw3eDgg}kGOvzNYxXv^z33yD1$4Ll`Hn^&H+yfazF0rH)kJG zvUaZukqOSVlP!tiA2dThs$-IPk%T7GpCy#_u)USm{iU?)tp;FyH1*>5KQeYe6(dDcFklq~^Ah(Y6lHoF2CYDMNgU-2(SP zF5dud+xfxCnfAhN>RM}7OahV0^s}wm@}7xhdTkg7Mddk+G>`jtYQ5#i&s67XKj=$F zqIbXo?Qm!GgD#wWz3fNRMEVizx1EWZT)Fg_bWFvZ9z?y=?r~h{P5ePW^_10nt=)G; zp#w4*0WnI$dkcfcT|~y@+QUhz^#8$i{gIuxJ>Es$6bw)QMNs^KLJoR=?jUd5BxT6Oip}|=E_G7U!{0B6;L%tMzKW9$_^7Mf+ywGag6dLriorIB ziy1SKy%2<}R4UfL@KDrxKpY-1qCPD+>yoinc?fUtj)IXWM^>$2tmE=?C6Dzkh-yJY z-dz348m2_6XWS;y*AB-=(nSd1Y8q$e8`iITkln+Y$jFo3o(U+DZ*_k-e(ZDWbjeH% zK@cUoJ+(0zy4r~cRIejl4xzJnh4fLjzqoCJPUF-KKXGmG_*N_@ZEY5UR13QAHPqf4 zY`T1kD$wkOqwsdFH4ZDL?){8=5t0E@X?TLF$!4eOu-MLwJK;xDap^i7>X*}qoX2@#!%}^VI&Jx99gou)|V51Ne|nxn=$;e4OMLjfzm|1;Fe(5Ww+X= zuI%U~L9$%uP0E(qi?G>Wnyqh?!>lI)_a+igl78KZyC$jBwbu_{(+ePCT|YQg=U*lo z{(=@qqRF?s6cFUFvypT-%Pk?4iMd|IuC+sae7D>7B?oyRF?6n2-HTG!q6|8+93+~t(8t7fBNT`-#L1SOP znD$v~iDaH*#)!vlvt%^>iJ>6%s{-&^je__SymPSyXaxbE-kzQ`X{3=qRPBUj%_4S7 zjKO~*Q=L`;yVc4-{_(YyCGkg@t@DG%uetWq|%6MRfdBf;Qm!>3x% z!S9h*bj#4tPdO&!=c?~3sPnj1T|eeETHIkYnnAK_lA^>x!VOrG0p}FL-cu$Ex<5Xk zp|A7!RJMvUjb;Ua6&vW1m)Mr9%}G%XeRl2+e}E=c+pRWI5#?8l#Cnxx!4!e?4C$iQ z^L2Fo@*fh9eF`m2Jg#3dDja;soXTC5-AgWIotRXgcl_%KZmQTg)v?SAu1s684-N<$ z;D2eLu1YA2D)5VZLF)Ma#NDI(N#7|Hv=+}Y2F905#Lzz=CY^H1|DxQm!8qn?Inrvw zQP4)9Po*SuoLv~>^N$;gGUXZckwW*EM5L7DAQhVACH^KWwU@bzL#p_678SExvm zmE~1;u|;VCwtX+q*N2f-OVB8@ixJ|WQI}pG#%)LE#ALfC(DxEY^l(uiYgPJGfndPY zUEK9)&>QGV>&YfuAb6QDNw)Roz+qGLnb8nRDO;)$HotXB+VXppb?^h#c5D10nH=A3 zJ(f=C2}B5b85|Q8z%psLP}tax!L~;({hf;cMCTq9z}0wG;4WeO;r;*lA6*E3F9=ZL zgTFSqA4s!&a-l#qDF9N3ueT!Vb)w^Hk32(TynbGoCZ&ZZc$2KeEm_VD3^T35?g%6D(BB@kxho;p8exANN}j z+9HZ4I!rM6_@oy7*)h97k~<0kOM^vMw8wGh0|_1}q?K$fcZ;7D9>aSqlRg6e?4sh6 z^jt<5RqIZD?#{-!+Iw#XJO+vA z2*Irpq@}UoF&^i1uR$;);r~mmi}pRMS9L8-LeD zB3Z8jGZsxd;wl7`JsdtPeCvHeM4&&`pK?uw)F+%?F;cL8UgXuq520LO(>`{((v<~p z8KrFt8%IBUyZutS2D9df8NSM$D3baFbPUP^LJ@K1-t#Gi)UGDdOmb99ac8A9Xz!!d zY(7BJ0HxrIHRVaBOtiI0izV#MS7;Q6IoxKYKVq7tJZ-%k!M-Z2ZMdD5_5*`hl`=}3 zrLBUB-cFeJlzBSF-IOTChr~im`Wjt$&h6UHTLgmWl+1F^udq5d6;^Cb5xlI8pJ!W< zuUM49F;Hq7E_=TqK_K>^FN0K`mebgcvir+vC6NFFUp4c(b5au|uCwM17s7U$NorKv z{g)&IhN5+zQk#dchJp-4QSJD(CG@yiF%9=kX`SOZM22V%ZKMn94?y{GPVf2mGYd_Z zwR`o}HUF!(Jcw{_2eT=O6T^fWu48*HGy!6$cI_&g!ojR@>CgMyk<#_k$sWgHufO9GA$-NG?! zKjY*QyZ17qG)cm#8P$8kmC4pRfbGEqcdC z3!QXybD^chSty#g>WvzqG`9E`SC*b>EKFK=y4nK|3PXo>>Ur7DexXP@%TDU-h1 zJ%V?>pD*)=n5|WL`*B3t5psQW`qE(kq&tF3;x7ugjZTe27d_E*8JLY^DMTdgE z=vW7t$ek{q^Z6aApOa2tSy?E_vAQZ(GkiC&orH9J;IkAnxW%u=)lO3Wy6`j5n!)_C z8)6Ct_40Y1?swW}R9lBmpCHul(6XNrp!8$VyZGF3xpU!aj@M|+bt68RZ1hfQqVaf} zjhu?xnFJkb^`-CaDQAT#pdKZ~6I59-^^2SL5+>hM!IMLMT$I2vfUB%aoq&{YU|4&q~iO=W4(fRaShMR|?7130Wj8-2m{KErvf@U*1dj z`dTZVASZ3}3l^`>IzFJ|ZYP~16xQ@J7hqxoqxpt2P~5B=f0+c*NQx#3DXLoQFP^e6 z##Q=LCk}_a9A(-@L3}?L3b}bLl}l+OWoLrZD#FWz>2lc7g6jwz{?5usTW52%;3dAk zf*Mlc2-kb?7UQHZme4mrp|LMm+fqz9A`cRr}RGMcW6Z!92$stz|Em5!w#@7$G@sC6p#h5s}r_7J1 zkJ6n}tv@~ZO+SOyCW`jFGF-Z-(~h=pOOCxXn;qziks_)Bj3EkAQ1i`FS=gB-$7HqrWU56ySNY093-8-M= zPv2!5D9MlB8BU2wig{huNAME-q{WZCg4Ar=I1R<_tn3T`T z?i!T*ld{R&hTL2Ql{U2s^fo}!uX}+uwsS9LLEo4HA*D&_Tn*_nppgvI-71p%^<0^* z#9dc43YZ$zNYatM`qZH|58TjsbhY|NlJurz8U`UZ(A>+v${$N?B0WO>eIw43oQt~i zPI5G-tAp$-G_PPQ;+0R~lt&3VR!ScBWY<%0G+DK)(aD()M;Q50HqHy5)YI<0{Gr0$ z)r8>SE2fGs&?MdCv@zA$f`6B)U72(WShwv50=>^)Z}xU2@p@usK8tO*mWYn~V#?0# zc2k95pP5ja_yy}K_anB-0X6_|@N6x+vBXOC3-3uNq^-gz z8Fd(-_3J9PiYR;~$Kp9%{4HyeE6pvB6snn1u|2(5^GE=Un>@)ZM3w3PAJ}jAZD%Mc zT}?1wFh~JR+_`zOHP0@q$I3O^tIL5Y2XIqkZpK~E%`f#kps`j&VR+_eDy0Hboc8}r2j9&;*-Tr_6mashg)s_jt7g3f93xmM_5eH4^I z3a*UvofLYf;lun0uA#=Hrj_&AZ-u|5LsKbn#s%Cfq7oE#qj6055x=D%BpL`csYXMpLlXa6p$4aTa4vri8W&i`^g-FyN_=SUESGScn4fl1fBPhS2;hnG7I}o z$y;Wy*T4Fz`(&sN_v&B(fkB2v!DJeq0%i8Yo|nyOqp*f(737iF65ZDR=dbFi)AANSvz`ay7ikZZKUJMCX~RnCw?sO-NPW zR`jEMc`~oXFs;*ym{12?;Zh@a(`XnWooq$}=LYYzG0=Zb6HSEr-KRDJu}6;Ejx5tk zCeLkFm3|u$)N(n_c@Q&gT~f_99V?edxL1DW%7L)X39Xf4-`7{~e12JJQ{(adl#hyO zI9&ouM>FtOwgrt*;EV5kHXd(Bmxw40Oli29qH?_MAx*8FkVR0jcPr-zgF z#a9nK=HYkm`&CEi&^H-l9Omm9cieQgkQ(Ycpx!wADje?fU05c2hlj~e()o?*#YWQG zbi$C7t7vyWuPyCtxlK>wur?YP-C_~8xxsKm~DB~w*I@Owqc;#Uh* zTxSpA@dOZz`__sjr7S|>St~-4+Q*Oni5O9262TaHjk zZfP~YGW8{O?bb(#)*WQtOy!K-U_QHP8HZb;g|y_alT=i00wtj6dOA zW`GB4ZIwk6hf0jQa|IxU!1>279lA{m4eo5*2zUy$$Ywz+$K*-94`hPYK+qgbxv7Vr zt7gBbo6&UNFbw1&EPNn;EU@Kevtg6d%QzOMs_R`PEuZ8J#m~Hc5^lu~gC?mu)cpWgADm-HN{_)lMX6&9giQ6d^keySYd0ns!A^Q6Ihxxx@0F=UJW? zP9D_Z2Hg{Fha>1<^n%6tPQyE;xj4AhS3WP@O`#VOU=uz<5F51J|0sw#)FM<>9ru~Zx|HrZMZKGqhj5WijPI9g z6Ii)}{h}1q+Wj^6r#BX2cW$m+&9AT#4On6}4|&CQ5aZoI3SzG|=Nm@uJfXgVdkTtG zK56%S5NHWQb~X(|gA2Am6fxp280rWmeR6rM8mySgO@(Ch-lKx;VIj+c{DXKiPevN9 zP*y^!e_2Q^6e}4MMi|$Rs3cM8GK7blXQ@2TZYaGcBfnC*QwF}W!>wXYEI>3ae2qk} z^g=O-$#o-1kl9wQ3V@#(Ub+@=0L@A#gISfZ)`wtqOwRdK=uPvwdXA)5#(n}|d&6d@ zDC8_bC`K{5*{^c{@Cs7NKbrEMFL3LnG}fY)_T4!1<}U?W1iK=pz{MoNGoDh|m);xagi)Uj|d(RSH3G_rc_q_%dmF}VHB zvk+nbKc>z)D(ZJz z?#}z=++r3ml5@7~Y;JkPe676V-aUv7NjOGf&BJuPC`B-@+3KrG_~x5BAN zwr>>5f4Y_3-@N>pXz7#Qal6KqHj_h~tNQLkwdb4_YyUqrKbcT#s4!J<`Xno9^g_EP zb?vF!&+9AKL@y-bqScM)R$yofJpFw|d6L&MfF(b8#&Or(?`kc@GP27BGak4x{vZ>2 ziSJYaY5wdBwcD&?@PLWv)L*O^Oc);m`=?MN#p$Wv zhIB?w+|j*^ZU1}ZWP=~UpA*L`p!{=(uD~HRyazy$u>`!s!}lHU(=ytZac+pZfM;?` z=W%~3*AuiCsl6D}T2IK(?%pwHeaPU#`PQ=ky=p0xYTdfD_R`4+xHe1VZd`TGz5o(7 z#MF@}@ba(PyE%gis5-2n0$!43=zY{1@Ya;QD-|8Mc&iVGfei7R8&V~qc>VcQpLIwM zj#`oYyRwDvlF%Q2y)r7^C|3c6kY(*Ia3=x{#rD~veJin<8*oiJ{E{L!KbtW7s`AJ8 zv;}yjyB~+kLp%1{ofdz%t9{+(y&KjXCHKEF#OzLE1uE&^m5-s3bL@+JFhQn&JO%lKm- zP(<3IyywI~P@sObMl_+FUh_x+M~)}Nkc%8`g$lLOGmJEzW%lf50;mx_JPHUkw#xXD zY2Su{;2y&;DKc$FB@M|?SgFfc!8?x^AQMOF3W%(wcTTB89@$TrI@dYC_lSz=@d~ab zs!5k*B(F8!U+;ubLM&EAW0_#*z&H=D1U3C`nY;s=NN~qC%{&>0Q210iyMp%f`XfX^ zTviFKfq~?CDhr@}Am`vmMkE-`de=Qx;_8PjUDZeeCX=DE`QrOv2TUJ2b?kCFH*-Zg9SW64N5d^Si^vKT^ zKzj>}#S=FG>I5f&S!p=30cga6i-C<_xyZIraa{8-UJBDPO|!EF!cuCdmT92Opi*|N zsLgVl7x2CsG#pOo1#V81Uq`^#)ITN$h)n(8TTP$Xjaz9Nc&rh};=h2Ap|J$eJW@oH zJ_hcO5F23VTrk_Z~1RP5x!M!@-va!Z1cR)!!hQJ@r~ zq$6~y))pPMuw{Les{B9GVTL}kgf`_UNC5Y1KLoHWb8AsxeL;xeL926*Gf*e8T9Z5( z1Q0OMktol=DzpDPcXoF``-}fdNrTeNLdo~$7Rb|3Cgh`H1DcWxRs<1JKxnfUIDNs^ z;dd@8xOd~_PYnUJ!5A2{^hb@ZO^qdjap}m!3!=%1{I~e|_Qm)@-8C#8Av!Gp+d9rs zOB55>g}obRv+2Xo<}I*K8-xDh=@JPMdkXv0Uq_@wC)crrZ%=WA6C@p1=un5NCcxTF zg(L%j+*?c83vxXN*u7h3XIeQDNak9w=-FU3g`cwy+7X*kj!=e0R}9~74X&dLv|bI_ z6Clwmz2qiC^F$LUQ5Fz?Sz)A=1LmxXaQC(nOg z6Ey)7Bj=pXBk{Q2Ski}mRxjWXLLQWAAN7t!T^-BIr1VnzKVJ$LLd0GG2d-eL;KK?j zFd^%+Y}+mm?i2%e29m#20Xgzun-cYH<2jKrg0XdPVLbLg(K1LIHNjQcyq-=h*#`9+ zKPChCJ~0nuWIs0%LU|iP@`pr@otVb=a*6nWlT|Q-B5??*Tq8kUPcA`8^tp&~Abi!( zT-UCCLOwF>Ul<-hM!x-Rsvp-w<8%58MZ*F(Vjh{rn-| zzv{GkU-Rp*(+DK)62pVNb<<#Z!pHp#CpleifLwM3hDXU z5*`45)4%A{CgAa@J(lnW){%*7N7CA5c)l@tVy3-aK43y3Y#oJN^9T@40oCG3g%xhL zyWS}Q!e)jGLkf@N0@yP4Ms4hI78Z>ZY&_ZRi6E7U+l)Gn;`x%rv!3zggS;{(1RDwX z0c@>*QCOBj65EHs2{T&e4+yU{#YfnI3C`ub)6XBACn#{K2rZoKiXpe7MM+PX{o7RV2H-y1RO=8kZ%GH3NA*cJ1`2bH6q2x zGV)$G@d?7`!>-5}nDnmLQCV;BZ~-bLJpQ>)Y8-mVX%T2Ypp(A9J~csH+TU~%0z~W* zP_zvA(rcmF5KVexB*2EUjc_Z_RT7x7|25XSzBjtAYwN~yL>h5=7S_TeLkD~HhY1XNm!hY>fD#Ij*u zfKax);c34CJU1?r_XYrHW?8le|BI1NUlp<-@odfG5%qp7`mdC@I&Phk37t`Q5~4W2 zztYY3=h)f3+Q<>LS$MoUL#0H?u!2el%0CXle5&UQ+p0I{!K5yjWOeB43~0%t`(?;K z=mF~3Re`_SvC+=^8Dh=ulIk-Eb<~rXp<}Kkv~U-i0OqpYMPNC`IgZ7t{k6x(X#jIP zvh9fIwV^`O)vlsxj|HoV0?cd;4_%=zOADbbpD6-fwf}vGi9hHOTYkiE|xx`RZ=LM?ytcU&1By0OHQbqlD@{1m&?Wfcs@+ zIgZknO}=Y8Jz~ywr~ga)yPZ;$vi1|(WzoM`fUS&E*kqVD=?y=kg$d#9@<_14hWp7| zUkTnkTZcc^$dcTGgBiY6eKcO>}lH)}wc;s{qA+j{+T4K2Ei zARnXlnID>r;p#6p1$TLN*h4-I&5DcmFabuABE_uqJ5lG+mnnKAP`P~JQA{mMhx;a= z^E3;<0b2XU$>(&qW4*H@?jw|C^~TreU5OMBK&+{^9S*ZW8S8iIpxdnImH%u>I)5N45kyy`+H9{62UFF6lQ70!?_7MVAJQ>Z>dTJu zd4agYx8w!F%_`sgvDgY_pj4bRe;-6d<7n`bFw>@* zw>aS6qhc;HGd*l8^UxKlU=1}+4pp$7Dlt@S1>>KAvbcc9mSc<^UKg%LM)1=Dy8NwX zfE6OF>1J$rN`IgnolixOU%g~yfuW2YSW>mDXJ7_(U0Jna4N5LrkkbW#9t?U}f9PzI ze%*2b+>}*P$@W|G`T%It0dWEd<|kA!dvS*Y$09&G^y9ISvRt8lx<{*)#qb@#Z31{b z3Rm)Yb+qZW#mgXt`bxG{uj6`z)2NDFDqp9M5t_Wzm=W>G9q5dYt{2!_X~oxWBxj@V zU+(t=w6NiEPIkY{O~+7PDUD31!jp-VFXh#R{w>GYYy+>sYhy$w=-+( z_TWq;P~5sf3@X2GmucTkT@D@qw9NoY>0E!~t>{z=u_*hs81e*Hl z%6Ec~^Ua~zHHLueTM7n82Qgw$(0Jcv6c8ROe_Tn=25g6oN(TmIu|+;ZGSGw(EZ~PlV4MsecdmqZfaKd%k=nsltsln8PcM$%BTq);B#x zl`4i=FVg?;n~N^@nYR4+O9iT!VErLj8_jLKLR^Ry%&R+j$`^p$ z^ufC@zHgBJ&%4CSC<^xi{pAgf#zXxAI4Z68DOTg zK#X?O5;F~Kb8#ZpC(P%iv~OZQL=4E90v4X)|0g7Na?_2LD|K@FtW+hcn|(GeEloqO zA-np5Kk}!fU?ya1UKS9a-p-c%GV;t5>B*$WYW{7kk3Qp|BM2sIh{E(t9&^*%`q_PyiF0z331e!Jwg>Y2{gQ^ESzZx z9DAV8Zt|1wU1Bx?A~t+Q{DliM1QfUhsbhh^%_m$Aw)a`;PwuipnK+smsf3D_Q5n8^cd07?DPfAOh z>-c!ZG+oE{MbSM3t$YoT1BwV5C&>GC9)XaHOEBdtj(ln9zeh06%_u`)k4o*EfHfQ# z#n^k|FJ#5m2r9_BG2+vLqRRdkd~qF$6ERj78PX2Q+U_91moC<%jZ z<@I%`_RBhWT#3EWms=_CXjG--7n$(ydIRg?+VRKa5=1KN#Et5RjOK!0q-kOm(~1|F zW}4F?uKN?-Y}Nvzgt_q|{iGJgEq9V8nq@A#ZqcWoppoyiLEMqGrb6}*8SYr43YfCw z8g&JswjlQicaDliUZm$3xw-j*WOF@u>p|d0$SDYHw%99=7sNG48ZLurSR-I#{G}xZ_2E|K!-59b>UGpX9;WE1Z z+1Zc#ATbsTj0U4&zMxMsY1JQ&XCFJ2C;e4t(2-+>-Lw*$?azFXk=guca$nrnE~d@} zy^K5lpoq$97g@lc(yp!l#aSgys8Av8g*A~&)Q@k+y*)X>zR?U%wRqKe?TUjSl4+aa zbP@NQ+)+Jpw4q>bhx+5C zq%h=~u`Ac}&7{mJwPZe?cMh`H$2=)L_*+9vlk;wc>;146Dm>(!@xZ>v$!D}CV{rRF7&+5 zLQ!6n611T1Or_0H|L~;Kbe>@}FMjoB!V$do<-m`Y&VfKqZEfg?sn2q>WB3)wbUrTz znHuJOC_P-JEWo#N@HjyTzqP83o6sH{&Bl3cw1Y{)8|J{L`kH)lqQjRQC@8rfLo~Rz zjoIZ?+%S`CvN!8*>HF`g1OVf)CM?s7_|CftV z`xNaCbN6-TVap0UqE>Bq;;?eDHNx5Fmg$gsNhE(ad*t}Y5`i&V>t8#|>~KCrO<`%L zenFhMw^SQu&vcQz8v&(S0Y%rk-LgdP-wbSLI-3O6ex}`Unf*)D6JM)2tkq2W@{-BT z(oUPpjKo`B`(e2oq0Q(bCeSRmbe|xod;1CM#?eAvcMLQ_$I~;EC*tI@E=~lBV2R-u zU4gag!ylVFe(;xXa^~WZAEN;9ri+yC?3F`fcN&xBH$X?$2d6q}PTG4#9AsEA?C(=PP>TQ$LT@%&WxFgLqdt%ydT?+0P@&8r!@)Wtq)%gIZ< zE5TZNTST6cD#3nBi46S479)gvzqr|QIosch*E^Pywn=TxAm}?Msa|A9tRSZMOw;e4 zMuJ@mLU)?mCNGm)w0z#BcmuSS7!5&1>m9p-EpY&1Y#(Z)Zbw0W!S;68=oNl`HbhPC zOm|N&g*x!JGg8Q%>pmW?ja)+3BGWF%785KlvTpY`lmbW7{oFE6+%}}#CAJqH+~PM7kzc>+gOJGo+XCJED<6btIv&) zoFuk3fgNK{1Ly$(Q@sVCUVxA>2P=!;OV8=1gdB*v13&+aix`pR)&N)Xl8}Fnpe;73 zEHVuy=exD_oWfXoJ=jY{%3eU>jQx$i`w$fNYCZzA!3xsVHd{pLgFPRPwrHjL{4wdf zD(fip%aQMaP+uTftHXQq0Gk0nkgJ%+szYFn$A${ovs)_Mr`Wz)b0Iz|lxl!f93_D% zt2OW7u%a9pM4P#e49Ez=B=DPZ&j_%IB(-@SW4rC>efktiLAHDcwMPseKyTB^ z)HD6$H3C7soM;(Un^{Er79o!okG`>u3uFoe3ZvA_dO2ZeNhA{^YAJX z+4b!S_TlgY`~faupwh(ZM2po3s`6S9%Mb;PIb!!NHQHx@upPjvt|bc-QzOir3!{*HCqT(usVNF~U#*gqFkQShDa{yli(-JHT zWG;Lx|N4~9621g%0sBp|q&L#krPT#8TOswyh{AF1$Kq-+vr;W~oZ(#01rQqqjOfyJ z1~tW|PMd%Y+0`+4uOW$1z%IwxZ06eB10C*imnQ?wZiM z_JmMa{zfr z$unBcEbbk$N||BEuaL@3_qQeB$q7wYmX^{O!KGJ%n0`f+w*$_0q5M&N6fCd+$j?-G zmwevS{63zzDnuA1^aR&Nx|)W%EhSEs+7;*3{rI2p8CNg)Bhwb+sJb4Bs^EeOd) z!$r8PqgV0__uRC6-?%#J{GT9APebq#l<<~xpuZ?N5jGQGF;MXq>+(?Sh< z$$ujikhr^cLuJG5UUpQTiU4QuOCmQ093_z;%4VUr2(QE^6{x{~b~BQ{k7p~?h&pMI zS#7f0jHAdy#+Qv#Q%b?F-3Zs9uI9Ih{djQ?#4VH8__S2GVL&yj!Hbgz*EmhTz22P` z{Kxn=3XD!k%$iqLS_g0Xl9Hlpq26lHzibe{$)5roUHjfdN?zZ>!Gl*+u&-AuJ`z#$ zz53(Ux{F)>@iIR`AG<4b`cgnG9Y3n2tEgbWO9_d^*@rOXRvpn7wgIo-3-K zFj&4}@(vORvWOj^c1m*0d8gk4d$@yiYjs@C{IV~*rrUVPZ2WC;r|tKP@)mshZouF0 zb-R7)+}F_k_H|A+0!C1AZwI+JRHSV_1%-s6y=eYAt?y@X zxksa2MN2kw#<;caNm^UNEzmAsFN2q*)&gHgFTlL*?X5E^tY>`r*DgfTFP$Cu1N|bH zdwy^LZRERhwV4mV8>S%jehV1nZsMY5W@wG4LCn=Hpr5O|5bsI`z@aszU(>-6sjx)O zOhSkIH-YTKxCS_2UqZzt5aUtITT{|r%v#wuHT%;w3y#p$no-h%<+@iPRRV8{KM+Vq zelX>@#vJ(rw0KF(A>cu0_L7p=t>49(zI?+}&~%Bn6}n9qfwWO#D)_4VfvFjB$KC1h6Sa4R zc7ChJ<1XJqdzKxzG`_HSaZ!n6T1SQVE6gajvOte|NNcZyB$p-{B9DVXQO=gTQ`2Wt zV{EYG!B62auF4ppP;jxdqG^6RAZnOrtgtfRW33Vi3&AGKWuFTxEd-oy1%aOxqT5$l z?&gmqX{VSPexy3Vaz%!@az~)sPXti+FcScGEH<>RV9$&BZyqmk^yk;(Zw^dp*wYhy zw4vckC@%?&RL+NpsGx@@F?&+h5igzwuxVhjz8}=)>_so><+IGgL_3WTFz-xn+&jA^Au^CW174dYn1Ph z6fZd$RNW}fosKcEvC(~>L3EOXNNx~~y2q{}GBsu9PX@9p8$QU(|qD z7LS(ulRAa$Qb7xHkIcu>cr$+$%!rKKCTEvjiMYF`T3!@!ybHu77bO#Zkyln~lwyqfF2;yey7gslI!kTQB6;zW z9%Awx(Sf@kWk9Osw4rC_0F?Ec1sMluXU>J zngOrg9R|{)iI|&GBPj;w30H(-8fXr9aAHEy;{;B)4PaxO&XPw@yH@2ASD_RmTEu2J zhejLXnZ~JkcG^@wjJxSG)GX-lH3Swv)c11Y)MS6^r9jfei;wsU#`jMp!C(rj(I; zKqOy+y!^t3-WjqMbvQe?4tJy`7a|7y6n5fRZM-XF9w=LWMK z<^hB@1=2-Df8Z^m9s4Uq=tBRQ9&)f?T>dWWV>#?DJA(y>zgjs8kYT zO$+wI*#?W$u2#f}W=1*x6Gl5wiaGrdk9Dtd>EYObykoZf zHs6`qvdF84vn=Tw_W`L@yfWC^%mfQ)ZjACdYl@Pt%EPy*ZR@#E2q$n@Fu(YIDXl`D zsT-s&&-Zq>s@sAjxyl}dxaOd@baETYBEAdd=|a16^6Smw-1}AW{(~v|4ddEL;Iqp< z;<$(wV|cqXx6f@-6X8lMKSK4Ek|H(|e)CSY+tpC^Mc^3;He5uiV@V|R24sK9lFk)! zCuldiAJK$f1q^k@Z?s1Vah9W8repqY)+(HA27>=uEUbG)21imPq)9AsaJM^+tn}e| zA5vuO^iP($d-!>Kg|?^#nm{b*yiJ^iF7}I1?5v}LOFXmse%6+Y%s-jbA5JJelljiK z0Xa6E|DsO>U7%WdeJ?}CnB8CvyM5P}sr0vCuV>Os;rDsV70p3HNG$3-adl-gc8!8g z))?QTshG)%DbU|^&Uz=5jo`6ZIvDj^)fEB$(^?7F#iVz`7bPzq+ z6f|}D!#e}$fg`r5VjWcbFOwfYXv)!d)L5@Or36ui3%%-&6CDn*)r0PKYF8q=zSDL( zFm+dxZHR{3*rrb*tG8CNpvvj2#0SRtq2DoyzjY>u2u7J6bE_8_aPF$%)SQ1E=P@@z z?=vQxTBP{7o~}^FLL0zxW`t=>81}sZ9xaS3y&V@sz*n~TB-A!BV!xZtByG7MDd-g& z(IL{o7hQ%A2E{%O>!#!0SeVvwhDs&U`Na|WX{rTQa8&%=mq_Nq3IQ4|iro22k*Y6T zN5V$RYm1h+E_r4Fl&pS>Ljk1jwecVGKK9U0w?9t;Wh&CiIc>`16e+~hVqukc0+-+AAz7y#9+gF;nxn@2<0x|9X3le~EBhQ^p(=?P_ScJ_t%a zA#j1ha|yW>e_?I@g?A8Ha`Rbczy9fbkJ7Q3rH96yT&2BU715zaUMDd?U>tIlSC*sQ zp3ieWv4nty3Y6UhY2?K(fskLQ?4n#{JB%xsH#>nJj_!8w{=(1M_X{iBSw~M~bO}%$ zKU!9pwjU!hrH!5t>~0;LvTP55TsSylcA!i7^WDa8v5E>dax;VI`my6)q&ib-s%=OR zd;<0_cbqzIr`T`&K&yZThkZhK%#CsX$9xUN-*>{lru0$Bf-y<#}A%US6{NGF)SQzzowt_O6^#G;b7)fczV%?Y2f?D_T5&PP_X=2dUp zu`*_zV>Yfs6otG9QdEQ@w2z&MEAO^HQ%gE@MVsL6Zl*dMnIRr$uGDLevZIUO?1#9- z$Izkhv`?iXS~VrHPgba{r&DUMUO{yGC|Ew9LE z!N1xCRxB6>J-HE>BvnUTc$(?jg*ATbZ^${Io*W|m=y=gXE@GFY-xEmt&` z*~;}X3}?E7$IbJY%We)!IPcaR^(DLgaB&m+6E1|mJA74$z(l}V$ZwNMeE^Q^hUZjZ zRnd>xOjoevN%8}d%z;BJx0&bG?umyMb z?#SF6X_BsCsWvRO3*@#rW89a_x2q#wr%7ClVx+}oHNs47NZEw?cBnGBjg?c-95sGUsRBWpYzQIx%hH)Hh(l2=B2*P|~ALnC7tG>R(#W%8H!XwwKixe15ll zfMEVy`(Czn9@ucBm1&;tDB3OH8z0cJ6i7&5hu%TH{~P?yqgQDkhCM6$0)mF7nj%FO zW#F(NCSbBAaLZldydN?&gDo#-VAqh+w6K`)o_di~5^S~Ky!Va3P-#D;iJ6a{@t)(- z%F&+sQEA&)In@<(UWaG5(fjtx=Nz6} z2wb$CU@d^|$-h~EBWQN zPaF-g){J|VbN)TjLc;X{m(1?pSr^{0G@~dS%p-yW!XK$H6zg?PTql1nJhPn-v_Cn^#Ayforo8to6}ne6GmY}t zb&pJ!9YfhI(6UfyVJH*x6d$o#4hP(!Jh#=O8^wjW>Y;M`(Oo5x8j z36T`t8Gv@02Ytk}MzQot`~Rks3eB;KlJgb}nV?Kr%!V3BZ3Z0nca=-^NiJnAJ|&XV z;-~mk``+jCaS!0jqsLz5<5a22>knYTn0_l1>AS%jZO>~uXCV3XWO!6B+u=$}<`cab zHfkI<=UI8;h}z)r7hXnlLA_9S>9~Ta8OHuGrY74uT)IFVF_ZT^vf*THDY&mVdD?o( z1Bmj#bLy09i}Ygy=qhOqbFqbQ3y5~R^KOsZ-@deDBaOk$1|dRTlb_F<$ZYT?{W56( z&Bn5fA$C};wUr=efPG5Fl7TA-vIn!T1j81>BRYj7lvz3XxzDNf22y*QYGe*S{*qb{ zH#p^w3f1}0p;rUTtMgTsY(MvqfY-V{X+}}itqeWhjbP4B6^%KO)$T-jAP6td{xI@{ zk$`L7B+ynRy=nH8OX>XOVvHLJy$>~vtb$G=Bb^WS#pH=UZ>zUaF1^W1MV6wc@3VOR zj8hi);qr=g9BoesWo%n1U(h^w&86Y586(3OV<$>e_&nU+&-`NSCn4IApuJW$uU>8@ z?c-8fXI9SBP~dF@MMA#|e1tG;4S2}{P+1L0SXpUdlHav;-CGdtz}x2OeJ z{S{IgkgW>#F!0Wv|c>eTKk1dC+>tl9#;-n4pbw29ap{W0N?OT4V)jEtu!Z7Un$* z#^no_*-vXoO{L-;nG}f_D#aAO=Rs~@n+b^=?QAOxL}pW-J6~}-;%}(EN$56A>zo6h z_G}M~KL8YA{Dz9#$jX6+2evqU!7065TjO>OHUCzQUEy9Jcu;FfV<9wkz=t2<9y+2R zFLtU09z#tVfp-$SbWQD4F&+w=N#mi>U09l%FVaNZ6ih|#S9qrNwd}6w8_!J$X=~cw zUo>n$ZY#AO#Ndd-guG~?&Q>ILJ8HxX+{=6aq^+>R`nxCpno*W1j72MBDM#_)L}XRL zK~slr6ayGmXXF;v0SG!C2O4O$%BX6S3m{h(IY`k=L&UOb*R+ysG<@v`ii}zpgO1Bs zI&+tQ(7B`_+;IgkR~FIwuHK%la}MUW{`;lC6GVG-AVE(@B~C`bH7t=+EbBkzB;SS< zs9P9B#6^J!I3ji}3kYP5K*JjP;RxW9uL=k9Wkes3Ho&Q(7O9rbG(p!ZWBL*@Zd?8g?+(|Im*=Gf zXMXf+D{B)O%WHjI;@1&~2(^g#$gBCwV|raEQ_L795mlkB+coZ0olJ;O z1Ro;FUI^%8KJE;ds%vzJn6R&ad>UncrnEs*79Rn*^Z7El)0x1wyiOYoftfE-vERIs zkH%#ZxKt6*Tz937TILO#!ax&-(+L{qu%m|YY4j@K{}8+P-Cai`xF4gAC$&mDjWk-K5gTW=V+#Ep$QaTwrI!Eq0vD7&>Z9Vos*sq;{ou;aX*}D^``m4 zIv{z1U2nArKa|S21u&cisnLe=qCM@EN)~_pMcDb9F@e8A_^Kp2z|_y3Xx7q{s2Lxi z5w5Xd1dI7S8lY%>SC+Q4lfZ)@*-p@8(Uca6S)YU;>vbp-MRA3$G%oYG6b2CwgF~5S z0`*s?P2vBz7=Xuv4@32U0eiBK@^cogpAle@SSrbn8F+|TjGwjfi29SX z>jo8MWAHge^HHmn@+hJ^H|ULF;~5mOl1wS8t`b!5-7&p z;uwVV+QT7=Xz6)Beo|vEcmubBdh$s{?eNoAed%++|K~BKH+zdx>2|3v51e=;@tAi& z)06D1*Z-C0D*0H4lJ1n`Q(dGxQqYPSgX+zW+rb}KuZSCbMp@ZGb<1HOJ5fu^wz~J& zp7nbQCF1%FR;=RY%gSAaG)|1jf&86oKJ)ws-CUIYVqxQUJO~<~2AS3o zdZT*237M8d@AhYrgO*x*tVyT*&7-xY$5Z?wV%IJ6A_DF?x5eiSqB_ zJm*gR!+z6E&JG%6sAI>+Pv;LjM!b$?BV7*04*v7A2eQNO=@SMOId`@>J2{vuGqLGn zqEdKQ9B4MA^Y%=LOrouNZwYzAUwv06BQ;aOJtbc>A92ziDQwfOketSaC1Z!gMJjjp z1o#i4N9kA{0Hmsy^s7tXZxK^ee&W^Sp zdn7Ag3KKjl($IgFHZQ}*L0^Mt5`Wdxl|QTs%spsmrS1^GX78m;yMxXpi$?4tSH(Gp z_JDnK3A^{4=|J(Fpbiiqv8t!h@EEnuO`Z-zk+GYnQmIc9MQU}3X@!IncC`)Dl@pN9 zydY4HbGAOYoeM;nsx4trUEcw)KE2d^?9ZfD{2BD00_w2#?UjS zHpWcz0nl;9dr;dZnY!V|eS`>r6i-)k6bP{Fvr!rerTZ$Wo=fllH4wkJfW(7T+7yh{phKMn~tbo=^ z%|G;Gf(J$HK#;2a*v^#Ol0!c=wT<5(VVK@z=PNO8`#?dj3RZ@=c!6IPKv!|)iB*rD zXs=bS+V>cS-_UM~|L*O+{`UFTbA!yNVbO=%-J73LeBuI*&>vf=M&Na@flM5A0pF;! z@a3JYx^Q)|G=6@66S=8KkuY~k9$ttJ=3TN6oekPKF_FVxUQiIuu(3sf!pvKO1&q`m z&GD`hMAVZP6;&%PTbQ>)fYR5#aJ$YwogE?4KLyVtd~Y%jZ8Xk$H#dgp1XKW;P#=x} zJ5~4z-L;4*c!k@ex~Qi*lkex;%%*EV>XFXhBJ1K+`;T-; z8}AMlPnDEi%AwA1BiZ>>L7z^V8OR;(8yG#>KS zYy_D)bWPKzHxsjWWPz%dQe_Uzc=KGT$^UW-{72X1UVMP zxyS&*;$7$+qffzrl~;oyJvGdD1Q^vCWXRpmYE5!o^xe~VJ=|Ro0{N9XYy8y*;6pwy z^jd(~d%U~JNzK&yXLbVw$a!s6_ETG@Nb`K79Th|A?c)pQb@5dN_gff(B|)vW!Ln1nVBdMWu7#%E4*P!{VJ;X;05 zmhhI*?(Yt5B`flZRD>aOV?2#qmfnsX8dp=awLO=}31tPrW5F-0w>1I?>Wq z&-%@)QPXIW9jg4anFe^)ZW3~C8J!cq>N<zty^gy>c)a; z4!+{Uu<|NcD;$#uGRR(USTKp|B`urZKx3MSp8zk9MUFRW-Fkf!z^z|8Js2ncYc(c;piv>QXX z99tUhC4B`9$QX?fJ$G_buCpJ_QtG-!cx^yrKussfY09JTgUG582|k|x^jm@9I;n8a zDTh~f?`6H=tE_+9&pu$NjtrUpc$d&ZNxK8wFF=YsWaF2-`yRE_n7&bYaLODG(fsd>?Awj!J%~r2;5SYqv zew3`0)l9va?&U5}WO|Tr=7GI43f~6y9LUls^L0V$L2-BR9{9Fa62#~B{xLYqxq&Z# zzwO#~H|~cB39q;=;vPkY0+0Fham#~1#Aip;4U2Fly#lRq*Rh!p-i~|}i_jGg(@0`n zhvSVO!@8{B+9oS$?Hx=uYDNt|uk1#d!Ub5>+)6)+OEpP^9}XXnvy=&yN@t)lSA?VN zaNR{n+kBjNx$3ivIvPo-jR6n3k2EcW!fKcz`4CN*D&ufR8p|VJj)`BnKfTh4bR5Kt z_1L4H4SUh4uDB0-So{`tS7~nfBy=E^#0~HPZrmb^RlRB7XhoOpSCRg%cmnh^GTu5L zep;7T*Lc3yzmNk`74UfNsWb}u=cL;QB(U+Q&_u$Y*pMP3p4A8id=xs0Zvh`%{+tTR zH21vK+USfD_G32? zc{Pwk26YzCGf}WY_{O^M*?b7^cN{HX#d@>9^s1b{D){h8S9Cqcz=AaQOKL?(h1&oc z(WQ_IuUYiKMaEmAn-9Y|+9@QAEKEps7FS5D8euk4PJjjXgv4^Wf?B)QnMToz{#As4 zJ&}J~UVo;vc?ZHDayS&H{FzB~HjjRyRewyGTd_3hQW1(W|o~|}6wS192 zkCn&DiyilH^@c80%d4g}3eDn3H{~V~X3f=hPAvTIMRvJQ1IC@5pAq3)n%LkC``l%T zPY7y7Jw}gflT4~*CV532FldohS#UunO#yde4qafu=|@N3xB#Er$ujRN&W_2lnVX5E zO7ae#$+C(zEw^e>b9^}?a7XCcw;xzLtw5NwbP2W&5Wi*1N>{&cn=DM!ZemfPF#S+O z(G?~TRL_Sc;({6+d2H9xb{NyNP(UJ)G0#lkd51tPRy$}jF;SO~qfQigr+)*1o*z6e z1bKflblZ;;8tka4Mcx^GKBWEJOL_R~rB`d%xJ-HaoN5eMToFyz%( zDB7D67TFk`w{O}0Eud>LTkCH>i#6lh!D1%T$+Mw+q-~?^>wC|v@aRYpnqP1I`*Knr znV_&;y>|saGAk`i9*7z(@aetSuYh=Wc71=NkaDmdBm_$q^Su{p##sl_M?4=#xdzI= zAwU-l7eLb!U+JeTr*QZgR=WgV@YW!^Gx_jCS8o-efpRTC{dszijV(G=sfo(EHOC|H?`7_XXB>=)Iz-O)zv?<#wB3-V&Yo0Lub1xC_PmxoH6+#lgkV?^I3*L9VBeI#JqdmT zs!*GlGod&4{*omg_mYI&{Nm}G3aRrMo621i+A;iL^!ZgZlGx0xky=7RG@7neaICKp?NX^h7lF~V}fCvIgcPJ$xCEX1J z64I@tND4?wH&RMVHz=i~@5x&0f3Np`p6&Sp8((y`xz6i2kJyj>cX*SBL3SZg}eq&&vX~=Jw5oq)aQ5W;b9n(j+9s?Eu$(Jo$EIC(d>N* zygrn8X5u_qZ=+;%I@I#MNzlo1!-$WLVv1F3$1mFM62FmvCJ-eP;dZ)wHy`61*3Lpyj&1pXB%*c6;My229ixt&2vuDI6CP&qJK!#6spj-I8Cl4algA^muusmJHO^?8Hb=j&Q~B_MI4_^ydH;vu}ri4fq8WHU3rg9r|ROCL>JdtBwSrA8$=KFC#yT zVUTnMZouTeYt6le1>M^hpuYq3-Fs|^hIEn`9Dd06JSPV`ogM@7L6MBA&$c@;FYi2? zZV(ytp5hzm(zOFlCXwC_($9V^a{uNC9y7k!XM6pRdAtlYM#<*Jd_Q$wc#A&mNj{#L zKX(t^o8Rlpjen%_)u)I^=`WoHlwa=^ycWdJPR3NVO}Cl3kYveW^|OE`>Dg4(e^IK7 z1m@Lxk9+*86b_4-`l@;0P8KvhccE?b@21_om#<5%S-I_Yd{;hBzAWd;(pS1sCyp@> z+RFtM?Z)U2m`5?NNVSwdTNNAWr6Ec3-=i&WiJ_74_tDFr?Bxa%4U9+)fyB}6*fZ6)S+)F{&f4JEQiV=8 zy?(O>tijrK&4{(Ccu5;(aXv&V(UBNNcVaR$mIWy! zrP14wp(?8UN=IlGqQ}6O?o!0wse9hoyiD3lfUSObGIkp3Zu?jHKDPSJyR*4T1SUTR z)fg8a(*yua-Q`4etGOy1&CCJ6g1S8Q5Lli3GHc`b~KNK`G zR*is=F}4lY1y>gt7VNo0cjBaLHe#bL9Gu%F)}`ItV2^FX_~n^i21GA&qWLcGE+vl4 zt=0T%CA1Z`H9DF*@PRB~T9r&K`}}Ai8Tcdh_eC$l4fQn$B7Te5A|agowChf_0@&Jp z2{FqG9x7ma&DnY-x0skEKlMm=MJVP@rPn-(FQYG)^cAleJ(Z>eBPRQ{{Z0etKL7LrgjHZgXgen9V1gKm3mcY8>|7q7`4X_`A4IRR=kG^?U(rmjL(k0VLl?W!kMN0b|lzw^l1;ZaS$& zg&G*IPhR_hVH457BtG|93~}u&b58vn{-OH5u(PPvK}J}KU!xuT&l~E%1dYfKHE&@Q zIST|TIcwrqetD5cHneIf0^z#oY49fyqhkz&+xMA607i|O%q6uH?d6)?d^cV9_|y4D zhK-Fu%iEk@+$$So-OiC1_y|hHrSGAZyBohgTzG!djqj#=SD6C_mj^=Eq7oeo%{$&Y zbEY4T0)PDsUfJs}cYHLl{+T0~t&jBW}Sv@bGY@orD5kJ2H#2#IXd^-2&v(o z*oO?8vb1PR061ugkH*axNjumL>`-G^Fp5P@yTIi#BFv3Nw9|)m6 zqyJ~nVT?ozf1vfn^sw`arc9$2oic9Cus!`)U`RsYPQH_G)>bLOdQpte|H}^?R zrBL8Gy3xO)`VHU&!f%S-zhyG#Y~*THrhSB|M^w@AjZ2|O_~}PlLQG(DRzDCZ^Bx04RYv~(ol=n^ zIjlS$uXWlUOjljSsjr!!X!}sU|8C{(YU;{I(@|)}g0_WoGxoDHRw!jZHk(I}YG%P; zA0Nl5&5LF{E^i;&CaoA(^gbTX}*-V zNL@pVSivX8Mrl~#UbLITJDHi2{AVvHoInW{F{l)m9hzYLq&w)wvk1A0qiFqdZ7m48~vc;utki{AY*xR zzB#&a$l2{MNe43-cKUME#dyXC7*ZDQ)(=tA8`J#xsP$!v&2wSpR|?3#JAD!ywreQf z78UoXCNXq;NoSEMv-)!D?>u=o=A|EFDk)=1_Nb?E%c+J|Bp1OtqkxhQuMNGW(F?pR z1+OFV-NynOft|$CKJN;DUA*;5syXB=y8Ju3=oPS_qrL0Tl^Zb*A!$%fAX>(Vf@f(o zLkmOAWfNrJxXSFtD(qOYpOq`~dNgE14B^P_yiehb%2ZGY1d?=9jAMN8_k8&8hkda( zEx(6mHunxQkA3YViQ_lKy+^aX-j9}hw3wk40=effw&qt#^ScL{Ut&IH%M(5!V=W`K z+_k^sHYFzjY(sNSM9&_w&xAnMp-W?5!9b6O#_b5FI#V#uQG7xZAE#AE-L3aq}O1s*U10+|7Ny?49=o z@8-_@u&tb6=C7DvQGa27Z?2dAw(t^{Kb}!qc@>9@g7>K=`1@jVNfXNYq4>uZ zbpJ%vnl}6L%T@P5#_I~dPVYaHXv%z7O+}BN_`hxo5Q&9w$JMp)@}ha{H0_f?-u{w} zks7>SArjyFF(>MWg(%?{#If0F(J7~o8i3jL^4afPv>4!4L%xo;K0x)=`O6A;LUp4A zwmIL;@gL)CVsNDJE4`N}Xw!MdP)W1v$kbQgbc6e_bht2lsU7SvWa!v=exNj%m^^pj zFT$fCR?mH&J>|Hm&GVg!_P8d}Ww*sLI#aXGgay{(unl9Y)k zUnD9D`D6z8&f-Z^7!NIg$){$hFzFm1LoNUZ)s2a6j_h{Yi*Zgx6k#%+^X$YxkplHQ zF8%H*@NMb;N(o?sl3APqlN}-Uk7t-jp(|?vmCTD3=%xm)6U+KuN_6|A4>a`6AQm4^ zrM~9J;u|OS?kaL@Ew0g$`kCl*U4#Bhy7zw0)~JYMk&CER+#SQ{bDMJ{U^d^A@|KRY%qB z!SfAqj>31=>^qmuW@MB?zu%=> z)`by>OboVXbG0i2BaUI+KcLfmVV^r6gOQd7PH1hIj51}+KHaN!k~407k}6wujSM9U z9fBu`i+}r;EG)B=8s)L27>y#D`LIo=tx;WF`Ye4xRYW1^ngmZQ(n!kBfLrX*u5^!V zkIZzaPOKn?9j)fBWd(*NSFMw8rtBB|-8TWekg%`yw>5CwFaW3eyffB+O0UgSr|+y2 zWG`Hc&S7IKSx9P`=6&l{r-l$^X-`>GsI+l|=Wsf3y~65TreL&;DHgXHAP=97`3}6a z=qz`hmM_5Gq<%D!;hplHY`zLpL3&;1r@4eVV2pDRb@Sol#-r}lS(yBhDm3nEF-KJn zMi84h@l0CIk*HjEJi0h^c0rJfXsnXAvt@&BN0A$ z&F)cW9xr{o-5l!+t&?0+|vzbTcA;_(wXgm{2bUt=7sKGINwy0N(1g z^h>_RoI;1K+~>Z6@Ex>X4sWM^Ds)Cc4q*kP&>^+ah}flPmaa!SeD2^pM%*XJE`nsw zx$XK))i&`~Fw(j3+>;gdueTe|6f#q2TN`dG+m2H$h;G+^_y6%`2Ou=CF%ZavL9vR= z$+(yKPJ!d0w8o?zPm=zgD2S!nqnDr`iz_!hQ-gLNh~#g{s=JS z>Ru+3r5;I?uP5JC4dRj)qD2&5iClJby@KxJ2XV!bO@2a^o0r~yg5|`*SSI4&^qprU z_ec#iZ6Z|nWW~cQ{&?F;$;zUuGpE<;oGknt-~QQ2>>={U&Tbk}G{Zk|Y>4J+7I&+g ziu+{+IA$k*M+T|cJ5G}P<2$@{P#3G`SoofckFF$+b|?tcV+ z|D{O5YBgsif1Xz=9aWKi-)2vWr2XR)LOfYtxhz`5OU?s~%p}S&2CiyS6#prsPlXju zi`4Fb*RS{lJaJCj2YK58AV&U-&m|Xj-53h%^$vwclSwq-d1X`u`5AX>oKMIz&m!V@ zt-?w_x*u%02kn8`_m0k9x08B;7o83=md>+_JWuoUG$hI$YAJ~H17oMtu6kYX4^NiP z;t;$jC>#c{bPrlJg*=CA$YobKewBa!6oYu{M6Q=qyS=WuNn(yDh^x?e+E{m{q3~D< z&V(@>p=DAAnHl>fpuN0bcBTX+Ok)DZu)^W#>d%)i-nN9e!v_ZM#kG}{SF4<9!9sI{ zdi7<=NutlR%w`e4>N%11G_wKR1}e92HZDCR(ugb6=lmrPmKfrD=gK00Tf3a z`nTLg6W5g7U&*hG+Rp^zK#09HU65E*+U~*S1%E>Sr z#oBmA{Nt$)KU^-;wmcPa)Mu^#ev{jQZ{q2^VOcw=?wuq2(qA0! z?x>NNCc0WWfa}_c2ksG8I8n;~9T=GI{O&e~FpFJm6=+3GPurMVl1ja+g7_a$>g6Qq z6^~D+;#Kc;pEP2X28wAsH9+T5E??MZd3jAkDiJ+E@%iyy-33d;Ej1#OLfCD|6GmF6%h{u{6uLgGB9)J;oM^>?sD-Xo&b&(SQPvVGu_EeGiGue#Zb%H=fT}v> z!#|Pk|GvBh;Q`0oR5G%6yI+t6>Bl4?A51$yy8;f8i`n8vt*o1vt9@u zvrHL54!%*n8Ut<&tz+~As2h_rs~+$iZLWE)hD_?qN#9GLs`{)Ko>VF~96`cF+eI8B z)-5XAR|IU^q8S8aC*<)m@3Gg2aHf_BzF)cPS2+`H{7B{rqY5%z6cpqlAPOj6g;{n=&9PkCDy=GaJhJ#X=T6GQeo)T z^9D0{DLO_w0msx5(SB?%;(T0Jg1@1hp6nM#zEzA$@bj!%cu>?18$`($cgS`2Ye4mJ z?9==2F0e{wB4)|2WjEdQm3F&Q z*v=M2!7N`P#FC~kQzxOPz-f}fHT*VHxWY&8d9Az;>+l48UyhyaQyf?JUA~QTehZ>7 zU3?N;7s=H-7NsaAuT;UNY}KfZQV@#jNClD1%y9W~$t_da63e#y2X(;|1L-kyL)ZJY zKm#^c#?}gY9`vp_V|QI!L&@^lVH644oxjoqjno>2UJc>v$h^SU7iDAFf}9fu>u9s| zomtU5e|8&F{~n``5gMguwJxvu{#zC8zUB>=cV*?j z;|eY<=`IzY{gG^y7I!R%bN zYDclHfR3x`9a-mmxd7#b5TMJoLzNXkRLKs)mjLJadn+`W*7LotIc&dm6j50e6^^WZ{FQx@`T}c{?s3WUY%W3^ ziU#R`yp*2<&!yZfHQ$H#B|bIsZB{QAe}r=Q?W6d*79AIc7pWhV)O#1pw&vE>{tRY8 zYmudE|43`|Q@GlT<$E#$&E3t zV)y_qZa>k2a}dC{B=S35t^P=gb|Y}XOO-`9-;;2<-{gdkTU|)4RrMVpG$fqmxp>l@ zW5Bb)COTU2Bt%zWblEUtj%qA6`$53*bgj!^T}Bv`2@l^CKcq;AaM}xR__HbfcgA<$ z&Sa2W1|b=~6P3i$j3x~@fiy%zf~*{CjT(HoYyr0(--%SpG*i0yJFTIn zc4a@$IL@g_MVQCcl)=8Hzxb`7=r6miLhgB-^vdfKh%nZJ?4x!%3bf|igP`Tv7}Kd{ z47tFj_k=TLuJozaT2DUWQ^q3U9Ps;i%VF%ht!i>a zHG=ApRi*PsxM&`(5n3#CV7^LAq(;Y#Fyu+-=+A(nyGc1!2mjz!Wa!7&9kVs~^qVly zQ664Dk}4ta7&+MqQegbv27Swu-vDJcgN8@p;;edga}0cIZLwS`?U~RGPokIq49&6`ZiX;Kk)X?ko&wfI z8RD&yW{-1}B{xZ#3aa8W;iM*U3CM@gn@bd-5;0`(xC$LmoTwtu2Ru&1Y9hK8AI9|C z>@+D@Q0-C;uh5E7){LNke*5CRVvpdNnAN+7?;x^xk!8!DhoP3#_;1-9o3`JnZ40LO z`#omq%cmbaCkiyGt!lN1C#&Iv%z!cEg+V%8-0Taa_ipo06YxOZJ|ivT`EO8pPI)`j z9?7jcVzWa|f8v`!XYmp`lxP}gN))VS|LMHhDaK3Lmx}g=ls3v$&^M=Bl75#j<}=es zy~TF-z~bH^A3yGIF)?NQ%`Q@>+C78$ZriEBR_4BH$84KyuUQpqN6Kf}FFm{;?hBh4 z4}!izmEVj7l=caif^XV2?)Bq)4>uQ{y^_l*G+Z{KzWfB@&Zk=Hu)tv)`-cIlRnDtD z=hwBmDjzv~a|XOYXsN?%N`up6YdIVDpSzgoZ<)Nw--?wc_Ar>8RX|mg{U;}J8?t%r zw^p8Us=bww{7wDWC<*_4DM)7W?&ojc(^RgpvR7=l(x)28Kg#D#cyCQ*q zhuQx`+yDLw^ou~VWre16abz;eR?EC#Vcz~ppyGy->x$AQdMvUG@%U~Qe%|XO60(I} z#rJ?)`&^uA7skvMA(ls0$l6DG4Gm>bP81Q6^%=LkM|6y6*c!CtZfMxTyWj1c?V%Y* z-Z_)N9;LtVM&b<>P9s1PhO9nGmwR4y{d=h`Fq6f<(j}LMsV{7egPc#}N(P}z@MQ=f z*Co|y<5r!BDA|w9XkW`EUI0Ad3>vkHP`U_aV1g>uBmp0e{1Yl5d|3Qyt96y}JXb!O zDALjJNj$w|6OxcMUPS4xo8j|k+c(2&!D5JudX)bQ6OrV6_LBah6Fo*zxe&@CSf)4} z+jfex|0P9u5~o#>!k0ty-H|7i}x9r`r2;{wE!NU7u&W3BYy~$wlH5G3Yr=@@OZX3 zaHke=nQMt#VnX2dq~~Vr$)(6D13F=slkAVB{GNOM?{Bs*p@*SsomTg~MqN$ucCo7O zFza$3t$m5F<`;^7BDloqLa+4IkUSHXk@l$z0g=_Fudfn|1Ers$IW5I|pPpwQkqR8z zRrxu&>O|SHYu(NmU!LD1G8U=k+l>BdgCN^(ry3$NY!LYLMkzZ1X9ir73g@1cEoTEq zc%lKVG6r}QpK!0xL?hcN#>sDmHMETpK6uEH_(*f0waSjG2-e(^#%6O=aat@viFGs$}75}cJ585 zfZHvXilqHve5-srP0Td}UAdNo!2A{-a3hbxsz}Mpv5E~7Q?KdLeOSO9#I^fUQmN{h zOqy8tTe9xR1|6VA)0aoyVbj!{R_<5&Dv(6z=GwE&nWBOkcE!SPqhi7!tqttEGB2_H zAu%e#V|$*ZX{Z;Gow5R7_7pN%FmOpneZA}&_c#rM~^ftMWD=e^-6_PxXl=HVE+SZ&@mP@2kZ% zgRuIpF-!Am|4NjV(Y-(E7t7wZ29NBU$m106_mefcK_~&r0g(uQb^FEpUnq0X=xFKM zC=T8X5d38rX|1b^h8uu3DcNq*M!)ri+-I=B<_lx%0)p?AFk%Mdbe8F$KTwiBs@3d7 z?XRAxn0uNV7dx5!I7n%bTKV^L}qzTFR#vM=z5NpM#iQ^ z{tX_T`*uK~3?|Qu^TEqD2}B^A_dg1{wt|Ue)+J=;hc!df07M*K?JK{C$hhr&{DkO2t5zW200Lw82y$t;g>LN z)5FvgCwY;}y_)NSk~L9o17{)VDd*z4EKWY0YDlD;lti4F$!UAQ%sbm{P{Fk3JlFWS zT|T4o3|#7K>kDzyq4iRzWLeyz-X1cfba=5iE*@=l0dQzApZ)R zykoSZeD;uS<0I;~B=4q6x;wj~sDe&C=Tn7464AT-;qK!-dLh4njb%Mj1|9J=k*IA6 z>=U>Av)xM4g33Zd9M6>j*K#^~ zchFCEjDKCD2YOr&iGys4DPt39EtM`L*9%8iPd@BsH4+y|Y0De%?a(n+i?nXt$X=q! zO=JIP_mndTcH)X-5*geiN!@8MeCOaIT6V_`WwPP5Lm6~0PD1{LjYGj4zbo~z+Ln)? z-<4Fn|b+aejw9MQA`=3G8rs z`grlAM*A|SQ^B6?dv<8_*8{~kTI&0puGssEXX*d{C^ugmTsQW#Q-)D9_wONkX79}C z(<)HxUDvn=-B;B*TLw3`^{Ry$doGKmuf^+2UtP&TMr(!Syz6!8!Oc7 zCtIeVg{2G?upau^{UQuLNS%@S8HWhP@d*)Kv`x+;osAuN>S`KeS=~{ShBSeK9pW;w7o)zum ze9cEnrd%y!C((z&;!-1exa1K?=9Qs}(jpMzyu*1zohe7C?H5HQ+Q{ak+EJN-vMLn! z@YJ95&TuUi(m9#1cp2%nQ`2DvnI;i=kl)Wd;8Kc0foW=-kJo;eWW4(lB3HVLps`dy07JV zc2zH?#euNMG1U^rSybl!maBqSj!Y9NyX)ZnPeW%YvkSL6i`Gux5UCss`wi~T>boH1 zt+Sez&TBcRDm!7)p$T?{y%N?=4l3Rh6As<9s8%Sy>)@6yx5NR!GF3Ma6vI z>XFvBPyHUCc(mT>$QFbQKzW18>xe-${onlVwzmGCzh0B0Pck5|odXyIh(;roV-jtP zi?IW-ScEm@m*Ls?^t2;`1WKlKGl_j67mP?UOJ~#?DXz;sq92AD6x38n#oZMk>2Hh& zJWnr@O}TsvyXr@8;a_D%WqQo0@Oie^&%rpBNh`I&B^TI$tjj{iUnoDF^xF6m#;+Ma z$-&IQXztoqLHHg`+19+4M4RncTQkCVfeV@Ps__pK4-|WVcVh;Ot-jrpjiVE<|G2o@ zj1zN8eC?g=BNJ5M|02lst8l8GHMP>DQ-wQB%Agxjl*Yefqp4je`68I>Baj(TvEp*j zY`QpzWIqp&{JGBAkf=ChmdE}^KI5B;J^PDs~YpLJ>VJdUM!T-oM zTvt6K?*q(ra5C1(F|Tbi;oL;*?6 ziAI)c2VRq;C2rzSy7nQ$Ew_0;{Lm#&6cDubRX`Eqra+1U(2~tX>Q53_7e69 zJEae#;f*LGjd`!4-`wd(%9sZW(G4<`X}w>gPGZ?v9~LEQSM)Y?Z5mWwVskQCrzjN^ zVQ}PHiFUV>WA9;}fG#H@;bl#DvQ)=~QBuaP<8BG;O+4priaVKQXH`nw19S`X=@(y^ zE}A!-SC``!V=6lc^AtYxV<0lKq(g}8+vGk>f9RbF4?p4NTGY5z< zt0#ZMAow(UnZsjY`c>}rU@8?m;=0#b0xI33MbI5eqj+;nH6&hsd@}zIW}YSwl5`p@U{+J>idPQnm?4$y~$CZ=X)iNJOhkv zxA}?wth>i}zVu6&7qKu42H&9if?_d5s@UL*GLt`38UQt#f2&_tw42<`o7Oef}=}$mhkl)wDr)BvGo=lXn_*nc57; zR>_CE1xLb)6`iSdEJ1d@$d)LO>LVg8$J)&oaD^;p6x-weyf>bU6BI?4iZFCRJ*E|J z{K-g&sL>G}dxYpqG~t#M`MF`5(Y%U^E?^D0t6YiV6(#@HgEI=aIq! zT6?U-ecxX2F#g@Gbz=QOjTt;Im(lKY6qq#P8P9YF@Kpc8CY*Yf8P&ugA?u~%y&Xh} zh!He)IRR^dr{jumpFN)|=2~8xh{^l;P;wdV(WKRQHwR9+(@@^c17sG>@qd8AEwUe-ox*f%dl z7{=(IZ`LxjMpoApSK4mUABDKcJa;qU7EprLWtw8tvh)yM;P@tq1_|QtbmA$L{En&1=WMuVUeLx zGF~sLlqO3BeM{hjQu-Jy3BuZsH7%p4i5B(0)`Inc5g`p5$-+co=cn(vyB)z`xX{gr z;L_TkIIBa%PUf85I+Nz(Asah3W#aeG=oUvhRtw{fAPpn$qkf!l5!ur+5z-5Gw>u80 zx}Nk;lnbyl7)Awg*~yP6ylvw>6WRNu*J~cb5~Gm!q@t&^jm$Fb8zuvgg(|ZB)BDPm zW*pmVJO^#R?NMrl7ZhsWwUGHgq@u-HMo@aL5zds|H!0qw5@ppNnCWmVK_>oO#9;NX zya@5hMT!;j;GEl48eKjLgHhJf;^n*8W8(ux4mKN1)Q?v`6h;h1+csjFC{z(|J~EiR zC`$I3>1xkvVY&1fk?zPjb|uJXETqCX2c$iR8S$j>zq)S*Bo(u4Y9Q^FCY@rsG$ERe z;v4pt>!~IqXGn?O1n3u_n7+G!+`?aY5-#kZIg!o9hc%@`u%alkKJ&wP8G0pcv9h{cbauvZ_OX8B%t zti!3D-0FG+`@ zUyeHxiTnuIo7iXWOMDJ`|3u}xnQR#)bM7NHM@AShnX7M#V{SJV1k25Y3=DKWvAfpJ!)gqTg?9k~%64gl% zV6kX1P*>gCuxh$4!5Uj;&(7h0qVAR*q;^M8{jJE6nb=3-I4hKKG=|)dLRO-ha(o;N z@)}+zjVvJfJ{tmC%;BAC8%=yey|H#A|}!fU+EPC*~+xl@wWXlxe( zwUCH}?f8QbvxqD{IUR_NSXC)xrfK%y89}!hzLGW{?S&KTo*jNx2M)brZrWSGnNcM~ z@6p&7x%snN^Q{Tpf?q4NZ_F`h58O@r$&p=7Kc`g26>jAeG@MJM5{mcg*VZ!vl%Wty zdti{7Kg$Xn4rL46ArB$u0DI_nN`dAFv$;yB5>*OJL<7@Bc1p6Ma9tV9Un`57B?$VV0@ zElxR1Uqc{3&)mU9;8T)e>hk3eIcf5mK4OXmj)Eoe4e1hO3J<-QJ}Vc6xREpqY)mHHkCcbk?w!)>IO zEz76sZ_n|wZuIH}h#sw&GnCRIQ$_P&=K+#(T;NY6vQ=iie8?$k5nu_cmCPY}Nm0`# z{@3;JyYpUw&UV{N?BUdcPJ;Yn|z2v)AnRs~3@cL~fqi zf8b8J=8b^p=*5`6=-=~EX(3)xU|SMMuZ^p8l##cfIElvi7WP7|)(IlJFtwl{o$7TD zq2S2(E>E6mY4NXY{W+|C<4RkuFy;xs5bV20JMm6)Dx?dKFS$lw1l)Z)+lsiNo=5Xx<}I?rfzTDvGv?~>2T&wAWwrGlYeFvpVTp}%J)nMS@{&-Ct3U7 zajMsmZxF&R>I&C#QP?~f+ekGdrw+`PCn6RCHgaA&nH5BFnHhXGzz1g-Tf;I=uAeg5 ztredyrIBa?ok)|^s+nl>)O~2x?ev$s`NFefOM%n59Un@+=z3nDw`;puw$JhpMj!>! z3UEDTKa-#S&Tkf~d6)2D_S9hOMjAsNCwwnB&$P=b^;U`SuWsmAERM`mc?xVfx6pICUbv=Z zJCgGKC&moGvu^2xhIMkOcUtubJ4ubZgAH*{>@Q=ruEz9f*x_QCM_q8){kFe1g#DR7 z$YER|vj-fNTrw+@sEK$*?nl+Bpt`B?l^$xYcT{2ZX7F#CE7vN~I?JbE@8E3SClG|w z+Vf@hE&@r%_>o4q$YTBgdsr~Bx=fyq^N9)qBaB%Gr(L9jf|}&&7UURKt;5ncJ%zPX z9*%;0Pw6~syj`)T;!YxP;_rU0B@!;18ApA%oD@Dm^LP2J?$j68r{f(YnXh>SGG8EG zn~U_W*q8OcSqO4Ay3VI=mSeF_(jk(*`uUtRi?uHwr~LSQZt12Tc`Cw%HZqOkg-b^) z<2;({6PTRP&`j})5emLj2V3Rw*3m4_dx;8{IC77YR`g`(*Nqw1Ok38y7l!eMe(rd2 z!gUEi6xZK9&RP5k>)_B(>BMDFP4lLfX3u#`Vp(9+OaI^6=HFpZU-3tZfn$Hf3^S#; zh244ZeP*b5upQ!s_Y`ys7XsJMar%NQRSB&S4d?sMbdFsSXauLlKv2zPfjr^1)V~O5 znWw-xVbpw26CmJXDLg4_b8PDH!{iT**M}O1udRy_GM`567P8x#&n$iCU*A4>@_%Iz zG$3af`-YS0+(S(WA!jUCft?c_B?C=-S%wJyWQ&hP_N6 zrkvIK_WK;}VWF-<0K5Dm9c+tV$QmK;6}CeJF^tGY{ppIrk>lHJ2Cw%3ggsRz@ynmT zsDcQr9Ghai+=hY*5RG5Zfe|;6YzFLaHm{kiBRwEtQ#^)}t=!|3Ddvg*57*BasT2ce z(NBaDk0#l3tcERU$s~Ils$k1OxUvW zpGZCSe#^j|9ftw1aU1tBt-gX>LXxSjKwEAhKS|q?UH-)pC$qVBSeZUO(jAPMUO{~~ z0knJGay$IQc{`&#=dfw_LzvBH%+;m~g&I!)RUe;e#h|DJ8V30{TMv*axwyq8ky*eW zsh=?djhS~|-EmTk+Y8g*vZpU6yu$Zq8g;9`Kl_b_Wb4eUV(vKgTXuQ80S`EQ z0I~zBb%)z({Q?htvRUJS_;%qN{>@qP?)26H6Ja0h@B@eXnH~^0Y^20*v+v8PO1~*W zy&8%C8N1ZLe}Wa~*Nj|3V5zO~^qYxv#wU#%8evC64qL=8G6iLFGlWId?X5wy{#4l- zno0k93-Jl88+(5t!)iRdC0#0L*3p64+Bdw6D{tW1<_^Ws)S(ELQK8qwlL>tz@$h3b z&`WXLiz&o5{w@BNaiSYPLpUp@`^Q_W;Bp`t0SpalqEG&{PXkF2?=H&PLX*7}MI>hInRo zxytZ&tA7gWXjP%olKUa@?kgSqQ9T5c?7X7y1%U9L$m==)$mRPv(B`DkMj}pS=clLd z!@f=Nq<7OCNiqAywBGYA;L1`bvy}exuRmeidTH-&GRE`iz#lM{QT&Fi)B2RN9t*Nr4@8C#EQeszhjCl{p{SB^f(t-^1$w>>2kaDkC=Iq7>oXyQoi#eJ$!6<9ng zqL)UE;RZ+Xo4o35e){yxan!_ku_FH4*Yx|36&KPb1|B@aW>G?H~WO?0rsCLuZfkpG6*ukZqz!>^fc@vyoz#}t*k|3t?O!3dP zW2)t#!MTGTAH^aApc0KHN%ipk*uznPCXK5I)3&uPKa{dbR z&+50c^FUcy!|--)MVdUnl5bh=vn3sx@q$}pd2$Pc!t-MR#8LgSneVPA-WO#Z!ySmL zcR(m#dU8xOs<$n7s}W_BG~c8C6aU&5K&G$!XW>;QVEonSwS^V4yGJ#Q#=vPPP;Xnb z+*~X62*vVvwKqOTfiJ^3SqSOh6r69l%(!sn@EQFP+&_RE{N`a(W`e(wEFg1_?BNohXp8u=lX zCVW|s7~{ft{ZbXhHDW0$%w7$Olk6f1PtIa**rMX-qkU3PLUz zFbvCA`r3<5LEP9Zh)u6!2y}$+IL&whGr$Xc9p{J_{txFe%qtU_=Avc)s@-?HJ=eKY z6t}q(`k}_6w1M;A`#J+YUkQ)(^$1^i-(0-htx5#)Kp8p^_UnnX!HI5%LLnm9vd(M| zXcIMa^}tLXTS7Op=sC6{I^Wr7oyPC`s9d23lZMMM|p+$u$v$hKz5AdvBe_;arY=Uq+-{;VhII$h}znkE&a*8I_!c84OwUPZt-x3w1`AYJj zVfD%grjh|GKlgw0DYt=*i!?URdMv& zTZRBkS<~lUDwM@1E}QMMS)Y^NIy5YYWka~}da5=D{fI~PZf!w?t%qPsOWV6vSfXdm z$0HdENd3iaaN-WAO1{gnhE8%ZyY{H`4Ds(`ePLpLH2Jc!VI^w3S$1}f8YjEfdjoAU zR&G_8yhu~F2ezaUj^LF`LzY{8Ani;uy2taI6q&*=3&@gkoHk5_(sV`UzvdTM8E z(Uu3J#Nu%!sU*>GO^m0MLUtWg| zj#@FpIG_QtVrNnH*O{r`Gb zu3(d#+DKofJ=5zpAMqMSF+GeIsOW#g=DmWD*U6+oSmX~x9+P!VA%n5bUoyB3@k#M~ z&yVKbX)iWn#fzAD|JZ|_G=R=?SYTAbIF_mzPMF_iVEy+`ue3x5$rCE(Cw;Ev!zo~C z$^U(LP)m~1_%he^m>lsb#0aNj@)GQU9YkvBnn2Mxc=mU{wcXTRb~4=jpnz`X`1^eV z3r1d~RPthzzI;2F>v}P#@7;A*UoMPc?G$5|@bne2WjX~_E{#fE4v9~UzgLW>-_N=@ zA^^Hkxjt9+x*(Del?x`@YLKS9n==ciYkuwYnM=Z^hz{BGzTyq>1)aRoWGq58-&oCw zde+z&mBwq5)ziRppJLqpms#?W&)l&(vC_OIA(`RXO4N8o*?iwbE7R3+^WuhVLrx)1zyEL@d( z(dYP4C2Op?fGdY@!mp%jb|e-~^~WDU_!mbzxh-WC_34+xFZ~4YtrsSZ6FDd8`Tq}5 z;RQ4h3~I&+X@ts`uL!E?0^jR;$YuM24eG1&H?TI)|2T~ckXf(?=i71Q^ZGEfPcA^l zn~Y7}{!gT<>BT*pkC~69z>)>wb(+BcN7`FQRo$*z!wQS8MT67=r9ry8JEc*SZt0Se z?hq+y5TvC+q@)|9r9`B=r0c!cbM|xgKKniAyyF|+KRT2(6xOVDd6=;=};67+?UF`@fmN|BhGv$F-g*`)x%3`ZF@j70*W-(`1z{-EQ22w36*V zE9gI72YzFJiwpZfD&Y;A>5hJ2k@C{7@futNRNl2KZDbPlE84F}t+)^%_KzR@KI)}9 zKy98NRiyaa3qZs*Vz5~u8yiDy{vS`+;r(Ba7z8|Go7ND&i%zO5`4P}r?vxIwzJ%ew zAYNk}LajcXswv2b72p0b5e1UYxLm$G`TzTq)+4u`WFC0R7y$y3*M)DvQEJKJTdT$2 zvg?1s`_OL>WFK%u11x>j@&jK@co}|J&cP4X)VQ8D$lULD;JxIM?$Fu@CYSdXh+7Xs zvcv~at3@2V<`;4U6vS@F?CzATaJg>m_8)441Bw4Q*$*&h1TK-ABua-Sr=Zm zm4h^reel4Z-QR=4(X`^5m)?BXfw3RM_tWv^)p*K6+wFYYd@(2LSKepD%||eFgP;RL(#j9N|UYdApT+ zJ`1p)D#80|tMJwoKo<|N<~H#f5Dn{e%BjCTsid#pfg1A_M9xmKnWPxL7Pw#d+_b+< z+(3dc3(Csqy+3aO9FD_nHV3ztqyA?YMtQtgq?}!HUTJ`GG1VXND|`-;Hk?3_cO4Zz ziS`EV>jKDA{|$GRHG%EhKY)My&Fh`=hBMC;{UnT45YW;4!uND)A83}&Y^@i0z2{(! z^2wUMO>uz_qy+b|>=#1a=N#t~ZTGhai{nac6s$Wqeus!26DoX!qUT`T@A?hQnIj#Y z{bFvWb)87>RY0i9J#pJb_h!TD!vPn7>c7Hk^$b1=8a$tNk#mq`1^Dy!ue(6;U!GHm z%>YGc9(*>{K6nyV;Eg`_-GWcPx?#QcznaKiNNKwGI|w7E)0e`@<)zeT@#Lbh}f>VP7h z0B2Txu9fQqw;ML+wR^HEvA$c}t%%)q`u_$)oqzVio!+~5ArrIkM_(Pq`R`u)lyHOw zvaReK_?-(?Tq%k;f0Ge{4O4h5j5UOf`tG|l_H&-K-d*h!WSd2QYSFFAzFDQ;2QAG} zMV|UK=uV00q<)g3kQP$;-#BHn&B6BU!33cj$RH}CY7508OO7ekKGr(JmNsTzg9aW1 zZNbsh`JRLSynSUma_h@?aWvOsaek|xn~xRmx!k^8;Bz5}inkJZg9Ysiz#lMsn3m;H ztTcyp?>+OvqY=D|)914wK=0cO-(~Nn|DP8eJyHXQaI)laEPux+?jMCLV@jrK-Iu;o zFPypwTY;tL7#rnN?L485UV9uybih!7xopd8uoPon$uwIQV3c$_3M0sgAY&N5>0r#_yc2V5yw++@{8N>g9B5uUx?~`>Mp& zGC3xzFBE`_GCNfIYt-1CYx=VjcR^f5{hW>8P-m?0v3#3ONBAo*IF_@mXqg@xu`(Q* zDnsO5bbZ!Fmmke2+hoyf(M-#Fg=n83?w_Sv9nQa&lNl>5L4mjd3{2E9=noN0Ai>zE z&*R_1>Ii1x-IT}g2zrZw+~enj32Ar8!NYL%Vd?IyVQem-5+%UCs+)+}$Nh9l*CS5& zIQ;$=@IvlT7rr^G$7+5PpU|oSWN%34cgnjb)x-^M2MZXRfTN+?N#D>6Dh$K6Z(K_* z@Cp-mS#atVK;@ARjhqc7d%YP!4U9#e`yYp&!=w;Ck{e$}9aqj6c{fg|iTM&8s}pv- zze6@l2eAj9)ha`<`Ycczve=2Zw)YCfZj0#)h)9Di`h20{)bArD`a=1&r(orhZ}5X2 zsI0=m6XT~MF*T{5@L!n>S%npGNHIl{cF`W@w4{)Zith&gBH=;}|3e+FW3HnMBCTr% ze&FMoQPXi+h-VR;?&LY(m1B)_J=vrQlK*;tcYW=oC~stL4$C93#xrNCeNEjbc^r~| z2FgfxT9j$lTW-G|QcG?XaTY~#PBBve+DMe5q8;KWgr+4vWdK}n;Z+7~-Car|vFsxY z;GGhE)btt=cwU6Xm+&5I!fY0#U1oyyP{V;A2DL1jI(n+Mku&HUrbdd_=e|u8AjOUN zA-kYPL5T+uC=Vr#+KM<|CJx(1vjMrF2^<30TaU=ry4#%j$JHF98rSLwW*(Z z0Sp`OU<+=-#O{em%`DfST}9EkobXZnDcDl1A^r<&|2x*V$cL_Me#-|2&%ier#Py!BO3-Mz7i>L1+mT2LV-im`uhb=p}$Q zZK7YxagLA}kgmhlL@RkIDUZui`GnU?4pg-U$LcjR1*prX(L*p|Bc zQ#9(C9DY=5)ZcM*))L7d$>R-9Fq5VMeLDNTsW$gb_}sE?>oH-R$Ql6x&S-9ik^lfd zm--1RE#jeC(u+2PidqjZpP~nmxDENwsqchbodppKl15XPL8&e97-KV?aO+z7E65(*lWK`H_yDl;JeGg3o;2C?9#*%>9JjSp z&sw^{CB6wPc#uXDcTc#Csxnt3uSi}*st0RInmXuq!~f3mwb4$=lH{wqgD@sjHTig2 zEUix({aqy2uwPtsEno<<20BMgB<0Gsy~7}r_op=G&qdtV+!(GitKUz40KzV)hT&B5 zurM~;=UAcQh6Q=~h5Xli#??C#qvZp}Re@t9jTfbpc{Kebf!i#;#CWYkRL58dPk%X% zmApq{s*0xgV`~4$1@%p>?%f2keo||{UST>peKW@*z`cp@bm`}hyNR2{+Cj}7$Uw){-w!zUd*|Z z;wVQVsG7@mq`uR;<4!}9IplAB>)#)pe}YwUJ|Kh4zAnKUjDp+$LBZDuBG9BX!zOq} zJttnY!l$C@3GmcSje$K@w-j|wC{!X3%E?@kQZ!FUDjk)iYcz{r#xAc5n7~i)2$dFe zV230h513@m=L{Ez_P`v1ku}gd@OXhPaSo?N5m25mqiRB>s52$<@CrByx4 z&&m#!S|$!O&>NY=FjGN&tP<{)h@VivJL%21vl1tkb?Y@(Yi&fzHu?=a4@cH(VA7wO zRElTiE)WuXMPn)a+yy-1;AKVWt0Ro&qs;1Zjyz4qE$g|PT0*I zVDwABk_fkW2MsdOUvCjP^8~((QA!n4r_tj2*JO+Mbdxe*vbeCOW^D^s8cU}by@JCZ;^61VaP>m!^a05k59r7K7nbSN_y zT{QV~6s5Ae%IGCR2x?56~$?G)(T4c?_YXv(6xE~i4;vqj63xaV{4NMel{ zo^#P})nheMx@m3eu*CTo5lbXr#=k{3;ZIR-gLvnNu*aI#QY3PAZ}xH$i9auR9vu{I zJY))e`hgg=G6yT^c@F{yL8-M+?(YkDhQv3exE6@$TdPNpPV(tu#wkhFs5!^kV55p{ zZ#UH{ANHW2g;NJmqT1maY{Q=_y+U;zj%nJW_8v@=lA>Rnx>A&%O#qBCYT5bR5yl>XxIIoJ;8gD)P4lIy0Ld%s`A?&_rP|EtK(GV7u^G<6lUYO$mHe6qy(LpKq7H z9uajagesR`SFOU8&(=jFh47*uBrcRfQKyFf_6_~d*Bc;!Fu;uRbVyl&Eh;7y0-_sn^5pTxk;?D$J&`+5R^?es3n%!3wTb@PNj&ub0GBMa8mnu)|T zNunc?lAZ(71{tMVqxkxK(O0yG7~Q;`39KtvvbRBOtBt}z z7ek)(t1_se(3di#I&Bk-fh-c3+*`-+zKbPtSTH*tLE~dEcQ^-8n9bMWN!y|!^eW2V zURk-G$|8|A%+e}>q*fgkFCh9oQ*|>&LW4vn*uKc))|8DeDf2&vcn%9OVBmX-zqjhF zmX!Xq7+%61EW7SYK_K2H^$oq}S)w3EqK5{i<;Ya>3>(Q{5#p6jR>+BkMjIdjO->%U zknU+r4pRT&e40#pDo#a^LF$hq^5?rnn(>)ks+ixarzlM{GTwe4?fZn4MRs6VZgC&M zNYtcBLH0lz)Uueu{RcHMeR#zX8K)fAKCb!`ZpZ1{B&X3Ru5Mg7K&?$({SCu^_d1(c;_z z(ZPg_DK^z8qq)2oXeyHj$K%)$qVOyZ`emz-i9-=o3Wi^iYq$bxf?H2eij~U3#q%d* ztqC*<2LedUTS4|WnP|3i0H!gLj6oj@l!E%xDsH4(2h>E}rPB&0zVtX;7aUc2iK1r7 zzK-eVE-L=ZkGK+dV5TO}MkD`Qw}x*B7~IYE3(kY)if?~~j2G+ZV1b2yr4?@wDxn1z zE!xK_loDrf=EEjR<_yR`p5xp$UL>om1BFhZ5R_sS%x;l#mgkAQzIb``vJk7*T(m$q zV}Vbn+}9eFU_Atz3S{*PWiOof$vh<+)V=WD2A#meb_z{qun@)@wEd4z9se*VzOB=! zh)-zG5Jk}eaL>z{V?^Zqd6;G)i7A=QV6IyvOv!M3CJ($|h32?g&XqSQ^voz!Gscfi*(1tEpk<N&05R&}s`n+3|JwD_c89iFSv9Q2Z!OER$A zDyp_$hm~BHv@HyqLQttXlcq0kq;W)Wr?$L}JBYYTqi-=#pi8&snA5b`#3+D$z#lqQ zx9$8A*9;Kh)iDA|;Clj=qbjX2QWiip@2U1}%lo}k7Xx4r$rqPQ!Qx}qHP zmFM1YnoV;fD$y&Z4q>|>uWw*3gh%NKErY93!I1Dyp_#eWqX|6^iKu znBE|N!fK4J90H7p_i&;yUZE}o#F$GIr6lRg$E(nq?*b+iPTCG8OiNGu1E$C*fM^^g z^!K9yUq)W1-(ARcy7HO8rfz&@gZ_?TO=y{`h?vszSHNtxhTWvJ)+Ke)Apz5-q+Q5^ z_ay7)ZrO;#W|bAozty4b2M2`F94lLa!dsFC_7G9MGL{tL+2=@NifyV^ zD*GU4O2?2@$>Mmmf4>(j3LuBs z_K1s5WVV};i*JF^>uAX=>s8jkObWOs`<;!lUD6%tNCvPXEhm zw4}fta=CO`u%cG%YV$FbcMPZ zxBn_+|1W=q}vn{2**C|BWQiKJ&}VNU0alpdZNXD!{#*Cw>8PWlSdADS_Os=2V*FNc(2a^6R`!i z(^`p0jgJLy>-6(cOYq8+rz-z+>ZN#n_^VytPYpP*kWH%TOhe7tn4jDR-cfHy7Ad?0 zjK?hV4MoyC@CP$plSL+WhGMyZyC%$Ozm*S@gM`W5Cbs!6|5e};cv3F3WadUGgnRW=moBv1=IFuTs zwrS-FLtbnfB)WHg{p><+pA1Wv%Nps#K=^{4fLD@}?X~^^K8rGF6mr-KbXd7uoS>ju zK{+`wD;&@lh|@y;+$23B|1=&Zc$n}LpVLx4=OeaR0ljGBxFYjq3vJJpBiN}U^6nr} zIn?%JvjF4TF72A(;vePhH)ZL^3s_zX)@;M8H7VQeJpuRb8BO815Zfee9qUhDoAzhj z8^jQZSu4LG=nJ3?$$f`$fh+ERYcu}auWc^DFG&BHilh-}5k&w2y$Wi9w-@iCBS z-V{u5+VV-b17nv}ROb;qvdku9j#~mum8G2Ke@_J$Azb-TkZzBM!4w%c+;a6D?{Bzf8_$fsdj60w0=PZa$*gjdf&i(J&4cQ#kTTGfSzO(@DC z-yi?J8%F&*m6S^hh59t2PO%jYyk>pu&g2Z<@aL8M05|89dKSp65_!zV_fc5+4b&)v zp!F{w(DYopkdQZL>s;c>X6|%loFVo*YzV2#u9iXy>nmwB>@3))%H_g$mkuQ`5n~H3Pv#>aTgWTg0q&c z_;nic@gFAoidr9F=*$xW>v#=2#Etxb!>;+NL~nD_f6;BGk?QU+Y|NqHPZXHfM63Pg z0oM$!ZzR}dRQR~dyRgO#-;aGn8uWr?c)+*%$YtjL05Jd?z@{Q{&mir9x?}?GyJ0-D zXWCAtkXh4Mfu7t~Mw34y**`9F{0uLM9c6TTH3~mu*I-E5?z(dKG%=dQvg?bHL+9Q= z8?IRl1Dkz6YIV&S6PTyB&98F(Hx&QB)V04~8SoPxvDu>iGTBfnX9o(Bh-GG>&iWtf z-h&X20zyK*%+Xw_Fu{Q`z@kxq5Cyq}V{gVGvur-g7}(tn1Q-f5@LOgc{8+c8@w99A zCkGg8&6N_kRV=r}MxO0(r^D=HYFzpxSXAUFkeGHAytU!82WCoI)`mP?ty6P1W@sU`3D2uU~VQBVFW&!AG z%T%{N&s#SreGc38je^9zLGF$K>Ia{SzHbCbvhq4!1J!O*4vGSumR|#4N^LTiU-V7N z5(~&cSSi-pGS>)y=lh3Cpgrx_4uHse(>~~w#9-AbcvRy7w~MIl5-aVkm{aXB2eK$u z76tbx<43D!$avKcZPoynf+Wjq{!(WSf_CPWkVJgJ+czT?&C)UYC|91>dku@gx0q2} z|A{FzIe>Vi$@o=Jwa4j~=me%q+|s{l%ys60Pp`;v-{Ub}g2#Q7pmCbbkTsbM(}`ia z5^vhrw365bx;+*3+v?j&<4zk!+;$z*P->uC8@$@@myUtiLT0nE?y2bzEfocsE1&fr3tusq$d(lU?I0#YW~Of`TmKxi5dj0;H4D&3&6GZ;n?ni zgTTj2we;t)@{7~-=X$5FKs2U55WAZrt8~_101MQjn*Y_aB|12!r3!z5(5hENuviY! z?`K<~VH&DMA}|L5Aax5RX@Gt76@RM}E(pTeIBcn2Lxsa6u zb}xLU2Uv1@+q%{gv9SxD(S%Qe*!NwwYSh*VjATywmW$s}q72C-w!;A0w-HC`ruHVf zgl0W`rSd@yTz5WS$+oHMmge|ht%#S|yI2q3N!WpMnz?4jm>l}g>Ggjy)Bgh1Ya_v7 zGL-rL^MDspa`DF1kW}zpwuNt<;5)f%3sHo{@9WQQD$DN1alZiRp@js)C-A%EQQRM` z>-+b6t?B!`T|*9q^EO?_rl_^C@PDcIyCxV0|`#{2+gQ*URU?iRqYD(4gQsZOP=2V)N7h+zTj7LuzFwx_m(s%83rDVeejo*xLK+XxGot>lUE-aY&Z7OY(<#elFk6 zm8uE*EUjev8PAklAH+$QigOGKX%Bt}XbwrwGSiJb^5c(R?LlOL40b@k-v{oEMi7~_-J)C$xQY>U#e4jWns{ityWag-p!N&0Q_0zZ<5cI7?>pvY zkMH+hvn{IQ?Cm$~saC|k!JM%3XgQO~nm>wpZRNkm5LRIPzp5x!aJThdZX30F_sqvO zWAy^z;VT>M%g~l*IR7|X+l;>VN`zw1Zm>0C2soIg6UPnfPnA!3=m zI)r8*hRGw0i7wQcZUEOngdZuY*-{lqDHTJE$O3B2okRsfPQRra;0yJ{8q#6j-GsVN ziY?%nhQM^#WEK2zAs z`O~9o;PUy&;lKu@X(NerANVYVUu!N~p59DJ$jQ^lLx!WCXs=X6_Xu}B;C$&dC}-;# zOAMN2vi(FNL8MuY-FF0l3?ae|NqJxSTD2 z*@$!zxgip%IukGdR_@xMGd)|YJCCRJsJ}WzzoS+UuguIibd8W+35vBGx0Kj!up_{zxUGriqnCG&l`Qeu^V-}w?&3;-v4&SzY!!G zn(N<$oCHfpTy9E?klGCvyN?g(mm7_qsunck>yc|<>|4pjQNBo( zC43pDNNRJU1Ukmpwi(%sx16IDE6hB0T@aEXrJ```W~nTYQ7Ru_w(SXGYoj*-B5DkK@XN% zKw$A93>Gfost+LLyIFI@&%`k|UQDBw5t_gaAB_&+@}D)0?vEaZqkeEj8-czFK9w>w z(B~=tq6-s&U)r$>aQi>bcRi$D!Dw=N_e#vV?|iJSQ1|5?AfnebXjfv8v&w%{k==R@pxamlJEI)pmc~ZcsE5Qi#6= zm251hO!l@qB98POw)LRNEr7h>$^LravmvDaLA}2m?+8aZ0=4Jf1Z;DUXaeg66{%$! z-N6*6TXY-=q-7;m=&85dxe!6QLi#-`*A;iOdE$cL!Zurjw_6k%f98y}Guy!b zSFk{ysPGcMgDKx{AP8<|jC~9C2RQyTCpS}_adG+Sp?(ya!78gB0~jEIYmdwot3n_l zREB2X?pk8G7*MJ{f6LN(@!JSZ4=#mLoW8auLAb>N7jE)Q5k+l7Tldaw1e^qOXnGc% z$yIypeM|cv_0Qv<^)LPZQ~ldyL&cO1EWk5ADHw z!go7*QM2UOi8W^Ok?Cp2i`!f5i5vI4;dU@)`UV^PKxfaB^h2=%_9b)D!A0DdyP0fR z(R>_f=-f|B!Bk3OhO1%1Dn)=KlE^oEct{1N+4O7vI*-+d(wCLWb@+L-qY)C5@a#yk zYB6x7R#?&Vf@x+xF!(Yqizoo8W(}htQ7i^kP^D7{oJ9gl;7Z%urJ#B3RH<$uv|AaJ z&TDVb`50X3&4%F4v-Gl$Vy*8B*Jm!P420WaUEYUQ)(>$GnspfuoDOk~egRBK3pX2s zlVtcxW!TjMKuqN5nI`#BL2XcLA|p>@wRKjdluaAyjB%jI(t#((FZ9W6xr1+MrB4wM zFX7YWH(a&U>|ia2~V*WTNZ!R(}R$) z2K-tJ`JaL?xhB7gpetFf&>~@MFnjrYH zYrU?S^A6#M4h8k?@@H z8=oIfOP#-uJRjos2k%}J_(oI-;%5rt%nC z!Y$IKG4fF2K!U3EwWeMD*}|H;Cl@jUa|~;{Yk-(`h5Mk`ki9jY-hr^gW;N2;!Ya{= z@s!rp^Dn}^q7oIwru>!bbnK`By$p|U<7$WkODp}>7tFvE)N6oCSyV~}-moO|-3po0 zIzQ#FtoH{!_|08{)p8U|b-2SsS!OskoA*fGA6-Lxo;J01)YqXCn6hMF;nCZE@Mx6N zl=x_h+J1OGi7DCVkf_$Nk+X43RqgHEDPDDW&w04yw*dX9^0|6|32RE^dv5?-bHLgl zj*fskB8*dD;Ut!Yy9cE7KmG50#Z(>FJ4yP#28yhM3BLLI8QV|(b2UJL{N9Ah-Sm2Q zF=6`sNx){}3!DT*=BdNGGBJjLN&O%h+a1BSSzGJE+Tuj6BO~U9wV8k7LFA_hh)!&u zd__@cBy^V4PUQm2Uc)1Bc!SbGjI6D){ipqsi(n63YgWET0RjBI3YUhb^9o1in`_e+ zmX|Hhy^}%aJr$^C27`d_4M>K{JB^oBf5FULgZYI@BXg<}5ND8A!DH8lQ#n3X3iFTs zMvY#+374WDnUFyqL!dX9oMtC?bJD}i%qz7Em4wez(se0(>2vI(8#UpVS$R+%Bg_V3 z&`A}7@9zPY^8BruwOkuLUK(%hNvDRyz0Q6K-}U5xT4f8yADCmfg9d)%%8@UBdE4C& zxc!Atnr!F;C!gNs@^Izo6Ef@olPW~)$b8lR~KK^t5seWw;Hf+0^BogzUy|-Cg*S9e8;3 znM1~wlV=KVE*h4M^)bu4c`Fo>ft=cx_5k)7OJMlPQ+SuWhMGe3vFWG}O`$|2>5jjK zxa6^mq*uy5Uz4q>Tp3#dvzi5BJB2eOxJHL{ogs&?TBDQBKwFs=f5X+`t-s(np?yA+wlHcWfQwCbQ* zCk%=rpg%2Reo*OAsFD&xy!$M~amWjisUVsxzDIwMnDiR)4C!mzn#lbA8D6LS{ZD0) z+EOe`0+6w@Gu0E|IjBn8hew;$81~KBdh8pQ znJR9y_X)7%q+lUKRt&drqgIchlw!J~0Dhc*f7ZWBDmg+>5-V?x5u~G*c<}|qcOdOK zYyk^Az%1vcWjj@=_f}jjm81(`q7bwCRBT>(QTxcDqz!TwQi6(EE1 zHZ^lFtMB*n@#`fn$ToaT>(tclC5RE=L0}xw*Ct8j6yYBW)yROnut%2J0Z#W>)}P9Ht;nK4Df(!!ym4PTf)@*#eQ#oK$f<>zUPj zALm#f93CN=pohB^vIMI4Z)8HLfuSXsfHfixxw{O1ps;FVo`~a(} zzl)n8sSSh&F-TJ-M$`rgsFvkf1akN&rb+m;he)x_$dEXMv)U;4?iRrqBNHlt?a#8`9L#| zpG>MbIJMxK%sQtle;$8i@=v312t9cN^{maQ$=nTCqVlNPK=*b8L4FkncqgZ@Orl|> z5xHiBc|x(7MT8L&7yLVAHO=FX_6S4h6SGLkIC>yGL-7yLjVWnqIS3jwaLtGEVXVzf%fpd zf0T2{Dxo%aI4fvDZFK14-@`xzZ`#)@BrgRZU;@qGHYqKtR+3~ytDzq054P?ZTo19GPg*C{u|&q zcZ4@9FR7xAMAm)R9oLWLQ z3hgTOAAp)le@}Ley&YReZ)TxUE{CO&DCmYDGtyLs(HldyL1lg*WBBdI=;oW>zU4G} zg@G)Qc||0)rWLZYR;H`(>YnWAP0Gwxd{o!tg_oa7I`izexXOV!1`rAam*`t|H>G$~ zf^c&O<|Ub}CEWPs##i-w@TT#-yv@gRaTM=io@6!&uVfyToy@M_RfgX^VuIm+3*&A3E{U;b z(Gq*68LDw%Xd_ZvgQd0Cz>D2QXohmd5AtBm?eJ)wxA3D8%U+OFz~=+Sva0r>rdZ#+ z#J>=~{?s-Lha2pUQ27@-IONi4%+^Ul-RrHd)XwD~ntjo?RSVjKW{_EaXGVLbHD%#D zTJJn;2*3AoSrkt*$;RUh6m5>Ps)u9}plsSD$`(IzV8F)`D(_A%hR~~2j`SvK(%@v=wypPA5PeykVdCd%i6u2 zO~nzI-xxul;#gPOAK=GVnvLRVx?9GMawBxv1b)+vgM~x=-wPQ6i7xH~non+U>(L>? z@KG**Du`?XrHAo?zxpSze9SYuFwcvWior+RG&GHxBWxv=ugma_SfF=_5 z?y!hoO~tZ~?#D=~7vG&yq|z2d9A8INpn51Qs3js*#rRg(JW$%(323A76C*jVx$yse z5XQ!I{^a7blSAOrlRMIdkOGo(om#>g&yyntvAI z1C7^y1qRv+e_k}SzVrplb6eQhceMAdNpUubC%HCe7Pxq8>U}Pj!*1VbkAE~OLYaHw zv9yr6EcTur?_H$C1-VC)_imNkndKa_{rhY4eShoGUp-%>^ojJ%aQ&A;m&k9$rVfkO z{jxZsTLV(@mO2U}xf!W^vuaQFAD2$Qcv*W%f;=4E_)7AX#ZAtZ7^jE&MlI{U>x`j; z$N?2)Bwp7s?sZG7LxZU>ES~FbhcT2*)~Lyh67iYOz@dn7^v5<%x+P&t>g!~9XM9rs5_v$s;pI8xs~D}Sc9Q{&UabaZOIGbig^U-%Fc<7qE_wDniV2(ZGic=60xXRK25`EFkJUsS z$0sk>95KVzt7A-x+!eC~T$jbzP1<`N#^_LWfP~ai9r48KPyEWx>b(!+RPpgxerSG9 zF?z%3l3>BnDT$Lnja?-9W5pY4aY+U-Cl9ZRuk2m&3`Km(>%t;?YOJ4CBXl6{Xl|

S!w)4Cq$}H3mw{nBa4x$*sw3j=o^HaV)e|WF$_CogO6TugSE<7<)6;Wzxu@T`dqY~%4e1n`PD=CLOF3Md4-p86EW zDOb&>V&-4o9nG5gGLAkK5#Ot}N3YHp2?JNW6?HU+UlXH~0T?SE$b%Pk5+EGwRzX>B z(SG?S&acz?cG_T+vBz;i_WTCt_seT^VD%iXz6Qd6wZ)j7Wl+(KA~TJ%Ig3D@87K0R;6C7E@vkUqA#bHwNkg3US z$ZY%bTHl}96jpv*M1~sV{`O1t@%IMX*T9RQtKrteCPWy7SMpgcI-ClD+|Qg{Y%j*- zyE?X5?Nw)w2d7|%B~P*U*7KzKMDNSv2*c}rOeo`v&Vlh_T09MnhVIIz5uit2>l`j&diWDkE(8by)fFOc#&XMiS)p zDrLXgYZXZ}zIB{U-}0mEQ~UgWzV*bq5s1~~{hTOc0OttGN;!IDGSfq-aTFf+=jRm) zf`t97kikjky4D{BW-L(Dqp!=pin5S`c76GHg*)i`e24t^>1@Lwx&Iu5=tknbzB&8K z^RY3g!~1eefp2(NoTFg^>@G~XSHmzns`_nD&aJ_>myi2-RL2bF#J;uwU=q+ncR9BF z)=#(+)YlRnP3Xex2$~H%^sPSU#*o~sccPh{cZ$+(OyzgLLrI7BcR9!v%LBP-2NnNcInf=zz!s` zuJHJ*pYU#kzsFWCIbq&X!uXZ4qML2EOC5{ju%G7f`7C~0>&*2&%Z*1k$DZXE29|sa z74NQ!HZBePgg?(2R-0-q*L3(KS2uec`OCaP*@dK5nZ-6_^<2jT&keh|_wj(jxEgqO zSfmWqB)p3s^qfqq&HAQd z59`PB_!JFj$Xq->XWe#6D-pU1AMG(&ilU-y`X;)&=@b*iv+$HCpIzr>6#E6h{pX%r z|KtGn?sQXIyy^ns6^ifp0Lwvh1C3>muzbFS!>!=p4q}o0+A<}YmD%ltw|E&AL73-f zl>mwFJlK3*bnzM8Ve*SJFYCs$E2yC}WD`kyWxB#6Fum;;IDVNw-bjYLXG6SOr<@9! zi?~*GQb@G>XLGg$oBn%1$Z}5uk=DJEHLEz;_f2BHHI7Cx8EomyOP^>8a)Ko_1T)9v zw-0DM>&K!&09&C zLq;_Y>14=@pakUaA_9sySbj{yZ&{$lJBeJZtY|@eCs^$m-tNGp-#gu!g$bVxFF4!! zU(TIl{2P}8<@XCFDS^okp4UoVGALqrR;ci9_HjdMQPb@JiNQ{_=L>JEcX>1O&iHX4-DbB@7 z__7<-LcX85CeH<&l-Xt2Hbyh7mxn*@UxX&@V;Fzs)`{%?cKXJWeVGHGdas>>CJK*< zOdaSz_Hm4XxNT3-X45ZMarSIZ5tLvVyex(A?i20lN6gzY)(6itvsZf`@zR*69_8zW z!xJTKT}|0gn#f3zA^}F^hpmMin};q5=qaJuMADBvOD?xNg-KMl_p7ET#yoM2vsn2? zVtcd7tmOe*44_k(<=D-ZI^)u+#0##6$6K1d!>Z3S$G$+LzR9u)Yv--IrgLBN;vLF# zfc5ZwLzE3p?R3u{%Kh8HD%MI2=n~;~fCL2xLQT29H+9_~Y6r)B5A()sv53kgtvq)UYcSS&o6s?U7+}N^Kl=pA`3pK1J!0v zXS_={V+9r&%y_X|RHZ|oT$H{Fhlh4;fd#*8j7uTk&mNx<+J>>stG%Bit-C$FN}K6s zig8-Q(BU(Ph;!{Xg+`11pgo&c8J_>DwhV^Zf6_ zZXyT4P-0)V@kS6!4qO)5bJ;^Vl=-X#Ss-4pI!TaI+}8_Wgv3LV4=_G0*Ldva@Q|Zr zOHJAM6rR5Psg4abO18tv$omeB0oGi&&Z~6KZ_Y}C4%r0a(+|{UKgGZzoA#OTB3v2= zzf`k53eoaPKR(&JEs^Z+fq-J`bPsG@(!{ud%~jUpbMxy*{>u*6 z>xue9Al3I$nUd=xD!D$Mny2->1G6X`kJGJOLDn74kGpx^T+JL5GXp^4@GWO-alVTk|?7`{(6BTvBgv#JLkn9h4d#Ao>oUV} z&quki{#h>WRSNLK>zs}#KH`>b#%Ke5LiB&)zoa)^8iwvUHl$d!+13`5_@3w&;CR*~ z)m>mOicMrbp!NtVWQy~jVSn1CgB3xqPcQ|~i$-Qd7dLkh9JYN2k^XcY&D%@yw+JT% zf2u}rd>aGCi5x^~l&WT?gb53VrTQ0nw&5zjXndK0w}1OSM6^)mk2fBqh|KKaPGT&Q zgf>eA4r=IdHl9%3=YdXS$eQ9}ksgcG*mQ;cy4p)fM1RKp8Wx^MxkEkL%a5Y9y7!Uv zzZT_dNCgNdK>vY|fs35#_F=)(dmYn2KNtVBFD`R@4vF>sqE-92U}6Bl6Y2@)l%pv< zbN@(FrD97nfuwt5A357U^~ih1)fwDmJiJqWGD&&FqkSzU;z~BU7329s_nZGvt~Yf* z(C?loQm~YE;mNG89SJ(YEPxZ^JhNdD#V`B2IpyE-2{1n%8(u#5ZF%g$@tLH>{;1g? z%RDRovIdHLRv-8FOBVIGD%(Q3GE8?^VrXvAdIiTNXb0;<^-_)k(wq)Qzuv!%299Eb zT;I75F~|wBuo-WB`kAVyusBlI{VlV0k344v%fh^C-@?lx1Z-XPO}j&>e52XY$B|X2 z{xFF4Pjd%*fY<)P7>@Y9o@ihY?Y=pSwTJy70||-cJlZ3_hv?D!1L3C*ZEa>SY4myS zYkRvd138nSb)TB1RRFx5sGdu0kB-h8*PY#Y`mv5!JuEzNl_ZI$8FoBTX3#M0H&aux zdPVylUhOsOWu8GhwGJjrdiy~Ij&ZJ;Tlxon94uK(rl%-2Re9&Yj+7(Qf*+eT{jS%* zLiRz~GrDr7nG(mO2+8-raF5d;@zYNVG@;=3&5tho6_Y`03-wlZI)vNtbSmf5ABPRU zq22cjS@IukRMj4L#upC`#2Qs_^}xY`z8`KcTtFmsCk|-J@rE9;4jy*^)xox(USnBD zv)EdAyKcmxmTD*z87vBQ=^KaW{++Xj=)iPG2`|6MJvsAQUVcTH4Fa^xa`RN_MX=9> zwm^90c}1?lE?RwJmz3J*i1D1E&2YpdaogYzhWr zL=O1!)Y0m3#g^UZEXRB%CS3;I>r{2H`c#zIh#%ILwUF_mvH;b`MJKGJ-9Y)f##880 z`^mc01no|C!BTzB-aNs&L?k?Xu7}T?PV==i&q@ea_98}G?R-CF1#g_#CHw_@LeAx8 za{neOmAQ8EB%G6Y{REI6(KBF;NHn!kPdw|#u2=i*=ByjYf0}^M{FOq z1mc5zn+L7Gf>PqlpNA{7-5(UTYj7N=%Z7k#b3VT&Tiz?x?IB+uZN@|eWXPGX{=mM( z<4e9As1l6q()jsTw}&)hGfur;0vO(e9*B$wOUkNEMRJ=1G=gB}N$T*AYSA;he#SE`on~~> zHlVhHp?G)T*8vmpqKeGVyf$6VD)O@$D02S_BEj>EWE83+wD+r`O*fPxAAR0+hAPN{ z%Xx`}PE(o8%;dxn6=gMX`zF~-r!5Cd(s^zZF+Gj?>< z1~%FIBaOyq)1JzqzOzTB^JZvdq&bJ~K;XWiH9actfG_Ono=NR;ygiGr!9+Kxot$Q} z43_6F%=LqC=hjF_ada_zo4TmohkO5>MbQ(%?@7^Eo`>gN%gKDcJPuYkkcJG3Yw)Ks zuFvEF$q@P^PVg^hXDIpo^JT8Sls%$38K`@qp!BXoV{GFR_Vs)hQFO+~KuMhl!(5fu zc0hl6M%`O`V+}(wNciE9niIGfF)EV2^QXafR)q~41CjQ!4alX>bn$al(^uPadrv<< zGCWv-Np0IuFQ)-S0D-nZ9}jKsmdE9X^Mio4n{=82C#9}F49A-7p0nX=2 zK90|y_k7!lsw0i!mVMJfxNy-QKbY>}@p7{;!%792)}nhmo`adtdL%mGhHO9+?8it{ z%j7~iaXp&r;J^>uVd~n|-5&suHFt=9nh_jk8CwATdFiikqXo7}i|<|5G5ygJ78mI) z@R8h7`)yMZYa8_q4)v}3cu#DTWO9YMW%^=)TN#7mINNUKQ$xdf*H#7P4PFZ4AKf8V9v0znqeLVIAE)I+Bm5 zU|PL^M2OlnU)Cs&$0EN$Bf+N4J|k|!b-EoM-47=ato@g8)Uc)3z%0K0#(>rCFG5-Z zrQ6hcOC{Lym=5z;S$tz~(Y~fMj_ihy4yGgI%f20#^O(!~yD_5sfKGqjW1q8K{UXt% za-eX<*LT_i-1)liYhC3%U&)&~(}SsT56b=h*x)znZ3gcHRNC=4^6qgd*&iDOVTUm8 zr&xRuHS})G$2^KGx!EH%5c|0N{c)K;6ue4F(dC-Y2LhF?5Q)**V|}?6_J5y(Z_G?W zNBXud&fh!WUhUJuVA2xfvbTVt740g$vhzp*6x+ ztd?=?pE*XE_jy9j_GA`Oj`lvR0-8yVpAJ$_=hCr}RqW#-5hw5a(?MEYr_=YT zpZaT%JW#L`yN|zu^Usy?s6(&j?`Et1xCKypXJEl<=YU8kE(^l*yLt9QdV-8!qg*#ogB+=1#Y0zYf=NmPp$NNTO(5Qzz;jTU9cBLXFpZ#J!RL+l4w|%xg z2kCIOB9BS2S4h%ZY_g(HCs}AgYQa3#itf+>9U;T~8H%s^ePJ{}g$3AQDkJJ8| zbhY9K+_;IA`}b>?di4|Tz}+oyO8fR=zao>Ba`%Ljg1=S?s_2(@211K1@tG2?esUJl zyzgJvK!ZkspJFg<8+!Tt>cma)B>c>TI24tMEDR#q-3Ru__eWFhyRRqiVM^LW;(k=_ z{^oIZ7nS`?ko&IedbuIk4q4bb^HqZCk;No<%08Tb^KT7_fy2%H=$M$-_hB?4#UL(n zN`7en;jB+jfvbvnZQrr}ZuvUlD#4*Xjx)6j7b&)dajs@nvY+1OCywnhq#%1rq9q`O z_S%m;S~FCp_g`jy4aZrgK&?{wmi=%)o=RQu4{hUA$xxFzMgQ81CTdRGV(7^u zNAkkbVYT7-YM&_7mSm#+>cS~ewP9a9(&8dBKWLWEij^TAQ!mewt!Yw_UdXEXddg)7 zkuMSGWaRH4=F9Bv?~;vaXb1L@=>lc;OsD9~DMH6i$0|cdF|Bq}JGN zo3e~TXNAD}U5t}9}$gSww|`0}QR4^O2ig``pEqqFDy7YuzOhYr&to-ha6 za#(+DvZp|j$7O&+yh7GBvzbU%eboXG07)F5tm2;f71$*xMe5naIBI*k{ z->(mQEWjC&w(6~LeKhy_aZ9w^?qGY3tovk)7cxW*B24(|(689Syh)1r%y%}u@kgk; zqPW@T0?mct+gUBo`@oLZsp6evw&Zf4tGYiQG=44DmS27%^s&#JeOGH~Z{F>AUFQ9( z?Sd!CrUSj7jd$$o-3>QR`>`iaa4}(~BHq0LdQefIgs7tFi$fn%k^RfKk{)<15J>hv z_M@=qCdAX|J#GJ6OX#-`2VuTnaFv2YK`=Nx{tucT?mZ>@K;F%$aPRkJO8dL+S0PWM ztNGwchdPad!_B<)kbUKj-l=x4d!o|?zh|go?ttf<{Q|#`Cx_Awl&`Z5`v!O}BK{eAHjeR!F_ zd);0cq43*SrMu4+Zgl^CI7L<__Q*RVd<%A zm{7JLG2I|AlgZEGJg5O?%MMk1zq-6F5Y7vX7u$(`RRGVtm!+{?VXa-??1#i~COCuL zyU+K*t4RAbb8pj}31vpSF7&KW~Pg>Ij(#Q&Sp4RGK^^iHKW*_!`#zuM}=YP zvEjjd7=E)^___!E#Xa|n@6|0|~=XhUs|iU%}R z8668MYmUpX9m200?~9j>svr?_N8rn@LB42ulji;J-4z$8!47@^1wD;OU;Z)P@mt+t z2YZ?{QiUz^(~T+AZ?}EEzo_TG3BS3~GV^5v(2)aIl)Kr$3;{HIg@t=c!V_8>+j(O`8(3O^n&z)%*tqnp%aS-@;grLUhe);;d)XAV7C|328`9>GP_@zUB^e)ps9v)`?Nuv3uOd?Lb~9pbG%IxZO2?8Ne4g1fSQ z9RJ?-VOxxRgXQj?NPO=j3t~+(CBuQ3#ba7p`^G0V5u3eVBGZU8<~!JLq(N}b4*T9i zB_=w7_}Rz()GsW-srzlW_;=li_LiAs22qoeXe+~&l zfgZ+vy&`U}tG(Z7!!E+Q4|8WRbc*Bcb3C4x@4heu;{AArh;D)`Z-03ic+$7eTWX-{ zY^N!^1<9Y2d--^ApX0@U`Iq0~ex+RaS#V8MXljp_t{0f5@%Q`d1!f0V_ff@z) zz50QsG}f8*QA9{5w0U!mL9#Kqzx&e@zi86}tar#rZq2y&;TM{{v+h-WoDh}51bsP( zuA5Zg5Oxl{P6mUNVUm{RpSd%IC_%z?JO|islz)(-bvhtnaq^qQF9q3Wo+yvb zW)3FUhrR_t(6Ql`CJJs2^v_CH9@XtoU2mqy_mj3>)+aHh3w8j6&fbZiaup0jYgwVN zuMr_30teOli30>O#9N`E=Du7orK`vdR_AdD%<(nJ3pY9SlSaErG%p(bKukOWG-uMp z<$)fM5kID4SsYOf8JM#jvT6Q`Dx(WKUDY_W^{HvF$@zJIWuD9a+y+Y)+q;HwYk0Gx zah$ohM|fnt_E>DJk2_pP{=uvU{{^4m{yTLV{ zbR3dDUERuHzpR5Y=pN$ZG07{MXp!76G->^Q6q~yq&3o}mMa-8fg4oCB2R>+XoviiB zcT?R%9_Vqh;kG(0mWW3x>e!2WY~GMbu7|DDPjq=bLD1H7j!?$L3AEQT2Pq4=Z~Eho z&qKW~92Q1db=UR&&a(KLYR+@M2Hki1+2lD%0ZQ$?(>h#ehKU5YMf7xw&F-STrSDIB zW=4S~XM0+pjDDIBDQMazUSofsJXz0MyJKUB5IQ{5XLuzJtgYXh-^)T1p?Z)Gnmp_Q z*0DBnUpbydL&Q6o0A{L?EqmuR<~kms}*_Eb`q1d-lYtGcx}b zb#OP>FIjmcVlWtzdz5K6PRnnKFMKISKE4`ASuay9;xXh;DK?Q>Gy%=3a`<-XeUd#L zI3pznqdk(^p|?^Y*<$~P1bJtac{GIFiTc>iuSH&WYFi%W&vm`e0q7Dm9QepHqkd(t z5Csm^ya$Erig}H@KGWb5sPS~Tq~P+a9Upb!8Yx-*?FJy+V5u#wNO} zxK|b5_l;$g3!-DJ1!vYQkr1`ig>i%0Izb7^`7k{U)mrdWul*$^0RTfIQN{Zf{z5rD z=v9`Fr&e7p(?lsP{%(!5FJJliu=_2~ccq*fvsIXXDlC34z(-s(bCKgHg9h=N2)xl* zJ+D2<=~(i7nGwtw#g%WeWhX<0uk?jmVR1gdJ6?rLTvr1*ysvc;I6CeuN)d6YK*TB0 z&HYqQsxQ-ivysQHM5iJQKsRi6;VXl~ziQmn_9n1;iu*ZkCRxN*1H zK9H60Cg~g*Xn5orRvDYedYNwa?U_9)|NgMKyPmkgz(78%HH5dh*Oj}a@v4JUa{2Ak z#&y&TB_Kc(LHkcjo)W0tAIL>h(x0k0kS<28#76NLT79A~VPI#Oad}J`%Lfp+tlF zdqs|^z2mzBi05!J;ca3#VHoXkfcKQ>=pH6Q79OBp$3iL(rD0{~2Z`bq2hg{{TEIM6 zl3>0k9(|4zZ~r-nU|6dWX_`WxowNl;D*JDE!Y`^}BWE1%i)3|E@t*+3>o= zgSq1MVo@3t>~S*1@id__cN39Oye%v!Q+WMCylla>g84Rn=p|l$`u5Ww`Ld(DXz*!X z?0)Hm)5r9-0Ef|5{vIIJ{Z;T;Y89R4LZhW-7{%Ej&6Bq@WRiH!3OlD@qQ1kwpG{McvG+h(|HX(TlnFvZ}aZsA#$ zSh)9__0@&NUP_~>;0x)D$GS$KB7?8%!++X{ueu4Z$fh13)RDqy)<@-cuGjs|=a6UogJB{S$ls*!c_+y1#+9JcCl@~ap-X!tqmDU_z z?%;X8RX@6z_R)#M(PBnqL{8)x0zBn(K&3A0t=h1m{-EM-a?+6|r6%L3qYAOF zWY2GT;XgDaa{76EN`X<3`_w)eq;yI&Vw&K$;udo~0*@y=_D@2OTG!4K=;bAY>_iOg zy-*v|U!|Bb$4_wb!-$wSZgQTP9MCvJAHirUxO<{ayKVU&swXxmv&qH*AG{w9H3n zW(mBf-laN*rg|TL8*O1ne<>e8M!!d()N4VwqPgPec!!I}aenCCZ`0{w-JuhOt(soN zQEw#R2jtzM2%iR#XfE%k`^7Eg`t8&?b68yA82+&y%^vK)f^cw?)5yOsBba_8hpq3m zmge)pVp2<}SD;1^Um|{4toneLX>9nSJ`7W9OSMCu?H9a{h9e2Z2Zg|`d)|XzRwkG4 z@lx*BS4-|^J#%_1`LG{D8|coKG-On_FIS?|>3aw0#7Rs>St04{tAJMi`n&G^1J4^3 zJ#tL+`hi~%1XJsyx4{4TXe zik;0L(C+!+&1s*H_iqC##wTv7!xJs`y!FXw*n0swDgpG{oss5UMVFNFqB-5mY7 z2Q_mT`t%AdDN}%*jXSP?0UR_L?rR7^lIDg9-Ef_El6V_f@`84?i1x8u=nNyTq#RP zm1Fu8ASt*zRJQD4wEOpde4zr&?GN?kL&KhG_&2op0~Lsq-u0t>+JUil6&O@eb3l5bOaM)oteZLEU2!oAk1m zc(Uh8wmBrT;(=fCGk-uqJ;ql3MQjTXu?%x>m}VBQr1WU~0+@0~o=$6Yn0~1rA6L6C z8P!jgLH(8o$W6K>uM~tB^0|3r_wpTOvajjAbJ{pGzTy6mlZNxxHkQ}5%iGm>S#GHp zgZXVwS++1S+XdJ1#5^rAAqYJF`+mdLLD**^gV^3y_;~53OLa_=3tdMypOE_)gqz?t zHgEj}JF39lrx*TYUM;!wekODpiB(yRj#bK{8tu-^jTAPPmp;#gW7N~n*)OalBvybrbqIFCZha{A z-8c)drmE1~-h{hg6>343hqJM2+|m1BWDL#i$#|p^|2E}K^W5_=iL}{16e@859rJZ! zI|)pS5`Ab_G+g5Fp?Uh=XC0Y9mOFr2eN^@WnM?`XMjnXw{m@^nlm3#HuSsR{=^%N+ zxmgnVIvsB5w}5Meax@AkfAk=1QsQWs177r&Ez?8Io(VhoK-!+4$G18K0s5@VA8h{M zgqt!Em8j3h*-yYA;^!9KM<(YsM4k^nEETE(_vk${lT6*Dk)JEpc zJ@`=iLgMVUTGZBAlRww}B9}ep++&KBrAtaeMz>L*J#^{<9JuD~WAY}typ(tRjo83T zG<{t6>dEfV|4=otYa|eACkLbv)w^t-MUzX<*OD6hJTo52f{ynH4KLZn7GJMNC{u7y z_r}xZB4zE8!;NjspYnA`&&tji3?mash5Ss4l zs#(56Y+>ufanDUK)LUDVo==zwNFVcbIiZ&VIrdaf+SDqN&FynWx7=-51+CMD<@7 zBlYU9Q3Q_7f%Qk9vE@CI?TOIq_Oux~F7_P3CX_n~(!qjp}a0Q;9zz+2kS! z#2yK~&c5^T0C{<`n+2G-(2OdrK1Q4S-VAgSXRMeLknYf*2K!5ab=Awffe^SyKG4Z8 z*7;8p*_?g{Bo%;|+qV+0#S4mC6mlbaINf#;nT%sU&G~q``T*YTCx`+rAn^BeyHXHV z0uP_t5cyb@6%E7(SV$=X68kmiCjvt{{L;QbW39uCb{^H8Jc7pF4GKHIgkhG+HA|8r zKGuv1ikGcY-S|2E(DOQZ8?7TP#5X5#YcpTzoAQ;| z5wMGs_}9+hr!n?e`0RZP+{ILUCaJ5YIrx3@a-!tsNHfh$&FVpVsGM+?K40;v)P;^0 z`Bsfuu;|X7H~9e2y8-Ymj-v3kmT})ceUid5x!ljdS>V^F52!_A@_ewo9NnZGK&tcQ zu-77X;jdzhb0%i!&J;NFd}UpOm7Nx5v&r>!lx_{AwyE$0W|>`bkz>^EdaxhS60|xs zr(@Ki41*V`DZxAa7--YD`s>A}{D)O;6u z#?-4&xp`|_K4OUz`2hRgFziB_oXGCjmq-cIB`X=uDm&-f_w~|c>JRc8tZ7O(o>&=Q z-{=-}!Z?_$*KEYztRll&9KXPW?NMcNxG9;V?u!ohPKeLpb@0(Kj)`0W#lV_lf?3cs z_`V#dFNg^g#2a7aeFu~T%%WhQt*bFenZwN3e0a-Hye+q6<5vJDtxw^vci>z$d6s`` zIsd}$0_vkmoN0}-krugNfqFCV}662JU|)E~0*A;Oq85D1-g_{*Mn0 zW+#z3V4STWJYNYl7_tLEAishslWOJB zLOc5bS*;`6mAi$v@EEe1aqiYzXs%C!zq~uVndc5lb=4Azvt#oiN%D==3vOTdZj!S< z3A6-khxbYQ7oRR=m67f!^!Go1E9Gp($P>qB8@@WeyC5ThCr%tFjoNT$!U{Uk^aLbN zf7e1V(rWI_yJq?T#Qpku93W;!ug&odg~f9pZ_D2mGVPAoNPgGXZ;s-SU~bnB2aYj z*Bj)k`=BP6Mt#8P!V(iurVC!Uo@(x#J?`rNBzpfjvV_=O84q@8$tMM8!8Xm0vmE7V zUp0jLJOAz4{taCghxbim_Lf4y)ao}EWIfv<0e+POkAB5((G{jvbMy=SI)3NkTkzM8 zT(1#2{I@{M&R_a)|J%x3zxMECJJc2=K`P5J@(tl`d~Of(`wrsCK<9@JdWB=`epHG) z8rpDT)AM)Pw26(h(ZG9GD-J_4FIKU~e6dYfeo`k`&ILH2SG!5MpjE4UJiG*$%w$Xf7$tRJ`#u9a$=45bercJj(&{GU!GD+a@ou2ilCg)J~qA9koZf2bH8$LJ-%zP1w+vB~Zi zB|5c_6&{_CdK*52j<7tBueD+9t0-ne5ccpSl*+K90UEXKZ6zA3WM)u{u)z#%4~;m?(WrCQ1+PnDo3H;qJsHihgb6J^U{h{(`Rc z!RycY=ATbVwtqI{%0&Sc)9|~^Fa2wTY&PtBnQAZ7j5D*CPt6YA=DRz8i|^*3F>9+B zBtgybMTbEy+8ZkqV{UkF{k)IkmS2)Hy&tT9CDy(-pBLb5;C?Bq=j_fM;`jys&C#n) zO2v2c?>;u@qR$@dw8N8xZ|6NaVJ#PQ4dgb7Tq_4)RMJ?4{^0NBhx%^c&^=48rhL9$ z*4-#GMT|7$K0URn<$ohoZ3TCRpF!J#?zrpUtY6gN|jf~?7jX<*mP)u8Li)N4(dAd zC_g0URQn<&^?b(*RgiKfb!SAmcErUx62eGvsq%?nW2xS)xZ zJI}pFu9r?q=WYHHM9{5g(3&TxWT@X?F7d8}Om#klZ-?F*Dee-LqX1;csq2Jc&wpj5 zCEoTZJr6nPgsff$ly7(yJF#8ydEZ5DtUIdRZ5_0Xd3O5!b3i%8n}!E9o)5*nLf|4q znCmGd%dann3BTQk?8FBAzDIXo%Bx+VS@((^9X^?vXlwXL+|PblMIk*w<7(Q@J_I#5 z4+zP8Aa0Q-rgS!(62w*gsL`$~e2#s47HRTvylhi?U<(AG=LWl1yk_tsKgZXs{k)IH zgQWW&>|6_HHwjY{#nD?7R2yJn^)V zST@&>6lM8*z(~EHvD#vC`LHbH5Xw8{QwZ8qAN5L`zqn*Mn|sWxiL`k2A9pg;MKL0N zeFitsR0bOQnP0HS`XyY&%js6nBWU_&0Fs9**rf|~V>;l34GEI|6I-yFN@jOU`dITR zmswfGR^hwoWA%*Pe2oK!qBkY^$WgHYKjo<{n}-D z^hd@440zP;l~#JlGHeJH?2B*}GYZTcl-a&eaFJYfu=v})_=!I;NDrq=wGa3rZ1R&; zg=i$p{h(&>tJw9C?T(CE2ri@d+lNuvqQ|H{I*qlmI=AmtNk#0<$kpR|#@P|p1KOwX z+JFoxy(^l6=bHnI&`)s+C}_0gQ=^0lTQ0QN9C?Qgxo?tOfr;IpTzn`WU0g}@X+p3S zK6&s~Ef3id5TF2r!y_)GIQfsUhW%xFYVOvV82VP==TwWN<42yld*RNHPA0xi36t{2 z-P_{sqMd&@fajeEPp>B|C0|tVp1D8SEUR8btYTEjJu zunxSw$2m7Lw0jr_vcKMV5|aopw{!+K`j%(j zb}QVzn(pMpeF99b;ejw3`o(EE7*PQX@!HjWKLV;0_C?DhjY|3Oo_RBts3h-K3c~n(te|WY->sU;5!edf zleaHXWAL$Ka_*R{THmLiq;*9648oOT0t`Kb+w zozHpQ{~TtsVT5zOH){8qYY;D)>3bzRc)O|VmcO^#hanaxtKA1THLg1_x#1G~u!>6~ zak}3)2(>zY8tg~*P{#cV_U6d$`;?c(@s0`-*=XrLztCp?Rte!6phk2`_={xA{-SYD)orB?L(1yK3ye164oS)!Ti#@{DA z=M599@WS)VbF-bC1aeuR8szisF1%W)nKEyT-_d#GVz zIqspng(;aBn+f>B2IX=l9Fhm=7nkH161hl+N9INZ{meO3&qwGk;d%dVtR`z_P8`f& zuAHyD+JS-TJIH#4ik9yCF2T3wDR<-d4=(jXv(H^kY-rwu3#^c>NORft^isI{+N>9& zWp8tW1^y;<8`>GS9 z;vOow1PcI!C_Sqb^6m{Z5)abT93Y*eAZ3`|gZz#fB^W1|k2>8lz0;TVxxbb@ z$LM>%&%maTv;^Ee`O%Q0zlhBGwzV^&c9&TSO=qNE%da=AMFV*yp#c6IlJf)a=ld}E zCMfL2=kx;Z!yaba(eJ%rdkwK=WdsJgoGroOjI~VlS@@0uk4%iRM+SRy0p?<1pCsQ~J&=SiO;MsLxov4~d${gFdtcWRwteO7lfY_a#hFWCzhYC*Y%V5|Jw3!q z)pXVU965pokW5MRi(D~JMU952y+GRX_rTCbfHP1;aF; zJ^j%(d;F9;UU8JVA&&R`FBDGM?L7&YR}?J5ir!LS_O!piAlN!oOlx%c>b{N#ze2Xs z*wzP|M;&YsIxRozfs-baL0&E#z(1Y{3z>AbBU35K4`YYRT!Y_1)B5W_Kz-Bbq> z?j${61uskzGFj8iLsIaKsIVHpHOZvl;lo~YO9yqIkuXfL-$*dQ;|FWWzcAzDCAwB& zEKO>hhcvGLeT`a{!&CT%$LvRK93L_1(qOP@r-2^6=6lK$84-bSN5c~rD(&@vCIjUs zn2UEI#=DgwmuZWbEQDYjf|Gjsn?+LL3gF_zT>Pe9$d_J2u`7vRXjo{0=}jjj7z>HY zP`Zl2LPaSI#QOW#V|4hliBD zp6Dg5wOj{MKYW(8A0$*+(eQu|NZi>9tP#F_o5BQi5;nL@hc}128T#INkE};Xjb+Ab zI^=WOjZQO@cT?;X>|asmv54iot=z*`aeoaZwetA8T%=L#CEU5Mdc z$z`T`1@h(e(a+`}PYkD{TOA1AM|QN=?K{5F0KvRF^)dCo<4=7WoV8xFQ|OQor;p=& zcB{nB8g_Y5wlx2-Y2!V`7D;+QoI)ysxyWKPrMP|$)`BFvJe=3%DRD1-gL@rJ)|2%B zsl+nw_$RB5KGbT!RjX$+8KKdqK6l^;3|I~`en_$tzhvmu>T@1OhGAEL^ZxJ!lk3IJ}za6+mKiF7)7QmtN=So>WFtX<< zC_iMR5`8#CB${+e`S3NmH^jR7M+&Z!b!z~GpXP$0SUK^5MR~!@5&fJarU%R=LjFj` z@y>K71tG+9;Hepag1_~GQ%NmyPQ-2Wt;bbQ0qj`Ldjju`9bzGJv}GRNoP4;SR>55F zNNFCk=?hxM>na?BgdZ>a>l04&%-rLLDEZD#E)MfB(i&Vi>d>4(dJ)B$^U@;DT49N=_QlW4&5Q6;e>NY3*x*l zRpjCfa_ZH!xGBf&{zC18#Dvlg1 zRysD9a}hkH-`K3%1mW*DhOX;6-q5k(&QujY&iS{(?5<8x%tUQym&ZA0f5~bs%U?f1 zTSpnDJUHHIo^t!y;LJReZ+!{Su7KWJ^XTHRnr#N3y8k{lwm_@b%^SIGzfOB(dW2`d zu|}fnCIUVytYWEOLV$6)rNw7_h*ZZ#DW9kHjlxRzW=wA?^ z%ze;jD%Vb4U~(cXY(rOiS-Sd*mwna4ME)2lG-hN|tXkT0O3kP9ym9hI>icX4!xaD~ z@PQT43qIovX1Zv74;w7jRk#Ld*pX`PrRJu6^D>Dqo)1*fqutF49;7)uS|{PP8+)O_ zD_-0}(+Ywme(7&7)~nU67~s@7?Vn$Xg{(q--#VAxvn=4Cl~Tci0seFFaQnzSbJ&!3 z#SHz$W~0&hcpdiT;D+4R%zhuZ;5|2R29<(6(f)+$e9_UcekfV_1( z6kp{^{cH}fboL}VK=7k@y*1BwddU0-gTC<-rR!UvU+2@l{)RGDCI%0)7h*l6RJXtH zX`MdrdGGQSy#C50;~ZYb`zWEl>9-cTTyNo$>lrOV9#~n2EO!o-9a7-*3Fdx!m~{*_aj!y|>U-LgcU4s|e(0rYHl*a($7VBq~gf?-Z%| zHkf~~f)I!l(V5Wv70flR8m@#S3Xz~_YY&M^=G|aW{HOmK-`0JR?tSF_Wp&jnUBX*$ z{k);9u#TIqU%R{Szc)kPZaShDYfO;hh)Z~l5YQSnC9S%;!%21?ONUb~AO~FCja!Af z{m}(hc>GF>Nj@7UJU+C2Fw<=XIubVJcMK!qN2&XboU10p#SlYss)HYosK8FIYtLNW z>N)f!4QI{naEP^0j)6PdEVil_ttJYE&yffgI@t z8lnjK0=X&fcAAr)%<`vw|8l)K)=`JkQha!>nnxWiH+&~DV;7AJQ4L#}%BzfMkRgvb zx~V>H82V-YI?I6&2asT7)%-kpcdfodSVJA~irECO;!mgzRR+YTd(;wuG%sIK;9S?F z=v=1ZC}qTj|6<`o9+%l3dn$3%G;gsyz|1n|{L4*ce<@KNG!gcf*1^`)rnHD{^6&cu zCAo`C|4aqO--m#POJkIlN_~H*I|S&^k|*!aK$iVU%RHbT2REHlV%52}@&l6D}5 z>(ID;_vnz1!UWpVEMe<6e-+_hebIP(Nv6naG6__9t4rg<`Fef5Sznn8v+}dNjeIu$W2Wyi z-f30I^HLUZ4vEw(vY}ANbcN!xeh)>}5A^f%ImO5&T1uDLp@)`l6l(fN z<__X6jl2fb>weOzr%09tSDiLKZK$}8ON>vEBBfa@{K7?B(-wS-G2FGU5z6nbLCu0zYX4Gpetl}i53qcSAcjUZC$Cqiew`mwVfR&kvLeM+HMP&| z0kH>)r_XJMO%+~7trHZ9oRxZ&n1=zOIWGxS&F<^wF_2w;hn#~eVsjPNFu!pCi$4<; zG(DsH*|)}q-_2P~DhZs$9KBoZ6OG>Wl97{=An%X%c~7LL4pt@djSx%$7Icoj zkiuLoID?3pC*|vt;mntZ1Iym-;nz#!HcV@apFs*?P;`mX{9`%$_9}|tu)#80#bx@F zz6ay}tP2Q*@+0F_dHsO0oGAzj8P;SDu)v#~wMn;T)QX0Pb(Obyd$KZf$j*ps6zFNX zH~ol&+julRrwYvconHu!BsA((kctaS6nau9-0L2>n zN}Gc{BTQbkt#U4kvq$XOz9W42^Pa>5o9c+*UWk&{8a#6MOxzv|0red(kolwLs0aOt zL{|RoarZ>NzxR)x4DX45C1K7qzQ$b73>d-fEtEdj{?5+cjYk_>gL>?jCbkFi+u`>U z-w$l=On-C9GtOTNs| zmxX73SDt`LxrY^K3?|L>?S1Gfs{3Q%Ncexu~>Ca*~O@ zPb1g{UC_ltSW_78^S(OM?=O*NsrdDI%}3Y!@#-eE)z{cR`n@2ipFtF3E~9$d-u2GR6%NAxa05$0%= zsWzeKKYE64go=va(fa-vG{vReP3$m&mA)y~9VT;7Kli;U#Nh!cJtvpX`}9X%^Go-7 zv$IQXq}Tk-$GjLl3aAW;*QFJ-Xc-9;Ejh!%#E`<%VLoO#H2s>JkzPKedC#K=RdNzPiAr`|a%T_ADMSY{RR`NqrTV#~yy-yJR-~W6b$`{B|4y>%Uxu+7UaHmhxi^roX->iW7!#-*tMyBKBXLKsDBr!2_=|5|ukY9)&Oqsv zLN`m^?$OGqy=}9C6cyt`5!uK6JJqdH&ADs0rRiLlQAvS7`V%5Lq}hsWFaK6*jD?!$~97!&ry&dog(Xrn#!OOo82LfU6s^Z>%d>vG_t zDne^^Mf2@y5a?Q?ztT<6{SUQF!x@b;>2V_7{@6%hwH7Z3!ziEfhtd$l<{Q3(mv(mX zR-Ss1`!#)y9d* z$g`bw5RBZEb#FLS#JFXHSJWG&NQlqx#>PK95RD$mTEYIn1s8s}Tr@CAsIy$ebill; z<9)2hk8##1$tW{N=ez5bTCT1q&aWnps0f~rCqqh}#~bY*WHe1Zy$yi3`BFk$MU>4& zTYs6vFSqd%`hWZ*p=Zwr2FG)aD|2QK>h=DG%6v1eRn?GX$1(YTWwC3e>)|59CeZdb z@b=~xE!A;2wz2ihHDd&MI0RIuyTY=M?w8LqU!fKFYhKG5b>n4FG;+V%Ul9KVa(Cuv z?T{gX09%tEb=%?Pv}fZY_UbQj_gB?3*sf`DMkUdhmaokDOhM^L!%>Khdn> z4Er~hr{LAPFzkc-rcTygUoZCrkbLu=0=k3J`UWz3m0RayI9@+Ve=DZ;4X_O$>{vlP zVvj%;`9L3;#?45?x3huXb~o13`ALurJhYhBqK@lxo;Gt_>Z<^f!rKng5?M?|iO?+o zWW>AmdwnsdRd+sW4NNorU_-vt5~X_4^$k+ywkSW)E?LV3tOdFXd;(&csa;``GHI|x z;%nM{e-sjjQ$poJB|$Zoi_8rRd4t`FR>SiJFqRUvpz>EOGh1PN9kovaz6oUmO>lR0 z?AcM#Lc4{@o%ev=_H#7)Z@LPZS&-y_5H5ZPcW%F%c< z4q<^3v4gh9y_-e3%La$;6c|lini0h-D0JVf*M`WDJY-h9alnJ2Hw^8UxLro7LB5Sq zm@vT^7^|Ro+d0)S$DRZJfN;sr6nrvnwL5rZYGZ4vsQ_jYQu$*e;dS=Ky&>Q@Q(s_bY30GscD0g-Y8!l}GQ zgxUk$i!-fLDIc8xDBI6Hnvzys7+YLJ_g)jP9~>5;SbN(yd?H`mH3$y=Z`54XS-4ax|6m4|1)k)>-t`i*%d!+cen0&K3%Zr=CW z($`2tXEyC})~VasDEQ0(_{y&aw_I{dUyq@XC&~XCL-ZNK^4I*Ttg(|}uzl*@s(m|l z6{nNVN4YL|x>PT5yE)+HAk_E;;e|8zUjE?~9gPc0j@PuWA|j%V7x9#RNP{mZRumKt zG`yx1yITngdofq&uwT$*r3!8R2A`(ipE|OMWCN!jO(C6r4(ZuuF8yIxB4dK9gLTu( zVSj34f_jseAI^4Fr9V!$^w##Rcl}@xKU}HgvI37HFK{V1FMN)G34Qi8%MatYyt8|6 zOy=tW3&fZ2ygOue?q|OvKsMr-lXBVI$-53*3e)cLIrGXY-yJJ$u9_COJrwL!oji8N zq!50QVWgb2@B7PkIW!clYEidDqDGpOFV-|=4xWhv%-nsL(#`{Owb5d~MQP7y6a;!s-_1+^Y7;$rT z#I!i=wI_hw&~8a*pXBi%1**xV;VIMT!W9V&ogedpVF+XtVoe#FKxSkB*P zw66w6J;x2n)&kp3qsw4ioqQuIY`F(Ul;jDfdG~s;uwlN4C)y`2Q*bUgnfKNOIl^&8 z7576*+WAe&rjm%IlV|{D{1zn;C2@2+2&V21P1DD&1#dl_EP_=ljO3Uci5a zmwb`52m#+p^ZHM8@6N%Xrudd7q=WVvDZN`f#_N6wpBWVL@@mM&LnErrHHusLfyvIc zk>z;r*_*jXklVI7!;rtq&1N5apw{kCGl6sP&#eD8>KD>W9znHPd&AuYThtT$2^OKz zZuN!)-Px5v?07$&s_+B$+swR9w0V(s1shhCmGiqYJO*$ z3!HkLExsRx`=Wm1^Kslqqc<$Gte)V7edW>L3nxng zSH`zcGV-y^=<6Xq0wkdq_3&D5FmNS)dVe?-IcOlK!&#NwBlax&9GL*l9Z-aDdT!63 zqQMOglZslAKmAXYBwX$v!@qF$NEuSktXC1VCVrl)W`=m-x2^u0=A4fed}u&`M6_kU z#Sx{6Onfn-aFP_;`x)=pqe`=5u2d%VTWhvWh8%WK>DZYUOIp`U(Z)u;-p~`zG_oVq z2Dc|b2w*5jfu5}SoTp(&UfzomBeNbq_vuEG@-*?ze2PU5+D!cO+AJ?~zQDcQPn(%| z*{}Xyr30^K?=09#J1SGlQ*fUspk%#G_2ARB-wbzbOph%$*Ky7KI)lxA_pLc(>6PM& zmZWRWmi%Dhc&IVOeTIq1Fd>*gF7_Z5e0l66=4dg8Fm)Q~Fntp~%|Z>i=)+5CfWqJM zc6#^+qSdqW;aFPxY0p9Jp`PR*OWzgl=>+-&hN-9;j++&?lh83!{~6JUa5Vk7(KZ`f z$-HGG2fxWv@+qCA%sXY5bVAP)iRi&Nb^?9Cf#!60nz4-n-#V#>kl;s3tt#P9={4A> z!;emI>IQnl z8#v=q%3+TvU-pxke;E*K99ma#veCRtROkY?_`1K_aD?eco*BgN#XNm*@{~y_KV-pO zl=o!3KTd56TS2uYGvjYrwl;vOqTNIG#o)Q1^At62@Znw#U2gr&70-euf`b8XrbNm1 zoce9<p-x4BSR;VZcs4uDFp_Op!NnDq5;A&V7T*| z6%SBCx7oM)7C^N(V8`ZrP8|~WriCQw$!--zdLpr4Q0jWt+1S5(YdXEw_$PdxgMw|j70cBI_vvDO1q;-K1=|<>cPmt zX~FMeH0Pi*4T-&+ikhzwCih{ehSnBSBe@->K81LWiKY8_UH6R_^)bIyg6m@5JobaS zG%a%M^ham!6{J%g18w8)+A8l*J|ezEh5=$K{hi$ z8lNWp)96>*nNB~aw^Qb0Re1Ru) zpvs2N(^cbGYJlX%E1hf)e&5a>{#7efl(Ec`uyfY)R!u)HaUWm){)q^w2`A}!fKZD+ zN4%v(FpXZgxkYvD8j#0Y6=}wM4MP#p`ek5Cf0|%g^7^W;eI*bgB^xF7J!vvP5uyVV zo)HHIY9$+#1(MgtQ`qhf(K|v=Up_ES`(B`3ouyyeNgeI9a@3i(9D6wrmR5thAtVZQioxVI z{D|+~bFBo2^&|KU$3C445S$iM%j3LI!M>DlH|Q1cmCw|yr~+cErShy;mk>+p8|E`H z6-ssw$?~sG_FHpR=WJl@>s)A+yEPZ}1ExSr`lAWd=|0ImfV_Bo9(|!iCiL|EN$G75 z`zYj_Pe~~qp-Q<&Z<)LwmN>qN?xCS|L9aJhvV~Mjvy0!mdTrGet{%Jt-$yz=ue=QJ zlFMU|uP7Qn?xG(Z?Zym=>B+2;rWk$oDcg|0_+y4=?t2Ub}m&CwEAva7gms(gwkd z8~SHEaeDvh(e!%kzH50z;!Md$Yb?d*OYoy^dfTl3NP&AtiH!{6u8R+`wU?p3y3!Tb zH=QhS=(X@P*t*F-?{rcx@ezhC>iH=ar+wrZ$SITTpOGHnf>xu+DC zs1CHZ$@#SgxHBCd;IX%TkRHw`58&zV60?!uT*`}OGC`JH*m*y?lk$56fvK%1(fB`= zrK+nUri$%TC5Mt-Z@%|f>bQj`uFEu3oX5<&+Vz@mCe%TDX7HAM-|vS-1jC<=z+ro% z$NUnYhEATG>#xg*8JLoq*aw0sg;^l$zfP7Zhkmmk&%ed;E^~yb@I&DEddxmIDUca= zy#a9sJ6BR5^^oOwg+cJAto`hV2Z;ADV+sbzW#Qp~Y;R)%u#DgM)$?N|-SOt1GyGWp z8a5VAxkTG}cWV$t*vh)?f$$`rmq*!Mg2@d($;muKoRe|(_G$8BAO2B95YK);e{6XL z9ecl__FH%)w{JD>$#oGRVsAE>HH~cQmVSA=e|{!c^kAD4cm)v#yB~@0i91+Aw`XQD zeG^qozzdFM`>LPldQR-6yR1-k4BU<1?|-99EB4!o?R>pHKr5na!j-8!hPWs%e%QqU z@%@v{nw%aMs`ULWj=g(%%{3izuBHJaJ&Px-%ppt1v0SzG;@18kt+Fpl+1Qv%0L0FmA)xXR`S5;n1O_cTUM}jr%0ma+31`0g4bd zQ>rfMv(ospz7~Xl8vWUu(4_@9-ib79Fh@?YuojMdYMN8=?ePJuJ9bJx0Zm(_TBXZ= zKY3E?Xpg&beP>>0W;fqS%lmUY&6>C_*#suaupx7O}y76w0%cm{~eqr_s;*eb*{LQo|V=)zQu1?n##1FNS~okS~v-f#BG+64e#$JapR!@zv~yl)n`SfG})t%$3U+4Fj_SjU7KFI zEcAma>-{ck+zXf^;;Tf~IMsBi{S4h<_8I{p@R2V=HA4HxrzbChxG|sKp@gS8%IMX5 zIX*{u;!aKB`{O+_XBD;5l>J<7LqWkdzLHBfPHQwqy&g=taKE87h}a`R15*{WGb|*l z6$dBXW?DUop2O8HI8@2gPxfKpwwpD$+WQC$^hJRd-6gC6r+81_ox9Vio8-yaFRlH; zYzkZSyTjuw3npPKoXP#X@8{J3ld3G?hkJ1PhtZgQ)e_E;l_vF;{1X2b8R=0Cx$6>~ zx5nHrAQJRQOiNJQY)+Y;E28P83lGgFo~eiF2~z5ih30b~;;X2sZ_Rf%eUAe{BlQI1 zjQyvQnW^fYx?&;9fNNoEVV+=x!H5)my(n?V0=?&%v_!a5cd#mt+4ZD3R_q}erdWs6 zkyp(&Mm+-$$r|Qy4WSrEk>rKBO|beo|CNjK6n?&smQS!VP(PP#nj2vWasP8ZgAiN^ z?w4F=fYcI2-blqVU6?P7e?N-5Zl_Zqx-&dTO)@op=MXcrax072!&h#21+(3wZ^Bsy zx;dVbe#~JwA9dD>_(sLe{tBXex<<^O$`&CN$CC=hrh@c`V0M0nBdD(R+Gq6iT9eVm z%h0OW?LXoJWJds%^q%&TGh_A06QJ;XS|BrF4=gfq(b=n_Qo~wzIBA42I=_qSta!5U zT+fe6wXef;g~tvU2@`|^t%gb`X5z)|dc+%kg(g5h(p%xW$5~@0 z##Hrt*@t)P?mS8!z6TKE12PYf>iz(M6rMtzR_ojC8BifnrIcpyjUn$v4bx%E(i9s{ zSYR}=MapV?nGe7`i+%XsT>ujg`g8w?jM!f;GJ4~02hO_x(x5z|FBML%IWze{pgvH>R{7Yf5E1Pwu&MKQG?&RPlG|%2dW1dN;q+qNefnQcnwxT^EkUqZ2h^oc;EJ~m+jC3zk$KY5R#)`b2q#BK5_nd# z1josX<0Q&{zD}nYm>JeRS@uL$v#>7`*je;2ArTjIB@H_o+JK+o7WSK!IqHct)!JK}k zzi2Ir`1G8aEkUvMSCo=1ryb_11Q?Kb#i2`xqq%EX1XOYheH*d!89q~F!*BKdn{M@K zsZPWq<{|TzMhjqRw>|RtIVfR>HuUb{EI%U=-dLBip&QkfKyJUHOSCv$ATUcOXHW7q z*gpFt_k_cJ!CK>Z4q)pUtdADSN0d^*_TJ{|^osVF(tn*d|0tJY9`EaX6kxs2#E+M^ z?*SUi*V(w=;RA3L`j6vQZJl(cD{_5R-+kgk8^6-&#pJM_qd0i;jUuVNtE7Ua>y0PV z-?KcZ>xXEt#@s=B4|YhMAec-@GG1u?qAy!~yZux@eCmO|ip>9vhcb)#ykR#61)Tco z%;kZ@je0}yn+}h@`s&p8%wFyn%g=1EeO^jJJ+zRJ4x*seGU>q*0a*@Kk&{wr4lV?W!TFb}Hyz-|2SipVdzxCgI%L=}3ox%X&T7H=biR`5G zS|dCviVp^@^3}kw3P`8YsN2 z(sIN{e1bDND(Mocyo|e3F=?_lq-aK?U8fxPC!bH{=k(%;@KVinfsB4zy+}c7N$vI( zc={TIH=jU)*$r&+azA}iTb+1>-{@fP7=u6C8r|n8eMwRKw)y$)pueWXTL~c9e-Fk8 zo_4LiLP2VV=5Xq~xfio8KgEaFJuMr{rKHmqM|&gy?>A0+A`M`dc=}%q+Y_*R%-Lb} z_g4&3gZ&m})Cs2m{BbuVI=P$N;0hc0+=cStf^`QpnCrtrhv9|ejzFIdLv}cfYxzWH zDPC7mFFYd1`8dSwvhUM=cO-%)CW4P|`?0mdWCC2KUlew_UTx=t1UDaWMw>zu@=02gMWu4eYQ2Zl7zz1G>^2>aQCpR~OTTeUjUe%BdLP$MJGl5g&4mHvDcunQ>9g zJ?>{%Dj2qX=-<$Siu4|{>}vw`juQWT&Q)x=>;xkJ?R{K~sOQb^D`pkec_!!%B-o=u zeah&YT@CXB#6h$+fLOW&@Y^Iy<~a)@5MJ$DANX^ZtyFEste;$<@ch8g`PZV+It1S< zNshG;f@rt)h;WD_I?np6zw`UeC@rVuZn}@=JYsPW6o#>-hldT$ySwSd+;G~$Pz}dE zW|)xvc61ry<@|RS4f2xJU>{6I{GV7Tj%z7VD zXV=X1eHQ%YNlo=&`;0<+6XdFV?DLPG0BcvE-)v!jam~RqzmKkcz;}^bO@VlI!JuOU*}~QNl#e0#I+K*^(#=M#r6Qu1)<>(g<)YG2ZYcM^`j4SIf)`uI21 zX7^3?*9^Jl#y<=ht&rvYI~q<+G#ZdJ{d-TWC@&W2-7#>lHV|+EXqWrFB=-3hdaq57 z`VzUL)V+-4#}vV5>%$1ZvxhAB%5KFZ5aPi_)a|?D0OQ$nEOOCwkHo8!)F42Ysynk#t^5ib7Eo{Us0qc?8KQNfGc3BuEe> zgI_w=ypj zqeZQ6S{-pKa|^grx0P<1JigyxkD4zax^#z1=g*np5BUN%Ujmm$Jj>8%3be6DLBq;0 z*IyD%_P^JuJb2XN7a*Db@Gq|iQ1y-B%C`F|&fLxY+dU;Pe?WFu{+Q-5zNJ%lkNEn0 za-TLc05|RjzSm`g{)F9bgvt3Hh3{VD&?5gb(bi zCjL&9L;A3x>5bRn{`k(VBNOeCM$aGXMlF3O9v54QpLg4{nV&f{yua>;i}kiW^BNn8 zO#=$0?Fb}44{MOHNF1xHWXwKVwwIiOwzdlE&R1I;_Q3oKv>9cX(V(c5GSOStS@xlS z$xK>En!ia2ygWzhX~kKY9kOwJdh_d?Saw(5Dpb@bh_8Qp7wBs*-}woN?ML&?;uKsS z2n6`@*gW`X@Aw6+MkEA`E`*n%qV_^dsr8)K%O|u^7o#8IBfJL2Gs?e9S_SJF2_gV1 zFBBXFEI8sp0lES*vd0f(QRk_2m?4kh^l&4-(fj1pHBLj&wEVsHkS(6)+O)xQSe*^E zi>bZ(XJdOoyQ0nvC*H(h>HYaHQQ;cRi{o^HoiC1_vf`cIzw6+sw?e|l0+bD$xXVKP zKzCvK7j~%%CIuSOH~G0P7+Vq$GRkE--}=cD)WZ>u9h_5M>391+k-6Re#%Ee$Mk)Ay zbe#MSFAybv)GT()!oGV<&os9H&5~7upfcx_Zxv#O)w`a}TiDvanRx}H)!(yFdK{wR zCisj0+!e%fS~2hB#fv00K0zr!{cx@huha-;#_Uy|-GCw|COWaE{l0%ZhY)r~q^5o@ zUGsT#V@B(16G!inf27+vzj0iOLGh-4N`!9xvYcfo^%knbt!KT{aF~fpqg=6qai7~Q zz{Mu`T=e>jrcJUUE>YqA`QdKYoDYACxsDjgcSK9i4O{@SDUz#GQ~}41iEw*tO8C2! z^$j)4cQC>r^6b8nw+U!B;uzW0<2H|=SIK{ssF(fUEY%wfnn^y1wfaFDR8zMR-cwQ# zTn}F09_{9iurL4W(l>-@A(drWbD2~)V(^dAT~qUKvH_M5l1usdC3uL=z8O-WzZhU4 zo+R<1Fb4o=$o<_e^K;Ksg}c=g?u1$Am(JC26;oOS&oZ9~-Rq|fESzkIN7Gji5TWkF zD`wa4J2}v5(h(tfW-b|gDPq~sX!JaI<@Rj)GvbsNvURO97c=9iioFR8AEqpzl^6Roii~vhCNkQ%evS^68dPvW|~_EFSlOc_}mVr z8-85zkm}sN3Ghoxa?nWzn8qI?rn_EvZ_GaWJ%eH+I=4Gl z$Gi;5m}TGo2J%X!AKhqt2B##MxDVOJQ)4vsp&y|{jjSQf=lc_U`>B1vq*4@@2!|1E zNy4Oc!K1>`6%4%V-M-{HW^Zy+@|kexR}(mvKK*uNpxa4k{fHb9Rm%)$yVhKdSFs*m z4U{rX0^9RT>)uZFFWS$aV8OH;&lpKQ2yX09-?EkMKcO{@$f^$M8|aDG6%*sW9gr9- z(O1E`Wqamxp?(r+tJD{KbUYDc{xrVJ!chu;ojm;U$@VuNfg*w=S#|Ir`FrHb!~GDo*CcvAi_5>u+S#88o(HcT^DMAgoAc2%fJSca%V!X)>A*~82dRGnjv$Hs+nEr{sr`sNMdQ`XO*a&P-5exoaKhsnt^ z2eP|w8Axy)0u+xY@>a}Uf3xnY!#{%Y!Y14|ar=_Y(W!6mMfFLu5I53u$KtoN~x51qIHCt8xDN04ycqC4f}HO*L* z7}$>82m{^ft+D#*mOk&#dLhVb)^Rk$4$_FT%d623Ko5pc=2cABOnzJf?mKRD0G6L` zgAW|Do&6a6;ks9VGbsq~mk4pn&BFW#c$~Y=QsXqGvj zX_{Q9RF?@OlN2+rA9pX_b_x;QZaD0UF z{?e7s4o|muCtp3KE~mRWv2D-Eb?pVjUBg?2XzA8VsoR4}vw-1atosGE8t2m8(;=P^ zm!dkkaO4=_KW2KDAI$o6I`gS4Z_DmjyvC%drJwh{<~9uzPArr{nPb+ZqOa1)9PO`d zF4g0-aP_tHA9qx;P|Ab_#iN<21Ho}~0P3)OpOT&g!GObD7s$HralF7kY5xSAp$0#J zKQ;EnE;*8ss}TBnyo#H{Nk?<}_)#5*R&w!pjdpW!!c6qjM8*4cyiOgSLIpe!ZCmxs z`j~!s%)*(!)M`mXFn2TpuBP*fU~_d}aNmi)1nxJpQx7@vz_dTYxf04d*^f%~Hmm(4 z$j9pPx|33J3DD!zu9mizrt@ClQ1j40t*~|`yl}Xdyp8Kf<{WW)lf|7swayz<;LZ|m z>mLGhSj+t&KcmQXjTk8FfoQ||2YckJDit&x)zZk|7wo^9z3bwPV?x6|><>y?8CxA? z9}kYgcVoO@I2Jz+jmwPn{M&j(cKk(WNpAxGMdYbdtq%{f@u7L> z*~(xe00F@1Sc*P<)6c#xLci^#x}?ag39Djuy-}z0NE{PTdN@^Z1mBxdZ3LCT{P2<2 zW_=-TYb;a?KDsaad}?VN$^Gvt5`!!?+5#x zO#Pkfu+i$S(Jn*?GYTu#RF-f=AvqLrj%Joh-7<%uMC+zk?q|Zggzrnq;hGg>S{NAP z&R~e%(e@>2@p~rIs=PVg&gi)OGTb*pkld4JE|+{OTNq2xZ-nAc`>ni<)(}S2%zc4{ zo`!3ItzV{Qj6uGCm30CUv^i~4+-nOc3EAn0$ZD)OUD4pIaz&Aor06BaK5!g&`(3%K zz84Kluir7^>3uO9Cq*%RB3;PCEI)d10WLU5jkN2v1?MjN)Sqeo@$~ZH$r?_aAK*en z@F8LRQS8nZ)f&HVRz0XnS!)uBGA4wBuD5T_)B(Xnh8g<9YD%ljO;hi2oWL3Qb(9I( znLlsB8}A2;I9wM~APd&xszNVHbiL^%@PxOuV^(BVuFShlQtVs9FwH8|k>;t7kGCJ@ zJZCBbXlVRXNUY&Kz~;v~H2cH$g=fKS3I=zCQi%KcU2gh;Q{7$C&`lp3dzSLFW+$fy zt|ix_mJ8-d^o(^m$5!{G4yN|oI;lPlTIpOU4fUHh?0NTP$NoNBdb*qqt2i)SeYpIf z(6D9ljHVWpPSI6b->0*FJZ}s{9PsFQq%MzVQhj!$j~~Gzy>%0bBpFdCWAPpzu>R$| z{Hh4*JI}@=EHy6gfnvF{#X`ktPxnOW5V)&Jf2^<338aOiy+~BzzBsy{(^eSRjL_YD zkEL!^1aqHvPQAZZCPa~3|7pyR{IlUly?(*K$?HQtzfOu70N~^B5LCDXi$+y>37+Qz z5Bo}>-;O$`4j7il2i`ZU3Ih_akaxe|`SZ0!seCY6kr>^c9G-t>d+0wcd5$07QAgZ^ z0j#tA<%a-|v<4O+Z%Y@!xvzMWWAoGLq|GteTLgTu!4lJA+yA%QLLh2o&>)6T6&YZV(fc!eD9Hcp%{fv{u_OQ-1k)`!7`7m)ZP zn3{H`cI~V|WpX$I#_M}IuAYrC_OKCB_QARL>+xXZh3|7(?p)m$g+yj%FF(#aXmNK# zBU{>>Uw^owWS#Mh1|J!b9?Bb{BY7`Ed7nG))h_-uVBQca6q9`1Fkko@$t5G2Q8y!XwfF5z}O%3oy-!kK)Y3G|0mO*fpAxvbAWkHDX^4ehwE z;tdzjvwDo*S3FkTBl>4duPwaBOGxPWpm~^!6$NIX9AjzT%Mom8J33}z9KN*KmB}%G zJ`tK`f11vXE)G%PQwU0Wj1yk=Yuvt&1b>d@1sA5Q?00)_FNBZ(h&{y}`XeeITV@!J zUC>`lnFCAAd!}_&9X_`^ONd*Z=i<>e!aYt75Ui zY5IWWi&30%jC2n3k9{Tz5zAhWFr&S5k=|TvZtz#jr(CEPVe=CIDSq7Lak*&IrF61kw+vs>GKZkOePdx}} zusoHPwIWxp!VN1E#mG)$OTGpa(SvX-l>yR|6;f;2C$3s6hM(4L2^c&i-_b6}=yi;% z2r~EsfMFp8e05dtZ*qOij0^4SjU;ZD`ji;d7d|ktR13~Kca=!h?q|SP@?Zdna=(US zoBq5Ne!h#C;s>*`M^MG-N9MO{eBV1?TF_ z_7R(wQ>)+Km`w7R@$|ebe!XR`=Oyd!cjsnSJVCCBL#&(mD)8qA{^^!e(AcE!_w*dt z^|j?S`tUfu_mMZ5eN>H56v-*v16}Hb%}qG1-OCAYW>^*9i+7e- zdlvL*$^EVAA2+B?t%pWstG_3P+q1Hp zu04LI7bXhvD&dqqOp^(&5J)Sme)^kS|FY6x0p+@hF}Xg|%bymN?s>EO;vwme5oS(( zwWN?JpJlh-sL8eH#RMRtE9OJ(H?ac#W2lOGft8H}FFm-GQ6FU{CFUC7IluC^U_QNG z_lZc^CkNJ$BCc)W^!jII`Noa_uyxt#Bhrp&ROJfuK|LDlgUoYG5d`bqf?v$(!h6j7lZHY+)?{x^?)Cc zHwxL}=#m@6bHXa{pYZ6neT_d;C>Xcr;Unnw*JJK8VrNdekZ{SgYfQZg0X-14OMXpw zGJ}o!u;CW?slf4C#iu+98%E>;9~kwGm_(`H_XF7SI(-`cRS`bw{n8cR^80-B4>UMt zj6092^9HZxlRR&Z*>6(c$PPtP@!P08GS`o(-Jb&}Bq0((|2lZ4Ei$2FHXfGdS@f&- zuvc<*{l@2(vj}=^0<59UDEHzEz6;Qh=}VE|edAAB?$*x%W>k0In^3}E+y(Bf6VvZa zWns8u1b4sE$0i!Tri4jX=J3roWxt?Z%MjQwD0+XeO*BnGSMc=+!=^HU@mDbq(VoA& z-oBWx<(?rLcUltsr1Hh;y$~lfqL!I6CvZ?q-|B0jh&c(rwqF6abC#tK_NU(69jhwb z!qjZf*6rS?#4ryBWA%^C%-`~t^$ivg5QPB}6@=5dai#KMdu^ZidPg@KRj^vd1-CDI zqDSxB_s(TNzRZ=gw4aGf?3uLl|R! zq}c$L0vfLs<5{~XN;02a`UN?=;AEn25Na96W-nftmH)#R)u=dZcIhEehfnS1I}*L7 zd5PW_q7dQR7gw`@Tv5G&%QnR4#Chz;UOhrQ*zk^>44MDj<7R^z+zXt$y(_F*o1PJJ z91Vlq?shkx>Avm5B5PZW)^%2gR?fPrYr9U}>pecBP3Nx|+m3=8?0E(MyPrS^5y4df zjhMToaCA|*g<&o#VjBMUDeA#8&MEN@yyK8IZ|^xD?=K9fnlx)pz7%}&&~A0n`ZAc{ zML_$>HLTQvLI?LqwC(A~Q1Ix<`W&V89HIeZlP;MV1`Nhe_JvhQDX+icE;nGa9rg`% zgXw8TsUY+|qXZ#^Tt0=^K1Lo}l=L*%fhl)hc31~UPK71s;eecgYxTygmUkvllrS1K zXv*`xakq+9n9tAa$R*!2q<){aNbE_uoi9mjZWX!Y)ze|GCcQ4Ij#9U6 z)vR2yT=A&cA=_7Udz(+4mq5~!l3rB3rOcbrGbs=Z!Rg}X!~yztPopV8`nhUxi<{?V z&>UG(#S-aQT!hBlFQTYCKNRhCxzY;KV>_}=5Eld5QV~B$zuY}=(=ptKv8i&7b8W1% zPCl?^_WiYwn%Od>guNqXpPQh6Rq-01><3GqAH`EHlu2h3DW_fb0SCttE)ZWG#x^JG z)okFa7)VkT1a7i-yx1e3vzSUn@Git-hQgJ01*JL{af=AXbvs+{=CZKQ_(r6b)vp=4 zz3!7I*dN%wNl~NGp5U2a4Ip=zy=e=|H`q@iHqKfR4A(qi>E@n3qA^bbOMWQSi|Her zZAE%69D5Sw>INV6SXB;x7!2!%e)Q?t(Bt^!6mCCx44!|NEXtWhTFUZa?7p_70K6!C z|F^x!w)qr$R6w-xt04DpUSvdZ#{x=VePr}KGJZ!|d;KCZVU&;0Z)IMTdlfAJYuC6N zVtCy%%^90Ced=A4^S%9*XFbGwG+(a+VW)wzfczo7Asac(6memN=cY>=mM1xW(bO}2 zlBU1kLR>K4wLJjPNf^_mAELi*VR4h$jaGpUPxMSP=qwqIW;4GacH=Pm^2N^7t^K{H z9DbF!8vBKP&G%&S&LziR^&OLMHh;LZ>XG8&+x;VW(dY+}t_$wS2InJ6ep$R& zcf(h_GHxNJ%9&PI^|j@E4C7J_%1^xGFZCzNITYE!??1Gb&KAhY#rbFvhWVMgfKg-+ei)J`CM#nWMwf%az?lfcB z%l^uN<=>DBCc>4H3O~&|NM<^w7F7(*D$grUW8W-BG`fI=WeB>r-=B9r>Kmb7?fIA^ z;8$3e8Q>w$PMWN$VKW@2raR}cqD`n|Mgsgup8gf!3KP7I;(QUimHjfX1|1KC6|DKH z@{#&W=3~}d@HG=ii>FpN^IdE^`;RfchXpG_Ip=xb?nmluYr4zBst%X(uKpgRE>uHk zAtFZku{ICg#cS*2z3*8VNpM@{^_%j~)$urf;xMp|d`iw@4F<9Eql9WNBZlHRVv$N$ zrgYn=?asRc)!Bn~4sfO=Zud)DqHAlvnui~0rwsFSxD)h(x&KbcNUskIHSq+}mLr5^ z=J^Ge`5x-;m*vlwjm`)_2W&Nq$3uCFCkj4iSLn!^{ThrU4<@7A6W(}!c1#8Oc`t2B z{J;UE10lG>;vvUM6PO!+ZGX?PGFa||=<)OAGVI=z>3`$T&*(_NLcPz;CSaewKF3)T zyzFCL(N1#Ehk)(F6>A{>{7bNsOBUb5K)i&0!QQ6p$J#GAELYT45tPHSEoZsf>8`{| z7qX~}3Abg7u0b|F*EAHPS~k^pcHM4vR|{DIp|fi2sbKZ{;xzkjx?*|uMt`88j5a>s zWe@Up9Q%qqkgU1+TkhdIl6$);v>7(!&wW!c9s2E8C7dfDU9RJ-fPMoVC`y!9HPq~O zMm37fm9Ug($v;B1_sB^fj2Q(-2z~U-Yjn1gj4ol1*;c|lu;KBgQ_ZKjo2*JaG*2L$QsFONQ2P*h*1XUWh0AT6R* zg290cmU&(I(wITR^UpiQ0`@+{2(4JSr)(1HI=qksN`Y6~BOAf)Gs4);YnZ+PUB#^F zkpt$&M@XdR+zZFaOy+60C42speCd9FoLXfKbdKUz-v_Jr_tiUx<=(4c(A)IElsR}P zUEj;WH7MHuQ*AsZZ7+!c?=fbxJzSs-yOI0JQ4i5m>&nO+-dbTep7QXUr$eWVL614E-SsROPkQF{o7{JoPS^ zsy4+RO^aYhmMQPY``oQRW)FB}M*U#mkul1*Z@(~Gf$!O8>%1SdXC$o8Mm*>Bka<5tY~Vr5_an$m(tgsj-DkLmNX--}5XYIn}dxK}Y%0a&K>g|@ji zb?x~~lac*v>Lam7?sxw~8;(aM_p8H_?nMDS_HYjP6^p3V$!!% zIO{^KK4yd1O|;-Ablbt1HzEw;$~3WlW6E$8^yQ|~o1s%M2CKQlS~>_21pSo3sAQ&# zeE(mL*+k|VnO`MneWfPt?$-*sH&VxyFfL(iRQnxxeOq3|eVBgOv<8R-Z88^pn_*9V z=akhC?2sQHe&BwONStH74E*kW#@6TbBK~SHVBh%d15Gfzxje*+s#OpnVczCUWX$1t zlZxlHy%J&ghF<3M;NLeL3;1FS4 zdmd?+8$S}365l=ApEqq$plYEZ4>p38)#mc^WE?2+z-S=0<3bCnDbtOgi zwbvv8Qp%;2L+c3t(QfC*=ujf30%K5Aij=h-W7F-s-jZNgufCW)y}j|S&uud9V{E^) zt7Pka(Ml4tJlaWdzj34>w-=)QdTee-2L&%ay9IN(r-D>W#Xi(*L_c@Ol%B`aJ4IY5 zOq~5q$V)jKOG3Lq!m?M-;lu=e793Uxs`OWZpk6PY)*)9U8h3ZymJd!p8n!@o_k6z@ zQK-3P*XdMDd}uz5?A=1&MQ2U(tU8Ypqi1s6V^Dv8A0$Z(k=pF3LF(@rk__~q8i|wb zPjg*j$i#deLNd2-)@8bO9Ms_A?1=3a1|ArVao#hZ9|1p_n`| z1ftbb3MI9E(K@>f&;1t$SnWOIN_bE_N#d;seXI%VaEIYlr#|opj*HMrF=I|}nc0pH zG8Mc~4zc0a@8mK&VMFr|=I4`J+NlM-Vpwo^URq+DTA}3=813CJY%^dCwMw}$I7u}h zgmF@AhMUBX;_crm3^^E5s~ge#(r?41U&-+CmR`bMTr&}GOKfKF_BmUEJqE!0!DWlT zV7*xJlbKypv_=ilaWMFt)U5kCIkEe_A;m4d`f%8&Q|`f95KMyKH<gNZY{L;$62zym224g$i$-emd z#H-TX?n3}Hsb@Y7oIDx~$NZkQqlmpq)=p!5Ycsn+95;$$FX@kK2Lg9IlUm@=YI>Bj znfV-e8={Cf0!IK3njhiG;|1bJ++C`?Uu{5gcx)#qepIb8ioa#SXt0{Qo?0K@rv{x# zh|?w#o;iL6c#61Q_8t9x2RPd?pTNet9rwM@aPIxuMO0RA10L(SZ|P}wM~Z#j_b^UE zR5_ezO)NgsEgU^WH!f%iKhUs_R~VB4G|PQ4V$q6lRqlYz8g8b9>*s>4Mb>Y$RJY7m zJgZPH9Qer<;RL?bw`2PaIH+dHy$!KQk=h(qj)O#vQBfEprPz^TWt zTE?HdN1|H)cyQNXzOa#Wd}Hn_^~f`tg>cnksvt}rA7j71fNZ~BOQl4pAqdNS|MKBA zSND^u2t)ivlXCu6Nr0aoSqkw4b$lkE(Ff4dU)0MwDEE+Ph0av^^0_^;cHcIS510_v zii3#K_(lEoq0#06?q7oE!?s2_MbFvm?qY1flAgo#H8{Em5HOjX8OKbv$?ag>;oXh* z(A4^5uK%kTZTrqHeG6GPk;>gnF=`{GzjFGI z-lqPtmxMjlCh=?Ru{nQ3vm}(|rND#!`KTKwaNHDrhi==Jm-J_WNT9e8;ex`=&lET@*=BRI~3 zDjYHMs?YV=ZtXMWYBCo;-Y1kCZ+9ED5LBIZ8>an|e|k_!(WhfWz8Vp0SABGET_%1^ z#D93Q1+190Ux$|%TV;^2*@?W<$RCDHzJ}stkWY}D#e)k?*&d=|LarNE&8|<=H?dm& zIhEN6wUo^M9KU?<`tsQUDAKuWx95Ap3@QQa_OB^F!M@0dn1DO^r=Y{RSoHUc&cp*| zZ=Jcm%wx{&_k<=WS}j2%4#*spl9A$jo1 zPcuL66o?=ZtaZKE`rgQbv|^4R3_~7T-#lr*`sVu zc}Xc2XM$HPGo?zS#W!h10=1qXRP>tY@$u+q2TUH;8`;RgTs@rjpGde{@rGv*TqMte zWf`e-vb|IRtqW$JOdBFzlbbB`VPYgmOaPto@1QkJfk@Qu!ygmf3vt;O%VD$sLdv%t z$ID8Y12JQcGO%=KsZGg?Fz>{pVs-W#Wsi5i{ELv4&N{7^Ck~}mL?>Zhlkj!*!viyZ zUp4fug|^V$38HQ96yL}_63!zXzN1R)Hp=FjB}Nll7_i#xG^jO!{NgM!twA68>F0U} zgt8rL*0XW`Yylin-Rn&)waO+<#vW`1xJG*bYFRn>zQl7Z`Qq*_#Bj7!!ByyTIQ1>O zdkfE!_BUKg^Q6Ulh;i4fAIuhNXY|r3g}IS>>AFss-&}N-%>`@ozN*CSH%0XR#%(9O zV2S6tA!Wj&pBNHtQ@2Ox-sW<@Gf|@KA;lKX(fbHRGR!nX`D^+!jWXi% zlzx$%4)lTqr)sJ7Lza*y0Y)o9%!S=V7{Lv%at0WhSeU)TxFSRo>WjJ`N%~I0J#4+H zE>-`Et)T)H#(heVA84r*o`&fZNzLn5xCNeX(It-!EEs@DWeRQCbZwp(xac_jtq zzK;N%5AV%TUu;M+(RyxhxCFjj7{2@bAV8?epl5K`Ld*?prcQ$1c+%RZVk9dVM)=+Q zdzH7MafzX{T8SPof%Go;0E-BIXk10ignM|~DA>F#_)qU!1r4Z1`RDn+;&(tdKoA~j z;(jCHryt}tKe*|9q8cud;{JGB`N!lk2YMEdBk4&ht+7J0;a6^S+ z%FF{?oJ0p(d1Qy0FT2=fzn7U>yymMN#QgBL1nq4p87~k2n0(XNAk%7%je9v!$qRGg zE!NJxAN?|(o&&W8gXT%-tufCX?}2;&{fftJ3jA)vnAEA9c=bBee=cm9WMEBFr4Cq& zc9rPs9_gD@GC8jk+{3h&ryz|mT;?+~c=6-kjLev{!$S%~l>BLPQ!8yK2paZjN8bcH zn0sK8k}(wEj&exO;}?S{zEcL2f~uCheU4!3Q zH())Jj<9Q(?kkO{;`L^wgwQpkpib^K{*c5^)VQapsdO-ly|&ZywhY;nJ!Q5tpr`aT zD=HoB8)ZoBjrdHqq4X61PEq%MGK{5zNB*SQThMkyme_ONz866&xiwqh$60@F-7~`Y zeTPGmQvGS(7w_}=H_HWR_U~^5*>Emu8F^hV=l!5{uLyPKu_~@33#!YNjhVw;T^QSa zW0jC0PXeC8DR6hm4&jwZ&X2ei6|nw@^nLw9e8o~{oG{HyJ3#ueG=onC+{g}170}gOozu2ph{`8Oj3_SaCFNYC9dZ4 zo8!j%9`_^#IWj$;X{e zHzP!~-}pG2`x^UIX?PGL|NNbd&-Z+`MWP|m#!w2j6VN$2DkA%IKk4)JlE-w1YD@ZW z%=8V9J$0voG7g{Tk$JzOOKIcvf^s#M`$%l(?&2H?fqafvS+v-i3hw(kxa}r27UNoQ zRQ_FNCbUnVN1&9`#L(~kNJ%!pALlZ3Ra6~h9cJImlE2>qHpcaZvE_6b&w(+VCwM*q z;pX?qyPbNd88^K?2Ev`YiAy2YPP@bJ)I7?AM^i>-bnWvap{oi0o7U6a7QA8Lfaxp= z3%2l`q_w{cm!~kXjQI596S#cZkA;ABx{nr9wZjM22^m?P;s?q4{&?@=w)ZD4`HU*KfU3p2jlD9{TNnP+!&}5e75-Rvw#Nkl<)&R zuaNr*$nXP*1d1G`p2|kp;B_s(Xf0SdWHHFB`y}`qA9i+fzqi z1mYPcD4Yq<2j`qO>U~xjI2`5L<@Km{B=eprCa{{7RY_5k&w_8f0pEJl+R&c)k zVPTpn>STWIQ=&`!k^}H5*2d?%D#1U5O!aaX?mq!|%H?JqCwN_afS~!V-_oy|8|i9& zoXB7Odmht@hZ_fmgr&7qxBS*|74Hnd^AV&26woOtf;IRo@pZVr+^U6>8s6nXT959f zUQZX@C=T)TZtmYcM$_|{dUSjfyh_~cd5qOs<6vL)o}b?PZ1~qp{bgk@2!IJVeYLoB zK*_?q)D4sZJgZ-6LK@tDcCA}$s9$O@v%NF62#qd6>mu+JWvlV)O8|``lOr9?bb0@v zc8#7ue2Wek^t|0()^pEb@U`>}t^LUW=JOtYyxjOF-i6ext~J>Yi^mKOq4zpMrAvT# z0JJA&zoMA*II#OEa3qFwYb`ug)&nspNIT-b?amTFLaZCJx>$4u#RlZf>h&gR ztvv^wgIb3We##K!I}HSJUN*7#jI$EIkPkRl^d+ipScbhGOs?*y}-4f;QPL% zsM$!Kyvn5XK`uVOzuYIGivy{C=mWdc1B8%n%z~}e6sKM|Y+e}y0uWwRevb-asw87- zKR8y?_sH*&GCS4Q5CL?nOO>FqK|O`}M8|i2UDnzBh(j%~V1jFgwW3lfCnwLoyQd-#PjVEMru7O{)1BZQrRz|@GHEu z+%ktdtQTMoau0B23dF~n*{9tLJf>#KS^N-NsSfd@USpf>AHKkAHW@ie@yJIO!&#ds zUCFL7I8Yv>yvV!(eopVhhuVY5zZpXO?LTWvJ#v6{n!=+3E2vV+(K+d$(}mq|$(r%! zTY2R>ULDo!>gzx{ct?<7kEkF1yrf;rtRk9_Y@o%t)XR%Bc$gxmcOux*B-m3OiTdr= z<(uBh>6ul5GJk6$W8q!>g|fo_jsqv7*hin!#u$E5+s>-eb@bzV{jl=qh!MF2xV7S# z;bFBCZkYPET+7>r{gRk*>C0~MM9%|#@cR*>-GZ7jD|vvs;{_T=5zbxj?K!1~H~nX} zuSx4mLHliXpdtYNW67ggbMF_9EwjY)N0e5^>sG5Cxv@sN2(KP=fVDtFxzSfS_$#9|-z<=h#=r@AE~_5$#P{YQftb z)8Hjxu%jj-Z}onN7LQrYG{^nmP|KXaW=sD|886_yG8i(2%#b|nZIOZZnsXk~rm$xp zhX;|{mIxP)GyFk9#G1q9vuqIO(xp0KkB(4^6oTIk-YcL&#Ue!W=gM%x03I@X3RPJpvQs4@|q+E9<0(mpau&% z5QCIaA)#xvS@{?O>NH~ohDsE3w!Ur zun+or7m-KH`{|K^m@>`{i%G})QTGIAv!wNfJ)zqGeY3jLVUI^FplZ(1Q$NXQhGIg5v}02m@vUJafn@L=POTjf}KQIAX^>n1NX{<)18OczRSUqMe00B z{p+Gl@g7I^5_Rdp;~k^e0L(NQIkHX4?FI6PP)}Fu%#wsBUgzbuofZBf7Qe%Ew+5et6&wJLZs*!C)b$6de8})Bd$YBi-l<6eS znu8HZdu9S@IBZ@0g1O0!din8VzsAC4f^Pe~zJC5uibHhj?z%RtsLQ>4ZQm9rQQP~n z0LK}=eS|%DfA=4+GQ#+6Uv?nL;;o;C^9>C&j6fH=YYnuWSGznNjEdOqeE7;=t0yo) zlqMqF&&?tHlh*@~bi?Gx!-nm$Cx}J4wZ|rSq8bIE_f2CZg987n)?9kO#tQmo(Qk$v z#R>v0^tfO_&FF_D;@_w3s1I@KC;>1lUr7pKPn{L+b3pS7GeByyT=-9b=MW0oIeX}? zihH;6lAldy-DvEj7}q&*$5gu=Y83cK>^Be0s${pH)e)Esirr%l z=dEpn1}vLWaca1&6(xm9(x>~oS|3^x1my>#H1#J_>Gzo*OOrcuqy$Z>WgLmX4O_Eb zP)ikiW7|&G&w9XIn!mrB`WK!s`Fs31UV(nyWpm`_IOkW=SziS568s9u6U~xuw;1L| z-!md5piLHi46+$J6X$+qvrxjAke}2RYQgV_rpCIw1;Jx)$X(~pk=y}!LqmmmFh@J8y-?_AG%)zz3$ zA}}k0j|bRSfv$N9GuMlnwCU*wsrDp>_Obf( zTWd3bYl7QXYVrNJe573IavoFCLPm6_HVD`wpZA5*LkfTjP*)sMbTdax9?=3XY=l8F z2Wx~-?Iwex?N6A00fDO+zI7NOG)^hZOD~H-T>8k$ zPH9RpYL}Tu$Z%ZLl-`;0N>4+It5pyVR9j0X)54>>-&Sy}n)%}<&>0IKLFq3U+;$!y zs%uPTCX}rdi#5Ykk-%ik*=^n@<#fwV_xmDuTanUISiwAQkI<)gPJ|N%+&iO&+)$vlh?woSJ z4tC&&y2Sv}Pk??61uyxBCIjil^ov?s2Q0Y`-J8o_cLlS>5B}I0DmvTyCv2$6w*?+< zUXCM*7nmyNuq8fRf0n2`4uwc-vmv>de`DX|hiSJ~q@ioFVAp0um=j6Q+121^GTyJ; zO9}U~&B*&MJlKBBgG}5M!G0kVr2ts&o>s;ilY>@JBG@`nd`vKyuH-AxQ9j+rv;22& zu!lzgHzXQ@rL5%WJr*o<|Hd3m_SNYK!p(1oA?25~Z1UxU#ZIKiF*bpU_oFObY1)1G z6K)T|idN_9_dix1UNyxYIdK;w$QJH1Af~nGdLgy%XIhQbsGQ>m%``*I8SDM|QdxAQ z+~dQQ0vC^PB$x2u^8n>A5uLC3(cKru4x==AN9AbpPBwSjcPMW^oiB3DA?LrC9#0nD z1xvN;tqTmLVxeVz(tH{)3sAxM=-Z8=K%I!!vjYQpdpj5&+4Im#_Q_0Jb=6m6O-fS8 zNbA>%9$nN7keq$q$w*_yTivgyNQnb0Gp$-iogUnfza}o-Kwm)kQc9}C_J?4$KqbGt^ISHCOCZj&Rc_amF7bM*85 zYkc-C{E!}6RE56*u^cPEJ&T3}d8GlSg4Tel4RZs^EcU97Oh>1)H>r22$|MHFfx9uc z1oX)I_Bz{J>ir3^`lw;=`=Okx=(U`gmmZ7iVer~sU>V+pGZma8AX0~M<7;2YOCF69 zJtvOUqfc(-9XIn|O?CBrmFqh_%{Tdkq!)wI+%@_hd&4{Va)wXMYcOz-h<1MGBHU!= zK043S23nbep?9$TKENXwTVeRHv)&KJrC9IV#C|p~ZBHe*dAn9!&^BfQGxG=L{28&d zmwUqjly>`maSps4P#?A}U(XtIMD@2eQl^#k>3Kt`1PGP>%cI|Z zc3?wkJBrtjR3~tYfuIz&fU6|ICam>>wN_q_+`WV+Sv~nFC(GmM;-p=`5mE**s#o##`^TpK<~F`p+xeP+QxVfD`oW@5FL!k7N}3T zoTfedI^}lG@4qVa-Xy}dD|S>!#R_M5^6LXe6tVnS$MikUuMk;`FcpuuwY(7XUr;ib z)AJ4=n?&I`>g=c2`p2#@r%4zOvAT7Q_oZ(t>Hh8>w<$93!3m!COf^*7ygm))Q_}m} z+GC~{#WV*6fscGAGKbsH?ky7czKv{IVN0Q6$B?1Qx5b(Skls@yyu`)W@5rQHx} zdzqd7urP;n0hN~pB`4rhaZ%BD% z?Ivo9rI!C#IbV2P@2pB zHwa|;%-}w#4ceDMwTU{ysg0?6yjZg*b5Dck2&y29a0#TPElvdve#H%VHOONH13pkzxV@W(DCq zz0CH{I$C{>t|msG=Rb3xBd1w~XF+??LEp&;cXY_Y1!FpXiQy!q0{l(}OLU-!WJP6R zW|tw|JxapWVb4b0hovdKJ&)*EaidhG^M0q5nly7W z!4b+uljH0D&W23e=J4;?55*}_u71bm+I2p_AD7|x^Sh4})Ho(iIO0D8zpX?|k;1T= zA0AdW2mj5anI}1to))kB*Rxb;68R{Xe$UT0fvFTWa;7JNdaYseWAw4G53l5LbkBH# z^`7DkOZY%ibMN&y;4ux9eO@^f*Iw_3vNz#Ui3cTp*Z?MVxKRX*WfZ9Cb|U^*B1Qy< zc;4@dvcU#7eWBmj>~?eD7YEXL`(mB9Dw?ViI4o|YuPWua43_dy9*-n zRi5UF)U0^Xc@qX_xm;hHF+OTADtT{3vN)1}((?uM72%UmsYkoKhekO|h5SZZ4J2aP`JL6a09OHzDpSI)?L}f1o6!@Z9mnP^nY54~=H~S-FKz47nOa z!EMBwl{i?BAeoOSyC1B0v(52sBkPU9akTq=&|%-_7JU;_5AUe)xC_PQ!UIbAJ`@l7 z`}*$3<5Q$wDWH9bynTVZ(78K{lPFi!?a@~<+;&gSalZw-+annc16X)i#W2O$;G$*% z%&}rDPfWXA%c_C5r`!r9v}aysLRvc~Z6=&PP)(yO0b|2pfXM{F)AD#Yv=rr>vEtbk zRaWO%eqkkJRK+L_2tOX!LTmo{QY{wV$sq5?_gso42|3MkPf?>|OA3YzS_=|k=RRP@ zu9WZukPpHu6`F7 zGf#|qh@IdJA37j?kfGt`l#@=CL*4DR5I+zDn3zB``E1pCsyzx?Ig-K>y4IA5iJdFNm#;D&m&b_9>~X5 z3lLmlX+H^3wl3$iUfJt)kwGK-2_093-g1K7_@6*4w3tk6gy${f%Mli)G%;{hjKm)W zq;T5&hL(f+_>@n9I!4YKu5 z@pH!drbIjE?UfV_OoI~wvNs$TIfY+@@idhdL{T01@b9UH9oRl6((z&KCP(UvZedOg zBFB9>y0GpMRV(?4tmtIDuU*OfK5?L$psUqzaA==?QSjpw^=ijPHUP=UTc4WyZ+7-# zm-l@hV5;U$uT`sEkMG~0U-(VhhurX*cogsz2gu3Ph&*OPQuqcsc8n}0dLl=%izkjN zZsg2dpI)x@RF`GKk5$rKP0**6UP1tBBZwRPP4{f+?59i4tQBndn(Ab~s>^seb-afm zSJsPudRPmCRO$<{AhY`r%ie20hOPk*Rmu~XLO*@>0eO4V1{yJ|n6yyx-CtO)(F4-w z$AS(KrM!z?rTCo1J6FxPq@SvWI^BVV|~V|b)Wa%KpfhnR^7Ubt={#YDWpzm;u5<)F15Fvm$PVCB1<=k(8qw9 zocJWnWtH%{xb3% zm}UR$#RFfQ55f<68Jp%8qf66&4Eb|0%5u3Lo*=jdcD{#zW}DNQPkjP!*<(~b-v@^} z8|7bHi#mSxa@uk(Nrk=@xbKNV25!QWV@ZWR#61EA_VogMCxd&c%DGj8jc5tj0Ov5X zr)3XU@%2&SF@4_QRgAcqdl!kprYQ5=>nj8p>S1MK%8RVU91mm|q=J_CYT3|~z3-p| zw+^6FiV;dHm1nxg z^uNM$FT*|tPYi05c-0q4M6DXRc<GZBAZJYRbrd?4s)`#>=9_}ARoBclbo3j4R=f!mA z?g|*e0``*t-;2%0LgRbjIh?pY-Y?_~#8HdXU(&vWmrWExG;_1ud_NFx%?b|P`jF>- zm;%t@pQfW!(GO*+?vu8+6-_U=Q5vfg5RmK_WzFPI9kJtA=O2g$&}MsrS<&NilS20H zZ|oMI9PSs83tcj9PWCZb4Z%P{7$-dszaYHG4)|D`M`%yTS_2S+$gB^(mNXv=1+678~=pR{mC!5sL;U!q%g!qn+ab z#Bz5+#0x2!!M@4@^7jA~lldFv^qb$F-?ihdTCnW%TRX-3mB)TwkxvG8;MmYihKqia z9&b=^FZTD8djQQGiE2ON?(}4P^z<`nm;V-j&rpxc&>IlFjQh%5X0+F>E=Sd~jKlKh zu+qyhV-?`((1GqM`-~5QdN9=o26mT|{emFwEGMt1(Sv6a_Jq%Ydwfb!L5E9UDk+tr zObr;D(ng{SSzi+v_u`U-3thJeLl+v~cf7r>?h7`Hj{6qgXrP@wI2vYs$^3JURiDOr zO^D98@5OT8Ue+s*1_JVaj8pZkUa92z3aut4Z~OExjpK(05@VQrHrtP+ZB6hY zY8WZ-CaVibq??V>JO{(bYe&x@+_iFR(~U?0J)(F$til^&>P+Ccgd6O2C+1>!(wDm8 zjDh;8(kN?jKnCLA%gJ{iU;w@YCJF?dfjWeTu+P8g_-TrS&I$9YHI_R{uQ{FCv!zU< zgf%KsbZ|DoJJ%mb^~pnvgiU?G%_Gh$1w<%cXh=c1(LDuT;tO3*ZE>%Co*h6gZ+FAU zedT~%RYsS2W5|>dMOxP^^xpKx8R3rmK;_kr4pmwog3S>=XSAB^fk9|CMpzXq!O7-X z34ZjILc8OmJ{0o~+?O#(KF04KA`-v#kR~EKVzJ*jQ{TpT__Dv|L$eWOOp=neFS0P6 z-VKzYjM%p6j)Gn08_m!LkgHgpfsQ>S7?0mQG4&eVQ@aq@>Jx>Pd7p|MzkG$7#uenzn`(j?AryfiH*drPB zC7vXYcej6XSPjq)dY{{5dS8%e=({_LSAFpC%bR{XqbL!NpSN}1L)e*9^1X%u#eJMl z$xAifABAnUz)zW2F8SCW2|aUUtneU6zZO!SzA!}Hh=WwOU?iCr6tFf0rQJ7&Pprq@ zG_GiDdoF!VbJx?CTOozzH`g9?TbK8#Y7Df(x>?h7T&PX?#@D4Sv*?>Q+lRPwAy3zE zXK8YB^85qinr1OBcDtfu=>;~QQy}kwjo>RJ4nIk1sr@#-eIGo%3Mgs)Y$evc*K5{d zohQ{9-Vq}t>f-0KCr~!I3T^KCu6V=WX!0eSKl{PH-yB?~-bM-A%({|-hZ|#v)8Y;I zm^tkJMC7HIZarEVF@wtUz*54p50m(Mn(rA&Z<&ha<8>5afPBlZ_wR|gzKB_<-~mFN zoZq&j_0d+VhUPslQJJG)3bhr3Hgm31pfhu}>+|lWjT? z1--?D=B-GpYgIk>Q~G@%9w1&F=i=XHHuDtBSz+JXoqTL^TKW^!KB+?SDERion#t|3-uNrxy;yjnLD|q{S zQ!g9ol&ncOkvo^)6dL=8()bu_34Yc*0UHwOBk9*cZyjG7$7Jx2F4#fO`}*WCnw5Te zyyoH_Az!)6Xvg^h&=0y^-Xir}?*mG6LK$(#U>rTj0W`e@M*fd*{Gx-2OfYF%|b!gE*N2HtN*QPc{)o$^}1WOYWKi$Phl1u zyFfh{^~FG1riM9Gy#cvIMCE!Uf=}zOL!}%;Tuq-xq7Ef|DtH*Q?tf`z&k&obN)_T4 z=&|?&wdeLSgIER&#HsNd`n#{+o_XQR$Crhbbj3E|5FByY$~97!s-@{#t6>1ux~NUo z2YSW@7lh4YdcH}(4fA$It+lFi*L~^^vZ#-l$+&)|R$jjRQBcSRE)5qm$Pg&Ww5!9_ zQ2olx6HB0sI5t#OO`-l4tgn>?L_aB-s;&}K-+L^)Q z_Qw_n^EC%AWGS$&lOMLcO;)PB4=GQDCY$!VvB>ZTPx5`tG#Rkg$6FGtbCIiY zTjd%z&tucYE-FKB5g6VWHcDkF!2n8**tE6A$l23P;fJzR)l$E9gq-40EUHi33DcMB z{=zKXwhN&QvMsA>3KpvJKA6)b99!+%?%sZK^w@2){mTo#{3&dEEK#D)t% zyglw5z9Vyk2YPxx@Au##Pb@fS>(gq8Q)|%yFe0kF3Yt^=Suqe`e=%o$bU9ZnUZ?&< z?jb3|*D|t0t34Di9L0ToBK?}UFRT!!3BMit)irUIT#r*TY)YU`uQ@hjKYJtnHMZ(V+PzGmQXkLm&INs~b>B2-HP05N-D9vn0}1!+ z{O%9@mSZBta*I`88Vd3?*2^$fFN))Hx{|z-jfzcG@03x>*||bfpmgkSqT78Pc3#m- z_Y1xJP6pEOR?+hjhiba-%=Y?ihELR6s`+5asIAZH@S=#Wh6X9JC170CIuXr|8!lt3 z9K`52!Rq~Jlvb71z$LA>c1M57FsZZZq00qIO0Y_b1V?Q8eHnobaOz=txRj{hp1Etf zhWT83{;&_1UM58va0`Nj+8MRYpk?FHRRL~7!tTlYY++*Toy%h%Bxu(xfC|R4%&pW6 zPep^nh*%Y*zhymCW0@~lbUcChz;o8cKYnS|xE{k$a8Z*;8G_hjkp>pVAzF_fH2o%_ z;7lP+vf`IRm^kK|@d51BU2kw$z;37Q52^m{XTS%Ws2!ePAl_qIvVVJ~Vh{1u+-;1b z+-l&=b$l7#+)|dwOO3tzvyOejL-CcHG!T+-wh1_hH*9;57~80*ad zCe7J?*O$%brfz8%%DpGCDyMnG#gIa=c_l#l(2`2_zGrZQ_B*ksm6>nd);aq_CN9fX zPJ2A?+zrUnv; zDXb+Zsp%))yah;>VRwHgSqwXXmMYl#53<@4_6O^Ph!C}EJ7kIP@gyXuQ@YC?g66RO!5^74L zmkzK+bk3&V?ZC{XCgu+sNMrU5k@MS&1dGrZQczsAoSv<^xsws1NO z&C@64zCE+jmIYjvMEc=1>y^@WuBXdR@wSUGY(Seai;U_Hy@tkGe}V~VO?thi6u*~m z{ovOv^&vX*-h1#wzud!HCB5~IR0*$&_cz-AQiaHd-|Y;xMq)W5S{SFla47LghE5`p zvW17CyyJVUf2#fP%+ioS56Y(@`v3OeAjN5w#h3RnIDNS6nT7Y!d5dSDuOD!`)WjAa zt`Ub7Or0pxi(f$tfMy=hY%oO;8&*1a3ROktimcnaGD}XeDAC>w)mf$fbupsK7RKLE zLSUc~Fq0<5KjPsnZ$`C{GR~L_(Rrg0aG&2^i`>d*v={t5uc4nE9ug*OP<}22e{cAw zd{RpJx-H@MOyx6Q17g0%$bMRtX^}%OjjiY3zg1YcP{We`MjiZ@8iOH;8`y)V(jB&V zzjt_3S^+9E3LAGsCfVzr`<5VJf0&z52jeW#PyfYfQp33(+n@#A6g^FyUMBzB;PMu$ z=DS<0@SM<^-3$(mA(+1Si8HeZh`_< zU^wA~-uMjj>?XzN>c#$C6(offMNe0&pdlWj`Rjq}DEIAj@WboqQ8KSgNc|mYsKv`m zcYF=)z@o8Oa{UO38Z`s*@35~*GMAzEz~D6>jFb(7f@rrJeQkR5p9TBkL|EvRDNcNGCx_z=*n<3Yznqz7yQwz(r{|+nXrEkMKCaa7y4KX=xG<`SKJnAOYzkP^^q!jJg&5~QdD`*qp{N~<&c*Ys&&lI}`+SmHo2iMxwV)6(7_Y&dU@)AW|X!?>^OQ5dnTy|Anu^oMs}-5b49diF)2W#kB?P94drK+lq=0DJj3#iTta}7z_~k z2-4_10k&^8Ls^NCo_zRy58MsW7;u85y@wCAYenY=35UadFy^{~T45iLADc5u{d9ZA z81p(Gi{OkXNsI5$_M^?%zHr*C|K9WUa@(UPJ@pqTJGoXS?3Np<%R}gu&-8q2?;BlZ zrx~pTOZydX?r7|h;TO2txR(^h{v3`|T33fJqdpFB&#hyv41=!Y?Nt!@8as5OKAlv~465@a7v`d(^Gbt+EI5*<;&!tT!Lqmi0%04EI=#F#@E8)?3E-3@Ww%9-@~2INoexks8ufP) zczGPHPbfS;3OoeN+?)ngXj`Xredt>8k}Ff78;9wE?C??kY}zmz@vtq>HQl2@LO9tO zgcve$=@3jCT$3A4<)n#cs|7q@d36}=G%|g46!FG#MR4|~A zzt>({HH+;14z01h^BL|L{Ag+Y993s70_!Onc#DFaf;gtj^R_@ z_KRM-J-k|oR_9Yi{aG@ug)^2W=7{~qkM&kOZv`Sb>yAQ&ezvY~uq?rN8%Z7`*q@(R zLB2>C`6u`MtfT7PCO=3$&<2aAMc6lUr=~m{y}7fcJjVEyQ%TBcyRJcYyST^L3Ty~J5^sCaPE!Obgsc3ZGqi;{6npu*hCj016o~WB&vfFksw3)%UpiT2D(ypCu42YUZ0u{IHp8wEWun(g* znSQ_JQuSGu?T5EJ&u-}gliiPGn9UpggD@zs%8$DCHU~yGc-1G# zzQ;y~M{2t<8Ya7yw z5O4P^pZDRe717?4KqRVYh?dUIr?txS@nL3fIGp(DZJz~li65r@fCpzfsJwLbq+tYCvD8N(&(n(w!)DN`~ z8zMBI&8DaOznf=`kE5W+*$J4cM)+P2)09krMO80L2HfvP)LD>(4x}R3 z93%1mh{K{i_A&b)-VdQ{`TfLI-+0ges6bj(YP06O9aZp5WYT<8Z|~elOx$tuEcV?; z`3X*dF-yCv%uQ&VG5T4GsuowuAt*eYw(#*XH9u}2^;>bjuQqW5T*umxea0|>drR+V zd^~KQIb8OUMw-&$hIvZ64|K`@evRzeLwWWdQyY0-x;}XC*8JRZYUz9SmXtj96>ASsFtH+ z24wMmZcJP&t#p|>0}wqra=$SA@g75v@#&wYNHX<3o(sQ0F?heaPjV?@O>g*e zA5_T1C%M=HmiPsGbpi9>Gy$NnNx3dlmp?lx8y83wE-!cs(Zgx}({ft9@!s4mA-``j zgnL?eJ}1j__I?H^y3^@RFz*kRqwDL(U!4 zbJ`Gy{c^3=ywlwG_$ST39meRuv)P)h#$6i*8q5=+Ww0Mcopv)7w0rDVrk{-K3Ezdm2w&b9X3^1C<0{7^UT&L#15U@t zD%UC(-*=P!CHvpt)Cyht&XqtFB!=%C&RR+q-*e2e1&p5=<~`}sq1 zKl+4+Yn(=R@4zR7L{4EDE8v}dE(1j9Uhd3cqMmvz z8@;ww0DEz^akN(8M)bf$h$z_K#d_QV7azLESN6-i@=|r?k6(eaSh^Y%VU=8$uT9d3&YBQ+Wjo z=CtGXz8?s^8D<*@8A^>`#hX7KYy_7w9PVrJxm{QG!DD zonz6fYUrNe-I%lDJU#aaw{yp^?LC0eZevNWrKVkbPbkT>4s5K(Tp!^dHd6MN&%Wx> z&s^`9X!+BS(E!noy(<(habVLbMCe-nV*i#nK6IhPw>Rq>JHEK%x||<3Op_n+ad2SQ z$#>s)cnlw{-OTJ49;qsDlok2=@9hrlR0Io^^B#0)weby1_4a8vB$MV6)Tk5DN!{b7 zE{7KxqQ zX{J6;C^Etef8TdsTO-OgW%W6EIvr61*x!YtQXd!2HdohWM$ODf9WI9PKHjC0Bf^AC zWn)yg^31D|mWf)=XZKAd5WD|S>RuCSIeJYnw`{{9JP;nM9n204-8RrP{Px%7rDm|$6Mc}jl72lqYU4O=kpRY%s$`Xz4no6 zA}V);e0bAD`Fc1vGKlZuGmI9NY_vxg^$+?tR?5M#*2{8$O7L!MpZn}RKbx@$!Uf|# zrn|{Kj^R3w&$_k+W4bg2BZ>DJ=+!+$4zBR~rZ&o}4TCb`#7jwS@c76Cxu((Y{<2*L@xs_S{ui!Hb=zS5obYPDIe(S0*fxN z%&et2SrD!ir4e6at_~uID-Pow#BVm55%*)!^y?39elXA%Hr||5nd=rBg1Cc^i9~Ct z>*IDQwds_SZ&eGZ7Xa-rnY{nFGl_Q9Ox%@Oz$1tGIdckXKM}_if>_(N1Xh$wgyM;_ zaX%|++4zk5Z!6P~D{pki5)6V(%|_$X(LS_`vmc>j`X1RSNV2Mw0AK>Hu2VpxEwl4T*x<^N%FOVi`<5qj`f4HT-5p*Zi8?& zCbKN=CiY%d>LY;nv@GyTcp4t!sHEGq#lm|7`|sq#0x^d2zcYZ@gO|&tXhJNwW%gh< z-ZpXNDosdsF>JY@Tfg#Q$s=X&8ybT5(DpIUU@pD&5rHcNap*m}!S8u}KPW1K3*5@+ zlits6u}sptr?L8z(^>e8o~wUEUQD8NuU8TK#fg8(rk`Ky9v_fqy+bZmM&4pjjf|_& z>I?CUp&6ryCqM4NAL^z^DP|mBC&mlUSG#2OGkQeX#g-BJjI?qQA9p4oym$8nGG9R7wYUe5P#Vl*p(2;JF!>E;o?tlK$W8q2t#^aE6kQ$YcC zaemh2kaOKI>+xt#2f>!uTlUxd7Sx|aPWu@|W!PoO}WRK)ySL+g`<>LFP#66_<% zqu2jE3%zhWD9KSb|OWKId6L_idHuw(x%^x{PHH8 z0;y#`w|xS?DkzB8HM6%)mExRNab0MXd7aH+`C_R7;V~X~-l)7(^S10ZmUYvUFM}P& zM#JZE=#m9~_13FRGYDTk$|hjo@i7bZW!ehxJT<_9ET1GKRsO8B<3oq1pr*_a_+{99 zIVNU9$L+>^!;CG58_o2?J<861 zs9ibH)GI%d!WlTk{0+;|3V!sKvs%&pi*Qn&HlUUa>Kh!M#5`GzAEM3hpdRm!2QqKU zdSuf5N_klT@D#1#!zkxe9MBZT&z-o>f^1)l4CwlKMv3PIl7bm}vUUF>&eWx<^!rUV z$|&TF5xpx=Aa(uK60$AagSvA^SD!C!O&@8Gv(2Nq7+^Gmen5;xdCme<(u=2~2oSO| zdfo=V8Wl>s5{qz_#m!oq!Pve9cD(-ODxOCVpx02$$Yc=59MvUj@^?j$_7v1_&l_7Z z`(1`*D@q#r5jLRv^?;{|>lP`$^nMlMZYDYg4|VFsqs6Rrm;D}Fjo3KSio!3iRJ{>N zn5HCrV}v&TaJ0ETUh#leL1{nTFQbk-_NmMLb35sdaJ?%~l>7U{bpsikx}5Y-$8f*{iWRy$K0)rR!uO&o z&ETQ|_$HMAiXAZ4+fCZLFve7*w95dsv>n9f8x%|#K6jTMx9&bUX=@S`JMq=6sh|XotHO3q9wV~ht`62 z*b9-_bhPS+%2{C}b-0{%sk)ZYvDRI=@D0mB6hZV!aW3i5Oq9Pl+QmC~pU0zw6O3{u zGS81Ms2kn*Q)g@U#66ga#u&ooGM}ja{<)~9XeNH&kvaJc_5>wjd;=;;!D`W^wp@1> zi8QCgaW(+IDBX>im&T$v5`T;L`4IHNaN}q-UX(I?d0rDVXDu*h(1#nDsH=<+4;mI&mVNrOO?yo`S%QO;p6OJH%=aHUMBl^PKm1L zw`c*cg^B#^9tj~7I;^~mg=mJs4@QIcE)ok>&c1X)93ney_d7GqzfLj=9>G8h!9jG0 z$0)0RUSG;?7c2iIrWX!BeO<_eTK2q;0h--iN52X*wXnJS7e^c?zB}5|t+(M3eYv2Y zyh$N^G=%d@?TF?FY~>zYoTbhSZ{xkEVD`9zksPwuA|88*kg4$2k=`MfuR(gr7({2x zH@&sE*d9%zi;sKF(4m#Tg%jagEeh|9o;|h8?Ft59M&1c3R9i)mV1tu@J4el@#tA6z z7Z$_k0;`g#f^ zG;sJd`*iDmQR7*`UYhW5`Bit*cVRw=N2!;yj~c`q&h_~BV!k8U8ieUX^U+E}kp9_eW{n zW$b{P_q8i8%X!v~X8-zr0yq3})DIcEt2Zu|@Wm@DI5|dW30FVs^TbO(-QVY8XssD( zIJTROd2eQ9~E~x(*R!N#?j7zT}A`giz|MliQG&5s8M=tC*R&L z2{Tvt?>B(YSSnr@`+5au*Obw&@6afz-r#|Qi)Ieu^1>x61{=Huf7hq!yOy(mxs>kV zjiqsjd$qKwX@P%+?)t>guBE)d8_OQ?H!bNHKXmBE{&ocFN%1ZtU`ZdSE^6^$8v*lD zMTjZqebVzI%#8ASrkh85Jf-nzM23{HAEFL1t5>N^&T%{Px*EyB@sjbx*=DhM_WIWrEVajn+K=e_*>{y@c+z;mSitY2 zELhQaz%DMTxlA;27Bj6fD=uRTwiMR@1+0kU{S#jj?jj%T^9-M(>#N+yy`TQx6|!2l zMqQ#G40Ozu-M;!iPY1M~0-(o7RdQMOo0tt>bq>egKldo;ibMUvq!W6UD>7KN+b8o^ z>FNa##C8Pf?GaphWSYDo21h-sujcdHTDE!to_F(jo?o#>Kjc(^Eq@$;Mmsy7$rCtW z8W*{b;8g`xSFMA&ev}v0T|dn%ZK0o^5}Hpgap_3x{dhR{r|F0~fG*AqJw*C46VF-Z z;%Z;-)y(3;c$pdL<4?uv-8zP&9&IQvEG@-(vY;HkcYJ)5taeS7S!VuzOE1ZC^SLw{ zPbwusl&uVn=jK8)kn%as5+sujD<_Y1{{yGa%Jy(y*(1g$sL|3_nx`X-=A#Hp8_opv z6bn^+M*9P9953<#UqAB?0#>hA8SZE1*@eyAdmD=uO_n`L%h95!8wne3(8QlA#NkrE z4-{^YyXQ3uC`U#!>`l$N+NF{CvE9Dk+LF8XjA$%(5xb>bbx0|M?Ns``hx>@Y+ht}z zqX8Y%SB@O^nWLAt*IW_jHyxxFuK^%E4pm+L0=i1HMS=qkEl{M$?71ZL1wV-gt3#}w zd--d=<;OEhn2iU!vCH$A4e@5}bM6gZx>N+?tD(aBiW*KZDoi{#>cD$l^+k-(%k+gi zt-1XnM6jpe9)aJzb?5vKt4=f2fF$=e&b*_~M)!NH@A2(MMy2PF-MtR1atf2(gImVf zAonoB?(ws78E}jtFTicq3RNH9hM8gSM0-0@2A0$hnJ0u9{kcDK_CQupHgufW&NF5suE_Lob~hpV z=)kCDu#VQ(D`1~n8u7mZ66Pdjmo@{Q`B+`d7b3ir{bWiWh|n#FnB4B}TeQ$#L7ZXO zv9ah({+YaCG1p{|k<}!6e#QV=Wum>gSME}9zlK6lur6cd+7bB&8|`WBb8rv$ICQMv zp1<<7n|pS9?DCi@#;@6^Mp;v(;V2SM%Qc#4HbvVZwB!LT2FD+go7`Ko3Ang+kCDJl zEfc_jA6dpCB>U`WS;u1h1*a}MtLmA2WMC=vBTgRL&KHM){94fexKZO`1QffVst7KA zB=L&A8JS61;vOx!1zDU?6799~o++rLZfQZHs670#YUTUz{=m~`UW=+y2-@KSCd5q0 z{!(|pjLUQut<#4#m?YS^`~2!ZPngM{3+9mp=YqKQf%&S{gErO6(>_KwL)t-I-^fkLWxT~YK#&vk6S@Lm3k_PmZeC1Pn+3$S=m{Ax2C|7%W zFx8M)L39s?Vc*92z`}7)5F`EU-{(rB65e(ubRE43?ZPAiQi}9k+HUlUk1NP#Ag+QHrN(4__p%Qs4X^#3%4x4x?{9+P(ohNUy(QVu8NfqZCcfK7jO~vllg+HBb}l zvT|^Kfm4Pz$LZ(RMh8mt0QT8;sIq>P_=`Rl?}`!m4VxwYxZHZLN{|x}v(zfXyCh_o zJ2kJapAXWA@2@kaNCfmG^y_Kwh8p(YjH(gocUc076lLa86Ua@xnEA^w*+VTb3@l zYZ%|I87i1BYPfq;Cg!kvzo)$u@9!y%H`*_X})1|FgUCKOq zsx#Q=*ZCW6D%%s=POFmf4$4MLJE;4_-mo-Hbmq1gv+LIfIt;K zI?)phwc<4+4-Sqr$iQcU+N>kRYd@sxB>H`p#uLfj(KFH4^SkF-3LmrNk|ys1LT^dF z$r(@nj)RIPCi-bGzh=6$`~KhMOgA+t_)U(i^DP~76X&WMB#+ZzX!-1YP^A3{@63cZ z*_vIOHet^vYuZy|@9ar8y}NG|^I2`5tNREk|F-Rim!z>VLwpza58=+mWk~PLT@}_l z7T=lQ(KiDQ$cCc1ckaS!45-fKk9wX_%DU3?C+WIoKLt8po{*MVo}#OWZ<|Tp2Vf2! zCBztIg%6gUC2YqC-0{n=c!v9(v>(7H%N)-F!BO|#2HJV#`ciyRy+JOlQm|OQXN@_b zLw0I5gnIHfdM@IM?zQ{r@m^sy@~67ePhZPjS~dM4%+MmvDE02xtju$|d7U`N-?n5k zS!ds`G$_$ww;{1sRGeM6B}ninOOQ&M!s4n?CP1XOqhnVxZsfUKFlj#7)0Rc>|m{32&O$fF0s9}0SF*YOoDPR zVCPF7LI0%`{UA=m@+RGT`W}t~n&(zmUi8>1tiC9Tg!ybsW&ed&K>u7=JAHOXI)jl5 z?lH|mkB)ygUT&1;)<^Y;mr(N07bRHxebTr z?=l$sRd2W&2|;JJAG$kv_JN`G5-Q{ZDKPfM8tzUxAq6|W?8yU{OILIip1*@beDoO( zm*4$-p+1nGEW20omF^=@la$u$EDf-Abe~;Tn`6J!Nois8?;cw+5 zx%(oJJbqu?L{obovUXW7m4B7KU@XR8J80P{c)c#iG^3?g+SQko#I-I92E!xz#;R7c z>W?MR#Fg{xwY`3YJ!7EtN|cJaucYyCiHi$!9`bjk@o_tCR(Y=X0M)I*h9VTzU-~^>(x7y9z4Y? zK@+GTyo~S30x8@%>v~=h}h4S(z{PD;3M4t%{KHg7DfH}{v3+4BtH>4X#x!j-JMQ@ zqR1Oc_?{O5IsdvsmStdzvQ}JY_RC4x20Bi1LU@v=C}-#KrrnO`ueJ^3RXz4!{vD8i zx`kmN#`q%l=ypE%-Rp5{r1o$kn)}X~V`B0}~p@EeBkEQeK zRuzeY@L!UQkARY+Ai*~YN)iDj$giK`+*#|)+@Kc~p?ml4s;_98>jKo=cnV7D$AVjA zuNV_g?8oytbWVeQ(ks?(%5&)*F8O?z#Y=Z~zza7XLt`3k7>k?$BlFN0v!|cn16}9a zK8kNgGTP5lTvT$ub?TjracFVS+&GF~Qw-DT+|G7jPZ3z7Ln}pzsyq<4{aY+zvW=P< zppxgIsoY1NN>V?weL(x=jDx5-TD(n;P_joQgQCjsB5kf86NzsGN>q^%xL0Eb;1Cf! zM)u6Dm`q(jZt|LCCn5e_FZNsD4RLU)h~w{Y5nXL8Nn!k4)Z`xic=vg}$q4+QdnZ=` z;0XdHr*X)=SSWXWpbVgEi+!p@e3h0EpE*I$w*AU|tKy}9&ooTA2`7;eb|0yKgE5+k z4$XZ&rs3`N&JgtMw3OBFS7R9-Vbl0fwq<7C>N%0dStKCXdLG)x58e(lx5p)18-wP6 zHaTJIk3w)r)e4VmRV3qg?yyzt*`EBOwx+UMFhj)ygRmuu2|QABJ{#ra??G#A<^jx> zZ_Ce_N3DI!-Z*=ffdHjX^Ing^t~d}U-6MdJeRcf8zOAnom*0{Ny~KFx_2rqg3gYYZ z6XTgHQcbKMsZ`joNA^d5N&a&v>Uth{CcxSw`*C#48-& zPc4wXcpH=+=D4qX61%)T{)SlUgM8nma?lilHmk}SuFnvl?AXsMGQqE_!1l@g7SY&% z=~WLMMIWz&}RiqbT?KchceF z|5g%twZBq+^123BnS5h@5q_z{7Di_>zgeIC5-j}mrwV*|i-;AwZx8zSd;m>M55vvM z@%rI&!Csj+BA@tpqoqk)@Q?naduPp&&K7Jrp%Wdl;|90eBe0PscP~arY$WSwQ) z_te9E2pZW8)(?!HRiwY#?+|Y8UZZJXR>y_3_q*+{p$szcRzhapv3-h_p*|L-pK`9( z!q*`^rCxN8?3a|bOON2|sJmUh?QM>`%yojJ|D>7n1M21x^DUFBUj9ecMp7^9I zaa>=JtyAx7Ph_H%La(pPL;D!?`!V1i9duoyzRJnh)KQUM{E0(qwT^x+pisw~vpy`O z-L~rt%;x-l2+qO0GK#R=+&;7Ey_q03NOS(?%RX{`9s^6*D39@bx@QxMuxDLMZ;w;n z#Ef}|oCy5B<)`R2_WA1Seq-OKCn~7(8QDj(aDca5zG;VGx^iW8)iZ;gYVviZVuni? zhzX-x^s^K!rA4NiZZ)|bx6d=+#IIh+@8wT@B*mFV>^5b&*;1uK=kvU3zfOKD+lmQu zpDwC>*GAmY!GGVt%7K0F#>0gDzc|7H*O3}JjcCgACRK=AW7+E-CTMV}Ja_-X6{&^e%0 znTQmnTy8QD37Lg@Uext3s!80N9Vp^XxZ-3w_ykk5x#C<+L|iR%>Ac#HLJgNo|9UMk ziwzGGg15^}4y%nK6S>0fnzruhU+` zzbr(So-}m{MX?F$^R+~P*R$bcGgkJ{cSyG|?Tc>%CC_?%PjHO~%?-KO;zKqDPrYz{ znjydghnn5#@Ik>RBGRy!_E*ow8zMOX@dgTVP{@*)NbPtluKSlM)~q6^W|l}1(Hz~KES6; zDS)?K%gf_H5dHUe%(85`6?L@_-IitQz}#UbX`p_(q)28HTzeDL)<&&1w6EXu{>C&f zB36&Mjxz9{bOXYdGjDV)rQ;$#;@kHnc>BQ4XIXG$7SdLvRTpFaDbYRe}XPVg`_aZQj@Y3A~? z6V9UvDYbG_l{v0P;pbrmS6GG0$?72iezazP%-#=oulr{Vw7T|JM(_y)YE+%nNajS- zLxs?5%)tjknuX6Z*V+y}qp}Eu=A7*NqT=cISUkmj23Xndk`feXm?9G|6_!E7n)#}1 zCU<)(9Ay~i@7^@fk8p;Zm5<+)-P7hYls_gpH22yG&sPVe)gL6Y#cu1aS?=-tV9h3* z`t5HiULP8o&*AZdJAl3t(sCKZ<(zQ@Wa9t|?(4DpKCp4m^T$U-5J=cA(T@9E6%RpN z)fEu1(xtLY>U>NP6C0|)c^t6yuIHdzlFUW|*P z8O&3{UbiAAGi<;$z|P(>A1Cj=mlo#;jh-VmW+s|DMCE*!Yo6c@H;m$MkB~d$dw%XxLyNPT76<&_;9zX1DcoNHG2d?F5ou=ZQ^rOSjPUaTq#gJs)BH|CNNW%3Z; zgi#CY@0h&Kl_&)J(2uY&xlNE)Rx_RQ6Ng2~Hi?5UW!~Ghey)Ln;g?PMc-l-&D$PEP zPi`u%5?I3!5I&HvR9QOUEfEkDbWM^-5*+`sDh><5u)m(=-Gld7@+WmBRoCA`S`ZiZ zzNqadG1=s=vrPD06`^V{u^5u?c`x4i6}UNMCeuUD=GQN;F$m?82}D?W?FcXV_Z~EK z{bDyKuy;x^`UsNFx65IVCc%QlR>!7Mk6RX}&(UeGkR)0mEMHcKS zKQl;-s9X?>@#48Y1bZE$0oHVQ(7_fu0~WWvcY`nr8DcUw`=@1-LDR_lr@V}Dhflm>vrkAI(Ckt*sJxfzc)zh-P{YU|wC z_eS=sM7m1dvw8^+X~4!IIZW|JzG)#pB2)Y$V!J5Sv5wzQ)f0e-u)2kxNqZoR^Us2T zBbQjHhj>`Y=x-%w4K+vpx8m0XG4!Suvdiz-lIvbic3FCnu5w$FN}<~aW@B!GHZADO z?PF!NN^nZN7x93(bNoz+|vmr$;n$p#MeM`cfQw^6_r-5-^APpowJ;dA;?=C~8Fnv73wd9)zbzdFqsoF;MzBM&9Ah`cSXjY)PZ8yM;QpQDPwS9(Bd zE$N?o_o&$IekhF-*<9{#F2-*+|36?)YNStBus#OuY;GytKhcQBqMe&AJKWrvH1fL_{a2C4E0R;N>GWU+3iP-gx z`5*)32%}4=Q%%#wqpb7p=NoTljL4#mGUD@d-o_Cq@nbgH`AKMZS%#cHz^Q8VGgJ%C z!ddr<7JR%L3*W}xGHDjyV5V!uzR zElWND^<;a67oe+d>lJ#_{+Wfp3Q3ztvefJ9c_V&rcKMDy?ezw;9Cqd^L4I2k*+5ppA{3vV;6V7=UVU3cn6$R*-!ZFlJyk z^Q*CIvp~rUwnd#|uZxmiMQcoFstmDn$(*C{_RbL-0)X4JU%2?`umMQ~gmMRAR6W#! zk|GB!(D#mx^$e9yqF)UkAbz|r5iq33=un?2=Eqwc^6tqM7aT`!=b#iuXf2QeM)Fgp z4R^UBoCFfc?|Znu_YV~`0a((kq-O0`{Yf_&@|f6Sq3n<^UskG~@=dLJ2ZGhD2c6J~ z=C0ePCk1-E_Gl)hk@wr6ZPl=tzbt0%V86Qh-Zyye-#)u_e)KF{9K@h}UKaotz}9$Ik%uJ{$ec2l&HRWW^|!W)L|8CcHH{3^{C1)4l%clrK) z$+u6TVR!^O)_JN)J3b;edP0^ogsk#zpQ?elXnW59m2VHudd*M%S65{)X`NDeScvxe zBfr1-`>2;7j-#!Q5k&mmFWy{MP4vu`S-78(Pk^dRJ$7BaMArpl{SlpF&eFh09r~ej^#&hPJW>n0JTqmDC1n zNW+H-uzr%`gw-s)Kf95ueIGaPsxS{QYB4>F?O^%2RgFpGkN_gpyvFzD`=05dw7vPI zMAgWl8kF|KXO8W3biQ z@r(4}WN4d2L>s*nmk8c|A*Xz^9 z%1d#Pn-DBe1<6)*_h63cz0o2%ZQEZ0jc_355ypzNcnsmF`| znic=iea6EThP)t?yF6iby@YsmvWKt0RHb{IyXq&FA=d}-;mWKsPR8kcccqPY)>Y+A zdWLXj#1V_Hd)l%KJ8;9wxAJwQ4yo7VqTJ?rpF9_4x{^11db_jT;c{ zf3TBUFuJ!Fsea{h1EynNW|~EkoTpbk3RM~Z3hDhR1fJj)8>+}U-S&Rn+#a5xgVmhV zuPywvA<*4;C%Bdv*cV&?4NGA#stg2TzydyX^^K5a7kYa6ct6h+D@ewLF<=2g+xc#S%n&u^lJGLZ(aD zycv`*>WOw7wjV?D1d=JSWfnQ#Y_6^()(yTc=*OOXP;gVgseLWX!|$A;kO%9r<3(fR z-o+5KOS1U57-V6u`*X=ojrnKNAEYz4#n>NwN`e<=Mtht7DvS3XHrF-{>i(Kf5Hu30 zqD3hh|2y7RM2;o?|G}~mwniI$0e2);kj~4tewMKQu2aM!OXGGRc!ZQ`5G6h&@_n2+ zran0e)u?C8vuTrvXiT%3t>{H7yl&E??Z!+$-%o*)ctX) z_tjBNhuaG=cjI3CfLp96Fb?~&MHI}rR>8cT<>anoC#P_}MEASD`fR%I*Uqul?tkMW z0g3{mAFKW}-frKXX+x)Ik+s=$S}tjFCx2mAuJ-lV;5p4!z2#0@HU!qY$=k`$7D?En zF6U6-a}#v4^UEw;2~TbJfNLR5PfNMB364 zyGG&xbN?dz7~$1sjudg~LowWHkoZ=B-$6X$Uvs?(mD3n1oBvd{lu2LNCzMv{(Gn^P zcM^_fHh(BS`7THoH*pw||MXo^cGB^6f5j#%@zA_bV3>EWP73egyC@1w^vLUiX8Er} z1=0kiVfKdKOh4$y&yfRz2=%_q#9+rzZnh6>_Qr_>16LIHvFL=)80nDxRw<4Qn^BfoQd#fNjw z&hLCl5Z!}d<6>1VK0sc#3Hi8Pkp#rVQlxvH10aHoibt_;|+mFHk*D^yK3Q1HGuc zt(YtoxWHUJv_SfM;KmT5p}d%Aw~L76V@XI$*UVy%U)A9Ma6WyZpEbax)vNageqnRR z#+WWJYXO25?BPKzIx>OEyV^r#sORLTr}8?E$tN1uePy4dvPLhBhu5!(XN2WB&X;Iu zR}ef}JlyTVcv60f zPy$lZ&OghK>2Ljlb&aPiTQeWM-yUT*~wqrCK8$8Svff$5MH@2Ttt}XW$Q~h2gT*|-1+|O->G;8?&G?N}M zI*M@Q-lHRsm2uh+kJG8Z_E+Coa%B_GOz2H{5bYOoq9@vy{I`nwV83zZUk;UZmh!B0!_n>XI<3!7trWdT9U}QkuP&*H8WIHC)kgN5D07JsPo~Y8F5Roh!eF zF31h@x?J$YX*%+pc3ZVi$(6|EgASSpq?$3TuM6+&x-}TnWDysd_+Zw_j|hd~ChTAJ z>!V$#kl%hFED!?^fvjNqk`9B_FE1xn{haS+dVg-`yJD(XU5V<^dgO)QpKHLSz;@z% z`XVFD9F3w+Dal|i9O1m}a2Dm+&OflOQ3DtW-fyYN^X2!7p?ZP$_i%o_DcRVkSI4Ro zdjGhLeQHWsu!#&QRDCu=lnws_vWK+ncZ>WW^)G3>n|x(+g~}#(eF)Fr3W*Fe>{0Ba zgBI=|5kI%8mwy#%ER~zQ@8D73=~VU+8)8JvGgMI{(rv`RgqE%5n-Hteu2FK^*?Vlt z)Svwe6mkc`gZ=c4>sK-8Y= zXttQRi=?xlJGn8a+G_IY01Rti;_yj;7{`Sg=?P9PJnPA7ptNWe+r zsYQv8R`$*KO{?;sC?KF%;;!m9P*6zXU;gmwyUajb-B3an4!wD&8l#teeu2GhKj&43 z`lnve26+0+)od+W@cQn1EN?tPJ@viEB=TF`Q#cY@9V|)(``2e}8gP^(pDUy)OzHFY9U_Rfes< z_NU8;#Fyio({BVsvFGx%h$#>vCbn8xgk+w-SC8oT@s(AcM|Yu;l+nSYp?`i}yeL=o zSDmkd_}rB}cb)zQPGIl1?>xn+^8mKqBEYbrJD@Kk*<|RtFZXw2V~&#r(?&)q!)6&M zM>%syb?`D641UObFix=$etI3Vt5v@niq0`LC!G)0HpZuYQ@|x1IqJ>LIp7ZvD8~53 zKHG{*Ax8A%p5O>@j=-5DRtOMLl=tlUPTr()J0OgWGpD&~OG_2plP@F}fFe$ZS7$YZ z^Lc=0{LnzZjGx&)i^>oyj0*|e%16&ihc(i}w_%@*{uCeK3g5mv>g_aH{WrKY!BFl4 zl0;@PWf^_u8-{&OczWD>xlaf+Dd~+!7t3eGBNx?4IT@C69COx-{Evz@?Dgo)zx1O@J@%Q<9}a)R z3zAsrPqnpOv3bp+`UgkoP6>K>Nnw)R&?xbi0Z9HA*z1LNA3poTOWc>&{BF}j=gB%F z$1;u(Tg86FLntvH*uVC>-sz}nC5_|Dy%EZ9nx8bm<eNyw zjWNBAe^-!*v4H>ntofdmf>)wI+snr88#}?oR@m^*kiu*0$L?uJ2x9clze$HvX;^^y z`K1hH>fP@n1x;N8gyw%LC7ZVJzI}_lw2Z?VFPU}WHsrF4#CwW9NK_raObZT`(UVOk zTgxv9=EGI}F#8RK6LQ?wh5K3OC;44|k*kgjTKv`J#+O@35&EpZXZ~FBaVP!UbD$ma zn|P^bvt%!KV=ya2(n_CM;C6k-YxFR0LeF=PwGKb0pXSMDCaS7?r-EciN7{8C|191< zR9mkCFKjzY-?4-xM&*SHXkE(dO}l5I%b<;Ur12AO-j80|+I4Ro))ljl>DW}j+8Yy({zAeZCU5y` zi8mG-$zLX5#?MjxyjB~G=4%Rs40X6AZ`MbITupveAV@lq`Ak!|r0T7?(!KSx1cb;; zyYy0Y7aSvWmk0-)&G_|x&0kesU}9ckcx6B70kE@WUl(Y) zMW%-cGNXu`((9xMJ7W-{-_z@^347lOT5`b8+k z7QgISv4|f*hW53{7z9!7J%~@uy9KwP$>jRm^THBmS+2bA4OYklt?tu^BF2Qjjbz&h zVqd(SWnUL**ISkzE#-?bj}F z-xZ@PUDB^wKIUGqx`1P09~ABMfT9M9RWM)WS51XNlm{!w(sEjXWTc7*k|sX!6nL9A zX=L){=Hv0jQ70f2W|y&scJzgPd<+IU_vC(okpKCZsvK6dwFA+M*h(THDUZm80?E?z ze1AkNyU(}#Y^^QaS&{aWnv<`;hHAsz`bTV31*od`Eo$G*_o@pC)&JSgvDW5qWwtMS z?Pc>jC%cv?>^`Z*5zK4kxcJMs2q|G<8c%HVHqI{!?>WWfV1bX+Kj?{Ec zr?$Aw^aJLI-;ZmO`}xo)(~75@vG~96hxU!eF&J*80pmt%)JPtt^Fto@r0bk%bG$0c z`z{o>Q>#R;1oNV}lC;WF<5kDs+3no|Y@x=M53VVM-W1^-fWIiw?TVQ#DAq_j+-E?2 zJ-;8@nS|mFK|n9#ey0c_Fyrz$!)0Q$xb#*uG}FFk-3KDMr`PIsMRP(}-uL#rl-8EG zD&5x1`IP?6RofiRFLE$yHTceyvO7=2o8B=1!}cs@{G5V>Az_5&xxH{Ta6!bnyxq5K zxN0xmZD(m3Ew9Ov=F+s=2MZR$wLhxL`#Nzt<~5cxvXALsIpQ(Y1mb=XDwHZE=wib* zD!nkgiFag;J(kxMUk4w+J8@}+;7%M!Ah%C2IZvg5fc4NZn|EY8h~GH1xxy8x`eQUB zTJSzTYBw8<%GPGI?-$IUjdo7%p^-*Ezdq2kb33PhD9cMzQtg?$r=@BT`1(`W%kkU8 zZVuQXV-Ckf6zE;~COQ};wxY1GgAlO6T-UMp?L4MJ!bpI`?)Ww?Z6KTXeGxZSae?7X zew6?z0N=xe_`_*FdMyRQDiu5Uy3x>4UCIZmx}IaT~}t~-nrTV5i8slPa3vRDVIB!OTf2c9xcq<7mJJmT+lznxSQ zE$e{Cd64C_u{Uj{_h#Y{8uN|a9?<2h=V$*b|F+p_PG*qvfU*jxMsyYqk$W03=^bPa zX6+oh#@W0ty5Wi{o9#6Zez0ZQ2iac^i!8zW%l<;E%RDF*5^P$_EF0ix&~hQV1|C@O z^1gL#i{2Y1|17j%0DD>O(Tg|+$Epo8f7wBn->$6pxhfJyE~I9}Kyf|sFkr)1wNi8{ zqI!r!@HYyXk>R(Ur;CHUqBg_%b@#fLj$gDtCn@r6+~mjYq6-2FQ-aOKv+#Tp}|#8nvRedYpR zzBQcy@t0+!{i$@B_43IHHA9d; zk&5`3$4+@=_PH2r|48JZS!KlClRq5Uayl`Y8?7%wUh|J=yg&hWDpvZnLp4Q9B5po~ z=w9-4e?f;a9h>d<1mvq)(E;Z&j`^VFE6zH#2fAInWFOab*6f(RcWZ_K%QD*q@__jZqH-mxn+A& ztMtLCNTS%};xM_@)gQl|w9-f$N z;mzxH36u9De`2Z$BA3QaTOhKsoFA6=ve(7PXlw6&mrXfKB5?Pf#RN$fUr_JRjkT8j zGa;nWAd(k3zr?1Cj&)(^N_I&EBt?*qE&g)_-}~SFrZR8AjI`3)U)^gSPYNAXZaH0_ zR4)4%$l~8g6GjdPP3-i?L1eItLPa({0!I2Q;2^PmQsuQUI5e)Fn}7kYLeAXMVe?#z zTRUs7Tsnc*3eTBRn(D-%ugqbJM0rs-ns|~?& z)1L7+jbqKcq4;8kH_$`g!|!1192+sV-UN)c!3GG;dD#Uda3y(0M?#L@ia1kL^sYE# zhAt=y$OJK11@Kp88zIPCU=jGcf62^8Y2yoiLv8z*k?t1^ex-e8vmfakkmd2p@CxCr z^va&@pZ0YW`)_r}s3z{id-h-hnTo$RMp)PR)L#}}MP7T3ib^xjB@lX#ctMctCAIhW zEU0sF*)PB6b-vi!VObPJMd3L4u|KQ{<=oo4x@J@?-shw06ZO|9J|f9v)8 z5Vsj<7We|29sUKUwFVLb(o4KxED#F0vt8mwxJK|)+bK~}-3NQ2X(EyRjCdXL&35fBdt2~4a zpJC_&gm)6L4^!qW1PAad%_HmM^AhRxJ4r<3<;LA$_YKeXb$NJNmd1}CK?urF^34Vb z%of_^36Xurm*^~7N>5dA1f~N8(mWpjA{_QuUYRdXWFB7zi$>nI6mxzc?K=w_N z5k9$dt3}15N))cT-%f(_ayjiDQiv`=;LrPh7v65Qj37wpxZcElqZq8NAh{)Q|jyPz4`&9uJ)m9E(P&(b+HJ?d=u(Ybr7HOn_3 zv*W1#J;6|6jOFS~< zKBp9)i#eQ_$Obl>xq4syd+3=j)w5GhsI}QZks0}i_VsC{j~DCL{4k2K515*8Dey+q zNn`HTAxaUUlA39qA7D6q)?MJ~Xjc#Ev0WeR`2kqn1x~TUc*8*RVTUFh)M1MBcr*v; z_o?ouo3@|v{_3`abdXOj?Xn97Z~1zKjTdQX^Yb|9VZOfl2)T#z{R5!=L&*{7fX!kA zX}r|#6Nr-oM&mWW4&elK`ZL|zi^u+&-xYq}_Lu$rFZ$qxexWWCJXnnRn9lNwaiq9z zhsWEVDkcqHk(oY%Ga{GJ_oOo)?&QcC_S5xnB_w``7z|jUFy6^dl`;%g7$bls zTW)G1cjp*AIFiks(veI1Sja2r=-{sf3j)l3SO~}zOmDA^{4}58b#A}rB^jtlZO05S zI=pXQ`mpO27V`{^-O;^}wLEB&!5Dwam`kHdy6<&xY9B({W*Fwamy7s$)Kh*W_hp>h z0gsMMHufDlyf9upKSXF_B$EpU1*qT<5!f{(IXiiBn3Ser?TahZg(hrN0YS#vEw}4g zkBRwEUmC$CQ_MM=ZFuhluOpIRPQ_JYtf%O;VC0(1V+U?F9$AqNEjf?YI|;~BQy{BP zC(O5frkzkl$l9Q)8Edmie)UwTyFH>KmvK<<;4y04*Jf0VOBe_0wi$hN|5zFd{~K4J z7W?XDc5SNIr&DL1_X6O~vMhdS)wOR>Qp--B-86_s#;^pB9=dMbdFpp0T~};=NK(v6 zAOvE=(|D|l7baEBM&4C@GtYerB>*jv!Iet+*L1X9XRRoQC*#5;H&J!<6VCF`ed zIT+c6OcJ&Eoh>MmVa$V6;J^!i7y4ROIT4@o(>369M`H%`ZM$zuo6PqT3VAc`jh>4N z#G(P`&#kbCai0bzD`*jE3JxZy4yGaVAe$cUYd75s8^q~pFR1a8f{%)4|LR*dxwtax z95t+bZ1Zl~*arovJL$Gh1gMn9>~iBoPT4eOQ$5#=BLrMX3bN2g9Duu%c`rw=_3noz z;F884ro5*UkO*-=)3Fh22%mZR%ImU@OPR86`)z!#!eU0k`qjrE!aGwAr+Xt~aLg3ggZex7Wy2PD+ZshV|N6)rqKx_YCWk4{(C&90MS?i^sg7+*{&2#@U{X8|7C0FqS1FL= z$I61))2C_hcXQfxNXa1BW3!y=-nu4;Y_6rGnwr-~%+cs!U@IS3y0FdT5A{@|x zZGVibBLz52{(Ia*CU6ME`rX&tAzUbagMFU@_lQ1SALWHXawV0;Wb4YW2yv?_gLjBM z?_yO15xu9#f4HotASN-nzw4kK;d+Xn*WQ5RU?v~@K3JYpMnT#jWd_tK6-`Dk!{;|` zu8#n7TD(frz#*S`NT(w;BY=|Tw}F=$MgJ7hy}KBa0WkNHIhy*Z2o+SuC zot$k#7LZoBKD*E3nLYW`UB|=W`=^Fn>($2_263iijwIHu>m7$OT|7AkcFMB15x8 z%|+t)u41YWDNNzAr6QJopK}^iW!G=I`l#xVg|U|b`=EBQ`EeNg5fi$s;lhHMoJq$O zU!4qMD!wilt$gf+IrU>P=kgRUQe_xuv)>*a*yO@K=$QK@4Ndr=J7QXXw9ovPkG&2y z|L12dvd5PyRGA2uVL;CoUJNijBD>L zIJg)&ux%!MH0TxIce<&UCm6#mth;-RtD=o%B3M<}C5d>y10L>dp{>%a>A zLr_t2KQgSvaR+US&Na;sXg9i7>vwMVsYhKeTK!bnM|h&rM5;e`a5h~hv<*~aI&e`s zqI#VdQe01PP`;+yD64NCAk3p+Lje*_vQcU7a?5&|Oz z7~=LPc^7lzjoRlBCB&NXk0-1Nv!|&Vyp1$}O5=WJzDez4ew*Lw1*Q4q)h_xivdT5o z&pe{Jn50BbI_T&oj0gvx0)w1OW_mZ>O0LZ<3!>p7xjjfAdN9JtNB|Of4{;zOM$UB6FpK=04sG z;`Wv$>JPe%=e_YCdxegNKU{>h!BTl&HX$r0Qk`smQ`2mN8&`{Q^cAMdA#sb^iP8HB z>Q&it{@pcyyM`+^6mN6BkbdXx+W!ie2=;k>0P~$VF%NyT8()!V92*xE()rhZs`op{ ze41JJ`c9AgB`6)^_pAvap?yjl&L0j#A06m2o+f1|U6Jbv>g`rK*tM*V$?Rq*-Ds|) z)S;c(9SaDkukXVigH2ET;mf{2WSE_2g_Gs+-{vrpARxNacU8|wEcn&s>NQ#v*3((d z8;dH60gZ0_OLwh0B1$2ex5wY3){ZbmpQ-yTZaK{<*?qb=^~LkEPu1ZP$te+w(G~mp z^O!6V0(fozcjk%n*8*D&=vn^H#3L_%-YA=?oI3(huc!x>EUOo_U&wTclNTc z!Z{`~fD%;mAQ-AO>15m@L3~gsHx=gb;E_Y3wD^SLe&3T9EsSVxGZ0i=yedzN_hv!| zhO}LlOiG@ftY!Oac(MY&*hbew8|G9T`8ZYG8(GEfvmAN7cEu|w`SpYT{CH_@7aAtm zvks@4+6U&r_22`Wcjk>am6$*G&+RTOi&Zm)+;Q!jKhUpXO;9hC!PLzSC4vYanT;L` za;jAPNh0l6|K$9`&2tZ4KyjK#_rKJNG>lq18x;|Fl%PK8KiUc_#LMV@ z3!y|J3mQm{n418=(eLCs2Nnw5>cOT2%a+~O%yhNb-LE_(r+ACk<5Gz9{-)m}jn2*v z@(f^vLwIo5lk8){Bb#g-vsihQ#L9VJnOr;GZ;_5g5GYl?;TN`^?zVS&MG8S{H<$lj znU4r)i~cRR@G-*^_Zq3^?fG*ywcRKzZ*Z=sizA=aN0BDScLDJ!dP|h{1*^Eg7bx~W zj40h9>DS7y9$iQG)YE<35@52(kZ00@+6Q(Jv|F^hSf16sjzebl_Ito7U6}|NW2C1~ z9rQ2GrVZTtF-^Z*WxpVB3*6eUCIdS}b7Ll998w(iS>A6O zckN`+ziboiRD+}=c_kF7KH%BV+oAGl7sGfYw1xPyr`<_>OA@xpwR31tAotqM)f%wqF zyegmAC&T&x+qVHO4yZ7BB#v{HG{n8_d;9)5KK06*$Qbqs3HXKN3`vdi`zq`g&6W(q zs$d3@sjm-O_Z5)hN=a<4{5}|Mv?){zH+m|?W5K09=j)k07vJFR{<^pw1VhN*b192o z6U2dyq9zvJ!Aq*#8&3(ea9sM8;$P?cI4aFP<4@)LB~|@5IxPCW2*yvBz?qjqxEdCM zR-R)YQXl}W_L*i5f2H?9#|;^W^rsCwFFH=v%Ah!Q0mm3Cc{#n1M8kpL{iyS+FULm~ zEiH`PcKSI$8R^XZdoh0LZqGkNmEH&4V-b$Divo4(rY~T~->6 zY*gU5gqWPZ0bW!6=s7JKXNFmz*E(BQ=HOg%o2&|Qdj4MgU*4;5lZey>jj@g+4zKY{ zl3q)syB6|qw`=GP_+7KOjNcZxz_VFT0ECTQ=GfE@&urOG4+RBy(b}o(oUR- zh`wVdM83hM(byn1xbK?&?lZ3wzO`I4+xT;lh2ow9z=1+L$v2(cYoslqOXds<`(Lx2 zCBoa*U9$H<`5o+1MG65F^j@boeewx2r%Ycj{b>T_11SbgYR^l1Ol9u*_$KYGF8+eN zUk6W-WePDv&s%;Al~P%>CROh#n2gh%z8;3##GRQ0%?f!22sS~NlM`!)`6|`2si%G6 z@k=JTmv1)qJFfPN?Ji1htsibAe#fRdR=;vzP+ZwZ;#j7ZbO263+I(@7bwbREWVTxDC-+UVD4rlr*O>q1xYAJ12ZwEeEcKxQQ{L=k_Nh$ z>VG~H+U37cRNvHH*)PvYQr7QluJ%<`dTz=Yq^4gx@aZSb1im2_`%9jU%>~a8{obGh z+9nCGR=0k%({#vCB_siqph|DxzsjZVOjo*z?2&0DBeXLag_Vib#mYe{aiWWeF@azFLfE&T22EG8gr~; zC`2|?GTfUe6#w9g53b$6D~FH3LMQr(?S&_9ta^0(M#5f<%oy=i`Ep7()!>dHw1Wp?8*5PEg-l zU9hU{J?GxH&VP|)nEU~TTI(4fTxFZp_{r|Yf=;*Wi`7DRJwYQ2ZUK+T2|GQD+Leq9mR$s! z7f|8!NilHC-Cg|5!Q3q$f}NW#uLhKaSV8f=&&KYRY&OFmcn^6*Fhd;0sN0}Rbj$Nn z29O>+W@nppEAJuXtZpMoVb{60u=Lz-&fC}@%}XQ&LW*46%j(j2t77C*_0@UplxzHn zqOKZNz!@@dw&wV7zKCx7dCefb!%};{@7SUP1kI=4Naa&u5OP$fs-HneU5_fS@BN5< z_JO0`VU%-&ciw)D8sNV5Wp83q?WJNbhfrX)ov@#%oY^d5uk;4i@%F_NFBz}rwk%j7 zvvL8;TBLI2_mr<6d?3__IHu%X8%x#uiqKO@{xO9at8X>{U+fj#xWmDN-++# zm03DYoAx^Jrw=O_*j#%NpWJU^HwMiO*o`ETeoM69(VK&edtvOPFKN6N*Y@EeP&Du6 zW)G9}S7k5dI^*$C_M+u|I~qaY*Da_K>|l;%qY9NZ1CncRsOjbp>CD*mQYJK;QXsry z#FOElxsp7w&AlPpplI2n8P6%V59lU}<15=@1Qbt=w~RyARIOYX$MM7k!be2YImoXFVPbJ=LW?W&N#s^?RpEcK3nRg^2F< z2yLkImdCSm#?oL+esR5+d?ZcfHPP}gPWvk4ND%v=Vk+^M-LM(YaK-f;74-TY>6>nS zW@LL#S#ghxOfcz&*$cb^u|=5PGbE416Ka2XZOeR@9*g@Mu*ehy#}D0P4}Bb$h!8>j zw7~+^(5MY*z~pah+mh<3_zK1NbRGtYR2GUvx?J%kJ1gXVSEN8Y{eJOPzCiRczZc>A zO%~bhaIYMN_vB)i99zbAX#cruh+QMDUo<&%9yR>ys;`+mjfFSqI8EPe4C^5Yy^ffR~MFzu;d zV$6%Qs-=&N3kp9xDgr26oka4o{Z@nnp3p{YkaWf?b-` zDxp**^22Aj`xj^t8B%Gv-uZ&<#&ddJWDd|y!@D6^Dm#}nd2QDD8M9CNkI~!gD|m=g zU*XcNh&?GD7?rW2e;un2ZdxoztRm7Ds5==_!@idU>soGDEQKsxIMw|n`h5ige#)+E z)yW~h!~Q{UGc2mw=k(`o?S>B~cNv6`9R?;BXGcJteT;*W6RCDnyu)|27$P|kZy0Xx z8uV<{NO|!MBL*j0>wf>z{W+oMXLqHayW#9f-!3UO%nq4(@jauxlcy~m&bDeB} z;sf4-)Ae$3?fa_JZ5bfkpH)LWu*K^3d{kGw6M8Vgf>-l=bGw^-C+>%9Xw#B%Tl4}m5%L+@^b0ZjL2w&;Mr|cp?@;@ zV|V|FKR<{y-0LDvfcQ8ubEYpR=OTvnzQ=I8tMl z3A8LnGGF%X%HGwp9`Qs+UpW<7FNm95iEh{v)-{DC|)rQ8B8H^x1cef!Hi0r7n zAl}iASr{_lWeI>k*TwL4OaDE6s+2vRhMSqn?m@%k>`=bfqQm`zmXA>Z~TCN$v&rs7#AVqdK9;r^iNK*W95KK%!#3{VyX zar2I!r*D^mm0)RK^M)xS_Puhc`+n1U>ntR#s;f}0sjlT&@DtsW2;Gg#po8I!^!GfP z!tu`@Jgd*b z#h`4pwhho-G0gI41r#%0S&~UFb%PSpK3`AOb%6oUDNc|HV0!d!MJRhrLiP$?G)10~ z6=73XjP_~Ix0%UfmrkbSmF76H$~P=^^El&QV$AG|d`TZ61dvw)prH&ouXPTtPItRf znp}AA=b^zNF(}V_G_d1(Kn#ID*%S3-a3k`}Vw~9)ng9Dd$?{a#*9ojpx*XZmB+h=f4p-T35 z7(wA({G3IDHM`G$=%to}dmJ2Zd+geNLQt_z6lP>HG->NriVjK zmmXn(sw>AhXWq(-J{akZFd#3F^m;QJ@lCykT--OUfgJ*Al$AtC z_c>9_i+%TyyZiw|vXl8L+V=3}Q<@Cq--_2*Vh08LPNwG1 zYdPNPQXF7US@-z*aGusxBN*wXZK$-oE@qH^1`F1T6Y~TM(|hrkuV<6r;C`wH%8DMM0|4vh zLaF3N6tx2k1Ol$USyaBaKd*$1Ts)Kw-}Z9492OIPv+h}tPV-d_>~<*R5zEkRh1gRF ziPy$=V!+q?Ig$17z>p)D(8)ENs4!f5_4)>*WSTUf_LxMugiqnkJXikV1TFhx&f@E) z0nHWa(ln`fTL=HaE_Y*fP#P4tkI2-$j#co!J<{@S%tmkq+ZOJmK=CL}6kj<9Xclq5nD|aT5APGCHbYrwA z`!ZuFpFDGnIZ_uE1vROCJ)6tld@c58#gGG-sgAZq$ue9guxnXCn2rZb!I*uxUEHQz z7;)6=)`miV2UzYm%BSLIah|Pjh@t5{tly5$FxxYRPLLYaiT5j26U2V+lL;_MBBYNU zeM?yUP0qrsXR^CsGdK3j)%pWfHv|8~h9e6qreV=QmfZzdzq)S}b2hcoA#zYprOaG@&x`UC@)B;`KUN1GnH9}dy4hZb%^ z0sbxgy6y!dU_45ZW`@W@*&L2a!7eIU0%WQD(fZ54e!`XgGtrz6Qt>UwVIH9IN6!aD=j}YUVdy|0)R9MV#IE^ z8rSf22X_?s50#@E;#+UTv;1E7d{FC?Qw-_MnPKQ~9vzhy7Klyc`G_aq zP;z@-zPIPLV%%)@Y0TnLR?%f9zpM|_dt#!CezZ9^U>i2wiwO_&mnd0}^UVCb;Yf+} zZ}Bn$Sfw)u)a3!8@?O$ARwP_qGgl4#{6l#nTqPmwZ#H=F9Pb=ALbw;vt97ndjJgb! zh^_M)*=e77dBrHm>V@SP^)vs)0_Z@Mh`D5V?_y1X0kJFELG`9lU^+Wl(feXb4t82_?O^jOmsPER(r`!Ob8 zwMR{Cd%!DM0YNGL%dgj~^Xad}q2Pn%9zB5&ObWGsO8)aEZL!X2uq%@1LwwgD_YOP8 z6a&>4>LKR{Bt39s5Y+gu9xgcTG|$9Y)nX9=Ni!z?w@o?Psx^-*?SSRkB_j z6cU=Cy^7)u!{oec@7w>I@o>?g4R}qrUy3vK!=T21%mXiUyj+Sghjo^wJBsYvPiRbR z{%EbJy^OE8{AlzZE!;>+Y`#?Y)JJ4F3_&LQrHP7yrGU;%J`Ib@W#Df2qhUFM4~>_? z#8|!+n)qbOt~tKgPZLxr82Am6;L*H4T+Sn3dJ4!C{^031A27pCooAAa@mbyds;rbw zKh@iHzHn#YJ6R*2_T4nEO#ezuj6NyA`Fi6kb3}SkalV_6k-2>VvSk11+zQYD~~r3zSm$7SAYTj8k|i@HHM z9In(%C4Nbjbth5%edc5I)d2i(_u&-9bgugq|Bdb^ttqM#L@_W>82olEe)Z||{!|Vw z^*8%S)nJ%SNWw<#j?hCj~vb@ z>2sUn=7Q{yJa<;l*K<2QZoQzN-lp93rq_BgMD_#9D%}%BI~zIfBndrCb#(R+ia!a2O7iR_585c;Vwpc4U|-*2bVZr8!|P!p%G{v@aFwvzmFp- zqD|b3cNwndc6Cx(GFI+tnk#X zZ_2jX`_v+ufW0IG#zdl#Ot8Q|bbe%RdW0Eb#3adpDS+VZeC;u?89Hl>(r}*TKngH2 zAazc{LaC6me{O&%c-^0CmFsFxGlSW<+~vqUe$m+Nh2Mv9F3}6Yv#SIC-}tOdr(3`L zWBGF&5?~&O@KZRdbW?#~^Sesxdj{t6tuLHjLBF>dMRWOq{qoFFzTXo9;Bm`-Gv0i6t$*(3XCI81SqYjRpVRo+o(VD=$gIM zTMcp^jt%mbMmvCaM?iT62UnPsVluzMvn46Nj+*4`?c!TJGlqx>RgP)i(bUT|Wbhc{ z-eRDXM`F4kiZ@{W z98C%X%$~jhsN@~w?Ws4u+BUt=qPN7LK-V-!4S=n88TZr0#4$<+j`^@QQt>bmEW`-8%_DL$^qA2tJHe> z^K)Y{+>KGT{V-HgKg9^6WN!254^pDf!#66AVSrulwu?gr)P`xDp+59^RZ-Vf1|8mO z^NA~S@v2PW?U<&`Ge52S6+JkY8Lqb{^(+)5<)b{tqhyzWB&FaT8IcKtK zG482ab1??K_{Y0`S%*vS>i$>xm4^pmVQcQ10{9&W-r4SmBD#$;CG3%bv6-Ct1X^D? z@;5p-ky%8hty~XQ$4mgow*_9Z%pqY?XLYDCsv>6&lyi^2Vc8@!;6LNLrF^k&pNr?T7%S$u?%Ndn`If=y z3Q}$9On-ICzeLEOr`EB|(dYi&t@GS32vL2oa(!pz>&>dJqgkWcjLC}U{v`z5HIl}z z8?y#Ktn=C~g#7qbHlczuq2e?{?UNEZ$qG_I%1Kdg?E@q~EtJANISz{{Cj` zdH6oATN|G70G^+ngY&0k7_|mdpR7^CQ}p3@6p649eVP9dWBw$$2laSk6A?UO#B9}; z$iMDWK-*H$rv`ke>i)puyQbAWHV$Q;T#y`k`}1*(VPZDrz_2`x^&8E-&%{#2n{MNi zwSx#12e5(R%VhfvjoT6w{=MGNs`2MUPbC5~looSJ?9DboIl?f>D2@p`9ZCtjk-M@K`*aAH z9SAq%7Phe3GdpwpfBvhVeoV`47*E1B2s_82d~E0<;vC=*8TMC<)EI|H>XqK zVKV)5hnZM>;tu4mraSQmjtuo}f8=}2-Psy&2qBm*+J(mavKD z{p)@{CwnC^bkFI`m9Ul&*PqgOD|o9t;*`1t)JLcDXihxiHF)Etd{ zp@zTJX@mS4)`>3T-(R<~9{=Vl&beQ|VJ${ML%>-1K|X^KbFNgt>3**4!ql+H^e_m z0$&auAFi!F%n{Z5+xh(CdLEgiFgl$%7A~nfvnjz^dCC}^Wnq9Sf@&`(;r82QqRP!Z zLvrk8KYl%y(2kwH+G#LP42MhQZrHe0#XZz;;o2mBFTZJCIdyA$mj5hh{7vciD};8s zA5hGhj;>XZkL>EBReDuh*EV}Gt_oJD3Wje~ap5~Yi??*EJ))d@z zq%gp!0)1klN}5ak@nS`U#r?B*Iif@0Q18Q8TZ;7Rp>!&rk1pHC61aAMZt0iXsS7CS zBbfKM237qTsdop7q@t1B1*VW*aP35rp%U{3jh$qk4w^QES4^>q#LZ$3Otc4CI7l)6 zctUi(OG!vRH=HH%np=%qT@@DTo?hWz-*3D-CsWt;rsJ9veDlmOyRn&Y)_RllQJ$q7 z=3Tx8Tq&=t$q!!0&NVmS&JnIhOa(d8;hOrN;5Qzlmv?J5hO*#b%qMYn_G{^_?>9SLG+*ZTT}NBa3bl)f z*K~X>qEeAx>2l!pnR#N^`?er-=?8e7mUfCiQ{I6|{Jg#Chu0{1#BbzcHqwb?c7!@a z-_5*#gK2=7?DLoNWy!vvXK8xk`CpMDQd9VvI67Woxzg5_Oxj%;Q~CXR>jTk$ zj|{3Cf?Zkne2`xWOje(aEFKC{cb`COg)FWzA+^vfGyza%KhA|WLPo^K3$?r7$TFV< zm$cbX^c;Ia3B?CAYDn19+g|^PkDNgsswcopPW9un>)|G*p#d%cKRW)2DE3#+_3VX1 zXkjw0zxCA)bk6*W4!@ZXRSWgGIoo+V!fhz`>eD41+edO+rlF0Jm)dhW8n`?GqZzvc zwF?lG05)eA^;=KNfiUiz_00_nkPKJczvsTK=l%Y8G_ngujPHeSUv^8>>=&jxS{33 z8S=iu;EKD&S@lZ)?v!k>k2m68E)N8Vm)nBy?P(`r5|JM~0|tWm2Xu4IK!K<*h!wN~ z>WLSzfUq(iXVOizF*Gk5xZpOE#W}<~tP=yos{lO?0Kuvn_2tR_-h<6-tsYh2*67qL zJ@`t`pXw$leNx?YRUn;%AVa(w2CU%r&`6@H>S_97A}lvIDr(dSDE z2u(4jVSQU=Heve^ic-vLB};DI0;_o`Uc|o&*B&?sKN3;HT_P?(G~!@CZ*L*Hc@mf{ zMEWFAPAr5vA9kn?lPB9hM$orRk&nWNGkmhViIeZl?C=DqorPrr=pgjO$&FT(UR@K}Ss zn5x>%eWX{REkMFXN#DBKKJ2VIQ(NPHJ|Tn_L*tg@?Sn~f7E()JghK*X8{YWCI24z$v7dy&}admy4RaQI=;&onM^= z-RfE2CilRoedAAQU@MaI0pM<;EQBm@MKXIveI91kGT$U5m9hTHu4X z?UHgyA%{i%$_60M*luwS;RGG3dpmZmTUT^gvRCh*(Vy*}K5nbg_JVoHoeyph1}oB5khUX{j28~NL9>E%wU7?y7C0J%5#0S$@eig#mOJfLPn!==_LW&Ona^{mpLA>Kq_-|(VSo4XzOx& zdt>+wSajmP44K4fM}0nb0KJPP&Jy};P<u1EQEH4+mZVO?*7|DkB4O>#x?O34c26*+ z#p@`v724`dLUsh7lk`^jD4m5R!I#9WG>1iayy{M;7N zJI^kz9u5mhAfs72b~89me4d)5t4Z?ApD**9JT)>`w6sJ*&YYUTJ5=3(mf@uCE3 zLD?crU$gy6gB`M;DikciRLEL-nV8oi>6iN_c)v=OZ!h=nd=*5qm)Zf7N#ZzDZhw(td(rQ@q}|17q;G>^ps;grIh}LtN?z}@1NA_|q&}{MUAGT@ zf^ipE12%5wgid2@qR^e+3ioNl*TmGK$1T)8 z#xrIVM^pA5mHjszO=60eIUm)dC<@>^*l}HMkS}CJbMYs?_0(?Por)d8BJkJnTUtwT zIO#IJ8Kv)|DTvnYNIJE#dC8xc#-GkIg+1=`>M-8Je7a0$t@3hM(O|}MCh)E<+>?tjEX}*Xc>Za- z9Sh98s7BV_`(V$xsj9A6As>ddr08yZrv7aH%xiU!-t0!&d-#uR99O>*kVwZ*dXYWv zL3!r|%DR{ktZ|)D9P49FHXm7=_)u<-ccPK-v6WMNdr5b#3LSc|xMHcOJ&w4_v+fhI z_1+~w66Bxh*nmC0ALxP=Lg1vU$Fg5eg%_Rwz|aG0gnO+5>c5b`#oKeCqqf1&7UPr; z=_m5u$@jD1xIDh+9ao&afVw*ou|Et=FEzi6UybVFZ{qbvsiPn$)9(^`lW{8djD*TS zRp*kGs1l3%l9xM4Jhlu9-lcR7hT2+I$4d&oJu`b<5i9Wf7bk|RC6bw^8tIP-K&oFg zuP=Pbq;UVgF6~^;f%CfBUb7atEE|&c$d9Id1f+PdfI_DtjUq4a*cjL^-UHj6St9Wwt%Sxwpb&bT$XM{E1(#JGel=ZD%Z_SMJ* zV9o;O68$ATM|RqyzwSyT0a^MLQY8%if92^`usjin9(4u4H+m;(M_CQcGtGzHm&W~M zKY3xTlLhwenAI0`T7)>F{8&%=x2m+rsLr5Td@ zM|3XX{Ah9UrP01EpJ8oEKA*e}DmWt%O=+Qf*U8cPmKq3kM5NHtx; z8>dTnAzNRWSh$Ll9$F;wTJxISMJ(FBWN&>w&zXD4AV54N=?7^HrKIi|z#GMsre~5+ zErR=fvwmOT`_cNJ>2pT*ff3vTdELJ|pLE7ry5 zxbWZlIRUvm;7JNJkW~gdPWB`cL+t4w))jkcONjF0(Z&C2jFP0pC+|Qt2to)C9vJap zJS@S+`9H1W-n``MK_gex5=mh5GHX2C1`Wb`4*>7c3ippZ zg$wzT5wAaZmDHQ)dStP_!TGv)3#-nE+C8*cF8FQl!24s)i{TvT=u%{5faiUdj1L}} zW!`(Z{kktB=$m7rp3D>j!{V8nKqg)qieB+a&5`{CybvY<=D63dBH*i1ELGzq*9oOf z-kUObN8^;7JTn&JaZYc)+9vjx+=-n^fzeXh-73S2$O`(1&ws(&rg z%RBo?$k`~AYmS#+npNWD=clc}I95Rqu`%}CkD|9$^M$QnA^KC}TaD!F2(v<&?bH#{ zkZSSI_m9m_yXlB>a-BnQR#Ox#H5%l0Jg+@`-HeKWDQ8ijMd`prRE zw^=byEXpy(V89<dl20FO8R__={qzXz$8T2PaK{82%Q?t8zqi}hCTIBT zWQ^V{(vP3y7JJ3x%YyLmIJ$@rB~dC?pEMAsP!m+Q0es_(+Dn-LCgq9{4(Bg;_yKL_bm9 zbfV<9ueE&x>II=rG{xRjp8;&APuT-*4T#LEA}D!Dj_b`VJK9v)6%U8W%V$If>0o%^ zmy=Ch&;`$OueYih1Jld$PL3yjg!Fs@hTsA{4*sZtdJ{pBI_BX>*CHmai>KnaxWfsC ze7=tGTZ*g$owS(Y6C0TPK$qV7V9Xv-I9+9KDqwJew%+JxinZut#c?M3dCNO}JPxcB z%Cx0lc*INIY+tTLcNT(Zet1kcw|g{7+Zo-U2qZpe61S*=%c0=CkZ>|^>PYH%i$WG9 z0OmrUYx!Q8L9RTb=0u){-57fG<;?V6x@b`4evKRt11t8~`c5S)J%+ufbF1Yz)dy(egm8;}V?Fka>o5qb;IKdpT>n=H!%r5^g?r2$mc%{4kruXn8U=x3 zBoOiAena7a8Fwx}hI@LS>0DqOsP%v0DcIsR%S8CqpOp)Y?fi?eWSD9Ch~v;IL#F@f za!2)?vgJX%%I~#+nv*!fke55j2c)#`^m|!};=L1t1k>4>|6K*Aps?-6?vEPiC3@*buM^~ zx@^)Ep^E77s~S08 zNJ#Cs4#n%w+M5C}Fj&iS+TK--5_Q%VMfLkL<3ath!NMaiApSwl@EC}$N}pv4Zy<(w zJ`R`$NS5|blJSr}aLT(HdcN;*=RH=8r=SfzD}8%2C<0QJw$byVa6e1x?sH5&Z)U!s zpYy!=?5S^qpE7;6!royZAjD~dQp;MpZ=B!rwVBAC+TUuwRbLZjHsQ`3(1AR+2S5I> z`_V}3PS#ntS;2Z(y!rDHuJ=9T`*T3Lv}kIcFR%8qh6W6IY$iRiJOyF<>*0rw!tBLy z1;8i&V)&+?^7*F*uGfV=ML%NE#k}xMsC%h?OHJ}?B8Gs8!XCE|;fw424#3v$`mU0I zjDM?j-PBtpH_rawP4stpp+h_3#-ERtEFtKFwPn_-Bq3*oKy*?<(#w@Me1&@<^^U6C37Z=p#ZSfifh>Z4oWtFVo z7qc~A53IqTOZ%4(sD>A()DG_Rhmlf8?UO_{%wQ0Pm}$AEHA;uml0LCp`$U`n($=Yy zu56>*R-AW-C5$E;hz=yiRns4YM>&ESp%Hsok$A^Eb~zxkr@i)4zMHR)3g&Q1qmVd2 zk0G10_veXiIh{2?w+#oo^ls!#rGf+5A3ZgkexE->Ry93r&X{!fEu20mOPJJGnV0vM zqYOSqmTzLB;$yv!_?!x{O^g-Ir_KU5QZ^7`DEoW5Y3%I?>=L(VZ$)`BS*{(n;-)c2 zw}ZMlZuN<$DwL}tnN|roiBHhM?{7Q^NFg`#cl#H|p6y>rKOI(kry02v?%||qZAnD6 zCX@qr2yKm!%{;fY(iTC9Xb)UAT%S;4yO`b3Oy00T%cR>@ce z(y&h$SyCMOGO1zFuDOiD88RE+>()awy1CRem^}~qg0#Hio^0ZqH7Yu_2DOjoX&kP- zDJ?JKOksMI=KRJhZfC9=Cr=aN8LRT!!l|H8ildfC%~y5vdiw}3ZV`p#e?NJ^KIT+& z{dz<6hC#qxs+{xhWr7$#&cBg#?y0^x`|0fMMeGEV@*TEcqlg_a2&Z z=xvY#wSPd)Yzq3@MH4eJkNp-L$3XPYFHv3D)pL0iiG@;ehU{g2w}HDpB!H1wApy2Wtx zOBYQgShGt@TR6>LkEj9J|E5=yES)B)00738nwp~Q(=)o~^gYiHc>mXD$BUOER4Ew~ z5pX-SBrpvJ<8hFkFRAo_g2%MqC<77JM06$0jo3){V`jcXSN#(!Yczjg_Ewx2Zn zdX%QM%#q~GG}>eb#6xgPsC)lYBfyC|OY=X6+_AKuP8}pGk<70h4F&H$4@E}6T%3jz zW%k7UlVGhU>rTaOkJmP>9kD52iOzJr)z?+ zij0+TW`ky4U~=}7a-kEsa`uM{Udh|@799!*)%t_1{Goyw8Qs<}v|o8D1W z1>HqV2MZd%$8k^NE2f86uytQ-S_*u0e{e*=->Eafq)|;gS0%GV!hfaXh-c|n z7CB?~Q_-0{JR-Qsk`aLMhGK+QIB56<2s@u)1an+U=6lRWUmU5yRO*`*D`L;r5U2~R zLvYFWF8wYIIuBcpn76bCa2qbas}Gn)400HrmVGvEIfKbqZrat#&q+VMOXp%jHO+4~ zLx1-Q3n}oy&Z9J#dMOh3@Ax!-o#1`_h}`-(F7P)%WN|xg-}zU@P6fN}L3!8J+YW2^ z^SsQ?SwHItDsJ^zLCaziQ9c08}`5bz9;w z1UHzD?%)RkgMj#r*-3`?P_vq-7jqm2IV8F7JueaSuDWjXRo|W89no_(J<=?>puT8n zTlhU8ZH2HTy(rdmINYGkre9*x@F2uZRp;$rnb(&{#q7_88VtC2T+b2l-Q1i9Z!W+) z5t6u^mgZ9uj2KbGG^UN!A9>L(S!$Z`6;tLf>PH(fhQJV?)Zx==>03J9ub(AQy>qlQ zw#;Hs;Nxoj@9i92m~&>&-~Of5lVAJ>y}X%vt9h*Dt>H@^3apYEn)0E~9Om1=i8m;d zNS437a{#{YP(XW_o|;H^;6Nu?>Fpa=ES4%Eqi=R;NbiU&_@Su2w^BRXvJgQ) z5Y_#Y^xiT(z0I$J5xmg{X*V~;kn~}c!r!;c@qe?@yqx>(oA2s#p)@8OlFUL?e$Qv=9-dFX8+ezQ zMdYPgC)cz3dVTKe+dGq+nTyyKu;yuz>?V7kC5yH| zV8xBvMiaR6E=>|esUAsomiawv6;Rp4CiNxG-9x{BT>7*v2dz9lY}nUD2aK_R(nNi3 zM1iz>L#LB6VL=Gn9Jbyrc7IhFyoRc+D>*0&idS$$djnjif|-wB5HJjswp-~k!tui$ z$@V^Z66P>uR~ES_7niTVlLj1xUhN2b4*m6I(VzmWU3H*mh+q4Yl8=O4L$cToMu z@z4AwhiWR%?UGexaemS;>m641CwRvx0y8W=xAy{-pWos0vzKqKJwJg4GXt@%5@O>H zJ^u}*$thJPmA^7qii|tFf)h$h`odcn`YV2LHE&hwagk3xQG81^M$8}$y_DEOt>sY2t6H?6t#^W1$ z{T*7~9Y5?x;mg~2EGgqL%$QL<0;&VaAZir?&%oTg7eaa2znA)|=SH=}cfEo2-&~mb z-d&tHmM;b2CxSFnm)~_?H_|h{+}xev8On9>o`jC&rkGEpV)%EEmfU?kzs|T+ z=|;W2VwN@9iY|5$etw@?C7BtG*QuZDj{+piZIhMJ8UtjX3 z@va7>IFCzuHPVS1m9PKec8I$orLX?yMKCtR6VJ|%g|oU&*yMiueua|p1pb4#gawgj$5)jKa=2B1>g->z zTNjs`!=LApAgKfV5g+v7<5xj7-IiY7YtP4PXkP%0&T%uzq`1B<47T6mn-ecI0Hx{! z1HT{bel7wyF#yW&aVx+_x0)y99sQr&WNA=lX34=E?Vh>Iq_(MjPR!k7<@q6oxX9a1 zQ|e1|KY#?|JJ9}rN=*cECY@8T?p_GP2)≤2E9&1f_%ntKVr+TUePkQXHGNvEmO9Yj)Fg!)cU zqf?_iLn{cxB*@x%zso*v;u%fbodMrw6yJ0`4`#1R?3w+hOfO>A3#C3S?cl3&0#RTd zLbS{&cm%U$6{1bv2o5<<-}|dBn$&!2FvQwF!VtPsL_HFW#C>Mp2=@i78ub$@?)QYe zhuwA(e~;QNb@WKD0U?JiES7uG3WxdJ_9Gl9jU_2RdCuC9t~i)bL3xlhQ!#dfDAn`G z*{^he-fvbHC<}qmjFR@_#GgGsAHMW_z*dY_9M#&@xJqd*;(cBU7}0%IPmI2Eke$s6 z#>X%nkJbEB#1UHJ*MTfFOHDZ75FHAo(c_zCTD7cgsj?ps8*HJ7)F}_odq7HrM?a4! z|JcI@e2;Ky%kL=Ck1R3MFnXlnxx$QWMbU!|i}KQ2O+NxPW>Y|1H}g z=0f1PdkTXa4{k>H#ULC|DN^*!AO`+Ps8EAvYS4P8qZ)d)_lV#mt`>g_q7bOE^X~H} zpvw)khmHg*+#2Z7$p>3K zv$vmk-3x4x?Q=IJ4Bqqd$-%XGHYA8l;7SpEbGk9uM5Yx=`?VwjMZS@?1Xj!$rDwKg@8Y?q8}~6@V%Hg5TkIQvoA3n^ZC{%SI(7`P5#iLiE1p{bbrgP1j%yGQlK63&i3z#roQO#HE-pXFb zuxp+DC)zHa;tfV~BL)WK(KjSLL=OXge{PI49dlq8?%79tpkT^>rO~5GU`5t>7Z6YK zd&mtC@WQz=dBrO%nV#G2Y9-m6^p`-LZkY6;lH;3fiPmi(+K^@SyM5J8*Dw8D`x?#X ztMEehICrsjf0)}0dZlp5uPD==@535g29y;WZJ)Wytx2Hn$)f4C@6Ji*ceM}I`4do% z!|DDqL|eLAfv%CQ@})J!^E++WOyWdJ!{C6lZsG&_BDT2&&yLJF(lA(Y-?NVc3`cig`<}=Xj?D-AiqHr~n)EVb^$=>+kE$R+VC(Ce?*sv%w4rEW*`A(x%nMS~ruvZKx#!E9 z-AlVpSD$U3-1O&JTE>{id(lTm7Id~e;otC;2D7ZyQ|M*RU-f-HqB?R$JB+%vkY2*B zW^^4?Q97MuhDZ!*r~-+DNEf}@UNNZ(hfKDtt9@iYkbFqX6_IM$HmRwZo>)w z0Z?~)@F9skIyKNahHnsY$(aKtOS{VKzwn3{Us6B0j3M8W(e-XT9Oyc@6?y(co;VZJ zmbZw>t_no2qzBx+;&;ec4~lG{FgaaoFd|E&jkQZln$M*QWMykz|f(iYA>oJxOjB``l1NV--vTeUjT?R^jY z8|VFMbr{8n%I|$-5*R>)tg?pI_xg-$7kiA*CSTM(1+m$zEkk6=i6nwdF4f8E>T9@S z1>3d`h=)7Yy9!LHPSHpHy({YUI$6eVVml8rI|I8KYXE~7dC#zLWJ_CqxMSGi{_bR7 ze2zzQtiB}+uY!VA2Whqnmqse7Cr+FO#M@g(3XpKG7!GL0JyRW1zK^w`^s?XY>0>$b z2jx+`*`Zf9MXSUuE!a{lV&Y|;&L||NO--^@aEprfn{ zdu2IzIZ&W~A+UhM;@q~9ze*>|tGZ>gq@VtXmIC$h7{m(+FkiC_L7}}+>6QENierTr z>Z+bF%j#Vp;Fp3g)gri5LXE$~QjpsRF90wE{CW!P0ts0XHvEYCPkN4o%tCc6If^UzK<5)1+fK9 z_;bLfqDh?hmh2qACYDbgS-FQ=-1d-ON*1H4&s1738u`mc(XJG*l#M@IlxinhN zogAHMxMlyOgO`oRIM@fbgll>*xv%>^?3efuk#-IC_vvy8LTR5Y6G&~lkZ~KloW&vv zs7~|CsR$^AqxBp0l)!KA(>#EMoQO&14$IZNO{I=AP+}<6ejKxsfYg0IB{kH%J7-&Y zj$#?!H0R|v1(WNyVj8(XwuKj9uC#BK$Lr?-m>moXWG%q(hl|WZ@IRt7oIJ@21Mc91 zb*}_Wbz1DlCmNSMB!^3!Px?Zddw~LZJBKdiChO_^^Bz(N0(DrM?1jz<%%VQl^XJt+ z)=3oH24S@~iH{EpiCn%+k~|Lv$>l36Z~}YoryL;%w_GAtrY+dI(A0qg4vbH%MAu_mq%ubKH# zOw3G~KDNOan8nTYceMd-b6|)7rWwN`Xt8t<)XNQOC7gNC^#{jivIEhU2=pLugW=Ln zd|M$HC37v^;9w{4z1@C=nm)cT#?=i`j&^odG`_iA1d1CBvyceE&@!0{VUKwT73NPO zZJG$g2*jb*3edL4lZb&@K((Yg;5nuwXlY>?Nea?&X4pX=VAnuhAE6r>Qp}E)&gQf* z2a8~ifChU=fq5caS6edA$n1a+=KzG6J0F1ZjM$A=mhV8 zv9}^ZB|h+zB7m-f6A*nNXV2tD`azK$kI%*7SPmR49Z-UBTRSr=XxK;r=r%0C)r@2> z^tTgYB13tBKy$TZIB?*zhoBi|)>M1f5EuwJq1w8hQv2iEhq*d|;mfO^X{$F!ld6&Wg^)*kXe0O&u^4Xqp9WzNi!&+ad^M z5+DdL7rMDvLHBB`qaBmy#&hA)eXU?Rl8_I{JRiuw_&aD>a%^0}odq;&=){WA;S#+g zd`U0{7rM)t`kAvae4;NugbioQ6>+J;xiCq9%(Mt)V;pS57?vcAOQ^s+OxK=CVB6BI zvD!gg7dvYhga&>Id__l{Fn^9OkilRi3&)LS2Yu8{Y=YSl05AtY<*;K|h=pAMA;dp~ zsY9c>1X`jvFnl9Y*Bcrr0qE|}#gT*EEJ@(4=wRK<$U01*M+lkWz<-38j1Hs(A0ND_ zEgI$t>xNRo@Q&UT7R@2R1OsydNs(l#n-*wnY9N&rVe5zIGlJomKvsio>rDnYpXh)# zO=D3bDR+%Nr#K}1<(z-6sB}yg0z_YP%@ZEa~LZM5t})l>P`2<2H~_2 zWX>`07vsR0tIN?1(?;78LfJZywPDeHNn9&eyel9fk%8t8bUz!88JKY2a0fh_>2bm74(1C+OnwK7Ni+Y{h|j#Vj`3P1hR-Gc5d|jZOgH6p>RPIYY1GK$`aAh90-{fkTqbU7==L(rb5)83yKi zSTLQTi!2$YCt%6G7%B|Xv-hP5ZA^j#IRqZY6nfNJ1?wR0Uoe^I%nh*#wS^u@JRzN9 z8tUQ(?MedOXzWnGFf;HaA-m*D;p+(a)>=MPA&rMDiDfw31}59#VD68A8y;aB7Ot%w zAMu&wz%JCO}(-Sv4fQAL0r* z5!h^;U4)5_g$`afh>S!x7C0*=&JS`H4m_HRE}CnP`ZW(b!W0;BPENXr5~o26VW;3g zUTA=s6`Nu1?*gr-0-*STjyH3Ib8XHvBheY)qL~BN9`f#5(1@QWv~v_-%&h_#TvM8* ziy1r2*%5kM0JXtS067;+%RssgOvV;QT0%-iz=XlZ@IHKK`|5ziq`qvXEmRK&hOta^ zm_qY#Y8V}@O%{?PeEHUFlr9&_Im{WM4p8#SH1Xltn+7|g8NS+fKxsAeA>esD9$SY2 zwfw>6WUN(~YiJ;c=?IiSqAuK;i6_G&7jJKCBg6w36W|0qoKSy9KMRZ{7#xraV6j-x zp;Musivu$4!ki#P+BFeuNWswNo$kxCK|ZRjw=+~w;B9agSfLxw53Qr^25q@GW&&3V zCfL>&N8{*18XYCDa&^OVEm?>Sqk=Pw^guCp(-H<+G2G~Wh<5@Ywgc74N?;CqL9lnj z@+^@}K|7h5YS~gvOzcAO7`|zk(1flP>aPv6dBeF}0mGX>!P}DpkQ>_R_}f6~HH3~- z)URgi1PqZ&_0l&N0{!W9t?it{ zeNAD;8=GvU6XawT47@H~?Qkk1I06%3jci8*p6pDugw~n1c$|P|0(GN4T&6G_iCTgM z1V4fc{9uaWlPCg2i{W)cq4@(7CTc=81d7N8M-KV|{hBSy2Ku`>^gM;f2z#D0jzDBF zbRq~LfR==Yp^>NA7y;hK&Kd)wUALXf2&2Mxs? z&|VlH=*vctxl9z?*wn?GE`X9;wvG>SUIpHcdB!7qTpudN ziDL(?6iIv%q-}NVc|l|h)`x0|53>l5v}1CinV1Py%NZ?j!XRG@?!$ES_9K%ySTl+@ z*B1J?X~TflU_^n^F##l~z=xkKnCx(Kz78jlgF{>oT1X_#1&%6_#-P|mL~?!ovF5Hs zC!%F2)+Y$!IbRA6x}V|fb$tXxJG!5>4*^R;;Z2=!-dbEOo+ZpD2}Krx%*LQ1Vdy1> z!HSF|u_+N)n98fGjn=WpF$3Xsf2fzYGT|e84ee3kk;_D*xp2aP21(IIPP$JJ4abBS z*xC*HHDUrVP@_)Q#zB=ZT*Dv+25MutW_&YVq-$i5ohv*S$-`4HP&f}ivdkh8@KZWSYAnmXhe;fSd=8qbt)4hYC0R}}vJ|9!plo1+g z!(s;TEHMa;k$}OGUA!?c1UwuAZ4~@bh{6eW1kGd~fw;&h62S%eXu_}%N3H`C!{IPt z+)w}w{?b|(hT!0kdkB$#xL{tSAB0}!Zce5Fh<-u&d)uO1P(h4PM9#5@V#eDF+}JoX z7a|nElXbOhsCY|08k+aep#?6ox5#)bWYP!0#lqK(p>0bGvUIf#WrG9)AxFo?0TJ*p zJ~7nFloS%8#YeOP85+&lFwlYizuJifb9I5psl~OxSRjIjEIjfzT>7ucU?A88x`i7| zYqtwWS$6bN6Qkp;K)bE+S-Ri1Ty?tT9HgE z4nQur(8x%RHpUz8r|pOHGx0~Zzyw2~^0BU_Hsm0>w;%F(0ojH}3xYkO6tw(M&@N1e z57QPM;8$%L)+&_ti*ZX~IZ{K&5jsB5u!_oKYcoUHIDs#WXTwJL!a*g3*~4crrvv>D zMJC#!`B>mL!xJWven4@J3=bzWX>JrPZC7$620D@G>bRn;EP%&lLB}F4IgyMk0-Fb0 zYHp>4MH=&)L*N$93WdEKwk~8m z*}^d}94|n+a{U?{WX7-v;zK_}Uk4c50GGjkq1ea(ls*qn7EP3)Rl z3&D*vkMOoK526Kg3IVf~?%91n;Yju;#o zWyQriGn^P?D8UDB6vxIPivci=wjGrm8IC9*8)&2o|AW~I5g5E>gdGl15J6!+v~XPv zva1ANoDL4=_`pv*Z4&b5VNS@?mPk3Cc>q0<@M~rYBnk<9Jew25!CBdYWD9-`aPYPd z0M?M8FYSu-%J2&)k6Lx2&0QZ6bc>-55Z96Vdmh&54NQvi^qdekD(|> z4l&dcxdh6AaVR_sNB zG`tR37v~G-nrGz?TTGy#xHzg~pc5$=xjxd#($|lKMnNC_KnF`F_){{Qfrf%>n4-zj zwbrsRu{J||3*S&`Fie~c$1-W&wt-BN8J4NT;|5_sbP0U+FOAAVF){X`Ot=Lbtp$(T zwnAqCWRJ-hfms0bfI}q1j_C@8>ejYoH=xj203rcS5DWxEcHhO+f=veWBGLp0M zDCko~HYMYI(4j$oSkT1CibjwGR(LCz0>Z%|a_DLWpldSCKZB6SI zhqojyt8;An`>fMqPY1Kwb8AYET~=85eC}oVPs3(AOp_Axjj-@<-o%HmqtEg}I$qp) zegDVj&bV+#LECig5HrTVMJoPV%>Fkd<-f)3e_4qC zTbuo_Yq+zP!7=9u*&yKEGP2Tr@CGPFf&4l|0e!P8L z7TB@t_{Kd4-s8erDZiD6*nE!%G2=9&MF#u-h{|^ z|7+zO%T%43Jor=pTKP~WFUj{ojL0Rw*7Ki@s{PIjw_U58sEGgk>fp~GH>YZ(I-~T9 z!2X}u4qAFzt?!iRvgd2SU>^Owefv*+M6i{7(OS`x(k3k%1;a@0*@FvnW4x**K4Y~V z*W{IT0%;1`{$zt(MiPEo6K>#m^ZTy`XA`7uJ&zgRn(ncxE=fu8<(-g?*go#F1hKo! z(p6Ix*uqBi)zeWj+*V~LJ7DJx1PO4@1O09@P6Uy7wl9&{7~ED;?^ZT^~oDIy4_(bZL>YQa)sfi zwzm5RfByP>vhew`Y@Yfrr5l$$-O-ow`}bD2Mm}GKhw`=GU$blnYH-<^WeuD<8G|X~ zk@g&$j_o1FWq}3EJNxRBlpe|18^|U%#;{5&4Nh~7)zK>Ytgf4FmrRccUM=z2KKfC& zF!f$h^Lvi=lZW6*tv1)a{M!XHJ|>4!>3OS>vGm$+uYnhAGeo;%)RYv5&qqz5m`!H| zB~qGIp$f2%X9IFG3iO0xC5~vF%J_w^1Ibg#2fuGVuBfY_oF&rDjQDHYXp9@(_{+7@ zmSy|Defn!S7`9O3V5wX8*vo4g7FRYL7wI;>8O9yp<^ac=yn#YQCwm@~J;r_dqrK;v-*^rn@UZGDZ)<~*-h;V-8tr1a5` zslW9wTbGi3rto#ui_aC<8)HuuEEvXR=+%7*zuzNud)UXuN~Uu0@2`P?UO z^8Qa{ejl$B75e6Zp!%8pp8bNk!SqL*Ms?@u?~3bF_K)VI*IYC?T!U<_(cHV!Q_Z@s z<6M~;TW9J+Bw!NA5oPY4rIywg1*L zlGKKuGJC$SBi%Q_rAOgn$|M_0T0{o{nIo1 z>GK0#lP_-vb%B~FG}0}rH{`=x)J=bdb*mfG0}WDFe0RL0F@cn=7oQ#R3ZFDb=Y8&Q zKC=Hyci!8b*}|cW{@S&Br6XSNkMQ8b3&{u5cTZHR-{~#6X*t}I{U}A%w4i#@b*i-0 z=-6yv^+;8da6pgqu0inX_!_m*nr6eh14;S`pe;+@miw;tZ<;Q7va2x8*-N;Uy$~ly zlE^#9vHm`(dH=gsZ|I}tPfv~27h`5MivL;VecBEyxm1Zu9^YlO)A0k(5H{&dRYzGJ6cpf!2=qZ84f34}I=nk?J}8=CI6)bPtY|2Qxn>EpaxYxS+O* z@_72*>?^5b>SZq8=!va$GK_wZ#pRuz5uRUL4=%{nZ)y!JS{^>8Q8~Wq?wv6zD{KDk zXx@bt7Y;56$2S?L^~KDl0Gfigq0@ zrVw#QRa~%bE-Y69Bk#h2$Z<%#7E@%8Zd*5#di*ZFUAty1258GS2(z|@q-w|*=k1YI{uixii zo*7)$P5=8`@yQ#3htC}MtziZziVtTLO3bDfM5mlux#OXsXjRVp6w?)wYxhQneUAhc znB3nPExTxY!($JpB3vDuCEX>)g_4yzUj(Xx)+)=-6Mg#1OE0+)+6ISK)|`xZCG=Bm za{h3(QN#JdnDx=wB>jn_h0bz+d%&U$NNu1@Yb_ocSoK^+h?5% zc$-r)mTzI4^jbOHW-61~*W~0LyyoyrOtUt%d+_WL$;-}iPJ`brM1OpY_)1&vxE38& z8}sBoCC2k4H#=wAx7Ubg3$fH^wir7ViOM&Jq+Z~YY&7p_zdC4e+Gfqe=nXcB5;fU z69U(6k}{Dku2G_jC1ioFjOb<**&BcPG5b0>dwN7WBk_%b5@R^S?|heM>P;F}V4g?P z%WV(1O?w)jW-P7bLzPw7G-ZQJF5<^=Dd{!0nijA1SQ+{Gy(71j%fFK4wM*|}5!jB{ z@CK*i7`02=DvmS747ej#FkWLXt~0i~>a{V&&Wk&bqMQo`-o=QBZPRliIC7P@Of~9U zJ?*s&m&e$`GCR9-jmXuI`#-S!Rn7c2TOMRqTy783jrSPS-#7ivWoL~c2zJ!?(39J$ ztY&oUo}b^R-R{q{=<^7K@s0X~>$QmwWIg4mc>}kkmx$lIJH#dalhzirOD~3A*`(FD zx=({~Y-LDU*S5|$#?VW-=TG<@gD&eLxEwX7+X`Zz%jFTTMN(2(IlKuSCMT{t+H3RX zOwpOSq#6(1I`e#u%Q#eZX`c%WejH4FwCR}Ist==e^Iv*GI`Qx5eI^-uM*MA_cAR;m zPBcEwAk{96gg&`X<97D?UpZl2;-mj}ZoGnG*O>xV%BlHn@t@m2a=kzF+?h0E#P35h z4n?I*F|lT?g4`g#a#V|{Hkco|>h|7OK8`Ng%j_H|Z=5+Ab#8d2=iM1bO!|_Q zF`7<;q9q3IBXOAp_7{v|Ne??#&nyjBuMJtO_ljBQGL>mOX}$aU>d8GVhm$_7HVG6h z?w+W+yJ}a9^Yyw#v#yy^UzISCpGFjna_`QbJ+ki322AS|YdY#Md#JW3i19=D@1e}Q z$A7O;T@e9a`kxT+RV^yFEG^?6yoPhUGWm2%kho3HtpMuByM@aeR;6s2Leu{_T2m$w z)E{H|k4)07_{ z8#U3<+#1R4t3|cNr6sqmDtIiv;+*~%xl#R&hsusyb?bwkyC#LIn&=<0%RkM|4>y>s znxU_)rg2|v@z>5z{qXYf*N15u=c2}oEpXHS$T4EHI_ftb+@SBiLfPQ%)H)GwJ;POJ z8l4x;I(vlGc6s9_r$9pf+3#Cv#<{1^DeQ^Pd-I{JN8{#&Xx+UOQuI@Cq;$+ z?NM|p0^eezcE#MPk9NfRPunj&P_+=@QR7U3*7;E z*~^Z7d@FtabG{rt9IsSdey6=r$wkn1(IhN-hAvj8jm?)(^3#8m*BS(_#6oVm&QxVT z$Uw5@=1W;Kpe8mRJWOuFACK}{baKB*10&hcX_%;_=6>w8*ynXOGzxzgQK5KJ3MttY zH}3o0_}wK4CazBkXZ8}wxM9;<-D@P&d`(Xumpk;jyP#HKhp^Zt`sDJ4T%tsh z?_}zD!SOW}D6O?*@zD_to8e}bY$U@VZ{^O}RU*TbeqGTUz4cuFRq)uWyHrbD7FAGE zPJNc_U1gmkv8uiHj!Pey!q}Gb=ft(1tHomPFMJE?f*?Wc^_oJ^(?v~ZucjFGbL;lL z|7b~GD=z-DGlWW@TBtCQ2x&54t zuBYgm({3Fe&WENMb;tjz)Em8edfWTyCG9jPDzzAG5FSVHd}+)aw`3w^p5= zF!3Th43Vh$T$?yi=gul7_7~D0eslY-{CBH>=lVNE8=LPA5Y_YjKMbROcL@SQUF?=P z16WDQ+&)!R?L)-cg3K5-Rppu^aUnY@{*hgkPvh!s>9vymdmf^q?eCd3Z^r5rLymiP zezkZI*K#>0F{R63rb$ksmYl^Zu~Icl^V}ZtPefc0b+(4yv;D4h+wSxKxD)c4kY}5ey&^R=apm%d+eArmTSo)4uIDamSjFAM&5()lO^!!V zzkE%MzXSr-Yh2$?8`L|Q>pSwz`fP?q;_8;;oh%*%s?v&BwF9@1U@2B?sng{XeF2hW zdgC{4q^)Binmm1xBlQk^^ptYlCu=*6w_4_wsR zY&u^)=bfD>>~6#MzlSiXGW4#D(bs({F>XZ?>%h|2H_|=Bg797?BHe-Yx}94WAC*j$ z3)L8MzcB66%*!d9&Pn%LuUpxlpt$4^h|o%16GqWyM)CvI*0n>vL&NmibD4(_RFA3R zpHbj6W4%8*ak0x{$GvKG?0o#&cx8jv ziHkox)9d}&B-Xu4KIQtL0)z(m6)igzH?+9Fc@Ui``h=TDYR$XFQa>Q`+^?$Qwh!>)V0D%drynMsq&jPbVdbYtN+WZmODDn4e5vzV_*fv?-rmq8@`4 z&AEd}n0T|(D{9S)E5`!L9`!;{>NNsgG){zul(*z};Iti$%UpKc?3(s{WDmhv#JKWV zbwUUCcn$)v_#3A`v%U?EYNzDARq~B5pDxG7PdhB ze>msCisBw`PS_vuG9WJ$Z~}Sx9}v;eRZg-CR`&@clboo%OLu;E+I7^!F6Go%XRciq zVc1qLpa?(_IVHj}%BrSqtUBCPeGGA5nafcl#jE3;H};P7RYrJM#$k`FP+I>pxA8py zHtx*8qAH-nk@ za5(xaI_g6ucXX9L4|7mX+LxsA^_&A4+ z5$lID?(Fid0B~r;dp^y{V)x}s2qGqW%cml8iarE91h2lbW#-6=s-3L!Y5A*DeDUW4 z40?9dj5m#5cfX@yeR{I1Wk$D0nC&-OBcvE5<9os=wi+UC!` zUyZjFbcdpn`}SXz9!$ovI^ND2@2@Lt-1WPpwQV2dX!9n^}Z4rVvW()}*M* zTkc9YyL{Eh{n&^G@P$mO21B`$pdzT29GBJ4=ZvhFb(h0K*+)diB2 zk{0-cUJ_c*E@hCKyPqU%qHcH56U&QAyt(nxeU|Lyttn?K_Q+*!kG6Vx>C8TqCp!O| z_~DuUh>CsBIxvpv^)^@)8*=i%4eg>CPu+5o#|^9ez@ps)az6q7+dKgR{SGrRSL9h) zHwibc2+Q>o&GwziE-8KJeyBryHT7s&8mOVFkD$;Ff14XNH)_a~*_*yBVXeNC7bT_Q z+6?Dd-ucLa7CLf*S6x_sW9EBPwZx{%hphTxPkcj&E|#hA=n*J^Py z>{AaacSK49l*;YTQ4Gm>OI(t#s1?3A+`KFh!s&MO+#i&P6_PXlGd1C&s{~ChWzbmC zcU9d*iO7}f-J_>#$IhARh`3hNzKWh{4l@*W<6drx__lj->Emr#s|j1VX9l_&*LYt6 z9MN#el!WJW#4^vE&m)N$qBw5C4*<%xz4UqYcjiP?+yQE*ryeP{IcvHdF7u+7@fXnNmkWr)&hx`(B826THo^7 za?N!!-38k$AAhV@j$%n$Qp9Zm!(Pzqd7LmmTGsHfH+|BIdZyxeql+V73VoYT| zi9#oo&L}^8G?2Wfx?rXyqHfEGMX1hyh?M)TGw1e55{_3LRarBu99s)Qbz`@;H6eAi zrlU$+hPvp*wVqsu?>l%ahRRP>oSf+c(AC2)`_T%0wNI0;_Z%=c&PuN|mAO_4*T(5j+}+Ghh)Tj2QD)n3+3PLG@OK`n-KmyUePf$S zV@dua&7aL456_*{B#eT>m5BV(?RVr#k{*cTS}%e3xM=o!z+{h`%vq-%G$9zNxHtMq z)u%0QaGF0PQz4oc=5{SB5)2!S^XU&B)2SE{*ZM=hkA4C8F)m&CHypFjTfseL{lgay zCe_~q!0m{IvhZpP9whNYZ+W<2U_eNGy8R?&%nC%0{%&p>$-I_3+oD(-gm zdNmgLjR74?$vzLkbr;vOXC718eyNAv$Cm70sd2?r=>>P;8Vyv>kHPf41YB>d3Xf--8rCCDY9+OA{W zJC^LcAb9&%TQQ^l?k39*lz$mBBQjO!sYg zy7=5ncI5{of%5*`rdgx#MLZ;Z&=>Lg-qilQIUM(3lA%ZxM^?K^OJ9(@~5;L?c` zv?kZlt;>722b2dU9lMFU6c+exG%s26c7xMxk!~rCyDFc+6}tIef3iwW9?q3s&s*gj z8+9E(_7jr#EZ~~p1zy_Yh)3$!gRAv5MITj}ZE^&W8AC%F>TTPNz4sHpr;3)aE*2k@ zp&9I0`}>UQn}cAol$QM-5d3AZ2p3<*s4cbG{>*6qx7A5m6NOw2J4ZWXY|pw-%A%pO zjHD@Gh}qwg)T6dLoFZ{QUk?PYHomNv(|9UtyYce^$HH$D)gvEk^*l;c`V2-BtOUt# z0`fP--1@mNU(Zg=(QCvKjni(*i8Kc8+Ss)DmbFUiaqTIzRxpc!>> zNW$T!M7E@4P}!d7 z4-M&?`RwaoaMtP;Z6_yAb%PKen}H;flf;Bv%+*JnU3#L=f-{QkQ?&Zh#i=2Xc)8p4 zx5Jh9+^yS;zk!JUGx^b5;I*tRpPFZ7IC%F!S!2NUU&dBIk++NGT`sl>QE!NzGp4b{|$ zPjV#OB~o5!QvC4h?0Y+h=APd+iaHmUfZ!B07TjA~N4)YsigbbSy+FK~!MU37I~4FW zd=*d3{d?@z^X)1&x=u9=@s_{KhtKP;+;(-d5{O0GL}=WF9Tf|*?*c4kxlsVpk6lCX z_9J2|a2Kc6U9#1?$%bSZdXet%xp2~Ik7j;-Ayy?z=Eb|@pCH{5&+K$P`x!O*-TRpP zThiI7gNL-m?~ij|yk`HWrxv@fue#rwQ2JHBN95~2a`w`3vlQ71wKWflZefa4XZ^|wmN%4;u-`M5 zXEP6o$)4O^n?t4=0H9iM2%WTy) zgyfrE`n8?IsT{`EjVbCc1}mO_i?f$ppor6jWqD7Q_zVLiK}adf49kLQ9la}ldlvyz zlg5hxn~HO$7=(--$UM{f!1F4@jlwZ0{Ra2Bnt2R~aPmf>gb+<*x zF0PeFhgv>eH`NnzKX~=hnkZ0v`^L2`pY|uUQ6a2&!oDvr;>x#NYg|Kmj_qN|O+Zv^ zj&J2CUNYU?d0HbKp~wgzcl}mi7M{Xz0p$(R`y%s3b7^9N3&h2vVVI) z2KVg+h|@hTh6fcuzUYXljNz@fSl5{F?QgOZL)BEf0~3ShV5804E7oh3l@k5lc|S^6 zOz6(vRr zT3-cE3Krd>xBkt;!(s=iaXTcbx$A+3qI$;0Uo(D}WOL3$Tdm&pB%lNE-`Ul=eCRIq za~!4xT!MfpO+KY|*Zj4Mg(I;`l@%mQJy<8)2j>O;AV;kn@p8`tiB zaW9?uM|YgieWk#Ey??gmHR$mEvTwLFw=!7lirCzi2FN(uOTTbHGT^FJ z_IE~;l=NS8D`jWnx7Yc+ugX|XkTrXZE$e`16V)HTR=#Gk zdu4b}Sui8QrRFrZsfDkRTZvbq=V$X@?(B^myFPtiQvd$7#j1_^~;R-Pu9_aE7e2PQ1Po)LArD5^ zWa_D8-TC{=tg++an)u(V2nkh%6rRGL`QO@7u?Y~VwO4#pw14nVImpa9ZzqPuyY1|RT&ff5SVr?K3aB6cDye464B+g{7R{)6 zdrVUqavyp@?T&ix-4jpa1|($su3MjQuBpkN(dqo!qCd$x^Q>r45bzhE;OTqy;@Wq9 zLbx#qK=diMP`fXul(^{hnCX${2ni(`Jj$>Gek+(0DpwmKy2w7I)q@O_%5dF+nIzer%c8v=W9;ZD@AxnyASP-x^N%V ze{m0M8ChORko!67QPnA#h8FE-wqXYvmqyME8vrlNIK7KjwJ#=W)0)}nvPYQKC*x9E ztxtF!D(F@TM$dc$3dTPluh~I#x9BGz2(f7E>2?v(uQ~7c{G79Qf&8`9Ugu}E!kRcq zZ_rX2+(hOefJUu>_$8U9#%bZ#K1J=L45K@pf5)Cb8wm~t$*}V!=8t6;nYWEifzh_Q z&-lo4Mfui{p$xyIhm|aeTQ0_FNn9I^av#-CmWxg;qUOYO1Nmqb7QCpgOKB?235sk5 z37MSB?#lhyv^am4GTINYm}noQ#8@*IoVI=~5D13UT9z+hTM93tUD!0e(sj)mb-}8Fev0=c8 z0$9&-o3|wQutF10r~?hPAEG18bN0nbRd6uF%4thCgc{!koi?Tx+3lMi53HM;Q|lf! zuyEJ9_|x=jCpPXeI&crzW^s__EWA0gIoV*9SXvjSZvs&Kf|d(p-}fp{&PIlWb z{yp$^gZ4k(ntrBle7SD#N+8%I-<58>fsofgc#a=Lyoi2Srwji331e}YJ8KrexjFXG zEzx*u_ReE#X3?HWRM`zf=XP~~sg$i>HveX$=iO4r#_9GAVkI3Ooq!Dd^8iB}M%bYV zjhgoj7McwkF{*pJ*>AbhIi>i1Mk1Lz`Rd*=uL8HG-KlkE3lJ%%O$tvwBI$pi@u|mo z6Ap>Pi&dYGOKp<4(k`1ROrekWpE|FegFOHMMcqW(|L1@`cddfs#66gkz6Mo46K&s_ zvB+ILUBuofU-0lHC<$lYi+VcaqH;A23O1a)K8T&2CHT@5QxflfV zUgs;!Z!bY&>&(;#SH*oK{fln3TgN_F)&X(i6e!NMEjK_iH8tIq#^+9@keyRl?~s?JV+?>QPzA1FGAazHR*mq88$BUX}$b9wyKVovzma z%2opyiM!uDu!r4?lz7yJB*wN47N}C1?AM1W8h@>h-6mQUC$p1a&!zoy__El(vLJTx zhY~fDA@GIu4%~wuQ$fo8~&3LcXRZV^_^F&r=F*b zqt_?Ll}k#bO9j6M+smstAl~@}kdwcX4wH(&gYx`-PUBvxXk&NMoj5ONSKri{Xp=k6 z6NS+~;Ju2aG-eGRdJV;$Ch6_e;6EjMy6~%L4{D*-0016`gMi;qKOOs**kwWx(^&LZsVAhxz9XcuQHyU>bkk5biJ%zl1t4pp+Tka*1Zb+!^Py;74 z_JJyK_62|xs!Pm%PA4B+{lzNXwMGv(C(+|I83itW&jI7=lzf3?JHxVSYlPy5M+&k& zoUxuI5*Xc^aEZiS6@BgN&I}B8Nf^s17lrs9rh3TeeQN)lv~rW@hEi~qzHvM$5td(w zfA8e&XqlYP3@Vc3671qJ7ku>(oR_exX)BH>uENcEmT`6RW(Pc=Pz8z-7VV z$!n#|OAHUqsM-IW@^h$S<*l5}!Nv3gDsgsU;{l{iG^@NZO0B`k<(1E_pAO&rrg{JA z#0Q%_ZPB)|d+Q7@)zN2J*XwM;B^zGMR>bHlXB^{Y~RH&!irJJY)7Mz~R&NBNyyYqkN! zOjE5cIzeW3Z<#)zl7s8TN07)!A==)tKrR~cj*O)~_+%ve?=w03dsOj1M>9m_i?|YW z#h+1bqM|4uscMfR6ho@Q##1uYMeW2rC6~#vo-8@&lCzJxAP_1u0sqT%T5$e zk=U9$<>8iql8LQ}KB1(KO?dS26%r&$ua&Fm&y4=se?%@m8T&eVMnSt}$L*>0RCv-K1s`kACm`@y`5_E&gsYIU6YN?1J^Fs z=Z-~E{F`Txb8;KLDWUT*IeZHX2M`b82vvRy?K5O>>K1ucE68}vKS!UOlsu_k(y&Qn zZ;_(+FtAYb+U{Y42S79D%iU^WR~FYB@4q27yC^m^5rq^K$d7EZx(&qrgrSiYjrYur zwHLe0ou9nBB1bfrd%!39S(vW7l-f<>UYT0MdWF^`O+B+!69We{ot7#K_FWQFdmU~l zi7Q!NXS-~hUuW|X-dvJKdH&|`;vXwtkmN_BCa%zDTo3FgJlcLQKhS4yWZ1OJxH#ZTnp0p2zmC@6|#RQSTS5>7H1>-9+Q_!z#5K zh?a&u>+aEv(*}W994MP|y%tRWap&~kI-F-K5Yyk+`MUJarvJo)t3X4L6+Plv!Oa*s z_hhk;>)DAI@!W~3nU+Ll@y3xMAwYU-J}5t4BGLNv$Eihb4% zR8$}F9Q+5@3oTKQSUC7}|GVVVq{6&xzS}t8xj^FjmyxHN4S*K3rq3m2;viSd0KC^R z?wzJ0TixfZh5k@>mqt{_VvMowLSyA;JQ80c;O5kzGzeyT%-09ast*xFS{5Q0eW0fEq{OMt`*XM$ezTk?Okx3 z_!)4<^7j>U2)!wG+baL#F=|I%0+fIfOuf;w@Z71ACBN;QwZzO{+s_~M+;blygRb(^ zD++DYZ__R+s$6>V{A9_hy-+qs)$k`1UbM6@u3)X&vgJ5Z<54%G>C9c8s-FF+dKdIomYA*$y;`K1V1HCg3I(*UnFSD<_E6@ z&ty-cP47x|2G+~SkGkFa_+)qS{7w@)(Jn5mQE)7OwUH zUHpCs*aO^xg68o(Nxl$SuIQ3`(gU&iKv&UfucnDobUk8&IR`%9E8>!U*|xQft42cI z*hvjHOqbHV8Xi=+1nYdMqBI|v5$P^%(cAs1^!Vb5Lhz1_s{Lczj0cymSz>?w!>zQDDhpSKXl$n z0H)1_?c9o??wWhH7Tojw;<1w7s0Ny&JF*i$3yjhV>o$npUe=I15Yhw`(0fZXe#`Gf z@s$2K+J{yjAKAKA)_@e)u#sJiyaBbqVPxS(`^ zT=w1&u!@makky@nV!zH$>pzWkYEIc+9@$~LmR@1u{(FaGM;i)=-^;_p)&E2{MDPiJ zRix2EL;Oe78ZvM*Y}G}&)4d{hUMsF!-w*X>i4&#?(vsQw5k=qDA76*r)+Unn^T)f> z_BBw1P$P|LBJ+RzswVsSeI_geD&Z2q>fL+)qx|9@+;UsBea0^wF8z5kVnnI8pwYt4 zZyzI}ext2Hlxk}HEBFGelPLfK-DR)&FCU~Hb_C*E^~SEX<=J1Tc`NP{^<~_Z!_(_% zFUEGP^E>C@_akt2><1Jn6aVkV|Nr-wZp?=g;N^S1Pnjz1 z6fK1;meZSc=$$+WF5>{m*b@yw?i$@vq%;xM3XfD=uSw_q$rAkyf>u^?(&k^Sm$4LV zZqFgj^GAweMC~+CP=4$T$s-ihT_F2|0-YWYv9abSh=i^|?ca&F`e2KY0#lSvLkbE! z*(t~x#7z&>A9-=zy`EG82!Is$N0I=rdye}A{YgIzAjf`##hu^R4gafi@;_^VHZwTQ zSrRY%{?%9h&)rlz365Z07uV}E|i22f?~eM0BO|HIvT$5Z|P|HBc*F&apP(6lm=b!?Kd zvNsV?nZ>d9EFmQ;+1VVj9V=u+Mz*Y^jAO5mbv<5vug~{$`+TpruHSXte%C+OKiw2L zj@R?~cs?HY^^8vLDA&AF3RHu?O3KZKHXEqQ<6x)H?8Oda3Bwh?0iO0pzh}G;gqPcc zvFcq@;rPh12{2k_9VQ$%m3Z?T7DB4%xHl&9HVr`5NWobCnhBtu+<%0YEA`YSSj z&0qMi`q%l3jRfW_VIFdrJI5L?!E5}^he2buPXama{p^ZQK?aaR7grR);BA4oXG@h? zKMV4`d5ty)ggPWZ&ZNc55);aqdeH7yrh{)&{1}sc;1-5Ye4u7VL=67DT6aZ*>4mPv zcfhaq3}Rno{XTrT|28yR`YQ{itjPPpmHdDEgV_FfDU0yhT=A_)18oRXbSF6P|LX@K zrx)agZd~B;210T`wnOU=H1$TdL>shZk!e+6zo~Qdi2~ob1eSD5HSCJD@q?P zXu^O+%gv z|0@;a&kv(0FmfHi7?yWnmBzacaZmhsobYM`AN}T49(F42fDKaQ2K(dc{#lnJe|>f- zWTq8Oh@oH{S}m(J_cBRh>gXr1A5PVjAhO{P0dKkp3xJk2j|QI+%tJfJJ374Pew5cx z@G70#V0F$5&1BueyI3FaDiW>m_=i^VlFa{l09?=d0D$&MO@v9{KT1h|+5yy2ueK2{ z15h+%-#3uFhSU6(+B=H?esh2glE&M*h|zsbWfLN8=q3SQmiYEx?2T=qOa>kb<1xfS z>;$0>_3!~5EXb04glhp3L)0F8aXa%ip4oW)rrV#>zZVd5#A}J_4 zv7A+~LGQ#_0nqYdoN<3scDxW!b`krz0iGQ|-NpfnB+)X!Xq*;$V!CDp?o&h)SJ$U! z!{G93?u=Q?{YdnX%R>279pKid3}KX8T5e(t1dAd+M^UHLpUehCYFWghp>KyJZg_&o zfg0@cE>jQEH_4Y%v13HF1819y&%tuv1irBTj`%M1VITIKe5uOIqAqJByzPP}pV~Tj zJ4D8T1`HlUf;onv5YdFZfM_E`u3ARl@42(NOqJVBAG~TZKDNK-_-CghEbbACv((XA zqp-D>K>8$mq4D&_1k^Q}NRUnhQ9dMCAe)T#+?~Day}Sn{hZuXN-x$s*3fN{OLzab# zJ7aPYRRU1c=#;=Sw*+u@AhPk!@osebky6!7e@Uqa$lKtdo&VyQ3!lj%@IZ`^H__WE z81v{ymu7(V3f<`*=>q3VJ!qNF#e=Na>F$&2&k<17?ulqk=02I=bfy1XI6MXVp?MGtx)i8x3Dc6F5Po>=DlXa1*(WlT$70X-Es;srT;tMhEz~)mLm2T=1E;Kq&j2xNy@C{!<>e z=BCwqWNJYUOe9z4eiP%y0>M#w<$`=-L{&#($luUX>i;NEn&#%}Yf7WV9_j`G-qo%2C+z4s@C8C&^X;dszjAXPtckdz(? zAc42{yonEz78;hmz$)B$)pR>7_|O?}ZGR&%PP8f=;SZ3NqcJ9xx=TGSM99s`p>4@P zsO$F_%uH`y4P87W&Ek8UmEfIRaXWhUqY-V=mwUxOBlQ};F~|r8d#RK&kxfZTJWo7Q z3}HqAFu13+r?G>@%u#O3x1{s215vhT7_0}Yh zwq_Pdjj_C7vFeEjh)}i8b8j_4?s)(R)dbtg_IIYlen9(s}txf6vIZp zuy>(M9}85Hv9eTGYEa@;rp0!S$!~(O*t)8zk$>FoC0@GJgS2A`(2*4g{F24mamxZyUvH1KS`|<9KJpr zhp>?xrx%fWUdn78AJqLq3c2!GN;xMSU`4TWNC`%UacEdclvJDeNBJNB&dI;gk7gPg zsPVOZv;Z@l$0>y_Bh3AS*2JHNV(7<@1?7W!f> zXIIeymUk0mQie0oHZG6!W5t! zy2JinQR*UVj%?x_)cY3(7KIwDU^($4>gMSpjSBVj+s=UhDCqEL8$g(QvaOaU-d%c% zfua)#qM3^xG9=+9TTnGp9`ZBEI2}Fa)47GLqVnLV-^2b}v)*SI{4@8rYxbYV9VX?Y zN=|-$uVh+m3pDJf=GFDHy)5mx+mD)(woyHhk9!I|VEgHFCQ6Chrqxu|sg%!x?W8sb z6EALXGixmfp+B8$xqnWs_yZx?N7sj-J>hWKnt?ltRf1d}00|q)V700-=Ebo}Z>$*9 z-a|yr>XS1Vn)UWh$&h`CFUR=JU{%}bd>%VmE^?!Do4_I9=`RnZrdVfUhX#3GX?{FL zSJF1zx+BvxrcQs1xzmkS+mKMgQQI&r4Chur$>3e+Z7TI$zk*2MBTH^L1@8*^luK&+$Itim4;zL_(5}pF6^dA=vN15L26sxLC?z-umM6h~7M$0HZ zZl^IZi?n%V?#E7n3G=Sz_?su~JDT4d)qZWY6uuF9TF$9gOy1o0-SK$S=xNAbXqj=m zoodl&cYXUjF|MEn_%j);?1sX`uH}PmY7(m_p?j*t2Fj)!(B}QYAQUtS2wxNFs-5_e zC~Z=HzWL_Tv-8KLHq8d|jo-I2G8gu^M;@XgNVJsjX?G!Fp8nDl+DJ*uAX!PUHT|dv|JW z(GO1+nJ9gt9hV|h%amT{DExe~KV9Cmr2cvmdO@CW=V1lW2+5(7)SqelA53>9El(g~ ztpG9Ekh3(4CJRRiUHpEMPPIYU)%qDJ|NErs>7AT*=bE&#Kw{jJ8nN3o?h0&R7ViT1 zRV3O&D}WTa9-zLujzE#nlvH!)U7G@HETNa>Quxv`Akp_qJA2+ot~-%RyjL2vAG?(J zHYkeyc&BA>OUELS%Hs!c&Ks}#iI(@-(<(L;n{c*kIe1J6qdy^y36=jDAuavF@k)@h z5~HgppD(|fZ*CL$>{i(&$1WoqDztTy{K{PG>090p4b?yB$9rZiG`BC0C4>0Z6=X$>|_(v534d$a%+siL zudVZC5he0RZ$w`3(#|1i%?0Mbe~Gg89gNDH$6MGn?I|kZ`2VhDf8m|)MTSk)FV9{q zloRc;NHq{?1ZnVrxR;w!tps!f`xOstgYr)?x2bd7i4wsYl(?Gwj<=4>%;risfle;e zt45lEf34`6bDJjvQie?5w}8C?kz{=Ptd&bx&{ivG^P!w7{^G@0sa59}zkKn9|7x zeYMDp<(o;ZUy8@8dfY~U=R?PJK(rabyt+ND*||GOccn_ox+F`qd1_Xl1oS9IG4UmB zxbetR&B-_LUC_QY{btrMClp2nbVv1VikAg1ETehm3)M5C7D?S#-`-*P^!VFbwJRe< z6m>Khiiu?*hFOwhky(($_+IIo zCD-tvyJ(=b?+H?iWl z&4tauM7S2b*fkLGRomX)#_E?D10C8%=S57o)2h<4|Y#i zuW-16aEF#c!MwCXo`fVu_483b@zvT+5b>dpbAdef(u;`4&4Tg`#UKn*W1~nZ7(=>e zxpKx<8t;cb-I>!&@}<3&%fX5r8irDm8%mSqPh`Hm{pOr?dxlLR-C*+b8hx58nxOwl z1cma+g3HrysuG~7caAwS-bbB=y}n_`LC=`vVyIkO(;g?>@60Lz+p>6vp$A%KpQ+#| z>bl8|lN-Vt`qhuNIHKRtbw(V>cfHYv;Lq^z3h9H|)<2`n7Rt2#qMwWEROu7hx5t`8 z+9*%_OADZh3hP|Y1v8AlV%NjS(85$az^2&l%vG2%a=R%ClHL$CAqkvyc%u6x!>_Zz zERx%q8*0>pgkVYQ4jwvQONXYjhMDwIsTwqD1{+9VXaTb*p)aJ;u+D}5B&Cha0`a^M zf;D<5K6sj_Rt=`|p_7f^?H2}{<3}TdOwNo?FL@-UEnpqiN*uB%KmR)3-K;Yv!W_d^7ghO`8S~|5^|!r@v@&ruN8Nb#nL)KS+}8bH zW1jm`12IvLf*FKMezfvUiy+~qw1(#%Lp$#W*hpdfWmq<6q(83{ePXTa0Y=wQnzAZi z304b*P{t$AqkQ0zHR55gg*dTQC$`TRKa;IC^&D6<51yvZ9!L`@hyg?w-Z3hAu$>P; zvo<9ry3vaqzo6sQ6lnxO)^U2{GF2G?b#zuLTVEz;1*haYeygt#(gaxItUWH<$?MXo zL|?WMH8lgz-F0KgE9R;ww;sXKp!;%h_^kKr)5!Esk{*c)y)U2(O9e^M`5A<*B646Q zEY9>b&BO>Q;jXCyu;rR`;jY6LWb2gpEx!W8JC#fQ%UK6tIbT;@{@2Q|1f94vL}0Ux zVz-#s0|qI(?Ca^Tncf;!DmK0y=?<)O9cbS)2lgSv^dw1;IXi@(^vKHgHRc3B{%+ih z!jYWp7-$Ow2ysZ1tiBt}m?RJ+IdUVr?>v({OO*TmM$LZ6_7DIab;w9NZ!GZj3DWKv zk*6n9v5rUgEEw4EQvjjZP;BojM6MIK-&;7SF zq--T%s>%<6rO4x8m6wLti|Y9FU?L>ss(SF?=V90<&gRn)I{f2IfFCgEn%%IAaX0TQ+4l16(Tmx-eu?k+Z`ga83qRraXSF{8A?;rm3CJXh}Wyq z{v!HtM(77a&kbO74?t1j6W7@Zd@_hsGam_m1P>2%#a2v9YFX1+G4uIy06=JEoyy+fkZX-gP(pH^a+k+F#u^fbK=r*h4Pe|F4( zr7FmdcEl-$y(xrF%N%RE1)0gBkh(60ZFx>a!Z?`?;xJqTXZ7ZHe}i>U#426sZ!8m| zx~%Y&As*@I%e1(^6^HsXrG7An9`%Hd})=R|6p9(DG(ZJOTJJ9Ylg z+6iIy;CKBl&zP~ZnXbn%GO8wuC@KB~V{mtXIZH}8nsZj9yPTFzRivJDB~2(%Ke0?c ziqk*J?Z@GohhxyaEW)b%fcey?YmrMMe&JmV#i*8@5^Nr;&tsCsl+A{qaYOJDj-~My z-go-FD>}+;82d8^9V6b87l35g(kFXy<8Sas^cQ{q<%*Oz!Y2-E_zPy9@&|SAAC=wJQ1=V|%&GFofHl8jFfFBbR z!Cd|OZ~&7rdhRS2vIn8mq^s6O&H$+xPuE_7ecby682AaxqRW*1Q29AuE zL-a56aRt}q23mHjlJ*V7Ghv`N-%Wp%L;2nEg*nl98{+D7zbzs3`VnCPl)1YDP-xh` z_FY55D0&PkySzJ}A?Q!&^JRr?kYyb9*2DueLWw}gsfz0BqLP+USc=@a)#prHTshIk z0cY@*p;2O=!8GZg$h$$gp$y46%>|UJou95G=&yy5%603wK}_T^S}BtE3(5UAXKscz&R&c1m>J8FDhIQ)VTifuB0AHitf2z ztR2{J?`RyjiJg)B19oSREicPdCHr1To(J}#o^_p~G3{_JKU3?<{);MMg3?C|`}_Ns z{jQ%r|N7~Xa+38gXXIXzXDUC`Jj14b{*y>V%#nxR zJgdZN7IpWF9bFfTJA_>03hzv9Rddo#%@z0m&S{z|>_d+&Vru#-ZiipyH)$l_r>Bvl z6LzrFwR_X;H3#^s8JKA9lrI`d@W)}_3{r<(%~*fcXSzFfv)0S;_F5S?bFIv!hiN6!e0fyE%zA%ikO79bWcLUDYkJHQq2HK3ssO+yz^3YH{9M z%hwbHgNm{II;)dy^8k-Ff9l+|TIFTR=D}Al^g<#;j!9E!`B}#$`S8n%*G5WdE`L@` zr3#C?c0Y*E>g#p;4V5FN>z2w|llEBv#`AmZIC-iKI>i~TCkH@2+q=TpPOF|lgO1wa zKFHNKNbF)CvFLexUE3wzak{g1SI)B^VQ15u_M@Yitb?6`dkf<>|d0;sFb8s$&!_wy{kAXto|VT<;8 z*bqdsD!vabg95W)UKd4k*0w>&Sw73%-|Kshhz?n={7EWL|lMNT2*0ku$;W4N%B=-G1RBH2r zbS%5xh+BcKWbxY+sQOnZ8FYLJ2EkfV8_A*bD%>Eg*ovRXRIk+93aao@lU|y_nc1(! z*)ux`CDTv9TTND0vIY3@up{ak(>Bl|I*@YSU7%F*vd#(hllARX1lr3GY>W#rwg8I8 z;?!J5)Qa1{w>A$5%Nkf72z27KaFWwT8^&=NXczowI=(yo1&}iaaJ9tmC9&2S(+8B< zT6yu^c@36%lpXM)Lyde7h3-feO_6%)wdUIreRLnbH#|2eGxQ!bHP*>x$c=)!QtoA) zpNwk0x#g$~!@!7R00rIT>bs#NQM|ci{HZH6K1fb&(Uo#4bjefIzS zH}5$b9q4SF8anW{->CM|+n;6sS=h`NByXl4D3 zsqbSq2~CD5%)DRk%FotZv$i*TW~iSd5U#P;aY;V%Iw}t z#LV_>jc>td)7ulL7gwl}Y3T7X7Vt7RkInI;{fdVB4-~=jWy6zBN51LG_~SBDHtmzw zY#J?NrMRsud8_>79bp!jb%FX&l$?Z19{S^M=IR#DK?}!&8COhCc02XX&aFi9AD-2p zr_p>49@ro+Z7|URPxQ}MvDgw|On0Dv84*O=PaCDkzMy1KR(D+lqq4^l1*<0s;SAJYW$7>c`Y%?bI^ReTk z*BlHPRCaqrrcLF=iS2dJn~oS8uzXB4ibAT@<(hnWnQ%{oQ)ymvU^vWyI%u43Za4Y) z{mqcGTSKhx^75;-BG@!mgk=ExoZ*Kj-|3!KA*n*r%tn%hjWkT9((jX}T3aE?TPgIN zgLcgfQUYFkS`vRmB3JCw?E~j~h&Q|rQ!dpf%pAEzW3PVbOLkqCq~=I;l~T6xgZ0^d zN8^VPxMWvPGN%sywhFC6^N!G&Ifjx&1kb}x2RQDxV<#^&L0dAW>yM(@aliOqTQ2Qz z0n7p^WZJGB;v;t>IStP8rW;#aZZVe}c)vw|&~sv{AR=it>v!Wm`_EhRzcyc@1TiEP z7&CfoCeiuU-K*tv{d6P}4i}@TAyDUZT)q=ekI%q**HT&<6AXeD;48JY#ub4GT>tt^ zcN4Z|&!wgtD^5BM$W-m9DUyV; z4g3w%s1aqFa~e<8HKGX%bZPOwPix*0S@y%s4SX3>FgOCbV2=GMqbPYy=nlZfbq+DV zrev6z=;q?HLSLhT10rzfBf^qX<`SA*j4TGYqA@=02~W5lqCVj5+UjO#5k43(Fm&!_ zcK?JEXJ;NIFQG}$2J0ksE^Q&M2SEHuL(U{LpeUAKl4bU`8XXEE5t6Jw>6a#^@2#TOGiLOjI2vYZ0Mhl zKRDn_UmPMBoQom5>GQAC?w`Jty3DICRV`f!Ga(3J9P^+7KryIE9yRSPwt}&AtqG0_ ztvBc*{|H=1CRv;oJVN-Xqj6VV_`!bfJr5;_lUuLK1)~-y5aGiZZ=B3S9qE-r4~A+U zM--fzyh5{MnQW&=dmR2eKfo36j*ga{iQbHEie@>9vA8eR1NpU9s_+zN-X^r)W@aUB zu2eP3bK6?k>sYRJAU+41m%*Vtecc(^eVdz5xrC49*1)gQ|Lez&+a5JV&nS; z3X?`ZcB;4>pWmoCD67Ar`PoUpEZlE-{RwW1wf~a(-WyGtt(Tp3uOa9cEGFCs$H9X8 zR*=rWu%VWw@E&4BFOTTKtcui1on5GD3uSn*oSJYS3(f&W;kd15o?AEEB>3?)zSqu# zX=vG2X@AVNze{;S{2B5LwLL5kd_rL|ghZx=53Zd?{X>iM-;Y(flTcvPDFt*OJrvSO zYX0KA-kcgV_7a*VYT7MiAFtbt4kJeX*Cv|j@CWT`k>8 zK>2ufZ-zd``#8gpb7fe|n6x=dcmYs@p9#K%wR{$R3izz{axin`u+sma0j`E%5N5@Z z+)EL-HMY(4^@yCCq4W=t<9GkDF{&9aR$$h4mey2W6Bj^pV+V$Y;mgmYegotc0d4B1 z9v$^wtbs7n?oQ{bF>urTRufd+XJG+`~OwiX~R%7DM z`N3nYzk*4(u7qo70)|4Q+>ncCS`4zJ({WAKg9Qy^O5c8Z+$(KcK-)8N-mH9s*P$jF~7n+KOw z8KD=AW`2JuR7{=K*>LmEsh1n;e(Tg9FSQrLQuSKOz^2MP)NpzkI`DE=A3U56whTCk zJ>7U0NJiG&A~XJIUQ5i7Nx*UkHG^CdV$CZmi}(xn+2L>~X$+y;77xs=1=(k-kn4#1 zdczF{(-b(W)d&V@*fq7m=41)I{K5`ROJ9}F$Ok)JSX@ugr%GfGI;dH+;h-j-?fCN7 z&MN1m^7JRNs0T(Ue|kuJVr`11AkZNepeayhfOro`c1(ytQ(R{AH|SyA$Vdr&Lco~! zU7BNbkw#7>qj&a*W3Pr*j1=#3s?h=n(!P5D;s3C7(P&EEX1nfWm^;j(^U2RSSMER@ z#vMsKbcMKeDT!bEFa3#WiWQ?c4J_fFxa!AQ5+fkjpnYDL4QwFPk-T5Fy_6yo-Mtpq~D-VFtF{a z2!NY?ECD&{e?_?r`@muR=18e;2O06u9pU++=*9aM5}LDa<8}VGr*t-6>lQzX!F|ty z@Fp9*3Wwa-Rimp0xE|s}QQ?snMU+ME1&DZU?v*^}vbYDNw;4oDD`+fTI{d~C^IB8O zNJIOO!H^%Zsc&2l&0H^i_Jzk;Z}==C;~qDj*}J^FfvF;qw16P+JH_$g5dud>W<|Dd z5Dc>HQ?}fIMprwRaS`1`hAQ${E0wlp&oY;^ZmQq-$DSNH_)#}ul&LMVQ~z6Uz{E~0 zw!dR1ywZGO_dP2~mc)as7U;`;>|wOs2pq&=Ec#FIpI*{|%8YdFY0IbBH9r$S?73|_ z(HOGein7kAFv{wDi#wSmA4izKoNDa=TIvmHebf&)imd|w9Lq_WPky$<;QBLvBp-T( zJHb|#uBvT5TIq~EoKp7~Z+({BtxJ+0b5sYjqAq(UkNShEfVzKnrBVTkCNp*dLcZqe z+)?t*1oM`Z&1}?ZhcdKKU$f~l(Ls+GGVKzzU?y{nV=eZmR7%A)Qr{ba8t+&Z0OB=^ zY?YJ%MqRDITO)^|i}@XGp=MylM@dZYJASi@M8ZIMf?b@j04K{bm(zuL=Nh_kl5pg? z+-sKcW9&g*mTpdW3=(K`DMvRjZS1B4$OPJ}J!=JR=`YYe;@-n@F-$Y}UpQ9#8w841 z2N={h(3naAUCRa<$s<_%-qjMfLKH zy!Y8LlNwbG|uSQtKo-y3oyF_lPl8J14L<${eN z@^MPM8nx}EE|Y8@XED~j#WZu%vD4AeF2F%uZd}C1d^XPrps@tyl zCJq3njyV5FO?El;&CP1?J_DSX7 z@h}Z;dFE3X^qO2Pn%G}1g6*f&C8XW48o~9t?|{0nA~D_PDJs}G_0WqwA>cL)9z0l^ z{$eehM;(c<2H`F&$KU0{N}6$47#1=^DqU|PWHec$UclYb0{-39l&U0h1n3A3L@^kR zEk`A>l2GSZYI6xy9ZDf#dqj>3W&Mzv?~vbfU!6deIE?0odcHCSFhyOMN_IknQCD3p z&_lsj6yH#H_i8W*^uE-V#1OAhqcj44!T>TvY`(s2gg~ncXB9M238fFd)Rlg5K*_N! zv5Ncupx#^cc{J+Llf*wD$yc_&L(-g;eLw$ju}>#zl-(;G`wCU-Ow)@~>r|`#_3bgW zSN9vFjhq-T+uMdN6nC28{`4mg=tr|yiKj|i)y*t5Gc+Gl|!E`)J=lR(oQ z+hISZ)aPyB?QY<>Y~YBw>dI_U#Ua%nPs`Tp(L3l4ap?|FE2m7qN|*Lxuv;TAM!RNu z38bHGh3Y6(!+0vJmlC9$bB4;tIjY_!LOHSC!zff$euEANv%#B3eGzz{{#-~x6b_a) zw(~diP2Db!&xHo@@dlT_xCTy~WixyI7mRIXV>2$5aCOYRYR29%N%Sql!v(lJqPszf z?&kpE^(YgCbn9Uz>8x|E<@Sf#qAxl)^8q&!+v_Q!B_P_vKQt(23#Y417Lv1 z;|;Lvj!3uQ#MVA{w^H`B@qMXun!@H+Pjbb?l*ZL%pyZE1w@n>Q!7h4ut$@@&EG5IP zU8spz#kV*84x>2rTYU5kk?Fd7$lZWt?`_j<&8bnaBk4es_UfGBtoFvbx?OTuDNaBu zSGSi~Zv7g8M!{<9+L$ChIj030f{mTZ_8K&HR)+o=TX%;KOCRg@fi>)@5*)<#C39yE zT1iOpV|h)8FUnd7HH5^i(M9c;X}<#I;HeOK1D0L}RpT?5T8&b1;)$MOrSVc|)4DJP zWRd8TS%;HxZLG(0Y+u%0LCU|hz}F@KV2Y%V7Tq|vq87#L|5QDMPJo|SxbnCOH2sfu zP>TvN*BUS{)zj7d>1m?X1O$m4dU{nxPGdaqr!zR63|T)T5fKgC_q$zgZxDvCWlS^N zHLd}mvkPNkSnXC$X3VOeiw#CaIU8G9r?pK9l<&*dS-9LwC_A{&!S6_GDR(JY90EQ79jAUCtfp)@&$xZhLM#E zJnZ`Twdmmlnl~*AY9D?RRm*ld9gAC0&d?v{!C*B7$Ff=aA#MS+%gU6&cZJtKoCc*a ztr3?;vqBb0m?-M{%bx2{=Q_Y?fqFn^>DvOXy$sj?9v=3fkQoZyYzlhGd9P(?%l%6kid13 z&t@0iT7OdTWSrgtt@WFuXJ(u;Ews6wKNu|dNonx0d&Cnr^ziCO$Jo9q83x08wh^zK zUxgmKF0q1-liQ+s>M^JL&^_zf7LrprvyvSjfl&M)O11u$oZY{N#z-^W#2J~eh+p@z z>I3>&<;2C32`KRFLUtElIxXqNEQLLWcdqGdLx&5_np{pGHePLD&W8={67c=86DVeD)H{^4FBW1{>NW$G1~$lHw0$onUV(s`AKc@ zqI6t;E9C#~P?*?}!ryS6o8)g_&$LYhFdiP)xCb^5Yg<5YiV?xv_K}vSe|ziy{X-@; zlL9~TM6I3l!hgKI|MARb$e^#O2VcsMYULy;Vk9FoS3Og8X3^{F-=@a@ewjnwB=Bx- zdbM!=?aRI6WQ^d5*Q{``(t{!(oJz@n9ss+FV`TS)$p6~g2}8l#c}LZh|JT>qIjLP} z77_;m)JUEHP8yN)0AC#SvwvKO@^28!zkf&hzJ~~OP7(k0izPBXK)~fZhyn}XRMCZl z)d~g@&g=5b|NcII`-qrXLZXDJN9gijU**5?pTB)8c%Bkiqz!%(%60z#<_rJVz9F?A z;EF!VQ_=rpsrm+r~hlO{@>N%pI=V-H~?m3QgJ5#d*160UD)i{na%V6 zdme-&!by@~LZAI_d9Ps>fZvp-O+5eSU&a5^hyDMHMMr(Y8%!tNdwbh9jwJ#k_Tk9D zF7xAaiclMfi26ax^K;P+SlbeCJ>Ib6{srvtnG=ZR(V{#3j^j2OW?{=uuP&V#wDDN@ z0g&G;X7y%S-m=8p9f?T5>^&Dr%zau#__n~wwiYN47Z^Ze8xB=F6H zUa0^$qfZcv?Z~c$ecJ{YG@C}&4^Nx!G)3gn-~q_zeE^*A`?gpCJ$R{HxQ|9eZ?)*` z*0qBcnS?Ry5xr>h7w`XCt4Wx`ei9l>CUY=)^ijOlf1=*@~i;KlN<;&FuWYES2O3|&z~n;`Svraz){2jN6Kb)rJSOfQ#=0y!fC=X zc-SJzs=fkG9qC-{#GR_oupK{j5j8?U_Yq3LeMxGJH^{_r65}vCTB3AL1+aZKR_@U1 z_yLB`hTRNWMX(qNk4S0b27SQ|}Yw!762h#~y7a`pI z<5`)j;FV>!pZef+!1?K&d=bthmNx#WzY8i}e)u&%G!HTSg>XqweF?}U>zki|ZbZx- zM;2^3RC3kK6JqfKGuem0jp8WS4y^J+_up%u&d0=Au)yMto3%_4rz0%*LTBd(r2djJ zmp~`)1f&}0L$t2hqS4_C?4ON0-x31zIrMvDaj_cspc&+EUwAP9 zcFXx~B-500GcKbgg54a*8aqbTTf$afi{2_x45hOswpW?IeH<{PEBRxxEjE2ikze}X z%lkh+Vj)3r@}zd21AaAsnjP=+oQP*v5B8K5FoM+|VTC;+qvc%lY=0=Bxt*ht9m(i} z$S87QtvG;nQa%m7`L5Boa4DnRsa~23h<0TXeul*6+si^)u>o zg7_G|KX1`NPJ+L%B<8DL%FPfA@ZB4Cojnj04X(W z4q*Fx$ig*$)G~1At;GMyq%M^1xHqpHw6_cH!io2*ov=Jg)7|J*H z70v@MdlQ6Y83R#-+yU7x-v9Q9=}@tSIpDZ-rw_kYC+5V9+drJf8|L z{82`?uvxDhT+<^)5Qw}OvO$mZf@%Dc#g}A%PfApO3D};sranf!B0G-%G>31#oyb-w zYi2`2UHJjr%jO8JdYG9>Z)x>}xKFBl6mANq1rMx4MQLG5M1Ix0YIgA!X88{cLqOU* z`9fIsAW_B2c^H_uTn>gh|EyT1CPGxRA;kVWK(hZJoP#ESl2r`J8WI-x9z9k9!^q&g zIZ$-PP=Y^GLdwZ&6E%|WuwRNmVbW#gSW8SBEmcUY0yR5ZF`B#9>~pj+JfI>Fl$2At zU6Om9UvR(mE8x*KAVkN4LZOBF)ol$Zr-cxaT&9Tc%{E8CJzzoadJck&-Uzfd!H6&c zxh!1|y5L-3b*(EP=dTYG126k#_F>2TLf}-+s;^N}%4es5S2u%mu@oF0J+N)3e$m{| zm;yC<@u%=BLvU6gWcx3Gt==@I*|s9w3nHXg&GMXjcTI?Kxk*%2$y0Y%0J7#@f5^SN4a76n}nP>72_KQsU-2o{k2`#gd}rz^eT&S2^!EVCDFFa{xF-FGuxh+*9chW_r&mQUCaf|ZXLsYY@~VGl zRoqmK2weyMaw`_xT3Vx5ZdKi^+w3!x^DuSEa13-3P!) z?p>Co!q_8X*%5QxF%g)#7Myde7jb#58eFx4;GG&S#KYm-^8W4s?X@laZoaJIpAqq& zAjShD4wGPyb>(tn{&-o(I^3#fEInP~G8nkf`ixDje;w+n`32cf`@l|K48Xh#H5hj> z$V2%BYqVm^9q^fvDn6C_D;^m&&qqD?-5sMxt6cS<4i0<5McA+~4e~W+W&2&wv+3|+ zX|$<+y^xr4AK<7b17>ca2emd~FQ7G8JrOJY_o5O_*2}V)DWRIbax%;cFaXBB=G&XM zydyvkSZ@440X50;F+3sF=r$Pr_49di*wiz=`FLd#Ccp)4>%QkvVJuW3lFjc0tYH=v2sb%us+1+u6O_5fou-U z_|@Fl{4QO!#8Qwi7{}rg?_8d$7fzhiiVKGeR&~^FvFJQJhsbc~1Z@);&mFU-V+_-{ zb;o-EdZ;mEJ{IY)VF`<2jqZml;XT#-d5bv_LX$RfolOTcF_(2%K2U3-IFPGcI7Qy( zQ15B5$ZJ5~MZ3`Lo(6A)wf;UzmHp|J3Q#Vs2Hy+8i`YOr2oJ&ibR1bf>-8)ny{wis zH`CweUiW+DEX07v(6P2$J(cMfMC}{9j7tqXCt33$@Gqr_l-ERs%r;Qq^4P+1ZLw@u zIx;rhXB!TWI#p9Jjz;a7z>Az-Br>l41yfpcO#Mj7)-}wCY2u zp;O{4fA6X?vttNQcsG;!C2(}6zsnKHlEU47U4hY6J!T94T<}1eAhs8By8Xv>?ws{MrCDgp$XfmA*^s>ZhkqsTR4hFA4+1{S?J8{q#{5iGG&>)x88{E1^ zl^W`YmpCi)^Ab}wQ#6_=3og;PS08xnj>S{Rs;ZoQG86HZnyoEQwNw!!21ukLikK}w zoAWIqy<+6OhtE6%NK-$|{VjQ^UtsKrN4+VE>rf z?(ysq$aBEuk>21JbzLb$##kEjNR8yC_ibWP2vl6C(=d$Y0&M}rSjC_xX9NvD<-$d% znpx_s{g0ImRxA0Eta`?k4fND7PlNA?*;`_sY1|UnL#wCX_Q(84^YlqQlqD4pukd`! zotr7U7-^1Tv5$#=siO$kzol*Un%92F67vL}Q$LK4E0r&mGR81dZI(6t?L8#H^|Lh< zv1xG#N6*he_P9VoEz~|MK(t=9+!Nyp197sWa6p+pk~KGeX>)spxVE=QbF^RwS-;7=_Q53bwg`{wNF8QPow4I;Yy2=bMx)Xy5`f z?J1mQ)kj8sVJ#ALIc*Fj3&&%h^+2PxV$fBnh@57bUZ#WY+i z^YiGv>y-WyG{F@hU){A@7bV70ONDS@sMWosQ@L||j8HPL*Bh`yiFL+?tUK?l5E0tG zBg&%+B4$WQshf3+9=zO-scS}AX36Jh;ZJSDU{==t1Qo$jRBBv*WaIH=!U7cTL3<^o zFHnp2-qVQDv{8Bj!mTpMm|T;RkMu)U(6TxZN*5losov&#+`elBUWN?k;2WpcJK_XU2Rt3jBmEdRgJUQT_M8pm1Rj}! zLgtmK zy2WtQm*LU+lS5TROe)}8K();}=S=ydFIvpu5}YnoAbkqv>bl$pzyJGHT@{gjRZu-l zge;O^ZHxPylDkAedpWj{qTbP!fwjN{_3o-8_l=ahZa2TYFb}s+JH$n;m-_D+e(9*K z$xbd~d_<1kgNWNnwfA>y7|Z9GvaPeg zSFjS8yx@d?6{W;lNky)b(fy6VarkAs)@o%4p*AEDE^VYN_~6gJ$?-9`Rvc32iYjc> z;v!gsNGjf6Y;<_BeBj1sC>)XTe=F}F~PY3s4az9vP zaR#7d*)!6dRgh~<0GP@P;L zv92BbyP}C5CnJ19P+3_;?)lr+uL*P(b@;4@1uX!#t9#G7lVOy$@r0;~<@`W{z?BVd zo1u(&3*s|jA$VM$=#6o;2rR*fEWmmX@#;C0eV^EZwv$3>$hBReiY5aCcfT$vgX;Z4 z%;@UH!QU|B#oMLaALJ|eWU+ri&G=P^z;>5(^8rz)?D&o;KV>eke=B36) zm8rpzbq0(v`4JlPwl_3X=stcF{SoPCB>haGv}@CwT_i;!qMuJCVTz9_TR9Qu&bF4V znl2e>&f%e#w(ztXI&(gJ!4u z>n*+-{F}_~$ssm~U zrZm*OqC5k=JS|&K@#o&HDheX953NQIsHZ}^Kcs4xG}0-h9Qlw1MiW^qHO#*}T+%m-`a#3O)McddFz-2ei?hFgQ8Zc0~@*mQLj*T*Z%W!JgOq9cP5 z?^*UC(AmwQEfWEe1#6TK)*qP=t->vLkB7C*_kKJ`famQ)1(>kyFZ#dI{t`?~VMAV) z`Gv_28=zBdB)VN6Mw7OR?#k?*hUA44zaj{?^lNE}iPmj23b<|D1am$2_dNPbO%Eps z*u?Wa==`v+%}nL5=#$!RVQ8*~Nn0b-&E%#YMLa<@w?W;qyuFRj&Qo>ZSf|Vpnjd(d zA|47_4;=s#SFgXA`5fref#1Uu=hL`p*m7yGYG2~T;CjTNs`3)!D}xfoz$&H zJD8DqMgpkXY?Qda`=+3b9$95PzgwW1eiu{t>k*tTeUKs7S;{XKGdkz*uth-&^U%6lJ^Q^EK=AcJ5g&sK9ChdbBw=!)& zrfmqWEbAoZCHc08hsQbcRkkH+@<+}SPmjHSM|D=G#4-k+W~+F_CiW?4E}zt1&nx@} z1CY2YT%II#M^wxy7UniIQ#H5~7RrQ3s~Q41z)frpNGmCW=fDx;RYdjr_4bvxAB$!H zR`5uU0P7kx*k*i_-u8H zANKwCb3YW#&;&aE{WMGZH6B&ly69SaoBd^D7Yv6Om`-+z--Tu^R<4F_>(tujU3ik! z022UzKc5R=#@2i0ml6e;F;6 z0CD0mWnohTQzqsd%%ZL>ocOa%knm}VXxTlp(2T?*c4{hO{U|o3*o6M#1#yT9m%q)} zyQ_SZ;)rQ)n`Xc34(7Oc8Q=pA_IH$uJOH_zeDq!TfKFSY7NNYgJwp$~DgH2kOP++l zNrci1bz#)j+0vos-d7X2sex$SK|(`(?aJAD@UbZxsL-qpls!&iytRJh-GXzhfQ^Ir zWwOl1!0zvd4WB6~nbn59l)44cnh`ZKK{V`h0GO?NRzpLKm~)bp@C&r$Q9t2ukoXC> z*lcJvOT%B6fQ3RZx&70s*8KBPxolsE8Ok0Rn{Hf>aBLG=izjH0Y<*sHxq<=7WGMh16@W0oowMRCfucAhj|^ z?wU{E7N^bEv}8i3F2;BNiPJFp_zqEvzEv5x4xqDpy=BAjbD@A!#^I*=WPmwfoVgzXM)Jt8N&;XTHR|siGQ*GsmT z$4|`L(4zGbgdAp&#jq9VUb3KznLx4DU^cFce}H6vk3J=f6he+#P@oI_b|za{4IK2b zjp0w5wBKzBWiqblQWBNfkm-RGZn0Aezw%(@Ya(n*)5iV3943&l z;#P{1%i4U{W}XD=o=;WAgb;x{(dgA8%tECaDh9Zo0r;Zzr9f#>E|;FdSC6GHPk6m- z9IXVS^2L2hi(nh;23(x6MSE`)tYIcfeoVLwoWN)6-a@uG+vJlq#R5ZvfLa%T$E?EhAkd}=k@c~!(=a%*`)Ue*mK$CbD%k>GqCvX0C@Y^JOv*wo(Jm70>2BU7(AdX_)swZb)*athWO4Vn$5qr{d zQ)tU`#P8a#QR9})N(Hf~69SN}5`ZQs*LY5{rI~pZgJis=Cpsk{oO+BURF}& zp7m?<@E}|c88J$hW0D)mix>)WSW(^ zkzbDa3pPwyQ`UxWiO`5Sa`2-6fu0uN7hE86h`3}A`7ia_H{?qdaR=fg9Ss`yLdTi? zJG?bSoRCSKq1hFD)i|i3Cdi68Zoog}ym@~P**Yo0F1Q5iGMDD@3)>Cr%$*IPaz477 z^yIEUr#&2}SJT}|hKTDGvAti)zPWG*u{uHsO7_w$c$I7@l8kx8Yi+XR3~oOlby}Qb zT^>QWMW~}L!4lNaXOIAzK0^fKq;JiavHgN*nDt7$r$b()*FN!&LEj};r`PLel?DDoR_q?6F_$4BwX1E ztd@T!^vZEBxi2h;(Skoo$dH!fASOo&a>~4JfM>ij0Gc0*; zIvAOT>3RF|Dnu}W8xi7dSiQ_pRTUAp6W4C+Ms5=iK(a<8l58C|kq_-qM~1$TeWTX7M6(*119Duudv-iqhP zMcuU!%gge}1vWZc77`2ESAe7sxryG^dQ@Uj;WP1qwMNIz823nD9_SZxXg=lMB(z_1 zPz*~ant_~DRZBCQT>6_kMUdO^OXu*Z6L2WKd1Tl8+y5W6`U~Z{m8%4P-1X%|!N?33 zpHaPX&vB=|(km{y_*?8*y?{WpEjq*%L)@!7lGE$8r1f5fDK!_7+m1oj`<(Ra78v8V zk{D@*5GzyyRP43Q-8gUk=uLG^p?C17x-8}_FTU#i!>zNL-F z$b~r{NRbjqv#C*hj$|-^X@7M0kx!mTD|kH%cBYS1idM|%fV(uSSEI86yPKuld1&ZZ zvPp6x|Mrq#N<*AmgJ3|X4vtIT`)%f*uZY3$PQObbLnmo9N44o|DgaF?$wb0GYD=wC zU0!kCHH<;mE5O`7ddsmU7moJu>=;`3SacD!DxeD{H6SAd$)0m z7Ba^mI*pB*mwptmVkltmpnzScU0wK<^G?U9|nY-5ZyJZ^p(G2{BTy~&B83UAN zBhNIVnZa`TK)%2j6dyZKxzEhc!{}xLW6FuTZN;(^V z4>acIE2CnkZ#&$%9;X(v8TQ39bryAJ!d%x4SzDh1Zo4TYnI*%J4uS=zs!($6GQ}%H z&cT8KU8=0eRo=9o~dj6rRh|Sw?wD@TyxjD-oFneK=t@>Pcu^_XVLg zYE?-`E;Mujeelq&1TrKl8N15?%L|mtS+e|wNk*r=V0mVcWn_(3JD3Tfcy0LNkl}}L zrvS#i0Jrc6{^?tSopV~X2k6YygE^Ozm7H>QUGGm{0fTKXU=i!s2m>Rd;-n9FG2Rm7Dr)$krSx9O->d2-RYPesDXo+gPG7-O;4x12RCBIrf$2 zjl*dv{_M_{`rZCBZ{`3{B95)kzS`;uwvOf26I))4NlPO%1LB=U8d7kvPL_#ux`j)h zl?a3`I#Ek^^Mfu>G84t_l?oyiBF`B!C_OWft4h*%=M-# zQ_~2j%MsaB%)kPGD;=nv9S^7D^QYc}Kwo-wZovQIaN~`vfETvF%Vp=TUo@59XK}5R zb)W^{&;#+>ICNO^O>sVSLEUKT$s+qV`y4?M)8DOYKKHcR0YbBpETG=q&|8VfJcyb`289ifYY;zNG{uC|AR$D};xp!#S;$3N)bCf`;Be;mz&*CNSSG4+`2! zLNlT0ic#E($0EzWrx}1}6hR~RAD?sp$DHn?aafRg7Ry7w-<5K1yW$$pF6%Hbb^BjL zQbkq?0>d_d%8HwF7flc~<9ECJUFJoL0dU(2TPhCE3*&jIi8^~7a*`hRKgk;ITX&{t z6|_J`;DkQk2iBO!Gp%S}b1**#oKb5ksZIQx_yTHyXS&iTyb19h{fJ)1RL(-MT42fQ z)7-J66{m~Vw~y=YCP7Z+i$XS?2gPt2RwDeJOTo#+MueM^Bu%7Qj3EB_5@hev-e(}+ zGgk_P{(EA2Et^cWNB=yQ%=h&z$cG5splkY|VBqZr3pd1LN!y(lzkE_}K|NS8Z6O0e zq&Oh+A(ZlJXdi#4rE9O1-4*$1*j#aBKF=ckJ?+egd3meqHRT{8q~#z|&Nc;)N$p5| z3yT}r6<@^MW!ARbE{vy8x5;Ur;&5%edEr0BgWgv#O6l-E;;%R}Bu$!4#yE`NH(6wC zpNEvKM^P7E6#ufMFCGHsG`>cb`yZd7`>6IscOWG;ZfyU(5GK|YJM>Z^JU;`)^nE)m z(UOAg31TsZaBWgqyE1fBC|;!4n7Pa~(agt%@LM?!U?F#I`)<|anaJS2I)+4Cp;&i( zyu>+pA__YPjHfM~H2MH*2XPt&9ne%^x_qFHn)5<9iX|@AUJY=8vIoM3A{P&7I^qEk%~Nbo~t7q=+;z zTR2CSuh?g+gJBHv&^P=~>y;35+gW!24W7heZW(mBz$w~MV5iwx z^Coj;c?serX%9uGW1~=n-uLMpk(7DTiFiZw-giJ3i8Ss!W7Qw0g5|{BS3hnGRD67Qae8<%xBojARfzalt(!p2 zT8@hsn96X}Vw|35&+(|F>{*YHWI!k68Rl5f6d+^MixVd2G}a0qrbbXvz4TBcNL=^@ardc<&DzSC=S(nFU$O85X1X^>mR; zF;eXUGTrYoXnr+|=>v1T-iDs?z!bE$utc^-fzTaC#HLxb9TgHVJw{NU#f^M z6Z!W_CSHLzy9mO!%3G4rGDFXgAe6&;TjY5(J9$O%w%c+#BhTX6hX)-M776ch${qc= zqaIVuudueJznG-f1V06zP*d!l{$DGl5gxQYI7s<2`s2qUb~jb_d-@6Itff(LAw^K9 zDc~cO{aj^;c?B;jKaUPObo5z&Xp&b;(Y^!-v-JF9^1F=Q1QC*x6Ylui?Kic8&*48j z#X>BAdN2*4wb!$8j|A{skWt^e4gWYKf-aRlDEx$EbrYjyAfT3b0=3wlr%x?%H0-2_ zq=AvUmJULMQ#Ri$Q zG#0S=iVB=0yX2xj3Z5nVMqqC^$fujSyVC60*u4!m2q7|*7>i`ISsYl8nnjH$ECOa( zOJT~hJ{yBDXXlGSlAXcI$xq+J`NHqy)h!g*a`P>s7OO~zVt#{;ag4zAZ+fWQ0XpgK z0g7&yXCX5;%B$2`s+xdEL;Y3CBN$-ADD$cw&WqagkUk>y$#sC8DK7cw(?k*g zgRrt`$cwr0^)cZ?9uPv(3(C}c6Q>7qkf{LrdVAI5h&OnA>l!i~AWa0h&T)R}y$?Z2 z_uNB8ucRlFOc5F=ZGVsthpF5(%}}mrP;tUKvrC;7+UEYzqLvd12Bpr>lU%i)uF52b zaoThpW3bYNNUnLz`LBdXi&GJ4txsMqL7G$QvB0LXkmrxc+hD{71MsOz1ghu{la_K zea|7Lpc?^_KtG^zDNCdnW8t01TFEDD{u-*N+sflGP=c4Mb5ypu3+bk=@y-=4An!ui z;rdk#e11Ra$M1p1b4;llAP1W{ZrWhJ50X$yy1^PRb9C8EcqGV)eZITTtg}Wka&*c1 zK9i$-Z2RIefEYCEU6ydbgI5AKeO~bwXPeS>#M8Lp9_=4n zT^bh$)#b6DG+}|0*OQ^w zk)eDoMy5qAN1G5$_D7XUD43Uvw3XP zqBGcjD{POuCst?9Wkj#7H=CEo$5bqNqSEe5}3DiqjU}n-LnW2|bQ7uJKSuTE6h>c}n19l&| zic}PcPZpk_yzRee(&i&FI(epIM0vm%{fik)iTD4MlCUQD(2kve2CxQ@gh`YpZE#BQ zFvFV&k(l8+zj$Q->hyD`S+_>g7Ka}l{pX@pAEX4y-3Wo+QQ_+aYFexHbBKG0cRP#* zM-%H6{t5Sj?7^K}!2T zc9g~XkN-1p2}E#jCdp1dk^HA7Gf0VT9q31$5l#5LgQ`8it2+af)?8E4&Cawg3Cv$y zsUl1N+!DaO0q@1d$v&|o|M;1L4{b$WcpiX+i_gD6Gic={pz0T8J^fUiuX`LI=nAh3*G5zW> z{2>M7HAO1jYc(;pfBBtX3;|_Z@o|^UlT81`9HEmTa^;FBA)J(Q7^Q9 zp%eJ`kN@L~z@Hj7)aRrB{*wRK&;1{M1pNRmwX&r7rXBx}pW*L+cTmtF$N$%l@b|wd zK?}KNdTlSP{^yz4cegLJSt2tuuuzu+vuL@(C=LtXoR2AxtmhfQGfy2k4G} zg!Np-5X)MwehVY&0@QiLw@2Jo!yH{Ojf?}BP`+~b}P=uH7&4jrqs$h{}B zzznvF=_Z}hSpUB3TqPPwx<`DNtB)9+IVE7K;%r3={Kb80b^8q=UgTna_l-3m8h-?7 z8v37quMoO)Dp~fUs$vtLMs!DM5ouYQ*kj9 z@4gi!C8=fHrC0pw}->2>tH=7qVj?v7mRXKHbrOG0acbAjxT!tZ{} z$jf2gD$u~x4c&lof2BVG%hYYZ1G(@BTJAE8+7>Afu<}^w76sS3JwTb^Cf~_F-hLtH zpC60=`LB3ocuEo<@vZ+KyZu%;zGCNRbN!c)H5IgPJjl{yfEbIOPCk-nPgl}rt6x9K z3TJlJCR_^=4(r@k`eytoFLOR1#RUMCln#Qc;+ZET8(vsB*}ea#YqgCPEJ`&h4-bv* zxlkR%1c*h;jk}M_XHrbC`&(&;j5BC57H!^wg%g0xqkU^AMVT#-O zc_r)~ZpQY+H)9`Mp;bR#1RfTQH_PhiS+MC^KM zjN_g6oB0VyKqaC9TUqp85{A6(a(-^;!8{>g(gb39`(%kEs9@c2O7-zkc0*O2Tv>u? zB_HO>n&mBFAbivP9t-zP=vvlz;SL18Zg!>Nz94?i>CQ?C!|!&^p^3GW{`z!Q=PXgBu;^FfrQ#Ps5W6vLG#tQ`%*$uVT9XlB@jo>4cz^i3ipIy^(>BFQsvcnf%`q!(snpKArhaZu{5z}Z<*7EwCaM)@4G6Mdkl(4t%UqOQ65ub)W zj+v1crY%~_{dF`3Ckbjnw(;Y=%d2l@0>ivT4{$;f!cx^G!M}dw@7^egB|Hw*ORACC z=I6Q^T)&Qehyt1$^GLodl3vDnI6Ko>C9hKvQ77V@+gk&Uzy~23=$Gq5^}iBo3qZtQ z4RyDdT|{S%*ms!%a|yEHx{G*D(Qu6_lK^T!Z*{4Ebqvg@Dvp74tO?{Nw3X`rVI7~G z0{j7XCBwSICD?wTJfE46S{u}JIUl|LGkZEv@?_TjVhESRZ;aB18Q83p1bVNH(yz`b z8PvV$@d0FJd0Mlu4RVC3e|ij&Z~!@{dr{!3>n!MK0tV~TOT=P)t!4;5SQio&fw%)l z`UH0#gTXS&hN!~y83_ae#ZQ!5H2Rz1ScWs`?afj1I@#MNmpFv<#BdpE96b}gB{?uT zwD_N@F+mX_GO^x_sm?YPcLgGLV}=y<4?`}4NZH5V<`vIs7`W|`_bEi!TO?`~ldp%Y z_Va`SQ0E5;8OC@YjjWeo zlh|KQ^jB30R>$0Y>#kIzm%~0}Xk~OAJ<6AfsCe!eGeq=9{n-6FD%yQzPmsnT{8a+e zpg)4GJhCm4I(_Pg-_pzy1F--x-_skHkf3AMxtE5=`wNcbDRi;?b=FijAJ*!E=W6pZ z54oyN9}t*mWFefO<@#dx7GArs|2d=o`>&De2wQbYYA5SozYl)ER_{Hcsxv9u^Os?XRFX*QN;D?^0(QhlJnrMM=ToEyaq#c8Cwu~=Bl+6{yFB%_G?7TJg}}%hk}u*QAvh}HLY~O`7B5wXSRFaX zK6G0#2phkCZ2(%lLD~pvTEULPCeN?kq+Tcl(;+!LF~l01X2ok1e25UG4Ax(eMFu)< z`dY$#nf@(3A`iWpevJLY=7-IbAh-445gQbSa5IXSgR|hKU5CbX9gp(}%xdO7mU5=|7D?a4wp`__ck_jcHD z{m!%}6(S{HBbY->_Q0M{gVkprtOU)-N|%##s`H?+65n&_umd5(H;Xc0@9fQ_>zwX; z9jnRDP~hyd1N5~Im%^~9H)fpTf>6065n!KrWwZl@Py3w*u@v{gw6Y# zi!{G$@#!$hDVkH5tL(6&4NNN!lP&t`$4J8*-t&|3Zqyd~)@&6_aO6JX{Nzpx%WY9`+T!PoA4 zJY0df7T6-7mSvOH8Kp9*i_WCWs~>0B2N_E1v??4FUKY_d^dM{*xEHoEQej><4mVM4 zLkk_3JwIiS89_oB@Lo6ty5Dpv*KZ>gCsJiO)Mhy*cr!a&p~O#6GKD>|-+HE>$g#lq zh;V+OUXcaoh;&Z{I0n}9gwB?mRCztq@0v7TlovJn(a2aawhG(=E@GFz0;qy0a%T}9 zYxKGX`_He$-@ujl!{E-zy}O3-v!*ln$p(RI1~3|2Ta&D;Kz~}&rXh!7=nd=QqV>IW zQCWIu0};q1zr-((zl8*gU;Dz|p}X}gLDygFtUDObUg9<*U^k&{Y`Ta zUBd+WXx{hyzPLx@t%;$mGmARB+UDFG`P0V*QB(=9e19~HEiRZCVv1%J+6fB3mTN)L z%2qsbo@ygXJurNBZa!iXv;O;z8DuTTjw;w@Yi4wqyI!|cm&VucJ$T2;EMLo%kEz>? z&@#%FYq14AvY0!9WH(?nlZKO-{m{p~7#&S0njU0ExF#x~j0+Cq6>t*^LFLRJ&~+In zvXtwE2*RMzxySg(Set=Gg1bM}5(ac!0jj1SPqRgBV!u!^N=m#xeCt1Ph{Qi9T^Q7gvJlmGU|VN zQaXP_mFEPwLFVHUrZscc?%{0KR5Iwz7@tpV?g8&`VMZodbP?GA(`iEz zqjVVoh@P$xt;m7&+bPwL-OIx-&qYo~tcA0b0GfnXhbN15~_;b;q~+0b9~z z9l8t&xeRLNFy-_07E4sh?27m6!zJs6Qv&)&=I;mWIpqjDktZH4yv=LPYb)C&QgP8| zX5{xN3(wKiXl$4*$1+bU7iyvNyoa9*uPNwBFB{t(MsBz>*?-!m4R=)E(y`LYQ+2hTaSU(g&xD2Uf}X`FH#?)BvGHd zCMHBFL*@8>ls9{X?kKaO`3NQ(3GTrA`dyMoCms~WOWlQppF0#sKGu36-W1nZ3MYwO zLifG?-b%gHWo`S0Xsn>nu}A8HeZ=O3%A?uL*63lPFb=zkMVaHB&RJ12G_&RtnK$w& zY@ul8(`z3NeAZN0Okpkf%6ZH?mo?_JFn6SWsW!$g0=8qoBogZp#lfi;+358_@4dKj zT{|pRqHiTdlvlDpWsBcFusJeQWVimj;REatiIK4~_u!n8l;N;DWiV4~9;6$S*Xxaf zJ6&0tNAj^@U>Yaz>4Q$U1d)-%w!Jx=?0zoT$P#VN|s|}Ce_Na&@qkjMc~^w1Lm45 zv~1l6A;W0FFyUS}h@R1xtHY8xzEJV4l&eblI^KHH2R3-s!OprS>XmvhCJu+c3;TA8 zM*j#MY*z}C{df+=lrbM#TOowIWgz`tjpCGswLp7jhPs!wTkG#N#%w&7FQb9Gxq z%wC0D1qLEa(0)`niVctUB|S^SHjwg1OEK@rKqB{E+qk{&1T?kfjQW@?8=@s2=fiud zrKZFHgJ`8a%DP^L_>F@?eUiH79vqF~1~R;v!=Q_`ft(OEIULL$A>wqE%vMv0bq}FS z9k_%a)x#=!#Np+9PD=w-5qEZjh@)IlMdb$w*E<&97Ceh2P0frBUKcPMmMbKho@SD) z;A4Mc(51;^RUn8xX2#Z0+8*r>!h0|7?^wGpEt zAE?t|yM63){Ycf9;ZxPn_hpKZzI!an(8XbEmtd**Ed&PNILHyODXg7JknO`A#g;X1 z$1TqCn9ceX!{UW2&xX^n?~qvW>_87+SPSWnf+{nBn_4yWs zg@g?EEK%HHgZHu~-LPJzg^7jxy@mUz1?Ic)u7jZ}y&s94;l42C2hY%jr@wFdi5aPG zyyd1e2O$9}rJrLe_s9<3J}N{0QKtU(PwbBobU4}W#n1mWQkV(nqc?0|iEa`UV>d+4 z;n&6igI5GSs*I7^ULkzHU&i(%iWFS-Yc!Y()p+*#AB0-;JToGX1Y_l6%9V?6gZKB9 zop??1wWE*=MvEmmZ|U+s1ArsN>?98d^``cNL)Wq<;s+w~zvzyLlOdz~3et9kTJQ0n z`CT7Q80$QHB?EJoqRpdp#Lxib^4^_EQx^&|&zmV3)TrPBX9+6QJVSzS+k=P-ZuaW7 zJ*fBWyJt8s@MbS^dvVuVpxGHu8t3|MnHtVqCHM|lnepWefRBYjZt+>JF9Qsc+-6st zTAfil`PDSl-3F4pxzsV6>*rvOVK3H1H1|hvWwWUha)?jH=p@10Z`c|)G)q%$YvS^6 zf>)b*HQTC06n~hiEoFYHrA?2i`|0kxYIjc%!Gz-Z`o7?HkGiIhl4B*tla}-~*>698 zF^~E}(d68-xt>VbrR3p)dH`Sc&3kK965RRsPEvb~_-p}#r6YouDqUbn<+mD6&;9 z{<6n38Df>X;GG<)C4Jo#Pxf$6Ma1fRDQ_AMH>0tJhkhZM<}$ z2yqTG`6T~HgA|j<;hC>xw7!U>b7wY_NFGd9 zICcFqN|wm}d1V%5c``X3wko=vV4rJykshNbk)9Q<$+3>jP=>c09CbZ_@^EtrM3^9} zKiap+m|X#MG>siat+jrqHYbYZ6XA``oR)Pl<=1#(4-q2{Vrq5nAh(P?aKINbmSVAN zOSe4vBYNjTd;(yS6o;xr2wYj*n5bP9VXrg?n8(*qzyeKD?D8v#F1398167NP`pH%4Fp)m zT+3PRg6X`pGe~8U$7jo{;v}YS+d84{zBgPOkfy2wUPUMAXNOB5+#wT;Fk)fNk_7iR z4bX$pVsYF2DQ{oQ0}7+MNV(Dbs@AXN792@GTI;St=C6mSRe^!?XX10-BE2qcI2(#< z3O8}l51D21iW4P zx+xVwPt>Ig-+0rqgv>I&?>UVJc$v2OutC>SiVT!}e47D;%3Io?e^( zMk_KTm@;xC>TR(@tp8@nN7ySC`-*!&95e<6NHAoWkU`c6<@$jFR+gRA3+@o7116)g zYgEwLxf~WUx6fb`j=7ILEo7fIAwaU-Jpj+-Ytm~cGZ?sA3vz5RJ}*(W)WgMq1=esQ zQl*h~oF$uI#oc9v{?;#|*MNrwSL6q%M`$8l4X!PhJo5KobcfWzK zJ1Y!={z^KuZwN4u-h-RHDU3VC=GD{$9-E0X^wZfoX{LnXnEMvt3KEYmDHSI~K*j1F zaWo=aerB%PHl8Lzo~H%RR;Gvd%vwB9KLu@x2(I9cFi$w5-QDR4`aWaCIW9tUH(|0P z=)w_BW>iS}kuy)^26!##%v+&qlOI5OV15Mc&ElX1=86=4F^;3e`PdJGO77^onLu;@ zxz5$RXNXj-2bQdjDlDA}B_f#cXuFSY>JtFH7bdwltw^w;Tgf+hfuqHFQpPT`hB*a}OYRw=E8u&hvT z;AxsRN))VA0yAO8KZYPL{}}-JsK?9wwxQ)#`>D_1JlsOm z;@3qT@XwgG1|_wP;kM1yP{q)v1-FhcpuCnC4NQgvcKQ`BRw51CyLQ!ITob9hYeGARurC*K0;QkX1>2x8m~Ebb^{-;a2m`wEV`MxZ-GcX^5N}^ z_DWq368xJ;Ju)V|Ub}u%y?x+^^%=qp062C?9~zy01IRVODS3eYT|_v4&w$v^NTYi ze$ml9JxPennlJ0@1dp#H02(u=pUqyihLLCDia$|1at^|C#b`T4+TJ!bdYss;KeJSz zHf;5e8gt-v|C0vJ9<%mmc0x)x7>U4Qm(m&CcNQntMD+NaD3UV6!FGf$j<>^Yvofpr z{E`d7!K{qTln{eRF%a-|>Wnx`Pz4|j_0G)Z8;hF*5g#)#k}TA7%J42;PK=~Ggpk_w z9b6(f>28r zr|rVG-h0rz>kg||StEl2r3sO?x6}BmQblAC1d9l5G&y6b4A*02<*<~*90!94HUX;*P()U5Rz zDC+OZRSvl5zR~!2N}iV?F7?URpzq4y)xY4EVD?gagW{CIkhZqP*K%^a^z+VS;+-dbH>^|9Re@ z3&7tXpo<89uBo)+N0$Z?r6$ey&1gSZGiD7nG`!+g5KCKKuXxUyB1wf3e9D{RQWLw{0YO3RewAe1#jqDr1$gf8M@BE z^b%PC`vn}$%Z0S$D3uz~K+nq3an(Ow@~s_7`h@ztk*LM%2|^0ulru#rE68a^QU+lE zYvE6Io!uq+9;+)!aptRc)W}l5;*K(-^z~mMumBt2qmvYdNSkAGCls12WNol)MZSp? zXC&3}9FO;)N-tMHi#C9Paek-zlfjVh0--V80^fKnS{{PGangp|U+^JM1&hFxN9}P9OrhNnw3u_8_`*0*RXx*=Y#C!q68PTh2%%&RD(fZ8T+X*yRmd z!_Ab|!k2_r-2}36&f6LC3*fGO;n=L1`Rx9dEF`lUHU%=Sv3`!qRPl{)a@{hZ{-gdTZZ;o{7S8(7VDg^YLc1<6YV7rgcc>gLg zKUef0BQjbCu;AkkM=(FX{Z2cW;U)ztvvjD1W?kW0g@~jcIIy>GiWRdC$tbro6TF?O z^)LrO63i8$NaDm@A(VwbOJ8Xj)wvk_W;J5CWWX(4`p)OI2#uVcc#v{J|B8nvSU5s_U*W3yI^7kLKaVCp!JI{BxW!(rd7`2s<^ z6o&0$qYh_=hv6m`*^=n{%Ha^rGT6R3IdeLl5_QpZAfnJGdl^b#o^FO}Bn7qD15s|c z#?4+B9V?k{yYD#+Qg@x@0ox?Vlf!gyLi&P-svzydNECNcr|zKTU$6J>w0m;xfk_vGBRJnv;d$wzdN>%)fuMoL*lEGOnxz4sI z9tGouUE}nRSEmef<6W!jYE{Q-K|!{C>&#d>BP<26i^8HXQeS~DX5hLzugT-kpoN#x6DOclq8(y0CMj|P{Z29 zN;&KNDRb|4_9H@7d+Vn9@Bkp-iS)C{Rr>r-TthOrE>XS$i`RE`u)Isa)}N7GvOfIz z_xoH&SlfLp5QI6g&8(IbE2-G&Dq?d#Y_nSmJjFMRa}wrj1>hX02kK7UQ7fadTfjW z>;tYjhQQK-TjR-~)pCXhm+kt2Ki~Uh=**G4?iz-6A`J|dFMD>(1R>y{HKe3G=%SiI z@+h%ct+JL7H&dwx1N3{@JDcOTWbi41foXelPWC}w;kzL|Ew|)dH~mm_)RzTSx@$$Y z8wOmye$;Ei41`7jV(~6oU{ff$J-7esvNjUh4>q%!e0bj>hTP?=#<>U46GfakEyq?~ zYJvSg9Oe0pV@2a&TTA^Lo=z_wNEgi>MG{1w@7jB0!{5K_e?A()n-GQeh8JQ#*9P#O zQ)D!Q^P!V$cb*Am**$_ypns_KNG1ECkCDm~M0SADKaW8fP{r^)1npUAy;fo!aAEx8 zPmooE$O?38wfvwl5DxuDxq15!`o?nt$wTmmVnEhM zE?j2cN&zL(O?#z>xDAcrfeIlXMDhWUNGz8)>@m`bq=?`Z0X@vPj;RrovGY?(&TSsK zj`1*&_4-};u((lhUf4%FTR9pCQ}oNa@6S=1+*a%aJVxef|u7kqc;{ul+6YBruMFGixgC(7|o z4AARI(X{FeXA1l%S7%ps{nI`$Ani|zcCyhB@b7+2ykckx=sB-%*%SAftOqS#sdlW3 z2a)SCUice9g|FW^)g%vFPd|E3C4Sdz_wWCLZCL3dMvL|jSzCU7YNc*gBby8$j$l(q zs>mMt-0viIWxca!k4rvK_D7>g1s0`AiACTXHHJWrD2+^|euxovL{!#-T_1%ZqMRU) ztO()t%M28rf>y9B#of`DnytN8%#yNGk8m7KYTsJ|UKkhbc(TYQ{WHq?AlN{50Oe)A zb=%ITwm~f(%$?Un;@@oi=nDMMddy{^L!fJlcV@qRs1X3SW7i4P#VgQIoqHCGz5yb} zdIUcy$)r^4(_}c_B4hxy6qxc1wuEABChAj?}D*zxHggE>55jag|zfkYIB0T&&*j$1?!GOx%=-PJ0erXQQMiPj$t-DV_vbk zq;tc_{5l+8N(R$~umA!-smn9yy2gAk3MU>Nd`J&r<$PDwIJ!C%7%y4S_k<6OsZK5p z!aV9duKA(gCkLoMFng7&3)z z;kD}Cu*}nhOUz0smk#i*E-hD(S~&(VcFpEAk7@o@!nHl|O zmlnP!In|0FA~I71dCQL|H=bM_irJXRhqB`+)t^^4Kd^Hm>30x1F0#9@dhGyPG{sl# zIN23(>#+Mxo2$(}nL}KKD4#jLp3QR z0x^!gYVHKQV|>U!K$yE-g?dgpHe8k}&)3JHy@c7UlsWhcbnUc@mzLOFfD#tT_pvx` zk29P}R7J7c!S)Wy1_SG3mT12@h`6wB0L~mH=Qe^EU2D5STC@DTnb%k?L38;FI@GbM zmghDY_Bq#)3S`AQvy2C^M4?=|YMtgVfnrbc*h_BShC=z57~@$XA@)b2?U+3Jx#F8?9>2rN)x+mv=_Fyu-6%kcgGgyuodl#GU)#K*T^6){71zy*`M&{<(i z;FOGKwiUv~>7P-hBKle7_yG}LU`{x5w8lZ9|0q`;x+?Ky?J3P*T^!2{hSwp1*^%z_ z+k}dV))|%F?B?HvvMm|Ze)Qq%CwxXb(pbemB?LiFPx`1|>|~4?Y4fXGO4}1fUOFp< zao=GJOC?kYrj!v$Gs*@SgS~LW_iN7&U_s2S&f~#xV3Q#Xx_4Tri%;lXkjfk$Ui8jY zKV7Q^->3?*du9^0(_e;qS8ldl*Zlo4ef~zZ7EOF7PJ9x&zDKz?ur_pVoi*~`Oj;A* zP@s`1bkZGzH?UO%^JF%4+)zL#$GoWk%$>Yjv){*4l7w2bsuM-W%S9p$lnfc#pN?!u z4@zsEohmz^n{7G#SUGWJS#_8?)?J`}{NgGUhZ>x=cj=7JbfUI=96jj@k1ndxpT%4; zjJeiLtHh4SxBtQ%vZx)8^T+f86Y7`T88%c;z0%r;o)KQy9T5NKvwo}jz&V`NY!TQ@ z<|`#&>D;Od2Qk}7@ztkH#vt>v>5)U z6FXex;oEcJ#;MaL76Vo=_6nZNjHsl%366+)*S0L1%5`kS>oMiLaP^q#UdWmLbYC}Q zcI1hc-Dqx@avhqFAzN|Lqu_>Fm55H+Wj4^w$?_Zhux;@MGJoaPD|7o~bMvZQpkp2C>3e|rKNoIaF+be{GanW(p3qJaI{Oc~2|Z>Hui zY8<4vWT$zIzO8u%7}2?fZ%z z^HQB*R$RJX*vqL?0dGFFcYlUt6Ibg5k5qBGaz?ciNG`1O7L;F&aKm1Y=+Ro`{_*`( zEc*@J=rgFkcG?k4YPe!f+0f%_8Hlp!T7oqn!yow6Y>+aN8RyLepQl`?Hog1X_5sUPkNmzV!;+o5fna< z(E!1r)0u7A%(vgHx$5m(IEhv(2KBN-N7ktFj8Mh=Vnls_A0XCu47&;e_ZL}sOtK}C zE3rfQZQ@#jStJ`wwiypg_L<3PdOp`?b%rd>j~B3N8y``_H70}v_D6Rzp`4ek$(^*~ zmR6tv$PH_+=zJ^?+^5ONp7&XfDE)X(RYyY+rW9RXMb1N8L=#wta7WkU-Sh|R?n>iQ zZyA8WXdL_tY`YCGy{>0wrWT+fVRrznUB2v7yHCSUt&IPwKfzidz?_FJl<#iXO zu6%f&#ozAtHQ;>HV@Ve_|GUYnb#^*mZ@&Qm*D9UzhJMkh@(6ggr!yzNk;Yr?lxb@G zWRDY1ro6O3$>kN_UHbqji?aa`&o*(Hdc*O| zVORrn1s!J!(#&gug)K;QH0y}aCQ@f;?If}ad(e$1l8P;?@}Z3uB}Y`E?OyxC8ansH zm!JxGge@n{yi0J`PMsQr8J&=;2#M+rHK5Y(h1qX3qKY}kM^uN`u+EsFbSnOC*CgVK}aj;xgctd*j=|LaExM- z`3%7O&ZTUMM?Baj$-b_~^(A;Sr`333sSg&RDaQ3Cvo>=q=#|)9r5^)+GW@7df2VA6 zZayVEGwPv*XwM$wg{$qGrOm$j6Jz&{NRm5?m7B3~K9+L_b#bf#0QbGZSbgf}h9XC^dnANsMjtv)uWvNuN3@uBJ2_}8;E&3rC>yd8B|$=@*L?Qq3t zTN;aI*l^o0Z&UQErUZ!KD&$qmjEx;#Z$H2ld*Qc8>KzC0KRmQD{bqMvW*bfGO#jh^ zx5G~WIX!Ub;rHjeVf5N|jSagy?i7KXowMZXPjvQw9_gQJBY-?g!7x-EcGcngNumYi z^fweygYbB(m`SN?A`dJw7yHgtIi)fKj{!)>L`dm>VZ*kf2rW?#(`v}ZI7qGePbzFF z*c^L-_2^T-p+~vWGd1um^z(`9oASu!WMw|WS6yZ`B z6&>4rA@IKOKV=dEtPy+?@U17?enz)~lp;{IG`aTRFYu(?9*=xHsD9oDDMZ1_KxCNS zSjgi1YXGqd=U6~oRqy~8z;5|+|17PACOc zaZdN6@Avon{Z}04^LbzI_xqZ!>vdHiEicMI6x2K;1J_ovXAcVTypaYGF`Mm9iyy1s zfP+z2c7|(5h3B~>J@ql9;YaBaXCz_7p2 z(*pCK&K>t;hu{Wj5CXnMlQ}!cgPTBvLsJ)QD7p;pVFqvqU=al5i0l#6x-G)h!izOI zUYjhMVOAfiA0Y^f7nZhQCx6!yNlK;`T>^9LVCSRXeD;QpN=p^MHxXauN2?abtthklbHjjkr22w7b-Jdw9y9B zFkpGkSvE;L4{IiXpe)tfyTE{*rwt5xl*0H*&_3%z%sL36YPt}{u5=)bTu3v?J)b&r z(Pbcok~#36g|i5VAm5wO?EO1|`R|L18})obh#k}tF5^HMOui6+FOdsuEezKCE@%|z z7k!5TOym)p(AQ=HlS44>5s}c#4K0Pb-nrVNKOXTF@}nPVE)o3aIhYM%VC?Az!Hf{Z zfvE{bV%NCei~*Vj(Y`|)FvLP9p#+bsBtm7A|GMXLna!thXI&fb!FBX zcs5f;nrtOuMJelMhFcq}W<5UujoQsy+%R|px~m?5o%HRA+}Nl4U4lrev* zGyQV?2-|{M^<|EoUJa}tXmhfGgRui{IAu{J@J40A~&;}S535$@amI45~$$hW>AaeI@c=89l#aYX!4#|JJeek6n8-#FUbf8Bi z3u#XU!UO%kW{h?MGw&3C^=TN@1fSp%fQ&o>KJVGEdBpZ3b;wK(%H5-){tgacGm_wM zw48Fwg%zllj0mJVg=AgXx%M48?q60?bPH%YMjCu$cYYP_A^K02zT*uMAXRmtbv?HX zW@%23B1~>l1I#;@^`B4w`(OXqUGeYV;>nKJ3IqK20NQBoRsjCsJ}7l$2b*6C-Mx`7 zg9j8}54F$b^*`|J{y+U!^aKIYV}YLP_`+6DNhZ(%y}_wK8>L+P{_IZO@DGjzc?#^M z+mbHtFV_5HRk;T+pfj+L@z#S}oHsTSxG_}Q)710+aMoeMTQ}Z+pOnIL-nf!>?){%U zh*(|=E-vKJ_c{WjE{#U!s-U8ddfdDvtPuJ|wVE?e}f1R5QB4TT3;D=K1 zr96FTWynE>y59j_QKFd(MY|3_rw26)T=K2ws%&;98UJZ>{zpGkO$70zE|zCwf3aUb z9r%CxdeOTS-~h?{p29x+r(geXe+J$op>AH&-UhS(FKZP;ffc?hWNE^ObCWZONKOGq zDGaAQmgfc0X&yu|rtch!mS(!P*Il<8W&oD4U-r%K2f;M(++g#X6i+*nhi}I}fK;4P+mR9-O+hyu%tG`s@v860^HrT*LKnqGqlfe_mJr zEOzH#{x`L<ut@-p zBM>dvNrQ8%w7ic{LE;wi#mzJkdw#$ zKop?*)+m4$S_b0!4ev4&WQh$hXFmI1p2p|KpvVhO=(*s$&Tp8rOmm-E)0F@l-)&O{ zE&>ALJDYb{OxvAAfW8PaVptffjqvItG;T%U|9BIGlFY-%gAb;Yu3HOqp(3s>FFMS4 ze-R}7$F%+ZuYW9ygFaAwEDFt`DbV3-rU~|9=J^R5Q3Nc6sGK}^LR~A{u;ASXaN+L- zJn5>#eaDs#DMj+WPI71*^zGNe_=K|?t|Jh%k&DQ z-O*hJqIi;4j#vfA)IJnwEVj3z;gb$>XH)Vo4%D74>_G311>h}jNIHxd=Dq*^52YL!I^N?0wab{noKgVfbO8cv z8Uit^$zGs&F@*wf9zX*+p_#-0{D1VGZfhRIl|iOYKZm(6ok$$A1@kci5ek7`mvvLh zej!NnPX+5o9E|G%kLd?3i3ogb$p%mgg{~YL#T|%AKmc~BN|_Zf56TqG9^chSm_>si z?K+|ENLMuL@@RP$kXZko84dtV{{TP+!CUdc0Af$X+l3fO|H0>%;sW|GWDL+h7Nc(0 zQ-OrUvT6m;zE)WFW*~TIfhvnGwCP%pR8IiH;VlBKoSA&IXYUjYc#+~agWEfE1q^P@ z58my;4G4FyG$Ujv2y=lkfP)bdLK`8MM{b?a))DR8Y@f1VlU}lH8POFF;at(c09h5n z4`Kqo=*e`Z&T@ow0Z_5satQAY(zN6XaavOZ38l@*F&;2D zqQ_F%= z(vz3p*Tq|1t5Uu;1WYyUM9<{{2%=>Kzda6jSsOQ8kr|Ds=z`f!+#cS8cg~E$3G4QF z2Cc4dC)U=%iiB2tco;kP9Ws5iG)4%PXA0r&fxE+Jc8Bt@3-DSZnH6u^n%{5~zbJu7 zh%ynE>NZE!>h`_|+s6mKu$4R9Ivr}DSEq%izIGVRe{C0r5Xtx)!LvZ2;i3Sfg1lJ= zj0*Xhs~&!_^~}9+9twKYmAkY$tz!3j=n(k)V`ur>s57Ey_r+MUWMUT=h~?6B;y6;7 zPCb&-S3ox|B4wDonST)+)GGZ&aG>TTi7rq>O4Gc|y7o{aV0!Bc@D25LS zby)VXkGJ+_0ij9$q;S$bMOm~JD&bx%dorM4tZ79kKD9(zAlfO;q92-0f~`Y!n<3G9=t8%fsTB9+Ev_gdO%bE2=swhbWle#p40l=}8H>|N)QJLGjoZ{| zkcy}(w4IHZd*$|V;z`oIcx{hR)Pyk23~7o^lBi{VOKiUF?0boqNdFln3(EE$I>#B3 z4#%$7LUZl$ME)s8R*wR>q_g~A*6y_rMEmf6rsWVy&xkubl%$&F(iWBkIjYZN0MW5p zxNw^vCTOf1hlCK;P>NB@9|Wa3C)Y95vW!ves3w_2ZS z^-xlOv83`XwmnXx4*-C-o9tWP@pLJxSS1;! z+bgj%x%>#SNPk7+%`~Z((_3LveYJeSabo)&(diz-Tz-u1JH<0O8+^>`&1LF3+p}$o zf1p`56(yJDCgRiBWL`X5?B?hF?hmoA$@i>JJxpf}Pp-=takST975C_L#qso`S`nZiE!;kpG zSu&<1s$?hIFUgB45198|$OpnSgoU09HI6>VL1cpsWsQY725Y^>%>V;~J0d8uBppSpsnNQzifP&rEOuuPw zz57m8k_DeUE`FWq3OSefnu?_5Jfz}a)pYl#e?sr zwj_EVDjwB}j6Nw;yXo!$fTnC6pR0^Y@~4TNlf0Apo#K*!2>tAtN68O?nC)p|vq{#y zJT-LqCLD|I<}Nc2t;%rplHC>2#7K$*rI4+^XXdpmKJYQp<=!lf)jKgFy=ZpiV5gye zYYNI0)BYqMoA!pEtd!hMfr|f!l3~8L9`#%99n4)?N1{NvfQr}&*-3Q@g|>&JL4}n` z0?8vV2sf#)(x}KUprUnx;nYkFlBl11I5&y<&HmH#GvawSFzQ6_S|7G5WYviE<^bW^mRen zjo3Tk@~s}1)eY_qLf%FX8AaL_oN^1sDw*#ea z;VkCv0v-NdB=c)&DHFdHS`1V?OltNB}4 z4$UJxQx_0qcIhAc+T0K{wUYV)Kv=pzS@XSvkVvi(~0=TrM|x9j{t-Q&+uf3SC>d4j9h^1AQy^*LG1wSdPwS@CkenGxHq<`~h&F7?Fjrb2ySfpCA%{FKJa+7Jo(Nhf`^-R3lNX`ezz2{&z51~6h^B%V zPW>!+E;j$6jw5&kJ>(PDH$buva+CpR2d=bdK_-8Lb*YEMXzg*CjoGXbVBakC$%0a` z6oNU>y3G#k@)gC^x#G0i6znL&qPLp^`~b&PuTnz65OH+_dq{{rgMvz~>Gclvfhmi2 zWwbj=Q3-Wzs;rQdRdiC~+KP2}$Yws`nXwnoRcKvBXB~=M$Q1aD<8pNv5k_!l`w->l z`PWUoCkXRR#PfFX|I3^NKC$=23!Q)E|Ns6qhE0hcW`H6T(GWqXD|T4NKGK8fHtuJL zAF>QlrU4q_M;{ZUbl<(1uuSsF3YNceC2`4Epn?Ln;PDF7Lq1B=l6^YCs!)p_kZdPv zk)a}+N@5)YGwOyGt8}063r=%4wmU}=vKX#LF%bp>3@e0(SYYsZ5r8u-Cc7Y*RnG?x z32KVap{RaDWi*I|n}B5fczO`&rG(VceuR3K2K3gKxrdEm z$XLyAhl#{Y>@i_qo-3zxTWuz~A@LC&daEatqN6^>ll0_$z?U5IWC=@wrfQ^{1))jp z*Y{8bg#O2lcGo0yB(zxa8a6SkSZfe8A`?=ORR6mi7>B^=;fTw^L(gLIIGBxDH1J&A zROk1MFBYYrs6M!hnfr{G|Z36&;puMLd0?tU`cSOd~MMpP56Fm?U1<@qa zPr{yzT=y*ntfgd8uIJt?q%jR3iWj4&4Ut)maK)dY625_vJ`^Z-3(l`IZ$}%{;*=o5 zxE!KL>kLuY=tl(meV}H|BO4m?CLqkTeSM$k(b59MW&s&OP@LzcRYeu{8$t;b?VSo^ zDmlvtD*3uCZrof?cRp;(gD`$h$M{PV2lhaYUoAnt6;N0ZOW(Y?kR*|K7&Qu$@0=B6 zxzil}>Lc?+`1_z!Y}zHz6(G89qiF>r)CkRb_sf}800JmO1G{@BjB%AdP|Gr>R^ote zE*O)*V$;+Gz$<80Gq4La&8;?2r;cg=3{&HJ?9e33J%)pfvUV!zSdp#om51tTgg@5R z?daHm)`;N)V+z+&Ei(jcLzR6`)z-YkG5J5INXgGbI3hM~keQ0}!E%MO&!OOR-JW># z0}4j6m={g+B2=M+3c+6%U}SYbqIWX1(bz!g2*#LAb`(_X=>+bJS0mLiPza*1UXj;Q z#K>)?@((;d?p7YfpST4`^kB*Hj|s+Oh>0o#rRRvyCRSvDiDD^FPJ0dBI9Xx5Ue=k_ zL!U}vf>NAxI?-Jjp{19JlS%0y@;34;d1P!ZRCGF?D#!ufF+#rD(*Xto?v$;Z;z)iW z6pWD)cST4pgt)9(k2#l(*Fo zWmTmdUIaM_t399<%JXKeY4RGzBW9t7nrO_4TjG99L>=0he3kx!sb1tOWsg&}b-xrd z1tR9*+nM2bVrBp_o5Y=Y=SGUau$OqX${!J2WdVnocRCyCQ##WO(W#J)`T)R-`Lz-1 zN~qEutxa!yJ!_C0H4ROH!w~?4yx(ZZWusH8c1s3rwe%L^_Qx~XP_1n>Rcr&-ScWlK zipsz5(G-$ndVgG|cEQ1)jnkl!9zjTS%VjaEs|0avYmQTq((qo4UV3~3hIg!wGm_Em z_ppIKZ+Mz}Zq4DI0SY4@P&mBiIynjVMIjLvkL}ojDoy(Ei zYk_NbzJI{c6@gP*w|O8Fr`hjOxdO8+IYAa*kF`IbbNH_C6SL?wp}9H-oS^Fx%HKxs zkk(h==P)$_uzP(D0;f@clVS5vNr>drog9t0L?X0H?53h!FWmam^&v* z=wEsIN?g*iPq-c^xsDD+NH3ZC!Ytbk zdO_LsGsXeeKm9-y=A4G1>~=R7kfCGM8?@3Kam+yJt?cgt0$GhCX*eS#Jue_m<%mXKo$+8w-HuGwFD4E#x5e z^t4b{i*{R3;d$doXM}Y5OjzibecJ-J!#!JvU*V?Yi$z(v9M4ppYOb4dja0EJz8tr+ zS@!R&^Nw7G78h`67X{NE;oXn>+j2F&R><01d4dpMC@;v)vzJ^u3?cGgV5LW@=MrOhtw<1 zch3|NSce5*jwxDtK=MDBa=js^_nC+TnWkz(10#QmwB8ZO&2_XRQy~G8F7|O>;=ZK8 z#ER0=1w)NOU#Qf-_)$~|Umxea;&h5zS{()2XuZSvr3ZiZS_qfE570~WZC(MFSPtl% z5Kdj7du6kcKBNTbBOpN#ph~t#xth3~CWW-LsgApea zrNv6gO#H6_=}?R=?!TSbYyg#N;-OCzzl-KVsdV{U6`g*L5OEj_cS08^(J6!#A&|rt zgRsW{0HEtm5PSHSVq`8d0vj?j@gSx!0c^m*8jvy5Uk$JswE(&>2SBLtRAHsM`2zNu z4d~0bt4@hlbKu4vD>@WR+5wf0@c0SHn35D$d}K=|%l(m8&5*1d7$1Q?Pjr}d@z*3M zOti(zL~3=w%rEtPb&6>MM_?uIgf6Dje6fzg4&8LXdi+@W?MbQmS$d)ekSnmv6Dn;< zY`2|n)q!m$cFVE9N@m|l_Hkz&w7iX}@k?z)_wPl{k-@{;3euqlI?9J|eD9wfbs}b< zkNE9UFkW^QS~{Lw7hML6kqu1D`vefSnId|PYx0n9Y~5pxbTIm4JbVj~`z|CY;Mtn0 z+K%2{M1!Au-g;KPpQrmSPiyzYQ|SFxM&KbmN6>GUXk9liKLj!~76h)VMKLi#J##U{ zq-VmV5I{3ngkU40-dt3{ikW)@@BoFY2$lkxPt{Ht-fW-)v|C(#B@6m9ii$5Shqmjq zCeVEV?L1emM0#5v;5Q)u{tEljG`I630#ty@XDtFR-52*;#%Z|=V;fBp93Q4595s6M z92duqK5bo1Sh$S!GltyIG^_wEhjfJS>ear|;-_u?!Ihn2)neZP#0&$oL zP#X|gGLV2Hb?B~Q2U0GX=0y z4xq-efSmt4DNqGz09-n5X|*XAn870qSM-rdojup!YmrgNSQwzt;{cyfR0RT43P{)Y zRTV-sjBtApE&#a+-@&T0oy31PR7QLjLwY8EIL@2NurH0lOXYhH=YUe;)(!?#%|7*q zwq1ryl!7P=fwaE>l8^G-Qjz9T)r->$&FuV1+P23f{<9t#g>V3-sV5H*~?Q)__Ik z3zBOH%lRnzkRzN7sn_qIGjC$Xp-G&nKm;IMw<^v8PgV)grcMFr%blXD2yLANdjSJg z^lu~JPSb9r&}Z=1ra{q2$Oc-Wu@FD0RW(|}+2@l}RM(t%iBPyc76V2Dz&7&{89O7` zxP$7B(UY1b4sXF~)d;UkmN;yslW(EsxRs|tOI-762H0g6bOZVO$OXxxC6;1;%kVV^=%3A6Z6%NYhf1!Rn&LgzEL&`XiCn&1k!Bmh!CPe}6gBBKHft~zv zqePRJ9W9QEuZFj;5=wj&=4J~?^&6j^<*H=SWJ|HnW86{(SP}pMkFF2p<9O|FY$r5P zYYz?&mQvGc;B=b}(v}?8Z;+3Wl^20;?d}ERD#+yWc~I5E2p!FjaN~`Ws~TnImBs`AxTZSiAARQEq~g8OU~=@9JQ8ry&PO0)h7Gs zYwCxPySC5^_w*KCMWZ&Ql#4o^4>a880?L3DqZ2BL!}q#GmDM-nk4k$yoCOoAR--=I`dp?8zT|c(OZJl_JD`QBGzy zLb4BCM|B)=K8Q&bjpBrn7f^6K&R=MxO1^~*z4uoALqIoKsQTV zxd#gJ?PNkydFrfuB7Ho+Ht>@PYMX!^qL@boHH6!ARil>$0orz~P?d!|IW1wJf8r2d zw-ywbd&Wo+OryHNccf#vAyHxk>DN?LM+ZP5m!E1I8rTahq6@27UM4h^B6gn!?b~Vv z7RuuYk{h$O?}6K)&UY96+fuA-?Ddz#^+^)bz@soo@UDwj6Hs|vMD)=JJq}Vt>#0Oc z&TB<<6zYOJO)p>FQ8GzH^Uf%-FelMxr6c+snN;W>d$@1H>Fyklaujd3hmuu7P1^Nl zglLs>6o?cgdmij3rRpbmMf{*4n5#-i6Z!{ECQqjMyuJPfQ2UZs`dVWZ+a?63Cc!Yg z?acPqblZe~DaT8PyJbR}nolUs`9M3cbg5YYUM%xnW%czBNEtWW&N)H#H1zCbB8|o5 z#jTT)*x0C9@IQKrsmq{yyLpno(8VF|K@}w$cLN$WerbW2jXj`H71#_Ac*>w}?BQ+x{f{1Gow!1X{_`?$u_C#6~ zfzNDwmuTW24IE?&J7Rseb&%MFWh}ubKI`s*#VWdO+mjg;e;_5)x8{AqNZ50n1XGnLqLiXv{MoRr_Vy~p= z>DTRd_qQL%R@n(2aBfzqtdvTTNQ!OLAv0h|IXIk(fecXid&(5eA5Z9Qz5Oy*V z#4#Hg4~WTaM3><*WoOs(v!2Nqjip#7*{{2l&mW(J9RerSn7H<1K!q3a6_&=J6ykrm zI7Ly>*TW|WsmbVWwjzhW=ey-F&RE^=kwnket+R=Ms&1G<5Iv~1; zv`M&L3W2rdyLS0l`f-2&=_9RUlZ}&mgNdy;fJNR+u1T0qn2h*63;h~6qXnFHmuWx$l3GzKP&Ifs&@CU^{t48OKD4tvQ_tHsR-6wcVm$>f z(^{tU;b-Cv;bWE)xmZXR%8BA3%ow7uy3P^jKWuYl3v8(`lX5u<*VyND#Of`VsX7kp zoIN4-H+15kFRB(70xJ%tqvyqG?LX2%O++j}&${q!unG&6L^XX0bd&skakL}KPI{nI zH?}^7*ibr@w+@-H-2TuKfM0R+;f2*nta1E*p0=vJWO&#Z)VB=(I72%|E;ecuawQY| zZALUem@!S@PVALy*3$)$+ChE`m?jx7lZUwD0IVH!LvqpeITKHkolV+Of=Qf`9E}Pg zoj)0*sI>rlU`s1GoHUJ6?1L0sK7D-KNp@33Kzx`&+?@;Hxb~CF2$BWLR4m$ICdgcq zJPzu3p9ErdBoCbCXqt8J(IVi6E}>7MR@xBk5)#-#!XXzz=ypIMJwUuznE75oB+Qlg zcQcgRXX0Wb>0l!|ipw*QBtyY$X(@^sT?F!;PnLq*Rc7TZ-Nrq(kO!$Z?#_Q`Mr)~f zOA$TWT8hxA&2-o2kk3rr!DF? z#n(pYiq=btD~cW;(86&OKBv@ubE_MY&E8tddJRGQ8G>vYC>(}fpFho1{n7c)ux2}0 zSph%GCfEOvtB8}XXgM}`dS!N=?p5dO)mIYU^_Q~0V^0oSoxkYwa|E+9ZV^3$G$sx0 zEuX-#>7c@ynfIWj)HAd&q0)PViH=?%{7N`~Ox`EddlcuBm{e3$ZZKP|<)}btXXT3r z=G@sX%JuOds6#rRI$dmdv(xeTSwkEkCqgoa{{&vtMW$};W$-jXxHkQ9GYOv}%dPZm z^n~M-boF@rF1kJsb`J5ir@Nf(J)bG)y)%gZht+2kAOsiPzDKaQks!FKp5WkcJ-)Bx z_S+t1=>s_S4jOKs)tcx9%7vNgMax}We;WL@+ERlpw%v2FM^>V#gUlkG67_-9#2t1Dc!~-WH>am^RZK{t4DB8(Eq?D*C`|U z6({SCp8(_Yh;$DtksbnMtL5dLC*n7PPLdqX>~G5KE^mURe3X}kxRQg1H(WB?>!!w> z>fe3EdB30KYvO~%$5qi4y#FCy{MYwCNBTi7HY&Y`M;^m_zL|xCD6I zhtv78_ndqx!4vamuvAUe{6(CWqMzTOe1rvxlU72PO>l^_kcZeKJbAY`Jp~Zq9>Doi zQ5%BM;Lhewwh8{iq-`P}Mhb>mSny<>k$ zU#*F6sEzRj;j>SlajnQ>?uh%}bx#C=)3(@bmJ&C|^l^ z@4r0f$CH;BwM27!d;eJYr#IR0ZldZWQ$a)d701~_hql~oni&+yts5BkGprgNDtY-| zmm>N|wB#Vw^VB@PuY&))*ndAlHjhAtQJJCIV&I^!OqSv`M@7E?lEP6&5%GB+>h|Zy z|3OfH|7`;0p1oO1^NeBcySxbUs|k(%42D}LBIXZ?yQp^f=PyFXQ(32-HtGQHB@G#WUTvXrRG;Fp@)^6?sen(^-97*bn~dCzlSoM>+9vG zj>P(>C=6b=WmHc5$TPItDj4sTKbrb|0vq~^EvLS&<-xE(EK_*P?>GsT@-vy_{9Ed_ zZiea=<4HNQn?m8d z3krqlPH*XM>jhOLyF#FNzB9^Gt~X3Km3nP8c9N+;&*gB*ClL|u>My_8^W*2WL~Y&- zO-tbDrk|gP=E$)3t09poc<9GUj3ufw6VDoP6W$pw_Lk-&-4cXg{LuD($jsBfsI7eebsy~+@x!oe+#X!f4Go6`RPJ-28 z)V!T%tIz*xWoKYzXIrMl@mBUUvAmRnlThF?IdLo$?KKqvbGM$3M=4j2Y^F3&b`8Le)M$EzY;RS^R|5d|m}Bt^ZIz@;s6A$}H8N zT!UQLZ)c$mQ_kV;HIC>wr4fN1?Bd1wspzBf?+2#>hTgkP`$%QEUSm45^D8jb=jMi~ z_o-Vg8(Um9ev_;j*}k2K6M)R^!XfA8zAAH}Gq5rOxR>5Gj2*S*xhh z->EdpA4dS?Lr0Y^R_l1QUj>cgF>RpF<=3rN`Q{eGs@gB)sf64GW9>W<|tW=r|a27ctn71GX4 z*h8Rm5sv0l44VwTh|9`7#D$eIrsKrfIq)9W_?=+%d}o@cad)I{C-qw9ZP!TMLXx|mwBNC`!k6YpN;^eAItmRPJ-=)cY-ark z!>Zk((BcwL^VU>t)eCs1VCMoctB9TBc(EVvIALxc&*!RUA@W+5C?hgBwo^iq1Q=F- z6Sby|b-ur`0F^>uD;y4OD#aT!p1i6vKKh9v^1?GT-V$&&?Bi|NMyhuzfjB>fZM=fH z<#$mzW0S^jBNy+8it3P<_zms%Q0(BY9`=~Fd(h6PobFi{;wLEoU4NQ7H{ckaHs1LH zc6Y%QbrHp1r#RExC__3+e(QDdEqnzU^^oXhsWN(qMnOWv%HKqm+E*vf*ss~B!@P)L zwB;8HI~T6tmlJPK;|X7ulHgpQncV!ibd&NiBb>L1IzuEJHq>3=-*DSfM_Zt`^SF3m z(l-vz!i&{Nqe^G1qlw~A zt`3hqAi-1G+!5sw;?gXF%Zm&veoa%HH${5^tSysr@h^Pwn>XNm8ZfKi z2QCQ$m=(rV?RSZ3x3eDpbPtbR;jX^qaqIL+vQ3n>>fugl@%n@TdMwk`>|aTf5Txn( z2HMtfjxeV1cn5#A7*RaGKy|H~^mUxoKRY)k? zmRlnA+-|W(G(FcN-$;0%CA8d3T$=4l3!mSVI=(y~65cGmYBNNmDCif1e0mTKCn>78J{(grL9 z7_XM>eq^HLL7a(UK6v^w!5CxZ@08#FSe3CLA76iNl7#u|>K&@u5cA7xZEV+BONR4u zGGV}CJ7CE97dP-c*d>V;ZX9VrjMYO@E0uNk-Gz2>OLhF~uturGRn6v6b!s)Pm5T)H z(BLC(X>iC(jjh`B|Mp=|H}20&5XGxqs#eE$(I!;;pD={BS-gKCqVGfMCf(LREI!g| zQILLq_4nO97*P}`Pt*rI)kt`N`*HbR@xTjL#=nZYpztq4DG~3T%XxEugfbQ6WSG93 z%3@G$vFPxCIA8Y#b=&h@Zvv7|coL|O=kQ}ZkJ??Xo+Oc8pJ#Brfag=lmJ#qV1>ddw zmUbu0<&bl944t&4*&(kUo@%~dgv&_>AkFh;SQ+o&MrjkS`B{@k*wBkhXtUyYub8#t z9lX`HB)&^C4DFP;&jN+QbQ7r$JDd8gwB&o@25&fr`BAwWJWTz_`377ywuj)*g}EjM z8H%ut!{Qo0>6IIS3y@-T+=w%two#XrEL6WyIB z#WU%R&%vZ0;hvYeh7v(?Vo5JXadtLphS0@d_Zzh|+Q?7cXpDxZq*Nwv>$@_(`f@X#Jgv`fZq)I!k`iVh2tI3}t&%*`xfJ{BkIl z{m%=WtsXVbuYJnE_lxxvzk0MsS%eNxmgO-N9U|53Bxbgfe(v}#ON(#$8*vv!yRb^* zQ>1L&x$N05%wN#1@OST5$ZtL+t@0tQ zUcaF6MUPGGG+qPzDiFKEC)C?ic+sV=q2-)_9zm5%L;g_8JRu#V)<^H6rntCb1 z(QF@IU-5T`RHn$V<-KIgGafj9xHGJP8xp}fw^Fvf8N6*Q+SULyC7jQ48WQaj-WXVP zUI-1CZMXa)HvWC=7OO1*&Zl14VKAn7QhkQ;6m&7h9zYpBSNUO6m((jzomWU?(@;ur zQq8=CyU$WW%J>hQ8;5UxK`AX+;l1AhNe9fkXMEDLM3nNS`ZaIcZrbjztod-EQ}s86d8;9s`0;mfq9bRq4V}@)lA8K zRu-HjB~uSt1#nNScD3zpixJ`;e; zlcVNf_)w&^VvED+%;x^nN>0;(lW7uFaiJ%6I|-OX#78wMbIrp^hwdSeyBW3qz?K&6-K!y+oL31G@cz!P{1rz9OBC1=g@9 z|Fjo`o|@mDSc}ZxZu)XJ$8i1K{`e)DK4v4a>c%Imaih0HlKy;S_3-tDbjuO{abL~PO}wlg1bw@m8}@gl9G$v&IDlKCF& zVIl5Rs}XrTn+5sRy1E7@$Ei7EP1PK2?A=?j(__)zDqpM!`30JV%r!jwzJI(QxZGna zGih5Y*G;mEwTS!g(%5QnX5ZXTE5EvBs=0Qrt8~r-Usry-rKOc#(!}Rz)2X+)Ij(a5 zPwvfenFl2knuPm==U*&_J6UGlX?ESVErc25Yim#1kL(gBNYX-BA~&jDgqOg3)kLtl zJ{`2BoXtX$6JdR?>#$&kB@>Rm$9y|FRyrC%TDFub7W($Ity?}u|awk zB}-52yL^OrO(Qo=9&#|?9=@I8f5i`GBfh@KMh@4uaK;ktv*|eF%oHZu8MRc@C$(NL zpoqUI%LIG5^y6k<%01zmP;pu17FsiS$gxpIa3eV_B!b2);mX!vMdV;sc;Ni`&0{#;~3fU4q{TXTxEv_fpoj$efLx(`L^fIbBM1L+n?0XeX%OC zP9T#rTWqCLw%)V*^;iW5LVC+~%5$e|;3Y-wL3{+25r6-SqbWKD?J8 zAX(ISD7LR%SsxSWI^)h3q~_-n%mt!wJ4iZ}uLDZm<=ttQi1-kfrDSWV$Ouxh6X|Dm zI~U!^o~*2+1@QKyKa!x*n9lYp(+w|%rUX0HN6 z%~)nUNEl^njx2m4GtJhIpZ??A2@@_E{Nmb^X}lY0>Ap|KDWQ&fb1L%&c`sc3sF zZhWu$Kw|4OcEfOWYsK49n+H>x?sR^yr2cddFO;{K7(CZ z&RXntH21u|5z7$9NP20W|tG06QTVF+ref6WE1k<3v!!C* zyh4kzg$in!2^6jDjc`u)>DMxABuu~3XC(bN_x}+0I1gAoV7PUi+WCn+VbE zc#-g}2B$cKcX3RSlI?yHj5ltGl^9qPu7TayTQsXttWh@c-b^t z4?imAKILD^;hboa84;mhDwI3U;d)^b70tpqm+2cjYplttk-hqEe{(_8o!yPe zJYq})XPa>Iz;I_*4=mEzX|0ukTOplVMH{qygX|{<+?ud(wuG-z;^N&LC2ZJLLxIJ{ zHwxUm1VW0M;jekxFKTpa>Y^l>{=4dyWI@iw1iBDEi#2zjU~kb(NNKuj$>n>Ko%->c zI&}CxXOs;FGo2^XC(cB{(ek$2(r|4l-P>_sjD)oQ)r;N&D`S;>;|~X7c^q5mRg&gW=lSlSWJQbT<`j!KQ-5yzDnKP zx}5x?tmU&8-dcC4Pc0*)3L7%plZx+PkW;CkTNi;HVz`K}&sLMaZ?zs@aTy&S10o&L zv=W;yXW1w&C>BX3&itoj`j^qfBoMt$q|Fwa6k{OcAW~r z+caj-NOjGwo5ptw8*4NpNJ+`xp2e{>35=XM^Pk5H#^a2>SVhcy@891%?@mX)Qt^#q zOkm(KDfH8Qi%T7ij9d=40j~$|({R^#;#`#H(gcT*MIDXNet&_M;Rl6@MP3>M$=`tP4RE+b@)?#K9f<#f61rv1zgG$a_4oi5?<=EKK0*;h^;5 z>!U?|;Uke-Irt(mB5=;u*N5;dNo?Dx@Gn&@mTK@7Vua#LH$G@CD5ao7z5n$7 zQ_tJ{W!R0xj&pG4_d1N1EH=%%FRsKxDvo<|gm2iG8CNOnJR^kEH{o3>i&^&Lzst=V zQ7gp@m-9RI0)i$ww7qiF?6mRkED3v~Ylrr@$k215!x0O*&9g2+Y3GA38i_5PYqb4* z;pD5U+22J|Mf!% zL@~?D)*@>LNIrvzbZaRy_ngmd>{O>%YJv-)XWwF+bwg;7wKX|il1>d;zh}&L`%+f$9Lf}0c33&|`VY$E4U%Sf%fNi;#di~{ok_$tl>)7k@?J0fM^fsHR zOheW&7ITIjCgD*zImKA%_7*8esoj_9&EV8OQq!U%=(exiU`>&A`j~s;uoT$;-374) z(Mj93fF*unSc{x!-*PvXGf^KQ)&b~C`}8C43jP_36GQYXV=%NfxBCtG@6U(ZdcxDjo0}KE5AJ?MCjhQ%qF#2|3#Y~i9{NpHEiJ5RGqkk_ z1eq3m|7vYg=8V4`3zTD!@Fa!C`R)CYqksNYv!HnUX6*#k>caY`NEi*83ccscLd(o` zy8({S?64E{n$HLEWi?>cr3AUZUpAVIQACD#KwMqP8(_(7)ZC3v8#P+Ne7*}=FBI36ECWKiYafTHjWt$ zF=k2cc4}82cWN)fPqx`T#6%QWadGS1JSta1L>Z$~MeD6{SLeW@>%9Lsq>sH1W1ZHg z$JO-1clF7klnh-AD?L~6<2lZK1UG6f`bP-NBotdVpYx3|?#jXUHZ+v9=7eU&XNQ9* zkE7GdTtZwo2ES@_Q2nidIfPCA&P48dGnNqRCfw&Ohrb^>44lPdZ^nU*;&U?J=4!*Z zLv!d)g3!kFE;KasGlr5MeXE8>@#l7DB~b7LmiNbn#;p|fv571KNA^OH29MCH?kY9D zBG@5%0N6n5hHd(L49@8XZ~PL)*u>{%*Y7u$*gQS68YMJU@bd@@#H6W(Mh<5Aua)9; zl2e;5+nPP(Fu927<*NVGzh6YjX{@bTMrK`joqX4X{2KBGuCwp|{OJu&*sb}xO7aV^ z&NeN1^2Lm&yQboq*8Xkc#c&6seYx1QKjK!~RGT3PI`Q_+M{+6+%WBY?ip>K8yuDZ0 zct{_#=M=ocF&#LM(`o@-;lrOuglB6o4wPeC!yH`2pUwvOcK+q^<16s*iWn#t-f8Hu zrOeKm&5=`S5Gl*22~32* zY;7a9SHa%9o~K=ML1+a(`8$_R;HRD@tsGE?8@iUw?7y ziFnsapGa!oh8`RS6U;ld+}pEPN69tc!1hUv<`^16h0A-_yl;yaq9g1MOXF9?pGJ$$ zicvnWs650v+wpDSaQtwS#7}#niTOKC{d?0QwlB_jJQnhNLr2Gi)~86#3Lbp(P>~Vh znWo#e+coo>a2U2^>D%cr=)A+-l3SQkb7$7QbZfH1wAhs{*3`Z&o1er%J~rV1fx8!E zlFs_&RvwnYDwe5$1L|Ae*d!4@npR{~C_B23CI&bnjCW75Wg?lzw!RrWm#>@<@&`-F zC!sh0vp^oLgF)9wEq=7zPxo(o{nY?E)vehIbmv>-AdO*paM5*yYkYe#-kXEx@+pDK z43qfC!W~J1#(a1Onw6fbS8+u_FU#EM`h8#=M%jNxV}r`VavNMr@!d|>e>=PLY_lA2^8$?8=1*YZkgR`au|47}jX>*P@RI7mvFU;2$ z&&BZR2bbpRF*s7LkDwrw6+lshC(S}w!j=i}1b52fksY*+H|W1Ih2F76E2i+wKkK0k%12T98oW5>68W|OK)N|eV?=}Em8{_}UR zTVh0>3aV^E?dpn7>pm-GB5aD9>fI#qfuaBi(X|+S=FQRbKS305mV$1mYR8)4=_k=} zr~u@Zoo8bUkjZYG)Ck(xoW(y4Z$$gXaN(qp64Py#W4?WQb!zP0!8#Zsr5!>+G<>UhE9#arV}T{MW~ zy*E;(f8X(9$OUP6A^M}%Wm)~1X~L;Wpb3c1@Z}I9+Lu|Sr?t}Koz}CF9T{u&w)Kh1 z7jjAi;~Fm45lxfK`+qD8tw=%vZ};5$E^-+CNW+!$nI%A`b+vRQb`^@_cyb6J^rTeh z?l~-?<}|$QydpK3SBe5T(a`VME4QjkOShq=;xgxs=U&T+M{O@e%4{=P)xh89r8nAV5ofW6!Oayr80)G;^Nk9TUK$cP+Z#098+)T-`u(R5&&RXv{73ng<>NQAXkKRHy1gcuuTs;dT6x)J6Dea|LGee=#Q~A5x4>U8xJ7k(q z&ixecaLBGbyO|0EC(G_+)a!e@aL&ykX3mVswDI+|c5fNs`RPolvUPRXc`%%NvF4Gb z{?aU-hDb&hYPO3@6uZ`Jsc4YR7&JoRZ$>@T@_Vm3SJ5i2zD(^~m4=}{CAeNpx%`o_ z)o~fFoT)4^MN=4FnL}qGdYAPq)C@|3)C1qGl;%+-P8(}Vz-+r+acG!KL{;&oDd4O0 z2{kPX2%#KDf&*kaEk96?Ux|DB-)E3fHi0=v-`+-e51nhy&5(X7mRRJ*^lw^3j$Fw}k(vu7V{@%2k?7 zhGR>h$IelzIE^j!**+W#Tw+0nS3;!z8-ejB(@_;z@XlqhOS~j8b*E?Po5Lsvo_- zKu{h}j@%kRUtcXnll5ng9T&S-4Km;M*My1y+qJ4*qVaGI9@UICb6#q}_7$A||B+D< zAfqq?BL-X9xN}B90tSq+h<;}R z$Do!egiG6l$NzCf7o}d=Suh2-qLI+>tHTN6j3G!N>U>)s zoJ;=poaOCcp@b0cK(;Dwgx3V>`d>-@0lT5D_1czR?_89wOyv3Jr!d@m!(`&AJXwo4LGU6HJ4Hd8@Tdcg2pb-~hw|elH?-br2b^6a zLFXk+tM$k%@mrfmu@c)GlXAszX7Tk_YWn7F$Dl=ir$m$4uW!Yy-f0OA2YPACmahh+hEoMk1Z*Ns8blBY z7kTuiDI0-Tqgw=h?QlM^pY+#&A4?}3w>rQLko_zWF8%DzUU)8O-*c61A_k{6rj-S% zcpxAKZ%ygGfBrh7-5&YgD1tjNiHw+%4f;N}Q>y8aQb&&3L@i5V!3&EA8Adi-`@ekP zP+G4+;WTPk?0*>thY9f$vLFaACjCJeZMsY|0I!We{Q_4y$)VfwZr8RXE-2VWC6sM4 zVBqzo74qfFc(AL@=$M@_Xumy+M%Gw>bSsw)z)%jU(lKM0VxEZmFR0XFEjrUq&E#v2 zspimF-RS}C?l{q&GJc`QTHPs*ta~kXJ)kCF2Eq&sPkQhw;LeYn=Rk=a?s#{;mHucJ zy=Rsvjv3gm4kIie?sYAh#l>?$+`9uhGIxGdu*4+IPHW2dCW@&aOo_Fw11T(Z0Sy&- zGuLk42K|esZ72`T&QwAG2A5ZhzAJ^hr8|y|AHR4Hu!Z7K5b-)t5k2#3xPoz>FlZak z6bOC18>)l}`jllKssV`w+30SwEhrMI$ltg$8?&y6p~5>nkuJ5s_q?6V197w8=-c>A z9v{kwBn-A*7>0`!g4?EO^Qf zd8$$D1i`T`4WSYx4du25(DQRi76j#oCqM*15Q+vLN8?HYV_5kh0GZIk-YkfevGwV; z%o;|V+d&$>`t=(94UPFw@<|?t&BLdu~B%dT8zBk^gRfb zUcB^HA>Ma%d@9*kbUiosr;f*WtIZ4Mt87hk6fi154B8tqA_h<%Wv5VS03aL4{3ARYir@Rz=Yez{pTUWAgHP%+^h&W&<Ux1?ABwUezW->`WuJyfz2FR*NIMX z@-RGNgdL5(f+-X8KbfY^5bgAPKa1Qmh#Kg(W>e{aRxaz;pg$aWiq_P<0 zzTaS*o`T4cLd)%^O!L+CJb#8tIHeXtQYaXClG_=2NkNl8DeocGbzb_)))q*~AtEQ1 zqO7Hk={K^9KA0Amhz4jM1<5*Y4O^?ik5lk8Oj4#Rce#bB4yd zwFPux+(;gcn{AJ;UCJJj6Z6rpL;h z@W4vJ0PU(vdTup0os{C0>-sZ;52EUWPrbct6YrlnefhSeT17#^<=bk(VRv3!xjaM_ zaQnF4>tk1+-KdD}?Abs+NkrIl2sCcHclNlzQ7TO+vF#g(u89pNF)>6gf3-WxL7M2) z1t;B87wn(td#(h^y>$*y7ybrO6gvJ7a5&L!kRXO#+^8&MdgX_l}$yRb;Ug7+x%nGji9wkZGu|r}9zp^fe=qXU{ct{V zI%|ONfKGt<{|^MULbIe>6On=4u}c-S;uD}xOkjVG`9G*Q1vBd7?WGtO^98;lC1r+_ z@*=^J6jz#)@PcLeeM(v2G6)TMd0Tj)F=@0LpWA6koNw&&0?;meK!<<+q(c&D7F$wx zchdK4ZQz%fc&w_|xX%cHbG8sTgGQ=ji87Ks`n}I7#H%%281$YKj^2y~FK@t#`|WE~ z&58#9LwK<;2eBbGeyg!&^cr}6+k=m2Q-vZ0a zKOe6y2Tr3{ugsPuOz!WJ_(Kp#fyVzK1uq5`qmfQCnc(9T8n5O)yu(!m5FE%wQI+ry zgcg@H0=~C`2WBS-PK-*%qLs>Ce?IF<=Tt}Y^1^vDfMFe~3+4FAC|s}HJdAfcknwJl zO_QDyCFQFVL~KDKO#96OCeb%aVQXwbRsF)44Akbb3l#b31&rNLgrlRO#*l2pb8_K066IEK{bm$2T{mqv7AzL_Z z0J5|>@5i;Yl5g-1so}oHEW9W)esEY3gh)GS*>S~n?2^6LkpP*c>>CtA4uPoKfPntmN^mKV&8JtM=_w}93?jt3U}u{R=ScqIza}gR0z5s4l_!I zdO#Y}UDu5d7#yIy<6vLpLI~HV@$fL-LecGcX7JoDE+GI|zd8ad-r1H^y(YY-YYWd) zdGPoZB%5#vki`=W#Hz_v-#mV|x7z?Cr??9Li!kZeVsGX>lGo_}^_$%v%1!Xxy3|O5 zpBb@5^_o$9n1(a$4>zHGCr_2knzbx0wGq$GO7hx*_k+Rn#X^$Gm+%@c-|sd~#mMWZ z^+|Z~d36@}h36p}QX04au9(fQ@u+lF=i57Q2VRQhVo@6izgh#a2;~nW(weXHsNDa@ zw|JCbzX7>#0EGf40HybnQOW)Bg{Y;Z{yK56)B}xI5bhI8;IS#iyaB<2_@6#Trjh9H z0g8$O#M6`|x-cAvWY8{9wVzg17|`*nzXrSz74SxHaXiI~bIifxa(*-_x^LrWb7);m zb7(zWu}nE}ialR#N%RLqR?p6Db3_3=RS4?5f1f+c33z&}`>~)|F781su5nr}wQ&8Q z-Fd5=xb8XFK}+bcAJhlBIOewEwQbbanm5qJ@8E1YG#1jf@BlyjeypHRfncz}atdGd z;|N`K9De^+jU#yUB+Ya}*O?CdVT>1(W#zOSgmV1=I7z{mJnp79zMf|rag8(~#v5Qd zxpIQ@fKwJUHpG{4PC5s@K)58ls)ea{FUSdF<5V;=#ZomVTF8n~ZCfO?^c5WVSi7%I;DI#ICsr%Qrj z8{IgT;!QpT73EMhNM&-x3^sdQ?3FKvhrm^qJF#T=>+D6W*FXcmnlaE&381MAhid6% zjF!r&MB#9)T$tb*wdpyxF3lL_B*!lGmfRY~u!H+EDCMEG?^MMRA3_){-kbE>!EWe? z0|y1k2DSK{2TKDEnzDNKW;qI^sDi`<-e)*szmF^p?BERD@=x4w&)`as@-Q%^Eig-? z60yZz*r~>CQoptTA5khnOR3FY)jCfz%)Yl>?r14!lfxK_^edc}?Fw9$-!6fd=D-{? za&wd^5U^>#YVX6h{|9}14jAo|iD}}vMw^Y`#Q?e#30{M#mwIjx<1+`$_d&rdcRZm; zt&@5>D_NusKIN>AUA|O~*8ak&q0``_2fQ*#EcQ1VR8O#P#af0;4rRsD$j( z_Kr_G2YpP+Y*A#k)YUww;<&wr)X)olrJSwuR=(ly#8?B799W)5jYBPH0tGXvw%qX9 z2)QSYL$69p6POk^12ULZJ$!_-6`Rgq zIdqX9J+Xk2E=%qTQM!RhuZ#6Il=3!`AbXXpz*;@$5L zFoGLKunx@AwdwQ_fi6%;m6$XTtHV)_Cjckhnr&HZe@Oh{K`Xt`8A0ZrMo}SPs-BjM zffQ-x+!kn+s#kDa=|*bUb-ap>9_7V9#8fb1Oog1H2#)kZ0w9P=3JJZ`^y>yf_PuO9 z8J{lWm~I^gPRr4^T$bPemGol~MyuI^IVdbSx!yh91&%n3KW%gg7htIM}HnCgPSkhx&~fZ(CT zV8jr^Hr)6RVh|iVBXH%Iui!PC(yd;EFUY0;kPYCt7w%#5yjEC`ybxQD-;K*y!4SqT zEP@$Sy`gmODhlwzxM7StKJ*ymm}6K6Ozkh7Vt8VFp4nqky2WEEIjqa@XC8}7j68@_ zhh$@6cfL6bLpWhDbYb zb*Y{8ez$!uas$+q;SUSP!;yXezWnnTsD6iPtz0kmA!DJPO(Ym1dKOOzf+k{Q(OhAY z>8GK4=5B2+J@Nt!J!K#hI3yd7{Re~=d=*zyaEpsc%CQTXes>X|T~8y?c4M{$V12k| zLl#>5SoJPYCnmADX~Z_$Yk;a^%)?+hs9>nDI9n8@GbUu%b$SioKHHJ=0%ufx9|P!` z05uj}omURVP@sECR?BiW7lx)N`&O)BRrLm`;?R#vjRXk7hhJQ8sy$vJD5LngphG_| zRyMv7tjh~?)o#oQEtFHwvG!Zuwsl|0J~SyD0RCir3x75SBM|#6X_9yOU{;+t%JZzg zM(U4hF>$mM3r=RLm4m+*1{J$@Rg02Wf{__4<>^U7d9FI^*S~u2P-^oG>QR!eliwdV z`C%eHT5&KU@XM=|+AcP<6m&esT8=EDActPI^`;y2EXHk6>%I>Qn|X=10V@; ztM#Qn&Jep39~cLSASq2w>&8=J*A z++2vKKKtQ`;VlE(ykKju=Ev9WNT^R z>Kh~L;W}r3l7vx)vNkua;Q+{sHNT|DlF0{9%0-5adBsOmFJb~}{cyF)mNCF$N zMwaDpP%j~|7xCPb)QE!{`09!kCmMw$CR0*zWsw7*Gae$x&WP|B6@1BV5(j(5FwoJt zBsc`sb;vjErrzXPp74+5F?3o-eZP$az7HUauyW;ea`bhKOle*HE*&iNUN?G}!oq4g&r<>}-txFhDAt%yVsc&&? zw$yQ4j?r;50*lqHns5i_s2<09^yDz3vgOCOa%r7(b7Gv0aj>bWOPt`nIWEgSDrYn~GI7YM3N8y2^0#0cXOc%{d1y5OGUN=f+q|<#^1RU~RX!gqGpZ za~OK)WnkhhC5H|$+oP~P?5dh| z4h;<$0p%Tc-!D)gXc;ieM~aQS8MP}6QDr~ru_leN=g<~nW>l`yQjDwh!f<8vMemHW z?wkjsGw8oZ0{M-c#`r;y*ZZQEEt62cai?Y|zfkeoon;wd_H>Go zBRSs1@+oQj5j7#pKbM}r$pc|`3wfR>jtBRrhSusw+(nQn=?+*-zEh2}sbjuzlPd$n%w^4ohMGbn2Z@uvi zd6B&0V|M@P4>0M62MH{|kHDM^vSmK;gjw?-&YSGnUX_QypP57#rQrHAeqxLrhM^N8 zuJ@9nzn*sp`11WNRLGP^b-daKmW)@8{r1vcwSYY@@U}pSY>Y}Y^(PZ(Drj6t ze^MYemtcX<$Y!6ZwX$@IiUkZ0W7OlTs)i{us)fsRQ=$UZ_rfA7h1mP|dLPZ(Fg2bg zXOs!$49a`9_vd~gBC!IXDxh)| z^hZ@3>n11^g274@O(u21`MGRl3Pj%gjv1kmK$99KKX;Q>II8XS0`TF8LGul;aLL_a zNqF0F{4^E`3{ks|lZhq+m!k0xsPW0Z4gs+%a&sv$FzXiBr(FVZigAkrMsV~v1+CMS z!cL7}rAK43Z@qUK_&ZI$=%-si@`@!Rx{HlVih!(k6f3fJ7Pg0uE(+dk`&!TCBqF@` zf=P2TUb2tJY4xB6V$cQL#rQ3wr0@J<6rJin7v5}JGt>sJ4Xh`OEeEsA`w6(U2;DdG zUogYn3{UsN1D{dujX;xFOjNv@?+GIIP@D=9KJ;^L=j(x9bLo5A+^t})S)p(;VV4mc z_qXbm#5R(ZHWVc8Zb&kHs2T%`NpOUOSK`Pr+q*PA#@vwC3asQ+E1&J0!@a`o{*zIw zde(5~)7MbR2royBXUtaExUv? zut*37U;qt9V_#Hq*hhi9ZALTS^!&uV82SM|&-#a?8lY4c@fOYAUGS52((fmbiV?D! z3xBRjQ&i{L#;tDEDz^&9QrA8(OvZ%*JSxh^rKnt1`zZ4k=(wyVE)ZLLXS@}(FS zhXOCDY#Bt6je%Vj1CZXa5Q*x!qB0{sAmC=GLSsvikA_q;4#TUb2b*?i3R* zpf+LYIipP^LuoX5+AhW`T*u`Cxcj~v1L^~}OQlHEZfss-MX{n$44n5{spZ`E zqR8Tqc(asVX?|(4sYSv0ozOOllB2=lqsME5L;Ly9ZH@JGPEsd*t&c8E+RlEL+F4Ur z(Zu&}{=0|%IPm>4G1BeFXG%5u?s{*#^lUj&T4!cl_TsODa|a^+n-owao|*fG}^pvZxCFVChaFwS(EWX)Ns=gNKORpzgg=qWkC=liJ;6o)&p zrwKgDDXdZ6^|F*hA8yg;Etmn!d$P2-jixWz(wv*VG5FL_2vt1lntg0hRDj!pglkcB z$hw$GY5U)a{*igOEAQIKjkOj;RiTjS^3RLk8(`G%&B++rNI9KFWa}U<;UY@SE};UK z45tsa-v26=&L!~9JZq4MC&cFDXo6R&z}lm`Paz~HMze0(TN*Og27kt~uZK`YJ@LVa zV6I#zO~(6!x6FT+uXb=(XBI$?SF07ebpz8fk(+%JaUhk#MJtlaL4BV1=y6)%)?Q5q z&7m-ZIG44tz^sOgwHu@L#j;=PH=fmrhpH8Hh4^|^4=k6C`i)2PYm&!o#7t|3G;Lg| zd#gQaHavE3nyM78$b3gNnX*#*k_nFzIwC$SbtG#q04|^2agQt5dDLMJHGjo(Lu_a$=JoU0Jl}(6_s8#a-jD$%b>Ey$aIp(U z>bWwF7iOk>i_AA3DKg4km>kh?K(r>xc{4PM30)OxZFZFJyf7(>aMT=NG8i|z3?c_L zzAvM-)D)Vce3~BUb|q24V=VJXyEg3_fgN0A>na|jSwd1xPWV&z*vCRv%b0VPN1R-J zfvo&S7kiWM=wl7@bh|I+C5+Q&Tsj2*%~t?FbUlQhD8g`e!0$wn)0%D%(>@33M2r+$ zZpQ#}VfnrD9dPkpFetdc8|2$%f3#!>eL61?P6-tywm@!pzvc8NM{jlU^`x%;u6`k= zMu91!mTp8u5Uo)XF{6pEEqn)ES}fmK-+QONSpJh~P)%@AdbXL`YU$Oh@Xfw@c6kKt z1j6R-J|Keb7Az+JDP-gX5@uM;ok@=eRO{ZkAE()l$UXz5AaYO&s!c>_=XMDyJA|fc zkl33sj(*EN|t|+WcxU z_~r>ol}U3QQRbP(uNx9H3DXUGiROa`vQ8L8fcq|{TC6rL@)6s_+jU$Qut|^d^)g^8 zF^l(e?swY|v3%&dJYW)-rF_eWQ<=NYyRB4d5rz=S1#wzsn-P;&cTGSouWJMQc5u<^~o~uCK#`> z#Z&vN-&q!DXKLq(BF5>w_G;D4-==2@REc*Ju&^#up$#xbfsEaAFaF1&kHem`dO5j29t7Q6CWy&eL@NGBWA+v^7yOiYou}M7&L*i^;_S@wo8HC$WuGf zz^jWM7Vg8fFr9e;IOBu_6<}pJeLsAIa8zBZM{2ryDAg=nttu!a+RMem-uWj#!=)iG zO`E7hW5V{!v9vI95v;x@6+N|(v17`m!wR3_FTmcP`Tq3o^#&hSBZw}szp5d3WY zsZoVdnQu-BwbLIa`OfJEgUf~Fa^sjyDdDU^ZD4-w(6d`#`>odD9+9BA1`<0@kl;G} zbhV*(Ah@_?$9ZslwHD@ZWw%fp>x2Pso0L|c0|}@; zsbl)hJnP9zI_vN=w{_NY^o0d^i2>rUXL3?hm}bJ$HpWpeYYLaQ`kwqMro{>nTvIh8 za|1io3O=<0jCF#qR~Ms%U>`ukbuMl=31@^}7RZM_ng)9XTWr2=Pa|P{InBx-mu1=q z?}H;S7ZkX<5gAiHhEiv<-)ug!SY#IMvE3{$=S!yPCW^@f!JAf_qx~#ZiK6Rkqq1^I zr@q3vWW61h-)sj>j>?`q4-Cj>j-&5XPn-*78LXx(A;gFn2vvF2oIl1v0S%*UL^GW`}fRB$6!6>vs4~XWBSdfi3{dAEuMQ31eB{c$@y{cM>$ zp3l~EhMKCO9+*wu z818d{W1=U+D*(>)v87tMMMsObebz;^v4$N()+}(V+?f`Zy?&$n({x|w&!?gPSM|1i zenq5|7oGRziM&5e&A7_s#S%?SXF@|DBpq>oYU_Cku&KTs|C|Y8;VQDAOYy1An5RJQ zg+px}j(8$lN9TvrqC?x1%!?ax2YqE`%s<~&x(-?@7&t%m7`M1|sfU?d6J0m7l?@9J z=t4q^<(qi~Y+Ml^fz331=N0A@^|YHckWKdE1qA$dG(hU1#YBCdRu?kY){B@z=Ee9u zn6_t89#R;H_dYGO#r(UAaqE}NP5qZ&wN9TcoTQkj6mJqyi1{!5)>B9YAu`c06!wvL z*TPubOLyB&*#|t(Nyc_UJtWVj-%j#~JrDP_Le!{8Y--Il@_y?a`k#sNEl*Q6=PVHH zr$RK!-t*5oy{RZm;z=DdZ0GHx>xJF4=W*nQujMOEe6`r#)ZUy876{A6gE47cUqg2D z4c9Wp@DC^JA|B?xPufK*MbvJ`q5Gx3mhf+1Upz^}Axt}M{;9ESRHnIJM!D;0O_<$S zeQ{__SXj+369*^xu3geUoQP7nB&nBOw#lARu(g53YNlB3-$qQm;hAg# zT{d53r?L4^F=9#`96IEwd;GYddQwbpujlL;B&x>>a%VM#r;h&UI~a-;8DwH66}m27PH&RxeoEfU(kw4LGTZ!MOY zDoir`YBvQC_m{=ux49BI9Cj`R+pMgaBXk$m&hvJh21Kj2vd;_AwstU3+!1)!H8bax zxnV`2=dN1~@lbR8X1^1_eUqD8PyHyPL1!@cqBf&}KI0zRKv>LZ36@V#KjdGt&iZyb zf6Kvj2JYu~LyY{iEB(M5>J#VgoquB12LDMwZn$0e3s;AoukDn4uJY_2a~zgj0f-9j za8^^9ikZKgK#EUR#yF|t*jUH}dBV*+fhLFcl-h0jFR;AecWO^YETu0N#r^yk6~X3n zW1pu2-W%S-ku=|h^HhI2XsekW7F(}bU#}1$CfygV3oj+AwMF2i><0ho>x=)g(R27b zt30h)ThRECR$oPBStc*Ngb2h4|sB<>j9IVw#>uwkKOz16i`&UoQ$yTD#kg+npcZ zoTA!ZoDU5ZXf5fmMp(j}1q?`J5Kn9n5C)CONk8MGg{cCV9+HUyU*|_UJFps<#)FKD zAY@gl*316=4Z_j;S_N!pd=eSiBAq6<&2KO~b{;F(3uiEFaK)7C&}+QIb7jTjomPz- zU6MULDLbns!j>bTZ2!KBq`9o!(V!J68pHoqqS*v5w>BEuuV>{RuRX# zrO(VO#dPrBnn-NAdm2w8hU$m$D`U!xBl7zmiG%W!J=qx9s9t)Gh*F+diHRYjbsjpq zmnUJ0ut%{)Sm2e?SH!qt!ai!T=8g^3ytG+y6MHSFI;Li zc9VSx&oh!ywc3iWa6-+5jG()s{IS7Q0X`Vmy*Xb*KrYKZ)r;P_QM&oHzh>>l$-Ex^ zfEQo#|G@Ed0H{>9aqoyI77%;CzUef;XmLjIn2tRPqDZZ`XgOxqs;9y9Ae=eu zrM#!e&$MiWLF>O6$C`<;0zuJ5>jwqj6T6H|{Uk?ze0O%C+PezG=7cHwZPc)YbXq_` z5^bNG^33YXboZld0XG)YL-jW%a|^fxT~X6#O_ zDz(^~WtXB$W&|@);i^nlq}t5U1?%4(4Nz(E#h_f?z+$;{E#fN|i$$c`phS$vHS?0O z$lWyZ0f9`jOmM0^J1UR|gBR^x>mhgkO?!Qd`bpZPrsGDDN?cqvk!QLywoJNHNA>*@wgGK zik`_oXV@%CXs|nZ43=8(m$xkE3PJ@>Dkcg)P83N{+YsFrv+CLEO1Ps3rsa=7$@s-? zM2Bv!j7pW+AUZN90@1sPl>cR||MXw0Y+VN^Wf;09%qhk{EZ-}%A|`UE>c@hX&8FUK zudwBfaKnRZ84OLKT~xX;+bbHkKRn<9m2QP=ot<(Ie!4`TY0{TnTnX`+h|5Lv_j^N5 zxdYom$qTL~?$h}NYiD973D`BQbH5MW7ShdFeApy>Ua8;d=6GcJcS4?OznnKd!HHOF zL~>&F*!MdxlY{ihKP{D{R%5b?g0BdT9nH+X`Z8>h+t3`!lH$=cKQ!af#Fe(-TiT5U zYd%8<#$Ql9pIQ(-ViSMG)AP1M#wqa+JuMw~LQaH_xP&qq`ocX1n2f?B1xitViN9jC zJqup-00TdIqr0_}iuS6BX1ufS0erm+@+BwOr8E?h2=z|z&0=~F{i%=8I28z7qyCM# za&kZ;$TitT3kE2zA5BMZKD4S!pTOpkkk~Q&@M(ht)wxwtY}5TR#p(~njjtsZn%9kn zqGC$LN*$WWupzaIgjPgy(N|v78pQfD|gK+@cxa1@9yJ@PNnW!)S+xg5n#tnVQ$eI8{ z-tuAsbH}cenPbjH3?%(-ZU1C;dV9!$oGCN}0Ct+=c5!2dvT3fSZyl~CZxP;A$- z?64$kE+>a~Ql3G-W0{wd_gLanzCA{5h2`qYex(f1wddBN#10T=?+uW#RC0BLV#9Ag zyyuYF*ng;a&eTem86>4Y2^C7uRZL4SN`1oGXl9(wXWeN{=Kb7|g&bC;HylM|Tb+W^ zxG^A5AY>%89G)h$`2!0RMA*K$h55tHgm}4IsW<5rwa)H-2jWdAEV?$E*{XlsAj2Mj zgs&1aL_}@mVr%euwt2gu*Y?)GgJmlb>18gPrt@Qg7qiB=%Y0JjR&N4}S-y$CAi4%Z z1vUvA?J+XdnG0R6o7sy(>rUHi$1iTkUT|OU3Rv9XU+t@p4xJAP87@$Anaa|Du?L_} zgwork^R+8QK#w0kEBeX{J{)QquxI{%`2paV$SD9IVh?>zZrnrLpUPL2u|Ahy z8AlWkGD`rY|0wEI9(mR;9+oDgCSL-;bpY)-iZRaQtt#=3k|tt`Yl|tS2$GydC&v8 z=uh@xXBj2aH)cqz#&Qw0LA(mwBuf3}jnnY}ZY`~!zEjr{{bbEg-i)Rxa$$B9T{Qcg zLc8EJ=u~Q)8Rbp+Tnd#cZf&FOIA%@pe+e&^j&zS=8K`t0T7`=!0Sxlrm|qAvmEJDA z-1TVsnR=jI#1=`q=-wfrFTgNKucbtQ-EE7FdVU>!7lY0xo3kkvRlOU=8<$$@&yrz+ z3(QB`6|`~~^*XJ*=~b=)UcB_CHuq0aT-d5pS`ZXi^x^0>lxf{;8%Fu;+*l1FE@`r` zZ!6mwjDIr0?_f|Hkrd{YYR(@Kq|7fx)FG+Ws26f~ZG=`{BYmWv8#eul{;v&Hm<+=C zgrR?Wi0+xLWB~bF*8B}-9shCLxbCM+VNU!ewR}U=?#ZUpms?@zA4StUEbpS$(7#g? z2#oMeXMBBT1_$OoQNJP$7C&Bf^_Y;ZnlOtyls=N-eizpo9PJ}!1B#i%)_b3rY@~A= z$hOzZJPvs(8D{ry&OI7}YoJ*$+oG%_fsDz#*eYnQtnAQXja*O!Pk(g3)QG@1Y8MYL z$JVIO4VsSthgRs*IQKXNT9Jv;GAE()&9}S_G$x{BqAr@0F8xHs!|&3;1DO{2jIxv& zrTKbX5UhdhCU!JFl3}@XR~cfuB*Q9l8_oQqx~Xl}k3Xoj2z>+YWj9)JE}Qp3iVZ&1eU+zb;d7$bG;pulzmKZF6si3-=#da1O>YUp1BXus zX#T%_Kk-s{a!sM^+We#6?Fi69Leq~e8dlYDsJh}#d5?KSW)0%v?hGkppy#d1UN1m4 z;i%n$?f|1KU!87^xC<&muT>AMH|M&V-6`?`l;^M7eCiw$UtJiyFST|$kV{~(!7mPt zguy&^wgMZISF6RU;yaY&vF(;%SkTuu)NW@>!R)(yNg=wMsfVNB3NJhE6WqUUbS_C5 zT&dw1IbE{~9^-WBvXet@2-ZaKJxNppflP{Q(Fg5I4BILRyG5>!Dx?ZKC~dR^{_^SH zipmoc=cu|$4L;QCsV#_we9iM%mmQCUm=J}265yMN>GFzjiZBf8stI(8-~p&1L-lx@ z*g|5ct$;O)1Ly!{=gcX`<66wDzFb%sKt3tB@C~`z=n#-~3-DmI4DTqI>|BbpdwgAL zzS}^j^|%;iOIOHYO{%e&uI^l9&3VI{M*{5->&=J)h(p@?+;dpZy+~_2hrG(mfrYRl z7#rqVzk(MP*xZj>z{K00`tpnS0u-xX%G~(eKQ4ubrQTR9O&yk&ABYfOYVN^fH1};- zo3I7dGzx)#>CBZs@~D8K+y;2nwd%Lg?f9m z7oIgDWg>Nj)H?f)b!V&?a*##Yk(_83oc!d)99|gYEE{ib9M8y{p+Qm+@iZ=3nzN-O z*-y#J3r~mFXt6n0lnkLf4-0c}T3U+vdh;wou&Hlw@O}`Br$Vy5KkpB{*75HbeZ3-d zMxp={8C856HioWZsiT#KpVFrDl3bl<(kiMg;qJtIHMZe_?uR~JFmLCp?)=6L6qk4$ zpVihfY$*cqX7n-oj~nfUBKT971STVroE`!yP#Ei-`6RNpUBxUZdF&cFQOjdiai6;O zEP`%@b4hls^US6-0WiAzaIbdQM_%bpg;;R8=}!#OKL0)Snu9$xuIVFs(-GhBFwvBX zDLq$NAI>4Rx_Dzanzo6%OYFXvlFNFW;QNfX9D#h*E4DIy7pPIia(z54)}{kz<#*>1 zbS^dTRC0);z=CSO6h$yX$p#jd8aZ7BCaNAhB@wC<=Yenwbn7uM6<{+}9J=fVBSjXz99utToW|EdkApxW$9nBpy@{V*d3-}=`wHux^@Khq z4qZ;wtOPCUjKRHDE8Q)2U~~mDDneNN0ivW-A1NyGf?QMhpA;8(N!->#-Jt_+q(GCd z8ehkv_9PqMwN>@?AKJR@z9%oc$hcu<}Go%ke% z17&6_$*Z%O-AqDk&Wk>o3zv@9XNP}&|2~Ot?F;~0KMv0qG{iT|TcH(yoqn8*^1FEv zQov=POvb=HSU&tZ!)vgiyQ~)r_y*t~0}H*J<-|m;s-7kTOa7DGqh3RyhtB>egIr&q z%tmaN9lw;T`8?j3pNH_cn!WP4O0WC8cj%8v`2$sDy5>H-Y_Mo0Nim}Oe8!42yVsoC zisZf5K#a9U@od0ir;M7^?@JgQbF9GraiZ>tbvskm0Ph{ zje=YoiDC_ECX>+P+QToX_4gOI>6(l2#$@?@1i&+eYJ*=-^Sx^IJj;l!`Ej0y)`pu@ z%|uvStVv%iHW+SCR&ZV&I<#;7jUvQz=H7=sT$hj&R6cl;8Ri8L=!35EM72 zvB&VAT#41ge?hLwst;Nl!=~AammbJy=!gA|TQK2R_`}$Rp|jO9({Ooq^Dl{_WM=t@ zXsow}kVD@~25NV1p|K52UL|t_b0RCRR%o}F54M*c6amU)z>&971%5brf#Fr?`?7I)e{mq*Bs*C{@k;?Lc)^iNErV(%-j$Po7H5tk(l1p1;YPfoEF8jklcrRS-Tf(7w7ERl|#P({3kg1)b7DNBQ%Tvnc^cinc< zqu2$D9rA38;>-j+#`Gd{Qd+m1Ljyz$hS-~(8~b-mV7V3gvOLWN<@0&$UEK`#JdD<- z_4e6=!#2&rc%IVi|73#)m`4BG3wf}7hpG@bC(3$nbGUOkg-zklOkFYkdolq=b^!MD zF3s)$A_YS6KBD^4$%Le|+{fdBjHU&8IsH}=2m8w#=$l>YxmwClrIG|>G0xW*LCq9{ zFh7Nq0I62v)R&F9c$-gQZwY@^tZnrwrV%4d*R8J zPImcPFcv$+pJL1PkaAKnwI5R2ylfZ6{?T!it&W!o(4 z=;{bgnWYx&B{fYn-l@JIYI4wjI8C2m23;-^Sco!X@`5i|k&ppilfvc-T08_VfN9h3 z_wYEy_DO3&r_iCBp$CrLpz?q70sL7i0hz?Wx8V>@*VbBJPwch21Czm|ty<3FLR2INcv@>kE)^ zqj-$qUBw{%`g>T1sl|$4OS@%QUoajXev#LxHi%htSy9%6@DCXFmjt9>x?_*;V>VVm zp-zN~V2y-6Sc0q{GfX1?HJ&OVS=T*wzn2>UlXBH!z6+QI2(Yal6By|C!1j`#qcnjI zw8?pIQm4jjetVNc72fdzg-rw<-m>vmgT*M?S-*F^{J`(Noo@I)xo z&K(7tFLKa%z2@F0R4t;g#v3eXSOQOJE`j&L7e=K0gwK!~{B93qRWtM);T;R@GaPr}0Ta@r#Gf8{9_Ad!$FB7`&;IKW! z9pBkchO$@8?h<;1i_*vGAv7W)yOgE8JHaOiLEYLCPG#B*{P%sx#w z--eBV=jE~HJN7O9I=Yv`8BFSrvIT>IVlS{y;SlgjMF}YCbaY8A4$Yv%giDbg?x##k zmI>!vx7hl@W{24j&4Z(85K;W~()A7`cwjfafgJ4fVgxe+Uz_iPg+{=v_%L#AP?Wu@ z1tXRgsnbcYxRG82riih3SzN!FeidZ?mx`N(jLCE%6qap{9b!J3oiU<R@_=9BVnBXZ@+?^0q@>*J8vC+ilBDY1_>_O|p>Zpt5O_%hDfpv&*Mcov=G^cVipyH4t?8ZJgBJfb%M92y z4MIJ$sO-mAe;JeAAN=X=4_H=&VxC%-dpB3e!f2kSe9(^juyB5?ByX_+%bchq!S=!+ zuu6S54-qB|5}Wr5wVC`-qsq3lgpGf`*fbrM8s@wJ#OSYt*mJ`vvmzTV*%I z*>;k(KSokB; zryF<}F*X4)B6i+9!p-K}FW6A5(7i?*6BU)m1MwY9t{0st?)7FhyK=j zR}J+P@Z5&Lga4!ed$Y~<8rR3=&Kf;i*PV@)M=EH+5Jj!OYKylm7b`fFgC z*D2R4!t{KHk;493=mJZ#%a;=^WfReo1f(&Jml@Mb?031;aG7&;8(p0SwmKz8o=`O< zHggy_Fhh&uqacf*GG|uG{pi4=Y(NvR@=u^konp+-^~z$(o~6Z+#@kvT4}BHpCrYKj z%4n7}4N~Nh;>Fz*#E=nMdi#u5DR^_4J=wNNgv+W;_7G?m%u9iDG}=5O`z2|+Kirpq zf)t1nq(V)_+GvW>bF)h7!8pP|xJ2XbxJ2V>*{TmVVNnDsJ-M`NAoNLpVaFlkA!n|% zoxn9eKgj`2z;Gf*B6VNY4*Q>CHSk2h%EtBn!s!& zG<+Z5V0+O<#x~ko>L)jtIe#R}SMKPbN-Jj4rYbEw67!>;oM}}gB_nxlS&x5(wC0lS zk)zM<$3Jh5=O;LF;^zHxgy-<_Pu%ps_}Z3msQd^%-ic!b=M@wb6q{j8*@^jRs!etH z#pi*-COrc#b6aOUR$V*SGd9AA{8>!wr|r5JXwzpnJiOF&be6U{aACOL0ZcQ~;D2c` zf2J2F@p~Etm;}MPqU?taU~gVSC56G<{_WwX${^KXT~jYu2Fr6#*~DbD>Wx=cLPER- z#vVT)Gu+xn!)!qE<)(NZ`aE2}`VWAQp0d*u0iQ9uF(F z7xs*(71O!r{2MzG@a&z(App?&0f`W=U+7q&`ILq1is!)3e=Ij(&neLc3Tu@xwiVJ5 zll?KGLi&?1J-Ox7I%DeRh)0e4sVd^uavWe(mv*$S33a-5K>%?Fr?(a6{Qi5wZOpHz zU}$E>vaQX=oyOEHodx|&@aI2+g&xH7v`J3vzo>eLCWVr?w2$BXh%?WMVRA5`$WPRf zj>2NySH;+lb(#$oyo+gu-hX^d{Fb)A1|jZ4?`P_5hH)?ZP~EOfy`0Dmd@hODS}S&Ccc8WM`A8EG9d9vs>@b%fpZEKVtsl7_h-0!WEq3 z+USh&^5|e0>G!M%lKpl=a-B7Z|SVByE#vyZv%G23aFa>|nM);K7$e;JZWhK8H^bCas+||YC+YNbZT1L48)}yG*DX@=3jYxuPq(UplSS{} z(W`BPEtH+J%Q;{9sl`Ekbas4hmG!7B@pm>Q!g#)Ow8_@yXQ&bL7=`NZ?*bhKW(Ew5 zY8owQwA2?>0*Q7#%muR2$M;64Bc37-@#5SUF>}DznERLcxvv5K8?(Bs^J*&Ur3)(B z?%^3pTjsg{HztzzCGpqR2FL!PCsnZUZi>9ob~X`ph|C38c)6#W?0h*n%f@^7Ms#KE z%{8YYR9i12H*#%9bo9g7aD}Sz1Ye%8@Zldu5&ic$p1bZ_l1!Q()UxP~6z&+w6r~;* z3|-{^(v^4;XC5{-mP$>z-?eO$C?b$OJ>txM(8U4BYd4&7>HAaGO>Bx^r<(W{?8Rd{ zbh$L{aa~OOc@zGb4o+?f>nkr(k`Ju1Y|Tppxf3^=NZNT#_b+4mU}lx$WUc5(&7gt8pX)Wr23|-~KoSgYV8rb&|3rr!K(|^Hl2R)_@z7i5wD8Ufphn?f=mGT2g#`*uG#7+eMhcL2WeX=~7ZgU_sDG zZH~3X#yLdy z#YhH?+hHcv^SbwVfAsb6V*Gf7M}JMHK5Y`UWP4a1AVz#N^c-!@xj6~dlRcw2&=p`B z8V<2V`0!J?qf~Bn?IkYaM0HhCtBZ2*w8C*^OC-LDO-9-1>2R>+?eHwit_;>qDb}Fx52@)PeSsY0} zU=EvgR^B0mx{64~kC6g9TFF4Kx3l?lN=z1iz57P7fve!{V9V#!(s`Ut4>k#uWH}dk zO8^$8d6MWx5)6N~-o3IiK|K`)_@8>AmOrj}M?2xWJmU7z`UylE7mVRX#FPBzCKL$) z8`-ok{^A^_hnw@!tg6Rz=MRZ#Z9eK@^LE{oTj_Iuu1{`uv9PmB)BE1;4`}|R>yZDV z$>37K3_%s!2MS}}+~H$i)K90#}zVh0(w$yi#yD=F^1yv`E&wLMO zt&rhhglui`E-;>Sd)Dn?v4Sq|tkd{`cqQxR&#Ng)B%&yI{d2UdrC2biYKwS^h5P$@y;hyFA!pkC#Qv`d^|^*7KMlCnA=YD2h#X1k}}p-uzqBz_BHFv(Z9x&*>ctqi2tIKJCoz zZ*`3rzO!bvSno0-mUT12j7#TQ{6Q_34&v)=5NC%t|3`4gJt z7aW$=+lA1d^P2FzYPc4(SK>gLEN&d`bh&>4Cnw_)0nT zoC+E0gY?mbz&z17*aMk`vi4I6pG~PJ-$gd6;OYZ~CVUT{jV38SSlN;0{@w_ANY=aq zZF=Z+8e`G^%`AQ3V=40`*fJwFn5;o9lo_b;uUnOHyuk+q)$9l2)PZ=f>fc$q^m?>yFYm@38t zH)+vi715R2^u7I|*$;=NXs2KINOl>rq?B5%s@u4hxklmoAM9N@v&O6CLUMo@3|0m= zJ)`pC>zVj3phHvYeP-M90;7ax=0=QaTn4BC90Z#1aJ92aQn_#i|MRXoLb_T=)amal zVJ5$yjTi?bDG{I1;S((dc5~$zZ?iABjjtWnmuM6N14T&L-)OTl)5o4AzI@3(`D-iN zuSZXot8$oW`V3iIx|s)b6MPu}^3fqq*TbYlta8)D$BcfdoSN9QH~XB&vkiPIac8%? z(RhU=`;2Z!jFeNWzcP(yLI2vpFXY?hIdA)&CE}8SG?ecakQuV%ej1~Tv+b7e8P1G% z`@L0F>*SoB*kG0|NjHA6_8uQAG?N0ix$ls^$BA93KlZPZ53cwa*U*s$bBA2oaM`7N z?BXWpUSKD+sDv`Nc+*5|rgf+1M1=p=`M#nIuowNqnIu2H8L&1eT{{{XjWLOfnkts@ z1RPj-ZL6UfSgJibHh+k&!jY#2i3eO@;@bE@2rsvH#bc?{Ft`jWNQ?@SZwPSCe)VI8 z{Sjhr^W!A3*eHjwfZ}17kJR@Eef?e#alasTOY~Xr(_H!TqwHh8dCH+M+KM)wc<~Qv z9GN5x{9KtcUsIbD^EL@xr$QHFU!y7>$nM5N@Y%K3BOnTaKoKZ(@$yku*C*?HINJ?p z+KdTbgq>OTP|ID#gS|n{(HlGT$2snxN~Ce}^)GczWR&NCUDg%hYeIXDCT&xNf?EY~ z&0mQVnr#vc-NzdF7exqlb;Cq#x(SjJMZZ_x8w>eZ^lMq!)dYka(bnTlw41N_x1s9> z;(g2Y9E#k6GUT>C`QSWG9bjo4u9Py@>+mrvu%sMl#!xlMX27Z2copq6>=!U_1g!`hX)iNXdK>7 z`bL=N)q9-KyE(6IZ`_HV*U>=rqCJb4px!QQOk8UFy0)%IL7R>|46^YMB|XotjdoU< zR>`pNlyGNg=oyE^5d>**XXIIuP?{fvqapCyawtBJMxxOdm=UA~L2OD3KFpUph94W{ zh&yV-yL@Eff9NG)-9qD$&s;;_q@@u|rJ>0tYI0$9GQSzRZp1@E64xl;oc|%%+AAZ% z=gca;?I+^fK4)vu`nEIYFh+z4v&`TBl}3HY_;o*8YU&5|g%EYQa&BIoh)p`bU1Jhx zF+)IeS`0t=-O!=F9%5tOY)YD1yj!WWCbBhLdK4sd|AJ`EZ_Bu4gT46IUSLo?FAi1_ zup`DY+O=4mV#{CasI@mM4b@ZgzRIQcVv&6MXh*~>Th8glud6mqw=joW)a1Zc9f0}7 z&IPT8Y^`#H`eRM_edRRj0jeq^z;DuH%wj=qGNT4l1X;V>nsLe z#24WT4C@CU0qsOk&(+);BA<6V%rDZqH+hB(iPqymFei4r?~uOB!Ck41hp7Dg&lZLZ zhadZNptmJ3>MEGd_B=L{MQ8Cvc@hKF>%MPKzts^w=<9hnR4$knu_8+sjKF2Pu9SP$ zL7wIahCj)mu8IC91O;hUNy! z{)&MuGW|Z%Bove;lvq5*8YIxj4c7T1(71|jg;}hT#wAC?J`H-#^C`j>H0q}y9;(DP zm{hqD=ZeH8Aw2A2RwcPFewoE6C0t>fv2oGYnI5I1AuAz!o4t^C_|IIO<`OX18O+VE z;eiBemxWXV164t|zQuNOZjex&3!r}%z6KjPm zCnLLMH;;jWEYbED409>pp2v4`D!Vdr?? zOZ~hPoq=m5iCmuGQ_t?e-knm%@JuODueSrX7P8tI5T*QiIF8npJ!T@OIfZVG&7W_n z&l3iyU%`{jEVJ`@@A2Qc2cCQJoDIL){_U;S!awtFUuDX8dDZQ&j71L)>SmurYGqSV zvOub#<%ujA>9vZG0HALrZ=|)L|Im*?VvfWz-OLiR1)lPGzMikC??M9Jyv}R(IZx4U zdnL|27h&<{;upq<(dz&vDhbOp@WQq5WZl1T&0s6Uam5M0u?uyUZ3ra}J317TKRX|4!z9(#?{tZ$+g(~WY z)c}imsE0Jk%8Juo1RVpS_lW+F7Y#(Jcz=L)AS$TfVJ}P?4ZqQl_%JBwfKOw!s&Bu* zM^Z&Z&4q3VWMK$0Nw-g4rlF7Shd8X_Fd)yq@^mQY4J-KuNKhGi8*imcmw#0{t~F3q z&vkZGeQs`qx?U%r3`69T!#rHJD>Q@=cSq#=Jn8K}vk1Ja1<~Q}ZHh1rv46hxlIvKJ zIuzDd$b^cm<{ODLZkh*C z>x3%}-38bB9M1w(j_nXgQ^k6U8RYykO2p0~Kia4)39ora@bu;?~4;Jmd}sjI`K|(4TG_G4+kQlFY5g1xtUc#^0;*h-ex( z8`p$7=#b3ycedW0qP$}jGEMP!j}3k{(wwk;;=#zZ62i-^3D>ZV(7q>_>ULnxDqC-} zX_y(TSt{M6+2U+k13Tv_^^?5_GW3x>ahLQ1&pky#CIe4tQqqzY`jyEpm`Q(C{XrpSv%`&|U-2;mVW_pQ_u{DuJq((+yA6s0LD*OE^N=rXBLQ z&$pE6!8)*ml?Yk1*oN0Pbg~J0g~GgLd}RvXYo^+Iz11xCAjESf5*oCjCHEB!)at{b zW-ltBd02;q5xUi>?%+M09yDPHf@N}>g=&8U#M2~m%?-o|QdMG20Cvuya~DTM?E8bx zj4M`-pQ^x1Sn7xV@lx^?E&~eleNm!kUl7~bo^i;^P(}~J7Z`Ma9GSs;{+y%-Das-v ziGe`!c=2W=K=iH02NJ1Z6_UqJ5XQ3g-M47`<{eZ;kcHxWSAeM8i@82k5%Umxs+5CU z9b*B#1YNDJe!luS10P|3pdSgVR0QCRFrYN9p*lJ66UrqVP&TPtr5=`B3`R2Z_W4lS zYQy?jA{~~Iv1+2J&4dkd$|?l2Cs*^~)ePwYUk5T9pgGEX@ow#pqQg#}STqc|g*(h- z$4kv*fBk#?-{JyJUjpn(popmp9@lLqa{*{AQZW=^GRL$+|8Q?`oRT&df$$H9k_w|C zS}q>LQ(3Ch+k1h!YUa`YsFS-MLMbGqBGq8F9adA{hR^ekFpW!jz6}YcK0r{lN(LqX z=5nz3gtHe}U&ulD?;QFdWGjKn^syh!rZUW32is&ymRD!xu7|4bU}A5xP0m~9OIg#` z#DMroj(FVZLSRSHz{N{EMla?@eHU^b9i8X(Otd<>Q zU$3@lNa;~Vp!2Z`J<&Lz4p+^3XFn7+2WKh=0UKu+P7*>=%A*w0*UjSSx^<+Om6=Zie&&njZbq zc|6?W``c3EIVd}J&EcqAsNz2;!1LKv&ITxIUgX)6HdUh$LHH0uiYJ(+P0^`=q7fZG zjQp;W>YS^T9)5d*Xb$kvVv1Z(xhh@C#H-Q^_6C+f^5_LgWHDtl@t7VxrE&hzl!mH` zq&Xy>1jt~wB-P}p zj-0L+#9_y07M73AY#z`im`ftK`4fcvYc`vopfO#B*ViNXLlx*@;MOMGx~ZA@pV?a} z96nK(>}byz-LUcOX)-FAC)6kFFBaG4w~}AI9anckOa=jFWn9Khwb!aDxj^leUp{C^rLv9X069Z8cJ=}}84)O^$ zx{3hd*fR|Y2E4#Oa!|H|Iw+{ey0jzv>k^O@*G-hxa=-*Fl_pZup zG#3b-EwOda5sMoMh{BV<qO=(N z7ttR>9DQDLSf7^B{|eia^He>9NLDMic%$8Lj%RXtC^pfT2&ZUs2!#kJJX2~F_x{@v zc^9!iPP!fXd|Ez?=zdJ}CyA7-Qpl+t0aXvh|!2zo|;DTDDWsiZ&R2rkS)LRa_-kw5%U&% zsyyf&f2E^H>c~Hq{ZUBcdwXA$hV7n(2Q55YDed7VRuLAKK2v}}dJ5aS0%lfWvp&3e zs!o-5GZ%{M6b3gp;u~3SP@$iilGiIbg3JGD1EC&4`Hx>6*m#&&V(`4UDkgq!Rck28 z5G`EL3ojHdhv+Is?D6E~i~^=Y1TYpz_zcr&*4{nhhZc&p&|RG&4`K4&i;k^ujkE!0W~(fxW^CEEcK+gr5O0Ev-k8l5!t9^xQ{d20BWhY8pUxW2jBZdN)tm z?Y@0_Eb$`jKC@r9n?ye$$8Z!tYVK(y!a9)SZb}R15_l>ht*yf637P0e41f9>-apku zt)E<#^C|HPGnaCL>|P|MwR))=1t~cFuR{8Jjk~EQIPkMLv_``3rXb} zO)?tYS?!-QrPFz=;lTgfhg)@*_8tc)d!PoIs%j=WwyK!4sx6%Xg+b9HeE~>+fK^ax zsw0%pE%9SyZ@yL?gGa9mcm40*&OHcjfZzwK9D^UZ1Gj;4+Mr|eL(~jRP(XGEI>+^w z2>CXOmKRcL3QHymEU8bZulwOXb`lSfgeb4yoQkU7p(|g4#Z6fR|6fc3!!F2+^-l1q z{!v<Lonm`@?RH9I6z*aUr=hI6ymU?0r*F5BbGxu4-t=Oc4h%3Bvk+-1L~fn`{U9~`Fhg#O@`?eb;equ~`r6)_C`y~K z-sM)i$ciNAH-@TUU}9AZ2@+bgxGdf%sE&)t63oUvlPx;=8g6cw_?W7*U?>TM&Taib zYCZ(3$yT-z7ubMHP}BBloK`{a9;yVSLeWM}u3K8sy!*wm%dXfApm1W2R#y^S}bN?mKA2~e}e{t_jv1H(?=s46Sns48>fMonTH zQARN?O`jay-Q%xJ>JEBlkaavflGizl@LnV0_WbP1M&gV*;D{I8V#;YtKbr$l1FV=4=%VHY&+)Qd*PfT=y$lPXT#qm7ogNDi9l0cGYf^Is*k}~IVN4~^IK(`@;|!w-lJv? zM#;~-k1}aZ8o6!R#zV>Hd&m3Kv+rFmzE{c5r>o7+?}t31PihC~^Z>yWOlx^5W991F zng7IlOrq`F%2x8sY54T*E`dJFQ}7psbu$)K@ausRWG%+6p9vWQ;Zy%IQ~9iWhbwRW zL{~W!@f2})*BP|E3%f4802_m-0%WHEHS?kftrk0tnmzWKE5l{)kfyzZSQS&+roH=D zFt#v>a5A&4EX$@=&rzY}%Q`Cav{4&_2Vd$sH|eJs8!9DXu6k00Y^JYm>(#c1LogzB z?ZA__=k~hFcNzJvoN=igLL{L$*lr80BwVH^SG~tu{b2%-dd|!+6(sRDYj3kvni+Pg zv2zrBvpoL$J2D9t?D))Rfzk}Lcywrykoi><6P$(aA)D_fXchD7w%%5|YBP`DUrJrc z5Gj=~sxbs{I&o$2ojbiNp40+CPCWS)(erKtE^W>hFn{htd{!d6ueAxycO+XUVMDlt zE$r`LD-~7diGBvkJ)H53Smk?^6AKplF|ehm4#32a!K>m0z~XZy3utAJzWkXSxTCKz z_cp@pnsk_ll28&9ywDd0e6f{#8`O|8$Br2eG1|$D!m)H%SR}3jlQf*~ClcpJ*e8or zsfu13)iGVLD%oOY$WJi_xJ&&o>y8A=K(MI;!?YxUmxo^uokN_^L9}wM1(kp_HVoQS z(l(Cee%d%uSF2DRY-1AkCR0i=KJg4C!jH+N&nWQq1(eq>>O-4tMYP*Q6mfE9ZW5^P?4_{YISLiCraBY1X|1 zl`fODRq4>F$bIo7?uyvpCpof}e#cemF;-ONLFg+|dJm7ZYkN+fw6n%a)gFE(aNCrRm71h6C>1-Y}c~C`hEa=otLXUm=s{Qg0 zdQR3BTBT|)-NS(;j)2mk|6d$|Jjk>xMY6?3X;AaO~odK6TYAITcoZt0gg!q{AKj>L@VUKo|jt1SX&}8(ZnGtL@N_F>8xOA*PaKv zpF4kqjQ1gAzEtVn<}?(L9~FQE$@4_Lu7)LD#3(#AMf^S6LQsgH%QHI~vTgiS=4xPe zkfwpFmH9`~q9q!e_!pf5(zmIOJ@S?IE+7>0$lqDz@m)DkDTdUiLMaisH#c<}c${#l zyCQnyagcTr><(`uF(pu#8U{%|RiC0Mp5;?>z*LFlCm$sF7s2OXl$ zrKILU>JMMS1+v_!iTg}Y2^@+F+dIS;_S&tv7zTY2^c+=IOz|KnhDM6}Y1b8L&WOP< zWTZA9)frCb8-Gk{m8J?`?gMe}&4ch6+px2Z+5M?a;lnT$lcW#qkLd6U-r+sWVW(wW zhBolYPXaQqvW@ITu7SXDls3D9`)T2@W-n7c`OLX|ENt%Z?MDHdsED4Gs_2hasgGVZ z*{JHjy9zY^_IqsPf*znM%uR^4{2bE9DeK~vn$gvdmRVLNxJOjS= zc&xDvmNg>(aS2@cP-|Is47s8p!Gkgy?FsK9Jl$rkJeY80IIco=taiRjjo zE>FavZ-~k|${i#ZM3r^5W_y*Ye%})!L!&6JaQA%Zt)8F0?zO-Sz%x%ABy$0%Spw9b zicv$ZqDI1qa^ekg985Hn~n)XgaIuUBX!G6esKEPlta+LFjnWW!{WO{$Q37F8*CA`jaK`=BCi*@Ku zw_OaJsr=TP?PLhB@gvl0BA{+Vj%vApf>;hI<|I_6l?fiFbfF!Q-@-~oUv336MZXcr zvi^4E?xsyMye?qyP^+0q3M)J5icFfwgQ*mhMPQiFU|J^5O&lvJ(yiU=>81(u5y$~P z(=;$rNrLP5e^UeQA;$6zcH200d=0+jVCC(4y(;lr*SZ@9pxAf_ijI^8M`0GaAyE@~ zNGABKE<&vJtm)=gG7__XHU@=LfQkSTaaR^VX_(zQ^-g z%`1^*x;~7e-MYXI(BCa>@iFk6CaIrr>BT66ss&JFwfi7-OBl<@l|dOt9GPK50Rq5< z1nIkryFeq(jo=`NHG^y`$oa;dT%urQ`bc(_3%;x9TvyJV6`)((l9DTvSI~bmfg@*X z{bwhQ4xz)@5bZY$6X6~|0V&*3b4cZ=q~jIcp6V#2rh9CWR#i7W!@i^{j{c=U8U9B``)R$)@iSDBmW>0@_R?=vRPd;v@C!LB;TkyW}($>t4Yf2 zsV+pAVGOF&($MGfeFso~_W%W$G=Bk^Rl!WA38X)0>v(@ZF4fB`K)=6!*R^FUOl84@ zUxQ!U5|xdmjclH8Bag!wcRmD}Z-36jJ1X~X2<|=IG+E!>erzoLiG;imoCf#tb#Cq8a>0A?K3>37pE_M7;G|!dIh$9l zs`Ry7ips~YJ&SRkpGAQ88~6{p){ioTJV}Hv5WNO^mw^E!A4CA%)Zd(;A0b4FhEQo` zt+|ghy8o(4`y&}TO4st_N!4s`L|}!+=vYY=3>>6Z8m8Vx7%>Nm1 zK2^a$gG_||)SzXR>`A@(0RyFv2_mcV1lW&2V))=}Yc|z;K`l~w12QS;ndh&2rKX37 zEhGEWzO1D=h*_Y75TFHTbTY=E&^3S7;0!56zk|v^m9#i2)obbU2&su$Xw|rNaIEqw z0m!TH*ci}A59Tes3vs9|yst;L!YwkR|2B^pUu>1_{32)U%*s8B=r>3`G&*mHc0S&VNR+YhVb7VNw@FXtD<2>$Y)HW! zVu8?TpuJ5sBFNF(F7jwA5_t6&-5eX4W88VqjoEF*E`s}rYrXm{jh3#hrbDL!d~qv#$N2RZ^UWM5Fi z1nlb z?8?AVt{PHvVkw@YyamM3DgKKp+3LZhXE6PDcTydR077{az454#nN~K0`d3rOD|peB z(5LR6$4ZXFnb>zP0V-_qFajtVMgjfrLXk@>XbrietfhrpBU9^&oA{rdbn;KU_&smR z8LP1{utMUD*?)wIUY_OFDNUC4?agrHI~(`Wt8ZhZ`{y5y=!cv32XpKXKebI^KmWNA z>6S@PYtbhi!e49V`s;4Tw7P^|-`+Ey?V62iHFwPzXa?LIZGuc+e3|@5V6{g`7$&xh zWLC(e<4)L3{}Q=L=u5Yyuo(TUuRN-QuMvi9RCOY67wk!}8;IjJG4&h!dr^>3M)V(u zzqg7w)Lwix7f9FzlTmwRp)KI^Zkm*nERkkjFrYP3SZV{!?<*PUG>{3_S>594X_C{! zjs-t~iX%nAqQD$MpE17bVrdTp9$)T+?HueUyI(C1s|A^^yo?S6PQ-g)n#m|v#Cxzt zs59J>*fC%mzA8#0+E0f|BYO@fi3grABJmO*g|wJ;@a^V12z|0c3mHEmn))0)9AG}lbH_YiTx4udf(wp#MiYI zH4kK1MD1sr-xIUOuTAH!3D$^BqB32G(l(yrO0l?^Fr_8VcqCLdWnQZ`M8~E9tE=sK z?Q2IrkHyon(L685EwRaR;)Rjv%Cxmj`eB|=V+Qj)yfQ?5^HFz*Umu?&;%SbVFO+?} z`=yYo7tV7kNyH7N0WEBWLK4Mvx>}WEj}l@&di6t9gKuwxV_PruYyL0ea4}+ZyBdOA z-)GdgZc7hjJ~m>1H8Vv-o7<_;_2i_-jpu1=87RKaXV`r)-s?ROhSGn80$*Cu@y9;e z4H0_|JZV z741XA12#AcjX+)ng{B(^Dy9)kKzGdx1$IDHf%Fk7!Su@gmfn+J{B2$G1PrVY8H*u8%+EQKjUw;Aq^xZ7-oL~=g*nU7Ahw0KHPblTAY<|N%JipZ zc&zF#&^ID`S9JBZ@iz}wJ97|k>b*7M|Pg~H55`}N;;@=z^5`5N= zbxPIx9FYD?#P)2g!ClKn!O(szLC`wUBpk~QGMjM@P8y(hvxyd|-o-C0#^MM>e!Qw$ zT>jdUmt7Ug%ipH(pfJ8jHGgogYv;KZcc(h`VDUm1(jmH7UI8j%lx5kA;*xEx5xrhqcBr}Kj}D4hgP$K^|0DbED@3%#?gTp+7IeEOgi3$R;dUn? zjIw;-b?GV9uGZeRS zX`~WLv_^t#o*b=fd&d~O>pFAJ$ACEx<>pl6LJ^ya*#={#Io_D7(AXi21%uWVPxtGb z$4X~*xeppe^rYpKaoC<*@;>MwhW@}^^{zuH37vha@%Ss`Z`r6}*j*`S)Q=reIr0$~ zCHsU&YUst%qJRud%-|D4aq#%%M*?jIaAj zhmT0L6@^gvC^c`?v4cl~*#pMJN(#-=*^2)U3s5QAZ+yUtLgvPz6%70=uNj` zdb)$F>z^V*h0fVvcHO(brNy!=UBF4A-gPo2sB!4?XT_x9XZ9_R7O%Nae~J)1&RV9u z*qZ{Z0@->{ZtOwK6`ru#jQpjt&6{!l+GBO z6+93!uqpfQveGTsMPvv&zU%C&uWdlCDIsv?Cc zeOIf)&V*{e@l9VO`wa>&#Y~3C+GK$Kq~}oHA+IO*&9aIoT<=4a!mYchJ@&d zYXm_Xc<7&_1qDA{+kz<{`e!!1iT+&wE6MIxVs8Tj@AW14!(t0TA(FU@X<_atrY6|9 z3v{P8@TQk%>?LTS=4xY4rE04r8pk-6#prYsN`Cyv%qrGaaVaC zbNVWcu>nC=fae}&p#5_YNYMv-cWG>R@^MX6$PPIh4_mbV<>g*5)VCiOFXhed&^@5O z*=^8BWMV3fw2EQ}-7dEv*PWmfQc}8qG5RJ!*@hVwySfZ%Xe8J{L1L^xw%Z`$4ne%I z+fXRj(I@W2|29|vJOf2QID-~FwU{FHt>H-p~9 zU@Gy|?2m%yXhqJMAHDb?o5ca^X75oA9AApH;A-^7yARvWF^KW1!c6kgVXWhrZYr@< z)Mz>-UZsRh&9m_lvj$wJAkL+|e8eX(R+}wMc*z7){E!FXgLx$XGaA7v*=k9FRK=?MJr0u2;6J5u;@HAUbtHD;k#c!Tr5iyuUz>y(O1r zN6h*URR7baKEBmO?XjM_J&X_-E9Mq*yE@@M9=zmu7A@Yg`{jDN9~P1-sN7!wMJfIq zoWH-S^OyT3Ihc5M`1SH%L#J$bEA!d-Rvb7G7A#DsZa&XSp_}e8BI)S{ zd2qtapGhjPS6O7P+>tlF-&D8A?jM?aApN6i4 z6I+gB&LDGrD*NQ`pm>GnTSoGmxj6$Li`dnui~N41y7IOGls>3{bKY)RFp%lz_0gFxPj_S#%K2HvZUomsWv9`i#>{QSq3MKu3oN%q@L3 z_qxP;`Bf-{j(+`$+2AfT1ojE-jyWYcZGnM543o;ndKPUtDv1=B48%E(&YNB2*2PYy zg%58r`|*0VChFQ$dW8z1ztXYqoygd1j|8}gHCbnyxPt8-tVd!tRMe(((CuBC{ga`n zY4`Dt$Lx}WpO#!YIaekHzU!F^xk2`PUmE@K;Nt6>CwpX-CZ_6ccD8XQPW-j?VevP4 zvhI+|_P@Nco?fQ@#`&MQdFr}sO(;3RK;&fHL^&?fGgVGeg#0QXvT z<&OP2aw`qGuK_Jd-N92pp&*Oj z=Jxv7&!hR#u=CvKTgw9}ao5uJ-A3uAPG!ElL7ABYaSg7MwF#X&D;8Ju zA-WsFEj-sPQ81A+r#p7v1;!e`9L%twO(~YWat*RcS?gc{MO43dZgUp)%(3EEp1pDw zCkZwWo(zAIo0x59TX5CMk4OeEWb#O>xS&ODOw#sqLd+nQtq@N)=#F+J zwi1F{YMM4i&{douK7H`*2XK1gkGmD_t0JaX@GLB)MT~LzHulWfu~%*8F`bNzP-5Er z+Qod8Gp~Htj}2}sm%=zCU%3!xjJhG@**FNiS9TcmvbgFF5#OE-rO-EU&ZA$W zh$9B*=tu(Zj}*z}RvPFMs|x#b3IEPYQz;&Z30G9^w-Y_zibEXB1HIUt8%n}Q1PqEo z1Qbx*x@Ng0x1#Etb6&*;esw96E2(>R#Rls=Q=h9}pu&CT4k~lKCJg040(^M`gA2-X zHtrUiXQ9Ds3GgU~C~I!wRf}y!XBp#b50}lbz+>eLUEz#ouu~|^guiWO_hd$V#2fRm zwtiD93;OmQGi&*PlcVX`nRC_qxN0c6W(>yoKh{2^{fbka7<1h*%aCxott4CA__?f=^#Vw?NdiA`SY zu+546IKFeHyjI)s>`1`TV^beJ#QWoNE;91jlYN08+Ts>x8!S zvOK18Y*Kt8QX((cljvxEWu+;cu^OnmvB4A|A$n>Dzbp6UkjdcnLE}@1VYL*zr8;y( z&o4UmNzooH$GY9Y;zix=#??ki2NMU}{pUQiN7n9Hvgl8h3c=T}u?J2mvhw-C7v`c->R&y?8-*?u+ZzGylpc%x>pJ>ybNp6=1ALe^m585lxoN($M+8oCnJpw!^9l ze^7!klXd5%#qUE~AuYzV9L3b}LKyE(4&(WgP$5qoy>;vF1dQ`WSA!4;VhxHR+9p_C zw3#cjJgtRmqu1#Q9Y6d0YmLMv816wY zd^3Nih#h%-JLm}}lfD}iEgy&&8ON~KVMq|}fo!Y=<5k)~ofIE@%7AsPxHX8WvP(r_ z8I`>yG9|A4+yed25x5o zpk3V`5xe`4r^3U5?2-}HaokucGvX}boWHXu*kJ5Ml>A7A=i)|g!cTMG(+Thb+pZz4Es%jTNBCnx`pcP4+@XI6Ur-&I>~cm zd=BEquj}@{TG;Bia8ymqg$48z|KQ|-om|2CVJZnYn)Gt%?G<1_oZ#P8yXcD#soBVV zZ_gH=?#x`%Z{MSr>9}~G#;;==5(xu#^<26$g2Sg5-v;B((4F?<+OMzwI2%ZNPRl)p z$idmjX9=6={Tsq>SDkY(Q+TXA;N(n0)y!SarRWqr%<{?|RgchT zS@*eU9T6$wzsv&mRG+Idj?VtrC&9!U*Grt&)b^E2ML9Y+VHt~J+6Fg7#YzPJ$_osa>3Q9>bg{t5^V$n10AvMOt8`c+={#W{-BbC+6jx8Rp-)~6#uuOUw7`RkI zK}2&s5;Y*v!nG|Mx$uMAY=V+PHLW zxPP?Uo14g8Mg%axGSS3GLMLQ+*LB;=Qq)=Wt|P)z9h?QTclW-SIf+!3CT9CDQ7Otk zVdAF;c|UwTUSu`=y1Uh99!7I6@ABM14@-0h`(upe(Ob{0-RaRX5Ka^gQ(pcHG;fT~ zKUP@R@cXlqv(ESF%K+Zgj`Sqf8Q8RxS-u^nw=r0=d}oMxy9)3*{(Px4p(?$;BGTDd z1Dmz{55}q(_OIc57D z3P_s>_gX`K*Wx}m6pEOD<&R-9dz$-=f$dxI9>-EFp-|sdp^YbCA-*R$Kf7!clt%h1InFeV0C zwF~u**lX*E?@Z1d*_ydz7f4~qcEIo^-@j^c$2Ir;g8JaRZ8;@k+3SYxg8?f@$?ryl zKS0^8Pwkj*s%N7i~7_|RO=?w+ZTutw7bP==a;|6zJ zS)AdAOV&rpHwOy0dCQS=zH!#c>fb%q!6HU>*qFMkkpN#sw$8y$xR!zE&j_$4L{Wbt zd_}3Yiw9g_7(3-aQ4m}>iI|#Uzx2qX!20ZCxSe80I(e5cTf2LxDXj67v`KNyQITyC zh{`1-y!cE4ZBak78P={dS`gfMoa)P6GM!I*0SR3)2{hl6s}g~ZGsiQUXek$!hUh+t zoD-42Jh>faObUBSDOKANoxn*v-px6Id8@Jomf?s@j1WVYT+R9#*hiWekk?rtqgC?8 zLOQYsm*WezoZG|%C}V#VCKh62^e{7kUhehHK2+KQc^2>b(%p7y=k_>W85W%c;8kRn zP~SrVC)s_>9rT#V>r|3?p7o_lN#>}_{Otg|CBm0N z-zn4r@%T6>zYk?wSQk+03-SwQdJ`BE%L{wLaDfD&&s_Hn=Eo>7R&+Tld(L3uE7zKc z=f{piZC(Uw^h*fq9n@ZQdRK|jY`ZrEllFtpLma$X!{(DeivLUVg-POuafM*fp&}(! zgGzD1fIOl@w2l|(g15sG0M&m4RWK^&bq?JC>#K^YRaIM?dw~U7A>{FF*+F$~d*#wL zbFEuEzK9v0X*82PmBQ{^barJi(L=;!z@Fwm2I_(NQRs9w^_HbUH{O068Wp|LGGkOvWa$JapiTi<(YghgZZO4Z2`yD zoo8Wx4Fy7r8K>ukZ3J4wsk-0u$tGgif?)K~kAyr#v}7jV7nN*=O&OcBd!$!HIeWJt z#{E{v5E95zp3^Kf_orbq4A56LZ83x?mgeHim(EqWlg_ru3c|=~#W54bsa7dMe<5Gk zWik}Nw9OW%29IHelfCw18GKQdZHv8q+&t8~6?gHH{A#6!gOMHZl%HdlV2c7gtv!Lqo1aS(|ix_dQ0fV?WFy%zLbA zeW=w5q$ZA;omhP7+VCUQQoY^rjV~%H*|OKwax*MCT`>lbJZtFWbo?0XE-#$V8uJp^aV!dC=VL+(^>hA3XT>Fa zt4=%Nc3R8rOGkl;f-q7jWv7enl}CZpH3GDl9QzKq(~fS=GTEiJuCh8KO)z#m)j^^eokJ0%-Hjo5=W!MFw`XH1a%13UdtNrzh zeWpt&BE#;+cg3~7GLma$XMa(s|1+rKadL`6+UDjp4-?aW1>~IkU-NTJEnSRimZiO* zLTFBWyv-Zsgq)n5LSx-jt-9S($B%!mJkX>ZpSN}>bW6h}0~?#on>Qc666G7>)c)VQ z?_5pFjwY@KpZ zlb827nOyciXvKw`YJp&*$iWlF3xu9s##kDeL)UG3;lAA@>RgssU*hD*y_2l5GNVUT zKeqUm?J`PQ+Yqas%B%IpK}(IhmV8-jhG-{h znF*l#xP2e@ar+eNRRbA~LKhfew@;tL66ew_b{(IaV3(ZzO?k;<8%uZJM4bz{`S;k`moP^{ zJsmb`FPR(6PSCeG^U~U?PDxS)w~W7*s>S-#d32&``IY9&+I(gX#otQv6yGIg*A~lc zNYdcd539{G&wo1n$9+AX)eJU#fV8WM8*8u;0?#psO*27-qnsFe=pc#a*EzH%h+ zJlO%NMWY({%wF2x?rv8&JVUSIC%Va9idRUhZbMMWQ4!G@$soPEgQ_H&AeSCoWJbsV z8dHG!DZ|hW^QH5JvV_wvj6k{gxv7jOr7d_3FNr@>Dn0s0IS&`+?y#BD?dGz*4@&lSV)%)LlFtTN$FnkTmRwIR7Vhy>QmmgSn~*%5IOui5UIWcy$y4ysXB~=V z8au4D7WNn0C4pD6&L&L#k!WZd4nOmKJPKty+zA)!ED=Rc;xv^s!WDOm8nq85`E4>t zEICr;+T~AS{RNh)^_?2HD~@_dxIp@K?@18D#Mnu%7hqrGW)9C>FFiR^`tgRg0XH{y zf@MQu;V$En=|cmZr3wRys+D3Vk{*xj5?@Gk(3uP$YRyY4DuiYm%HpjZ3y0C^>FKGT zx5_xQKiZUb&G_z$H^qT5FWKD<(Db?PZCwLV(r6> z!yX5khOJq%rmDJ0*WzuQ&%nUYli2w|7yr?Vbwz>Rb;e;QwWkOrP8BhM3*i|H&r@-Q z^78T{VoDC<7G1^uBBG+q4Ph}ar~;Lsd@BYmnV}mZw_2V1 zcuFe@ddIquFt^X*^!CDom3_>IR3b~A<&yEgyq_pp>6={b@^^o39LHoF=A=C!QzEl7 zsm?tJqaE|21JOc^A4uMZZ-p+n3#u{}oAt~d4}M=;g}*p6GPSnBl2~0` zt=Gi=T0Gx`F>$Dp%dLy`(&4Ok;)QkN{wgmQu7tt|L18}AI#Vz_M>ehEyXSmQ^kZMj z9Pfpa;aH7^kwZN8`Nm-wn0a|D)|7`_IQoljXumKZ-Xef}7j;dLv(%&c$9$KsgOyEoU_dN|2TW^aH{|Re>|I15+MpHR92Lc zt&C))?47M+%dvM08Iiro-pAfT_8v#a&d$sp$Km@>sZ*c#>-Wd+x?I=GtE=nvdOp^D z-fp*h%mIf;L2zzP)o~OHFchtV4!sS{+YuCqRy$QVseRKGyM~4aQKmNIZ)F9B-?E-n zMrk7s3vx|H7xGGvmb8qw7DJ;fv~DE8_Q=%xot4RoJU;vHnXgh-_p$d$G+pC-Xl+RiJV_aqyivFu2OR zVhNUZj%bc$E_N#Hily)wO=qi)J(z5>hUwc|PDzgujB3#Rmyd#PLJpri@xhWwVg79J zu3e3rYR-bOlsW$|TuR*#vb zFHuKEJ`H z0H5FYrF;pW=N&AnmJH1fveP==b7OK3CrbTsXumuscXP4S8U!xCDfGhU5bvS<(QV@f z?gcSdEX_^sLNT}cZ&bBV7re~B;3hFQZ#xW`up>Rmr^iOVC%h3q0z=)=k9!PrfL=;> z3CPDRb$uA@t{A(BMT0Var0`mJ`1A)eIwMsEt5CDaS>1Yt;jy&L(~xQG4)K+$ED-L< zNOzh}kM;;cw81tv%7FrIS-ga%jST+|q4vXHfv1NO{s-G2eXUH{aU*%JH|ynOw$43R z0X`WJmqk(m6%&^^riE2s>Inq}%|-RpG!gklKDiz@i`$AliSQGNhr&2v3C?CR6w!R* zAkzX(t=Q3n!g)7Z@CPM{M9y}$ld>>U0hRyw1+c@fcja&gY~U~7U1 zTQ1#Ixycw_e^LaXC!J5jMO@e~5o-}Ua!;P8(I-WDd5Ir9sDA6FLyjUEOFX)|K=amY z4XTKZ7QWGwhP%%3>FxVjv}^87#tTboeHL?k7f>r<3ezVb#t&xDv{44n z;wN)pFi#to)g5H{dxW7IK!1a-XV_}tQ)j0^&0vhfZ=veCN1#6f z^1FC-Y#-{&Jvrtv)m@3W(89$n^{mW!54z>z@kG4n!r?=u8h_wT-)nZsI$spPPeF*| zcHLDU*+UD7e?|24nwj%7*kn~&JwnY)`*?<8DEHRs(V%LN59q?89$WbBm4{o$P|va$ z+`|naz4>g54m4A3tnC4A!8>pptBFONZCV2M;)Cyt~@!l2=yZTZa@3BU)pI`xcmr$4Ddrht8POkQG z4D#^!eG`E(*U#l^EN?xJq2qqeg6VhR#sXfW*pYDYJdHcoB%YtxfljWx5D(J=o|3C& zf0|va?aB4P#s@J4v<9WSevPI@)ADFeh^9W*)%H)Y2+$wUDD3jm8V*@()N)wOp@fPA8JGTCbH16XIDCXFjdAzlfwrU?r{BBmHs`3>vB4*H~MI3^CMwINOto4Z{VvCixbjZz5c^@|@VwWWqen zF8P+%wm6EmB8`R?iD6daYLI8~=fC4d5dWwNXGjj znTAEXqvF;-?DkNN1v)!G9qOrcztJ4#ja7QbLl~cjdB-hp$A5)p8dY(Z{;=Bd5bWy0 zow2nI09JFT3E2HgG9qg=*#88td#5Ff=PLh-Q9pVTlxt?0Z8|!d< z!~0vBUidwLyzlpi?@p52upylGX7Z<1yIN1)gafuTu4V;%a+L%oq`vk%j3D0EiRRKJ zZ-cf_G5C#P*<6?mwg57(ei9BON9jiPC4_u5JNXMzvhWb_hG|-`^>=0B=ke&dv%lL$ zr}b?=-SkRTcX1)>(%!_%Q_s)M2h1ck0Gg3s{w67idOEfd`(=|+NV1cg_e&a{CwKXZ zZMJs5SF^g}QF-U$r}<^5SpUBYd*D$_tm3Sg1dclUvSf(4OeD<{nUijP@)dV^TsN(0 z!GyVo-gbk%Awhb)HfpM)UsSndx+>{vh~=N`@N(Wv-LWhlc?WCmUOC7 zyYEM3m-yQd@zAdJ?p&_v0{B0ad39NeGs{+gVW8KKRN}lxBK2jBhwM1ax|0SNZ)H>x ziHWSu?<012KQ99?`@#6LH}r9i^FZAfuX^`$%bqwM6-sAOe6VJA-_J1+TCkHpyT{*L zF`!(#_vdB*&MQVrY6Z^1s7wpxi!}3n_T6RS&5_w5oULSgw-&rO#M~y5(}=Q2Q5eCA zg5mQ0ykcX7aJp_|k3?6Gv3YF`a!wCBnJ&Xax{|k&Rg3$tbhdpziC0r@`AXF6LZ%f9 zxPHCJ7R-$(3u-+uIM>Pdq%HZwj>ItP)EQMn)cU<>H)4vmlYCuk^_PvbknhC=;$dUF z@OJJ6kFX-RYQGmdL|{C!DdJS*t(}sQNx2ENJ6OA8TSr}h4NUB~sH4-)Q0-WZ4%f^2?}5!<*pBsIFX$w2x5E;%u_(^?K7( zy;BwL)^IK8>KlK44qREmd;hbfczo>3ERTIaG%R=u-q%NhP($Da`Z!Sw2F!h2dl9(w!hrqhJij!7^9`%#@wjKRa|eiwO}F+o9E*n6RBe_fA1rXR>AEp}a4V^C`|dS$2ahINsPxua z5E#|fVNuC`>~KhMd>rGA3rs0d6TOMsJ!yFHWQyaFi+49ZWo)e^5EB_@m!$MpdWWT3 zcXZhHdRZt7A`$FXvk@)sps7lsSZx|+`4nTvz@(a zuI*MHEGV3RILiBTc*EU?0I5^4QhLo~?d;*VIJ%V7V3+~n#Vz+jD8ep@x*xuTy11oN zYB*SxvvCpSUT(OYnTGfEqNYU;5u7QbI+40tSpn#UJZ;1~DjL4t3C&EE-+7e1xL#VK zP{G+83nm&hu@xgy;8Oc`O#<_7N8DQ5+D9QDmO~#W(cqT}HW|j%$P=Y$j0=($i3_+FjFrPfRzDI%_;J8kJ!FZ)`IifiD{et0cYYzd z{*)j7$@Y!4LE~!K$!sAfD~%|W4CT?8D5#>kiAU+XAO9>#kV2&&581klQCU8IhKx4w zX}mm*@$>$2h04dm@djqStBxkS(ms8}JB3=+_yH0E5y;&#ymz zS9|b)hEh*iOLb898koB60uUkp4OKuM6T)jCiHT$cq+22*;x4C((}+Hjp+ve91>?cK z-8$Yk`NhKdVyGHs@&)5fJVYc)q=<7(9rdZGKPn+c@Ox_x+x3g#8JxI!`ZP);{~IWJz02N$y!~=jMbp3ZJ#*7 zZ<3Ny7S?Sn`CSBzS=_^Ec(d6%4VmYRH@&vt$`VO5l_k|1+{jPP*{?0q6?)Gql#w?hVX0zLF#DvS0QCcXGHyxT=>W4^BE z6*9L6Oo;p!3Q?rC+ApNMG_$q%S6Bwj&(<$1$z|^-CHXJn28au(WRF1#a_|cLEGn&> zzm`q~g^hpR?9*#&V^z1P9w0J=yur&VTE{TyaP3yjCNfuB^$WIl_m1(l)IGMTkKdlq z5b1L{UjW*fZ%>Xvwd*xFG39`>x{aB_x8L1Z+qwPR+k7OxncUd3@D%)$_ zpway^Lv+Bt`|_}gEP&sxt17^33o8Sjl{UIyvV&(_wCDvJLSd*ZI(84_YOVQ{eiLJR zi6N-zEMTrqW94Y&&%Mw%qA_*lL&n@aB!6WGP<; z^kg`(|A(VL&IqaiUZQw#>+xBSUV_5KX-yKlKJ(;6N^P+5|8M{!5q5{J7@Kl=&IOxNru8NWCr!o>J8N6yxaM075U)h`M-B~Y5nWvhnQ zXm20xG~uSkC_ROX_C$tX{)HTW@wRrFQRq^E)6)COD34;51(wqHLXI0706^X;0MPZaXof7G;*`7xFt5**{#sAcW!^X`io8s>YHL5$mnwe0JWK(g~NWtihcKR2dyqS zN_!j7I@tlevqillQm=qP^?yo4;Ge%y1NtoM+7I}S8-0TWq@3P%GNoDXIo0_fA6V8E z`}M~-A!??jD>vv^Ji5}ak7y5QHEx(_jh?1%a$d%?(Y&3O_K zy?xpHQGY9!h#v^%@C{-`3aSaPzvx)(UM3M$7ho?OAh|Ddie-T**cSgI;R#r32-C)f zuuqT4?a)R|>x8}7O^>MuhQPK9Ej??gxB{Aw6rc(Drz`ePO}Frvy0%?z05A;(mb;b!F|t`)f>!t+z5WA%KMi;R>!C~~e`5$D~DZ9sBnc$WmfX6_~pI@$*8Rr z6IXLqLqkKlVTlOs?ATq^T+K|z*Ey;+1c_T(^2Z_^;Ish!QX0@O*D+Ot#k(wAga4ph zUIf=RfEj~KaU0RoEJT1@bOw-&{?q%Zu>mB`)}S!XkEk1%^OFl^ZxGWzyx^<7`Ef#N zH5IelT z5tB*ZZBD`lNiQRADy;w5;kXmR$!FxZYT#OQd~{H7VC9A=hPQAhu^C{R0|D>c&!S-j zKvY<|-QcS12a$u<|FmjGZ`?lm{-){6PL1{;JPgphHnpt8{@X?@9vk(}v4|6!&q98~ z@rh*{w}KwV@d4>wV&Th@Ckaz8zRJiTOj`ol8l1CZmQ>g)BaVxull3&6nk~IRB{SB3 zKB3H}2z$tE(tw4Ndy*oU>$m;@sHiZ3xyHx1EQbv#=-53+psoEUMVc1}K}d~2%J^o= zboP$R93MNZiTc0YZ8mr^@O?hMU**&fJ52biplW zG^<{%Bh=Fe6RQ3|gmcK!6n>zW0c|Dt(g_ab&wBnT_h%o&E_t1d{$(ryi(KBqkU#mF z%6hdJ=sD(Zej@5TDTjbNW}H(ya*nTI_Z2xq+zb6KfuvQSfcytLWlk183ds%U-|E-* zY&9$SeC)k1QAzzL&Iv@RGg1{rF6&~3FBd?e3y@2>#c%0mC`VA4$^Bs*}{d1m^oBZRQ{$6do zC~)vnFY-V9y8$1Rb(ZFY0`@>fbq7~Gj4dE`{D1+yD1Q$#m}c)``$~y+Z;PYb!Ia8+ zVJi9_9BTb+*3_SqGW>>|<<^^i#U}lK0WLp3M|cAVFqFneF8%YB9;~Dk$gv&WL*jtu zsttND@3RV&JJ1^<_JA)eaHG-nU}~D=Y|VC2571jhdnFzN*!xI5pnafw45~L=L#cAa z(4K@Sf2D_N$3#i`CE0&B;zd;Lt{C~}5m1P78otJ6FS6-!;^==~X+QFC$1W$`S-@iF zmG3$_w0LJ;VfLrDFRZhSd5q1H1_MVpEQ|uJfx#+s6kg8M+iG7n|M%ooH~!OXbr1uyb=m0u4B9By(Am$n z@H^&hmfZhA?>mv*0o=xbS^#gm_>^W>SWTp$;5az48+jiJa)V#bP^AXoX0u9XBab1Y zi$c&V5@%?vA8rDg-G84=B{-W#D!w1|GxShH2Z*0>iE*t$CV+vO|6ae*_=jZQE$orc zl>2V)jo{sHXRyE#omrVZ~kgNjIJio0X z-hb|hu#Sk%Ha(kn3uxt)h#xu3eg5u&hmP>PE3UJh%;tB@)Nxol)`4;~FTaVl?T;%? z7{56Jd5!PAz?9lEpmY15R+N$nJm36krGMco_{{iOKp^ti9*eYe1WOYqKG_s%mXGHWpVg$O3WfqZ(Zg zH=GmRrj58dF}r-JM>mT;7gfrp{MoHO;k5YrgYwd*%T5K_yYhJ9fk18hwgfm|cklqB zWaY@K(2b4%w$5u{TYb5U{vC)GNSnuV32Hx}@TFSu=`-?Sb*GGhdB3-Q)M4`)H$zS~?YPtrf(^?%sEE(->qp3mX7Ar&Sxvp26&_t{1?2ql2sN<1lpbTr-T@ zsr<-^WUaa@zCCgW4N?!vc@2AWO|3D|M_Q)ecc=8e10AaWbg}Gn#5>55ec{vqm}CJ7%ljH0O7?48~c-$pR*vzDXVRghr;ji~ce+DJ7`!V|@W ze=wV9M&&c8MY44EKKeU+aj#XwUYC7c1-_Ol=Xv0j4odAo<3P=Wqrq2IUud1oEG(R> zYlK|kQ5`X60fWc%2rwo)vLd_(==H}&S)d1&H^g<;0nr)?f?Bf0s@X^t*hc3cX22;A zU7QpkEo!K>*E%hRWUag{exZgtn@D`BD3+X|Xp%{I~bJ_}I`a?1}gJ`56EA{>EowM+#ixVq3AT zsw7vf4)EuSayX zlc@4QL2i@8zqsUlf&~Ei4tij*K$6C)PR5i|BbX@U)bQwVuzPrn3=0T#3*9*3tx$g5GS@*agLD_ShKvBELrvB^}^Hr(ep5(7z zY)=~pW|KTdlQcSB;)}>1-`~dvdA+PYKpKV8+;$^U$Yg(-&V09JOdedEYr2AT;@5Ob z)%;8kl|$RKgqD~63igrYho+m51prbr1eM#7)Ju-YVZ8}G8g!m-+JpF9i({!*Fj152 zk~7dD`3@@DzY|gnOc0p!9`1(U0}8t&TR<)7%xaC>f5s0B0Pn3{lW_4b9}0l;gv_!p zI}Y2mRH=;Nv_s0-hnjjOaz*9e?WmM9-MCF`fnQ2eeflkUzd4;ht5U_}D$)2Ari#g4KkUCae7F3gnr3)$WEB~ecEOS9mSiSE6rL3UwVHfx zpm=9t@@V{)d)7^^Oj~2cdJFhOR2A8RIww0<6dm6sV!e<@?O93PhFr~^$AWHKD|T}X zR6JY#6ugsf(SfEfJhD`E53dqQs_9I84Az~$vie7n2jtdrI`b|rfD2Nf41ZkyH3Js`jXtB!WXwg+1zEqM zIxtc(doZ~7Hat^7myT{lgHsG@2GJfIrZOTr!z>+Gl`B4^wpgA!Wq7out+$>;(@~{x zgfMFQ{s|8~8u|!CZhlImsqxT>(`%#qST)%Pp@p4!r;sU-ZKGiMo&hrh{EfDWD-G5#o`#Sp~C**u5L-RQ!nVNxxI#(q( zgXLPpk+jk+tELP|7(^Xu2V$ks!^2m&2<>d%VmReGHFpJag?%qwZpKe+e6WW4+A($L z&&w5#tlcfCxndLGApNBD2!KPsa#vnO3p=`81qr#v<3VqUl3~_kQ~sY6e^BM4 z)Zd7bL{CycRrmF2QqD_IeMK+Rql}jPvn=H}zD8&BRk19&M4;db8t-ckLpbOTgJgoT z704(JS7VcqC4<=l0#;^l+TlU+L4{jZkmTOH(X0`Z)Nr1ogOSA@P|#yW*bbs!wFAs_ zB2HEQzMw01@5TT+|HzyE_kOD}+}`?1)YRUl9qW8}!V>-8o<=xPxGTf^Dq=bi@NH^iu&o%lNNhK{8}>>-@tE(%DMS-lta|g`pqter5nM>2)o|rImvRDIj<1gf%rx967dG)a(_E6q6`EmYf@|-E`T6WdR4q+ToBEV z($)xb2{1>|g|07vrn=s)JJyp#j^93%g*45)+~in{OF=>+IFkZl6gOWn|6hb~0!%OB zfwP&!4+s#@clyB(UejeD;+8jC1@j_g*uR<8ko8|AA1$Lz7AcM~rzraC5QQa9ho4bj zGUxy-sW=QEX2YGOL>_5SFc|q%HxeE&dxek}-(#~tXd-pT1R88OO@*Z1t6GA(jZeEWF z};Fgd5pJr)2Xdl-fO7rsO#{AFIZJNzoyG8aLCAEOSd#@eH;m2c5zJP8HatIb&v zFX~N)#F3ol3}rt`Nv|b@^%YqvqZLOG6pELik!Kw zLUW#!89g!O65)ab#;8ecn37$}RhT>ifydC;SZQ7^oB6!SNc$+T(v3b*=B-5R0#~RG z`h;e>P;T2}*pDK!ST|f({N8FjcK|#NbIPb<9Fuw6@+d5$MM(=RnOZ!Xa^Ehm^D`q7FG!HN9EyL9lXzb%%X|n!ZtVa@Eo^eY^5>IEQ{flnf zI6bR$cz-CTWUyp-5o?&YFRtfO!^Jnl-6SG#UinZeg238oZ0MM{2-I55RPtp1e;cN^-9myOBLXu?E04UZQ57i0TMFUQxe1aq<$t{<+f=Iw83YiEXv{W*PM%nh;l z4XK)!-}!0^w&Ohk*=~6iHTFMF*5lf>ABz>s+&%>pu}#!}w*+-1v*f%Nr04U{)$dbR176i+8q7z(Ve!%K z4!yy7C_6XhF-uY3ZHSiFgurULX4if6E!?}RlUsgT-ENGaa5`knak!O9o8U<9s8EYN z6aBvWGkQ!#R^H2%jI?39jrdF&PR3GZ-CxjBM+j@$FnKYa7V)u+maxU-_&L=s5j+lz z5zveE_&*yn5q{wYL%q-2y_Y=D`zfY$l|H-Wx9FJN#rN&EJ>IQ5mN!SP7lbiHQ9mWU za|Ozfw({K1ELnqN2`9N*rpr<3=13}O=Z%o-pHc{5biF>ek;#n{V)8GkCMhx-&%mGc ziWqt3;KOPV#uF=-2w{8x-!ch?YP_)bf@Y5I`h5qiidI`@^w)fYu^T0KM1WdFRyUFnSykq0X0E*gshQ$8WLq2x=ab<(=I`Gk0zc>-IN*x-$s96K(XH{HnPrqcV@ z5k3Sk)i}E5>LkR=C8M%s@F3{+BXiT8eL|EgF%OaB+GYMY=ucyc;0seuEu2w^p#MN1 zZ)-}(zj1h6wjKSi5Q^)}J)pVo+{RL5G~kF@?6Kd7f(#Y}{`%}$pV~@BJ!ubrK5_LkBwaI*=6bC=)PB9 z^M0>B^gVb_1{$`V5r6N9J9cQa@Tk7ZUPa*bM%K`ZQgzAkbk+DgdavFZ=GrJhQ1j(wkP|N%}I3zqgZ=`5_{D_ zZibiaxAh0VykqQk8eQymT82QLJqZx>*-8~GQeyG_{e9q<*(l*nz~tF+S<=B-@0$4AUsy6A-AsL&6^QoopU70!MlzkAP)%*8?SyD^jOWuFBe#iX}Y z3S4&RLGOxISG^O}*)Uo@+2(Bc;vsxg`#@~723f&m*SGH-Cp@L>R%CsJ5Pj{9=Z(2E z9kZ&YgVe$!E$p!(EgYZz`%Z*BI^B>K_}Y7|Ls(~BktIEc9yDpk21msnb0hZQy;Z{7 zx%c}%j?8L0N4}s=8tRZroDrFOKS1+@!*Ka)r!OrNX4XNE8aP6Qz@o9hw63AxxcJ*n z)gdT(bL;UoH5rkH_Un(iuW$=3ZhMgq+*f-pPaOhtrdcV)Pwjnk@HkNNj;WU`j6SQ! zTxEP}|4N};7rp0_0i{X@wyFa^mBhA-XT3m)ZuK=a9BsXve1Le7Yo9E ze0e;Ou2QvUSb2+F@9hGt2~Sn%dc+^nY8V^IVvYvK-^wv%aF6uuHHN#=`j9R56{}&D znZA_dFmN$|nQYsvtyM3NE>5ly+r-&E?fDdY~0G%uNV`v4x+chB$E+) zFdKt83c5tYt(CZ;!dz*~QO2Cv#i{6S-mIg8QgJ^vL70?kZI+|xS`rp%MS z&%Zkq)Y3~=y^nUcgfT<#9|vZ?^!5AKN4aDBd!7n@W+dgJ){=MS)bOJOq2aIoOQ>&F z@04FAkmwJ?>GB2+Yn@a)O^*h0#dl;ZGNf=k5TgGt{fRtcj!-qkLQ|KD@J9A`j;Q@gYA!!e!1jeY37O1o8nYjzU9nt)L$vZRgBXxo6;MXFQ8qaA7MB%AqGQz zCp6i&CGV=c|C6`9ecK^*T<%wrN2cgnTNwh{^wb}Ht$f0>p#Mek=BUmYt=QAB#m0Df z`9Ohe&J_a8k#7#Anh<`V#n*iHXirFDZqUu8*W~Qbp4+B`%3kN{zc>3U_BpzHcYy~i zbe)!X8~V$AkcHI>tMD2=jkc4Y5C1yCJ>nqOAN}lt;ijhr0A0GJZlBJO#mi)?!kLf5 zjI?3hR*0Da@t&f`WqG7RGfcNd0l`7MoA&Z1@e461U&e-9>+>-Z?m14?0_nh*4@bmB zQBe&YCS6DF1hIY8oeijD&n&5$nc{xzY2{vK5h(3T!}JWj3tD$nxkw;*p3C?V+bXAF zbZxVJFC;#8aEL(DEv}-+)*yqyLA=sXlJ)u5`}yPj*v%N9mOQ#j!K@+@Z3Dhc(v_#D zjXvBzQ~NQ%SB2?<+4bJ6heZ<6XZUU=d!2^O6*bN|)7UvsAC7ET9=*dx%)er5SV4|) ze=EdYuB_Q-%5v@FR?N}EKs&iwSIn<%TCY3###O00hLqhn0ij5>BKFm8p zt2A$UR?IP*OUbx&@XvlEsR))W64yx(wrlUL|q~L@9$_CqcFM8!LsnetANfJJNa4;i$Wm#iD_q*QCln z((?HY(2O<-2gWR$Jl|Qt;7WThdM}~YfUSxwCa%IZIjwE@c zNS7>|S2intwG)IY!gPKNSv0n%zvWuEt2FjXO$9MfbX7CB2rr*{hWF*$&6jwWm1C~v zz5eSV_(vYw&QW+pCE*WB5VLY$JCb@~9HyCU zIksV$I`?(QnZ`}%nh2bKujNZMYFjdu(>RsJ5g!72`2PgROZ4ZfCUCw~Ef)`|C~0rf z*}EZ2iWXHLVqU+E2a+F-*~{^ncV8x5xER3u)w+=&Gz30D>xW0T$Bq=8Pr6V*RJYGF zKwadn)tF&^!H_C1OidWOK8R(%mFB_jNZd^b*Lvw;-LmoF_8>enZs%i%gWQ+PVlG<2 z+?iVRBtBz`6)_ITsi1D)R->fh(R<0QBp_&SCjut+A`as2Go>f`^!K=siL`t|gLfs+ z9hs#i*nXl;OA{v^tBB8>gX+yN`Yrd z^Ab;KA41HV4HGn4Aw1{xt!PC6WVJnpHZ!lUUQh&%(|`7zL>Wbvs^f~n-+EUX+;%_<-woy5Tk;AF z+V#J9tyQ(Ejp$~R=v$n7prI%qxXkp5C0o;T3F&!ir}JT8QJA)WHgYACU$v;pZwr!> z{!j2yg$;FEEID5_FIJQXB0yRY39hRZG4s-4HqqbQOna4+bRpLNmdOTqG}Jw23dlkU z)@C^M-lx-x3@X%1S#Puja_QiejHYnS^r^^p)#%kq23sZRv8Af-NqLOsSrw7^f`@AM zaSrM;`(?l0Nkc@X>YkeZiH*EW56*&AKVW@-s_c*10a;Tpcrtq$VS4Nt!C~qeNCmH8 zW%V>$!e+wJ2V8UZLkY1)y}ZG~OwQl4nuAnrIK{7rtjHPrLiiU!B0zC^R3R|LRkKMq zN{ON?*7fPvzJ^x%xz>@5sJEq8-oI{BLVTRG`1CR4P}GxUn<=3rN<2ZCC(fFnB8kND z&b==kRjmx~8m})mD$#?zN2PdIu$Dh>XOOIvp3a5|n@ar&cnYo_2bGo`js_e{pLVIq zMaZfHI{H!}GTRLol~2ikbCZWJM4=Uy^3GsSs#|>S#1nk%l);p1k8`k7Qv*Vm0QXue z$RlmufaSM03{ZmoxRrLHg&>dt%ZHw_- z7{vOyPHJ?`Lq$EFrpqMK>EErpCQUqEExj=dGG}^{zC@%)m~cU)c*!~9iyEmueWC3` zI*W14C}<7sqW<{p5Z5=--L%9GQeyD?*?t&(SW9nr4CHP#mp6=>(URy(?6o}O=YMZE z{(*rkM{!a(EZeK_J!g2lW@sZ*v&88p)%6u@l!1*D_C^&Oe*=4Wz$t_>BD_KU71{8w z5@)S7adXhK8LxG$Q`JR*JF~6G`}%$G`(xK${4T;R!Y2tDORG#hij374w?|kn01x(6 z<7`ANs-36NrtZAlUEJ6ruf$;U*zlqQxt`7QuJWZ)SXJgkxlHrJZr zIGP3KszF?k$%xXd#4nsyHGR){a=l|WVw*v!Eec^P&u(R-7WPzC$R;jNmCHlEDFDJ@ zWF<)Wq5o1YiotYhcp>M;i`BsdJJ-Cwf@Ylv;OjdGYB;eG(jS+f1ZvI>zqMifoymH< zq7xQ@CWLNSGTMZv@mif=0W`1?O%7yT#uUx2U%1Y55Pd@-=|0MmK92JK@BmkU`TZcy z;G=TWe3$gV^b1D?lLumHww|+Zc_EC8gY+Xl`cXc$>)F@$$&j2-d%9IY{#S?MqZiGc z9|YOI*-F)aOi!0l;s4I_ZEJo5B*LZ#G zbl#T_zkFNhJ7ESg!7;VyLO4NgCOlF8y!H&c{64H{22~;ZR>q-h$4mMAg)p2u!Ow_{ zlJE2&zco(KKYL3xSsIiVDrI>-#Q!)>)bF98>py(jy6h8K-e?7`nq6SX2Y<)1E&zK&4Vnpiiev^8I3HsIO% zP|?{VYskuGk0ZaX`{fG@Nte_q@0!Yp6a~4rK^-T>ss-!}hI%bC7A}yyvxH%{>3{hu z6-*Ga?qv1x19FLc$4PdmGMBU%W9h~#|0n0=m3}k|=E|x}jWCWYz$rp+PWsa}oiNhuU}qaRuzdXZ9p@ zl(40djL(LI6f2xAqRv)!koV^pUHuawGBbHd;vl4PLw0bU1j-V^` zEmSA;vF}O|J7N=1HOQ4GWfA*s=>_BUU`c|NJ7f7YFjP*858QO{KO{ znNFrqQIWf>q0z;scSKL8GUYr?zL(Gb>%%{sPm4SgmHep{S&q`Uz#RPSjaO&TGrJ-v zT{3`jLtsGka)n%*Y zxDfs@u){kZON2`*Ql?LLbV@3SHj1E5HYl04;$6wvIkcBg2=ch4`)sSGj1nTyVrK*& z!DR*vVm-0Ii{SEC;}pktM+u(^-A+)PZ+IRUJ2tge7({X3r{tz4%4x9;l{U~N9a zUZ$%zJQb~i6S?laTh_5vg0*Q#>}MA)r_WDLznE24?aUT7!pG|rb@5Bgi9YVN4b7m zlMXb)4Af4XdG%h^Je?L&70I?K?PMB}r_OM_L!D#xOb}~*?w*Ng7ivxI&qR-W_h&Orc>(Yb5T$f;)~7qu5tV? z1!&Cz5L_`|^1vd1;oO5}(K4C!ZPSGqCYmvXmk(vtWNGFw@Wl@JOBJ%j8a)o)4ih?x z-7pNYV5lZ*3Z}BNI*<<3gi*ceqyOX7aTtJ8_aL`}KTV?LgVZg>VV?_dC%HL;6SV2# zMCZx#)w=E~MJ6q5LRh0v_<@%3CHd8T@@H1fYn7+&Eo`pq20pA3TPt``s!C@$^!VVu zWI+f20|$(UPfQGipi#F8RIsNyG@h8Vr`yfnn;yA1E`)eh_v-5Xf`=K|T6CGS+zvwX z;lx2<~V&#r= zRZ(=Q!0MJhIlT%_A^${gZFv=m@l0LEP|MCW*OkUv#AA_duWeOLgcd`D#nS_a_WZu6 z(>wfGmX4X5KI458KEbtqgQ^-+RQ@a!w0|2)R+duX=B`&~KrOR3} z2u59R$%_zWa@rHPg`5imX_sm$Oe;5^tcx9&TY@+zfKJ1_)%DZx@YFMWSWHRv#jkeG z5(tIuD;B8vfW$R_yPxsG@5@93tusQD&az+>npV%rWMY%_1E2y;qr+&SvaV)~EG7giV)Mrg0}(DJ(;WB*V)6#)S5mC*sn0FARA(v~%;3ykF??eX<-2;b?7L*}iw%nsg z#rYUF^^$1YUkSnS)q8=Ra;upv$nehBq8rucdJPHdmPQC+>#og}g>Be~<(s|IoLb0P+@S?lj{*^=?RYC;+*EDfu*VVFf(!QB_O4~Gi#Wxvp2nb(TY-i7N!m;IGIW_u^OMph z48W=#X!tX)C>rU@IC13auYEB3%4s0vT;zko4{&zLe*^~99=6U#T?uoQG1oBYy6DA= z)2z^YY83{-I>r#Oo9YU_I#y%0|a1Kr{kSo)r&UcB748nSm?_Plgi_*JS z+Iy#|JhB2Cv`$0S&cYZKzR6|vNq!>h)c&V&r^~Ta2wy*sEc?4C@OSyw3mdTlie~di zwL}Ujy$6Umu?=#!eCttZ!dZa`*uwP8P95}CR7;JoZk642+4AQS*M^J|l@Pg~IQ&zb zc^?l2AYamOI$r*~o%EV7+f{r^Xeli4WZp7BDn6pUzwDPGgY%zy7A|V}V)09+O zPS&HYzIuVyy7(reW@NCC=PoQRm;3+G_0>^PE!^9*q;v=Z0}PD_NJ*n~cQ=F5 zh)75?gn)E+r}WSu-5@0rLr4qK-SHjoec$)${jF~;*Yb}!oHOg3eV+a7XFq$-v+D3A zzikA%`yLe-r!FiEFY-4|`+}hIyE?wZymMCL`_!iap?6ziUX@Az=v@hcfTm#Z)=n2{ z%g`^^Y(QQH{t8IOx_e|JvHu)Jk_jBuW4xL?90lF^G6pmM_1e&@C~Q#*43qDR6KOLA z%$|E&yNbxpKKVSZ#|rYLOg=~rXO$(;dMT+x+AC;Qdh{YCt$xRAc{L_L+7OA|lwY{Q zlO?mi&Ep53#9rL-3H`c`z>~qk;wAVPFTT)+;PPuV3w8gu%5A!fjUs88CQ+Z;nr9rU zZY!(8@hm(zE8(c_w7f*>CPDd~d67I6?ID_CXKINpi-KFose)q4-{V9-was5#MR!h> z%Z)sBvPIY~A;Ee7?5y&trjC@wc9-cy(o$*K3iPZ1OJwWybD^ELPSe@I8};f9d}EgQ zda%6MQ}mJ-ehv$O%A9re5}pyc@Dg|K-Ek_u9l0?G3b&Z46)j!#f?Dg5*?>+6#d)!! z$azO^-mkgMAPT%D%2`+oZbPa81WKm?xz(!>0Wm&pV}oZ7sFnt=mh*4J^**c!^iXE` zNYNM$twn;nP9Uo)Mm2YN%z^pElio zl&Q73P=c4gQI?LqjVM0xqR_1Rn7VY>zR@3;5-@9!`8+|;%|IFL@j{V;dg;bupfZvv z@H(#ZQT$D+sTz%1#=ga%LQwjOya1tjF0!73T2JV` z>a@1X(K26`$c6NXYW?EM#a9Up!HUk;cm5$PPpz-yZ{%1)ri!0VK{C^xg||M;jl5yJ z4HI01G3t+aaIKpfu&$0ohyHLnz7e)K6mD7(X>Tqdv1mD#+APaVDNPuNiFGt%{SBhU zkP2?qId(Hkg`W}MqJAE(sQAOlqr-qCP1_$K6A^!2j-v*_BKRbqu1KiAel2WQefPB` zR(pci_v+kn(EOY|T1I?3?-eD6a*-WKiu6MjAA)!s4BgW)`2HZn_DOji8pYH~ zK&?(KiTD);;!19X&MJY~xh<{qM;QU|Wqr=4XD7OP1YVqeSpwls#2Y+HQMG8z8s7SbWeVGImJhQUe8d4o+!eZoE5k7H1a9Ar>hk8j(AxdPm-Ob#pBUo9~UNy!^XRW2h=37PjE+~gdfWz6t1r`i1iB#Mr^ReJ4)K;n6d6idel*PdJmxQU#>}iTd{kVl~8ocql z4e?D4U@4$_a&PYCf(h$$zvOrO^@0Hsj1#zja653NsBs!+s1?G~o8J);W5NpVe@F{f zm*Oh_a_da`QrGyWqq*OhfdWaw+CqCWG(PT{B}0~=J=K%vr33_PJYZx zwv!?UD&h|jj|Fztq2I==)t6*_JtgPipg?fx=?sx~stnQLv7euy0%jZ|Qc@dMY)Bf` zC(tTxR?+#qn@og;M5$;?BXnB#@-a6u^WOBSbKh;K^X#>JzL1xymDJ9LZZYuCO3k)+ z3M~ub2_NrH3dC&qs@He49SgEf57&rgB*8Y1k~21=1V|k<)kf71sg68B)KeT~D7&1a z(;lyq=q-mtkzfOaGYz;bOm)zKH}i!c%qvAhP$uCC`0J0+#BdrIX0z6^cm9ED{vih{oW8+>U-F;J0U=EUA$2mu zwa@}uU#QQN|L%vW1h$K#z*S|dcnBfqvQ<6a5F^OH;5gPrSc!*AvzUU zZj@OqHdW&tVo`PhBsO#HgIcs*Xf5FEskSJf;`pKkA3Ra$s{vu*Znu?Y!Z;~wT4&n8 zopOM;HXSC}`l2u$+%?D$G9Zk*nUHEZ%CPLkpr#_o z5?#=1N84Yn$0#t;^#kS0|A2Kcu1~f1F2Uo8(QPZ)Xwy*p9OApWa+vK~&M=+UyZH90 zXGD7qlFP0cWrrapxRzIvzFT0gnL6izY+g6cmD9Pwg3A2{Oi>hv?VjIsD4-Ag8=VFK94P#GGc-PJu^YDl#Y?zC^c$EUUBEaSbt1VZTZz6OI}LP(}XA1Vea z{Px@`86iy*vI`q>AR989Gu;*}ew=DtA!{Qg+Y^KC0dwMfRELjLGDlLPFLn);y#5$+ zFe~JMzb2t~`SQb40y~zkTm1MC`YMfpS=icF)6vjarW6ai!3gCeTcL0f*s%nK*amsv zfy7b&SyN}Owmg^Z(ONYjLZP;AS>0ROGW1&5BYY!&i98&yzzp1Xw-OP~h&4Z*5(7S* zsSjvHI9!Hsu+l^iO5!Dc(Lv@7IZBUIyo=)f52Q$`CZF-kZHgWve$@8r<`=K?YLkq@ zHDVH3Uc1^7RWjZFiRn5oL@z#t(fAX?pj*h~b^|1GxI8!=8M^0Ne>wT@CkcEgu5;g5 zTTp)0hU{={JoPVE*bz{zgagUS1%&YZ$F!KFkH??F{znB9W}p-EMlsejT_csyMjjRJ ziDW0(t7>$Z-MR!Eb{Q$izEX+~ODzVa(ht7k;i8gF z7>;>ecsNRY%`b$cENpiO^I*$xuJ0hO*Dn=ObEyTJV<{u0KP48|S~VP$Vy($PstR_W79aU+ozRM2Z{r?(KWyT`P~&(GQ^_djD8&{*r%( zFjPIIp2>^~FQ&8j@VBz^fL=_Tm&T0@19o|=kOY<&ciBfZVu(^=IeXReaN8k`!(hti z(8Yj3oHrAj^_VIidyd~>yg#Hym+KecanF>e^W(d4SvZ`;uBlFwR&+TkZ;Xe4A88So zS;R`rNO&q{D7YXmRq^-6XkfL)ej)MDPFe4i36(H#0cfgutgaIeIkw{LA*cZ~@y z;x2ed|4GMa33V(1sXKxPb(!b_4R`PT>w@lF<-<(B5U5Q0> zb8L0+Ak`3EK3s-DC3h?8_su09?V__Vw<$vszI*$y5)s{XYXp%)g+SM~L8qLZga;=D z%yK2XIr1ZuCXl5}!(!Dwg5NSa71GqbTsNbLnn&mNDZZD1`+wGd0FSK<*QPb{cqFE6^`1n`TWU0R{;4{0XO&vsaSDoEuLgr zm`(`=&VbP7qW$a%V5L(3yz`fB<;O=rQh^9Rr0xIl=+$kQd~g|Ee}T3l!oF7qz7d5V_a=LEYOpu($|QyUv2SE61EhaMN5GL@T0HwzZ3azwja z=lS4};qsp0N&Ci=jm^6prUaXgNmJmnYqw)cBvEEy&v}mJy#G!c?6-5QNf6C@IS9NN zd78^78Av6}9@nEDz%$8tBg3_mOBZ8$9$MoOYijYxgNlRgkxLwhKJPtj)uTLB!<*;l zI+3{pY$st<0{+wRvU>k#7IX)hkLjkTJ_J;9P)r=yS8&szGETpNIQa>?Q`D8-$GcJ?1ziCe+I)GUd>Qkr_Si?gfh%rr2gJCZ<# z2n;^<9UpCRMAwFHvTUpFn9rEMSFMARZC{O0e~q5|uNMHQr?*8%p*!G#l2rop$W)M^ z?dQw6cLY>DbMBu(C0V6wjSMiG7z9>W2{dG#v%T9_4KriEvE?ROjOyddXb2*mV^w(p zBJqPUsh9auxhO)`V9_CJ1QYC1VsYNy^+B^9Jsq2IY`;@V6T1nsQ-iR0X`ESHa+D1- z(2jTyjmBf~0bfjg;^nt7g`fS;_=ems4cp|nY#XA#xOo`T;6q|F>G991@CPa_rj=c8 zH~?C^9Zx@GUjVgDU`h>_?KWZya_MRTEPnQWKiqM*WpXb;U0JF4W~I_e*4FRDV#_7C6llcZe&vcH((I^b_LkNK7Izpjrq{_d^$|EMo2 zQHuRqicwEOE8tgQ@=^I9L75n0gJ1Sq4fMwhc}gsGTKEv@@Ip8JNJ2>bX}0aeK$+uO zSCEJ;QTv%!l9F#x3EnAo%~=&}_QleGW3)L=r*{}r7=9lb?^hMTG09y;&OJ6pj)~Sf zX-O-F_x`|RD!(;UjDjo+5lcA$&i_`lKKz5$XjaRFq&cHRrOlGV{tJf;zj`MsBL@nB zt$mNFPX#maqCY8X+H|L+34yVkQYHzz2Her;Ly3+9$c&D$f*F-$f!i%)m!XAP$}n=B zm9r^O=9abtNMc*y^}20F*?O2WcdP|&r>j=2B64Y8d-WcdTTio@(CsSlsC2PlhrNb? z6wIo;*nFU=a%lK3Y9`iR+WM&AGDS~a^HBJJeO~WhvwvWYFkjuv=SfqMlR>$ixb1US zf6jFJNz#dlYkfzK1*)o^C1DKMO9JO=l=)Jr**=m@-N65F>^0<_-x%7j5jRe-nD`kP z`|M}zWa!T4Qk1^G2TnOa93dbuqZu$ zY$8CF!;a^I<2l;Zt4A@Mg&1v(k5oX|aYEM}?H4M9qDo=6&?(g%SWscQikG2kne8W4 znhx6jK%Q}!2Hw`vLn8=0O#FuSaePCVGHQ1VK^rl^gJ)uoFTz6B>~^G1tHBJHMYY#QX^Y03mWp%?|q!+;%C zTDxdB_~oFsrO!t;RbDo9m@dq=TLLbi^IFSksD-4$+jvJp*Wtm~GNe$ztEE%;>Ey)> zFk9^u(&@iDu*G0UoO$7-b6>(>Ct|r_=Y_0s5&g%Uo?jqiR)y5Nqw3niVpnhUrt`Bu zVD(os>=p${f^i@9gr|0SGkrgB@AmwUL;iXNb>GivvI}bkj4R+d9~IrC$>sR>J?iSu(*wy3esa1lV@8~*CmpWb64*U#+)cN_r=#yd$T z_J5d@7}5lwow|?{CD!0#!sMF{(s+Ln$uH0RB=I1}PGpQ@YEcV}Os~{zk~#QT;BnBM z%~Zjs*pY-JwT6Mz#u!PwEBpZ%Jm2;(75K!y)d#ygxk@E*)JCK&Wx+|$4?l|ynBh-& zH$$dMlv~Wrt0$tB`sAWaliQ4X7z@p4nt!y`)U&krN$HhcX=%+eb718(qS>mo7t{Fz zYzrc=zSf;3C{?E1=-UTQ62slDD;$(?h8rnl?=j!k=57myZl<^_*x4iLL3cM^2O}9T z#ufu3x&nU@mzjk=<{f*4xou2+8!=Itj9`G7Do{j0W*TskK+B2BLBx5&7mbN32D?C&S>#LC5yIArk{=Nf*Z)%g-iZVXMW4xPV<#O#Imfunz zA_3XUc3$H^x6|qEXI!{lZExsIn*Y^hNB7GCH7kR{pE8vG=$RH@*~-C$aqTO7v4HMC z4R+Je{vrNR?RfwRQj!bZMMJ5{v$k4V(1%aEu@%U}{_g<5 zQZh+_?uf^lKl7`#hT5t|4R2Ze43(|0K(ecwzjW#G4muT-T_^&7=e+%>kgy2LWW?9X zx7TPcRmOy2gnY_z(0X>mM~`EH%oN~^7`If>j!V0Oi3 zsC{3LZ@k^QbcR6-N}{Euy=)a;IgPx6-l`R~sGpynnmV}fg0{bx#>}Rw#IswR@KY_) zg0(nbiqgDhZ-c%PEAHKo=iF2`4^WIf(ZkEC4_tV&o94v6WzNQKiTkK8#9BUX$0&15 z!KRSEu%~%cw~x3Gi@9J!V8Q^#%!`H}dd-6Wv5}I>kAkY!?Q#LF{=1#yk8;mB%XV$WZ8{(M7j7_QY2l}TrdHXmEhu*N zA!xcbww{Cq|I;7@^7kNm_jVgDh38A%>gYb_^R^fJt>u4uDOJ(G5kRVI;P@dGSkWM$ z=u>5P9P$6{Bw1(x`{K!Z;vu_)SfYpp3~A3#U~5(6ftq)wQ8tu+8T_1Hnna_*VGwvu zrNE~aHZ7x?CwD?t3xFDT^7sL<`3HLW2zi0w@`)TVfvrQ;f%vZOmYetaZ7ZX2^Ggp4 zf@Rm3Cezi?$ZT7x+}>?=oVkG4yji@>oji1gzKD#V5|;Ps!A(iUX|65D89sucK5W`zuC&*~ft zyD3@ojAfGrqp3cAF0S42vUWVxi94(HxYO?9+xsT0)d(vZc*Lm`Dol+v&U790` z;9G<#T$7p)I$(H~Usem0mu*Tw-!jt&J6t`oUGx;;gj58%*2~3O*(bKxJy$ugVl>87 z(28qk1VEB%D=ynLiCHi)@6o!vc#Mg~M_q-=2?C8$PxP!j$`wT||6a(hugyRVM1wb6nkepHArp%@6yj;Yx(v(j}bG%5U z6{T5|w%9S|l40>7{YtG6J<{RzkE{$Vc6mhZa&#w1-Qgq(V*waQo3ALsCwXef5w%Rm zzQd(fPjb;)4-h^-xTm^0=~9{7@bx}#SGHNz5XRV#m(Yo2Xw*}Fo~@Y%>0r02Jc`Fi z8pjA6;lWJrLu>|0bZ-Ei=(5{?_A}xaAIFyJYk$s^@?+ih`R1iNwdhCsN$SD>>UI3+ zWF~!N+n$)GbFhmh>0i24kF(FKH%HH6F<`f>zGa21^Nz8-`$GDwgxbpIxX^;zXB@j* z#kft!SYzqa+Ij6i{^16dGblN+nTRKZ){1JbchBB!y#7DE%x~7zGFm!b9!C;s#`Vz!pkt@I4Lrx0Lmt@gn^nuvOZAUZTo!U<|8`t+F8iy2E8$ zmnI0%RTyC1Pc7v})%{=^cf}oopwBQyaxKaWEk&=Y!?2rPnj6X*CdcE=T4nI$r7<2F?{bwvhHW|wE_ zCKTwm?!7{?%SuzBs5L06h_!ra9D=o5$DfF;&yW+*92vCmI`@hdiA9}os5kzUuk4u8 z4YBWC6#Zbz$s$uD#nAvvUxd)&^?>O1b;`qoG$)e!?-p-XsmTlui(w@k#c7S8xhvD8 z_67~M@gH8hx^^-Q`9fTf6&uk3^oM4h&LzP1HtQ5V)z5k zk;@&i#(ur^KZ_QCR23nJcwWbJ-Wo4Kun>!#svPk|K1wlC5YC;+oqDP&lM!DJB8{~& zJlcs0m=azcJY~$>%fKj8dNV9B?J3%Lyz>*7`0xXzGA!@O4pPQ|^o1&JzM#NYz4_kU z{1dWbNRNJL2_!6p{OnL$dBns`i6}2KlPa2fp8oK^lAcKwFkGNGl?W~E;?UZuMl98J zEH2hMk>Q+K<0R|0)?QJ`7TVQmT8;5e`7YcQ@R^PjBB>SM7>s}=3qAb`(UA>3H4T^R z)?O8Vgb$epW~x?rikN&O^wHB)f6`%=eWaaa&(L`ONE0#*_L}UZ4N9s~3gF?z2cD-E z)v?)oPEkdBVosNmeFP$NY|apGYZpc>Gx$F%$0uWs1}W$=akTU!@=Y+6SPPP?P6R@n)Q2@0vJP5o6A zxaBI>=A<*XWRzW97CDa2E=>f^nzfZpVAkS?)=G^1=#~e zKh)}g+5hlDv==3@dJ~YD?*m|bUUHym9&7rv6yfzOW(<0&oyE##!}fEZdzGjs`aM^D z)e!iwM$|BY#j_u@T+ejtL>A4~*J<9|miJWe!Q8%km>YQPL+-uEGEfAJKfUP#OiS*q zy?qtwfc$>kY^vpxe2Sk3;>=D@=6)qa+UCEPBP8Jf(SxCl347S3Q}y(_FJ^^b_#DTp2UEd#?ikqan;yUz z;GAU*xk{^Fm0;!OXf4Pl9G9XNu^P!jJ8OjmuWqS_6@7_*A zi!w;<)`{c#ysGSnNu?S^2Nv^X$s@NHn$jfR(=R@d^vV{>Oqdhb!~$DAG=g)rytzj=F3Cbaa(kiZ(k zrjd(r-z|&sH4!7*4x9BhnGF5fe*YEiar9ZaM|5cHVP7wZi*qFlquK?@vP{fFs<(%KOao0!C`uFdbO`o~k2R9liAe@8+o|)pzqqG2;tb4Tsk`8x1hX3>GWq#%%jY zD3q<@SBq;j@U{su)32?RxBFf!jiLKT#l0-*v{~~fs2%SztjVldHH(B<+-2>tX3P(Y zQ1p^mo}Iyzg6)}KG-y*QrBZbQVVm=yv>Dszu$)Z!{sICm6*BBC0c1cyqrK%3iUQXD z+1??%iWZMfT?5;KPSL>nQ`o;^1#Ci5A@=!zfG(QtC zV11YDOEdpOm@i7`FUdKjNCA+hEg=6{&BM=zGz9AZu|B%^&-Netp8uxl2 zAw-Hkl>$TyC0eNmhNrqSCKSV3gaRCu?i6Uv9O#DbTgwdnq20+|h`duA+2BrVrn33( z0pwHg7{Gia33qv0y33Oenrp|%S`_o?1E!Q&8^vm3B^O*-E@P-A9&6Gz4|1kkR__fl zC6ci|U6Ox!DYB`K6jkzyEd30AFfMP|j&Q{tu+D^$-zi1ZVb^h%#Gtb=qQ+Q&J$JUyqX$`? zcp1U18&v-1{m2JYUU(hmxE*uC$QJY=4Y+P3j>wy}1jU-XjFO?>Qsje(YfO&;Bk5TR z6x@{|59s2Xmv(VuDYeXmn#mv!oqG;N?~LCCn*q}ZtM|VPHiSWJo-4_i``+;z67VOD zK29&L#L-^)`#{}pZ{wR)#-*3-MB4tGfy2k>X1semb^l3EUHx`3sQz{fm_q$!SpMHX zzb2H@`$)XZi;qp~7LNf!G^$=(&a@S=_4M40L@H(2Audb%^w2hi zJ?&jEnVz-R-uc*m&h4}sumOYc<&IOCTI(hE>U*}guQQp##<3aXvdyeK14z-w47nDz^K!MI49AOUBBH>1GUkm8AS&CMl% zA7Di+ol@FVEN5gjZLkm1LxIQh6itQ7m&G@JSfI)oVP9FG+&q3gE^>>??Lq~0p!Pi) zK`bL{PSo){v<^%^4RGSaJ0zYlR1NO2c}QR#gH1siV|s1H1+<~olqyo*rTTa$o%_Jo zo~x}{0Y8y7q?w|euyB;jBpA-)`2(4x;wsn?YJ2Vdap?xqBJ#$+)7Uc=9fp~yr|QN= z{GG9cYGKg*mjZ9OZVz5oh#6`4XG1|dj1Z8QXpQb$X30JeZ-`6QPygvNL%{e3Q1I{Q z6IXoBL)o38(E8J|zsK7DYAXYA(-+@9j|oHVsAZ~Y!Yv#93VGJSQ%{XvtBC?n3r-EG zFQ;bcrzT2tfCb7a`c9p9ijA$kv&u^m578M1BXUf%Todh6+e~i-Klbh zNo+S?7Fq=KI- zzTFY3VM8#kHL{y#XoH6sT;pOFAI*vN@==8|SA{i7`z*`1E%K8=fw28to0lgm=q)py z_WL0IW3rnOx`UltUstq($-XHIVbA3hkvcxw^RzKLoizPgr8vs?6Fnkv=6;6rIa(}O z?p@$;j0K-M(5Q|Z*6E*+6pgppxH10ONcJ5kQt$JPy}$l`9sm16$?b1NpATEQgipBx zn_Ge6*}+)b4g8*5<8h0lyHRhv%cRZ#K0U+fGV(1 z@@>dfHmF(R<8bjW$4|Q>9mi9sZSvz(WhgLJri>>PhoYNE#Ufk8ILH7gVaVqN(pAEapROi#nRWpyG*-a;AJz*?0p zqOeJ~g;Lr3VdMS5JLK6qyi?zWU6GvDz&g?i(+QBy3|=KAeH~*B=9q*p5BGQg?mB@9 zv1jhMiU_$kg0jb+BOkMDWIXA3JhV`va#HD&bKe8TsFN89wfGaw#D4M*Az;?wHBNlX z30@`cc;!Ncz;8RnJ%)FCpGm4bWmjxjY8dR&ygr_`_i2{cm7>MO*rXq@T))F?Yv5=Npc@ymvbZy!b=P>)ltm&WG&9#9=ZKx&`RkKo~iyb3_&kY(*R8O?( z5Et7~&`h66?F>A6P)K$amP!dM`AJiM)P}tU!Cdpa%T4@Co3hT@Kr~!j_-?;#$uOj) z+xRbKN)$fH`Al5P4%DT+Qkhwap?PTW7oLw`w3 zalTe}tVxsglY3Ihqn(02t5K1Or3>^}|0GS5J&ebK;w}=jwhT3|WUG6;5_kpKbhTa& zR5#|$3_?pkFZ3b&Pk>T6Yt3qG!{itHEiWSy%*gu!yfka9p+jgbX#AI ztDh3es+CGTzN+k%k1-2>K=B|L=qLL%>?5ioOkm-;NEA$tWw>BeDpG>BC~OTkX}8Ew zrat6#Gy(fDKM==q#U!Z}A0w;-_k!{XV|QrOR*Y%5i*tC^^4gq&_b@*rv=o}xFnCV- zG!2Y#mUF|h*t|J+3oWg2!YK1VtpPtfTS*A114cDTA?uEpdZ)rd-ev1C5XmIxd#4v= z;$*TZ70`z%mVD$hmb_z_NMc`K`J*Y6;7nLHN$AEh4E9E+F}e)YakRNLjSysyFEK6V96S$E4MHF1^Ko>+uPYl@kZK82U*n{?}|Poxf9vqrCmtmuRQ! zxj;uU+BCP)B>Ig1GI;<6J~7QYf2^Y>~^fu)JTsM9q#h#OE)Xb#kqEgtzh7k&{v$SWv$bL}9QzKK+A`!)-MOQ~GeYdB?(Y*J2G%u3&WvVuKtW#`o5*1Tk%FeVJ)dG2|5 z-BGPzZ^|Xk%ljh-v@J1{=h8FXkhAa($o;d<8;YoKj)0JWa7leD+Y7|mVYD%Oq+OB~ zEi7JilUf(qYIembEWGzIOjt?YxY4`Wq$hY*_*#BO6K2;aV>U7|wqYudPLNnfxJsQO zkT1L`TBo5KwOO?nJzm`fAB<)s>n9{%H%C@xb{|R^k+v)$HEkgYjH60~KPi%T@r`Gn z&)I^Mcku!q!eW&uXC+}XMmt7ZvmM31nb=-^vW-By(}?c8dtyhpkI9>!LIy&}sHp6+ zlW~P(pCTr8gWhuWc8{^Z*8M|b!z1)8_Of|DpSvN1W0^lT3ANMW{cV@j@?iOXR+4pf zU;RhJ<=1{xJ(N3Oi?py5Y^QbqI%B$}p6WI!IelTBWj?-(Up~Z!y)hd5IhO@p=!%3N z7(E+=fz8&hwZkO#9kzNA$DEMMgTqtgtv8MP6N@?`633+;q_~~e#A!Fn-dhL7! zer6#5AR;s=VzLC(LACa{Cq%LZbz+rBQ+hMH{;w*6EQQdF==4l7yWz3{aAK7w^j}zt zKv^S`{Q#`QkV z=xplxizC!2_cz~=gH)_-Crp~=a?+o>k*cSvqRsGkecQ|8 ztY4~gpbb06D-kFj>B7O9CVl7++#p{&gc9Wwuh6Z5mbR=%>yme#n|KjPtabkL5jy{Q7F<)bO&-v}{yxd?k z@b{>bLD7j)T~2s*`?YJgkL(!L!Wqw^gqZ7L3)Z6qKpxuohWkb6#WDBJpT8y zFQqF2!Q^^&QSt87N&L(ZUwbhT6;5Z77OyATMoR)2jij&d{wuOMfNQk4iYK657X{2s z>=}#LFN@?;v9sUaO5)qAs_T)gDK#nEoy(Sg7^&v=+pwy@x+d=BSmD%IF(eCh?Ft?~ zu@pn5I3I6%wAB=3NB5bhh~mTT0F_=_WYPI@y5uurbR}_2x%|ms@dB`p9O-0}m{srC zCz;(C6J|3+dLB&ktX#Q)ie6MAk*rGJVq!Cju_p52J)%mgT5_0mxP}`T0R^j7W(5Y_~==8o&6kTQ-ruSNEpKPD@zT&ujGoZ8}w4+2l zzujkX>9E$ql)65R{JgF$9To16uN=~x4)%!RPqo3K;n3ouAJCE$!-|$LkV~r_L8?aU z`A&pP%}Ir=LV_Bn72Jii>w?P1j)z8m8q|Bora(>-bBwR^>DUW4C11syTQs$y9w?pGwK%7QaRx@0_Blmi2F0xCIMnTgTSu&8V2O zEcV(TvTTiOZL zk9_5dO=FXPJcwZHw$w<9)Ox;3HR`$dt~%G-VCn1us>pF^J7Y$?+s`T|A_$*oNKxDJ z7ebZYI~%+`_1ERANPmObU%_YKhIC}?J9qbWFp-8)6dUeoyY9{o`2}D9#XJ+F4J9$# zF1t3A;1X88va@@`;4?zjX(yWh#P~1BW5@J!4Fkzj4;vAgcyu^h2`WeI##l~}uDaG9 zLuLcPvm#XqsPKPF>N3E+?DDmJ^a^Ja`!Y0qBw}Q_ z!I9nP)v{wEIH=jeQT3*m9Y%6EL3vP80wpGyeAW1OBFO>ja#2s1L*gSy(;v@az&_%4x17jv zS+7iW2u2x`W`2{Ff5rTqck)NvjQ`xFl3YnXA;wpa=Gc=X+c2w45;0~JOac%3kfQ#O zO6Y}7mc5A!V-XU^;|P^Fa6e|ZU(f=Z37=d8j{j9?$DXsld(v~%GSiO);+hC70dWo6 zm*iFsS;a~^MaR4zCn-_Xa+ zgM@cNr#V?2+U@28sQ2hdaI$VFD`JFUrR!8|uah^VTTZCXKMQQVf17eOG4+JnRbviI zefObb5+Nj#&Sm3HM0JWC1Lg&@#XF%#K%gIL+B^HH-*zGGeUKkaeG{OZQ<{PhW2CST ztC{v|d5x0cqqRcq?ccqT$q#HpStZ3AuFrV%Y4+L`wDUBrG2$N-MPzt0juEgdjsJ;S z_a~Qx8|v2C1ncBm{NDobS8mQkd2yMDC*|Y1u8w{$S(JWW@h=!<0w8X9pehaIq56vL zJodK;S6C9qGZ8-%S80W80RP9}Fd0AmEBLtZf#8c|z=C0PIVSr`hxm2a%+v+gQcJGi z@k@B&oMv>}E}9Ei#W1nP6|!ld#OMZ!>psjPS`YeaoGzT_sKU@0$3hQ7qXxZH2&v3Z zWJ(XJLTYkUiRe~FT&EA!Yp?Nzi4?ZQaFL_tk>YVOJa?)S?HJ~B$Vr~$m<6FHugw(W zCS3)CP-=LiLe*@Xnm)zph7rq&kI&NgyrR((bJmxOQsi;{O!Al^3H&1vJacz|yb-Tv zMoMU^?qbV_*8-kX9!mmGfZOB{%a{ADs8~M0jqkRQRO81IKpt>z6ziTg$Ov z4C`uS!PY>xb%qra_Z=o7U_dQOvf}&gT(cZan)-rF(M7t!SynkmMhb^b2qfQrp6c?oS2_ zqpKsKT1Nj%=RhDPV|-Reg&Tz`VpK`fcfJL-j%S>C+Wm0`Mj(_D3j32WDnTBvApiXW zxSY5!M`odPaZ?()h1`*}U>(3Jhb{NFvroOH(>$Jy}FlUM-^dAJ^ zWxoTzB&0zh%jY1+Hi;8|2TnyJ%73ZqmPGp^ddW&SFPzCB;HR3YGhsFbZZe9lm_WM% z>N|?;9Oax(j6b#3Ak*CWf$g>eJ^DaIWlYMt3&QDE$kac7mCkNc@3 zmzK^rH?uq z<`1$_lXN($7Qi}A>=ahynpEPQA_*pqA9I`}V|Y0MVi+`-W9Usw6PHXp2`4ioI0iN7 z8D|q)G2N-Xs#|ej{Q_t7Cv*WRh&hV3Te|)&>0V!6J>!@D2}2ymnpsl$fach+xSLAbn6(zwJgM4lo5G^d78O(V=S0;&$ynB zekM8eY9l_Fe~rv5LajRAa6LI|XL45i7uQ?$ky>$5PN&Y|xWWiH`Y;lvuXOL!f8`_O zL`nKjnp9Y#B}Dgc3+1>-EiruY8P#js29djD(uw$AI5mnQ6G1O~W<*kZ%ocFJ;9&)| zN&YWkL}aL(0#FM0er1eIt`UDgRQ4~3$~I}6VYCoGGmE4?&-nH6n_?i&Qa_v<0n-9O zPPtX7Jh$eqbBmex!B0Z8Kg#=v(#KLoU$|?0Wu2t1Z}SPGVnpQqSix0RM?bEan<1m% zdh8|Ep&#<<6TTe=eJ@!Y#SEE)nT~CCu(s(MUf{S&O!v4iLS}%hYz!NH`mC?cb=;kR zm;}w^FiVqC|CF&+83LxVxQDF%zB%t^j5PB5gy;uiKol{RkHQg|Zh7R>inFWT-*7Mw}dLGvIN zDTf13xa7UN{orvR9_EW^6$3E_(w`&fhCg4!>$b^jvCb zru&v^QWxT!TWOVRYTd>Rtl#5p4}}C39#=3+|LJV*<}&ThN#JMm0WM=X)zxEV?^0z* z{%ouF-TTbe+r5UK&ytl*~NM<1EihhQBq3JDNAqRq3OnN6)*dSMGN1(7A2{e z{;e!&9(`DL{dno_Uti1usEv=(_@5yHHAvWhE2brJd>v_V-sC9xuUo1)KXYC;TwHuQ zEhILyvQ4<2h@7^%YBBIhyxyScSCg@l^FNJaV8Q?Fd;WfLIZp>;+S;uGKNsqXR?cbp zn!MTz^|dSmDpcLFko7VSPWZ3M!2SBcrlinlbZPtPo+>z-Kbr4e#p5$P9l2r~Wj;t5yd133?1 zT=`#UPnl60dXws62#oU;rlYC0V|4^Cm6XYxYodt;MiVPW^NuW;rLIlK zHL)_`)Qd4oGeIzLnX@-<;0TmRGmM~Bnq(R_4-uvADN%YGaQ1JXwbxpEZ!$W>)Z-D) z#eY3civy@qh7yirAishZ{U0#V0O<;MVb0LVVp(qwb;X}m?GY!`tbF(8${g3UVQ(Y2 zGY;I_QVe@!r%U&)CDag2>cmno^r(oHHRZy(ij`m}ffS<*3ukJ^?Y)mzs`182O4Yh3 zEd0yZq|(bPkyp5{**XCo+%ar~-Ef+4!@V^aQ7nRT=7#!&=FckU#{xw=Kby46oUPOg;pg{i z$V$i3(fRqNQNBAEFRO{FULFlxcq{phW>f@bjdKLBMs ztjoPUv~-~req?{1j2ypo!I%oz{=0gn%#be)W&ju--dw|DLHW%05MLh z_*5OKxmp&_wyFEd_e{V%+$C3kogVeb1ZnY&`%RGD?@w)}{KeK#>IeoT^9@=aQm?H4 zb=lk+2+)=8R{3xj7&H-=)>cY88iSZ-k;kdbK^Sq41+~;rJrb#?Bdp@b($0O)qFWbj zgD4oX8Mj!-$Ko2~>s}*N$=Aa=3UXpAgRK*yhib)SG zgtl^DVkj3(oZPH|su<+1^SartaHMc73skr;hIOKCsHBKh@IfR-k1j%1*sD6 zU5bUFY}lcdXjPLdKE(LR{kPrm%>lh<(B}~!6l?hv-^A2G<41WN-9mDWKTGBN3(NZ$ zQ6pF<=9P+F{-G0EFItyf2tT%)VAdwKsS!4zglD1S#J4>9Gnx1%9^kQ%+J-CgHB99u zgH1mv**1Xi)O9%&Qoq=Md@Z~jf+*-s@sG2>8hh#n49{KBErZ&KpJ`V7>DQ61 zs~L{*0P&@$l!o>TxN&B5dByv{Kth*2bj)!Nn>G75i)*$sT=0kVnnBRX?s%gw{ERc( z_vJ;iZ`S8o8->H}b~U{WU{JLf36_Tp8vuUmBjO5jRMARpk9kc)v6C1;J=#vS8!v8u-+^^Ep@Qw(9$fTmT5j{)t{eG5trqPvsgPO??=- zO?9F12gw8EM89|VKUb>R*W67{>K`56VSNzd{6{difF$BsG_cOF3;?vrdZ!-xvbp+K z+!bJ2+}=*go)X;JPBL@3eD|0xVm>%z@$hHxV)fTO{&}m7(MM;#^PB+xI%(07q;i#P zYF$#n$D%~?DE_ykeQzlN2z(iKA=xZ=Z|GZvzC#*nqg)aOY5x{Vkeq{0%9X0Ym{=@m570XB*6Q zee#U>0XIpbIxsXcC~P&S&r6WA7gfQ938Q6KH&KMQlz>Tm(&4h#pt)#MQWRtICGoYe zF*RCnwG+r3!c(Fv71pErT|G9JltZ1iGW4+EY(O1HMYlM+LZcE6<9V!e@^ntP;Z}q) zFSoaWBANV?S+HcPvaXbXe6kQ@7#$l~IylQ8WgnucmzQ8Hb`LTAOr9?$R$ho`sHTd>3L5Smp`#~ae<8^S z3(F&RrgLbIanxK*`MCd`z+`*g9Jv{3FgpSu#belgF{&&j2h+X*B~ctai>28C!hMI( znXayDUhO9@o)NNR`tE0^fK8mD$Lt(4k94sv@;fGj6gkYC3O81L5=5uC=%$cYGrt(G zKk#^8Y>Gm^#wzCX(sJ3L!-dfjH>o0(#_Q8JwDdAu=0u5^9R=+4do5eT{ErPb;-}un zo!b%2T=f40KihB44K+cw&$~x|d+5F220lqKJWUD*zwvRz8sgFrv{lwg1W>0L5X=~L zST5b^jK((!TVx__QxU{FYF6H>+_}-|v0@kj$g^9W!7EY%e}C2gLeE_);H5j4Bn21A zyxta~x1uwC_Wv(yFU^Ph{-?=tqE%bTczO1b!tr8fiFkARZ^62*x}*%mv%Uq=n4Vzf zZp74Uwm|`NHBfL`O`?XS)vYe`toIlF{?D)1@BpD|1Ub4|RZd(X zeVsc8%W`%#rzmh0U>e#yNh;U|LHuPJE1!E>0z-CdTR+Oa$i4_X_jy_Q^;O#3UDtEn z0%y6~S|BU!fO!l28QJTpV>X^Y%0u_i+? zIPS0>sw|vCp^;jLn^btNK~iRaCj;*0N$!#%V&d_(!(QP`eQ85aJ^9J?d__7*DAL>O z{RjtZDzhi6ZR(ddF(`zo6Z>1W$UHIJTK1DMSX`aiOtw{OIaC2& z*)wl&6=+o8VJg1uH|aJqhIG(WQgp1J=2ZosI$Sv=wNdsya=BOx01I+oV`qyZ8vZ@IOOu?c5Ein0IYBdrP%-8_4$FYBunHya2z``@b^3F@Dc?PU_*#njfnw zXPru$mnVM$YW1ZsVr)FLP7TstWf#szhFzDic&Ys_YK#(S4!}|p@7qhgt+~QHGZ?;c z+>X=F4q%w#-LK9zzaWme11`M+Qbr&j*uUlk{ zW}Qj=mFt5+(S#mIo1}yscQun0`Y7uXuZVNCHh{1QJllo@&$$Q1)W{;cpGO#@3^~zU zjM9YN7{pW%h#TsM@zgzKv%rI94Ss@H(2}Hhk&|FkeRSi>X}J&!aK;LrGA}o$Oc&cS z*9^jdfB@)hQT?>IYMW-bOUw?uMA;0MggI14LUhNu5)*f+rm8J^2mG?e5fmg?blEIq z1wJc4QX8pUF$f-UeAz+e5FKhj(f0AlHL;AI-qp}_luaG2+E9&X#861;m#E~L-cyZwi(q%j)jKiC zsE281-td4|7Ox_MM+3UDwMQxawe$-3uBfq9;4>0TNNLp7>lAFL0He&~c42+K z!6Hk~M+wL+lZ2YKuO4;~W7lMM%mj0SlzVR}EC!FxtOH$f|0Ue$6G9h{A1m*<@*bGh z%TYF5%KWb?;P)N>OQDCEAdYR@Bct!%Y))UM)Bi4iap10Mj0MCt%q=`i_lE<+*~eTi zZt7}TY|`BS2CV}|ameJ$y*^*B4p|7%Lbl)2%c=eksQ5c+FX8_x327y7hv||?w>&49 zSsuq(nRS#)3SQCss0VCjSfG&=xc^sN-@^rXi>i#9b7WOP=O1TRSD90kHJ*OdRydTP zZj#%6i0giIEPXu{p{+w&5n6|)(ts9$UzTN2tzXL$iwRS{hxdT&-jO=8lI7EtZs+Dy zxZ+Ub+E-(ON>P|akIwK5T^-cEDJ&Gj?-&hcA*H3};?GlzpkkHDLD?{2dhaV3eh7VJ z0@_TrrswoQX(xL?13cOIKKf?ka|5SvOf~r(EVe+HtQtg3;4PziFGxMM#-IlJef|jC ziHpe-HOA5AuHlXqe_dXWG*=DhYtZtN? zwB#H7RvJX+v(OK80{7kzGkU-8;+9i;Jg*%-q_l}Lp?@jJFbd2wjxQ-iAN}P|B2(90C;#PHGk?DIWrzt_c}=KSI}3LyKmPkZvEJ$-_vxH z3DC3!z`737@0E5ntRmZ&y>hW% z!DBK7l49Wk@2lgDDlxdlT&S)xZe}{R*eZlOO7t$hi=La?mhl=Zw53HJ&GWi^Uq}5p z_C=Di=_f^!m!_aw&x=f@#2c3Iit5reOPXJ{#<#DMCwfDX4T?R_+MLahuDsVEy{O}i zIgEFpE8f&4hO=gOT8#Ds14EiaBiQyuzOuq@?G9mHmlZ5@^P4J?O{1=-x3|Y8O7-4S zWOk=h1oLf4ZvQ5~=y3(neTC{Fb~L2kYc4noR@67hBxO8YUTX{?*!edF?|v z1Nor&UAFGVWY;vS)0J;qR9;)64jfM8W8%KyV^Q|0K8_TU2B}@oxR~2Ro2Wb9esXc< zzrRUK&3}&|9o~axROG?uxmMHBFWQmV{z+_p_89M8*`1{?0^tq-5uJW3{_{Zi zMsEmSNty}DO6llA;q<31b|c4fTY09A6x#&&TE4m``(2oXSp_RDQHqcB{xt9~;^d_$ z4i3QU>URDCOZ50%dYw!Uz4e#smg3K~As04#cE_;nE8A~57D(7NT0q_C&bIaeVkCK1 z&GO*#qm%{c==V%|q`U-7w%hBQlzr~ax-5oiI)v6~%&FKM3`WfM7a5)MP4t|51?IX1 z+-n8sx^ewaw!i;En1&)?bI}k%QvMJzMg}44Pt5smp=8XG zp6fbOv1Vq`hXTetJ{Ve6X-Gh%c3lg^*LwBf6Y~KZw7fV}hfx?ZJ9cZpPO5~B1B^vY z%vOFeZFz^8j0#=4`A$4tv$*+X-IMlJ+PdOMc8huuV(`%{$GL&IK4DLhv{hV-3L5vr z2jQxV_@{PzwayF)O)TO(qM4xliFXCzIzX~hUVAf!8drtN9(X(?jF<7N-zyx^1L{8$ z6e{*Ew$vF_ZTM~TTf3KdlP1UfNI%#HZ?ocB14iP zE}BM`Fea{1V`2M)db7wmZ^xMESe)ZwldIXAjO!KdV}WUmLXlD5{njPASS%x(n49jq z+Zwe;wewcnN(C}C1k-3~0b%Qx#GiD74Ew-8EijMhXb9U1^mlO%AKIzHH>JR@JC0QQ zeA^lH!Z!}I)e$>)CA&*avhy!=m9us3jTYnhHyW~7h*x&TUTaK8X zyWKQQ@Ebriro`1fCpoUvuAaZ%aCuI(Ir@ha3nxX zhD+9!LJ3T?kQTW!gED_%+J7L6F%f_ks(QK1Yh(dRvYRlW_4Tie?Z-*oOdh^rTekiX z;icbqWTVdq2t}6n3N_ zeNJ}P2~pg%5mekC^tb^X*kTaP$P125x~kZ}&p;Bct4w>hYru%D%q&R6h13GlnT)H@ zYEaZQQ_s9C_+IiXvPcysOe-u;1dBM}zAi2mJvN7y^{;b#FGZH@qDq+=F>@sorJ z?+;utdurZ&*ib$_+Y$aqRGv#2G%h+R%}C zED#)a!jdWO>mZ=d?6qONaFcz616av}MMqUg0gT=*-`ABAn$_u(LurG_2hZ;`6VLhA zSE`Ip?sT)oAyIzWrMknyRl}UDS>2mMX487^wvFeEhp(z_N87?xKi*ep%+=P|b_8Dd zc4lBMp9bqtd@S}a>(=@+zOxD0o%}mMwYD!vDE$M|N`^i7jN2r~we$P|f$VNYpT^Vd zWR})*6?xgmD>w#sx1)Eg{zq)4A}-8T=DO^GSzNmyD9v^^eUTdf8Ed)7-q(#UB12M5|CePsdt)2CNi65b=GQd}W z%1Y<{GOyH?1$CeDc^_YtzOzKLbIBW*dUdtE@*6p*Gq8esXTX%Nni?Eam^gC ztj7X$s%v~xGRwLS%AW!6QNadQ>$%P7*Evfhlm0X_1wf0xSl`lQ(XMwLXm@!|o5J7t}J)PR_WO2o9d zd`jYNIjR~X(Vs}T6G7WZcm*Sx;pxEi?7{&1RF#b=v$tadBm6r$p-chS3y1qh`k@9L z!ZV{>je_@(T6ugZPi=2l`o}SnWmcm|IJS{B(TIq@A$f)8T;s({3lJaXyFUt+IWbVc zk~sh#6XS7E83QIgrWn6B*Y|uTe)PF!!{?5IIMd>2ZRA5%>Upp%I>80t6Tgi^vFGZ= zdzfzvJ&&Krd+oRVkc3Xof{$m73zJ%3d~`j*N8c*Qc`G#DBsAyG6i{g7QGN_6UgJ>L z9$7nB{wkrc@Ak<-i$Jy|yZ@n;^rz;}+O3z(!MBcrAB}nQAMI_yK6jgF1dfCey42dFNcJb+v*-%$^|h~1+` zoKMOr>5t}IubDlkiZGKg*nGqJ1^2fgmgd6!0hKrfJ-bFPdGZ?h_7ZC=miC9BK)}?da<{^es)h z7mV$N^1~a`fs$lce@0f<+~LQ5xc8Suu6MkP;Xd&0Y^WJg3`qO(`UU6naRtfv@BF4y zCA}!W>nz+P;`sFzFmC$jc1tR0qG2medD|DP4R6W_X}QR%Bf;dL6LtJ>lUMwoE&w5!!<0RZ-r4=jA42j6@=Jk6WND{C{F)b1HO5u^aoIGc2 zky;`p8J2!Ear4K1gEpGtW57*JAmCQpT8&QTY84OP7!YL5aF^T*EpOkBsOj|jgJ*7` z0g5xi{8MeCwPIqcsFri@|0OVtAK(HvP(@vC4qMRvo#+2Ba0uWFM6d)X+pe3VHdTyH ziBm>#T|vg4911PfbVai&y9X2D8z`>V;TtV)EVqdMk81w)eK= z$}V!$!hzbMFI#dX@BK?lY5lL366Q^Xpzoiy427(H1Jp(@tuW*yU(cB9tQr|fjjNIw ztc8y%Jj~S*gEq!fP8k!o6Y^*b?Ym+x3FFR&vAeEzOmbk_i^U-MD10+{jIuE$Yaoh+ zn<;h74$%H%l-~wHwb&1Q9RpW}$`$jbal|i#@=l#X7bvK_IW-4}uX%ndh3twARptmV zunmAaQ7r2fk)+_kQ(y|wyDF9atr5g@KVpVIP_0R=fl@Uz{|?7AoQ zrdaGSgWK(d#B@1NpAPC6sNR(_L8-!B)-I9JZ^<~m>xTz$d9PL`>B?*f?7UJn3YGVZ zf>OEOGN`6P4>0kTv_e7k(24qosfZaW3z#ovH-EFhG>c#+9br5RzjO%9D2AHZHVB!F zsq0)e2m^G1Q3IOzE@m;QuZy}<8BPkxC z&=?RT`L*@NrK$%^hjOPz*2JfY263i56I}5#NGmm{4_8~;GkhaDc;NGkv@KbU4RN6} z)39%HEW5jM?7J^ZMu1rrKgVPGeY2mp&0gZf9F~llzxo%FcE+{6;dW*(ug~kPr*+AL zIQKRB->Ps6s0vG{4m^2%fqSG7=Y@Z!6ndXgNd-o+|Q$B zL2rU*L}IHICr{Q%3d3lnAfteXLfuOCnb9LA2&8{uRhpRr`-%ixw6mq0(D6yPV>RDR zvd`p7)v|{i@@=}a)a4#D>8KZy!qAb+}1M}62cvJU`DXrEyLr@YPnkq;t3a= z5kH7Vq?aE30R9!S{fEKBn}dq*64JBeUNPB!EWTe^a%K9%+RM1#iah`VR7i$7T-^LQ zAlDIXDgF*92_uZQ^C<-E|LfT3>VWoYDO3(N|wJj-rlKF2FDsWDOX#Yq3p>VWFjW(Q@F}W zdza~ku@P`wQ?l=h3cM&DD6FWnqLGTnXADF1h3~RK49)#m{Q46zwvC$sA)l{Or>bTk zdif|+e;7i`QY0Tw%v^bSLnv@OKd@J+-HrMPZx;O0A1%Pyw4Wh#LZ29^Ouc@%MM7$>=!S1vAdR3O6`VW_S#+> zc;-VdQ6~P(^TjX=Y#tbLbFrY`P4WV@l}KNFKd&-AJlL!hX(+d?5Pif$*{Ci)`eZK zk;fqseMYCF8ZsL=D|@&9Z8W|8i%CxCI`&v9AjaMR`5AEzS{hNa(;*(8{*8j=!s1y5 z$GG_7iZr;f;2tP!jyLWS#8!{-BE+`d~=_Q?go6RwTwWJ?@m-|hs>Gx!t zZG{MnK=^(E*CxAy_!nbyb-g@3Qt~p=Cn&cYwDz$DY`exvgwc7p8496H#LfAN4C>Y_ z#Ps1urBC`TU4$qo7#F+XAm@D#;u;Yas%@_YTG83nzSSRf=JT$U_%qjie0<(bb6_S9 zQ59%Ou~fu2(Gd$pXRWkrCdiM|eUpdcRhF&c%O2@TCBg+@AkV|PockI>iA6)y>s3+K ztAw$g-~p`-P5k!-6~kK$8FxfGOF1+eh&1G0UFGZ*5ZQj(&Q5)pZd5f+hK)Asxc%^O zCr2rKJ$wgNS&C+9#YrRuiPWv_Z|~Etx(jBBa88iM07d|_cYESo^|G9|oefxs<4xuj zJmlZI6vo)0onoGMBu;(ZUJ^TzY!k?RmE(7QmGQ_7DPyTKVj=0)rUim)pB;Z(!6U<_ z?YXuCU6Tuh%MT??e6$yHm1q8F&B)&7wG!OPTvQ6L=-R$Yuu#zSHNei7-7iCL_Ui3S6_iuaKG>@UMeG zj|LPEdaots`%QvzEE=)3+gtcEy%ZFi{9D>gKA*T+jFt zQIt{1KVAS|`dTgnW^+B?ATYy`_8fYN(K=h31l#1cI81`I@CR&l6CtJ!R)T{*!S_*y ziQHp1XXfX78l0zuZeCsK@lnTpB%2w-*kc4G{(x0yb69-fG?(Aq*Ph75Uls@63|z>f z%><4gt*-XbY28A2MOZf%36_*lz~`K$nzGU34?%0Clt75>l3Z&V*T+u%ot^UuifPAr`NPgj1tDvQ2c zIN)&}{z$jgl;;Dq8vRSW3yX#>jgeyaYsHX@6x~fYGUq_SQWhS>CfYjKt z@Yt5I@DfN)##l&IRD;bS)ZW8EnmsjX)S4dYjr^wW%aPHAMaFY^-dDx_n!hLWW$CF< z-dtiI*J)KAv!oqCd8eW{$4M6a*E!aTquz6nl%eNgC_#R3DLk%*cdz92$wGx2M@uT11GU;JTH~(E&Hdlj z9A#FL``&iEB}!ol@Q@w$Ff?IQO+gsJEh$sy3q@7q1N3+V&kGBq8DjXmp!Xgmdzquq zDX;n#6>r>MeW`ClGc}>d-F@WaiB}yv`dQ;c^)mmt%Cv-n{9U=;hitq+{$AwXs*?I~ zwx+`Jj`OuC$OiI`D{pdj6`lILtqCzxau`P04tNbpLWGx|3Cb8Nh|?`n%3Vx9k5;Ug zBLjqsKYDyC*u#v2@q_n|jJ7gb&JU=TDGmS40t4yP<2~_lWk^(Mj>XHlN2gZulOYfO z1O#lqAS}#l6JtCpQ1t2$=-lh%z(mt9U@BwWJvRu5U5O5;s`gBJ7lNRdpSSnZ%;K3A) zmT=!S%I_d5>2~tv=bR+8U(_(lrh|t_b-U9kX#1(`b$i}9!Du0vbVf8c;GIy1-G$U9 z_vypfH)$Zy5zoCd-|sT}MmnaaI+Jb*(8a<_jM_I@zJ_ZnA`kqz#v1wsSSJe`=rmoI zZyqQh6zC|j+~2noZQb^ba2fHFMvVuBK7(*TF2 zV}$RDu23_OM>YE#Fsc@^qMr$wmUx+P8>}&XWHz)Tf5Q-YQ>mOMc1BeDJEJsTR_U^C z?<+!94D~I`t>$7q#<+F9K{!ePiUkj*PKPSidc5Z(!Gaj^^lfRvBaU03pHsm0Uxg2v zbkBn7gQIY7_$glqqaWfWR_?0)lnGS06j{*8RpWQ>ie3HL#y6O=mAHl;-}Xw})pb_L z(?&OF09JLr^^x@dAD{a+v4p_#=hfKJK>1I(mej|+-R(B9D~l0}$1iW+VcV!y*gQA; zpK!(LJjskXyORQAQ zUg3O0W$iZs?n^0MHxTwaf(VP(0&1;z*>KAIOTIx_{O|uN#*~)?Ndjitn zwq|qI;^oUXnKTaXUs+9NjY3C2MIex=F}YihT2_9bv{WwXL%S1WHWy<{7o;TI9vT~^ z%meQ=TaoM-#zIc}sV0>12JH>VzABEG$YUmYd5pY(C(FV3xRF>K_+1%XiH=c$71PbZ z+UWSMo}vPxo8Iiz<3er%*80I`@w5A2k#*>BcBhAc*|$>PY)Z`S<1BQ8`&p`hc4pRn zr);Gi(W|2F4g$I$;h70_?mBxDYl)jSc5PvaZ#7+9-EDPJpv9Y#x7Etl%}Nn+uTA#H7rHTUqvp9kagUTUOAb2_adYk$%L>{RjF zfbHSU@W+DO*zXV6fA10gMXcUU1g_%seL6GjaGCjuH#pSU`ACNT_vo~t`YtD+V%CtA z(87{V3e(>lho60>8#krDwe2RzSu;Xoan=%fczQT4ndBHE{NiBn^Qs*b7W$L%)j_%pC>p=7HTwnefqyu%K%Iv#sGO8d--LC#sKee0T=TzLLxW zAF-7cF_A(YYnWx5@f5__Vyj2)8k-e5I=xxDp4ISN7Yp(X@QsO8YgUS`B9ZsL{b_i6 z06cuy-Tc~KEzYeE>bqLwROYjXg(WIc2=gS9o4KS4+2KLY)U%k7 zS9q6{Qtg6ZuLz0^k)kYYb)J(D;Z&4-fP(l?UteCbO#p{uU`vvqbGm2u!_}TGj={#t z{)-EsO=_|+Rvgm-Xu;4lpb?4)P=Dp`jfuUr1J#t5DH|AYmE$xvHhP@DUk9SLR7IKM zS~++S#ixOCVO}nh?(JvPoR3uVR6D6Xm+RIKG!Ea;{o#}GN`s`Mep?<{IktC4(3c*O z%y*Rl0xNZ3v9VSTQ#5eY(q(gJIuvfWOQm3^CmU7kkI&v7$#hBAA#@V53p?hY=aP$m z;qN(;NiZ|sZUW#{DXp~S(%;bPu^r0(R&Ce#coxf9e(tW{8m4tL&6x1aA002LxF%+$~<16`V_!o_~l8P0tfA=?q0Rv0$z~(~4gSM=(g(GSc zhSnmW@dJE0V%IDI6H18JN&RBqiL-lga74d0dr-?@zc7CQHWk ztf0GvjahZS$WcAh%GV?XM5yI(;|WX?Dj+irnE%rK4EO71Or?=Jl3)U?2(Pm^UtWuF z?ZC&2sJ-Hv>|#tjaRawwLT6Z>k|K^*QrPgCR7p2n(cLDGjKGmLf-V#UEz`{L5PS*8 zI>5pcSEVu=RmMdf=EOg8hNboy+rp;g=n<4dDMaBLKWG}hJxT>;Gsw&qYpyo*<mN@a>T7L;%?EKt72=yj0{a-P<-;p7G_cT{vapDp5~5@+ zUOiMrEFJ^;9X6tXo&w4fnE0YITYoNWzVFH$!zZ3KozLE9XUDLg}U<9wZpGriO0DTp7q{Yob1Wd7p=&GY82O-jB7?s6S&4|q^P75Ny znr=6|EBPB0(S<*m4%Al8(h}>lVnA!CH=^0-7O&i5Grb|?8hTE`^gxF~6*=4`g@RH<^|Hc1g5Js|DGcP| zdj6aZB@I0u=>#T~-gI^fB$fO0ub*^`e3b$5pRrmXZ2}rZU0(>q`bxHnysj4}L79xP zziiM@pm=QMCbpePhLvJb1|eSXhZW>ayuZwCzk`F?l-fSK_?FeWFEwXYLvuwT6u+Cl z$RWOVk_)b4h>%S9!efG|@JY!oMU<#| z|73Ldq?8Kwejt5!?au2*2~q4?Pci!w1uQc@Lc|36q8J%1j*v~CO59A zn1uS`{qFDx6ZkUE;WB01$Jku5kFMg0CN*aQ#u1oMh6M1S*MY;yz4`hiCoP09hDvXIo5 z10MajS_`$X1b1f}5*c6mECXY~s!!fWqB(k*ph$mJr1^~jtvBY3v__b+rsbOCBTFv+%xpp*(m+`+4YOy(+(Wo zxF_PmgfSt>yZr-m>tLVSU1FbC!3WP0$xrFTvCd1rWiWWUK-s9uTKHvZnq>o@*i5*f zlz>JhFf$2H*&bFA=K!+Y0PiM)tf0gcy;p3gy70rabKlA|?Kah8~Pj+&b*-*_# zOUiGfxoVwLN2{+67WUaI;a*~j5iRlZ4L1735}-GZ(U`%SNb|(U?kDx1v0DO9HSdyi z*X=Fn)>od+JP6-F1dj8M4!?c7Jj(F~MfHn@AB=LS+c9l2%W16($a|?4V^buRC0|b6 zRT>&;oXgtUf60$5#H7{~FFfgL6n;b4jL7Z3ecH5>>QDFlMi<*P1)sE_#wkEsyI(X- z0@i^H&;D3`mQ$HAgw5>sD%emHkowuT4YXj-(ckQ0%KD&0kKoP@I*`hnJu3zj?XA;} zbtu7a@pO|2cO;O!|3?}fbKK0Srw%|=n_Kaa{$I@g6>{T>T`D1jD%-dCWtp17tj|fh zEG^q8UU1|86aK_u?BJSmU>KRNQ_-NCMnq8=)cd^KZi#m3||>3 z6Bh5&8qEh(5SBQrR)3$HViKK#7urz=xNHyyltZ!PWAv8~Jx*T)_R)dwUbgd|qaU-npm1ASweJTl zF`tkafCMrT2irWuWQm+L)bC_CW`ehm3sE+ij@4dwG4rQijB*XvAle{Md(CRUvHw&` z^#l7Kj{JkgeBMraq}az>ucwIG&!C^G6seRQ`kCrYg+KXxA((;7PZYx#4ERXh-L48T zKGmfqsW1c9jv{xT#1hIMS-_CqF;%$tjjy8mCa*zLB?XV}R{(1{?4=E3Ri34Pqxa`?2V?xt*Vm zGC#}SlA_-})(l+f1sXnDF-fo-YFB3*?<5wD02J5+CSz$P(|eW`nHaZ3r%W)I^r@hPN5l>d@CKJTzw z)g6Doef9OIMEyceX8`t^^**x4NVa%4B&ca%idot^9B2dKt;Rjg3HmI4hdCNsz15nd z|5vj9PriJ}V%-{YOZ2J8tSAI&3j={= zk{AwoZ1q6NA@JFUG*6<+AX#EjWs&Oq zwNz_I8TY-K{HHw^zrEY>5+Y?@ol_vo?N(S#-0!ev7{1*?3!hg$)Zg+4>ZmHJ( zcpDjQLl}a?bCMFduA%Zc;x)VH|neAJp6fgMx8=GN;EFKQw z8!ouckjyP4*bLIc47_e72yaI^i6b6$RCet(X4B_JrBA#)lnzl2*!MXGC&M=kpR;5F8;qic9G>D&vrJ%U*Q<>b-NiIh?M#FO z`i)T0+?tJC$W&Xtp<3|JBU=}4p}jW7q0Zn-O)jH?2XEVW%tkhWh1Ermcm$P`$u%Es z%+4}apKB3m#`hW1Aq?UpHMM_zwjSQ#LQZ^G$A1T+di^2svk-v^^Q#1FOYa6x+_im~ zy3g5+&X9^buSTWYSZ)-koC@83fmmJXcrnt+^N=CwSPz#Uigi^kOH^+%u`N-yggw>V zBo1@3nVFAFGEpeH+q_)0g!x(CoE~!By+zPw+ybQF^He*zm1Hi!MKvzl7T2I)<9U9s z+TtU>jrFTXAq%#viqAn?xy6l4R+lk7)#nj5x<2DqVnZCvzjLL^643`bEqcFQp;WZb zo%5A>!SY*-&1rV|1T!}t7|}6C@mNNggxKb{z@fh(UjSxg-N$V_x9VxU9O%*0|9@}cmj0IKzW2W8p6~q& z5B0F-nq!VJ=9o7mZI<^0s56P7e?!pRbnvyJ(Rugqw|dAb2y;2=(z}xX`5tv|5OydU zFCaBvw*?80b|NS0zD0R9T-d&?8%s`qN*dIdT0Yt4syC~yf{_=w7tv(EoW-LBj8N$& zFyVopLFfXXim>qV;=N-zN`XdSiRdc)M(HLqV}Bk>{S?iPpqyWIUnQE`>L>1o<~WLT zc(VlG4g*@m8Z6=FMKJ9TI9ZIWiCtYMC*&n-RJ#vlJ=nRsuK=}DAI$)#VTp;Ch&lF! z9t$W>g*NA>znYwL38gwdTR=yLoiM{?h7r4jbPdRtt(Th?z|V!Sa!#>?f^u>6eVRPz z1_Wx%7}hon-Pwy+&P+BwgS}N#(w(TI!MZPuU5t;st0J#+?l#K?3*rZab zwTk#1APpOR_L^yxReoUzl9)DYxIddXZsG+gw?hJuUI@I&anPc;O%S)x%E6WlUdIrj z7xtD9{`tD6?-<3Cmw~#A(@-tJRfaF5U~^l-vk57sVp7Je0+I|fl^xHNBAmIKsw1oK+2z$aEyOjkAFps%B@*nS} zq3>zOjutksnA*Y9fwLGK8ZohIBMH|V+~ae38-0uyGTs=utksqL8hUkpb^pQmmtavE zw&8YSTDSvw$H*H)v(}hmzL96nj_E3FN-Rttbor1*MT5Ux!%*#U=tRteM(Komi?ef7 ze^ZP2xrENxR=8q~ynRAbU6dj3J38f&^`2Xz_|8|S7Ejao{snRU>PgEs!>^|&NOALl z?we0>LX{r7YcJoloET8{(KU@K)QK){R;(yo_+T^LPu!JS)p!%qJ@{N}$#^47tT{o z=9{!ZO_NvKKmY9oNKibKTQ9^i*?p95GeS;8So})Wmw?55sSwi4kKP~{8_u_&^BJKf z6GyNJO}j+U!3hVI#_NB7!PEanqf3u=W0F62E4?qs!I7QR!k*9D zh)8V>TfgEzT;Qr=ia57!9Ic!!83i@|S}(UR6T4#yD)-WHO!^W3JEMBWv%qLf4i1#}{DK@WAORgj(ps3B4 z{S4}lQPgkV`L_KIH98>ggEE%%!|SCC6WS^j0D~iB`E2ThIL1lf`?Jm;;wB{Wn!3RI zi=YRv!otT5f>P(Du?%oxWamX|XTp6N4xa+WHc}B=qffTTEniL9plp{VZ5MGM>7bXgsMXS|wCC}p`vE)BOjIIQ_cx8B z``S=h2T;BTHLOp)cC~@8Zm!M?ns1CinvZLC!^x~b&3{Cvh_P{l`IKkwI7qp4Xb^p zb~gZA_}9IOY#MEXNgI1j($;SX28mxXcSptvb3Gr9kcxKt-DQHZc%EIfsfJ~=OHYw} zw_DQtCjGJMtzpIiebYN;!Nu%5pSErv@8wrJ?K**S-e&&x}PTDseQh5L>D zxFd8L8NC(o1%rDUA@Z~ShMpg9G$T!JU2Dfj6-iq_tCsbHCQE8+y7RMaE3m&64 zGU0$Rb-GyW=C@h^|5CDCzQ!N$4)g}WTMP7S!8OD=)2a5VsO{dLe|iOhd_Dz&e_J7i zuGW{1?k{^{FD=SVDf-_qkbloaEyt7LDSQzCx`}Ja4^UK(Pb4DZW=zPNrz@$DMai3- zO6}@v5>}9|WiX)o38M^&p(IlTP&Kp|>`D)b&lUMf`YG5T$QgCVnZxhPd`{O`xVSQO znMNxfs*;%C&M*k`RI|vYgsSK?iWQc{>7tbC;D{MAobVdfztwTjC|}vHCSXp1eHygS zmk-QylgBb6fLd1bnL}zkt<%9cCC|Zy`~~&5@X7;p{Xcr5F$gP37xrs01K|of$J^h7 zrWD#t<5uP`op25J%eYeMeG|NR)aenS24E^qD*yZ{?LFrF1+>9BJq%KG(Th@o;-+Vg zr3xK|deaiLxh5Q(Bpi5YGc@FFK71ojKi4L*lIKptG)&o7C{du`sToFO3K+3ER2H@5 zIj}PLKH)B7n1>{@FRg!2U%7n)oo+`RI^UA7oB(jW8ly<#cO1jdhO?rjJ*k$mCf3y{ z7SZuHd<#eDsYUvH&Eu)fUe@OJ2J*wGj*KJs{b~dTDXov#yYaWwWYeS)eZU4qf+6)? z?ji}>tJC#2F0wkP803nAA_?QB)#O(wDsCbP-mKwDZ)5gzlo>kTw2fM?VWsz|UJCUr z?D1e4UjIID<@Yg|TVKhWjln`ka`JJIIWtqTRyr=vxA{^epg_>- zWReUCR&$P8Uh-tPd_L8g5diF9{ezTQ6oh|qvnMW`re%ucejy|r{l+_)Tt!6C4wLnY~N-qex5`P*D?rM6~4}Gb%7ps=hJTk`~yv~AotIM$Ye(C77 z)A&BefEx7Ju!W=1Z<_n1&(Y2I$kh=WdsQf@hf(m4;gLr;0wm0KPK1P%Y+Gdw zL*z9AVLYQrNQaq!t(wlpqgq0#oA* z$Fw$lgDOtd#OS7KUoJh0#%r_iVK_6@ETp0f9cG-*Yt~R@`vasLGB6C8y4!r64C;7r zJz}}VC_=h2v1SqAD&)s7HK(<**h)HhI8A;Kj@3XSlJH=vO!eEmYQd_wq%>=0pTfF3 z(+IkG*9iD@tNqVaEjH0Zl_XjYy3&!PNm67hr15?b9e`;#M%zYesz zW^(4j{@z61z+oEt(zXM$M0f4Ho$MD)PtMrn0yAxD5axO2zH=xxN0b$GQ?Gc=PO77L z%T5uC)kX}qA(D7YIbFa!Mk;bTi<}uJCz8?KxTJ3m_q{mINq!BUP87RMHXc zar@N~7-5bA-W$IGQ{;-hID1IsPqVY#N9K0aoq}*T!x!+;C=t|y+=gUg>nHFE;?ONJ zrE~-I3#VdijYTtB)Eh!6bD)Ub9e`{#NDIrOl))___nnaW7WZC8`ONQw6jZR8R7Ns= z6Hj4}7Nu$-PHsTp+y+iCYpS3Mdh!lWI(lj+mXv@Fhq84G5z21R4)q_TG0&O+iE#Q& zv!@fT+x3t$UW$lXCcB9^KxOx^jc5{ z_=lCGML1~4MSA`!MG@L%o$oE;VdiMyo(P0Fi~ZD5>97u`2;cDwWu4Gi-Gwwv1!IapvQ$-^nzU7H=HPg~ga?sY%gSgAJOYJs7uvAiA_&tfn5;T4|Tco<-z*q19|evIB<^Gr12C?Zy+n3#oHjXvJ(b>YTHXu1Eh{!6iSb6ch7W9I+_tFla|NCm_?NhFPi zzeF^`&+wFKw;$A=Ydl7e{$K}n)5(2e)O;zI_HqbCX*Q??0V3|lpj*~mRXBW4R1hkQwaoeevAOTlso}jz)TIx%JtYXNfJUQ`zZn) z;-qEP=t62Qj@)H*!mp`74xaEg1o`@Ckbx zW)x&Knv?mH4WG~U`9*4=28BuQR;zz8@#Rhb#5Ux)oEoec?fN=yPa%hM=-9we1?`iu zq`i#)4MpQ2E|{I26^2qSGKQ2YC19DFJxCQ>)f)I)lEwlpqgG5V=rSnL&@0r;tzWc? z#IOmSp?MV%QVI5BAQ+`-z(?+{FnJSbf-_$8wg4=gUx6n1+|n|pj!&N_!P?|BnG>Ew z+3(;(UAiqjwxJ96@fI?yrTfQbN=A7l`HoWS`|@GO(d0TV zJG^*@-Rl^03MI@`nAFlUTGU=z{i$wsTcLUPB$DOQS+3Kc_cC>+869t~InYjriD>&& zwwJXxW}4%8^5yH_7cYERc^pK~a35Y9+a^rNa4>D=^LhK~=(Fo~EXs(F+WKo^W!Kf> zw}wG4Xz-U0z#*_k(BS-UYQ4rM-DNhFT_L}@+v}@;4CT%kY8M>x94Zd$&p%yt9O5-x z{7tWd1A2uVrLX?YzU`J5YLwP%Zxr5}<+r8GZ~j6k|LQfiMMy)~h9*W6(tSSyCLyfV zPz3@-y20<~13ytpjCl5P=!BHZ7<5oe0E;JiPch-3gV_c6sWew@jZ4{Pcy`Y%5#E~d z7bn7esH$?!+_uH1-(FTH^OnJ44yTlJXDU{k8Z%5Kb9T}-nvVHE%W)XHQNEOO%igN^ z2;<*rAWEbhGAI7iia04{h#d>_{s6V!j4w#AUZ04_B_v=Xah4%}{;%?&g~P%Fhcar0 zFV@7ovC0)EkaNN85!jg4wTL4hd=4c~Tej;qyX7%WGDI zX8>1Yhrp&#Dq!OhI6S$#&%nHElS+mx$$F z2%LT)zN#ijL@kE2~Yt3p@f&%4cCXPC*?L~eo^DTJ9RABT6L^F1j#2et9gbXWCjW(M8yxU3H*Au+|L94UF zww@-|amT!QpgNiVh!)pSBR@*bNv$SNK%j>T3u<_X6tkzx==w~{>qVCNYG7k{BCNm; zAhB%fggU5x)#V^UTB*2%oEx8{GNkeZ@NqZA9=Fj4vdcfzfFe9#nxH+J7)wHe6&Mg1;r{u{ zeVegtM{Sw>5s^z@K=fGTUcD!1ujfRWkx+DeHX;7Oub6F?Fq(8b5yG4b9B+nRv4@|kAjgA3qH<+!#gq0%vm&n6j2N}t=Mua_n}n08Qc0zu zbh;4TJegiBhLGZf;~ZAEn5lSZack6vMVj|&5Niq~)ZBh5nXGlY4&=PfF$_J7m7zHf z#|A4o-I8T$OQa~}_cX8FIdiLG;`q2QYhv&k4+Z)l6+o>x50oex@8`^%jCYz#`ZNf}DWh*2L> zt^)K$IPss!sN$&4yqOFP92R5llfV~0h%Tl1QR@%;MTU!$a~(0@0+6Vr$3bKpT3rN?ql`G^FQA zhI(t*5j1PRF0v>}CDlANZE@+?&KY?MNHo+4R(cypV*x}AfvQP0e)L@mJEx5xgQG9e zsPu)jxPrMi<2O|FMLf-|jo_VQ4VvXP6Q3i{>5C+M03vN5VF+=ge8T!cNJ^;mTf`R^ z@0eSGL3zA*C+Z|6W<3?BnJCeTO^vcKbN{ z0og$Byve!N=Myz+0>Yf7M05$%Xcv|8W}gQqI`PT5-6dP?HqDFKZy>{e z?)UIN3W(brp6M17pszIQG%6pdvqDX9|GTdM%1B$9^p}=zQ7xG^V`5Q0nC`#X!c-F7 z|6YY41hr>Y(%;!SEIsUVDDa%XsygPXT0PL zP<>i@%4}skH*rcL@G zu-5jdqK)zOzUx)_im45h!(;89sMLZRR&q3%vxF<_5VUPlpw2 zXXagu(S+9B$B_>1R^}mDpyKxbwi1?vS+rYm0}Q8`X@;xtA=&c95nE$;#U6{N7j4M=l-+XCMA>)3Y`A^HxuX ziXV?!z9JWg`v%!?^WUa+-#z7Z&m~?{_np11fc{n&L^xk&#qWp3vB=EOLY!ru(>^Fn zc;a=R#opzYh9>Gx3pE|PEB-YU0}t6Bc1ZGL=FSsp-H8Y8o=RRTa^>ar+aL7t|8W}q zL2f|#$h9TC&Qg0k^JV!KaU3}Cv?FXKW%TD$|2E`N`5H@GusOwR4Zjz!kq%g*%2c7P zeC6vT4-jI!hx~9(($Q8|6S751B3mV(X*z|PXR_#~SO^5WwUu5&3@qbwhnM ziJ2!s11sZl$S|m-+c%Btoq1mC{)DjMdpU4&)90=F9l_}T6s|KFsb8^Wj2BQq&dYtd ze~I-gT^OW#VLS z1<&+T3YHuraw)?KG*@++_9u4+mU`Y#ciQQ}3c<8LNiUJroB^!3X`JA|Jkk^p{}IDr zw8^`IA53KoIZI{~Xs;YjSnDN$4OcnSrQhFw-5AlvV>!$4Ou5xhqBd!tY#^wra~&c= zq=Tn;g#n9{^L(%YmUm;5cMCBqz@v&1s7qpf-d&oJ4$fnZo68Pwt38g@mnp1rYnCMi zoJjblT}GkBpeJ0B9~eu|cx`ZzxV%b>lyU2aS=4FEFNwnplT^l|y6Xu8e#X23LX=dQ zblP=UfTM074gk09tC%X!N*DEL#_g_D>JGDb&V85J4@8$UgGRJrHmXJF^3j`*QiNqj z=f+P!tXtFTDv5%H?j$x7ZXl!oxSxm1tc>S17MGZ`oH8SxbPPy*+6vgwgues>?$67V z6ojVOy1}N0G<-PGsWk*h2D!|c%Z(|=oa-hbHBa6-=qGc!~790BdK*4o`@{(%9w{lj55B?-M9b4K|;vsON2N_ zr%)~J%ShG15Ry$fXdSDTB6`^L{^vsSnVA@O$;Pz$aN4`xxUL1+1S{#HS9S>lv4jMM zkM`2hX%xRy9E$Rmdbn>|Br=rpnU25AWS$@z*(xY!{7iu`f@}B>4(Sj7%W_5d9w6mj zzuQS01*S}w4!S`?0Jha(BS#y86)lV@a^2o0?RWfO8t3oOE&jya4Nucwmhu(eElW** z^I}xdy#y)+4rVA8g?Y!!^Nd7AR^AD_G7=Ae%>cF8~I4PywNW7>6s5c?8D&1G)6LMuB0$4f$WW1?v z>u1TK=)OG}mP2{+rYil5d}^LodtteDl}f0kR_BbDJHx|}dKWv1`d73*`<+ShmV_J+ zRx!_<75py&%IG<4h@}GNtb$@c`tYL`fT84 z!OcptCQi=+Gx34MH0y$fEqdia9!z5wECa7*_f)4&r=Rwnafe*3)iKvzN%5N6ay?2% zwQkuaZi1uuv1l^edr6fh*9?8*?)YyiaisOBS&IK9{U5s|Wqj{@q8RRM^^wlIsr*DmjIq|Jp3R-*hBm8A<=-(K!$VlO_JC3>? zN!-0pMy;roH)5z$@zQ_8aepbAN(k(s@iuL{LAVmxFMZze-sJsPnXUL^*WF}@+AM82 z|6Y+|%pHyuqDM{;$V9rIXs^?}k+h4*y{Z4&fR~`$X5#bx$Mz7%Q z=|gxk$bW0Ei*W$I028_TxUvZATz{>;=n;r@$&jsk%SCK~6N>a*GtJ9|<#W5a^teLi z-~*x7rmf40ZO=3M9~^2v;8X%S#*?_^hb#Ubs6X z1(%^&(K$;IfA}2^r?C15DHtv)EI?fpiij7kh^wGck*F4A0R8+XJR~!`5E1fGG><$B zi(xbp%buL#!b70T4xz+Tok8Y@ksm#eH^cNa;PR}x$UHVut9wsYgQHqhrG~3Mm=U`C z!IWWwogPvX^P_*a&R#xDAv^}+T>!2}J;^IrKn!Z&>2=)9_a4AbkT zNwl}5XrhkltbV~=e2Cbl#PrC+43bbB0@rsnyuqJAIP#i9VDjR(9$^2xha7IN#GZD) z;!?v|X()%Srtd(asLjK0A&Ccw=dC!3>c%IC?{qx846{ja*_+W}k$4MU-hJCcyPz>1 zL`jAEA^*w%y%+-vmbQ48GCg1jV;GT6N=B7MfFzqv2rz!!R5xWDR1v*4%=nm5@e>Eq zQb1;SK9z(pmo{G%%R(RHA_N%Qra39++}+s%_a^DH6>Yb0OiRYBYb#(4J${y9S2Ckg zqKpMg#qt*NXKW!^G2}clWDa6-(TtiMAuty|QW-)T#02iHAH6WkW}Pj{zO(tbkXA!Z z2dy_0j*QWi7D|1;xa%C5pGIDBm*};Wm zbB2_{$bu=gh1!BA^HJlOmFE+INo#n~gDOjC85ydC2bN_DU+dhXwsnSAddf9dY+n0w z*Ojw^QDP>&OlEyNo%ZiSUFFRo3Z7nBc1MoCh<~1!UfAO!@tMM)~k@_Kj`v*x-9idHi_gI-i`}dC-0Kj?#_r|zXX~Ve*CnLixU+OA z7gFmJm7GZ&S06+(3`^VUn!>70O%D6x>YxN3M{vcX>JU&r~j>H(#t% z>J_p?ibg-@A%tuo=0z$leF^w1htH8EALN7%IbxBPVu>iPnv^V<5XA{VdJg3Pr(cAW zO)Cyqz?m=(MhL!25H)Dd9DrKVPAE3e7g!`fb6Zx|Jx zJW&}v;93vX1dsKydIP)J8&-f>+e_IJzAm6ak*4^l7Fj|Gfsu65=vS1_9FvE3sz(=V z&VWCegBlai4>)6L+@3b%)Y+1;`|BQqx@Mo5VYS8F<70VbtnFdDzFA8U^?^`W$9NX& z#YudiqX!L0z_Cw}!PUqH85#Es4#unZK5hAr^+Y-w=`)6u2Yv$<9;+?ueCUSkEtB^4 zCiKlL(GmNHhrZ3{_?Xs=b)A24!o;k<}2p68Ea8&`IX5*ixNKb<+2w| zVw>Yk?KDw)bd^IRXw}r;Vy4uT2mkNzDq0|(#NIolT<#igO+D;f$mKm**&*qk>T@Y)P7xL<|)2wCH38tLWYNx>x zON3l7M3cDy2K=_C7HkB_{Q89u&??Q}!BH*V_gGTl$tUDNFLwE}CLup0&nz;@1*04i zbqBR26~m)Va2cn1=S~Dn_l-us&ZS&|JoA1R)aAB>GSr2NzTPfX^|2*6YP<*Yd+x@% z-oIh)^FD9Z>7lIDJofal?nItBTq5d8a%UA_Y+96X;DPqN$clizofCW43-ZBR5@IW~(??c9hIxX) zML+##mVgaLz>VHDCoz8zcf!kdH0Ksf>Y-oz9ZmB;<^Km=BLSNM9{%O>GOAH8aWkwp ze>*3x`|9~_S~imM8H!xl8m9)JeC3QD#xHGTmrs{1CX$Mas1n=#Iaz%sOcnyyz#ra; z3gc!MnMOq6e6dJ|Tq}2{wERGIdekEUb#dH`2Z_!@m<#Xy zNReGXai5^-9;}gvrz+Gu+W5^|({b{>(Pl?NNV%gB;Ed|Np;SE-XL;-q&TzNL2BvQ<`m52S-%4t+5QMKd$tdD*!sIseUr;@>86L_hH8j2v zOF1p++&&nhX7Cp8=gy86bPUIG4!-*gHC>fb%=@6L?gixJ=+EAM&{Q#T@M+A!k)385 zYxq%q>t~>l(8=n++?P+^HtivXHex}kl}RH`8P!GxRTVL#AHEXT;j7^%PoKcr<69GfRzeP zK=+Hzo7HZOVzaPd@Sa(xdtyC4HhaN}3X|w&sQ!Frw#KPIS}%qGd2K@8SL6DUD@y$+ z1H#s@v|pY4*^t&Z;R8fHaVUbdoGThfY(qSj&5SIg<8uW}mmjKKq^b+z)48nOCMfT0&<=?lDV?oBZ^Az9@JYXk;JA z`3MONA&zgjmC@$aYro)r85m%9#Ydu_}G>t`H4ZO)|SioghT|?+VFog;x=|T z6TwjZn<#YufR?VnmLUoBe^Eho$iAI7QfrTxgCr8yBeLeHYCy+?k27D8^;=>UNf3Hh@n6!2jGf# z2^*4FMpLpeu33KFM=Uci5X>fw)6Fnbt9 z;^Vt`Grp_!muXWQ`ND9dAUGUws9u6v34tH5%Ec56^OW}Y9o}2fF5K>4D0{{w?;%1G zG$1G!g~iETS~-wkm)XUMM!U=6tP%-Uq=P-Fktun!P{%$|)+vix13(b8h;x_TohzyD$}AeR*|l7{fwY4)H3V7Q69I?a`Kvtpikq%zsXr{L}fZIVBGqqTf)WcF;BW2BGEyja zZj&1y9;~0Ud0Gi4nLhRjZ z*_H2zb3(2=sC8qv8!f$7oR1&B-|HOyWAUzp3b1aythxM*>XZ}uR&QDe_DQRd@*m*3 zZ5Y9Fds|mSsFH;|{sDbx>-ArDd0!2=m1x06r@`KOjhBrNS&p^0_N{*g@|8I3Z&-!| zv?b>sMve6?(ni&%%z|@1w#O|bVSXwo<-*dVZLg7rmE74#6*>wf(hmOo7;QD2#h_Eo zr`*zDGyHoC1?I2?i3sT3{DLaIS~;*Xb>?7D;JM#-@wdSMa1D?F{FMA^_OCr!0b+<} zgDO>@HLjYR4A1VjX4+oSHxJQ-e0hzF>Y_oH#PlH*LG*oelxg6OUwR7Bl)pO3Xu(ZE zoeJu-*ai^YToUQ$hEgK4F}Ixo7AmC-%AYipJe*sT{oMIgv+osZa1FfV$SvZg$$=ovb8vCo0B;Ot z0m(<8wB1X|LgZtc!0>rK=-I3gEW`8g2|F*voVS|v&BFzQP!buK)lL~Vl#AN0nEW&$ zox9GX#u37u`}D@mk9|ovAu1-8G{r~?iiwiq;D%*5Go7FoowqpW&ID|F+0&yo$G7YR z=w#r^=(8fjD4W!Ao%qslJKBWbAj(=}<|Ql$Gk+j94|ikafDN_rNFOn}(U1*jx(2EXBB_dCZVXSiqvHj5jKFBQ?%M3c1yoxViy*M(p9rz8dm4CYci9lraq{< zHdi+|R=MnGX}?fy(+5C~5xnh9DP3Nl{d-H=CHrJc+V%IRJx*Bmg$u4rdb=Eh$S`9W zk-V0~CREC8oWSib!1hZO8(3>|%+9>rNaSiDe$W%_5vdsLw#ZhdabNPd(xp$Lz#qS% zp0_hhwQ1cbD8H9FKko6?P#`f40U|U%XJ9@V!9M>Z$(%%mUZsEdp1ZAo5Fb!8UD8^^ zn2VIQQjlTzWTI19Lpn5XZSidZ_VD!JUi8!v8HR}pi=!-pL|<-yb|3=u>q0be*`Z=| zo_&%Gi{pOZ!MAHie`1v(ft_TID%rOwSNKeZI-TNoZ!{I<^~IXuBz+EPly|?xLS{}z z9WuIVpQfYM$HFqY_V&!v&@^!n3+Q!p>VaU8fS{Jp#G?lRP3=3}od!h?Gbuw%>9U-r7QUTn;AlqZ*Ao-RRAPDJz4Lz-PTPR)2?ZavS$*Ait za)hcXj&;@5LM-#s#`BE!&70p<416lK=hnV$1LcnKLAAy1w2!jqENMN$@+^gdgk#PJ%nm z2HoTvu1ARA8p`yBAkK9j1Z_2RrbNeouBM6nL0oUa^kPvDbZVZlw@;PcBNEhi2@1LX z#3BlHeI2x(_DebqFAO6fEc&y#WvN=|M+Yp;W+*` z&crJ+7KdxPmODPqP(9<>KDH5K-YEG=VQdd+Zrm&>4fCtP^uW6lzwe1kGU5sTDhYTF zhLGVWs+p+yGN|#5U0|NXlbF#xzva6UNN7qPWuIAv5jllhxq=jO4LfIYir*OJGxzoc z;y&8VxR3p38gJC}jmTm))TP-k-3q#<=h55*Kj=-Ux5!SwzYA;TnNPzr87a-0vaZOL zF`#UZ!29%rDI`cd#^J6j)cUn3e#%=cdgO20BrlMNFd`iMbI{sV2Ev!52_Re@G)OFT zIDyZxoQkScpFT)-oK8<89oF=C9YZ?onf;010&drXMh&Du9{0&7^Vf48!=0s9t|cOE zcppGEu#X4IYBK9JpF+pAz)zrxch`fP$^CjgyL)1G9)BgxWx0E6i%ROn z#kMd=NM6W%QvQ&Q8Q*S(Vc4@dX9oL|U!=^>bY&z+ULDBxt)8Frg zn)=AD8&lOkhn94$gp|&I@+)$vj5G9DA_mejdi@v*=q=_^AHQ8=1&=F6g!0_53kS`R zwNu%L%bdDx&x9@fo?;GkJ}RrXZ$wV|`QcaL=}1zrN#z6jQyojC&W{hX5^mDtX>!p^ z8Kf3U!D>#B@>fd!#eL=RT9R85U$PdDae1v@5jBTKLV8%1JN9$7PaC{mlu7!8U!IVs z4zI)|j@*5{vpwFFU#ocA`kdrx{kZ+XMyNwnP~Zh?*n0@yD{M56=S`K)$jli}_}Z=8 zAkF&YkD3DKbfvXAUEEC#hqTVrM~x-DLuY4GK}?>6%Xjrp-w@~6t{8Yr*`{>x^HW{< zA_MzmLtSQmwVl8AL1bROe)DH&FLqhR5xJ7{!E{93ZsmMN+V9kCFT0Db61dQ79x+~_?o3=izW=3uTj4dblTP3RH`uAuF7)H{Y{T85_5tm%CXxah#mWleYAI58##18JM^Im^ZfCk+#Q`5a1 zrvXijgHSW(Pe7aj%Z(Qte$2rvSzY3FS>!PxGR;Sd4@r8KozRjC@gDW9_&+C|JETA+>Q5 zB^3SKdI|}-@3EXF!l904mORvb={${r&IQWU-N2fDkvO$b?JFiF=A&4Tdhnq4^+^<9DU>S@-`h;P2npo*!)Mom<^Fkc z2x&OwDYQ@vif?w2O#MTH0(EyIZH!LTA*HD&1C-KPQ`Ft=A_GG9o9D@03@??ZwKgnYxXNtIgH3WDCg#}L7Cz{O3Fo#<-B&7<8O`t$3C555byYVQ z5WT{I#6-CVz&9AHx9>RHPkP1B2jq?aXr>lP&^bO}>f>DC3nt}TipMW6i6H3vqv~ zk~*0_QEsws4OCrcUUNS|Nd>P|C7vEPoQZgD1dw$98QOnc&%Z3M5lkE6ZKO&$eep}J z#lLn$r(^T(SDS`Q^B0-z^p5IBdc5u#?!xMH`J1RTgze^HjXvbsBG-dFo8Ie(qt>Wi z?K=dYtY-o*hxq8UXA;ZS;;)5qHlVKYF-YZ89IFoQcgmqApgRUYm6;f)D{sd>>? zdt*MR0=F9fmxgu_0g!c8btf;cR9xj~1s)NB)et7lr%!YPB+t+hbJ+jg;8!TIW@||` zLSYO6<0Hk-G(syC^D$%4L?VM`h-%an{=jWj)h%x%N}v zlC7)=e3VP^H8_^HT$2wuxi$aAzW)$=6y63es=YV>NyjWSz%cU?JvS?=opA(t=_Gbegp6M5TC=vX%461J^d+o`8 z2-!(_0+%cOi4gQ&4)`;m(S3YxMnHA4>qj{PT}j92Kyk!%GLQDyPK1 zb5xWL$-9`Pqvf;~SJT!8d>9gVWBjk8zHSZ9JpUXS&?6F3sKq-Q~SHEtblSsiAl3nWG0Q6rAWZ4sBN8OuJ~W}i<(+CJLLUI@u57G)h^ z)h6kPbim8Qa3=RRX&ANQ#RR+N*N5Lgzq!qQ%au?G9L%7jO-R=(0L`0!qzAj%H^=nt zQmbWL@`X4l!>zrgL_ci+?s^Op2-mG1SMwpkl%KTEmGL4Z>YNXGIk`Al@uOT@DfcJ3MB0B>hTt}CQ?^gjmat9L)^h1YUt-k=QQv#hKWU(5Z!$XRo6RYJ7FA?T(r1gD zAsCxa@=R_mY|o3Yvs8j}aNUSu& z^n_ngKBZPy>IMD}PWA%JL`hmBu7FvH2 zsFvvQ@XJT()+M)u%!HP$B3?Gu73-v887_OA%CFpcKNSFZk8&y)+a)Q2`&+!7G=zFM zuUSK1y58MexIV@doa{Z<>B)1D*U!1@sX4zU1#VKWXfOKQVE=BT_d)Sl+db}nIBrTL zd7Gk>&BCXvpJ11LfLprnaw_K@6Kk{VwPw|Hvl8Z%eNf}hl~%v#Mvb{s*k~K|$g*Sq zt77w4yT%n{6h!3l#<2HamgHUJ03lD&_3`>{?*;eOMW3j|k^5>d=6;W|hmTFyd&?Up zM@r8_;CkT7-$`X3wCG9yZ&20BC#2bF`A+A@D}AeaOh1CxaMoTGw~8`<>*CZAZTdDK zq9@4Fsm*P#4|#!$Khtl(%FIk`>Sw(E`P0qBOLH+gRJi}tur4Ni5b)whm{1Qb*_c&K zPQy|n=%5d)Jole`M_Y@fRp38EgfRW142aMwdJGMr0fMK<`9AIa&0zz?Mo|Be;0mU= z$qa6Ubx%z+-U$-pa_2DeE;vEGe)_j`(^N&aTJ5$;uD_PdWe-3p1|eL8EfyobFJt47 zjHDebBpgM~{PC=6smBA!r)$0>?D=^^_bWnpzm!N@X3>4d^tGd(B$eWtjvpyQT(0we z$%I5HJSzR$3-Fcd6nd}~x0NAkrba~0WrY(Q9fPNVw-F$r@(iL)m4f?@;ZTf7c=t=5 zES6zJmVXOpM>N#1Q(Xl_tMc*%Z|j zAq_VW`H`>z-zuZ(VQ`_H{r|< zM^a5)9oXro#pY^Gl7G)oaltPGPEhK2Ul@z0v}WW5UjNB>!4mWfPiz^FT;86NN_g4| z&ZMC)2Lr5LPRd6-@w-Z1+pq^tJq>S=p0P@u9X)`2Fa`|^2hyXSfzFX_jf9Ow551@1 z;L<}*hWdpV{0zw;@p_kmMo|6?0?M8qNw0i8RN1k`>FaPiG)FZ*MgZf%h$Ng(B)To* z{V?N2L;x=i$f>w>r_mj*MrVZD$ocHXSZG{aFJ~7QH%R79;^X=@&5?z@;Ql)G+xo~#pfz+R%;co_&cu~q*-&J97Nf-Q70K^umz9@- zfPS{qEq_Fp&iQWQ+s^6v{J@*0GYn9*ATYVN1k=-(k!!s(Sj@{+$)ITrCMAgLuWY3Iq*=K;ssyY24jix{=`S7Tn!kgKKbicL@?8xD(uh2X_b-UhjKspL6f~ z#Rtt={9(?j8a2e=2}a1_();3<^=6o~zCW7v@u#~h7wxos)9ZO(R1jJItPX}A&%akIS9$1O9GdU+RNO9zD}qu+~g`vu%hJG+yfFq z!oatO)(m!0a&u{)0^pA`(~c`U9q#3!dcr%-ugU(H=eW$!klw5qN4wpN;b?TyC%tHI z{W=y(k-0g`9hoT@o%4H?27}*agVyfMccV`!?83nZQ!i`XtwZ9A{+Ogb2cM3-+V6r+ zq@c1RsAQ#GQKsRfn?UwIw~L`aJd~f)cNl)JQO+ z>gEF@SGevZ)q4ABMZ)rN7MsILqgXQ^cL zP&S^9!qI;d-c0_wLUz9M)`;`>>|Sg=p$fEET^d@{%k>zM{ER>i-y6tRi!4R5sMO+A z6p`h3d7H=Y7ID=T<6Nq2jx2G`m;R0XokOd6?5{XO@4|*v!%t_z1@-67s@#lz^gP7U zXwi`G*NGl@w$Zpylmc(H3mq{uHvSMfGBQDeb?}sHHbB{gvtf-wURfb#;u;QNsEm-z zLR3Z|%Krn5lD9!3;`|g^U3NfxkEN&>-A&)KrMPMpcRJctK z)_*=mP<|8t>*%YG1h|f2Tiu{^h=LrNQ;_uesJKbsqY*0ezS?1xP=1QLF=L76;k;~9 zRwjg^s+k7To~mLG1~Bd|Ng-QhgJhkKu148V8wS3?uY9sn4q|+@$Q>Uou%kVheK9kx z!uvSZC7P!G&FrlmeP~xVLMAVEHIqwiutV`X`N$jv$DnhMWO8N!dMBM2*uG(hD4Sl` zZv+g*oBP07T%n01%^7@f$lk7A?izofq{vsa6VAOv$847s;<^JZ=P#ZCWuzwWmEv6q z^M*>G`c>;V+Ru}6s0~85EkEJ+fFt$IyuHoGi>!o?U0n1dkIQP5)jS@=Dku%N=2lrl zYO^ObrFSl!oOKz|+UY|R;NqM4&cxC9Ya51LLDmH}$LV8n!*1Xv+`X-oU*%kL~T!i<$Em7W8$#Zd*F*9;kTc%J%)O@jLpq zPX%UouSEAEVCg@Q(E4;pI4|nemfjF?H8;m#5z{VTkr(=9={%n?1MzO zwJvN)^@~F@k!pV4?lA9Ui`UwK6W1sFk0)wA43@hK#rUwq6pM2^etM)^xH`|Xtc{&M zmhKs@3xSIEYZ8WvSl?;vKJ__<1Q#eF3fi?MnCh@ZK}y!Ubhs8<0}!fYwR|BK6oAKAXnB%)5Kxr9c>+JppaMnWdRFb*8n2VFwn6YNl}h z<(zy&RfqTLkaqgZ?hjma8VnZnK|^YI3D~Uxg5IT`ByByji4|ti-#vnEzBR*tvk`Yh z7GM$O!jV(K74 zKLOGCSVtGuUz(Zl;IO(w_zQaZjxMecS82WeI01@Cx1fTIht-$n-uRZ#{hJ z8+Ob_s~-L@!9$H6%o8yKX(Z=+s&GdF?nn(nMB_Oz)4iYk2p;Mm|t9_ zIuty*<0ic1BSZZv=W$J6kTvZeE+}Bf$XFL(!LG>;GKtv`z9uZu)FL@ZfSPh;Ks+CL zYL1GH4Zflit>G$@+*lCUi2>YDE|Y=WkZdU1QowSR#UvIP1D3XBV!Cu`3q?>GBsIpqfiw9CQUL+^ zR9XOYS80IJf@*E~ahn&J(xM1)W`quTft7gpP6tBz1MynHo4J-BoWgI7o4#TwrI#EG zLJfq#>La64pYa1zjps{3mpDY-W!b8>GmyVney*)pNZ?OmvJ)!MB-yr3ROS1w>@=N?)hpax`Xy2=`FC2%MQ3(furcQRUcvb#|wYT zZ`Eg#_J;So7M5|`n;ia>|Jv&CVbQ!hJmqRnk5|F#mr{~uI8|NAX-vkz3jd8#lGdD8 zKS0}ibt+N-G;TR<(!+>j3JzGelSR<-h5}eNXZE4o7hU_Ujtj3KCTWAAj;|#Z0&cR~ zNtr0s)9Txa_i*q>Z5?D*B|M#X2|6z44X_rKz{ z`+3lgQ~$_M$`re)T4+2r7gE|W`n(TwO%v>RI_g(;eWJRIb^5X7hJg*ah{oZdPqJv| zHPgHPwM@927CPX!b2KN|VUPXjzqyyNJ zfml@ZLsgl!SzjiIhNKiH?82ASsIoXwmzI1!E>LYsnlg$UVWg@2rd-+#A2_02Cnrv| zz?T}CWm`F*ErBT~!voBLM6w|Ns0Z7rfh)m0mP52f=Q5_BZ!KqHwNI<|V|S@l6X|S! z_*-e%W~a-ohZ$LjrVXeOR2~4^6Okn#mg>f`i#c6W>_I1Yi=cINn>R}O z!fv)-lKeZZl~&2+{0MAnWwGsKmWb9T9 z;Mm31HzW*&R)VU`#a&eGnxM;dV==0)=3k0OzIUz7F7gLeS4x_6C`Ta+XsV>B@W)n=!!05XgDjUk0w~^8LX1g|k|kc6gPl>8|DD zaaODmg?Ii*a>2bBD%U`~@W2c|JP-$mO4A@6z8|KA$c> zx(kGq?{i;n&rhLOrGZAF?A~8PQ#K7Y^V<^3B;p5e|9zlE4B%!T?lDsaKgP0g3!!0l zjkrMD9efGHucVxJAEu0YOjo=G_donAe$rzXMPg4lvQ+Hb}C-Hy(*}s~n_Yu$xiucIR{XR=02$6+T zlIa38-3 z)&!o7Q5tlmEYdAnGUz5aZ+v8?f-igrN&@RtgJ@C`=+lhSAS^QRoN`Nn?~{NEIOuek ziA!HJ-AhETDiG)sBvZm6v`xy?0dxd}xx32ETV42zI`I=uzlK=n6r^DmNi0wsmZ{4X`3;3S_Lg!?*W~!KFOS;g=VA}D@|hWjnerqS zlg2$cekn@_Q6J{_xxjXYOh?UdaJdHAOnIhklYo;y)VXx-&e@KkX=??i7uY` z1Zol3>GCXygRJGgvDsFA*KqvyL?2>Jj=u4XAKU#TpwRWiVa|0B)@2>joSSIMOe_>G zi(32hY9Osn9U33p26xEuG<{4gMiGas!sBttA@qnR9Bgvl9S}JRzou(f<%d=w0q28{ zm?yCey%)A-O*Z@ak-CFYB3m(6t>a71O6}p)G|EEmbSXIQt>->7wE3Z5yT@)1%*XBg zo`1jf`!*?kBVB3nbbjP&jedaU z9P3{l%$T7j8~wT}MPfon`v6a-mw{xS-3`kqF1Z+)FW(W(cTC88MjNvD>V(l+sj;@7 zJu%kbGCi36-f(*A%=6b#I6h`US=f!6X*6p`{*hbskoFVR5ALk*p zu?+&Bt1DFgnl#Xu9Vo~qgC;YUY1?#}gnjSd7t6*ue8H80$Vx6DYVgG?X?k-mX(f|} zG2A&3T)$t>eO3;cJCV3%X z2{ot+;wRtzzTmZ`$N!6z*kvPL`7j! zX{W^%S?S6%3!FpJeRq@9Q;7{}&PZ-EK?_fTI^ah5t~ifx`+9iy`RpN@y%i!+Ty9_X z2*FyE3=(XKJeFH!;6k=p6XCnx$sAVN4#Y%m`7q8-fR^LF1VD>rpOap83B=eeL-`9( zwdAn0yj*fmuEOLC1iSb~1L9J=+naiB%1i}{ zll_zJ+H%F%>T`14)H56j^6c5v=4`2S%V~+mhZ|VHemW)2w<(HM2Q2hwR+g!cU{|%* zq#I4az>RL8Vu)(AQy;C|1G+a`9)UgLT`nni4CDF&5QX@sI_dokK`inkh&QtB#7)67n~uRGOYA}p)s zZLr;$p1Q2aPfCu34r`D_1RIgHybC!6ZcVyURhJ^@^5x!E5vHQDYXsIgyX1$U=^$qw zUl3+maB`841Fq(V;^`;*ovtmQ0jHBO%%b{SEKidMEUj0>`@3*a(<42dT@Nj#iQ0?1 zk__|Rp;nh>5^?@Smp3uCi_#%)E*uDx=!FB4@PuO8Z->;JS}k2R9jUuUWO_1VK69k* zKFYt?U>|E{eEm#+&1~ZO$d63@N|;cYWU3L>yUZJ?Zb^DaG!+EUd9r;l$82=Rb@;hr zM9g~+zrV>Jq1=c@omb@0+ZrML&e|BI^{e$#dVBD`v;6Q*K<8Ab){(z-zR^fkA*dc* z)=++k!wO){91Q(IAlh`qF+`i>Q=!*w+gtyEN50>Uk-cW>2^A)Hd44o!rx`F>Z)V+mrhQsIcG`4hfFNaI;<42#!`?5C~Oi$k2 zsS}?fjqC9fa}WFnNP&em8Fz$%Z5MHv2Y<%uJE@+9!?d0b>yMo!|K5It^yXli7D{~X zA`Pl~^kIpYFH_5Byh#~uKXm?1?Wq^}wQFilRR={e=p-#Pa*R$Uko#{>L&vU*3rwiz z82pEqfGr_QNWo3k2$iQRoUYbVV@2prFGx!il26jvB^8b%>JG1e!exp%Fl%vn6`c z0ce&dk=T&gGKD1hB=+J&@k7^s4x^0JL>a~ksB1pyF%eN)S5uLM_*j9e_^(~nIT0a) zfJ43rIhBWaH;kYwMX(peOe~jG=A+cCjXIs2q!wKvRlVxf$3<6aoEFMDt1oK)uHB{7 zR%kA35+YQH+$0~sFDs3U%aw^m%*GU^QULd0h>unz4 z5DO!bN-+TPAfOu#Z_>#)2ylm(P^nv8Sh7_`9mbINVX(y}yU1bC=xLx-I8qF?AS{#H z!@83P*q3MA$dV)gH#si34#oUoeb=mKkZ+NB*UJLCSGcSxax%0Bi(Mx5jntYMs022p zo3+KOwI#dMgAcs3p&8#Z>?z>Yv}jdhg^oo9H~CpJ?=k!GMRq+~ZkJ&JT2anh%{i>X zsUPmd#~X-AIaDuaH;vK`cJ5_57$1{N4|VCV-==@bRtl;*=6TFu>jSM5o0^H$K6#N` zXp7(j3+~BaD4~4Vl9xxeyf32HoYQyfZ2lcv8~dxYUze|9-)KRrk`p90js#$eK%s*A z>t$v76zFW!iSZo;xfRCfOML!&tyK}l%>WG@q&14H7wRoJ#@pMzRtoC#+MO7d1j*3 zMjgB`0nbjbbD#F>9gJX+YDgtK8`oM*at@4~3!?^2^-vmSR4~VPa6fy#3A2U~1UK|2 zYI(nBvr|6K3t9LF@Db)tJDiB$i6y#_BwsaDd9ghMbwvQ2v{hDYzlm0Znn2||G$LQ0 z-}Ef$`YHb$6E4Ow1#`(u&MCzarO*A|MqzY3H)Y>J^xJ*DQK-0K%mj@h3PO7V2HDrM zO9YXThOhsc9Sq^l#o@&Nyu(QGdq4Z?NzHYM%4La@Cze8Fb*A_3=D49w2zx#sJja5nm9LFC3Nc{8nvvL-ca%Lex z@*D~?)3REFKFkKhr-ow^RqL~*Xq!!kFO~=cvoTN&B$^Te`1}T0zcWnjt0>*Yb0{z#^*-G$44cXqttd6n?dtl3Q z4m!42l9=yz1*!wL?yFF^5)ic#U0TA_!4E=Gv!qy5t(srAYc??5i@2ujN8TDL{g3>= z+9w66+|uTfZLkcsWW&cV!@58Tr?{WaWE1U zta#wD@BMA^=KHmzoC%@l?o%8)rV}N<7ze>OgBvCPlEB|(A&ozKe}NN8QpZ=k;~kT< zk*J#f0U)H*6arUgdxQsIiopQ= zR@so^yCit64r%WULa6A##|wJ+{{uRF-9)J)d-5}YHTj&2u*{n0hy%Ka|3}s4I9URJ zg%CGy;ZZAQ3q~C6a#)256p#gUHU#A@40OC7U{M<1Q)Ea{%*qj~*A&@k5dBg!dyhGQ znGt_+$U9O1regpXG$rVk&g#BHZ87>L7otXmImr6VB2hRmw(HIE2IBJ><87eVSpVZ= z2V@)AzQDpr<(qH=nI#s)>kEm83ri-Om}`)UkT(-$9In`1;LuvY(2keiwgJb-?9i0I zr$3kR7H&{T?40lksJh z8Gcw}N?;!yG$~mb(cNzxyl=k8GM&4mA#cLcSW&QC&t{kUM(CBIx>W~>Pr=CFuS)cs zbJQ(K}2MR=L`;&b+q&c}`)l*6DPx7Frmk_cmhVY~q1k#v9sCpn?( z@CxW>NADl;_&rMz>;Qhyz$&JbMs#{xBWZgWF8}%be)CaT&8Ae_gBnlFX2@Yr$7w!A zJ@R{Dn8s(6z=@`xnT9esOFT+_<8$$z%!H6jLs3?rVh7|3-U}f zvltUoh5EKcd`!s!X37DE0i)=jNR+3j$_?jiIks~*4QBrp>08Zr-@ak&SE2AyVXDLZ zmL%=o`Nn>1Ve}^ON8eeU?OM?SGyxUbdMA=~5}{P}54JAe;g@I)K!JZSvZV zZ;r(hbe6-Mjp1=^ZzX!?rDf>cG-j?rX&~T;8pzvj0u*-HVr|=+jXjQ0CYMiLmxEvC zP~s9qqESjsGLt4BF-!0DrEtJIufH!3_r7N7_h(qneA(A$4HOh3qx(ZIbAK>+6ocIJ z#`#*sWPT6wUtk>cn-ihHvgd>NyV4=MC5u0VpZA4{JB2h%|5K2AY2fdI$TH<^)N%>F z8U$5A-2gL3+avR!r?Ie#n5qBoo%#jMUt!%!S@YfkAY9XPRztfS6af*qtbtDc+%OX8 zN)aF3Fcq_%-2w-1xsx-ym0VQ~pSK?G%VaY|7>3_|yKEpI2nAUp9P+|c} z1JUtOLJ^3uL)oelHc45x7=@q32$Wy~tfdoOm>w*E_!JjuB+8K>A)-iux2rG{Xflus zZ^rn=d)egH4>(A;lB~YufGXY}xxUCW6!~F9m_$Z|=zuMocJmM|nzbQb#jHvc+GUzw zI)s4_gorjnfjTt5By?xXaHtyQgdO{%`oTg}mUM2mA}ij-SnluJgWhg+9aX9gjTZrauS7NPUpG6OW;(8gw!+0Iv&R zmtLZn3p(G2Sq+n4MB+OqbPXtax?AWxLZm*9br@Di2pqE%d7@xa&vP{rZM=^&HP^r_>erH%^A82Mrl<%VIxr#U^kCfEjBPseeGHu>7W^C@pEh1Tm>Mos>0S`t*GXGFzv}YPv&weoNQwIInW;MemetIkSuk2aNbmQD|h? zmqy2}hASN@30JmGiKrV$(f*+z_H>LUuADT=DEvY&k&&YVD#$|h-*Rlq`He=FEB5Eq zlc&-w-K8Jil`?Gic~j~lE(_m?HNgJK;`;}}MpxC`3gedxI(2hs0Ao*x&LvUV=xQOF zv|i&N*oq{1n$HSwY)4fW%P}mdI~)be4TruN?{Ue`8v7N8(qFG{Myg8c6@-0KGap^Z$I`|(^p=#+A}1YB=k@~lTS zYz{DQJZvh@s+_fHl`T8Pv@ZA8AiFR#+IAv5>6MN98@dL4m4NAAKYQX#NM$5W`i!@vOR{pOGiMq1|)C>PG^W=ts*jiw>|(nQ7M?kYk}5_xO2|}p zEinQpQ`hy~N|KH9%Cxm~nrc+vtawufG{>k#7Zf|<6EJnlSp=!;BL-CZ9S!+#8N#7k z`aWuKcL^j%e%6TgOX_H52_%XNMcqDfS_TO$rbC&6mT46@;zvl`m2(p+F`Rl%2`Zn* zpz~GTYe^h9Zi6gQ&7_6&`gFsLxv3Ha?+PU)dL#wYE~il-n#d&nQQfw!daPA3N(#{? z#G*1+=1tt|04|Te-B7S1k@T2IB`AK*ODffvEGkkLR_z(4lB#$uv@y9evhcE?7$(dK zQF~_;0{njD2ZkNs!q_{kA96zjtJ)oU)-j}n_;|bG%zKe2VIOgdSxZ;v%E39X#j1v> z^`wJ96%R(i<0t2I8K7`;k&^Y(Iny+<)n@;vlX1qNDk0kyoy9*JZ% z?PqN_+RSezCyzI&U#q9C$;;>K^ZY)N>;8rb`s9yhzUPU(aQDp)_x4HQ4jWgzMqil% z8IFVS-H%e4`1OI=OP#jIB}v^JuXkxDwZ;=|UU-Fj75ACFCaplBhZp>zsR5eoBnR~l z?>aAupMCEM+b)^{-S^?uqxsLbWTo{7&Ci1QYkqIfe>AChI3-ymDizD1A-X|sfMQa^ zkqtYBdwl;oJRh{-9Jg}GCSOK1U+`wM(uw$ATcc&{xytBJF1^wrfbG`4F$A&LQmKS zFF1brZJfS9mN7a(^$fFtKDEOV;17=p#AgtOm*g($bvnO`YNVCIT1bQ-eExgpi|HFd ziFlTj&-=ZO#5Am_i3(uEV$~%UWm_quGN2McLOLXlmBLGbqTEt+8V1_A*iu`-F*5fK znqy6*LVc0Iw(MXg9N<9WrJ2Y82#C_q!KzvEuD^*Kexx3qcrg^}(U&q`Pj%If5lf{; zw41A(3Hd_Fs^&X$ocy*jRAjFh5*eRpM7yr8$YujyJ1>S2LZ_NM2#^c}1cF;R8Tsr! zlmI0f<$*3Z5C?OI^?G4NBz+4#g{q2_c+8YYaJUf=j*&6f=&D<`=in#lavLU^-6 z{b1x4XoHQ|LRiC(<~jfFT^WZ%^*c=KPOUpjp)a~>vG7`e5L!_;V$oE9F|8=n23c33 z`4fD1>X{CsFC(2i*;h5u>td9)a|M$PJ&~D?)*zedw&49y-huh^zB~OOob2F8SLCM0 znh6Y4i^xxy2L=IxFK_C`q>cDJZ@cSsbb20cGU>~zv!peBaZ>M7igJkpY$~2Fj21Ix zhy$1v#O1mpo)hBw8HLg3rVj6U0H*AV`#=ug)val7J8VhhYz!l+-s+e0t?C{7pKJMP zj(&HtnzXtbjKph`zGN(N@wO*eZP!^)AeFup-fr^bdFADFs5>B~?~|KA#@wPmvGc9) zrel{Q-Lxmh%saZot(hLZe~yzwTcfVfea-)2x(Fo0fA$PXa+yoZe(jWg`K|g|Yv}QM zl~2s)p7B5RX%>C}yKjU&ApL`Py7}n=v{;hD6XMryLi z#;h~{`(-CgP~gZt?ck|^6W4STZ*Dvo+Uouk0$`{kgmofos>Ij1RG29SA8^jtv|vag z;O~p7g6@o7|L|g8<5JjTb#F?rUu=bw!$DX$(UxN0EEd;7Hxaa+oT;on!U5+`7c{h7 zpD_{yGLQoy*A!opbcOnV0Q8Cw3aYRUA22I84Nw~bYman*=@q6LjD>I|3jLf6_&3n( z-$XGe6z6EPifbcFb}&HG0jsOim&YN&r0qP^q+7-T7!@%}@pYT=)~yTJP?wr&jggBk1llJ2E}gSi(TWNav#gU6v8;R4bd-ZD zuJtPf!!f3S0`Vb3r`Hcts+zX`Ov#TBrOaJtK(rj-m<-k}ohe}QkK6ys!=*#Y^ebOuN;0$X_z%&KZ8P z%mkDJ+PB&;+5z#PVbBCEL1(sUM*AJrB*(~e-vn$8>R}s18810Zj<%t@w&s3#53^fG z;<}Qmjk|>9e7w*i7E_IvLbzk!`_g;qvw=8%&s&{tIPvaPHGah61bec?952Dd@R_&5 z2s%F4bCXC)b$6A=yz9?~tt}^6%A|)KdNIsfZZ{ehgPQ^L2BD#uk4_}Annv)Q075moi9G%d& z3A$otVjWxTa&KjFO1$}4WyE;>=SlQuZ`8n{GnB$N>1R;jQ2A7`H3ieGq8ykr%vC1nNgWeQS0>^50roHi~qrr z3k(nWi$yXbaawHGK-QUN9{kh?4=uAIy$R)_F}$GrJ6Q{^g&7MDBh5LQ zkAl$<_^Dfk^Hv3tBlXFH7KFolsC1YqPU>K7S6VRC%{erH6uxXRGg5+(0?hga;p~lFHkxfUokD`NIgA=7p zvXL`KJ0LVadO}qJwQz~U^+zIK)RyRnDt!6O)TMvkX;!#X4sTe4Q*mXmX&Hb|#n)>e zPThiR;!uC6ha>Wc9sbcLa2j(4AJ$`nHqjFd65=^(n+9o`?EqyTFf9~N;juL#HSUY4 z$PLxF3k!=%mGjADvgM;ds2#1wY+FSVaXaJiTh}3J?GHz+dWal3a>zE^nP=aQlK1}P zmjn;4&x@%mE4ZUsFrP|iS{pl|du^P#ug=ROXk}N(9k@c*xF;tJkYWJTC!u^B_>umD zFBe}-zhWPY?rt{Nl>oWmoy4U&rK6#Pbq~f;PTz8A@XGS2yU2*D{yJMuY>;IXv93}e zf<_wTC>`^sM*zvPg9K)YgA1VLu&-f^1+5gzB6CvOnCZAOL4jX^biP>(WiZmBa-m(J zlIusaR;f#PB}n^R(}6jS<^GH~D)U|{UcPo}qTS3!z!|rB*?l^SnLPPeuj$zXCG#@# zV%zM+%K^U37cr%HPV?(Cwz(Bj{M3Qb@*`i@Dp6PX^aNRIiT?NY(mx-o#{E!13uGcA z^#R9ku$uAbG=Tfv^h#fs{TY7`I+y9Z<^xPW9pEX^sPmPA&s{%nXj`}eSbOM=+nm_TG*dtU1=^cE1?xT&&oiv~Ad_%Osh-0T{jOWe-e6i06^jnfqzFyuLf}@1yMT z6J7#+YZpgEE_NQL@S&0=<8|zBT+@F8t@q&~stzoP%XIz8cnz5P-G zY*s671vOac2*_jUdx!q`9I%r4I|I}=YtlIZdpm#W4#hT!(}djInBkXQ)+)|dQQ8hY z*!Ipue%b;|$sJ^of4F%!vjTN1ZBE&XAg{f^~dztB$4ri!w0*62q86 zPluBN1VQ#GA0mn>$v!7fYgb!Beb7Hbbc+Li@F)~l#gfs7=Ibv8Ri)}%79v3`Zl4vK zcbW<5wA83N6D7(3)bF7E@(?2wsVW;#Po#4t(iSW3Zm$t3hM^i>F^3l)h|I&Md`roR z2*98{b#r!BDTdv@MxfeL+Ei1n-sM~x z1kWF~9VsDVL^M6q{+gE=t6hz()Ea7T)xCRw)?ozqT7+dG3XQbs)y@lc-_$%;Q7M|p z0d1Cr4i}J+tLAIcox6Cv8e9ha)fj8Z=G%A!g~#H=XjuEVO9FJ$=~x%eB0q+D3JDgD zE26Bb!@RoCH?I*<8%8u;N9%7Z?0jDSpAMa$tUICa&yx8yZU{%hsK^*}5#lgC2}u;-J)2N-hV>48}bL zmL4HW;p(*BYpd}mpI9MxXo<9vueF`4`N7BUaTEQ5$|N&>chce z0mo0=NTW6Y6fFAHgQ}`mO1qb&Lxk??gs-mL=UtF-Cc8h!&do`2bI z-+j~QT!H>`4BV(iK4?&t)W{|a_R8D&S~WR2ER+OZa6I=-^)clR?(PDe+SgiMY^X=f zfy*0jmy?%W42Y#6vpr516y2AX%sZz$n**m;)@8isr*wFBHtr~@K8E$sx-!7-k8AWN z`z%^T5jG>5PxP*mnXs*a=jR#5s>|`obM4mb&E~q}&_|}%H^c@Hx$e5>`sy-&Ba+|g zZy&V$OSiJ-4Ci=uPQmoN;xUxqs(CC8qeW6HwD>=(R=Ji|0o((iCwZN@zu_Ra3F7j=?qLzfOl*p%rff(Ks-q-f_I} zQ4sXjBRJIri`Aozxix(&l~9Gphyhdo z1Z`IWx01G*sG7kE@*7nfNuTcL;6bD?!)v~8Kw z2QR2VOhjY3d*oPI-)I~vJO4xluB;gNt8IVi*|4CvTo&;)Wy|X z*?;oQ^A@w0d@Avgjz1Nwv8(fyAO6gbV;cP(U~X;>-KrYKkqwtDVgkT=jRic24S~q| z6y@#(pTc8G<*ngGQ$yBTdNa0?)r(Cvq_GXfqQ8{X{cuh+ZzK|Il|(OL>GVkQsD#&z zLY+8Ka^F%FYR9$XH?AICQJd-vHP6<}vi&OPf5ewQsq|S>5>Lg7A=}&KgSomo4JH?r zgLLm#<32w7Z+`2dc8qaO?NxSJb$@lSBww$Wv~+!*YaRD?7wh<(F%xbuD~ZruxH2|H z>?ovU4YYOyBzRCNwWPYWdrt;21zH|4iMwuzWA%h1%VWN*|I+V_nI9#|686A7i2WMU z`tcby_0y#5lr`E?euxUv8mHlA)IhmeCb1D$qW8456d6>8A(-+vp0^z zY;9p%sFhl}{0?t(RI>KJ0HHo^J%6?hw#Roi4Mp9c!l*j`bTXnqgb2fsbB@IIdD z#&@w?-#hr7k)C)oNo%~)=IB0p^VhWMh2D<}$Fx7@_D2n2Y0OG2^L!I|Ef@xksWU1h zug|0G4E}5SUHb$#v&$>9bD=5Csr`yCwbSztqU688sek<5&p&{O=vN}+dtrj7yuMdo zD4&w(zb9W2VYsd!8!le;;*mSx*SjaecGFixUQTLB!BY6!&#mO|RlsTx)s)`?{li(?Xr3VEao2@Guu%i*=AP%%S*!zIe< z1*5k(lY9@UTE*hg0<79O;o8+GCTF zRoR9?0%9ltW?+3af+*W>8q}!}&D0oOp*YsZuR{UAoJlaU-{66G-`*d7?~97V z75gse+ykn7n&U2U>$6c`Dg7ZgCeCT_{rmUUi>vVNi0kND!+&(Tv2kFW6PCCjZUp|> zV__B@i#BWIsncF`nm1*u?e?zHR+q}$theD?tygBVkCcG3TJhGoo+{5(=+>6p1gYd^?>IFv&ClH+AAvoepBMn zwl(+g6F;w;=2MqgH56FhyZ*1~`v3p%=7c5)BlIsL8SRr5BM~t4TifMnUr%4?dRz)z zwOgL#W*9tf#*Xu)ACp-Jv=ir6B(+HP=QSaYQ6}Dewau1Inta?CajJ8ZVI1!t6GZ}ta!p9c1L2sn)a5mr3eDKi^ z*A!(WkEOF4+?3o_xol|^w=IcPQwTNgA9>GnMwZXi$v2M%$%EkFWpatEa`_bQwJlK_1T_jcaCntETXjoY zqJqJ67E`e;nwb}eCkxC)VrL8R+P=g3#a%A~mSz2|&dfi=YnqcDVFqV6n!NJl}x&+g&F_icNwnGjFIyexzQx>ud~U+?+dW zLK!lvqHOzAkqo7XU;s}aMji_(lj!8&YEf4mj0n+-BDTg5;SytZFu0s(qCI&WKg^~< zowkCxHM(K!=le~pnYVvczu#J#SAi-BNREA*mTfAE_O8PXzH$3+w>lmkYD_z5bcT#& zBR2pY_Pc0LbbR4TYy1$yCk0~;7Y|svcnjfAe3*pQg)7fMcBz}+ABOb5S5Cd4)R1`i zM&qy8e^|$$@djX36UcGL?JO0~d2A8o_HR#6Z}H)zhgJR|fZk;4(Ts+n@Z+CrZ{R^H#EY3Uk$t)x7-M&Iiw;)zb;eN~A8qvpZpJIIjs59=3 z3E25${QUD=n&y&tf%%7$>Yy@?z&@_P3SbuPWH0F_muKiVr5Mp z-8v9eR1EaNwN(L-Q;2Itq!5T#fC{}&@d03X^oYhd908CgQY zo6%w6&iP-s85eG3^IHBfYXxJAlfI}$^2Y~9PTwxZt_HHP=-9v4S?F?=;YJLK#9kx3#NJ^M%tO zWYRRBuZLlpO{myGrKI`)v2~SEQSEDAN05>Zk&dBDrMtnQySuxjL1O6c76b&OW9V)v z3F+>T?v!}~x&%NvY!de5fU}o6={lu@rR~bVp3AAFPKE8y)@Ju-I;I)z-p`}L= zVV~rB2aCj(HE_pEKbKE3FT+4x%Fixp9i&X6=8E3$IPo>?PPvLRJ1g`9}l^0wn} zPMYibK;7~57pJ4`kt(CQUG5&T`&XuYSNrkJ*@qJO)uNIwor`yvwf3zJ*fVBN1Vafa ziY(JV`)!?a4`@-WdfxYqNZ+53ic2N3XZQ)P&88imC4lrF=`zWr&&=t4qQ~!@P9;wU z*GZ$5YD#{{Y?R#mswJIs^$&yz{k4DL8SaODV`H~@i$_uXVg3K@ zoL@hGaAc$vPJXOwm!&uW&<;QXEdv9-YRbiK!4LeC)&#I2UIDPt^$!(3K4S8BSN$kj zu}c&u2RVk7WX&Pe0nNbj8IV*4dp%RzVtZwdCNk|`7|yjANZMoZ5}xe=q^0+~&eFIE z4krTSx(q$k3R}%nR><`4yM!gfdW(KFw-C6-ftzW6Dcg%|Ko= zq01y@^$rhQGWbldB+RNdSZzr85WfI*2xy*dm|W;Ar&UBUH}ED?Yy2 zd1nl^CXQI9zx)-);i(&;s6|F;DEmEbUKj!sL4pkwyd2A@pQ9nae2xsWbSlC#f!q%- zY8vqZIm;iud#nHhzhUX`3g!2zPrD=dU$08cw-WHD?f1c-U5|&6ZMA6O7||U{ux_cs z#xL=&f??kW+;s~2MYJCa)5xP}W69GS@` znCSAchXdBK2nC{F>TR_3_g~Je)r!we%>?KnvC$>BEvw@kG^9fwBFU`rD~Xx<qRx$dmi7KJbH|(U4SL0Cn2if|up!~8R(ewqC#f&7If*Zl zJ@Er5`5SYjgPu$Hj}>lz^U+7zti}sRzT2bf)RoWnD_BChqVc@Lb@{W)JKa2KbMiBt zY9&EYQ7(&VUbx4tH@q6WA_Fbf4XT!F2cJ7K*DdyWY&m43`8@zvm)4VajHN^>&E8-A zWv$;xPjEWi{-V<1cL>Hdb$hGc9Zu57e7bAj>%QCL8!%VGa5J#-yT0FJ*tIr;243%h z4+#bu^6+oEdX$`>J}2$uMEAALgUyK~O+di*o!=jChd&q`1XGUM3$o)pFwd+U)T4_u`?Xzh~&byKwhP zxV(oqVp}YWsx&{MzLDof{0~b?NXqXq+II$OLqA*4Wxeg89WD#Vy+|O{Z@825v^>iP z$9IrCzg&klU%YFnt6b0)D9gb7IB}KuY_Y<-uKkT-LkX#-e}nw33!Q^zY6Bx&IikOd zp3&boqkoO+MII^RehR*?d{!Z@^hSX>kQNUWXV7ETuCG!7i|#a0WT0xw>P2l+h!(2~ z1eO?1XDsz?IJ}BjIGMiWZtyOQeExfB7PzcXF^8>;-ESu!S{kE)oV2&MJp{Nkiiu3T zRRxur?yNS5bJ>xUXNcx+8u-iuWIs6$rpVpNUM8reyy#&v0@b%VU*36|d{y)Y?Z+Q= z6U{74g1_F;t>BrEV>hPsw3+PaVVN|K8()``SqJ(pCDJlVC$fBZn86aB#tcOU(#0P_ zg{+;t04_uAWt7Wgu`1i1Y*Of=daUYx^ucz|@Gdg&#LSo+;V)N=$eQ z{dCFEaq2Tx`fRITp9|V`CBw^viEqM-Q=_yHwg(*tw#V$Bc_H?^M2^xV(h!Kcji7mV z{s8}@g0VPn+OiQnU*b)jJY-Y5Vxa9XN3C%Et}ViSW3%32tt!RQ_z2eqZ-ux?4*}`8 zb>@LlKq`?R7`X9PJ`selkoMm1k*nl-B;M0a$y}u78$=3_Glk-9(q0GnvZ-4|42fXlS-Y zM~zDt3SQe|Fna5=%NiXta{Ftuf|hZ{Xbtnk<~|L5J6T-#(#M)2;IDklA2e4i_mnqz zLyKI+Qw3#^WL{fex8`zNrDBxT6=PU|9#8(!$xFDl9&ZxgJ?LJI!FnRhjb!v!LcZKi zeRS|96?}Ml#PfNq_a%y3W%~qec2NPlo)^8nAm@Rgo>vDk@mWdi$y%gX6hxPmonABTe&o;{bjT9|l#a^LP z(m(y2P5d!DDip{Pqx*&7zrkWa+h>3T0MURLA-{^ZlXLhDA@M&5&UY9M-vCT>HXXT` zvHwizAI#@J`UtNWV5RM4FL&h~qY=AwuG~WmJi#CaJ2XG&!*&wczKj6E0$pdMy{LqX z7$!y!Ge`wsjr5NNnSQ`=BB4DQrQ1yOF0KPx;zD~kQKBSJhTPN?%W79cgzzo73z&?G zp3RB5=iliT0SHxSkd!R=RHnB+p1ELCLsuiBwrvMkrp2I%V13pWE8;5>(~yGZ_Xys- zmsO`4nwLZ4?h|RWFe;{qb#nt0wSB6ha=qivKekvyZ7LdgM$YRTig7x`1}H6AAZ>Zz zIWMOEg3m86+gsZydt7s54=QS&c*O0CO4UDIj9Swol*!^qZP*wf8N)3bes~kOw0K8d zZT1WmhvD}J*e>_7z+ChEE~cH=NQhjnty1)n9^D7n=RkiOr@{|n(-by}e&Qg8(mK9k z9NF$*<86b9TN}+n73#{jz8LvNjpln3n=@=k>1xs(w@F#b5qn)zBzhck>V{G;JnRYRi(L3a(k{Pp!5)$Le0~SG-w)Esl#PPJmX>IafUUL; zmp9rDdONgQvMo@X)jnspoT4)QS}e9UL2OQ>8YtJF`g)+$z8)2ivilJ4f3FL?#eJJ|}-X&mm?Lmcn+zw}n^%NvcSi^$o? z&K}Zq)FqfE@Rmi>4{%sZYc#vOEIZkMOZ|w^#s95oUlZH|vW@_9FA;TknI(YRjMHww z&Bbe9VX9ST{NIXLR8x9)kH-rF1ib`yvdbO4bDT*xEzZBFk7V?FwH}Gt4yT?U7vG<` z!d+EJ^Z9D7-=yLDI^Q2}_&)VMLG%~$dcNu1fqV{1+N00z^;g#?W~<2dHP3IxPpx^g zo-r(U?2NFyDx(Ps8dCN}cy0E?8z^yo$yatid)MB@TK^c4W4p8u`hSLYuZkVN1@nK= zoX4ce=${1g9=;m;V|KnaQ1dk^ZPEdN;D5u@e-vUs?9ibh#O3(%gU@Szxr!h2@}f7s zd~&Mg|Bxs6GlQ;0W7#P)`Qxa2ifd*=z{1H&CiUP0Cn)0=@&794F=RlyPudA-oe?z> zzS6_qz5-A+_erD=4WSAUxHRzf7b$dqu^E&z?v`N zEiDGz^YmeA(3x=*z$%N#M@nK&8?1T>X)bs%LEq)5v-$C*l*fxCiq#`BVcCixx%I5_}V@t!8`!V72$Ia!2T%KQ?N3I)5sF@q5Iy`h|xHOKmNAX znGP=f<4d(K*n^_+p<CMc@!&>u~d%9aDXwc zrEgp2+l;#Gl)@LJ6$K$dV)Hc`Tm3J5{j`$+M4l>MUj zH9(u~m7qJ(Eq1cj=aO`hzNB8QA!Yb+$j29jj z-|sB3L?)0eG)L1a{%MHl_?ICfQG*BEk(nITz^u&y}Onaj2 zyOS$AdYW|+_YmNczr1en%;i<&__1%)R+M0Bys3Cn;IO_Zc`_&Xgzm66AEL-O{@d<} zbH2DaEMv>f(fWuw8Ev`83uVXAcH2vXPM?Gp&z^hWHi*N&F}+8*{zGii>=WRBNi7s_ zvh!)>X=|vYyv?gTGcD8D&5Xt1IU^oiXn?d3j<_<0CDiaGRWQ!02(&ce3@3#|TKL0Q zF=d!d1WcAeY&_8&Qa~3GPfH6Ht_d}MZsgy~9Hx6PLc+?+%3IAkF)<XvR}6Jgg7f2WVY?3=?lQs3qqTTBqNL`EBS^|M4@8Q?E*(l zLwVD7MD>urTLnH6uafxoRl(l5QYKfQ;lq{&mNevMpQ=v@O8p^_eI3AS!_o^PrN&w5 zy6||C9M}`3vS{8jQ%zA9eFiI7GLh$@FVJhw-H&)Rb^ZEU_ z#Kd(*sY+Rp4LPo<7Y&uLGV*9>CEf={nW)?v#QY|uHxYTZv4I)V%lYG7(3%fFQY!Pr z8dbU$7m316Nz>Q8cWHJTnK1RV5uLI9%L$(+9}(j%vDAp=X^tHMqO2b=KFUOJ*t~M&Q{YEy*AuFqV;iXY@}%4z%}H`=#mVjZF$)rw ziD8o9Be(JEjM9B`kCp3o+sols5@o7phIsya!x80@vb4=v7N1f3jbX{Qs-jhHnTX`U zAi@+y3t0mr7p#z!(e=r*5C^k_&H4NA!EfKUgXUgI)Wu{Wlu=ElEDLFPk>s8uROYH1 z8omKNgw@BPJDb6!Z#|05egC<+T&)6yB%_`_lVcPJ>SO-Io8@!*=CcNuaXjGVJ&xb< zAf^_YJR!1Ro1<&7Hhs^o!}UPHOyXsz-07a6J?GEIH}z7k!iw)cyzBO<@I>-k8@k|Q z`_oVkW1iKT#o?EYi!+wo@!RQS_fJQQSVko^`2c{ra=HDE>-0`#HTfe}1<4~kW8%|A zf$a!eI~2YBp-6UUDF&pOTPmd=zDq15pjl`3G56ph^|b)azfLz1$nkb2dx@09x`VjA#k~z9KE~VD_k0-)EYW}ws$XhG7)P%32P<%JXzUB zAvRRcV*}Oi1QHAq#Hwb&y~sV4k%MARr5y2E(`{5tln!xh)+6SD>XvzgANAfNFcEgq zcfcU=`4<|zH2w2MWZHhm+^MvXL}U=WyuE&`Dzc-@K%HMAnpk=^uZ<=#qA*9q)sJVd z1V#hi09kw*K7M<4I3^R|xvu!{7yAUgLHHD*!{~vK*ux)M8oZg{{+9w62{EbC?(8B~ zO?4Zz9MFUHO!4y%NU)l1FG$t{pYyx|MdU=4k5D(9X2Kr*XBB~bg4-V84KyNGH&LG^ znOxKyf^S{sLt!00bntg~cfnOeN=3vcuGHIl0=Ou#ENyME8CMwDJ%^5D5)bvM< z3-LOeNTZ*92M54W4U!d%JGKwmoXjGVhE(K0qLb#|Jw*Hz7F`kX^DJP9@eaaI>R+H? zwioUvVq!)oY6KQ|keDEJ1RuHBVPA*N4j$GQ;4?g;p#Yk22ijhB_c0O5F(%6XI#ni2 zlZ!!}17edRvH?fPFpLc1>)QuRL?Xqnza|ds5 zl763CI2JcG{f-EGEiVwl;xqFURAR2LqwdR!=}iN4S!K%c2dBN?94_{_Df>yZ1fsi- z0vy&s)6>(yz+bU3cl^lI^64r+XX8f#ac$O_DK%kVq=Vp6?7JiBP;Aj52K=RPu>T2I&uGfzTWyTi3{=if*iM2mc_qO^iTDXPfj&k z1eE+|5rB{h%<)C3fcdg;JC6JP-**Mzk8qv*QLj&=4SqiZCVT1(NJ~=3%#EL@Woy&o4U^5k z9JF^F?UDo2A-UayTkzw<@k*RL0%K@YdganxOSHlqEA^envXPe2U1l4@;n4(ckM1N# zm5G2iq0IR3m3_{mLHt1-mI;uXqCb_|lB?KKMox$fO%BDNc5zgQ9d@HjP)vZ6H|?2S zsJ92K{>a~pcnHjW6rvy|?~lgemIYbIKVyhPEC*N4=LTktrHj#<+bVR?hQ%iSN+-*= zP8?73+86L`V|<<*o$x9nG^v#d(~gdqqtTA;C%cku!btkcI@>LK-ln>^k##H)9wfXJ z@3}|`ay#uiUfvL=Mz~##%2Htn7q%^B&jsngT@ExbB$w4xYynM87Ror#5CEwR_{e@R zWz2#EWAnv|jx#1s{BgZ>nS}=a!eu=z;^qg6c39IiO`x!b(~KosV1wEqxP*@RuVjUM z4aZP2nDZpG@2^-bxWThp=K)o5s1VgAqR^CgAW5BQ!T(?p3=FaJMkpwz!IZ?b8)*$s zA^okck=lMzjsm;A%%mE?OE-157T8vkU%S`~5ni|X@bJ0SFNNecBi{DPET-^u7&2|a zKy8ffrTsS|8CdelaBTEX0s@8fnKq^jD-)bsu;i z=Z{NozVJVQtd=*le?ffXV)SllsTWvMGdZb!5G#o9co(p2i}b&=IKLE;ToAZ^D2=5W z3I=zLTSvjoa|o?7+A>8Xm>%!kpEUl(HZ}0YQ0RR^9ek2DMwRHP5K$9+tEOB2KPFzO z9Y<8zQthCvhubP%TIfn}>C>;-%l|S1IVu8VC#_dh6$M4*pO7jVduA9fYgrUsGmu~u zw(`K7&f@Ujb-mIQu>P}qgZmo%B&_ue2}Y9@{?5^vfm`M}W}!6Sarq~gjrEO4Hwo44 zVmtF$8t`hl3gI@vtDpUh;pReCXYtsOV4Va!abg(i7=@w=WaRYF{lF6)EMrk;Xh&#O zkVq$D3Al24-*&N0S^Voy;ZjRdB+Emw$U~pFgMugwYdH0?s9CcGKtN?#W$9#=oRx+Q z1FtH1EV!=D)^XEhevtt)*;wR3OV#~kcgr_z<0B=VN}Z#~_Psc$rSYWTJFcI3eKgOr zH&r0*dK<^~ftq87boMHVjF)i@$eLr_;IG0snP#J|u*9*mp0y@W3-O_6#E?N|lS5?N zfz!ezBS0LIj#t7KPs#f!@zuX~Awr{MDl$}dCMM4Ow^*;33T{zhI=EkHkU>|_H61yl zY)B8pSQ`iKkn7w-hA|T7HL*6`us=y)#nO9;qD{ylXs+wMmgorRe0 zX<{@zajNqy;Dmv>%kd#}*d9C*++@2sBsA3wwRx}hoQVgqm!Ks#C@qa!Wze)C3x!)u zV|1Q zZ7GCas2ybE6G0=9LtP?qJy6vbD>jn7aZB##=QW7wqPKf5q&A-ORo<{s6F{`Kw04Pg zzW6Tl*|ERl5Inx!cbSxakTCLSlWQXit4ciK`N?N?r^>YamSRV1_j@!VY|f(^Jcm%8 z)xD-3vvzXkNaQ4Mq&56?v9trVo+g*WmnRU z0cMlv)4uS%EX~tgX;d6DawTJUpM%r28|e?VA&@ zHisGia|AX3HOB+xw%JL`)%+U~QX-!%+}!OoeIi;lSu?MBxK}Tr)v}{8m{X1oLRd?b z?=Jc5p9pID^oAS>mJ{WwA;R$4f1JdI0a`PUkyuyABe6_LUZ%l_Z^=H5M=<2t2&!wd$r4eMvw{wU&4S>HT3O)Fkx(F7@J?fA;H#eK+2aN0B_IkT)d zr7)h_^W+P|W`R7g;#=uIax~ODX>T|RXg*ckF^w~;2AWu(AM)>Uif?zMi1 z)upK_fRwz1 z2|D+lX-V}^4dwN7?D)?c`pY%?CgB^hC5b~kZR_VX^t9d~!OC2RKEQN^Ih2onAuL*A zm73y4YDgEAM~mlLV=CR~0t_;Ptx7lz6OXI^eEL?ZC-|= z)XpVHJqRPm4xcW$4jVb~R9GG8dKBa3BWSvD?zXM6*XuB<#k zo5Dbg<2@_azM4TQP4R~28moxk-Dn)V5uEF<5j)n-FYNl3n}c_z5N^G5qjiUJxx3)Q zG^y-WDeq{k*$>sMeT(>$3`E#6KD2bLfWZN-s$kMCi0p`Lk_j#siNRIz)s6wY0F;ak zdQf|YqT#@7psFvdZ7&-u8?R+<&ttxz|1mW(-H2Dnrxby?@IqVh&5p_(=`IM`jW zBn(II%-AJ^Gr%)=Z}s_uSQ&ukIf&+u7WIdUdHwnO;QT=fJweasDd_wW`x8$u%RNzd zUbAl#Kq{m-{cc~gOL5js4=L~k7hJxXO^Pwz{^fx)_;K5%N9W_k8@xuZYg$JR!DspL zc~>1sV`&x}na1j;XQHEPQ5&Nl;}7u6?k3rzj&F+JLv7a5IY^z)2A&)+hbGRo3zzis z7CmsksrewGmp-uG|E&5$zj1BX9M$;!DI|Z~O(a9*^w1W(ujI*?-+y$;B%Mfw$>G5d z1o7nuYD%T&o6I%A!`=I9d3_peeEO^R1jJ2+T`N%f``Xiy+-3h(PuKrXMX4(F>H<{xIii-e$LR@86Kcy_zOT=^T7jHpv>(X=*Xq5L&a zEP_L1BP#N;=vyocVY2rkRAI$!JDo6au15Ax zkWNMDhQvUU9Wm_+g)m2OGkzyvWn6m36bMwIvMdY>`HPBrnOJy6$~spqOf_{i#fthd zyEt%x6O?jT*(g&{Q(GoOOke48mXWcq63c## zY1w)1twNtrs4_^KB<-;D6Ow*=TU~=9sVakI&$z%X%+a{=YGHc#$)cjxo*1>R)`$4e z2T-~XBvP01b2-NIF?`q5F=qdhvw77=#4 z|8|3O#HI1)Wy@U4t1P$XQO@5f17>}ko~DCXrlY#P1jmgxhD6P$WG%%AoENKHBmH1g zEV=z&f^uS?5_v9{6EqUd$y8ggIn&Z4*9G+Z1-os$X~gAP7>od(_6M2ka!CIZs{;dR zPtV1R6Xc{#f_^2F2`~FAZ-vw)i&E!Ez*IZa{m(Ho#k?(;ko9#XpYMw@Birg?gtMDd z@u--V+>;Xqf`kf-n|gMi9R%N3g1u`u$%{A#c6UwB3Mm2QuASv^%~GYH_zp2Nd|8kmLUB#MZ2aa1sdf>eG8RJ7ypI>2k zR3P9#4vdzax-)!E|7=kG5C2&C{QiMv6V*!HPZCdX?3jdU!h|fqTglq@0zkM7>M<)9 zHM#Q79m4z8Zj>tnp~xwbsRR+o^TL?5!69$M4K-!CTtlG^k~@|XxZ~)fYC-I*-{FDwAUFOOeHitj%;BUOjlc=mVTd_lv0!`y~8ja7O8z zSmm&Yu~+V@-}_lv1%OzOzI0(}+3CWc7*3TqWGW*k*LB_+S3m2$FT!2f6>muW8GjHN zW7k#vf_S>0HplTT#5J)$t@hRq3AV%y;Z60fc}6!uNYlUl)w}vPbN;K0NsX=Ua6V-* zO>&PV>M~xu=jm3s^cW856QP87d&309N2sMlKEx%x($_Mv#G5=)CMz-@h`HNeL>N*k z3U~xb*Ex>XCtV|I<{tdql02E6GIuzO>U;NloIC-{%g>Lxavj2v5LQs}<^HAKrxTP0 z?(=j=OYN9Q{@1kvpN1t+3+`%vJjVbGy{#w&h;wj%mg7#4dxMFyBk;1q8!uWKa>P$A z$kI*C!u2o!(}pAt_bjV6hW7sAS>}7>Yr8rHoafQo+HiFc%76S+jY8L%rWU?BIVZ?> zW2?cqVQv3Sp~ri@nYDfzS2AkQbh((dckarYK{XWrOnMh4kt#c3B8p=1!C+3VM|1h# z=fpqI@5~pu_~v|LZH#@k1Rd1Gt@o)M=;;3C>+u&Z+mS_c0=iDj8P89{^ryT48#Mb_lp3J#V@Nqd5Rr$axLd)&m)C0bR`eJ8*LW?w2R2 ze@&Txp3=&8M1XYJzI~n*ZB_vQ`rie1si2I1X4UvFiFG)kcNX!XeRFtKw;`(W4x>!i z^0}#O4tA1){VXC#%1lUP=a(|r1k~Kg;Os22eGwj9jd%bHg2xud`vjyEV2N+&fNTQwK&2ogm?p@^=~1?~>-oDzZGoLuGf!L6)1%YG86Yds zQ3nSZUS$whMpixw=LN!VOSrj0I21HSNkUEBX|Lur@6ph zPE$@W)z3g9eMh;58pF;ia74j$(zHl806SUY-O zzE)sbnmsw}*AdMynM-*68{4!MOh!QAj-$50dXgFQ^}QR3o}-<#y?qk|rk4KRnt-rj z1?^TSAh_IEm}OPlye*RDK1{zaiPg6y|2&EwoP@&3oYC!HN?8|=4w~Ix@Yda^(gyci z@!e1b4U`O6dF}F(cA5Kl9rqV(jlg@apZ&hRbGB)IN&`#hGJcv;7Otc7pOpe@-Ss13 zS<&fo+}!GznZ(sdc>Z5U(n&hTotda ziw}z0M&EzAU-$<=Ro7ak`i`A!oWRkItg%kp&Oi_ahHyT= zrpWpqrh`E{U{dbdKKzTH2pv$`VlZ6ys45U34C z%9zb>iCEQBVt2W~-2o6X{OjZ-sU(75aL7|y7I1TB)j?$aJsO@iqI6i7PS67brvpDy z?A~`!vbPXe+M=-%N^NjBP_IyWK}3C!?TB&qL*%>*a!4%ur>};ykfu^+a#MIi^ncirT0 zhVygF_kCT(?cW==;!NgssU=Vp*~rJ@0u;;Da+8nd&+CFt#@Oa#GDWyJ=VmylK1!{L zrn6}vIOdJnxs4UpS2m3cHRB4=N&S``7fiV6EvK8;rA~a7ArGAjm7%c8%RqE_A%$SZ z7l2e5yb%khF`vRFCt}O;98aPtA8z(iYUG0+WrCOT2)80f`vI#Z2cezo(=Y0NEj%Jl zOp~E4%A zxPJK+2&QM%|4u4+r@5Hk-V8Sl=}^C(D{?1 z;gQnu(WUz1x0Rmbhh5USsfSUX>*b6m+-P;*kMb8TG`yC}Y56lRTF2wz2sMNxLAJae zc{_=;+Vy@0L-rDGu#`o-e{B-{e@hB^_+l1c_(m^1_qxQ%wu}0IXnK_)h#EAQvaKMp z2i-G#-IQ8+(ZF^=3E6UhUjMJ^LZkv}hQt!n=WPSP9A@$(Tt8x&XyAgKlWnq82DWbX zm1Zn|VM%5ma4h~)k18<%Hjl?An>1i2p)Ju1|7SHJ#EM;3Y)Ft7zLPZ2tim+O|0RS- zIG8R*!~FFpJsGe?XnnPU3M}e=H|kScWlx1w>7XinyO@>pqm{uni6UAEUIyGE{ALkh zIhZEc!m+up22dxr@gbE#MwrpY8G(F;ab&!fSSI;32AW{+g7I%#LLbnTnrQKeWaLAM zF-#_K7VYA9UIurSkm>!LAWWtvyNimD*IRJ92sZvkn{+-zPe2j(uY89a<=LaKb@ z=cBMMHs&Jjb)(hJ3AJ$=p5Ty)t+hqSI?holGB7jy-Vgg)=lulu$K@LJm~`v9js2_z z7JJmrM3nt&*Hjr?6{mjs?iVsH{2XaAO!e1jb4e9R@WOQ?~Njs z^{J3H;LI;72K?w*pPRS*tRsabwUYHf$*9U~46uy zd%yOoc~Is)r5A8H#bI1p_SyQR6)+A+0RA;`00|79OZaig%YxN!o8{G?q5n&*`5tt- zi86L}TIHvasUJLbGw}bx(pS{ax1QKkPItZ^wS=}kZ@jAdpK$}T!5n&kQRPw%r-^5R zzI?ZV`Hy-4kXA_k$iB&HoW0~X6n34F$8?MRiw$=c-IaCojL06ZPBjF$nxz5$iIiL} zZlXe2V<-jujAgb;=sU%_wZ?~^CBtf=yhE~+d&Gf?k+jG;8)zzv{?XcF5=WG8s%flZ zJEXL)?QcJ>fT1=9CK>>z4E!!}PZ?TDMddxp31x(ECm)J7g^?}Drn0S<23FEi#bW^< z&QcB#e6>V`BP}_6YnHn`7C7UTNw#3!&JvbnW-Jfx-!@ozAv}#ml9w9jXD(-g^jayA zO#G*}sR)CqqY{WQto*_<+{qCBsGeDPd4vWNxv-JDC+2eqk2m7r<+HTV`lZcf98Vm# zF=Q)^lCt%YOw&mMRXD{L{#Im4E;4>v0l|e4GyeIQILu}5;7|U)oZRTf2_3M-M+m-I&#+mPyB*0v8KmYEt zjyE#8{sTTq`w1OU+ehl#*=Mr)1K$RtYfUX-15oKBbTIr&+fua>_lM5cC%wlH#5&#= zgl<$YGm2AD&aAGlDS`$~o@*Bo4ekd)%~)z5V@`V~a=!JV?VLPHv4+F=er&?2>l%O6{a=^-@l%&+O=d0;I*VnTM03y7EkZ@y% z>JLBX7Qyx<1UORJ=R3Bf4-`0P!TP|BnxL(!4XmPv{{rB)5N_RsOoW{6izlFk&2A?$`xl46`PI> zlM>d#D&Og>B2K_($OPqaCLzLh^QZ=39011xaLw{H2Ts)4Bt6^C`$Ofky}~H?xiyoQ zy{nx{8ID7P_QJr9RgYN6B&-q(+^Ixh1EaF+P9tUvMDXGTf;pa9FSViG4l-cW+dWrA zECipb4$Dz`-Z18NSBHK=GNlP%T`!i4H?WLQ@pILXhnwrAn%q-$&TYap5uNfI2UEo_ zOYK%Na0}PD@t0xiD@XGyvcEaC!!W7#**vD!#xyY;&k2g#*u7&>r*^nGF-#oVic49e z6`syhq7N*PbSP2w zA&6Z*I|0tY-h&tBP9m>&!hg1usAyuS+(Ek()J7gpFV1Egz6MR3NDt@vMdr3}}tnWD*sQ-=AI2a%vXbE#9Sw>YhzknV{bnP!8 z!qQfO9st}2Bl9v~CMBW$_mcrNBkmt+#wq9Jg-*a=%l_7BANYGjM4&JrOM&Z=ji^)z z2qcL$MKqsB1nBWpiFm15H45~!4e$N(zNF@704Pk^Gq>bvfSm|182iXoW@X?safOP& z!W_2=4{Y2V(!k{^5GT!|8a^KyMMfx*bDPDHKvt57sil(wr%9+JMG5d2fQGq_3R=qM zRBGB-nHQ4F@{Zr|&A?1D!E`D_+e znQN|8L zj|tJnV$xr+B+mz(rWIWKh``CE{*ULI6OHFvA%`pBWEoKm8KgV_LKaQ?Y)}N_WoQ?o zV)htfu?CWTYT(@0WshGP>t=`Vr$1+eqE}>VHVpt1#=iXoirE23snKEM{pW^fyiNv1 zn?AUMSGq`FG|%=L_vJVEUkgTJqnIn$sjUXveR-CV-|w0~%ckn81F6$(k4g$scQD@@ z(zx$$@7xou_$ol>@Db15R&Q0#ax$XdA@JL>Cu!F0L%Uxei|?zDUd)E_2+ykE^ybK7 z7eW-)nbWJZp@zGT5;rQG7=C|VmD7K~E5X&tY&xG5R-YbN+DUzn5suc;yIc!ny3@H; zp4@I$FG(9h%x6huGiDH^v=<5!K>4?8^RtJ_R?FE!0zeb5B%N%?&1w-0zo>~j zR{56q5MNj=9E}kSC7p97z#7J*>Q@6!PXZYsd}y}>eZP{Yjm>6Ti_ElaEHTEtOhyqR zaD*`60NX-15ve#;iRh0+2z9dhSar&5#sFh=Q*Qy+gsCqQB848rC|nnd4BNoxooskB z3rE8Dr0izTb>KSLmx^ zU)Q0whIR>gxKSaOtb!a*+*Q68lIx7ukweT52b`v|uRJ1b;8HfX#T1grU`oW32<|sK zJ6MGhB$HY1s>F)>DNJg{%Bm+DnnI1Mdy|)yYf+1I$EbepI{#>G#D=pFcVTlt$YNYC zyhc=crBl)xUHs_<*Q8K$12B(wKo=vPC{nd~1I}mKQRG`L75Q%Ol(}HeHor>rsQb+j zhR^*?<_zho1ET2e9Q?9_A(~B{xHu3u@G|3K^KTLH5?%p%Y`rt+= zt7FKxjxkRiOT8sQ-X}TY^N`-ySOHQ$&h`n8l$>DSUw}~LQSLY8z0oR&ZzuT=I^AUj zKOIh_+TTCACp9Kx8be}H5#Z(+HK#*sK-nh$+1(yc0Sq~PQC?rGQs#)072)Zd7hK<= zeg7kR9~s8GTs(EdPz zA)FSkz5B;xV&DrTfw=mP?DM}#Qir4e7)HkHrIquxw)yGDXZSfU*sBIbU>EG_=LaCg z31K?L`<12mN<6VJ(Atk&Q#eg{CdMCfjkLIIc^21jn!*&hfKBA<*XoMaH8X(OlXKAr zdL7>i4&N{Gma*IKZb@&wRTATkScN$T0aTgy`*jWDY#r+8$F&Bk4{pfGhi;U#*otyp z@vig_p0qeRGV&i1y`O7;ulz-0ZER~2b1AmyQk8Mb;Z{YKLF@2h10Tn!x@z+p9oqq6 z2-QQ*vRevbA#TK;R)RbpZTM538=)SxAx%ufdOWXf+~^l|mzE_(X=NN@#duA6UK>x1 z#rRGl{(id3tn*a9>2GQ3 z*L6nIjb~hMEC7~mjG~C~b;<54wljv9tyu1ht=hFAtO7@nF#ek7xyxkcLgn@g=kP!A zkk2WKe;|up{kOy#udeUBDPONLa{<@Qv`#^{-EJdT^CRCU0V@k(YoyD3PK@cSkYD%D z125@SJl+i2Q#$!2BTVucYz1~4euGOU#VJgtQ^ae~#346@%!~#QKMLc*G<@91mql0(2UMBZoJRzdNe(HIJL356_S26kpf!tY%ls>~QrNG$$j6DO}^m;PT$^0+$p#x*= zDg;yB+t7vpc4ZkFE9hrzL!P&@aPh1dmqf9>)Aj4&_#nUG-Im~7ah ztlVtU3By?CZop?v#-BVQI`@paDmi)!+aBS|&fq0d+wC24Kh3JyAsT~V>gPYu#RduY z#DAYbfXPPt2XU2_we`iu#h}pE2m1aj1zH)KEAwMshw)|$DEwTrU!N-Q;v2rf<@w?; zQ}y4mVl*_9sBl!AZ|4oBf_wm-$De#KAa|T zeGahg4J!%TOtIBnfn`{v9}L8s0!68hx@Ziz_hu!_<*Sj)c$V&XIJ7!(3UlyEQuN0Q z0kmrCaZ|t}p?H?|&X3ag!+Ap6q5YgjWTEv)wJ^?1Ii5*~x5gP7GK|eU%)vbWeesJj z+S&=JY3Nv`$t%M+A_78gEh(x0qwB51qUyWvVP+V*K^kOeP(q}81_4PClo*hb0YO?) z5Ewd?5D}!L5v7OjRECm{p+o7APT@V?Pu$P_UfIN)(b)@QB1{`?-$ z;FS$05>`Y)nSVkM(d2KSCYzb=KpTd#!}N`XBuJ1u!I`}XkkAEg5CtA9JNI+<%4p|n z<6#XNBJjE+CItx*cG7~aV8m<3y=;d6N;eZHrW{~;i>`#;acx%y@)v02s!8#YVWGNF@=O(rSm%N=v z!W}~c_mQf0wfW4qOlt}-dn(=$@RYk;egsk zlEuAnti7j)IFUE0>~c<}(eH}3@qB^a#cicZ{w2HqzQ|YIGXTqcz}r~G z6H;(m-1S@8UCvv+-d=fkE%e^|@L1>1%ty24Gg+fgz{B%zowtx;{BvoI4O0S2?g1heJuGHAbbl0*x28W^u(eRJWlq;7&_c;2~p_e%sj$ zsv5|YI4hsMfyhbo9O=mB17t)u@{XeAM3sSk#x9Kr&NiFXYzg%Q8UqfDMgz`(+Z|o> z8|bDqv4o$)EQ1NpuAa_)ZUfI$`PQH!J(>5irfP5{dytaU=ff0kym#Ij{9gpsOgc`~ zt8Xb8b8|Lo6yj)d>7o)&ZwV@@2Z&$rwS6$4?5;E$cB;>hKb#cncZU)sa!o*+t&kHA zqM&43<{|xcE_E>~n|HCAT9xqgSmYQXFa%{2B)&~z>2aemMRl=S^~@3PlLmDeYF{}6 zI-PvObWyZ{$Hy=nR+t`v0OC)v4YMVK5_h$$jx9^X<87I#b;;D?EnuFDIiOn0!_bJW z@lHKAK6&mNQC%<7WAj}wLt-bTsvoMd60L;sjg{o+!W^ zPiPNfC8~5pbt0yW>3Dl@c6zi~{k0!z3lDr4zIjNnwd{ljK-1R3P$M((A3pBCyg~-m z;LZuV(DnDzoNS8TVg*pa*S+b5l>Y{q)@GhE8o=bnH?qW6DNg&V*~aakk6nVcn$4Ev zr2gB>|1*Cr_$S?aomtE9XVMA$=U1)YDP5v?AAa~1{qpJBx}Be(Qe&&b!VXey#SU4jU$8-JC|9iN|_ z={T)g;QpIP>govx=9b3AV>|Sw54`#bkQ)d2o&*U*--{1P&Bu^y$Iq(8^}n)sZhNQh z$m!$iKyrExJvMb=UPI4eUO7)^-|zbrqnx?1SPWi!YmfonTcBX_!zgR8qsMU#Pd4sN*3Fp+Y=F=)zBssYlEtXh3iP zj9XXvkoBvMr~y&L^AYk9LQ?T9(BI1QKk_~@$JvxV=0_u7PBoz)VJUBbwHzh_bRx2% zz(B)+}`nNds|uk5K((uS~^{t zi9srR0gTNPuNCgg=E`{P?wbuS$ivN~gF1RC7RtPcMb9aF`qAnMvl|k8-NV9tGG8LA zys6-;h{+@Kz@io$1VNF7eQ}s5?4SsCPyq8IE};FM!=n(bvApc; z@iF>uL71UUbIjMzw{7)PY-yjLaO;j6py+v9p5*qEgIbFFIURq}xwxw@pQbW>YRSLj zC(qCD0H>HnJ!p$w@#!M=KWj&1u{-I4;@>`u#O>%`>)5y z1X5w za`9tulSm@fq!u75O|VGLt0gv4MMcvVxA8nRyam1A1#BEn*w{)ARGJ#q%7Mp1M zR-M{`WAfNJRsPekDclooxztZNN1T}#QY~mpR0$lb-$^QMF7U9q&fU`dcr`Tc4+{-- zOUHCe#fR1*HchujBK@=6XM40m588fr9HbuPp$R9S+;GsCEz|LO7MVSpVk#=xvT&|4 zo;wko?Vuz^@_>~^e^<^<$uUte{k0NzcZyy%Nhn8te*Qxt!-ssQE6s5k6CQ7#60!P} zg;LB5!qh@zN|GT6Yslu&NobQ0W`$90yX`fwnwEXNgNRyW{0T0udi9}Pj95^NQUhZa zf>(K(e%Va1C&i+jBIbOt@spWx$=*i!H)=~idt0t5jhyJJv2+2_GPSh z&a2=;v>?LFk3 z_X%t-KCGg#itas0r#18#kAuJ#yQ`vqCGGva%eCSRCN*0XF?o!mWVGuY)}Ha?_`@`-#y!7j+b9z``GDuLZaA=7|Ku@ z_5?+R47eVlPWp~G-Cr-Y?DyRr$C=O3%c#BdPmrbG(cPTcsy~5%Bk(eZk92m!{#`)5 z9QzO0pce8d+l}E#)^a9A^1=h1e+Xj!EpeI5fK*!$7zB`$@yct^RIwDX0mr0>58 z+?EblmK|fm@!U+czj=VogtyFQ>A9JAKS|N&UsJTE6)$9g6RUkoElYyNNwi$TuMhbo z-r2CK)tcQ^h47%NUNMOzHtK)n&lYTd1e$C*I}a#;c1k)=&o{yU3WhhstAX0$_~2nsz0w{5laQ_2Ngx(cEVY2Ii=nh z_z0aAU6PIT*qqL<+n77byw7=UGMoSsrjx@0>EzeHw5e=__r7Zu;ER zz+>jth&$qtvLZ%feb{v+W8OX1<9FoTES}!^1eF!b@`RygiUP2x7fL0R2`QT&DlL1n zl_$B%-*M^7s6KJ0gp#u=?{S6b2QI(2m{w6MglOir+XKok6IgLzftje=iq?ZxAv$(> z=IjL}dRALWO-P>jpk|1^s*N^M)y<5ReLNXDt%isF^45~zvd?2AfhaCVc^D{G6ILdM z_yqX0ns2t58w_^xn7%H4NzxnpFun*yJr#k7`~Y+r4*QfC!fdOV3MMv83V4D9ev(Q8ZG_eF#~+uQ zsgdsqc)xtu(@foY8(Ef4kL;H>c+0}f`Q}CtEN3KU@Hu3~nDe`TcbMU0p8C6QWDCT< z)Hb;@Z`%;+BxMnUm_#K91?H4Ag`ky8Y0!qY`kBJrdw^WPZ6f2F@7$#X3qp=a7Ofrc zz%I~gAaCiHBVq&ISo&d7d-sH8<7;V0*Fk~6Y-`^pQ=SSLFL;J$LC}73J37+tM&_Mh z%o$YXilQyqo9R)-$S;!6A9Ha%ru<4h0+Bo8to3(8EM5DaD6@PJ#H6092a;*nKzXd1Ne0)l8DzENT)W#1uf z>i>A*AmgoSLX*Bf)4)gn<7UA&EHG;8=zQIM;pwm78VgGlXh8-A0G_F+EWsN35BR(Ag<^>cTw}ex=ZB9T1fQ@`B~}U+?`Rcbv5U(;>AN^<=vMhzY-tflolv2}~lm zXi{XmpDw#xN_VE?!K&(m93mJ)>O&s zo8>Lc7iFVu%?K@PfuQ8mR|!w~sKejheAFGwH3?lKLPrggjr=g6y=|n|?m^;0^5|Do zxP`1jCLdNJpY9Q0;=^OA_6gGEq5BIcEMBmO*~bpgRZH}X`LpuwIVQTlk*ao@)`HDO za$%bx2&NNQyF-u^R#o1Hb-vv-{%KxXh?P!Tk%~D zoIE4~nD_*KpzEFE_z*g)6~S8nqTsg3!`k9IZtynq$COb;JpXH&LBN+xl!lOb5&wdj zQAAEDXRZ^l%mA!_mP()sE-MP`21WFg1o7tgOHbjhJ}&IYL)G*EoL_3XHIgKLN-Gvh z4qjZG)X07x%^we_0qq*m<6G8%0J^qhTE1H~s3?SBfWMUkZXiaP<93aQCFPvm2qSK` z+jo*_FPW5&yPQfdb`KEprcZof8P3g#nTip6+EQ0F9Dx0;Zx;d&F%X4OejQA-9=D*p zUzQ8|ywG-p7jmy}%C^R&Kyt&#w2IoLlKViTJSg^*kEqg?@tOz}LVU!JqqhYDE@k zY&$Rqa1WRP@UU2k`gZx6DUX@C#lP#{3TWL^w|P+Mi*GZ`Ykv2LcH z!q0w@^THa2JCAYV73l@|Sye&k61F`Z(g?sPHWLo6@(Xax7A>b`f&Q-WV zqrVHtJrft0a1*9v1l~$)c9cCf5gmV}v~6+i)?GR3Un9qh*%|mckn@j)Eo*>frGRh* zz`wvfdkbozfAKK)z{ya1--?GoTM0Of^~0!;`iz!au(zjt+^_Cu=@Bj%ITqBu=c+O$ z2S)L@FyqWzcZfd#D=m>Z5|te4uCO?9IQnzv+od*+?T~G{ z>>vtL0i^^D%93{x!!r1fA(bYrQ%uUmH&C6~2o|LS*a`+yPS=Gz;^ezEY}H>Ms}${1 z9GRCVYb(YSp+BSjaHm&gJE|aAO~$304F^8%Aq@^-&3ak6%TO5?ra*qCe7Q$Lxye#vsjhR&2_w0aT&di= zKdh#!aG>gce}hZ?D%o`@{wdjq6QUn99RnX704DV}wkn_q1xk@we^lMg_Hy76~!SK5iHCj&}V zR(i8rfQRy-QINyjJCUVb1xjSUl)D4cXgWEtlGsLwk8#{%)fZg!o~u)jqm+^h(y)F~ zolH*^5*JOk^pm#IX$CfFcTYcRkjC2LIrWs=yT=m+co2^@16&{$+E!cC;J*9D9K|q2 zX7PTiHAGeHr_vc>iLE$iFd}y|-lgKJ_^ng-M{o%{i#zHP_MW05B_^MW6_i1_))#RUi4QS{g5oMwKTF`IL3sTPmQqfZ*xx1t zd}4BV9v4_vy(T2qAB|}WJMMI}jWVFiF=PWQM6dfb61g_@cN;HiJ^j^;^_%H^Xwh8|=7$G}i-j#A46R7m`Gh0V)p3K{@X`H_%g1()p zP(OP&_NYFv8Hrd_BojGWF1yVZZkYCfdgZ${`TcX2vF4I}FL4oNpzVfWtBeF4 zFc;xvS#>r3e{B;acn#<<0y1ZJ*?b2LE|M(7ulN6d96lky;iqz=S0MVFi7TC>ui`h$ zIw!JziUx}Fw%J5h&Q{;&ZrqqVt8g1(xCoih1r})mqY@X+#Rn1pK(z#bJb}_UL7HE^ ztv__5KU*=4bkSZ$&Zc*`8$Fj>=O5(!@6-_gN0{qQPMIG-dcfAS;sn`8M+iL_;aeas zOnnIz^7R9n>an00{^)yfLgr`#ROnazQD)ZV)z4DOED}_y5X6+Eah!N}`8PJPC2 z_aRE!K@KdOQPi%Q9*@NM;RYSl;F#t1qualF6QCwq!|H(PN+k(NqC0e(+Tj+!=LL4h zhwVCDH#a_r%R5N+FQpHN$Hf&@;B(pOJh+sO_ykJ+D0yN_ZK3W^^@LODnR>apx?{Yh zqc6T5UEjw))2E&JK>}l&8ILrMqqAfMBYbH0(x=yEYGcYq;7^iKDQO`eK8766D!b$z z0`m&f+6Ai2*|e?XcG1d&){vi7mPt%7U3Q_mhfX}06(c8}_LwDwCGh1n)|VdIU2@R8 z8}Pkuz`xIp;Puz1k@R>d9A!N){2>Q_cW!n9t$L)U`j(WiO3c%STeOCV2WfiLUGFg(R}RIh%j&&@AeE|4Vf2^q?Pr@=w=@P;x78X-w4ca&H}S7x0=W({ zC^3n6^%PRU4pR`~fX)g76ASt{ZiX2!dXxD(w9r0y3(_uIeLbjJ3L36&A&;BI(;T<~ zHDMKAW1uudZSC(5zeN?@QOJ#1j3iXpCK!fFlE(l(?cuHc z&}gbF--OQ|DSJmiWjyO+aIp2ma-qPVb?oZL#r6tmNFL| zn^L6i%2sUkOjFVM^xCHC-LqM0)j@tvB7)Fn44YP(aUV#OQ% zuaoww2Ci@$PqGv%3v-yc3Lv&*q~p{JwxSNCRt6StWGP7A!U%gflJhP^lj`;&S_>69 z_NLxZI|~vy7+(IOXM2fT|D=a3Y-#XcmzUM=~gRL+e!4! zEef_5EqTv0lb7YF|8a{zEVTv9vpTKz21=FLsA<4r{b}T}A3pp7X>Ri!C7@#hTrKsP=ro#w zUE##;6d5NtE(pE-n2?hR)0d5hbYlhG1^Nkfy6tqw9CNE&J}Q`*Tef{th6a8P?1b8Ba^555+@P2??M~m{$u(;ll7r)VKDg zUmZL{b+lYY*zu5%1ch9-doS7L2JVSc8#yIKbS!5m9-BGYtHQEz{U~Y~P9PvOGD3fj z<5d7Q*|I5YmJ8B2>^n|szg=*OSQcbAO)4`5?hyof=8lapT`zn!bDg+oniY=D{L29OQCqK2@Iq}6UGM|T)P7`1g z)0E#$9NmkScgYsll$NnfCGX?A1xKh9V^sq1!~^sD#jYF4bXAE)n#HT%TI zLizyZ!0D9PH27_Qe;)v(GS0kMmNJC<6^Yj>PkCGs9e*FA1jgXLN<`Fo&OA}`gNo7i zauuFT5>PRBC7*7=4OKfz&COm0vhtw8gT-*j_Rn!T*)@tXEEe{Wj!>BQIeb=rdb0ci@R#2o^aiMo`S2LT)yn>&m@2)3r~?vv#w@ zEj9O{EtNYJe|7M7zWt)G6#7WsHknmstqf=CGbq`>Zjbs|V$*IDiT8$w@xUin=j-sH z?`)ou3m+QRtkd(sdIR?epN%%@Yp#Lg}*n)syB(h?wSUb&R8M3nkDf-$3 zw%XQLIi$7NN>n^%gREU}&la2E7{e&@2I96pe-v|fl`+j#7~lxMzWrlCc;M0dO&4$) z4sR>b-!HAEDKN%s@r1pBetDm_*W`~+?ymr=z5fS@4%{xhIM}Ikjgp(^y!+=T=c|6- z5E7V=#p>U37XJs*0N!Yc?m&HSNsM%_AuGs=Oa;o_hcaKbwLXI#BOMra@PIc?tA{k6 zQZJ3|hO-reeQ?3act}mLxc7ocYnqpg_b`N(H`os~A=xApxN2{uVRYc%TwUj?Y`@_v zFonAqI)05Hq{j-XFjr86?ULksnldu&$<_Y{WuLQ!rvT3^!OBkV);74CqIX>;kL z`^vsE+;&ujP-`&4KjWQV5eNNB6Ym^Wf)?qO%+)d`wyq2#oi4C>mH3nBJ{G7+lUWMO z6xZNSocgVfLrHdt5+w?8>Z+i-PePtoXM)k=1}q{T>PeKz`1@dP#vp6*Sxn%a(EUe* z2o?-W!vjN8nOpNdrH#QThe6yFLo%ibvGz^r#t?xtg{bPzxP?jaz&WP4x4*m{&KVOz zo(FxjLqRZREuI}`27m;?N(_QyxOfvL$rtaHu zon`7qfTzG{d<}29xahAOO6CYy;?@EpduW$paNP<13?`5mmkMV7s(;A5nXm}v{?uTdNoEv7W2jyL2w!+!@14VSc5Br$h*^N%62(nw z?*O|KuCpr5mO$qIf&Qt*x?aC|S;dH-KMLId?_gfuz$v~|9UOEOqS_*7s~c-HL-SyP zi>qwc7yE(HbB4|&V6~7POB_?Rx^Rv(Yk9`PaJw=jGnhQR?4|U3q7MrLup0lDJI#gP zz3#0|{1ZO^4tonbS}@^eNY2e<-(TqK45j=QDKEbg%-=wK#v3S$k6~&BqkneeBa5Z0 zi_Q^8N#_o1%L`6NzNY@ugpJ%c=IGiLst3N`SbY08fd9aGhWiijk{s4dM6~dc&MHwe z_87{EEK=)z$eS#<)L>xSE)Df(1 z{Ins}1SX-~tt>S|fEjN!5pVK{(4&LFM`7x{?f1r_5OPFs{qIcf_$rFmik zs}^vx=PRCP1EI}G*T+yrog3LO&RkDh(ymX|1xb((KY^VBe)GYPX&GH6f7BB}$0cM9 z=D{sj*;OsW*^N9wYiWMfDnErzH;}2sN~h!0_Wfl`IHC@YmsK|1AoOJzp1B==cNt0%rNMU+Jg9_ z0%&;Ll~bvSB2x$-mrm`n*3@qm4f=W%_T|KxsqJH)MC-V)K||Vf zY8QO5hg0^rIlWiEqhY~eJC*jKUfUyfIyyR+fipMTYL?S&o0ThT>bSg{w(oLUDeKnn zS+&%?n4)@0{bN>~YS(mk^n4^np7y$>Wv=#_m)EPD<;6~y&54uN?!0nIX6Wr2*^*&4 zF0fk2_?N;^_){N@N|av0F+Of{6cvWBoWA`8C$C_RQhi7jd-*8N&hoBY@F(-L8$zaj47zh+pK!fyF-}XLTq<u5a1d@Ns z;sMka0s5u$SB<0gB#XvptIsuZuL&Mse_91J0)Ho^|HbNqR>-x4`zG6WHl;f9(gQ9F zo90JLmzzr|e+N&Or!)n^uIM-iGE@w+Sr=@`)nzm&du+b){;xI2o#*gLT+}e4XBVW~ z1=XLPuh+5K-US&^Y+j#A@xo?(E=e&TC)ayem;VtzYy1DeI2BhxvtJbIn^?^g8ww=N z3K+;^_aQLazjg@+p^kDO;Rc~)lvD1jMPZu9orIy}q;e#fV|G#ynw(tQE!b&3QxYS> zaQHTl7Frn2cZ8GQcmG@OI?92pX9tWPl>nJR+{nTqNGjAirkp80Pt)oi7@4FP0(EG! zz5DS22&s?r^USuBxR9is3Ca4y*9|3bq{5GvhncLmKag{ozKI)Gg>R$|yDgu9XV$$h zbGQ8qgMS(6=QNQ=FUcT_DSr9Z$gub1A*_K#5*g?4Z>BzPk}WlBOo`s~?;nZ4BtnH` z`Lye0EA5ucamqu4UafH`f9@Vt4J-o}6={`gDb`-z+k;cS1w%+@v0Bi~glenqtUKS5Il#gW96%dPlME)|zhSMTR!> z-fSp4zi+=LHs2+wa4qa|l$9##H`{QGq#;aL=**_78}YJ@}&8nbjh! z_(ALVH?sg^HpvbRT(?Q>_6%kj}oDj+nzx_dB8p?#ZZBDjQtXLdcnd z>80$DQ+8%h^3fI$5Xz<^_FhvmhDik8c@QZp1k;W^R3uy|hA}b)i+A_j(?WOQAiGI5!;F5`WL@Ut znZKVeTh990q+>JQ8m-SK`~58=9c0r0R=n*D(w^>Aptg?~t0yQ1GQl!Bp;5Z9szlRi z=b-0q&ti({?SC`&I&M9)f~>t=h24eLj@)Oda%>?&W&n`> zX@@g9sroDu2RT7TH^)ciG~^9=lT848QOhEMNDpd&bMY%qmR2vTD-U(52^V8FhBa39 z=%siG9WdQZwgHs1eI;_PfGGjau$NbBkD_Pbpj+~HX8*r(!EKK%VV3x18I2PFYh z-p>@5)6(Os)Fn1*DBYEQ%u!CCG{#z1cs&Y!^{YR2S?6+GXAyvC@WGN?%A`E`=%-UE zs7Y|en5o0&MC=G?D(U>Ug8M4o>BO}c=ErT+Ob9tOvK&SSN~Tz2?A$+|v=LIWM|b(t z74~M_&)JJ;T2!?oRNdtmkchK36zLPZaRQaT37aq7p$|;{r$+qvb7CuAO``W>wPVlkpOAc>JB5tZGW@$|T2-sQ^OGm7 z%ipy1t3uRhanW7IIWv(+;6p90 z9grHo*6fYAM`Y~@)n*$eg+2tK5s~T5ssVAF>S1&?V>0&Edg}TU6yiEv(mSOKS2H`x;BpZwqxcyb!AbF2Fc2SvMu())#1((S zOa4JPm-o{fC4iR=b!d4?_;V=p*1e)i8>0d90vs$|!bHewSKM%ob#C#dEMYa+!X7qx z6piNaEyaDJ{W+_bDW({NRdC0Kj*F&PQrxWoLaHM@ByN={7*77^mNGjC4cdPK!%)L> zvl_ully4+Kb2}M44Zcg0p`*M&Qi{^(hT4}M8b`WR%;lGibV~RO+G!v~sCW3LVuirHkF>|nde{%?7B2)( z%?Jg>&aElzk~8lx_H5KHc2mAJ=8~h+SdANe*sPjpv*twpmX|x>Fs>KmIqE^$?m?QG zI;czkO$VgD;#|Xmmwgkj_B%S+XEJ3im_o+c*t#$7eO`UEfYKlulYbLLA&95UYksPD{i(y*(T4Y2+(0L zI^bLQm8L!Z7zSnCJxQ@nmo``+Qah6F91=A$esx2)w*Hgij@!d1%lbg%sRa6xneT}H zVafzM#E(uBs!R`)7?Ik?gVy~ZMVp^1MAiszOKvwcoU$#&3SG`7Psu*W3YWZ=xY=^$ z*7aEs@*?LyT7Y)z0X1-yu0#e7(!Ro>O%*E&2s{~{2?bINllu1E>1Nr)!S2aEev|A_ zcs$cDvPQBmV%YlC*#!LU!hbDPxNo+3enNVc-7{EdR+mwYVRCyJqbE_k;mim?}X-X{@LkP*`GKs9hlr*cbbdy)k~b34*PAH=wVW zPZ==J=h;dnt7GcfssLZx79qtilKm*zSa>1`+u*jkpzHQO9FPk=4?we;)()+*-o-^9 z@N^yhl@3p)qDX~cRT*JyLTyQ@4>e%;g{bH7B!#d##k&|G!BXfUo>nuNrOz)Fu=+zz zMq~vz-Dv{{YiS8rAi->~Yuv?bIP|%%pFbpe+9gvtfs{5wwZ_Ty3XZB|CRK14{4)By zNI+sM?1y1OT4tGo1-<&;DXEcUP_t-4pR=49IcSP00hq-Lj%|2j&if?T7BWTEDM5aF z$KGouj#G|-s)HnH$abFKXU#*Vjn|@W#-c?~&SDC7KQ$&?c}*fq!7A=IB{)W4w?iC6 zJ-I2VLu(#8>}8jN?9F7D>@yQ?Spi1t*@4k-ARD8GtS?krqV*3%F)?_`aT()zO@s*J zOvCKTzJkEV@7pGndaMlj*gBy0UHZ<>vgNk-w76O_eq$e5(DzM~d>jvr0UsPE6kfq= zT(zx!=7IOfaB~vG-G}c!p_=p$!9hSNSmb_IKUlAR%^KM5^5Lm(VX#xFy(2mt7wy6P z-fqk|k(Fy_s$@QcMZIcX|7=ULX{Wz@&e=Y2vpH>({+JQDd9>^3JX)$7?AtqrKRP6J z>w`Bkt@v2dg9SDYd03C9qx>s@fZbUU>U$`cz03$NVnX_e=amgWl1A*^Nx7t|u`yI3 zS6ZkdJgfCd#0|QloU=ziAUT>La9nnTWs?fd&HcM>D@I%xZG2Pe(G3f*`8V6sLc%