From 4ea61aba7be0eaac95cea254839e4560483cad85 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 27 Jun 2024 18:27:54 +0900 Subject: [PATCH 01/13] fix(lane_change): prevent empty path when rerouting (#7717) (#1355) fix(lane_change): prevent empty path when routing Signed-off-by: kosuke55 --- .../src/scene.cpp | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 505bb3ef93340..ffee23dfc25d4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -467,8 +467,16 @@ void NormalLaneChange::insertStopPoint( PathWithLaneId NormalLaneChange::getReferencePath() const { - return utils::getCenterLinePathFromLanelet( - status_.lane_change_path.info.target_lanes.front(), planner_data_); + lanelet::ConstLanelet closest_lanelet; + if (!lanelet::utils::query::getClosestLanelet( + status_.lane_change_path.info.target_lanes, getEgoPose(), &closest_lanelet)) { + return prev_module_output_.reference_path; + } + const auto reference_path = utils::getCenterLinePathFromLanelet(closest_lanelet, planner_data_); + if (reference_path.points.empty()) { + return prev_module_output_.reference_path; + } + return reference_path; } std::optional NormalLaneChange::extendPath() From aef45291fe3b376fc7fac67e3944310c7add1f60 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Thu, 27 Jun 2024 10:15:39 +0900 Subject: [PATCH 02/13] feat(start_planner): yaw threshold for rss check (#7657) * add param to customize yaw th Signed-off-by: Daniel Sanchez * add param to other modules Signed-off-by: Daniel Sanchez * docs Signed-off-by: Daniel Sanchez * update READMEs with params Signed-off-by: Daniel Sanchez * fix LC README Signed-off-by: Daniel Sanchez * use normalized yaw diff Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../README.md | 15 +++++------ .../config/goal_planner.param.yaml | 1 + .../src/goal_planner_module.cpp | 6 +++-- .../src/manager.cpp | 5 ++++ .../README.md | 1 + .../config/lane_change.param.yaml | 1 + .../utils/data_structs.hpp | 1 + .../src/manager.cpp | 2 ++ .../src/scene.cpp | 6 ++++- .../behavior_path_planner_safety_check.md | 4 +-- .../path_safety_checker_parameters.hpp | 5 +++- .../path_safety_checker/safety_check.hpp | 11 +++++--- .../path_safety_checker/safety_check.cpp | 21 ++++++++++++---- .../README.md | 23 +++++++++-------- .../config/start_planner.param.yaml | 2 ++ .../start_planner_module.hpp | 12 ++++----- .../src/manager.cpp | 11 +++++++- .../src/start_planner_module.cpp | 25 +++++++++++-------- .../static_obstacle_avoidance.param.yaml | 1 + .../data_structs.hpp | 2 ++ .../parameter_helper.hpp | 2 ++ .../static_obstacle_avoidance.schema.json | 5 ++++ .../src/scene.cpp | 3 ++- 23 files changed, 114 insertions(+), 51 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md index 1be3e04914cda..3e155aba0af2e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md @@ -382,13 +382,14 @@ In addition, the safety check has a time hysteresis, and if the path is judged " ### Parameters for safety check -| Name | Unit | Type | Description | Default value | -| :----------------------- | :--- | :----- | :------------------------------------------------------------------------------------------------------- | :--------------------------- | -| enable_safety_check | [-] | bool | flag whether to use safety check | true | -| method | [-] | string | method for safety check. `RSS` or `integral_predicted_polygon` | `integral_predicted_polygon` | -| keep_unsafe_time | [s] | double | safety check Hysteresis time. if the path is judged "safe" for the time it is finally treated as "safe". | 3.0 | -| check_all_predicted_path | - | bool | Flag to check all predicted paths | true | -| publish_debug_marker | - | bool | Flag to publish debug markers | false | +| Name | Unit | Type | Description | Default value | +| :----------------------------------- | :---- | :----- | :------------------------------------------------------------------------------------------------------- | :--------------------------- | +| enable_safety_check | [-] | bool | flag whether to use safety check | true | +| method | [-] | string | method for safety check. `RSS` or `integral_predicted_polygon` | `integral_predicted_polygon` | +| keep_unsafe_time | [s] | double | safety check Hysteresis time. if the path is judged "safe" for the time it is finally treated as "safe". | 3.0 | +| check_all_predicted_path | - | bool | Flag to check all predicted paths | true | +| publish_debug_marker | - | bool | Flag to publish debug markers | false | +| `collision_check_yaw_diff_threshold` | [rad] | double | Maximum yaw difference between ego and object when executing rss-based collision checking | 3.1416 | #### Parameters for RSS safety check diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml index 915d256aba1db..53e06631a81d5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml @@ -180,6 +180,7 @@ time_horizon: 10.0 # hysteresis factor to expand/shrink polygon with the value hysteresis_factor_expand_rate: 1.0 + collision_check_yaw_diff_threshold: 3.1416 # temporary backward_path_length: 100.0 forward_path_length: 100.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 2ac0b9493e67a..6caeb411f6680 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -2319,8 +2319,10 @@ std::pair GoalPlannerModule::isSafePath( return autoware::behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS( pull_over_path, ego_predicted_path, filtered_objects, collision_check, planner_data->parameters, safety_check_params->rss_params, - objects_filtering_params->use_all_predicted_path, hysteresis_factor); - } else if (parameters.safety_check_params.method == "integral_predicted_polygon") { + objects_filtering_params->use_all_predicted_path, hysteresis_factor, + safety_check_params->collision_check_yaw_diff_threshold); + } + if (parameters.safety_check_params.method == "integral_predicted_polygon") { return utils::path_safety_checker::checkSafetyWithIntegralPredictedPolygon( ego_predicted_path, vehicle_info_, filtered_objects, objects_filtering_params->check_all_predicted_path, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp index 901fe351fc68b..b079db9babf31 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp @@ -357,6 +357,8 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node) p.safety_check_params.method = node->declare_parameter(safety_check_ns + "method"); p.safety_check_params.hysteresis_factor_expand_rate = node->declare_parameter(safety_check_ns + "hysteresis_factor_expand_rate"); + p.safety_check_params.collision_check_yaw_diff_threshold = + node->declare_parameter(safety_check_ns + "collision_check_yaw_diff_threshold"); p.safety_check_params.backward_path_length = node->declare_parameter(safety_check_ns + "backward_path_length"); p.safety_check_params.forward_path_length = @@ -778,6 +780,9 @@ void GoalPlannerModuleManager::updateModuleParams( updateParam( parameters, safety_check_ns + "hysteresis_factor_expand_rate", p->safety_check_params.hysteresis_factor_expand_rate); + updateParam( + parameters, safety_check_ns + "collision_check_yaw_diff_threshold", + p->safety_check_params.collision_check_yaw_diff_threshold); updateParam( parameters, safety_check_ns + "backward_path_length", p->safety_check_params.backward_path_length); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index a0870fe428c8a..5790be377b7aa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -725,6 +725,7 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | | `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | | `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | +| `safety_check.collision_check_yaw_diff_threshold` | [rad] | double | Maximum yaw difference between ego and object when executing rss-based collision checking | 3.1416 | #### safety constraints during lane change path is computed diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index 1ab33514c5f24..d2f695071649a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -30,6 +30,7 @@ # safety check safety_check: allow_loose_check_for_cancel: true + collision_check_yaw_diff_threshold: 3.1416 execution: expected_front_deceleration: -1.0 expected_rear_deceleration: -1.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp index 0facd8c077505..a65f3baff01d7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp @@ -137,6 +137,7 @@ struct LaneChangeParameters // safety check bool allow_loose_check_for_cancel{true}; + double collision_check_yaw_diff_threshold{3.1416}; utils::path_safety_checker::RSSparams rss_params{}; utils::path_safety_checker::RSSparams rss_params_for_abort{}; utils::path_safety_checker::RSSparams rss_params_for_stuck{}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 61ff54e8f99f3..22c93f7d4bfd5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -102,6 +102,8 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node) // safety check p.allow_loose_check_for_cancel = getOrDeclareParameter(*node, parameter("safety_check.allow_loose_check_for_cancel")); + p.collision_check_yaw_diff_threshold = getOrDeclareParameter( + *node, parameter("safety_check.collision_check_yaw_diff_threshold")); p.rss_params.longitudinal_distance_min_threshold = getOrDeclareParameter( *node, parameter("safety_check.execution.longitudinal_distance_min_threshold")); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index ffee23dfc25d4..ebfa1e7ac260c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -30,6 +30,7 @@ #include #include +#include #include #include #include @@ -2056,6 +2057,8 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( lane_change_parameters_->lane_expansion_left_offset, lane_change_parameters_->lane_expansion_right_offset); + constexpr double collision_check_yaw_diff_threshold{M_PI}; + for (const auto & obj : collision_check_objects) { auto current_debug_data = utils::path_safety_checker::createObjectDebug(obj); const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( @@ -2064,7 +2067,8 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( for (const auto & obj_path : obj_predicted_paths) { const auto collided_polygons = utils::path_safety_checker::getCollidedPolygons( path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0, - get_max_velocity_for_safety_check(), current_debug_data.second); + get_max_velocity_for_safety_check(), collision_check_yaw_diff_threshold, + current_debug_data.second); if (collided_polygons.empty()) { utils::path_safety_checker::updateCollisionCheckDebugMap( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check.md b/planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check.md index 4733fe7832da6..5511202c390b1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check.md +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check.md @@ -48,7 +48,7 @@ $$ rss_{dist} = v_{rear} (t_{reaction} + t_{margin}) + \frac{v_{rear}^2}{2|a_{rear, decel}|} - \frac{v_{front}^2}{2|a_{front, decel|}} $$ -where $V_{front}$, $v_{rear}$ are front and rear vehicle velocity respectively and $a_{rear, front}$, $a_{rear, decel}$ are front and rear vehicle deceleration. +where $V_{front}$, $v_{rear}$ are front and rear vehicle velocity respectively and $a_{rear, front}$, $a_{rear, decel}$ are front and rear vehicle deceleration. Note that RSS distance is normally used for objects traveling in the same direction, if the yaw difference between a given ego pose and object pose is more than a user-defined yaw difference threshold, the rss collision check will be skipped for that specific pair of poses. #### 5. Create extended ego and target object polygons @@ -56,7 +56,7 @@ In this step, we compute extended ego and target object polygons. The extended p ![extended_polygons](../images/path_safety_checker/extended_polygons.drawio.svg) -As the picture shows, we expand the rear object polygon. For the longitudinal side, we extend it with the RSS distance, and for the lateral side, we extend it by the lateral margin +As the picture shows, we expand the rear object polygon. For the longitudinal side, we extend it with the RSS distance, and for the lateral side, we extend it by the lateral margin. #### 6. Check overlap diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp index 313f9df471938..0e7d1cee65f02 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp @@ -23,6 +23,7 @@ #include +#include #include #include #include @@ -203,7 +204,9 @@ struct SafetyCheckParams /// possible values: ["RSS", "integral_predicted_polygon"] double keep_unsafe_time{0.0}; ///< Time to keep unsafe before changing to safe. double hysteresis_factor_expand_rate{ - 0.0}; ///< Hysteresis factor to expand/shrink polygon with the value. + 0.0}; ///< Hysteresis factor to expand/shrink polygon with the value. + double collision_check_yaw_diff_threshold{ + 3.1416}; ///< threshold yaw difference between ego and object. double backward_path_length{0.0}; ///< Length of the backward lane for path generation. double forward_path_length{0.0}; ///< Length of the forward path lane for path generation. RSSparams rss_params{}; ///< Parameters related to the RSS model. diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index 3f1094dfd70b6..d0d19b6b8fed2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -26,6 +26,7 @@ #include #include +#include #include namespace autoware::behavior_path_planner::utils::path_safety_checker @@ -98,7 +99,8 @@ bool checkSafetyWithRSS( const std::vector & ego_predicted_path, const std::vector & objects, CollisionCheckDebugMap & debug_map, const BehaviorPathPlannerParameters & parameters, const RSSparams & rss_params, - const bool check_all_predicted_path, const double hysteresis_factor); + const bool check_all_predicted_path, const double hysteresis_factor, + const double yaw_difference_th); /** * @brief Iterate the points in the ego and target's predicted path and @@ -111,6 +113,8 @@ bool checkSafetyWithRSS( * @param common_parameters The common parameters used in behavior path planner. * @param front_object_deceleration The deceleration of the object in the front.(used in RSS) * @param rear_object_deceleration The deceleration of the object in the rear.(used in RSS) + * @param yaw_difference_th maximum yaw difference between any given ego path pose and object + * predicted path pose. * @param debug The debug information for collision checking. * @return true if distance is safe. */ @@ -120,7 +124,7 @@ bool checkCollision( const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, - const double hysteresis_factor, CollisionCheckDebug & debug); + const double hysteresis_factor, const double yaw_difference_th, CollisionCheckDebug & debug); /** * @brief Iterate the points in the ego and target's predicted path and @@ -142,7 +146,8 @@ std::vector getCollidedPolygons( const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, - const double hysteresis_factor, const double max_velocity_limit, CollisionCheckDebug & debug); + const double hysteresis_factor, const double max_velocity_limit, const double yaw_difference_th, + CollisionCheckDebug & debug); bool checkPolygonsIntersects( const std::vector & polys_1, const std::vector & polys_2); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index 7bb8c13aa65fb..b05d869cca6b5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -26,6 +26,9 @@ #include #include +#include + +#include #include namespace autoware::behavior_path_planner::utils::path_safety_checker @@ -482,7 +485,8 @@ bool checkSafetyWithRSS( const std::vector & ego_predicted_path, const std::vector & objects, CollisionCheckDebugMap & debug_map, const BehaviorPathPlannerParameters & parameters, const RSSparams & rss_params, - const bool check_all_predicted_path, const double hysteresis_factor) + const bool check_all_predicted_path, const double hysteresis_factor, + const double yaw_difference_th) { // Check for collisions with each predicted path of the object const bool is_safe = !std::any_of(objects.begin(), objects.end(), [&](const auto & object) { @@ -495,7 +499,7 @@ bool checkSafetyWithRSS( obj_predicted_paths.begin(), obj_predicted_paths.end(), [&](const auto & obj_path) { const bool has_collision = !utils::path_safety_checker::checkCollision( planned_path, ego_predicted_path, object, obj_path, parameters, rss_params, - hysteresis_factor, current_debug_data.second); + hysteresis_factor, yaw_difference_th, current_debug_data.second); utils::path_safety_checker::updateCollisionCheckDebugMap( debug_map, current_debug_data, !has_collision); @@ -559,11 +563,12 @@ bool checkCollision( const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, - const double hysteresis_factor, CollisionCheckDebug & debug) + const double hysteresis_factor, const double yaw_difference_th, CollisionCheckDebug & debug) { const auto collided_polygons = getCollidedPolygons( planned_path, predicted_ego_path, target_object, target_object_path, common_parameters, - rss_parameters, hysteresis_factor, std::numeric_limits::max(), debug); + rss_parameters, hysteresis_factor, std::numeric_limits::max(), yaw_difference_th, + debug); return collided_polygons.empty(); } @@ -573,7 +578,8 @@ std::vector getCollidedPolygons( const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, - double hysteresis_factor, const double max_velocity_limit, CollisionCheckDebug & debug) + double hysteresis_factor, const double max_velocity_limit, const double yaw_difference_th, + CollisionCheckDebug & debug) { { debug.ego_predicted_path = predicted_ego_path; @@ -604,6 +610,11 @@ std::vector getCollidedPolygons( const auto & ego_polygon = interpolated_data->poly; const auto ego_velocity = std::min(interpolated_data->velocity, max_velocity_limit); + const double ego_yaw = tf2::getYaw(ego_pose.orientation); + const double object_yaw = tf2::getYaw(obj_pose.orientation); + const double yaw_difference = autoware::universe_utils::normalizeRadian(ego_yaw - object_yaw); + if (std::abs(yaw_difference) > yaw_difference_th) continue; + // check overlap if (boost::geometry::overlaps(ego_polygon, obj_polygon)) { debug.unsafe_reason = "overlap_polygon"; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md index 066708891652a..dba4a0cfce5e7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md @@ -436,17 +436,18 @@ Parameters under `target_filtering` are related to filtering target objects for Parameters under `safety_check_params` define the configuration for safety check. -| Name | Unit | Type | Description | Default value | -| :--------------------------------------------- | :--- | :----- | :------------------------------------------ | :------------ | -| enable_safety_check | - | bool | Flag to enable safety check | true | -| check_all_predicted_path | - | bool | Flag to check all predicted paths | true | -| publish_debug_marker | - | bool | Flag to publish debug markers | false | -| rss_params.rear_vehicle_reaction_time | [s] | double | Reaction time for rear vehicles | 2.0 | -| rss_params.rear_vehicle_safety_time_margin | [s] | double | Safety time margin for rear vehicles | 1.0 | -| rss_params.lateral_distance_max_threshold | [m] | double | Maximum lateral distance threshold | 2.0 | -| rss_params.longitudinal_distance_min_threshold | [m] | double | Minimum longitudinal distance threshold | 3.0 | -| rss_params.longitudinal_velocity_delta_time | [s] | double | Delta time for longitudinal velocity | 0.8 | -| hysteresis_factor_expand_rate | - | double | Rate to expand/shrink the hysteresis factor | 1.0 | +| Name | Unit | Type | Description | Default value | +| :--------------------------------------------- | :--- | :----- | :---------------------------------------------------------------------------------------- | :------------ | +| enable_safety_check | - | bool | Flag to enable safety check | true | +| check_all_predicted_path | - | bool | Flag to check all predicted paths | true | +| publish_debug_marker | - | bool | Flag to publish debug markers | false | +| rss_params.rear_vehicle_reaction_time | [s] | double | Reaction time for rear vehicles | 2.0 | +| rss_params.rear_vehicle_safety_time_margin | [s] | double | Safety time margin for rear vehicles | 1.0 | +| rss_params.lateral_distance_max_threshold | [m] | double | Maximum lateral distance threshold | 2.0 | +| rss_params.longitudinal_distance_min_threshold | [m] | double | Minimum longitudinal distance threshold | 3.0 | +| rss_params.longitudinal_velocity_delta_time | [s] | double | Delta time for longitudinal velocity | 0.8 | +| hysteresis_factor_expand_rate | - | double | Rate to expand/shrink the hysteresis factor | 1.0 | +| collision_check_yaw_diff_threshold | - | double | Maximum yaw difference between ego and object when executing rss-based collision checking | 1.578 | ## **Path Generation** diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml index ce7ead87b54c7..d39a320a19e14 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml @@ -143,8 +143,10 @@ lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 longitudinal_velocity_delta_time: 0.8 + extended_polygon_policy: "along_path" # [-] select "rectangle" or "along_path" # hysteresis factor to expand/shrink polygon hysteresis_factor_expand_rate: 1.0 + collision_check_yaw_diff_threshold: 1.578 # temporary backward_path_length: 30.0 forward_path_length: 100.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp index 7554098414442..b07d6497463ef 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp @@ -77,7 +77,7 @@ struct PullOutStatus // record if the ego has departed from the start point bool has_departed{false}; - PullOutStatus() {} + PullOutStatus() = default; }; class StartPlannerModule : public SceneModuleInterface @@ -90,7 +90,7 @@ class StartPlannerModule : public SceneModuleInterface std::unordered_map> & objects_of_interest_marker_interface_ptr_map); - ~StartPlannerModule() + ~StartPlannerModule() override { if (freespace_planner_timer_) { freespace_planner_timer_->cancel(); @@ -296,16 +296,16 @@ class StartPlannerModule : public SceneModuleInterface PathWithLaneId getCurrentPath() const; void planWithPriority( const std::vector & start_pose_candidates, const Pose & refined_start_pose, - const Pose & goal_pose, const std::string search_priority); + const Pose & goal_pose, const std::string & search_priority); PathWithLaneId generateStopPath() const; lanelet::ConstLanelets getPathRoadLanes(const PathWithLaneId & path) const; std::vector generateDrivableLanes(const PathWithLaneId & path) const; void updatePullOutStatus(); void updateStatusAfterBackwardDriving(); PredictedObjects filterStopObjectsInPullOutLanes( - const lanelet::ConstLanelets & pull_out_lanes, const geometry_msgs::msg::Point & current_pose, - const double velocity_threshold, const double object_check_backward_distance, - const double object_check_forward_distance) const; + const lanelet::ConstLanelets & pull_out_lanes, const geometry_msgs::msg::Point & current_point, + const double velocity_threshold, const double object_check_forward_distance, + const double object_check_backward_distance) const; bool needToPrepareBlinkerBeforeStartDrivingForward() const; bool hasReachedFreespaceEnd() const; bool hasReachedPullOutEnd() const; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp index 9451bb3870648..873bab1043485 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp @@ -283,6 +283,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) node->declare_parameter(safety_check_ns + "forward_path_length"); p.safety_check_params.publish_debug_marker = node->declare_parameter(safety_check_ns + "publish_debug_marker"); + p.safety_check_params.collision_check_yaw_diff_threshold = + node->declare_parameter(safety_check_ns + "collision_check_yaw_diff_threshold"); } // RSSparams @@ -298,6 +300,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) node->declare_parameter(rss_ns + "longitudinal_distance_min_threshold"); p.safety_check_params.rss_params.longitudinal_velocity_delta_time = node->declare_parameter(rss_ns + "longitudinal_velocity_delta_time"); + p.safety_check_params.rss_params.extended_polygon_policy = + node->declare_parameter(rss_ns + "extended_polygon_policy"); } // surround moving obstacle check @@ -367,7 +371,6 @@ void StartPlannerModuleManager::updateModuleParams( updateParam( parameters, ns + "extra_width_margin_for_rear_obstacle", p->extra_width_margin_for_rear_obstacle); - updateParam>( parameters, ns + "collision_check_margins", p->collision_check_margins); updateParam( @@ -658,6 +661,9 @@ void StartPlannerModuleManager::updateModuleParams( updateParam( parameters, safety_check_ns + "publish_debug_marker", p->safety_check_params.publish_debug_marker); + updateParam( + parameters, safety_check_ns + "collision_check_yaw_diff_threshold", + p->safety_check_params.collision_check_yaw_diff_threshold); } const std::string rss_ns = safety_check_ns + "rss_params."; { @@ -676,6 +682,9 @@ void StartPlannerModuleManager::updateModuleParams( updateParam( parameters, rss_ns + "longitudinal_velocity_delta_time", p->safety_check_params.rss_params.longitudinal_velocity_delta_time); + updateParam( + parameters, rss_ns + "extended_polygon_policy", + p->safety_check_params.rss_params.extended_polygon_policy); } std::string surround_moving_obstacle_check_ns = ns + "surround_moving_obstacle_check."; { diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index f134e1645e9a5..86e35aa52095a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -34,7 +34,9 @@ #include #include +#include #include +#include #include #include #include @@ -65,7 +67,7 @@ StartPlannerModule::StartPlannerModule( { lane_departure_checker_ = std::make_shared(); lane_departure_checker_->setVehicleInfo(vehicle_info_); - autoware::lane_departure_checker::Param lane_departure_checker_params; + autoware::lane_departure_checker::Param lane_departure_checker_params{}; lane_departure_checker_params.footprint_extra_margin = parameters->lane_departure_check_expansion_margin; @@ -104,7 +106,7 @@ void StartPlannerModule::onFreespacePlannerTimer() std::optional current_status_opt{std::nullopt}; std::optional parameters_opt{std::nullopt}; std::optional pull_out_status_opt{std::nullopt}; - bool is_stopped; + bool is_stopped{false}; // making a local copy of thread sensitive data { @@ -501,7 +503,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const // Get the closest target obj width in the relevant lanes const auto closest_object_width = std::invoke([&]() -> std::optional { double arc_length_to_closet_object = std::numeric_limits::max(); - double closest_object_width = -1.0; + std::optional closest_object_width = std::nullopt; std::for_each( target_objects_on_lane.on_current_lane.begin(), target_objects_on_lane.on_current_lane.end(), [&](const auto & o) { @@ -512,7 +514,6 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const arc_length_to_closet_object = arc_length; closest_object_width = o.shape.dimensions.y; }); - if (closest_object_width < 0.0) return std::nullopt; return closest_object_width; }); if (!closest_object_width) return false; @@ -837,7 +838,7 @@ PathWithLaneId StartPlannerModule::getCurrentPath() const void StartPlannerModule::planWithPriority( const std::vector & start_pose_candidates, const Pose & refined_start_pose, - const Pose & goal_pose, const std::string search_priority) + const Pose & goal_pose, const std::string & search_priority) { if (start_pose_candidates.empty()) return; @@ -1116,8 +1117,8 @@ void StartPlannerModule::updateStatusAfterBackwardDriving() waitApproval(); // To enable approval of the forward path, the RTC status is removed. removeRTCStatus(); - for (auto itr = uuid_map_.begin(); itr != uuid_map_.end(); ++itr) { - itr->second = generateUUID(); + for (auto & itr : uuid_map_) { + itr.second = generateUUID(); } } @@ -1307,7 +1308,7 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() return ignore_signal_.value() == id; }; - const auto update_ignore_signal = [this](const lanelet::Id & id, const bool is_ignore) { + const auto update_ignore_signal = [](const lanelet::Id & id, const bool is_ignore) { return is_ignore ? std::make_optional(id) : std::nullopt; }; @@ -1426,10 +1427,12 @@ bool StartPlannerModule::isSafePath() const merged_target_object.insert( merged_target_object.end(), target_objects_on_lane.on_shoulder_lane.begin(), target_objects_on_lane.on_shoulder_lane.end()); + return autoware::behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS( pull_out_path, ego_predicted_path, merged_target_object, debug_data_.collision_check, planner_data_->parameters, safety_check_params_->rss_params, - objects_filtering_params_->use_all_predicted_path, hysteresis_factor); + objects_filtering_params_->use_all_predicted_path, hysteresis_factor, + safety_check_params_->collision_check_yaw_diff_threshold); } bool StartPlannerModule::isGoalBehindOfEgoInSameRouteSegment() const @@ -1697,7 +1700,7 @@ void StartPlannerModule::setDebugData() // safety check if (parameters_->safety_check_params.enable_safety_check) { - if (debug_data_.ego_predicted_path.size() > 0) { + if (!debug_data_.ego_predicted_path.empty()) { const auto & ego_predicted_path = utils::path_safety_checker::convertToPredictedPath( debug_data_.ego_predicted_path, ego_predicted_path_params_->time_resolution); add( @@ -1706,7 +1709,7 @@ void StartPlannerModule::setDebugData() debug_marker_); } - if (debug_data_.filtered_objects.objects.size() > 0) { + if (!debug_data_.filtered_objects.objects.empty()) { add( createObjectsMarkerArray( debug_data_.filtered_objects, "filtered_objects", 0, 0.0, 0.5, 0.9), diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml index 884812d0db716..fb8b02f1f0158 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml @@ -178,6 +178,7 @@ safety_check_backward_distance: 100.0 # [m] hysteresis_factor_expand_rate: 1.5 # [-] hysteresis_factor_safe_count: 3 # [-] + collision_check_yaw_diff_threshold: 3.1416 # [rad] # predicted path parameters min_velocity: 1.38 # [m/s] max_velocity: 50.0 # [m/s] diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp index 53e7c2f341926..5f6a4526af580 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -226,6 +226,8 @@ struct AvoidanceParameters size_t hysteresis_factor_safe_count; double hysteresis_factor_expand_rate{0.0}; + double collision_check_yaw_diff_threshold{3.1416}; + bool consider_front_overhang{true}; bool consider_rear_overhang{true}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp index 361fe60c21eb1..d7335165e5622 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp @@ -199,6 +199,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "hysteresis_factor_expand_rate"); p.hysteresis_factor_safe_count = getOrDeclareParameter(*node, ns + "hysteresis_factor_safe_count"); + p.collision_check_yaw_diff_threshold = + getOrDeclareParameter(*node, ns + "collision_check_yaw_diff_threshold"); } // safety check predicted path params diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json index cb150514ac372..ce36cbf949637 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json @@ -931,6 +931,11 @@ "description": "Hysteresis count that be used for chattering prevention.", "default": 10 }, + "collision_check_yaw_diff_threshold": { + "type": "number", + "description": "Max yaw difference between ego and object when doing collision check", + "default": 3.1416 + }, "min_velocity": { "type": "number", "description": "Minimum velocity of the ego vehicle's predicted path.", diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index bbdb8078aadf9..922883f289de8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -780,7 +780,8 @@ bool StaticObstacleAvoidanceModule::isSafePath( for (const auto & obj_path : obj_predicted_paths) { if (!utils::path_safety_checker::checkCollision( shifted_path.path, ego_predicted_path, object, obj_path, p, parameters_->rss_params, - hysteresis_factor, current_debug_data.second)) { + hysteresis_factor, parameters_->collision_check_yaw_diff_threshold, + current_debug_data.second)) { utils::path_safety_checker::updateCollisionCheckDebugMap( debug.collision_check, current_debug_data, false); From 6b13edc0f409d2d37452168e6ff010e7c914a03f Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 24 Jun 2024 10:12:00 +0900 Subject: [PATCH 03/13] feat(motion_velocity_planner): publish processing times (#7633) Signed-off-by: Maxime CLEMENT --- .../src/dynamic_obstacle_stop_module.cpp | 9 +++++++++ .../src/obstacle_velocity_limiter_module.cpp | 9 +++++++++ .../src/out_of_lane_module.cpp | 17 +++++++++++++++-- .../plugin_module_interface.hpp | 2 ++ .../src/node.cpp | 11 +++++++++++ .../src/node.hpp | 1 + 6 files changed, 47 insertions(+), 2 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp index fde54a7041672..bf9dc30145cd3 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp @@ -29,6 +29,7 @@ #include #include +#include #include #include #include @@ -48,6 +49,8 @@ void DynamicObstacleStopModule::init(rclcpp::Node & node, const std::string & mo node.create_publisher("~/" + ns_ + "/debug_markers", 1); virtual_wall_publisher_ = node.create_publisher("~/" + ns_ + "/virtual_walls", 1); + processing_time_publisher_ = std::make_shared( + &node, "~/debug/" + ns_ + "/processing_time_ms"); using autoware::universe_utils::getOrDeclareParameter; auto & p = params_; @@ -179,6 +182,12 @@ VelocityPlanningResult DynamicObstacleStopModule::plan( debug_data_.ego_footprints = ego_data.trajectory_footprints; debug_data_.obstacle_footprints = obstacle_forward_footprints; debug_data_.z = ego_data.pose.position.z; + std::map processing_times; + processing_times["preprocessing"] = preprocessing_duration_us / 1000; + processing_times["footprints"] = footprints_duration_us / 1000; + processing_times["collisions"] = collisions_duration_us / 1000; + processing_times["Total"] = total_time_us / 1000; + processing_time_publisher_->publish(processing_times); return result; } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp index 2b78a2f1495bf..5a4f03f6f20a6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp @@ -34,6 +34,7 @@ #include #include +#include namespace autoware::motion_velocity_planner { @@ -52,6 +53,8 @@ void ObstacleVelocityLimiterModule::init(rclcpp::Node & node, const std::string node.create_publisher("~/" + ns_ + "/debug_markers", 1); virtual_wall_publisher_ = node.create_publisher("~/" + ns_ + "/virtual_walls", 1); + processing_time_publisher_ = std::make_shared( + &node, "~/debug/" + ns_ + "/processing_time_ms"); const auto vehicle_info = vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); vehicle_lateral_offset_ = static_cast(vehicle_info.max_lateral_offset_m); @@ -218,6 +221,12 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan( safe_footprint_polygons, obstacle_masks, planner_data->current_odometry.pose.pose.position.z)); } + std::map processing_times; + processing_times["preprocessing"] = preprocessing_us / 1000; + processing_times["obstacles"] = obstacles_us / 1000; + processing_times["slowdowns"] = slowdowns_us / 1000; + processing_times["Total"] = total_us / 1000; + processing_time_publisher_->publish(processing_times); return result; } } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index f6d81f6f036d0..18a37e74df9aa 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -33,6 +33,7 @@ #include +#include #include #include #include @@ -56,6 +57,8 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) node.create_publisher("~/" + ns_ + "/debug_markers", 1); virtual_wall_publisher_ = node.create_publisher("~/" + ns_ + "/virtual_walls", 1); + processing_time_publisher_ = std::make_shared( + &node, "~/debug/" + ns_ + "/processing_time_ms"); } void OutOfLaneModule::init_parameters(rclcpp::Node & node) { @@ -207,7 +210,7 @@ VelocityPlanningResult OutOfLaneModule::plan( inputs.ego_data = ego_data; stopwatch.tic("filter_predicted_objects"); inputs.objects = out_of_lane::filter_predicted_objects(planner_data, ego_data, params_); - const auto filter_predicted_objects_ms = stopwatch.toc("filter_predicted_objects"); + const auto filter_predicted_objects_us = stopwatch.toc("filter_predicted_objects"); inputs.route_handler = planner_data->route_handler; inputs.lanelets = other_lanelets; stopwatch.tic("calculate_decisions"); @@ -288,12 +291,22 @@ VelocityPlanningResult OutOfLaneModule::plan( "\tcalc_slowdown_points = %2.0fus\n" "\tinsert_slowdown_points = %2.0fus\n", total_time_us, calculate_lanelets_us, calculate_trajectory_footprints_us, - calculate_overlapping_ranges_us, filter_predicted_objects_ms, calculate_decisions_us, + calculate_overlapping_ranges_us, filter_predicted_objects_us, calculate_decisions_us, calc_slowdown_points_us, insert_slowdown_points_us); debug_publisher_->publish(out_of_lane::debug::create_debug_marker_array(debug_data_)); virtual_wall_marker_creator.add_virtual_walls( out_of_lane::debug::create_virtual_walls(debug_data_, params_)); virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); + std::map processing_times; + processing_times["calculate_lanelets"] = calculate_lanelets_us / 1000; + processing_times["calculate_trajectory_footprints"] = calculate_trajectory_footprints_us / 1000; + processing_times["calculate_overlapping_ranges"] = calculate_overlapping_ranges_us / 1000; + processing_times["filter_pred_objects"] = filter_predicted_objects_us / 1000; + processing_times["calculate_decision"] = calculate_decisions_us / 1000; + processing_times["calc_slowdown_points"] = calc_slowdown_points_us / 1000; + processing_times["insert_slowdown_points"] = insert_slowdown_points_us / 1000; + processing_times["Total"] = total_time_us / 1000; + processing_time_publisher_->publish(processing_times); return result; } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp index 535510453b8ba..bf0be64a0880d 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp @@ -19,6 +19,7 @@ #include "velocity_planning_result.hpp" #include +#include #include #include @@ -44,6 +45,7 @@ class PluginModuleInterface rclcpp::Logger logger_ = rclcpp::get_logger(""); rclcpp::Publisher::SharedPtr debug_publisher_; rclcpp::Publisher::SharedPtr virtual_wall_publisher_; + std::shared_ptr processing_time_publisher_; autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator{}; }; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 714b6fd948a32..da997dcfbc6e4 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include #include @@ -31,6 +32,7 @@ #include #include +#include #include #include @@ -252,9 +254,14 @@ void MotionVelocityPlannerNode::on_trajectory( { std::unique_lock lk(mutex_); + autoware::universe_utils::StopWatch stop_watch; + std::map processing_times; + stop_watch.tic("Total"); + if (!update_planner_data()) { return; } + processing_times["update_planner_data"] = stop_watch.toc(true); if (input_trajectory_msg->points.empty()) { RCLCPP_WARN(get_logger(), "Input trajectory message is empty"); @@ -264,6 +271,7 @@ void MotionVelocityPlannerNode::on_trajectory( if (has_received_map_) { planner_data_.route_handler = std::make_shared(*map_ptr_); has_received_map_ = false; + processing_times["make_RouteHandler"] = stop_watch.toc(true); } autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points{ @@ -271,12 +279,15 @@ void MotionVelocityPlannerNode::on_trajectory( auto output_trajectory_msg = generate_trajectory(input_trajectory_points); output_trajectory_msg.header = input_trajectory_msg->header; + processing_times["generate_trajectory"] = stop_watch.toc(true); lk.unlock(); trajectory_pub_->publish(output_trajectory_msg); published_time_publisher_->publish_if_subscribed( trajectory_pub_, output_trajectory_msg.header.stamp); + processing_times["Total"] = stop_watch.toc("Total"); + processing_time_publisher_.publish(processing_times); } void MotionVelocityPlannerNode::insert_stop( diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index 7b771d0b04442..04e3e6b02c7b0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -96,6 +96,7 @@ class MotionVelocityPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_viz_pub_; rclcpp::Publisher::SharedPtr velocity_factor_publisher_; + autoware::universe_utils::ProcessingTimePublisher processing_time_publisher_{this}; // parameters rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr set_param_callback_; From 9e557401069345ae8f9b1d45e62a91da49e51767 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 25 Jun 2024 19:57:39 +0900 Subject: [PATCH 04/13] feat(motion_velocity_planner, lane_departure_checker): add processing time Float64 publishers (#7683) Signed-off-by: Maxime CLEMENT --- .../lane_departure_checker_node.hpp | 4 +++- .../lane_departure_checker_node.cpp | 8 +++++++- .../src/dynamic_obstacle_stop_module.cpp | 12 +++++++++--- .../src/obstacle_velocity_limiter_module.cpp | 12 +++++++++--- .../src/out_of_lane_module.cpp | 12 +++++++++--- .../plugin_module_interface.hpp | 4 +++- .../package.xml | 1 + .../package.xml | 1 + .../src/node.cpp | 12 ++++++++---- .../src/node.hpp | 7 ++++--- 10 files changed, 54 insertions(+), 19 deletions(-) diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp index e6421b2af84bb..876797a58df25 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp @@ -100,7 +100,9 @@ class LaneDepartureCheckerNode : public rclcpp::Node // Publisher autoware::universe_utils::DebugPublisher debug_publisher_{this, "~/debug"}; - autoware::universe_utils::ProcessingTimePublisher processing_time_publisher_{this}; + autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{ + this, "~/debug/processing_time_ms_diag"}; + rclcpp::Publisher::SharedPtr processing_time_publisher_; // Timer rclcpp::TimerBase::SharedPtr timer_; diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index 427cf0898470e..dde37b03ffecc 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -170,6 +170,8 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o lane_departure_checker_->setParam(param_, vehicle_info); // Publisher + processing_time_publisher_ = + this->create_publisher("~/debug/processing_time_ms", 1); // Nothing // Diagnostic Updater @@ -347,7 +349,11 @@ void LaneDepartureCheckerNode::onTimer() } processing_time_map["Total"] = stop_watch.toc("Total"); - processing_time_publisher_.publish(processing_time_map); + processing_diag_publisher_.publish(processing_time_map); + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = processing_time_map["Total"]; + processing_time_publisher_->publish(processing_time_msg); } rcl_interfaces::msg::SetParametersResult LaneDepartureCheckerNode::onParameter( diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp index bf9dc30145cd3..12cb59ac46195 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp @@ -49,8 +49,10 @@ void DynamicObstacleStopModule::init(rclcpp::Node & node, const std::string & mo node.create_publisher("~/" + ns_ + "/debug_markers", 1); virtual_wall_publisher_ = node.create_publisher("~/" + ns_ + "/virtual_walls", 1); - processing_time_publisher_ = std::make_shared( - &node, "~/debug/" + ns_ + "/processing_time_ms"); + processing_diag_publisher_ = std::make_shared( + &node, "~/debug/" + ns_ + "/processing_time_ms_diag"); + processing_time_publisher_ = node.create_publisher( + "~/debug/" + ns_ + "/processing_time_ms", 1); using autoware::universe_utils::getOrDeclareParameter; auto & p = params_; @@ -187,7 +189,11 @@ VelocityPlanningResult DynamicObstacleStopModule::plan( processing_times["footprints"] = footprints_duration_us / 1000; processing_times["collisions"] = collisions_duration_us / 1000; processing_times["Total"] = total_time_us / 1000; - processing_time_publisher_->publish(processing_times); + processing_diag_publisher_->publish(processing_times); + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = clock_->now(); + processing_time_msg.data = processing_times["Total"]; + processing_time_publisher_->publish(processing_time_msg); return result; } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp index 5a4f03f6f20a6..eb8a33ede2c72 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp @@ -53,8 +53,10 @@ void ObstacleVelocityLimiterModule::init(rclcpp::Node & node, const std::string node.create_publisher("~/" + ns_ + "/debug_markers", 1); virtual_wall_publisher_ = node.create_publisher("~/" + ns_ + "/virtual_walls", 1); - processing_time_publisher_ = std::make_shared( - &node, "~/debug/" + ns_ + "/processing_time_ms"); + processing_diag_publisher_ = std::make_shared( + &node, "~/debug/" + ns_ + "/processing_time_ms_diag"); + processing_time_publisher_ = node.create_publisher( + "~/debug/" + ns_ + "/processing_time_ms", 1); const auto vehicle_info = vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); vehicle_lateral_offset_ = static_cast(vehicle_info.max_lateral_offset_m); @@ -226,7 +228,11 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan( processing_times["obstacles"] = obstacles_us / 1000; processing_times["slowdowns"] = slowdowns_us / 1000; processing_times["Total"] = total_us / 1000; - processing_time_publisher_->publish(processing_times); + processing_diag_publisher_->publish(processing_times); + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = clock_->now(); + processing_time_msg.data = processing_times["Total"]; + processing_time_publisher_->publish(processing_time_msg); return result; } } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index 18a37e74df9aa..8397d0c116090 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -57,8 +57,10 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) node.create_publisher("~/" + ns_ + "/debug_markers", 1); virtual_wall_publisher_ = node.create_publisher("~/" + ns_ + "/virtual_walls", 1); - processing_time_publisher_ = std::make_shared( - &node, "~/debug/" + ns_ + "/processing_time_ms"); + processing_diag_publisher_ = std::make_shared( + &node, "~/debug/" + ns_ + "/processing_time_ms_diag"); + processing_time_publisher_ = node.create_publisher( + "~/debug/" + ns_ + "/processing_time_ms", 1); } void OutOfLaneModule::init_parameters(rclcpp::Node & node) { @@ -306,7 +308,11 @@ VelocityPlanningResult OutOfLaneModule::plan( processing_times["calc_slowdown_points"] = calc_slowdown_points_us / 1000; processing_times["insert_slowdown_points"] = insert_slowdown_points_us / 1000; processing_times["Total"] = total_time_us / 1000; - processing_time_publisher_->publish(processing_times); + processing_diag_publisher_->publish(processing_times); + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = clock_->now(); + processing_time_msg.data = processing_times["Total"]; + processing_time_publisher_->publish(processing_time_msg); return result; } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp index bf0be64a0880d..9bd662af697ea 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp @@ -23,6 +23,7 @@ #include #include +#include #include #include @@ -45,7 +46,8 @@ class PluginModuleInterface rclcpp::Logger logger_ = rclcpp::get_logger(""); rclcpp::Publisher::SharedPtr debug_publisher_; rclcpp::Publisher::SharedPtr virtual_wall_publisher_; - std::shared_ptr processing_time_publisher_; + std::shared_ptr processing_diag_publisher_; + rclcpp::Publisher::SharedPtr processing_time_publisher_; autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator{}; }; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml index d2a3e305180d5..e428719f6e32f 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml @@ -27,6 +27,7 @@ lanelet2_extension libboost-dev rclcpp + tier4_debug_msgs tier4_planning_msgs visualization_msgs diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml index c00e0dd856200..aad25d5fb20a1 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml @@ -38,6 +38,7 @@ tf2_eigen tf2_geometry_msgs tf2_ros + tier4_debug_msgs tier4_planning_msgs visualization_msgs diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index da997dcfbc6e4..6578c5cfaca65 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -82,6 +82,8 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & velocity_factor_publisher_ = this->create_publisher( "~/output/velocity_factors", 1); + processing_time_publisher_ = this->create_publisher( + "~/debug/total_time/processing_time_ms", 1); // Parameters smooth_velocity_before_planning_ = declare_parameter("smooth_velocity_before_planning"); @@ -105,8 +107,6 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & std::bind(&MotionVelocityPlannerNode::on_set_param, this, std::placeholders::_1)); logger_configure_ = std::make_unique(this); - published_time_publisher_ = - std::make_unique(this); } void MotionVelocityPlannerNode::on_load_plugin( @@ -284,10 +284,14 @@ void MotionVelocityPlannerNode::on_trajectory( lk.unlock(); trajectory_pub_->publish(output_trajectory_msg); - published_time_publisher_->publish_if_subscribed( + published_time_publisher_.publish_if_subscribed( trajectory_pub_, output_trajectory_msg.header.stamp); processing_times["Total"] = stop_watch.toc("Total"); - processing_time_publisher_.publish(processing_times); + processing_diag_publisher_.publish(processing_times); + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = processing_times["Total"]; + processing_time_publisher_->publish(processing_time_msg); } void MotionVelocityPlannerNode::insert_stop( diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index 04e3e6b02c7b0..8debb9cbedf00 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -32,6 +32,7 @@ #include #include #include +#include #include #include @@ -96,7 +97,9 @@ class MotionVelocityPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_viz_pub_; rclcpp::Publisher::SharedPtr velocity_factor_publisher_; - autoware::universe_utils::ProcessingTimePublisher processing_time_publisher_{this}; + autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{this}; + rclcpp::Publisher::SharedPtr processing_time_publisher_; + autoware::universe_utils::PublishedTimePublisher published_time_publisher_{this}; // parameters rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr set_param_callback_; @@ -140,8 +143,6 @@ class MotionVelocityPlannerNode : public rclcpp::Node autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points); std::unique_ptr logger_configure_; - - std::unique_ptr published_time_publisher_; }; } // namespace autoware::motion_velocity_planner From e403943d3fe9a05aca938b3538335578298e977d Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 28 Jun 2024 14:14:48 +0900 Subject: [PATCH 05/13] perf(dynamic_obstacle_stop): create rtree with packing algorithm (#7730) Signed-off-by: Maxime CLEMENT --- .../src/footprint.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.cpp index 9695146a2ad38..73189e732b312 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.cpp @@ -74,11 +74,14 @@ void make_ego_footprint_rtree(EgoData & ego_data, const PlannerParam & params) for (const auto & p : ego_data.trajectory) ego_data.trajectory_footprints.push_back(autoware::universe_utils::toFootprint( p.pose, params.ego_longitudinal_offset, 0.0, params.ego_lateral_offset * 2.0)); + std::vector rtree_nodes; + rtree_nodes.reserve(ego_data.trajectory_footprints.size()); for (auto i = 0UL; i < ego_data.trajectory_footprints.size(); ++i) { const auto box = boost::geometry::return_envelope( ego_data.trajectory_footprints[i]); - ego_data.rtree.insert(std::make_pair(box, i)); + rtree_nodes.push_back(std::make_pair(box, i)); } + ego_data.rtree = Rtree(rtree_nodes); } } // namespace autoware::motion_velocity_planner::dynamic_obstacle_stop From 91da5749330e2085323ca319aab4bf9a9d881512 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 1 Jul 2024 09:57:19 +0900 Subject: [PATCH 06/13] perf(motion_velocity_planner): resample trajectory after vel smoothing (#7732) * perf(dynamic_obstacle_stop): create rtree with packing algorithm Signed-off-by: Maxime CLEMENT * Revert "perf(out_of_lane): downsample the trajectory to improve performance (#7691)" This reverts commit 8444a9eb29b32f500be3724dd5662013b9b81060. * perf(motion_velocity_planner): resample trajectory after vel smoothing Signed-off-by: Maxime CLEMENT --------- Signed-off-by: Maxime CLEMENT --- .../autoware_motion_velocity_planner_node/src/node.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 6578c5cfaca65..2bc820d74693b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -14,6 +14,7 @@ #include "node.hpp" +#include #include #include #include @@ -380,9 +381,11 @@ autoware_planning_msgs::msg::Trajectory MotionVelocityPlannerNode::generate_traj output_trajectory_msg.points = {input_trajectory_points.begin(), input_trajectory_points.end()}; if (smooth_velocity_before_planning_) input_trajectory_points = smooth_trajectory(input_trajectory_points, planner_data_); + const auto resampled_trajectory = + autoware::motion_utils::resampleTrajectory(output_trajectory_msg, 0.5); const auto planning_results = planner_manager_.plan_velocities( - input_trajectory_points, std::make_shared(planner_data_)); + resampled_trajectory.points, std::make_shared(planner_data_)); autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factors; velocity_factors.header.frame_id = "map"; From d1f0430ba1910a7e629d33768f8f69edae9b7e03 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 25 Jun 2024 00:37:52 +0900 Subject: [PATCH 07/13] feat(static_centerline_generator): organize AUTO/GUI/VMB modes (#7432) Signed-off-by: Takagi, Isamu Signed-off-by: Takayuki Murooka --- .../CMakeLists.txt | 2 + .../static_centerline_generator.param.yaml | 6 +- .../static_centerline_generator.launch.xml | 27 +- .../rviz/static_centerline_generator.rviz | 34 +- .../scripts/centerline_updater_helper.py | 163 ++++--- .../bag_ego_trajectory_based_centerline.sh | 4 +- .../src/main.cpp | 14 +- .../src/static_centerline_generator_node.cpp | 450 +++++++++++++----- .../src/static_centerline_generator_node.hpp | 98 +++- .../src/type_alias.hpp | 1 + .../src/utils.cpp | 94 ++-- .../src/utils.hpp | 23 +- .../bag_ego_trajectory_turn-left-right.db3 | Bin 0 -> 2740224 bytes ....db3 => bag_ego_trajectory_turn-right.db3} | Bin .../test_static_centerline_generator.test.py | 2 +- .../vehicle_info.hpp | 3 + .../src/vehicle_info.cpp | 26 + 17 files changed, 681 insertions(+), 266 deletions(-) create mode 100644 planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-left-right.db3 rename planning/autoware_static_centerline_generator/test/data/{bag_ego_trajectory.db3 => bag_ego_trajectory_turn-right.db3} (100%) diff --git a/planning/autoware_static_centerline_generator/CMakeLists.txt b/planning/autoware_static_centerline_generator/CMakeLists.txt index 08a97c9010008..261e8beb0022f 100644 --- a/planning/autoware_static_centerline_generator/CMakeLists.txt +++ b/planning/autoware_static_centerline_generator/CMakeLists.txt @@ -60,5 +60,7 @@ endif() install(PROGRAMS scripts/app.py + scripts/centerline_updater_helper.py + scripts/show_lanelet2_map_diff.py DESTINATION lib/${PROJECT_NAME} ) diff --git a/planning/autoware_static_centerline_generator/config/static_centerline_generator.param.yaml b/planning/autoware_static_centerline_generator/config/static_centerline_generator.param.yaml index 24a5536949479..060590803428a 100644 --- a/planning/autoware_static_centerline_generator/config/static_centerline_generator.param.yaml +++ b/planning/autoware_static_centerline_generator/config/static_centerline_generator.param.yaml @@ -1,5 +1,9 @@ /**: ros__parameters: - marker_color: ["FF0000", "00FF00", "0000FF"] + marker_color: ["FF0000", "FF5A00", "FFFF00"] marker_color_dist_thresh : [0.1, 0.2, 0.3] output_trajectory_interval: 1.0 + + validation: + dist_threshold_to_road_border: 0.0 + max_steer_angle_margin: 0.0 # [rad] NOTE: Positive value makes max steer angle threshold to decrease. diff --git a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml index 3d786ab995e5b..38379a52e4c92 100644 --- a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml +++ b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -3,17 +3,19 @@ - + - - + - + + + + @@ -28,7 +30,7 @@ default="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml" /> - + @@ -55,12 +57,8 @@ - - - - - + @@ -75,12 +73,19 @@ + + + + + + + - + diff --git a/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz index 62b4c9b75ec87..fc916f188e758 100644 --- a/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz +++ b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz @@ -179,11 +179,11 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_generator/output_centerline + Value: /static_centerline_generator/output/centerline Value: true View Footprint: - Alpha: 1 - Color: 255; 0; 0 + Alpha: 0.5 + Color: 0; 255; 0 Offset from BaseLink: 0 Rear Overhang: 1.0299999713897705 Value: true @@ -268,9 +268,33 @@ Visualization Manager: Durability Policy: Transient Local History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_generator/debug/unsafe_footprints + Value: /static_centerline_generator/output/validation_results Value: true - Enabled: false + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: Debug Markers + Namespaces: + curvature: false + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /static_centerline_generator/debug/markers + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: MarkerArray + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /static_centerline_generator/debug/ego_footprint_bounds + Value: true + Enabled: true Name: debug Enabled: true Global Options: diff --git a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py index 3672165caed85..2cd0c2f66d474 100755 --- a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py +++ b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py @@ -20,18 +20,20 @@ from PyQt5 import QtCore from PyQt5.QtWidgets import QApplication -from PyQt5.QtWidgets import QGridLayout +from PyQt5.QtWidgets import QGroupBox from PyQt5.QtWidgets import QMainWindow from PyQt5.QtWidgets import QPushButton from PyQt5.QtWidgets import QSizePolicy from PyQt5.QtWidgets import QSlider +from PyQt5.QtWidgets import QVBoxLayout from PyQt5.QtWidgets import QWidget from autoware_planning_msgs.msg import Trajectory import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy from rclpy.qos import QoSProfile -from std_msgs.msg import Bool +from std_msgs.msg import Empty +from std_msgs.msg import Float32 from std_msgs.msg import Int32 @@ -46,25 +48,8 @@ def setupUI(self): self.setWindowFlags(QtCore.Qt.WindowStaysOnTopHint) central_widget = QWidget(self) - central_widget.setObjectName("central_widget") - - self.grid_layout = QGridLayout(central_widget) + self.grid_layout = QVBoxLayout(central_widget) self.grid_layout.setContentsMargins(10, 10, 10, 10) - self.grid_layout.setObjectName("grid_layout") - - # button to update the trajectory's start and end index - self.update_button = QPushButton("update slider") - self.update_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) - self.update_button.clicked.connect(self.onUpdateButton) - - # button to reset the trajectory's start and end index - self.reset_button = QPushButton("reset") - self.reset_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) - self.reset_button.clicked.connect(self.onResetButton) - - # button to save map - self.save_map_button = QPushButton("save map") - self.save_map_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) # slide of the trajectory's start and end index self.traj_start_index_slider = QSlider(QtCore.Qt.Horizontal) @@ -72,69 +57,60 @@ def setupUI(self): self.min_traj_start_index = 0 self.max_traj_end_index = None - # set layout - self.grid_layout.addWidget(self.update_button, 1, 0, 1, -1) - self.grid_layout.addWidget(self.reset_button, 2, 0, 1, -1) - self.grid_layout.addWidget(self.save_map_button, 3, 0, 1, -1) - self.grid_layout.addWidget(self.traj_start_index_slider, 4, 0, 1, -1) - self.grid_layout.addWidget(self.traj_end_index_slider, 5, 0, 1, -1) - self.setCentralWidget(central_widget) - - def initWithEndIndex(self, max_traj_end_index): - self.max_traj_end_index = max_traj_end_index - - # initialize slider - self.displayed_min_traj_start_index = self.min_traj_start_index - self.displayed_max_traj_end_index = self.max_traj_end_index - self.initializeSlider() - - def initializeSlider(self, move_value_to_end=True): - self.traj_start_index_slider.setMinimum(0) - self.traj_end_index_slider.setMinimum(0) - self.traj_start_index_slider.setMaximum( - self.displayed_max_traj_end_index - self.displayed_min_traj_start_index - ) - self.traj_end_index_slider.setMaximum( - self.displayed_max_traj_end_index - self.displayed_min_traj_start_index + # Layout: Range of Centerline + centerline_vertical_box = QVBoxLayout(self) + centerline_vertical_box.addWidget(self.traj_start_index_slider) + centerline_vertical_box.addWidget(self.traj_end_index_slider) + centerline_group = QGroupBox("Centerline") + centerline_group.setLayout(centerline_vertical_box) + self.grid_layout.addWidget(centerline_group) + + # 2. Road Boundary + road_boundary_group = QGroupBox("Road Boundary") + road_boundary_vertical_box = QVBoxLayout(self) + road_boundary_group.setLayout(road_boundary_vertical_box) + self.grid_layout.addWidget(road_boundary_group) + + # 2.1. Slider + self.road_boundary_lateral_margin_slider = QSlider(QtCore.Qt.Horizontal) + road_boundary_vertical_box.addWidget(self.road_boundary_lateral_margin_slider) + self.road_boundary_lateral_margin_ratio = 10 + self.road_boundary_lateral_margin_slider.setMinimum(0) + self.road_boundary_lateral_margin_slider.setMaximum( + 5 * self.road_boundary_lateral_margin_ratio ) - if move_value_to_end: - self.traj_start_index_slider.setValue(0) - self.traj_end_index_slider.setValue(self.traj_end_index_slider.maximum()) + road_boundary_vertical_box.addWidget(QPushButton("reset")) - def onResetButton(self, event): - current_traj_start_index = self.displayed_min_traj_start_index - current_traj_end_index = self.displayed_max_traj_end_index + # 3. General + general_group = QGroupBox("General") + general_vertical_box = QVBoxLayout(self) + general_group.setLayout(general_vertical_box) + self.grid_layout.addWidget(general_group) - self.displayed_min_traj_start_index = self.min_traj_start_index - self.displayed_max_traj_end_index = self.max_traj_end_index + # 3.1. Validate Centerline + self.validate_button = QPushButton("validate") + self.validate_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) + general_vertical_box.addWidget(self.validate_button) - self.initializeSlider(False) - self.traj_start_index_slider.setValue(current_traj_start_index) - if ( - current_traj_start_index == self.min_traj_start_index - and current_traj_end_index == self.max_traj_end_index - ): - self.traj_end_index_slider.setValue(self.displayed_max_traj_end_index) - else: - self.traj_end_index_slider.setValue( - current_traj_start_index + self.traj_end_index_slider.value() - ) - - def onUpdateButton(self, event): - current_traj_start_index = self.getCurrentStartIndex() - current_traj_end_index = self.getCurrentEndIndex() + # 3.2. Save Map + self.save_map_button = QPushButton("save map") + self.save_map_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) + general_vertical_box.addWidget(self.save_map_button) - self.displayed_min_traj_start_index = current_traj_start_index - self.displayed_max_traj_end_index = current_traj_end_index + self.setCentralWidget(central_widget) - self.initializeSlider() + def initWithEndIndex(self, max_traj_end_index): + self.max_traj_end_index = max_traj_end_index - def getCurrentStartIndex(self): - return self.displayed_min_traj_start_index + self.traj_start_index_slider.value() + # initialize sliders + self.traj_start_index_slider.setMinimum(self.min_traj_start_index) + self.traj_start_index_slider.setMaximum(self.max_traj_end_index) + self.traj_start_index_slider.setValue(self.min_traj_start_index) - def getCurrentEndIndex(self): - return self.displayed_min_traj_start_index + self.traj_end_index_slider.value() + self.traj_end_index_slider.setMinimum(self.min_traj_start_index) + self.traj_end_index_slider.setMaximum(self.max_traj_end_index) + self.traj_end_index_slider.setValue(self.max_traj_end_index) class CenterlineUpdaterHelper(Node): @@ -144,18 +120,30 @@ def __init__(self): self.widget = CenterlineUpdaterWidget() self.widget.show() self.widget.save_map_button.clicked.connect(self.onSaveMapButtonPushed) + self.widget.validate_button.clicked.connect(self.onValidateButtonPushed) self.widget.traj_start_index_slider.valueChanged.connect(self.onStartIndexChanged) self.widget.traj_end_index_slider.valueChanged.connect(self.onEndIndexChanged) + self.widget.road_boundary_lateral_margin_slider.valueChanged.connect( + self.onRoadBoundaryLateralMargin + ) # ROS - self.pub_save_map = self.create_publisher(Bool, "~/save_map", 1) - self.pub_traj_start_index = self.create_publisher(Int32, "~/traj_start_index", 1) - self.pub_traj_end_index = self.create_publisher(Int32, "~/traj_end_index", 1) + self.pub_save_map = self.create_publisher(Empty, "/static_centerline_generator/save_map", 1) + self.pub_validate = self.create_publisher(Empty, "/static_centerline_generator/validate", 1) + self.pub_traj_start_index = self.create_publisher( + Int32, "/static_centerline_generator/traj_start_index", 1 + ) + self.pub_traj_end_index = self.create_publisher( + Int32, "/static_centerline_generator/traj_end_index", 1 + ) + self.pub_road_boundary_lateral_margin = self.create_publisher( + Float32, "/static_centerline_generator/road_boundary_lateral_margin", 1 + ) transient_local_qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) self.sub_whole_centerline = self.create_subscription( Trajectory, - "/static_centerline_generator/output_whole_centerline", + "/static_centerline_generator/output/whole_centerline", self.onWholeCenterline, transient_local_qos, ) @@ -168,20 +156,31 @@ def onWholeCenterline(self, whole_centerline): self.widget.initWithEndIndex(len(whole_centerline.points) - 1) def onSaveMapButtonPushed(self, event): - msg = Bool() - msg.data = True + msg = Empty() self.pub_save_map.publish(msg) + def onValidateButtonPushed(self, event): + msg = Empty() + self.pub_validate.publish(msg) + def onStartIndexChanged(self, event): msg = Int32() - msg.data = self.widget.getCurrentStartIndex() + msg.data = self.widget.traj_start_index_slider.value() self.pub_traj_start_index.publish(msg) def onEndIndexChanged(self, event): msg = Int32() - msg.data = self.widget.getCurrentEndIndex() + msg.data = self.widget.traj_end_index_slider.value() self.pub_traj_end_index.publish(msg) + def onRoadBoundaryLateralMargin(self, event): + msg = Float32() + msg.data = ( + self.widget.road_boundary_lateral_margin_slider.value() + / self.widget.road_boundary_lateral_margin_ratio + ) + self.pub_road_boundary_lateral_margin.publish(msg) + def main(args=None): app = QApplication(sys.argv) diff --git a/planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh index e7f86062a9d20..c170e24e475d9 100755 --- a/planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh +++ b/planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh @@ -1,3 +1,5 @@ #!/bin/bash -ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix autoware_static_centerline_generator --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus +ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" mode:="GUI" lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix autoware_static_centerline_generator --share)/test/data/bag_ego_trajectory_turn-right.db3" vehicle_model:=lexus + +# ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" mode:="GUI" lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix autoware_static_centerline_generator --share)/test/data/bag_ego_trajectory_turn-left-right.db3" vehicle_model:=lexus diff --git a/planning/autoware_static_centerline_generator/src/main.cpp b/planning/autoware_static_centerline_generator/src/main.cpp index 9f52f271cd5e5..5afc7e58ba52b 100644 --- a/planning/autoware_static_centerline_generator/src/main.cpp +++ b/planning/autoware_static_centerline_generator/src/main.cpp @@ -25,11 +25,19 @@ int main(int argc, char * argv[]) node_options); // get ros parameter - const bool run_background = node->declare_parameter("run_background"); + const auto mode = node->declare_parameter("mode"); // process - if (!run_background) { - node->run(); + if (mode == "AUTO") { + node->generate_centerline(); + node->validate(); + node->save_map(); + } else if (mode == "GUI") { + node->generate_centerline(); + } else if (mode == "VMB") { + // Do nothing + } else { + throw std::invalid_argument("The `mode` is invalid."); } // NOTE: spin node to keep showing debug path/trajectory in rviz with transient local diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp index c5ecc48ee209d..24ccd7d660edf 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -20,6 +20,7 @@ #include "autoware/universe_utils/ros/parameter.hpp" #include "autoware_static_centerline_generator/msg/points_with_lane_id.hpp" #include "centerline_source/bag_ego_trajectory_based_centerline.hpp" +#include "interpolation/spline_interpolation_points_2d.hpp" #include "lanelet2_extension/utility/message_conversion.hpp" #include "lanelet2_extension/utility/query.hpp" #include "lanelet2_extension/utility/utilities.hpp" @@ -34,7 +35,7 @@ #include #include -#include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/empty.hpp" #include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/int32.hpp" @@ -55,6 +56,10 @@ #include #include +#define RESET_TEXT "\x1B[0m" +#define RED_TEXT "\x1B[31m" +#define BOLD_TEXT "\x1B[1m" + namespace autoware::static_centerline_generator { namespace @@ -115,7 +120,7 @@ geometry_msgs::msg::Pose get_text_pose( const auto & i = vehicle_info; const double x_front = i.front_overhang_m + i.wheel_base_m; - const double y_left = i.wheel_tread_m / 2.0 + i.left_overhang_m + 1.0; + const double y_left = i.wheel_tread_m / 2.0 + i.left_overhang_m + 0.5; return autoware::universe_utils::calcOffsetPose(pose, x_front, y_left, 0.0); } @@ -171,6 +176,32 @@ std::vector resample_trajectory_points( autoware::motion_utils::resampleTrajectory(input_traj, resample_interval); return autoware::motion_utils::convertToTrajectoryPointArray(resampled_input_traj); } + +bool arePointsClose( + const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, const double epsilon) +{ + return std::abs(p1.x - p2.x) < epsilon && std::abs(p1.y - p2.y) < epsilon; +} + +bool areSameDirection( + const double yaw, const geometry_msgs::msg::Point & start_point, + const geometry_msgs::msg::Point & end_point) +{ + return autoware::universe_utils::normalizeRadian( + yaw - std::atan2(end_point.y - start_point.y, end_point.x - start_point.x)) < M_PI_2; +} + +std::vector convertToGeometryPoints(const LineString2d & lanelet_points) +{ + std::vector points; + for (const auto & lanelet_point : lanelet_points) { + geometry_msgs::msg::Point point; + point.x = lanelet_point.x(); + point.y = lanelet_point.y(); + points.push_back(point); + } + return points; +} } // namespace StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( @@ -181,46 +212,53 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( pub_map_bin_ = create_publisher("lanelet2_map_topic", utils::create_transient_local_qos()); pub_whole_centerline_ = - create_publisher("output_whole_centerline", utils::create_transient_local_qos()); + create_publisher("~/output/whole_centerline", utils::create_transient_local_qos()); pub_centerline_ = - create_publisher("output_centerline", utils::create_transient_local_qos()); + create_publisher("~/output/centerline", utils::create_transient_local_qos()); // debug publishers - pub_debug_unsafe_footprints_ = - create_publisher("debug/unsafe_footprints", utils::create_transient_local_qos()); + pub_validation_results_ = + create_publisher("~/validation_results", utils::create_transient_local_qos()); + pub_debug_markers_ = + create_publisher("~/debug/markers", utils::create_transient_local_qos()); + + pub_debug_ego_footprint_bounds_ = create_publisher( + "~/debug/ego_footprint_bounds", utils::create_transient_local_qos()); // subscribers + sub_footprint_margin_for_road_bound_ = create_subscription( + "/static_centerline_generator/road_boundary_lateral_margin", rclcpp::QoS{1}, + [this](const std_msgs::msg::Float32 & msg) { footprint_margin_for_road_bound_ = msg.data; }); sub_traj_start_index_ = create_subscription( - "/centerline_updater_helper/traj_start_index", rclcpp::QoS{1}, + "/static_centerline_generator/traj_start_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - update_centerline_range(msg.data, traj_range_indices_.second); + if (centerline_handler_.update_start_index(msg.data)) { + visualize_selected_centerline(); + } }); sub_traj_end_index_ = create_subscription( - "/centerline_updater_helper/traj_end_index", rclcpp::QoS{1}, + "/static_centerline_generator/traj_end_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - update_centerline_range(traj_range_indices_.first, msg.data); + if (centerline_handler_.update_end_index(msg.data)) { + visualize_selected_centerline(); + } }); - sub_save_map_ = create_subscription( - "/centerline_updater_helper/save_map", rclcpp::QoS{1}, [this](const std_msgs::msg::Bool & msg) { - const auto lanelet2_output_file_path = - autoware::universe_utils::getOrDeclareParameter( - *this, "lanelet2_output_file_path"); - if (!centerline_with_route_ || msg.data) { - const auto & c = *centerline_with_route_; - const auto selected_centerline = std::vector( - c.centerline.begin() + traj_range_indices_.first, - c.centerline.begin() + traj_range_indices_.second + 1); - const auto selected_route_lane_ids = get_route_lane_ids_from_points(selected_centerline); - save_map( - lanelet2_output_file_path, - CenterlineWithRoute{selected_centerline, selected_route_lane_ids}); + sub_save_map_ = create_subscription( + "/static_centerline_generator/save_map", rclcpp::QoS{1}, + [this]([[maybe_unused]] const std_msgs::msg::Empty & msg) { + if (!centerline_handler_.is_valid()) { + return; } + save_map(); }); sub_traj_resample_interval_ = create_subscription( - "/centerline_updater_helper/traj_resample_interval", rclcpp::QoS{1}, + "/static_centerline_generator/traj_resample_interval", rclcpp::QoS{1}, [this]([[maybe_unused]] const std_msgs::msg::Float32 & msg) { // TODO(murooka) }); + sub_validate_ = create_subscription( + "/static_centerline_generator/validate", rclcpp::QoS{1}, + [this]([[maybe_unused]] const std_msgs::msg::Empty & msg) { validate(); }); // services callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -259,43 +297,43 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( }(); } -void StaticCenterlineGeneratorNode::update_centerline_range( - const int traj_start_index, const int traj_end_index) +void StaticCenterlineGeneratorNode::visualize_selected_centerline() { - if (!centerline_with_route_ || traj_range_indices_.second + 1 < traj_start_index) { - return; - } - - traj_range_indices_ = std::make_pair(traj_start_index, traj_end_index); - - const auto & centerline = centerline_with_route_->centerline; - const auto selected_centerline = std::vector( - centerline.begin() + traj_range_indices_.first, - centerline.begin() + traj_range_indices_.second + 1); - + // publish selected centerline + const auto selected_centerline = centerline_handler_.get_selected_centerline(); pub_centerline_->publish( autoware::motion_utils::convertToTrajectory(selected_centerline, create_header(this->now()))); + + // delete markers for validation + pub_validation_results_->publish(utils::create_delete_all_marker_array({}, now())); + pub_debug_markers_->publish(utils::create_delete_all_marker_array( + {"unsafe_footprints", "unsafe_footprints_distance"}, now())); + pub_debug_ego_footprint_bounds_->publish( + utils::create_delete_all_marker_array({"road_bounds"}, now())); } -void StaticCenterlineGeneratorNode::run() +void StaticCenterlineGeneratorNode::generate_centerline() { // declare planning setting parameters const auto lanelet2_input_file_path = declare_parameter("lanelet2_input_file_path"); - const auto lanelet2_output_file_path = - declare_parameter("lanelet2_output_file_path"); // process load_map(lanelet2_input_file_path); - const auto centerline_with_route = generate_centerline_with_route(); - traj_range_indices_ = std::make_pair(0, centerline_with_route.centerline.size() - 1); + const auto whole_centerline_with_route = generate_whole_centerline_with_route(); + centerline_handler_ = CenterlineHandler(whole_centerline_with_route); - evaluate(centerline_with_route.route_lane_ids, centerline_with_route.centerline); - save_map(lanelet2_output_file_path, centerline_with_route); + visualize_selected_centerline(); +} - centerline_with_route_ = centerline_with_route; +void StaticCenterlineGeneratorNode::validate() +{ + const auto selected_centerline = centerline_handler_.get_selected_centerline(); + const auto road_bounds = update_road_boundary(selected_centerline); + + evaluate(); } -CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_route() +CenterlineWithRoute StaticCenterlineGeneratorNode::generate_whole_centerline_with_route() { if (!route_handler_ptr_) { RCLCPP_ERROR(get_logger(), "Route handler is not ready. Return empty trajectory."); @@ -307,14 +345,15 @@ CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_rout if (centerline_source_ == CenterlineSource::OptimizationTrajectoryBase) { const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); const lanelet::Id end_lanelet_id = declare_parameter("end_lanelet_id"); - const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); + const auto route_lane_ids = plan_route_by_lane_ids(start_lanelet_id, end_lanelet_id); const auto optimized_centerline = optimization_trajectory_based_centerline_.generate_centerline_with_optimization( *this, *route_handler_ptr_, route_lane_ids); return CenterlineWithRoute{optimized_centerline, route_lane_ids}; } else if (centerline_source_ == CenterlineSource::BagEgoTrajectoryBase) { const auto bag_centerline = generate_centerline_with_bag(*this); - const auto route_lane_ids = get_route_lane_ids_from_points(bag_centerline); + const auto route_lane_ids = + plan_route(bag_centerline.front().pose, bag_centerline.back().pose); return CenterlineWithRoute{bag_centerline, route_lane_ids}; } throw std::logic_error( @@ -329,30 +368,9 @@ CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_rout pub_whole_centerline_->publish(autoware::motion_utils::convertToTrajectory( centerline_with_route.centerline, create_header(this->now()))); - pub_centerline_->publish(autoware::motion_utils::convertToTrajectory( - centerline_with_route.centerline, create_header(this->now()))); - return centerline_with_route; } -std::vector StaticCenterlineGeneratorNode::get_route_lane_ids_from_points( - const std::vector & points) -{ - const auto start_lanelets = route_handler_ptr_->getRoadLaneletsAtPose(points.front().pose); - const auto end_lanelets = route_handler_ptr_->getRoadLaneletsAtPose(points.back().pose); - if (start_lanelets.empty() || end_lanelets.empty()) { - RCLCPP_ERROR(get_logger(), "Nearest lanelets to the bag's points are not found."); - return std::vector{}; - } - - const lanelet::Id start_lanelet_id = start_lanelets.front().id(); - const lanelet::Id end_lanelet_id = end_lanelets.front().id(); - if (start_lanelet_id == end_lanelet_id) { - return std::vector{start_lanelet_id}; - } - return plan_route(start_lanelet_id, end_lanelet_id); -} - void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_file_path) { // copy the input LL2 map to the temporary file for debugging @@ -426,24 +444,35 @@ void StaticCenterlineGeneratorNode::on_load_map( response->message = "InvalidMapFormat"; } -std::vector StaticCenterlineGeneratorNode::plan_route( +std::vector StaticCenterlineGeneratorNode::plan_route_by_lane_ids( const lanelet::Id start_lanelet_id, const lanelet::Id end_lanelet_id) { - if (!map_bin_ptr_ || !route_handler_ptr_) { + if (!route_handler_ptr_) { RCLCPP_ERROR(get_logger(), "Map or route handler is not ready. Return empty lane ids."); return std::vector{}; } - // calculate check points (= start and goal pose) - const auto check_points = [&]() { - const auto start_center_pose = utils::get_center_pose(*route_handler_ptr_, start_lanelet_id); - const auto end_center_pose = utils::get_center_pose(*route_handler_ptr_, end_lanelet_id); - return std::vector{start_center_pose, end_center_pose}; - }(); - RCLCPP_INFO(get_logger(), "Calculated check points."); + const auto start_center_pose = utils::get_center_pose(*route_handler_ptr_, start_lanelet_id); + const auto end_center_pose = utils::get_center_pose(*route_handler_ptr_, end_lanelet_id); + return plan_route(start_center_pose, end_center_pose); +} + +std::vector StaticCenterlineGeneratorNode::plan_route( + const geometry_msgs::msg::Pose & start_center_pose, + const geometry_msgs::msg::Pose & end_center_pose) +{ + if (!map_bin_ptr_) { + RCLCPP_ERROR(get_logger(), "Map or route handler is not ready. Return empty lane ids."); + return std::vector{}; + } // plan route by the mission_planner package const auto route = [&]() { + // calculate check points + RCLCPP_INFO(get_logger(), "Calculated check points."); + const auto check_points = + std::vector{start_center_pose, end_center_pose}; + // create mission_planner plugin auto plugin_loader = pluginlib::ClassLoader( "autoware_mission_planner", "autoware::mission_planner::PlannerPlugin"); @@ -459,10 +488,16 @@ std::vector StaticCenterlineGeneratorNode::plan_route( return route; }(); - RCLCPP_INFO(get_logger(), "Planned route."); // get lanelets const auto route_lane_ids = get_lane_ids_from_route(route); + + std::string route_lane_ids_str = ""; + for (const lanelet::Id route_lane_id : route_lane_ids) { + route_lane_ids_str += std::to_string(route_lane_id) + ","; + } + RCLCPP_INFO_STREAM(get_logger(), "Planned route. (" << route_lane_ids_str << ")"); + return route_lane_ids; } @@ -479,7 +514,7 @@ void StaticCenterlineGeneratorNode::on_plan_route( const lanelet::Id end_lanelet_id = request->end_lane_id; // plan route - const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); + const auto route_lane_ids = plan_route_by_lane_ids(start_lanelet_id, end_lanelet_id); const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); // extract lane ids @@ -533,8 +568,11 @@ void StaticCenterlineGeneratorNode::on_plan_path( return; } + centerline_handler_ = + CenterlineHandler(CenterlineWithRoute{optimized_traj_points, route_lane_ids}); + // publish unsafe_footprints - evaluate(route_lane_ids, optimized_traj_points); + evaluate(); // create output data auto target_traj_point = optimized_traj_points.cbegin(); @@ -572,16 +610,128 @@ void StaticCenterlineGeneratorNode::on_plan_path( response->message = ""; } -void StaticCenterlineGeneratorNode::evaluate( - const std::vector & route_lane_ids, - const std::vector & optimized_traj_points) +RoadBounds StaticCenterlineGeneratorNode::update_road_boundary( + const std::vector & centerline) +{ + const double max_ego_lon_offset = vehicle_info_.front_overhang_m + vehicle_info_.wheel_base_m; + const double min_ego_lon_offset = -vehicle_info_.rear_overhang_m; + const double max_ego_lat_offset = + vehicle_info_.wheel_tread_m / 2.0 + vehicle_info_.left_overhang_m; + const double ego_lat_offset = max_ego_lat_offset + footprint_margin_for_road_bound_; + + std::vector ego_left_bound; + std::vector ego_right_bound; + for (size_t i = 0; i < centerline.size(); ++i) { + const auto & centerline_point = centerline.at(i).pose; + if (i == 0) { + // Add the first bound point + ego_left_bound.push_back(autoware::universe_utils::calcOffsetPose( + centerline_point, min_ego_lon_offset, ego_lat_offset, 0.0) + .position); + ego_right_bound.push_back(autoware::universe_utils::calcOffsetPose( + centerline_point, min_ego_lon_offset, -ego_lat_offset, 0.0) + .position); + } + + if (i == centerline.size() - 1) { + // Add the last bound point + const auto ego_left_bound_last_point = + autoware::universe_utils::calcOffsetPose( + centerline_point, max_ego_lon_offset, ego_lat_offset, 0.0) + .position; + if (!arePointsClose(ego_left_bound.back(), ego_left_bound_last_point, 1e-6)) { + ego_left_bound.push_back(ego_left_bound_last_point); + } + const auto ego_right_bound_last_point = + autoware::universe_utils::calcOffsetPose( + centerline_point, max_ego_lon_offset, -ego_lat_offset, 0.0) + .position; + if (!arePointsClose(ego_right_bound.back(), ego_right_bound_last_point, 1e-6)) { + ego_right_bound.push_back(ego_right_bound_last_point); + } + } else { + // Calculate new bound point depending on the orientation + const auto & next_centerline_point = centerline.at(i + 1).pose; + const double diff_yaw = autoware::universe_utils::normalizeRadian( + tf2::getYaw(next_centerline_point.orientation) - tf2::getYaw(centerline_point.orientation)); + const auto [ego_left_bound_new_point, ego_right_bound_new_point] = [&]() { + if (0 < diff_yaw) { + return std::make_pair( + autoware::universe_utils::calcOffsetPose(centerline_point, 0.0, ego_lat_offset, 0.0) + .position, + autoware::universe_utils::calcOffsetPose( + centerline_point, max_ego_lon_offset, -ego_lat_offset, 0.0) + .position); + } + return std::make_pair( + autoware::universe_utils::calcOffsetPose( + centerline_point, max_ego_lon_offset, ego_lat_offset, 0.0) + .position, + autoware::universe_utils::calcOffsetPose(centerline_point, 0.0, -ego_lat_offset, 0.0) + .position); + }(); + + // Check if the bound will be longitudinally monotonic. + if (areSameDirection( + tf2::getYaw(centerline_point.orientation), ego_left_bound.back(), + ego_left_bound_new_point)) { + ego_left_bound.push_back(ego_left_bound_new_point); + } + if (areSameDirection( + tf2::getYaw(centerline_point.orientation), ego_right_bound.back(), + ego_right_bound_new_point)) { + ego_right_bound.push_back(ego_right_bound_new_point); + } + } + } + + // Publish marker + MarkerArray ego_footprint_bounds_marker_array; + { + auto left_bound_marker = autoware::universe_utils::createDefaultMarker( + "map", now(), "road_bounds", 0, Marker::LINE_STRIP, + autoware::universe_utils::createMarkerScale(0.05, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(1.0, 0.5, 0.7, 0.8)); + left_bound_marker.lifetime = rclcpp::Duration(0, 0); + for (const auto & ego_left_bound_point : ego_left_bound) { + left_bound_marker.points.push_back(ego_left_bound_point); + } + ego_footprint_bounds_marker_array.markers.push_back(left_bound_marker); + } + { + auto right_bound_marker = autoware::universe_utils::createDefaultMarker( + "map", now(), "road_bounds", 1, Marker::LINE_STRIP, + autoware::universe_utils::createMarkerScale(0.05, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(1.0, 0.5, 0.7, 0.8)); + right_bound_marker.lifetime = rclcpp::Duration(0, 0); + for (const auto & ego_right_bound_point : ego_right_bound) { + right_bound_marker.points.push_back(ego_right_bound_point); + } + ego_footprint_bounds_marker_array.markers.push_back(right_bound_marker); + } + pub_debug_ego_footprint_bounds_->publish(ego_footprint_bounds_marker_array); + + return RoadBounds{ego_left_bound, ego_right_bound}; +} + +void StaticCenterlineGeneratorNode::evaluate() { + std::cerr << std::endl + << "############################################## Validation Results " + "##############################################" + << std::endl; + + const auto & centerline = centerline_handler_.get_selected_centerline(); + const auto & route_lane_ids = centerline_handler_.get_route_lane_ids(); const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); - const auto dist_thresh_vec = autoware::universe_utils::getOrDeclareParameter>( - *this, "marker_color_dist_thresh"); - const auto marker_color_vec = - autoware::universe_utils::getOrDeclareParameter>( - *this, "marker_color"); + + const double dist_thresh_to_road_border = + getRosParameter("validation.dist_threshold_to_road_border"); + const double max_steer_angle_margin = + getRosParameter("validation.max_steer_angle_margin"); + + const auto dist_thresh_vec = getRosParameter>("marker_color_dist_thresh"); + const auto marker_color_vec = getRosParameter>("marker_color"); const auto get_marker_color = [&](const double dist) -> boost::optional> { for (size_t i = 0; i < dist_thresh_vec.size(); ++i) { const double dist_thresh = dist_thresh_vec.at(i); @@ -593,27 +743,34 @@ void StaticCenterlineGeneratorNode::evaluate( }; // create right/left bound - LineString2d right_bound; - LineString2d left_bound; + LineString2d lanelet_right_bound; + LineString2d lanelet_left_bound; for (const auto & lanelet : route_lanelets) { for (const auto & point : lanelet.rightBound()) { - boost::geometry::append(right_bound, Point2d(point.x(), point.y())); + boost::geometry::append(lanelet_right_bound, Point2d(point.x(), point.y())); } for (const auto & point : lanelet.leftBound()) { - boost::geometry::append(left_bound, Point2d(point.x(), point.y())); + boost::geometry::append(lanelet_left_bound, Point2d(point.x(), point.y())); } } + // calculate curvature + SplineInterpolationPoints2d centerline_spline(centerline); + const auto curvature_vec = centerline_spline.getSplineInterpolatedCurvatures(); + const double curvature_threshold = vehicle_info_.calcCurvatureFromSteerAngle( + vehicle_info_.max_steer_angle_rad - max_steer_angle_margin); + // calculate the distance between footprint and right/left bounds MarkerArray marker_array; double min_dist = std::numeric_limits::max(); - for (size_t i = 0; i < optimized_traj_points.size(); ++i) { - const auto & traj_point = optimized_traj_points.at(i); + double max_curvature = std::numeric_limits::min(); + for (size_t i = 0; i < centerline.size(); ++i) { + const auto & traj_point = centerline.at(i); const auto footprint_poly = create_vehicle_footprint(traj_point.pose, vehicle_info_); - const double dist_to_right = boost::geometry::distance(footprint_poly, right_bound); - const double dist_to_left = boost::geometry::distance(footprint_poly, left_bound); + const double dist_to_right = boost::geometry::distance(footprint_poly, lanelet_right_bound); + const double dist_to_left = boost::geometry::distance(footprint_poly, lanelet_left_bound); const double min_dist_to_bound = std::min(dist_to_right, dist_to_left); if (min_dist_to_bound < min_dist) { @@ -622,46 +779,111 @@ void StaticCenterlineGeneratorNode::evaluate( // create marker const auto marker_color_opt = get_marker_color(min_dist_to_bound); + const auto text_pose = get_text_pose(traj_point.pose, vehicle_info_); if (marker_color_opt) { const auto & marker_color = marker_color_opt.get(); // add footprint marker - const auto footprint_marker = - utils::create_footprint_marker(footprint_poly, marker_color, now(), i); - autoware::universe_utils::appendMarkerArray(footprint_marker, &marker_array); + const auto footprint_marker = utils::create_footprint_marker( + footprint_poly, 0.05, marker_color.at(0), marker_color.at(1), marker_color.at(2), 0.7, + now(), i); + marker_array.markers.push_back(footprint_marker); // add text of distance to bounds marker - const auto text_pose = get_text_pose(traj_point.pose, vehicle_info_); - const auto text_marker = - utils::create_distance_text_marker(text_pose, min_dist_to_bound, marker_color, now(), i); - autoware::universe_utils::appendMarkerArray(text_marker, &marker_array); + const auto text_marker = utils::create_text_marker( + "unsafe_footprints_distance", text_pose, min_dist_to_bound, marker_color.at(0), + marker_color.at(1), marker_color.at(2), 0.999, now(), i); + marker_array.markers.push_back(text_marker); + } + + const double curvature = curvature_vec.at(i); + const auto text_marker = + utils::create_text_marker("curvature", text_pose, curvature, 0.05, 0.05, 0.0, 0.9, now(), i); + marker_array.markers.push_back(text_marker); + + if (max_curvature < std::abs(curvature)) { + max_curvature = std::abs(curvature); } } - pub_debug_unsafe_footprints_->publish(marker_array); + // publish left boundary + const auto left_bound = convertToGeometryPoints(lanelet_left_bound); + const auto right_bound = convertToGeometryPoints(lanelet_right_bound); + + marker_array.markers.push_back( + utils::create_points_marker("left_bound", left_bound, 0.05, 0.0, 0.6, 0.8, 0.8, now())); + marker_array.markers.push_back( + utils::create_points_marker("right_bound", right_bound, 0.05, 0.0, 0.6, 0.8, 0.8, now())); + pub_debug_markers_->publish(marker_array); + + // show the validation results + // 1. distance from footprints to road boundaries + const bool are_footprints_inside_lanelets = [&]() { + std::cerr << "1. Footprints inside Lanelets:" << std::endl; + if (dist_thresh_to_road_border < min_dist) { + std::cerr << " The generated centerline is inside the lanelet. (threshold:" + << dist_thresh_to_road_border << " < actual:" << min_dist << ")" << std::endl + << " Passed." << std::endl; + return true; + } + std::cerr << RED_TEXT + << " The generated centerline is outside the lanelet. (actual:" << min_dist + << " <= threshold:" << dist_thresh_to_road_border << ")" << std::endl + << " Failed." << RESET_TEXT << std::endl; + return false; + }(); + // 2. centerline's curvature + const bool is_curvature_low = [&]() { + std::cerr << "2. Curvature:" << std::endl; + if (max_curvature < curvature_threshold) { + std::cerr << " The generated centerline has no high curvature. (actual:" << max_curvature + << " < threshold:" << curvature_threshold << ")" + << " Passed." << std::endl; + return true; + } + std::cerr << RED_TEXT << " The generated centerline has a too high curvature. (threshold:" + << curvature_threshold << " <= actual:" << max_curvature << ")" + << " Failed." << RESET_TEXT << std::endl; + return false; + }(); + // 3. result + std::cerr << std::endl << BOLD_TEXT << "Result:" << RESET_TEXT << std::endl; + if (are_footprints_inside_lanelets && is_curvature_low) { + std::cerr << BOLD_TEXT << " Passed!" << RESET_TEXT << std::endl; + } else { + std::cerr << BOLD_TEXT << RED_TEXT << " Failed!" << RESET_TEXT << std::endl; + } - RCLCPP_INFO(get_logger(), "Minimum distance to road is %f [m]", min_dist); + std::cerr << "###################################################################################" + "#############################" + << std::endl + << std::endl; + RCLCPP_INFO(get_logger(), "Validated the generated centerline."); } -void StaticCenterlineGeneratorNode::save_map( - const std::string & lanelet2_output_file_path, const CenterlineWithRoute & centerline_with_route) +void StaticCenterlineGeneratorNode::save_map() { if (!route_handler_ptr_) { return; } - const auto & c = centerline_with_route; - const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, c.route_lane_ids); + const auto & centerline = centerline_handler_.get_selected_centerline(); + const auto & route_lane_ids = centerline_handler_.get_route_lane_ids(); + + const auto lanelet2_output_file_path = getRosParameter("lanelet2_output_file_path"); + + const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); // update centerline in map - utils::update_centerline(original_map_ptr_, route_lanelets, c.centerline); + utils::update_centerline(original_map_ptr_, route_lanelets, centerline); RCLCPP_INFO(get_logger(), "Updated centerline in map."); // save map with modified center line - std::filesystem::create_directory("/tmp/static_centerline_generator"); // TODO(murooka) + std::filesystem::create_directory("/tmp/autoware_static_centerline_generator"); const auto map_projector = geography_utils::get_lanelet2_projector(*map_projector_info_); lanelet::write(lanelet2_output_file_path, *original_map_ptr_, *map_projector); - RCLCPP_INFO(get_logger(), "Saved map."); + RCLCPP_INFO( + get_logger(), "Saved map in %s", "/tmp/autoware_static_centerline_generator/lanelet2_map.osm"); // copy the output LL2 map to the temporary file for debugging const std::string debug_output_file_dir{"/tmp/autoware_static_centerline_generator/output/"}; diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp index 2f25a064dca2a..42033f7956bfd 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp @@ -15,6 +15,7 @@ #ifndef STATIC_CENTERLINE_GENERATOR_NODE_HPP_ #define STATIC_CENTERLINE_GENERATOR_NODE_HPP_ +#include "autoware/universe_utils/ros/parameter.hpp" #include "autoware_static_centerline_generator/srv/load_map.hpp" #include "autoware_static_centerline_generator/srv/plan_path.hpp" #include "autoware_static_centerline_generator/srv/plan_route.hpp" @@ -23,7 +24,7 @@ #include "rclcpp/rclcpp.hpp" #include "type_alias.hpp" -#include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/empty.hpp" #include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/int32.hpp" #include "tier4_map_msgs/msg/map_projector_info.hpp" @@ -45,12 +46,67 @@ struct CenterlineWithRoute std::vector centerline{}; std::vector route_lane_ids{}; }; +struct CenterlineHandler +{ + CenterlineHandler() = default; + explicit CenterlineHandler(const CenterlineWithRoute & centerline_with_route) + : whole_centerline_with_route(centerline_with_route), + start_index(0), + end_index(centerline_with_route.centerline.size() - 1) + { + } + std::vector get_selected_centerline() const + { + if (!whole_centerline_with_route) { + return std::vector{}; + } + const auto & centerline_begin = whole_centerline_with_route->centerline.begin(); + return std::vector( + centerline_begin + start_index, centerline_begin + end_index + 1); + } + std::vector get_route_lane_ids() const + { + if (!whole_centerline_with_route) { + return std::vector{}; + } + return whole_centerline_with_route->route_lane_ids; + } + bool is_valid() const { return whole_centerline_with_route && start_index < end_index; } + bool update_start_index(const int arg_start_index) + { + if (whole_centerline_with_route && arg_start_index < end_index) { + start_index = arg_start_index; + return true; + } + return false; + } + bool update_end_index(const int arg_end_index) + { + if (whole_centerline_with_route && start_index < arg_end_index) { + end_index = arg_end_index; + return true; + } + return false; + } + + std::optional whole_centerline_with_route{std::nullopt}; + int start_index{}; + int end_index{}; +}; + +struct RoadBounds +{ + std::vector left_bound; + std::vector right_bound; +}; class StaticCenterlineGeneratorNode : public rclcpp::Node { public: explicit StaticCenterlineGeneratorNode(const rclcpp::NodeOptions & node_options); - void run(); + void generate_centerline(); + void validate(); + void save_map(); private: // load map @@ -59,33 +115,41 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node const LoadMap::Request::SharedPtr request, const LoadMap::Response::SharedPtr response); // plan route - std::vector plan_route( + std::vector plan_route_by_lane_ids( const lanelet::Id start_lanelet_id, const lanelet::Id end_lanelet_id); + std::vector plan_route( + const geometry_msgs::msg::Pose & start_center_pose, + const geometry_msgs::msg::Pose & end_center_pose); + void on_plan_route( const PlanRoute::Request::SharedPtr request, const PlanRoute::Response::SharedPtr response); // plan centerline - CenterlineWithRoute generate_centerline_with_route(); + CenterlineWithRoute generate_whole_centerline_with_route(); std::vector get_route_lane_ids_from_points( const std::vector & points); void on_plan_path( const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response); - void update_centerline_range(const int traj_start_index, const int traj_end_index); - void evaluate( - const std::vector & route_lane_ids, - const std::vector & optimized_traj_points); - void save_map( - const std::string & lanelet2_output_file_path, - const CenterlineWithRoute & centerline_with_route); + void visualize_selected_centerline(); + RoadBounds update_road_boundary(const std::vector & centerline); + void evaluate(); + + // parameter + template + T getRosParameter(const std::string & param_name) + { + return autoware::universe_utils::getOrDeclareParameter(*this, param_name); + } lanelet::LaneletMapPtr original_map_ptr_{nullptr}; LaneletMapBin::ConstSharedPtr map_bin_ptr_{nullptr}; std::shared_ptr route_handler_ptr_{nullptr}; std::unique_ptr map_projector_info_{nullptr}; - std::pair traj_range_indices_{0, 0}; - std::optional centerline_with_route_{std::nullopt}; + CenterlineHandler centerline_handler_; + + float footprint_margin_for_road_bound_{0.0}; enum class CenterlineSource { OptimizationTrajectoryBase = 0, @@ -96,15 +160,19 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node // publisher rclcpp::Publisher::SharedPtr pub_map_bin_{nullptr}; - rclcpp::Publisher::SharedPtr pub_debug_unsafe_footprints_{nullptr}; rclcpp::Publisher::SharedPtr pub_whole_centerline_{nullptr}; rclcpp::Publisher::SharedPtr pub_centerline_{nullptr}; + rclcpp::Publisher::SharedPtr pub_validation_results_{nullptr}; + rclcpp::Publisher::SharedPtr pub_debug_ego_footprint_bounds_{nullptr}; + rclcpp::Publisher::SharedPtr pub_debug_markers_{nullptr}; // subscriber rclcpp::Subscription::SharedPtr sub_traj_start_index_; rclcpp::Subscription::SharedPtr sub_traj_end_index_; - rclcpp::Subscription::SharedPtr sub_save_map_; + rclcpp::Subscription::SharedPtr sub_save_map_; + rclcpp::Subscription::SharedPtr sub_validate_; rclcpp::Subscription::SharedPtr sub_traj_resample_interval_; + rclcpp::Subscription::SharedPtr sub_footprint_margin_for_road_bound_; // service rclcpp::Service::SharedPtr srv_load_map_; diff --git a/planning/autoware_static_centerline_generator/src/type_alias.hpp b/planning/autoware_static_centerline_generator/src/type_alias.hpp index c5157acc2b525..2b7b99bfe81be 100644 --- a/planning/autoware_static_centerline_generator/src/type_alias.hpp +++ b/planning/autoware_static_centerline_generator/src/type_alias.hpp @@ -40,6 +40,7 @@ using autoware_planning_msgs::msg::PathPoint; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using tier4_planning_msgs::msg::PathWithLaneId; +using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; } // namespace autoware::static_centerline_generator diff --git a/planning/autoware_static_centerline_generator/src/utils.cpp b/planning/autoware_static_centerline_generator/src/utils.cpp index de362e3af5d7f..1a8e0eae2fbd9 100644 --- a/planning/autoware_static_centerline_generator/src/utils.cpp +++ b/planning/autoware_static_centerline_generator/src/utils.cpp @@ -23,6 +23,7 @@ #include #include +#include namespace autoware::static_centerline_generator { @@ -151,6 +152,7 @@ void update_centerline( auto & lanelet_ref = lanelets_ref.at(lanelet_idx); const lanelet::BasicPoint2d point(traj_pos.x, traj_pos.y); + // TODO(murooka) This does not work with L-crank map. const bool is_inside = lanelet::geometry::inside(lanelet_ref, point); if (is_inside) { const auto center_point = createPoint3d(traj_pos.x, traj_pos.y, traj_pos.z); @@ -181,20 +183,17 @@ void update_centerline( } } -MarkerArray create_footprint_marker( - const LinearRing2d & footprint_poly, const std::array & marker_color, - const rclcpp::Time & now, const size_t idx) +Marker create_footprint_marker( + const LinearRing2d & footprint_poly, const double width, const double r, const double g, + const double b, const double a, const rclcpp::Time & now, const size_t idx) { - const double r = marker_color.at(0); - const double g = marker_color.at(1); - const double b = marker_color.at(2); - auto marker = autoware::universe_utils::createDefaultMarker( "map", rclcpp::Clock().now(), "unsafe_footprints", idx, visualization_msgs::msg::Marker::LINE_STRIP, - autoware::universe_utils::createMarkerScale(0.1, 0.0, 0.0), - autoware::universe_utils::createMarkerColor(r, g, b, 0.999)); + autoware::universe_utils::createMarkerScale(width, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(r, g, b, a)); marker.header.stamp = now; + // TODO(murooka) Ideally, the following is unnecessary for the topic of transient local. marker.lifetime = rclcpp::Duration(0, 0); for (const auto & point : footprint_poly) { @@ -206,38 +205,79 @@ MarkerArray create_footprint_marker( marker.points.push_back(geom_point); } marker.points.push_back(marker.points.front()); - - visualization_msgs::msg::MarkerArray marker_array; - marker_array.markers.push_back(marker); - - return marker_array; + return marker; } -MarkerArray create_distance_text_marker( - const geometry_msgs::msg::Pose & pose, const double dist, - const std::array & marker_color, const rclcpp::Time & now, const size_t idx) +Marker create_text_marker( + const std::string & ns, const geometry_msgs::msg::Pose & pose, const double value, const double r, + const double g, const double b, const double a, const rclcpp::Time & now, const size_t idx) { - const double r = marker_color.at(0); - const double g = marker_color.at(1); - const double b = marker_color.at(2); - auto marker = autoware::universe_utils::createDefaultMarker( - "map", rclcpp::Clock().now(), "unsafe_footprints_distance", idx, - visualization_msgs::msg::Marker::TEXT_VIEW_FACING, + "map", rclcpp::Clock().now(), ns, idx, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, autoware::universe_utils::createMarkerScale(0.5, 0.5, 0.5), - autoware::universe_utils::createMarkerColor(r, g, b, 0.999)); + autoware::universe_utils::createMarkerColor(r, g, b, a)); marker.pose = pose; marker.header.stamp = now; marker.lifetime = rclcpp::Duration(0, 0); std::stringstream ss; - ss << std::setprecision(2) << dist; + ss << std::setprecision(2) << value; marker.text = ss.str(); - visualization_msgs::msg::MarkerArray marker_array; - marker_array.markers.push_back(marker); + return marker; +} + +Marker create_points_marker( + const std::string & ns, const std::vector & points, const double width, + const double r, const double g, const double b, const double a, const rclcpp::Time & now) +{ + auto marker = autoware::universe_utils::createDefaultMarker( + "map", now, ns, 1, Marker::LINE_STRIP, + autoware::universe_utils::createMarkerScale(width, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(r, g, b, a)); + marker.lifetime = rclcpp::Duration(0, 0); + marker.points = points; + return marker; +} + +MarkerArray create_delete_all_marker_array( + const std::vector & ns_vec, const rclcpp::Time & now) +{ + Marker marker; + marker.header.stamp = now; + marker.action = visualization_msgs::msg::Marker::DELETEALL; + + MarkerArray marker_array; + for (const auto & ns : ns_vec) { + marker.ns = ns; + marker_array.markers.push_back(marker); + } return marker_array; } + +std::pair, std::vector> +calcBoundsFromLanelets(const lanelet::ConstLanelets lanelets) +{ + std::vector left_bound; + std::vector right_bound; + for (const auto & lanelet : lanelets) { + for (const auto & lanelet_left_bound_point : lanelet.leftBound()) { + geometry_msgs::msg::Point left_bound_point; + left_bound_point.x = lanelet_left_bound_point.x(); + left_bound_point.y = lanelet_left_bound_point.y(); + left_bound_point.z = lanelet_left_bound_point.z(); + left_bound.push_back(left_bound_point); + } + for (const auto & lanelet_right_bound_point : lanelet.rightBound()) { + geometry_msgs::msg::Point right_bound_point; + right_bound_point.x = lanelet_right_bound_point.x(); + right_bound_point.y = lanelet_right_bound_point.y(); + right_bound_point.z = lanelet_right_bound_point.z(); + right_bound.push_back(right_bound_point); + } + } + return std::make_pair(left_bound, right_bound); +} } // namespace utils } // namespace autoware::static_centerline_generator diff --git a/planning/autoware_static_centerline_generator/src/utils.hpp b/planning/autoware_static_centerline_generator/src/utils.hpp index 70a7e61e19b18..e7fd51b30e658 100644 --- a/planning/autoware_static_centerline_generator/src/utils.hpp +++ b/planning/autoware_static_centerline_generator/src/utils.hpp @@ -22,6 +22,7 @@ #include #include +#include #include namespace autoware::static_centerline_generator @@ -45,13 +46,23 @@ void update_centerline( lanelet::LaneletMapPtr lanelet_map_ptr, const lanelet::ConstLanelets & lanelets, const std::vector & new_centerline); -MarkerArray create_footprint_marker( - const LinearRing2d & footprint_poly, const std::array & marker_color, - const rclcpp::Time & now, const size_t idx); +Marker create_footprint_marker( + const LinearRing2d & footprint_poly, const double width, const double r, const double g, + const double b, const double a, const rclcpp::Time & now, const size_t idx); -MarkerArray create_distance_text_marker( - const geometry_msgs::msg::Pose & pose, const double dist, - const std::array & marker_color, const rclcpp::Time & now, const size_t idx); +Marker create_text_marker( + const std::string & ns, const geometry_msgs::msg::Pose & pose, const double value, const double r, + const double g, const double b, const double a, const rclcpp::Time & now, const size_t idx); + +Marker create_points_marker( + const std::string & ns, const std::vector & points, const double width, + const double r, const double g, const double b, const double a, const rclcpp::Time & now); + +MarkerArray create_delete_all_marker_array( + const std::vector & ns_vec, const rclcpp::Time & now); + +std::pair, std::vector> +calcBoundsFromLanelets(const lanelet::ConstLanelets lanelets); } // namespace utils } // namespace autoware::static_centerline_generator diff --git a/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-left-right.db3 b/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-left-right.db3 new file mode 100644 index 0000000000000000000000000000000000000000..ed3448772b794d73ff3e094907bbf6343b59585b GIT binary patch literal 2740224 zcmeEP2Ygdi7k{1UE>OxIrK~d3LFr(GQZ|JGWfur(^4f-Gv>6>hfxNVc3W$L62?)p* z1Vm6&q(x*12qH^x0*WY06j4#Y@7(uZM#t+*Xo9WW{J!s*zTAX&&-tHo&${QPj7*a2 z$dGikMk&#SL=kle7Z;*WNC-jrPb3J}R|(6@1Kzq@{v=$i-gCT#-{?ASh(CPl;jbhD zUkVHinB;#L-r^Ug0Hy$@0Hy$@0Hy$@0Hy$@0Hy$@z<-+p<2*bYwr}oIAXmxAe4SiL zYIPE2wpcF9hqqcu2C4N-9MwNzbpMdS!~69gA5vyWNb>Ly)3A^*^G6{GDTy5nLGFTv z&6~Rz3Urb*1!)>)`mYE3tD_V8CiOS}NSIs(|IX zmP_HG%pVR<9vw1#Oj1&3%Rg%Rp82B?nM5ZE>6?_?H^g+WgCX2a(6Di17pe#SRP^s^ znX7x5Ct~h#J&#JFBtu5`9}f>U6n+)Rz6>4hA<@hL96jLh2-FVoH+vuUnbNHr?fVaMS1FTvDTjr>aO$(};3U zA$OtaX6QmcgjSkKDkaR-waf!B_rjR}RQOk{d8&aa%j8;}MqTcoLcY06;5`EVhhLZi zm;#srm;#srm;#srm;#srm;#srm;#srm;(PL3V6G@5sfqTN(dDp{~wb6_=PEeDS#<} zDS#<}DS#<}DS#<}DS#<}DS#<}Dexbr04nP57#N6V*gf#?z~2LZ3A`D2E$~X<*MS!T z&jg+fJR0~>;J&~;fja}Y25tyk9r#M%lE4Ll&jcC*X9Vg4)q(OrY2f6*ae*TPhX(c! z6a~fwMg?{WY#-PvuxVg0^TYpP^5Lmr3SbIg3SbIg3SbIg3SbIg3SbIg3SbJxOS%c!L=h557!PcM1FpuC4><|G+!^!W6(1z!bm~z!bm~z!bm~z!bm~z!bm~z!bm~ z`0r4_wf}R0C~n{v7zS5YecoDJFexye{_wvuX*?550Zai* z0Zai*0Zai*0Zai*0Zai*0Zai*fhsBBI?&(E)3xDIW#@aXfBV&EFL=xi**l$1i@Kfl zJ_4EapV&Jcw+k;!@H!25_Of?6ymo!Za=|ZfX90UB?4@_V{#F2G1}9-f36ZXOY$eiUC~Q*gI`=>S^C}M;-Lfv3J_YKK*;5+kCk58hfYp_&3Ila@`7d zl>)|9-?DM8He_U3?Gvqi^}v95WOY`6%7_jvgJbP#z|^a5`{2>)Coyd2DIYT$w^H&vFQUbj1nug8CoG+ zg#GCeDLRQxua(L)T|zRUwW3;65FZlZ6A~gLvvrxwTMem@OVZ>Dxz6;NUSs|{k{&CO zDdZ|L9^Qw9Xh~^&NL*xOR8&l4cvN@#o{GL18{I7?COS4e2JR{3>7+JWqO$Khx$r0| z=rYPYm_ly)TdW`@T2d^72Sc4R?fFqju39b=qt=qBMJGIxloU(Vs$5cqehL1ibcsSs zQklL2B5_>hq*jue3{oX6sFK>IL73Ehq?Y*zh`0%rl3J!#YpSAhKlmIY+9pJg^Y$bL zs)PJ1st%c4lA%&-b#f{EpId(PVR|m&}w)6;%>`EHfmL`6|efGMkiP zF7R+c?CD92$*D|`q|nMajaiYz&?Fny*(zag8O^A$1dT>gfCOr~hkzKDVPdmHuT$qq zG$g&u!@89w$q*~l85wd_hFGbVRmtH|^zbBR^e`Cw_}pcTg#Z4+pYARo63p7H4Dr?3 zByhLt6)Bk=^Z0~*S}d$|H*P|wL1T32KVFsiB(q~Mp?UNbMY@95U^ZpTAe!+SOt-}7 z4RmCu7mo6d!{gKWY0(^+F4iuCiKvWsX7UEALUe!AAWUi=NF)E>m-vSWDDrppeZ?o- z`;3>=^Pb0a_qwjL;P!w0Ma^s|AaX{U3L$Mn*zYfdIDl-h`%+=RwXy)B6{8wou-0AhqW zl`aMfH3~$sXUb`%Y7Ly&S4CVu$!d5C8jTkSn-+)ye*uwPxh0e?kt@VnNjgc}LRCg+ z2f)x27>U*jbit;O4WE1H3==l6W=nT<#%sd)Kv>%XjcmHC{&7 zHUc6`5>zx)D9J;Kc5vO&)8TYUg*+ouN1M7T5(4sCo!In=R-OTgc$2#!uFR_g2OIrJ z3O$nB#}0=T6DQ!c z{zJ;R;;|_(GzE?9&kn>(24BtA;1-@l!UW_((jYHKc}qIJj7~{FV-u`mfV4iLvYHEs z9_9$IDY6CeTR7Ah70Q@?Tnr~ILy=u>gk|wzgIhz*W4Sqp*LtSdPS;F843?Xm8B=ls zN?5>^fht6Cx&-AeswO%!bO1flwAACEd6hwPUDHa*4)Jj~mK>@}_{pBa4#i}*J<>%f znt*OGm-kpK%Zip~1>J&ELslilwna*k8+#HWQ(%z^_Cbb@uAE}L^D0z1Q_KUyP0?JG zATkn-1jJ;s<8R8on$`%$dKE%RF`Qekp#L4qzffs?MItj4{TrjmY$z|n3x+NEf0z2m z|L^Aaov+mUrkC3DPmkx^eO>3l?WgiZBPr?3po`3*kT+DqIuF$TWS1P$|)5 zL4B26tGC1n&Do-1^oMu_wIv2@U-Zd z=^df+qM$N0&$6K+&P^Yf*VP0mthum7LzT#wdl>V!V!i_x=E2w3)BFFbzSR?1#4(5Ya*uNQMnR zuuB!R2Qo5cbTz3~C$p&azG}6C+fKx}CnonaupPt!#+jqTCU+fW{1}&=Su`sKhuL^8 zC=MpqWF*>x|DR#CoP{Q8-Fu3`zy^MizP!}FtMrQ&N*ur~px>})7=P^=@LPH8tBUVAo2U0<# zP_5Tx>vfEOF2?>jZ#x0ol&CQ@7B~_|XFgej3>9s=Y| zrwSRuo{;l;lH^1~NqU)Bi#Ai9t`ozyZn+E=794Sbgu1N_X>3$Z?Ynsqd4`tOzJJ*y z5~=}IX=$q*7H$>vv0%gO5dBSOcV3thPL+*Ct$E7inMRv`Zy57){ZP=J+rY;~1auLB zF(67n=*t9xO?CcACyANH7?1;z>NOf@_G7+b)kL8}(564zV#yRdpqp!`H7Hew8N!pK zqa=~A7htHhDR!L5e?-i3N`}C1}k-23)yRRpk=n|A!I*Qon<~9lW0t z{Ng#n{is_HmmNeXn}ANK z5-_OH4x~&HrDfAR49XE5LBC$hh zo9rw?3K~NP_CUR%mZ-KJSD8p%4gUam!t+1`P zO#UB*gsPEUeoB@nqw7EcQCKD*RDu3-tvFq-fC@1&>=cmaB2%2*`zY2(@|+p{c}kc- zO&WucdKWF$Jy`c(-Gg-xcD#^zSuu33ki($_ zaI%9|8y|x5%$C2!3P|k1?jWbN|G=vGu~f5to(1+Q=;{doahhBKM{mT3JS8b*EM1Q! zUH^{R4E}#zte@rSq&8b(S8CI;T;b&lukIKgzU{}J8%?|2qixUg_x;i~CDAMpQ)5C`>$=dyjUZHR3{xs3O0buRee z-^*KxiA=PPi&f^$9nj|6?N(}kTb8=NlG|Id#Y zNCdp#AL+Z-r<2!iuLRG}J(Asjb{p&R8GK;d%P5!tJs#cY9*+vO6b@mSPFMa3^*Xsi zDAho>hBS3P+e3!4!83P5N8G2@=03Hq;|0VFyBHxYkSgR-d=MYBrE^du%-CQYh(lc| z>S~sYjxsuy%wEm!n9Qqrpck?Q6{E8&y(vi#Zq;yL?f4|q+|xER+2hR zfu#Z42>6w8FeuSHrrMo;o|4+MDPui}oD?{^wjx*99Ok>OU zxOJ0tvst6Z7y+RMz7MVPUvL_m@v6_ZFwGb(Ad;b{5I-L(7cX9c!jxtxos%MflY03? zN<~UEAYkHLbv~(J&hA43M%xHtg**!?!86rrnQcNw=|%|%NirXE<>)|D9n!HXy|U6@ z9<0(?3ol2TM$Bo3(?JR}N{0IA9@+tOiCphAn>EY+L-Bk*=pSl+{ zLM9-hBZ7*C39}_qrCKIT*Qk|ZsYE4C(`(Uxpvk9Jh&p`^&`6Zr-G!sWvE9Jh;)A3D zqLUCQOqQge9Mcq}tjt*gs9){ltH-CMQEh6PfQX^p8kUq&wK7|+LWeMGvUSY8C<{d4 zuw~}cQQ109;znYivOt|65fDN+W_hRysA(EW7Fj7}QwrcD8YPf*fI=<7wB;@Cp(afg z5Tb+%v{kBga6SuQR~%IVy~EIFK;kG2T@9bzG)c@u-bhaJMq={vlXnUac_TQ<8-dBo zOWyI58O3Y15E#V^$3IjcE2DT5m9nZ8FER);5LGg7zJ5wKV^isq1Vkbn?qFWi;OKg> zmR`Ns^VHGSS7hm0*$oK_1w&_af`(p8YB7d+F+3r)obf>Wtk`&PK=~OpequTOz|a=! zhblIf+7``X{C{^MV6*=a-#b1_y(0u?J!g2daw`G<-~H)u|EWo8@cFIne)^P2INATd4r+ND>_@2unQYs)JW|)?=Nj6cD{CMXp4jUpabN@+Ro>aZtd9 z0x4>o0@fbukc&1`o?dyl#T*oX#3CnlakwR(1@G7_hO%a>pP_7}N`W?5K_yg0S*#UU z!cLq9Q9@9-W}BZOET>99fX4d3HiLC?shL<-1%C=FhS=~J z+cT^aG8z1u6$6|x$e#RNsdB&;gYC2(mjS2f4z|(_nQD!ya!bJ!;;u3^gO@YYa+aE2 zE;o}&N@NOoMkY2Es=q;x8biXF8zW-r8W^BLClq=tTH0@{9HP z)_b~F2hWc^ly2)?K8KrSU&amvP}JN>O*?X=MoMO*;yR%^Z5k;Bh?7!v1}go6TQU-k z-KF126?$;?kUJ-oLbhBZfnq-yESF62Gy7ewM6XllL4lwcy%A@df7_DC>_`71DNCmR zG460AHUSwE&^RRDi=e#eZ2%T}R*P41r6hwy714;@sH!rJu2^R|DI?SL8AA9}3JrZx zn`cgJ>Jq`YsHyyKprsDXdAnnB7{Z!kG&Er=4bR}%t?jX|B4sxCxe-Cn`kHDG!6UN2 z`WX8`j330+Qw$epvvQ35e{bR#5zx=?1)uZYT?Ml|PP(^nRl==W_A<6KxI%oQp< z$Qi)63C?63PHQ;aN{pKhOzZ!+TCs}6FxHgLZe2_J|1QBqz!<-czKy*L1qVF^?pdw} z;nvgpGIlcf0-}X>xjorxxe9h*!-d{Bpq7i-;s;#p;N(U)#?}TOU{}k>XO}P+I#$YP zBOgb9oEH6QWbg(yc~^r?*b#M>BN}J$0^VfUWq6g*ctUJ6|7%8bv_SyO6FZrC*l>2Z z;oQjJX}3l+1rgFn=%7fl{bO+jrNepSZSW8fO1l;-ygWH;dFo_v2SFKXmxjX&(!aJK zwKuo{yAmDFF1!ReTFo)_|0EHh@w@Ds;(frYo98-@V7DTd-wD!T0RW@FAsAZ6(rq0r zk?yLi(KTwhwi|m=fLX)?VvAVH&%6yW$cPrE3ikDak?;t`3(!)fAC=W)a% z5{rj(#3S%=#3KTWhttF(;Bmww0*i-p#KZq_#3LMwhttHv?{UN<9E*n&#DmHIzsdOj z(cZ;gE}jPWOKv?}-gKDvkAKL46fg=5Ed)fClD`6xE{;cy7i^A7kEZuO;2sM$9t2}- zWoQmj&KMh_oMv7q^$MMwt$#P~H^IFVoLI5j+|Ue|BywGykSwu9Hq!K;X$Xsp#DipNw(=gS-hw?aZw2~ zGy;D0cRauF`r_#I1#*uKAIJZX#{R$4{Qm}zQ;AMk>{3!{P1);tUNKX|Qe!>1tZ3Lampvo%Pfe$KXZX ziHmw`Lpxwqj|z)=MK;*ZD!iUMd_8Y$XbWs=Ux7_&TAc)XV~Mq7h7!(0WHxiqCw69N z)OwW+8^&6(vv-pjgAHwfIW4Qn94s{smzpp`YhX+z9!q6XQ*q@HtMxjCoP@@`as~AB zWo={J?$s&PM{NwDz^h)i36ZV5!ZPJ>nQCBY1$=5{8=s^ab+$N7osT8x2`oeP3?aao z#?|2rmKTT1OI<@th{V{Fy3|OZS-dbE8phike8x%4XnW3DVe2=y|nYponAskeUcUHN)31oWH)8$e)=72u;!|G53XbeDVR1$^IG(;=U zfIlr=>nzzXOC}4@jD9YK9*PrMHYK#`8-&0a58FAz9$|p_q9w&njIVSybOpXtNOGCT zUQuGeWYTK$B#JClDPbj5B%CUtl)%~W*bQ+ezZx650Ke+WZPsv1BcJZT71QxA5O~SR z6r!C&+`)TR#U&wyIZ7?ZO3o%F7i8#+lw9?ggV_Q$t|JflFg7uC0=5KIhb?4&HXN{n zg~kcnx>^}J0(aV$--lXub+JCk%B0bx3OL?T4u%*LRW^NrwcvPl8#do;Z-8%%F?0YX zjjT44OgtlHP*)}cn?WO&sLC7Pm~{?3-pCkk2m{t7I+Ar#@c*&6InOGm_y4B|Bs8pz?K3k&8M8|T-P}ew8NFN;x z>3p(WA0BqN#h)Jm-^1Mrc)Al%d4@OvF*&si#ieRB1W3?PX^^qf>9uC9K>Ll19@prk z7E&jgzK}wX$9{z^eg!q%5Gx?0Jfv5tfeGsDY}Duy%1*&3A~oH_nEK&S-RUD3RJ2bK z8{I7?#;#y2)MCd72sID&=|Cd<3#dF#4Cy~OVin$D9z;e)MLFQ0;ao#^0g-A44>08& zM)_!d%4ewI(C2Klu#y@~c?VHG-_T7!h`h#PHIR94G3jSpF%MX7C18HLKPYk z!Dp(H@@9&oQy#%|B*oH9i7Ep}YaHS*sSJH9kB?cPZ)Sj5eWN#w8IOVpN^OQ#2p1ua zkJ+$go6;B(V9RzTkher6AxNgtnfxS7bw>mS)P_C+BBg4o!|{7!ZKgb3he_@TlII#k zm9MH6pj)YPu?E$UV9Gm!@_IvWhzL{(c5BKjNDO(0*yB`=p%?h2RTADh1cuS>2(;%K zdh+QRY`r^UuM=4BJu0`}EgIfzJYwtJ@ikG5|L;KrJnvu6_kTWZy>x?KB~=oQ+~TGP=@n0=fm4>@<1{i;k}Fqh%wCMu z9aJ5_<|x=2WiyDY(XuKs9I}fVIMhRuCRfOH1@R&1ykArsV){E0{Y^?_5Vj=k!HPnj zPHLeafqmb}{kP5+ftdL)uuhnsVZaooB!hh;X3z42^6*@_MhE@D#85-7s0Q8fsmkoB z%I=0F=-k2-w^l`V^I?i?t%gaYtXM-k`|NLwWyY&DOr-{{kKw70fii)i5JP8nH&($1 z+%3d;b#tJChS;Kl7#=9;hJ;uJMOL>$20~whD-V5Hf{i%z<>;Nel-e+;^3azR)p6*{ zp=pg=!@$a2QVYpJ^_wyoIP?`C66crpD?en$tApa*bGNI!9^tFpL1<%W|U9PHN+&;2*{F-!$0=$!}! zomvOETxk78Vk|fX3&uo)7t>h;vggd`TLo5P z5p;kE4lqmr5p;2)$!X0ul&i-Q=o|@*GK>caOm*VwSDuqt0IM&6jQ>BH2p9tW|Brfm z36ebKL;k-mG1@-=-+Ht$&L9UUWH<*3P<}5-gLA$R8ni;}i8#0*#Ms@C3Cxo`5$0iY z)`6XbjJ*sQz&Z7k;GDH8rgz<9U0i)#Z0u=B2L>viGy{=Ug!$(H{>2(d;2-%U_=hWT z9Nf9TmqGTVlqas^uxq0soxv5uSukRiM2WU3N}=jqt;&T%Ucr;mnsSl-3{qfV;gb+P zoKtq*#wug9Ar1J5Hg`HFs%*Uu zHul5Wd{A7VPEXg8Y_CuAre$+;vLt3yGCk<=HxTV~3T(sC9mnho zHg+{Afomh3$2A<&ad1p0%Ajzrdc=_&XQ;<`Ll&@2?mR&=`~Bs1c~rxn#Crlvakx%~ zX~4aqPk?)vUDc1;F#dl!s{c3o9Q5{q{Qm;CbFNK@bVvI9&=g<>fWl!-0ig4oS_&QT z$~D=u9M@3|XyC{YyW1|tFdcX%b&4Qccjm)>yuS8 zZ_e2cS%z=euXm2&ng{H2j^WD5KJ4E+$iMGy$OY~>r|_)|_pqPuU_ZZyLH}gbCieH8 zp*H&(bilp>=Np>X?{{L|MwCGdTy#$Te;M^@=3+IRJRGiJ!!^kN_aZ(c0%Cn7-rEJ& zJcaI3*Y$9tw!VzXlpE|Q3UbtrB92glX(dpn!43o|Y)3!`qT{Va&e>YjgK`Dcg6g6j zQdwjVORJ${a3F~dBn_fmKq5VyEs>;-l%k4I`gm$Aip~+mZWJsRbakdvMX?Mou?$wb zZ$7kknGJk%SZfy!6>2`F9E+cG#7}6L1#CpEU7RU?W;SBUtG477rx*$ujrpv=5oOU_ zlBZTE6T8}c^XU?jDF>roV>)Jw%+_TxCvM>*xU{6PpJ67zy3ol+oh74- zR}`nLC`|sp8`}TB)aRJjLqUQ^j@urWpNMYU0RUqJk)K!=t1pX# zDFN`VK;m59(dQMx;c#?tQm2umr^}`6HdgcT?b)P83LXY>;LQ6CM>9iH$z zJ|%|&8wXIHpjaK&N{++Pwq_SPu%WX=-9 z^2gVJBa(6lt~qS~zYX$-m%wT-fsFsJBm!dmp7lBJ9Vi&@vB~XPQ*0JgL1S$wvSMIp@ z$3NVWLoeq^6j^za0&EgF$0X`P)dMDubejAz=hU-ItcKL#q8C=`qNuvSFti27ISP|u zn8}+|$TKpl)58(7jb&RRRR`GS>^cclEGSmURX8Z;q@bLT3IsMfyH3K)MyxQa?T8pV zQUSm+v~S#*3Nu@x%f#HOKDYW){=lu-PR?RjrGT+v=@i3~@&AVt0SSIHd`i6j7Q}nZ zay#hiNeq7+FW=aWY5}l7%{!eV#AV#X>RYSWM`X>Oc&a(@4Q)Jr0(^6n(Tcgpa<4np z47m4%!fK8%dNAi$&c#wqfpgAF9+%OVR;y_>Od!lVmUq3VCcwL#C!;eRSc!uf$TCnw zH3kOip9}*XTEKx>$g(hwY6L7q9XFnU-C~{k#|pIiK4f32Auw;olVM(^8+I`ltIx$A zR0H6m^ET&}F=1qm+8Bs6D5F6c{~z}MPxL$H+uB1=$+4l+aG{&8 z%4K|7aRhu}9E?wbgRTc-JB0TDNIxnB*yKB=`fRd=GkB%qTd6{+mcWlrc9|Cy#ineX z8*})dnLl{fRCrW(C{YgyQNjMQ_>kD>ZZR>@vEear&$cy*@&7*|0tWg$@AHv2AsFqk z#_d;EIq}Kk4)RH*aBGIgFMMTGh2cs|Bb9e|Ja6~l2Zb=HX=vst1w@e$_|9DD>vG!=%_ zD4**^hrVRckO)G{Li>1UPfQxSW%l_0K13Q3kl}aH=SRr@-}F?t-*QvC+=QDBc^N&a zcmbg-8$C4}qUjQpA<_yfEzdE>c_cDPwp^SWVM!T{WlsPcK!2Z3*y4yBPehKIO~nZa zF&`(&l-OVvIMm#vrc<#3Vhj%p%$+MR^&Lz78B~mb7{^0>OZN#(e#er3Ce>X)Oejl! zt&Su$DACNU1VZZ~+bZav!hQ|wf7@gI)J!Uxm;Tm=(_#8M7XSHFH=sXXC=bWvoDh>+ zQ!^i94lBZZH)A@qw0n@c}j@V0I5JsaZISL86k9 zVkjU)(utasAG!E+xqw2RPHM9ycBx*492f*jiLam|Mzi;AOdFl{pqXq{@F|I`HM%E z+fS}axQSmCDL}K!u$Zmy#<7XM+cer3o%91mY07 zB5s(q$0b+lg&74JwKz>K(PofpC8^UCSe)9i^roCBzAk$ej&pcgecEx zN~H*hs4~U|y%d5LA!U{B9qp@DD=>L&B(Ihl1=UR4xr^>5|45RDlNRy(TPSTLJ4ubK z(lP3e9V3T0MiAy2QKkPMZNfLs&Dm3;Y%|Q0tAu$phPgvvj{JXbq7xCY)j!F1uTML{ z9QSi>gIxB&t@1CU7nKG*96abA4yJUq0?skf2o+?yPDpogg3>*OoYa6Dq(J?pnbRAj z1yThZS%Z%fa@aCp^rs}ii$E@3$iNj+Yv@A_rD_c-AAr&Ud`OV<0+vQ^YAP^9@E8oi z(t$RpII<&jaeGS4XsTxg=E52)O$GfGv&CuZ{IXigo(8k{&@)>b%-}thRqm-Q4yC3* zo2rx`dytAXhNCqGMroBOHP)pjgF7oSwY zo1U%R7rS}F4g7K<1&n^wG*I3Cm8_@GbyibFCEORe;J3;cPNe4BcF_ zNS)UFw|Uzw+I5abq)4ISP^Re;l1b;@U>_~*Qj*!aOn6(N<=0bMpbVam6xOfGJRhDU zGWL9&;rTHB{~{vbMc?b*y}|!);r^l<;j+ky&M*GyDkwlHC=DD@R*5>&$TKo^LbLwC z`p6;mFW_zFaCw_F!MUqiutIW%LIQ6yo6FneVF{9KrJ8X!$4(qm+!Ysu+!-fvz4TryKGRgjkLk&xWFAP}8A;sDR!MTAtoe)TPs?6%|Qt`oJ8LOn^|O1_-W7WWIvQZ{x0` zX;cC1I;tf20w<2*&v_Doc_e$-qIECmnS0qV&Lz%62~T@B_<+qh+JG9i?N`RE3ZW;zi|NEDqH>BUFz) z*(yER;#QPaK+LEl;KB`5tS=m`FEB`}1S#_WeThqO{-3{_?<+p7y>lO7+=L15_|jBgdf*I2*A_;2C|59>AF94q*&tM|f2A znwJ~>jqbpXR@G#OBo_{^fCDQqL#oS=P@|hC5fm5XFVv;$(jzTuX7qqzaQp{zzz3CY zbcH5dW31wZOqf=zgblc;=Z7>~U*^3YeUoW^M&?6@7L`OHmSoEsI?W-o)t393{W%M)F0T-enq)!J!vXm|Z zu+`Ouwt?Atolu_*-ZmU}C&@$JwN@vyNY?;`TB3`J9Hv+3Y?2x#0t%#gM}t0vbw<#qrm6~dbQ=MXSo=tny3)S~b)g%Te43FY}H#kI(3B^g#@HeAzHF1WQM?r6a)T4a{g-4e3Zv z*OKV4XVV!r*b1g&D=ND5(0VV0jZ3{V9u1~I#k@>lDtsXLm)7cQO zIie`hK)EgUNz`(gn9tvbG?M_hQQb5Xk_j1^i_=WiwybFX-z9_yDD=DPtMLBKYmp$t zW3_vG*9~wJzX+p?v5A0~ptaT>S~_na)af-Uq!{GT|5mNhRvII$5ThCmUm9%w&L}b) zLg+Y>!4t`#W*HkpQv^CfYjT-cCO`<5q$|bqGD)c8VD2(5R|VRquw%!eq2Llj@&~Rs zPHThSrgX+e5F;-Wv?$L3=I^pGa!wv#VDWG-bqaSikyVeQLI`F7TzH&{`9j3b5sBRaM2= zWi!TFeMSZ(!^*_U&}pvNwc>HDkpJ)M-;D^E2N(Rp6u=a~6u=a~6u=a~6u=a~6u=a~ z6u=ZHLjh`pu^Dp^-C$uJnTFzIrg~?{2d1mbc%dmel%B$VD32cs38tnT2`1F?Pb$|H z*p^^L$1$MMI3{UROcMG39xhu5|4^TPf^_$J@D{&nBn667Jv<2)&*$4DH$18g37@)h z8{t9_kFIn`@BLn;|JdF;QnST*YDJp`*S|(X45=cYffC~wXsN4oa%0c zZef?E-A(Ae(yx&(7rLYVntTS#N z*`|547erk;vlO8lnmL$tcbC6@j5eWr{s-5+xzK&)f%GSYZl!-a8r^{&mjo99-6VPN z^6OiQN+-_h;MU+!VQKgWT|B=7bd&E9*@FSyf2B^z)n5~fTvM;UJ~N9O-9J5gS9)?u zXo(9uZtG9=do22a8{K`vRzI8ge$7MoEp{ILd7iJ`oL`q36YUIkmX0G#JqBYK893NBSQ!p*vvsE-x;0Pw0H+7D9L5c9*rt zGO2SrDt<*l$Pg~>F>yFPm7h1A}9XB`d^GlQ7 zOR8nJCh!IC7^dbE#f{Twm3=kwE82#P zezDt;?wY7R<6Nf23roR6DiUwG|5;(_sbJNauV9tExuNxgk+8~+ib-(@PZ9{rnp*y-w%qvcJ$mrF%zf4+M-^g6%)|L3-N@AsCyUF*@E8`96Fd2H*g92ma{`Tt&4=#IMm zd!7m1!mi&2a-n>LxE;!tN!XrR;tFdm+4m?v> z`bLRoe}wL=`_If94d@{%^_y5~34%_nZK0mr=d@ERx zzI$D**WHSoU*_8~54YA+zT8-}6#M^NCT)$oUz{3frH6WsDgDxDDa>-IEtw%|+-|F9?nf0d)WHevdCV>@6z&epmd#NuL&$zW(!bUm$cp z%-A&)p<7*=b2{30s%XIO>rpqBaihEU8&~qri&~ZRWycxwC(PXM&%Mh2{8@|47NVMm z?gVxo_jsOf(Qr+D%~AXP|BP1adNv5)kFpcref4wp1Fu?dL(Z9G+dM|Rwfw`STagXv zZ-wr-Yuigr=vK`*9n6L9l6l{LfY9wD`%#b3UGI_GcPMt-?C>a;PWy^Vk2jWf&jcIt zliiDhz6Nx!SCo8&Vz*zNSMG1^HC6Q4qgQ^6TFi~^ZWCVjxbl5S$w_uxKuF3nJG{8j zeKGC+?N=|>t8ua0Sau%Y@;u+APWivx4zgc&d;4A$o#@M7yLEQ7^zyQ+WUWW{2wj>@ z^Z2KY=*RJNb&H=Bx?^|#*58Eg=U-n{p9|fm)_!^lp<6ZaH0>ej2VVGN450g6W0!6Z zN{UL~xwPh!O^}%gSifx;LU(q%Ns$QMVL_>H%nzC>620)}qwI~`=>8${?wxuaTb1-; z$6fyBYRcs%+~_`BID7fYb~R6TUuWlWoagxx7w!)IP+~v2Pw#iRdfcBsc1t|?B>yYl zO))jjFt+!B-uc0{c}zY&Dw4KLe67$OLruP5LU-po>L4z3H*R@~Mt6RSedum~cFBaF zT*RW6Z*-owV>NelYv70O}3-VcjPN8kIn z`0B@nrA>m*^f?QwY+lP{>!-ph`^7VZ*C~^xh&*2ZUHsc4c`4Vdhko=+zhAG^D{*1R z9m(1A(-*6_b4cHI?y>XhdLA{-hBVFNCeQOd7aunDh{}FFv^?VSh^0mwa!3lZ6&jY%9X~!&@4Cp?*vSJ|KeW3o!T18N+)+p+U#$@6@F_G@-r*u{Qy-})dkcFrFD zC_C|^`}q4Qb!xqbL=5$^X&&(}pTE9rFY^EES)p6>?QyvY-5GCv+>{I5AHF~2cjO`E z95}5(=x+Af*hv=v-NS`9vyOoO-y+=Of9sAFmVWWms^ANN?%&srNSg@gUNe8)nRh;% zBKluQ^bcz@xY6CTm4Am7w?jνVt})$~97fLnKq>nRNLzOQ-ye=~L-B+v7`eO=J| z)8Fk!_j8?c3%Y*EkM5c0S3R6i@0nVU?i0J#+cb|EXOI4~%eWNKUDpcTy>|%xOz4jO zdPNg1bU)}Kq@!Djg?H)bR&vn_*QwHG5}(?o4eesx9@miDf#D!W?ulh#Y23W zj01Fkv%+_eZu=BbhgnyTbr{Qy?t(Ol>%NaeOIowzF1j6P(dia9x`QN5!WP}Dc^T3f z>^vItJl|~T>T`!8>__(}=UNJ1F68%+=1lJTX0v&7YdyN>wCQfsJnk$yv@YURq`T`_ zp}W`Y2Ukt#UKy6&mFz5NSLY+$?O$>##RZ~UyDz7%6unnex_15_Q{I7n zw+nX56eu$hdVO&}RJ-+ScHt}WtHh$$?rtByrZabR>*kQ|MQO#MB`eu+Ug;+f&Dh3m znWU}i_P2CP%|rLk>^w4gp6}XsH+#5!Xg|7FUH{;@@3Z)$TX%XU2lstdSL^NWbGorM z&0|dJ3%cUxu>a5H*VerI#i@<0^w6NlS$j=-$j`G?8!kQc=Z1ktkRF=<{3?2tofx%d z@rSU=UTr??*Q1AvO5gwV%*h0*UuZX?bkyy zH!W%UeQ*9%cKr1or(bV&rq=5rO&HL-)t*JluJn z@4@}(-wwWIKf0HVSnZYP!@tTBYa?2Jzy8Zwk8UEji*54=K4I)c=a3p&p}YT?WLFcq z1)c|5aiP22g?oJwx_|IHuR=DY@-UTv(0!xfx3N187L_iZEJzOmbVD8Ao-=^%qPlZO zNC4ddn|zNQ957Y%+YiB`R=F!UW48}J(Y$qb>e*huvg5va{l4LC6?ca8=SW{N=e@%< z4&Arec{JyFzD>VeoH#{mKe`J)YQ1ET>oNY?t>yKvPW?bq>pdjG!?t<6+kD8SxOGT( zH?Tr?zZEeBCUg(jN`-Ktd+x)SrGV~x2@wk4({4wo&1aYJL>VUraTkqf7r(?&h4LY{v;tXzd zpSk~;;N9XMYn)~B6FU#@zp8$|Kemkwo88C${Qv%TUmW<%{WveW3qAk-dDg?6TCckw zEqi3sJSMHYs$5izqFcdM=uT8E9cx0j%d*s#Tb`vPuNsH$F6=x`^E}_@L899a zyV|e2=bqX=DDx`6W%9J4`_#A1?@nKU{r{R~sdGP1acT=IJv2OS(*TnmdNVtuBbOfP z-s$R51M-lz<{Qx}dqQ^Y)g`dX4*zA{H&ej>@Ak>FuRQ|)-|dTY8L0o?&?8fB42MxJAN(uRNHi|So&R?>_ex2dtdRsIfc59v%pa4?$Hsc{+7jqE%w z@;qO3uU19xme{X{Mm=g2zUc~o4(UqF+U=ivUa9q~Y{$Lh-?U{OZ~g7_AZ`&_Wt&@} zdzkN;-%aSg9daX#3*GZS8~O)A_npi~a}c`a%|H1Z?IB$s`upoQ0Nv;7{utU4a!9@& z?@mWi_IJ+uwnz2^vs&JYTamw;THXQis)AP`su8J`)GeLg?-`ms+w7(4GBJ zP~wY6ib_{5-rZsVp!@B8eP^Hy>1_4Kv&R6smyzsJ2)-{&808&a{fPH6lK z0VTh&{)F}IPx7(Im?b<2%ZO8%l zdP^EK7*p&0|KkVlr`a+O&6^t6A74P|Zfb?@A!|p@Frhna@`84p=>F&a6ol?6Lq^U( z=w5gErH_#R?>aK;`q+<)O8X8fDb@qJFE5ywiK<&f56=8P9?+e9>Oi|RgIJ_|{;N6d zg1L2fo!R~y&bRd}nZ}OuU*-1YcgwiZ9i{$o?!kBdtZ^PvJ$4?$c%IMO`0eY(`SzoG z)*CAmXWFteQM`0bnD$)lum2Ygw{0FT{;(mhuQzv^&i=m3*8&{e7A_s zySe<2&i@yA9N&h}y=?#HX{$hY?`*YW^#icG|K2iT=;wg$vHgl}quQ-T^TMUS{V5i8 zU$sB7$sBHUzkO=Wg~Ks_?(4>m+jnW)H^=|rMz^H@jn*?gZ`3$+zsJsF3D5IQO}IGg z_i+2s?fys3TR}cH>`dG}%Rf9Rqt;s{bEd`GG>KwNoS`>Ct{`twSB?H)T^_xw-)~X+O zl)c@ZuT}}eTh%xlaxpuP4m{5{wrN15tC#&zcDFS@zaJTMl;5*D7Suhd?RW3iR216$ zTmemOn#aPwnp~($ci9QGLiea&rxlrONJafiUAfR5ar9CeLiZmJAI(GP&fD?8clIv@s%T94>D=T!5{NOVW6S~*SHh1Ad_n5Rj zN`&qSgETa{M>Rcs@GzkJJkM=yz7qa*I zl}6t7qx+LNKP+j##|9g+%l1a!bsb#m(M_B`VADKSj7c_bd<*&iAy()fvG~Fo6S}|F z7k1`C_r7M&7a(*ePW${Bq`QYTB-R@N-OHb?7c~=Vx1u{vx_BHsq*2TN3Ah62e!fB1 z!-D|bKA{uuH)=3d6t|@9w0=9d(Ot*C?XAEL?Mk|{;|@KXld!iHH@f?_xUss!`;BTG zy6ds?7{v2@^=I_^?!gHA(e3xuS7Rm&ky1(eVeswR3vbVYN#<5AFsiJ*<-RvRw zn_CZgpMN;^z?$%qci3_3{{H1r1Co1{ojPy!rB4@x*0@zxz|KR=^L%$?`pFl^H{kc< z%Q5hOA=~~qm3Wf(d&7U6@&1eA{912A?*0A+o96Lmi|)M^99jjdY^yRKo^M}}Amr90`&Ze~O&7F%w>7{2A4aWy{Z^r>)}x!avd5-*95_^*_yg_#x3fa` zxKrJhn9%+5oIO!o=svt>bvi=#sE2NJ?Dm@#N&D+U>~>Sr(Tyh_Eh-&#>rt=y+Y3vR z6;nP&)h(`n?C6WCTW0L~zH_JJQ$&aME500{<3_hf_?sto{~caZ%8qL(d2XSrfE(Sz zG6PD6-mQ7)c4Oy}#PfWsFT8PW>3sWhNWnRi+cdpugAG~qT-MG9np%(UIg+I|&13D3 zZJQF;BM+&q6}rd1c>cBt-KSri9?6C7UAI<@L+I}G*Cra>zaQLktuvszp5~jqo{*WC z-nj8{-Oj?&+5T(SpvuHPJ?fuEm5JvJRPNaWQ$*LK=Qb`^aHHF0^yrJ%j)a$7VaFY- zKQJeP;70erM!)u&{a(#OH^I(h5YO{%CNB5*{FwddKAmSIPk8d9dy(h8pSQc5s`co; zI+nO&%RC13{-E2Za}c`QSfP8&sJ#tM=$7s36TyXU-E+SrBXp;=|Aj{Pui+ij;{n~f zo7VsI^ogRCaTHXy;QW6%N3F*GS)AI%N)JtKoG}IIp?|J)NY6Z)MsVq& z24k}Fksk7Rxhd@-QQ37b4FEl)Ty<5k7+#GyEZ0wdDGl3CCk`xw@aG5F?1}q9$KdV$Mu3bq{jLGud?%a zndkX}_Z+$)njOsR$CrnZJZNUVFqVInB~}@m{Z)T_tzTt{&x2doGLIt7yZs;171Eup z&^_hy=Fd#4YzOs;crJ8*J!y0yLicOO@6pk%sD-`yqYmlE{C2s#4Lzj4SQgzbZ$n|} zjO$Bf$p8N|{@EPVLrSy$bImzIEZQdDo&LWK+~|%?oVWBsaRf z_qW|QV{^?zcN9AhFP`Uf6~xbd>!AJUCfeVd{lY{3RrYp!(c3#F9IEx`UNtc99b4wH z^>&HRhbxc`*~tpslXo`oHlcf?Y-Jo5y4RmBrVzS2JUULJ`<(Gi*H(b;ADf=|*>itU z>4>#obcxznSo-Uh;j>WecK6AV7g6l?SHC%z=iHhia&I{;vF=iCbPrsxYma<#*OCV< zm~o0*E9S(J?5^@ zuKgYo(c&xH=CQ5cVdnh5j#lWNRIsP93Ef|fNsr}1_p0vx^ANiI6tB|ge);Z7qX(c{ zHMht4rO=u9f7b)<*4b28TDNh}g{c02M{oBeR3W{-{mrw7CQTKsefYwluyF4E|2g}T z{|F2gmMmw-MeM$I>6NA2nThO+Fa4T2uI5!HD%g3bd7f{#V%!H?KDS?YFKv_(v#%w8 z?3RdKHSe{%6W%Xx+0?qf=WVxX9!Y+w4^m%4y1RoFx>Ni595)>`_qPd0Qvuxv^6v|Onk*5; zDZ>7|@IYD0McqA7%a^^=F}x jAZL>$$lRGdS(iQNlJsjeKgJ|Nk~SkC8mj_x`yY zZ`YSva?X#7PVth}6DGX*8SnSr_-*7$smMl9h7M-s?IkZ^^xeHO~Lv#LnXvp6AOyGs>@Zu>Ce<+p*qtN+0p}kaFAf>T?aH z#kF1!DZ&aC+A@z+Idmwe_y0#&p#eKv3to@n0%Z``#Epen@(;A0vDLW5$p64rC;vN(_(taC~C^2@t z{5Ag$>3|8UJ~ulrul492^+wOWw#;Mx%BG*LUWshTa4U36*F`op>F(G%f4Fg>Tl7=^ z?FikCmN%hmNOyK^6u$w`-RQNuz7fzNePWNrFFXh6Zsu8MBFd1?-Kg|NC#1Ezw@2{% z@+qP^-hGcW9?FgG_ms!FCcoXWM8J;QEZDf}h0EON_USIY-TOrI8i(#(rg`u@-}M^> z7hA2dAKlj{b{>0G!ynxu8fy**w0yJHqnkMO>=B#h5jSpQD|&~t&*@aQ`axzQcpJml!D4?C9xv*R9|I68i(f!i{fBHQuY2;Z6)-HK-C zF`4K2Vqaa9KTu^qx|25jFYSK|_&XC3Tc*6bY-`Wj@BgqpPm9c;hdeNC)8-E|8;x z_QI(8C31FLALVDh30JsnNX@S2y9aOctZ_EvDs~@$Vs>lRT|y!Y3}ZewCebey&aP$m$k!`4(Lv9c_hf`Jz;V3Ej_!T=nKc z_fOM`e?jObUYtv#d%^4`y@mq1w+E?R=70@ZH)B`FkHACHpL#^skj5zyP(_p3>D zzZmW>7PSald3)ho-00qSNxNss7mZ6AvEvfwZT|T|FK%?dRr27okc)mb4&86D^Vr1m ze663En%Ute`_Ucdvv|RvUi`INJ-Yq*`SJ78T958so10#+WgZuHd9OUW1bIl^tk9jQ zK1`X=?XE5L;zDNUH_BoEl_uh z@vp~>Lg<$I%~uVhE1sT=qBziv~3=5-niM4woIa| z(4Eoi*SjWkYs2RXxX>+$Tz?Otd+DJOG`c(Y{HM?NfbK8O`o8lqod0+3<}3G)uPrQ1 zSkh6A&@K6D(+#x$f5D}R_h0duD!Mr$e%%|Zxbtq`?>YKYY`xHutL(S~_fmT9smop6 zvc6N?LBEbQZ~y-{>^#=+JfCXI)=jVXw;$b!kvGHq|F)sJR=?(e@= z>us6G!jD>J_<-)l_5Zbn!^NpRt@MzFIB>?Khu-{WSUoO1H29OYden#XrBw^3Bme)| z1&tLSfd8-mLNmQ7)R6ufI(}^u)R5-v3XMTsb~Z=-^f&4u^?8?ukB$hYil$B6J-6cu zZaow?HfeUxIrsLF?6?bE8{Tgez^#XV_xK@d+{0@%t`BJgb{=PVp6~k;Q~Px3ZoeK{ zIBre+mr48{(qEVI-NJvnQtSQyJumBRnn!Mv(2;ETC(Go#`V6m=^nR-^!8mt->wNY@06YT>^#=- zJl{KYIt@-}+T90mGlE}7s>@N;n23>ZFQ{%1Bt$y*x zUM6(kns6zQ3*CjgdbB|3?zlU2HbS?{=^^hO1$3{QwQurLK)3F0zn{hfx>N4V`WQvG ze9r%$y*m%5s%swyeoBTUWoSYfGewcgY|B_kQc{^^D$0-{m6=GWOi2+DQbb6Jvx_LA zl%WifxsnWpkov9d+2_5^Kf8T=ulM_V&iP)w|2?(d+;`Wfd#!t|z1NoTMLMLde4)FD z?=7Iut~&Ap$FX&bMgJB*8nK)>fR20L(Q>n`4_kMxa@Y-euZ2|C|MQ`F+{B5Gsp+R~ z!RPt+|6hs@%zkObKSL4}6m_V%Xh-uM(x)f}it<<*#}T~K7rEV1o=o@g1A{>%-IDs5 ztXR6APUn3=IwYULin$Ic_>L-DBhY=eb5V~H&>fR1Qu_$(-5zJ%LXYU)IHT8$?A;n( zy3=GiU;%9z+`KWy6I*wGiO<5Y2W&(sbe!zXOM0h=uywbXOJ5qOq@z0BZD<~^aN=9z zReYLVYyP^wXFqD&?uTEy{b#d}a)gZ+)5>}oGtOV@94W~o-~V;Nt2kt3B1fkCn8@%Y zlJ1F(XO?2=_IQ;$r#pf9>AZB;R@mORXfTJKG4jRA`C;$fM(yz~D@$W1R-ofT#`D_i zmSOAeowX}9sa-^Mx`WU>T5;mrIyyK1jzm)eM3hZdikNK<;SRE669dR@^x*m2^^-?vGWE@1w3sO^Vv zpgaryENgByGGTojfgVrS7t?G=cuyh~0 zZ`p_FPI9qwM|2ltYG&O9x-In-#%_TV((N_^ANUJ>V6CSH5Bq@bGX?5B>Ol8$hdl{47hj7Ic!LJjOPZ{__nfh)lPKkEZ}h_XOSR6{ zIk9xVG#Do$x{DO=dm_4rq<$zC0^JJg@JC;8GEp_ScFh9t{=Z0AepnCCU6u9rt~Suk zCczYZL)Q|zrpoX`d~1NO={~Wp zEdL9t z)4l59KY3K(#Anm<;Wk_Q{A>3)%`+L-i}26g{Iy$a&vkp!{>sFvlcGF`c0zXsz?+GG z&;S3o>-T@_&kr%tBCA6_eZI`3S@wn8)^%8QsPnaC0aAzDeIL)wvMu=;FOGvcRCJSW zu^H(9GspQ7=n8z`rmvUtkPgZ7_BT!qP=}U>_A+aPSU_CfooYMzvFp&0yJGjOV|i6p zqT_@u9*s+-V0TDbtFryhC9_f88qyWbV<%30&lR~(?L9XCI&|@rI^*PX{5nLK%=KCM z;{U)G(#^m5Qj*7Bo#~B=_mMTECYkOt#ryvAgmmNiX&x-yd+WA5M|A7{PMYhG3UB&n zoCLautIm(V2k-xj40q<$6#2la+AR*q?v@hE$9iOUt5w~O+u6VZYA^UP_IMO~mwnr< z;LAgT{3HGE^D&2!q*+u z=x}Sv<^weUlwEXV`fW<`(3t2K*gN-ybPY1yr+sQ0Nwr&lRSh?mZj+x&I}zPK?f%)_ z8vmRo9s+a+YcJla19U&IpT18I_HK(8dEJCqL+d;JI=2nh>m-INl_Hi#nvtVJY78tkp5qdOt<%{8XJ=CSUtNnSh@wy@23v}y1i|V zxFNe+W+xsqA4Zj_|?*l(DRyl$^WjC29 z7JxiMdauATYKGksiqv6wy!0M+9s2gX@vCPIm&!SGoVM|$%=|xmW%qY%$U%-i>O23R zLGxG`_viRp_dy~JZ1b-}rIvOhTgvgDAtiJuiZyho9!>yYUV zOfIS>=|0jtEP$o^dPv0F`TqmAy16xE=`I_>N}zk~^gzl(@C@nE>S4NCaQ-iALhL}E z|1VctE`@w$hsjlLpBJ4a56OQ=Y$WgID|M+R`alLw;{&JZYsz^STLPjTGf^ea#s2 z!@1hMgG{&oj!P9J-G?ed`LJ}aX6d+&=nk>3@j^PJth@J`?11hqva9`HfRhOo4d&}t z@_b+kr**%Pr(49ouF*rDZb=-je@hSEOx*Eeh4<2H*t%IH)w=gjuTjxJ$7M}T4+;O_ z&BRlSMcBK4vQS;^=0x-G!-?;x++L=lYxCFrZp)cIn{@mqqyvYuHXiw+OY@>TA{`RjJM9pqra zOTm+gMDfzHDNCByO<*=CqbQG#ZJ)*de*f=(yJ`O~{`ny$24r>UTn(cTsSYtS@`z*A zq3Ea8?#L{A!%<`I{eSN7i+QxbEZcu-?QW?&aE27#BXJtMWj8ds^9r(te5?QX8}b~| z$9GCC+NaH-zIPU;DO<4XkZ+LV``5$VDj(2sS!0cl5?)~6|M&Z1sP8@r>Z?N`Xdd*J z{v4l~bEL397stHs|NAJ@a&WeXg8Tn&xUH4C!1v(42F`1;hP3E&GmhQIkMR|yB?bx=tr&}rxRt#SOx|6n4bEOu6cSzk=F58;z19yBp zQG)dUUw&;2N8bN;jAh#+$7}(;tC2o(t`J+d>hBesKDF?vG@|2dn_isRp@KcjvVD8& zn^nh7b+fEGng=INd{TKC`xGC{U$-dNhMa?P_~-wGc<;xLb{EqAEPJw#qCE6m)2sL0 zLe`M_WV%Cbgat{uSqqCruyk+p+&qftR(DxDx4RXe<@cEp>~2MuipeboZ?~9!Ene~+ zbV!gAXF2k9i}e+SQpgw5<6=Gx76ILbr^BxC)MfRhUT#YC%%FMmm_Ac&VLO_$NuxccrbqdzeUP`d8$!~=KFtUt5}Ni&>NNI zH*iOGw|0@~KD))km884HEmRmw_h{LK9C9)NRTG?%{{Macsfc8t+visH?>z8@G^Xvz z(Tl*-Egfswa*+G~HLi#B8UWqw+>0YU4x*kjS;nO#G5#7^oJY5joZ&{d&P66HS+}fWb%Y$Kw zg7Z6H75l(4Crap$+O6%$R)*AWUPZCvFSc4jQn}F9^bu^`-tSwDD<#&cNTB1cw}(F| zIf#8S0X66swlyuMy4oFp=CK_ozJ?>O-&}by|Ju!7^eCCt9sj#q4u?IL!y$DvulsCf z7DaiS3#$%gjsAQ8|G(25{ZD>sh=~zd9lG$u_#UYa1wUq!!m2~lQ;}`5_u14w@r>9Qim#BkHxNYGK0j-x#Wmy zM_{ao*Hm!xdcJt4EQpSC)EwO7GvPLvZ0a*Yf+^UC9ppbH>CHG>5hu>_aNyGc-p=ZOSh0n z_)0{#=-G-n-L>qaub%_m)(cXC`P_ry;K>!tl`TH-#=fBnWOwV8+{^&d|3@w4+ATb8 z22DQs*=A`Zv)|SjZ=5?J-AkrB(oFX(Nq4lv zZAmQM@A~aI5Z(4sLvy-~PJ3$90NtylMPpq8gJJcXH8aM~ePH3m*{_fj(ycxvzR2CJ zwyUhe0$-Xz_QxzG&L?8)K36HZ;pi$l6>D^y;9_&}o!hZ>NAP>Z1n(NBI^8j79#?VV z`~B!boqNRmJESKpF|T5}@O2yP*{h*)U|3s<+3PiUGm)pc>=W{4;sJr# z4lSTNz)LW1L6I4>;qEtg{~&DLVQUBOMqXl75kbf8$@B5Zm%!HTTY9;Nk#zypbx5&j z9w9jK)v`QUF!px-wL4+=qrUV|{M{|WnUk)vskt<-o1lD&qC6bbc4NF6%$Wq*wxm}QfP%K7_# z1i{R{@#W`F`ofZ|R?m=K_D!~%tFhP%9htd*c%!5_fi4N$v z+m|*mZ%oCmLt}TvZd@>-zI#Zoqj`MBi7)Af%-NQ~`OmV)LbfJd+KT^{-R9fD{zYd> zXnr5^>qDPlO7bY#Yy8q899csiB-0%m6{kzmt-P^m3zqJyF+b=DumrFeVQt>M8|O`N3E<;!miyXTg9vWh^=xk+1kFt%=WJFU#aE4#{$q2mndn7cdv(EpzrA;g5UHBg;yJ~R&qC%$0ib;l!X=C7M8 z^qmh~F9jzPKTgg%x^AX<-GoznDa+%;hm9NNo=n_Nru*U-rHv%rr{1VYW9cTomE)P) z-D>ul+q>Of-Cte>bU$x;ZY*F1-n%6h$ybbn=We$Pzd@c%%$wvwXM{#;|VdbAge=H zZwxgfb%@X-W+#zlO2Dc^uNj$M_=8zC^=?))vW6Udx9Ob%s6!cA&vSLsg5cx=&gkTR zU--&4iPZ?^(@1-9eaO*X zt!PT}SU(i^4)-~J4Rd~b>GF6RHxe?&EpbIe47Z%H4ih+Uw0#2)2Ux=_#G0#Sv~c9V*<_V zCiKN0p(Ky*EhnNI3y}`Vj7;|xb#XvoHUiOoVaaj^C7^q! zoc5=sbwTj{HSB&o`Mz-5_SpnPx4HgctvS%my#Eg0>Nazzm$ND1djz)bAG!Bd=QHyY zyU=mI(7lFbT-drB47XilT*N_jx+l>*>T%+0VhOD>**AaP*^6|9WXABxgOSIJxGW#U0tMtiaQ|Ag3)%0h=FRHr)#&Eq0Y ze5xIvEhpB_U-v8N(EU~Y_|I+;R8HGoWznGdlLu zh=~nZ9ZJo7d>g4lNdKR|_z(kD9kLkrk30kFkb|n#D`b}Ky`*|O%~?iOIPqd>v0)Ib zqkF`TYrh}7rQPa&J(y)}cm<5Tz%1Jnc>UlNV{<5>#^-hVYV0~xCLdDE-|9k)L&sGK zsB5|8W7naUlcI5V>a3}*4iV8jT5;kldKLbnkh-<6({cLut(6&D5}XmCI^EaMJn-VX=MdoFdvE@_ckf}}e6*Z`+by(jSk~Xx zqx}<7?IeowSRTdKBangAZYwg~$t-!>NV=biRxQNR&AXKE1)|$$>{$w;drI{48amMb z8;x337P|+*dxc&f{UqcEJF2by-2!y4_c`Td2Xx2xD~w&pHHUT{eIrb;!`3ZQ8NayY z$tI#UI_`ItrpdqrcI{5>C~qt)=BGN{>(M;$;(NsHwlIHY{<_UAu!HHFtL_vhE(Jj#_}F+x{%)Rpews?}}_3qPr<_ zjVp5Q<{$VZ^ksAq+%Ns(O4*Dr?0bs-LmSY&Nl8P=8t6V4B2&|S#sad7+TVY69rpYG zk}OE3|mQHB%W5eK7-0vG20{QuG$-mH|2O_WAtp!2>QH9fW+l=r3zhF+ z!Ky>hx!a~5pbiD^h~6d*>JYSdiT7u)hOFXRqxMZC2>xW+uk$$G5AI~VBJKj}P;a;R z51uU_pp;!7=?fVwArbqJacN($bSO(cygIX`=LiVgc765rs?@5-i0R9A;o z(LDTc;GTw{PTZ;zM^S}TNUlsA-gh) z@_2L5aCUhob|>jR`+e;aEZyHf?_%--y4wm9*CDzs_e&5Pfo{hK+np~- z2f>fuHl;9!`N6tr=M6)E?urKjxj(=xo6>Hf|FG8r>dW{2s_cWU8_NvF z*#ze;8pWPvhuwpp=%~k2o$kkI9(eIFw(*}HapQnEu4LV2^u_Pz54}ja8>VapN1vdp z)p5bUWvBM7ARj?Tk>=Ns52UIn%0t#DhSBak@^p(mneLlf)6OK_3^^YcW9jx4(g`~W zbjL=lSd8e_4M-yv1KkR5>;*n51;O_+S`zX+{a_x#(WXS8+s|lSX#>#xbnE(}15Yg= z^=N_eDGO}fvLYW(T|Rk@sEUr8^^09p*^I5b#dK#~LR1Iqn@U%J*3w*2`PLN&?JpJYP_7hU8ajqquP!&FdyKlu(q%cR_;)jTcDmwj zHW5B|{*QD>jx~3guyk{re7yV=(CsF*>KoD_`O9&cUjVvC&aRm{p%VmKvMc0ISoy(b zp(<=eKzDia(%cN7n?YK8D7wZ1a?>p`GqT0jopYgh)2%Df#N+5V){*L(*fwn4Z?vB2 zJbN5Wb-HuWJn-Vn3r`Wbeu@K%=(Fdi z`IU)l5i3P`u!@c8tPezLw=J3O8?D;Xq}u)HMIyq!<9k_|w;kCb%~dwnCj?7yb$|ZRbMb}9KA675 zw_5rp1^xd_t3uM69W<|-u;>#-dDPoxe6I&L6aDS~|BYV$fATX!OpcS)p`5UNVWc|5 zxfNo^szXa(4XZeUI;0@F=sB{6>_{(sy$kF^-eBWZ{{A}<{-OA?)41Lb-ll)GbtR}n zgWTM5_d)-!=yG*g{A&y7<&3NU!(-U9Y{u1Pam7QAiKKB~p7+LF?!lgATW&ndH|)Ac zb#;i82VQ(G8GgbtitNy=u;swYm9KH@P#rh@2{$=AI7Guf+kzQ?zkqNsBYDZ;H#A>| z{AC9y%0qUS)3c1Z8`6%E>ArI)_7_RFR|zW{mTnQ@D<_Wu-Q!%dnTT#KNnS@~pnJ!g zlo%pI5FGZ<^$FpbA8g4Z>$wH!_9{MdB?#zNlF6-na@PV{{cFmFcQ>}~9d8;n_*Ke? zq;V$p&LxYVW9y!6`~g4J&!alsI%pnv@m<;z*}Wm09jZ!G65b(MkE?sZjp)b&mkeON zT7JRH5dJJ1ywrX$xK@VdJ0#BKxfJCwd*ji|E0IWtIH=Q1qaTWlDT zoPq8!Zjp0{?v1K>Mj}A>+MvwujjTbiQtuS8`jH=e@#~8(5YTP3p`pV!4|a#%raImBXdaF@@i}+u7{l%C zP|JE=t7*1ZxVj}ajT~=|Gk~q#9&J-xg8%$KA?2#~mMfApubW`NPgx#}_wWAmbc-XI z?px#e7fHHZJhNG`bTc}|&8A-e0AmWVR}-5*zESNpCGf+Lo9Ewst?gI|tR zZq^67>$b@#7z5oq%0BMs+G`2*r7FaCOE|$;YpIG;PIc3ng~WbzTzuy@&9o@&lZndB z7e9G3XHuPRQXWrn;@eoPG@X{q4ka*XYyHf4fvbDZR_`T;w;Y7~u4*j5xd?ynmO#{C z3$|9L`IQO5-h-k%l(xM6xpVI6mZN04vtD!*k#svd_%6lLeUvxl!3m(d&u^_hqPt6a zAJ+`n-73>BvCQWUg14V|_u4$o4`yN5{QeNoUHJC8*LI+Lxb8yhgoGt@qHRx7Q$Kd? z{wdM@+mV<@bVtWk6w|d;?8er;s627vQqB#k(>;skffwJV>~_Yt;AA4-#-?t}3;!Ig zH=TZlADp}8JTMH*X2Ac~a7U)f=*oVW=5?n>Z`)5v9*IPSQU<@j_y1$f9@O{iAtoot z>QF&Y?juqi(%&Sz8mkWZ)=G<6f;u#^`=tG5P=`VUo28K((sI6DO@}@N!Y{7~E##W; zgNwd*zsrsvgz~u*6`i+!fCQ~htP#3x0X=12^eR^myAC~bHN1b}Rvobd9XIe$E9Yw! z_8PMAK)i(JxyMvjhpNy#@Zy{P6&5+E&kiX>^&Ci+ZNi;pCCmka=}Ii&zFK4~Cr^F;<{6P@)=P@=xNL4HJNK5I8=3BVyYE?$bZ=TizY0tDvd%~&YoPlH ztK1Gm_w$TL`Bp&pF3lw&O#OlIz_E~TCfu|FOZRqSv%3w@{Zp_|4AH%e;TiK`p!;e^c~9q;K-k0QeXH(AKiEkeJSz=! zr{#u4N&?*~QZ2z(z%!&WSBp8t2Qse0OjPw(i46&vUqRLrh%Abl)BN?n2V7U6Rg;rMt%Q!b>}#`#`{FMntz~JMT9{_sL?pM3(VD zIHOI&!?@EAUc+s(s~_l=KH0x@G0^?iw6V=_vn4bdbp5mF7`ARNz1K2Fo>daZ&~cpl zuQRd^VRuNma=u)iJ0DP;Zc-k2@!k7TFzP1>_HG~Vw>)_B4X$oO34W0)Etc?R?%wG$ zBNRN{GU6pG+ighm9TMTiFhzMp+_KCl$VO_nGnww(Ql$ct?w9LNaA4_vZU14}5um$t z?8E@l|I=^!u6YRPww_L-6PON!&uVbKF?#0*OGbFBOaa|{f|*}^1pR;KDz`hvEI@Z* zbH$S!Y~8o@TY8drRS?I}aqTxpCxq8x>y9Z2kD&`KqB`BAJn-W4eVA5I4Bl=Di9L0+ z@E-oTo7GQP=}J$7RV}Z`vAq31`hRyn?o*39d^FZ#eNP+qN;h{Bc~>!GdeD; zdiUVsZtUlf?3b^ZxY+fK>go_F4+ot1z86Fd#oS_prUfoFYps2UJImU&HE?e%Is`Ms zyqXfEWDU7GT-;FP|G*d0er=~LkJldyH_fdfy~uPw&}P_0((S50%Y&u6wIPzh80cPO zZ}%BlLpEF%k<0_S>rM4)%i9Ct0-u~;9z%Yx#Dn5UU1SaUA^a;F(5*(iSaea`0;;PR z?rUtt*8NT7t|xWr6m0*5trhZHDqD9X{eit2QKNAn26iSOgH`VAM3ut8N- zv5ajJZ*g@S_R(42wzh+nGuL{_e4=0t88L2KJMi-1zgR~9J3qQAm7+XKoK#&OW+7`x zPcq%btif(1-69rM+*rD&9^6qo2y_SDcC0~kuS)FpyasfuWtI|`wgtlXrB>5_9P@)y z?B$YA0Nqtf-WS$^4oUjVazX3G7LZtsq-Sj@w(cbdPYfT;dP5XN$8nweqEoMht$X=$ ztsm*NPpM8fDGxTB_@3@JXY<|44h3mxZ~2_ojH|nJfs&Z~)E+q9z&B&74E`E2eDu~x zQiOKNe}~w=_otLrAEqb|6=LSBOAzvevCZw)}mF30YLZ3?>ucqKzCuEeBrk-b4cf`49DRt zY~63Rx@a5ieofqoj+?o+bFI`CY~8HWb=zh2DyU93DG$8(T;5&3(&femy<7NGphz8G zH~SI6i-wC0VOx*E7M>aWXSWD8&Cidk>(ab#f_xA~d0cvGDx8*#)NXe&-Gw>VdP%xt zp4hCx(yfv8m0%8ZOJ4Lni|D=)mlkXebn`4-O1}%#?xasSj$Si<@BxiWX3;=*=M$yX zSAgy_9-SQO?H16pFGlAVcw_hf#O>i#9Ln`X(zp;;=cM7U*t*A}hpmda%BfCw8JY)P ze5G%9G>C(niKT7p3{Tv{KX=no2&|qdwS=EMWB+8c0blp?`oel!CqbIuyA8VRNKqck zPU`ba2mXEj|KFQs=lhdGOnk`d5bQkipEsnX3WS8P>d>slD$5<94o$j-lp_8A_#y?5 zVNi$IM@z@Aw+6zjUl^D@!7M93_O>!RZV(b*cTP)C_5;LOlei<6$r2g}+kd<%8@mpz z&^h{{Vb6PFFFNj{N3`-vUhI8Hqj1IEI-`23t3xZ%Joe+n7rT?~w{Si?bkO#BdxU!{ z?i%vmeNMNDH5PEq$}fB;DY#|l=!eIKM&s2q-yv;*iz&+EGhyY%nqXv>Jwv9OsP^hG zX_obsm=VCz{ozpjPaU9pZ}j5Jh;A)ugRKKVcTWA&w1uGmS3O>LAnBVQ4EZx}f`RVP zH}6vkK=)A4f~U4)7SP*OLn6~r*t$KYzb(3z+eU0c$Js9#Tbn?St$T%5ZR*;VmsF?Q z6U}24PJ9AtJ0_>UvqScg3~ha!_`17Ob)-cFE#T8O3%*-F#h+yfT>bPrLSNIoZo5EEK=(G&2^U1S?NCEZ8_<2`-JOBV z_kl2jh>_X7FMe?1>Py)TK=;wgja~1-?$!yTw5`Lf7SQ?y*85Zcu!cO%bFN%eyphI?G|Uchn^IQ)={1AGiV;ZIPob927WLFC#1dYQ?FY+T5xN(nnc{=)(R)s zKKNJdP71!=vU-{$*DX(n<~t;%ayp9g5GZ+SB0u+r^eHmkkKU;mk#z5Cj^xAAU3pD& zhXK%iKyI-vqT7P2zOn}B))-Yzj_wSE1GV-`MD+T>t{tO7Q$Y7g6>)`Rp!=|7K)?cU zcZ<*ai*LLGuxmHF-22@P74L|oac53n-52r$yFFS}_PyW65a@nFxF`2|w{pGjCMz^uV&yXfqK%=z}Ef5-oS_!|f@30O#0g(|Iu-;=7)r;OF& zSXIc${b{2Ds6wIEcYL>iIo7|&^|+j?jH-9JywGG_Agr^j#`p9he>mycw^lVU$8z)d zdpCmqh+VB!Xm2BUKAO44h}{Ewj@>@C=f3O1ZlV}EPDZ^l%<~T`ND1 z;XU<%@Ns@Rl_WZUcvs`7ZS~1G|$^VhO#_r?axK0Wg<(+00J5B@~Pw)67O4@1tM6ydH1f} zp$d3=RwPLwyt$2t<0}Af^K%Ej8aD>Qn{M7)6T8qK&U;&N`Y_;KkP><08sPoOz|P_K z4GSp2KZHl;dYB7UX>O}tklQ52hHOsPJF87;cS`5 z*rBD#uHt7|@OfY83IC>g$Q};b?ZRJA!M9sZUf~$ByRJ|3{eM^qCq;R5De>g6%-!AM zN2dG9n@#UXx)WW`3uEc#{4w}b4d@sXBFt`3}eJO%oHw+5F4=XZhd!ESyRa8>%bb#b_RSIPqx)_*I-MWQP(Rp&!~MZMbWbLH)f1IU{>m>77oj2R8+8w_NXQ zRJD9f`~AOr7iD>jS%&k@J(=iBru%V%vm8lx3culcEZvDWraImFXdXs5@#((!bf?{!9a0PDPDvZVKbg1+ zEl&}1HG%gPdtDrQO2NHbEe-ay+pTDRX+mIsMNuAtRfglQ?~?len}ntO%xa8>7X>f4 z`TwDt{re;4_cs96kBnqB=*6LhS4cHT@%C~ltQw>zy8D#`s6po6W3;z|8Wg~jx{epD zAGa+qPLO#N2zysOS;7z2k6H_6CE8*Kp_~|RowITuAfCJ1XD_N-g0H3dz?>_wZ`e7z zP4%Krem^l69k*JkoMBT4b`832@~~e?vxVwvP&k?gUVO2P+K;cWvO|ksoeDm=s1tXF z9gupQId1O&%S8%W)Y4OM!_F_>gz3zMG{1f%Y~!aa4{qykDXDYq5d#_T8WH~8B;G5! zJ2ztSZannx_9npl=IcxA5Zm6_{XG-CG>0O>;&C3_7poX_Kb!8b06_1I_|)}jkAW1*u1;s_V@VOzoRRj z@hQjF1P^qvLvq2E?7sdTxV-6KLv2 z@u4Zz;d7f?^klrBPl}F^cwf@JC5gpb)YbRYX25$!)@TChj}}B^{zUd}XIafTiz@>&^++sgR2Wgq zPyZ9n<#pKAy3;&wf@uLod6*kK6K0=#wJP zQ|b`jj**;+x`4O!mdxebtHH%YALN$x(fh+|I-Pwb0Ppkld&;LlgEW3qm0m;I5)vM# zH=Ov6&6}9BM!)KCFHsO3w`rYlu8%D?Z-Z8L)###Ts^k3x%>yq!{*M=uoPM)Im&TR{ zLyzC%R_{Vi&u`il`{2lMF9(5R_=}UT!sXMR%a71}gS1(LvOHeyG8<-|d$=Wlj*NFz zv@jEix7g#I8?bm!GnFrs1H5Gx9>_p=50vdQRtLPh+&b0>^e|`q9<6_Yy&mu zzC!0IQ?LiQ#v_P0mK6xIw}+>Qg6BuetmC7lL4$NjaLwH;`45o5?X3>aJj|iC2UE`F z3fRve<;b|N&y@X4Y(>WvyiH%3_#XS+e;;j&RLxEAsjdc*^1zGFz$Yk##fc5tvP$-a z^SckYQ>;;0z?gWvEzA*jN_n*_{xeAX7@O-H^1ji04cf-tL{T1xKPJ<4rp)#KOUQWF zZxl!+@h%T<*@DH}IxwAuAMn;aw08vQ|3%-9k9Y&#Pns<|)NTjD*;-ty#Yg;Lw*_MY zx`6kq1$`rD0B`pC2Yjz|%%LnZPF08#n|FqSo>+m+Ct@aP+@maiwGwRJL83Fpbeio{ z$2$wn11~-`+l?F6<+4E;90E(q@8R=ysM~t$^i^BIis$e$cl;3-D(69Cs|d-yE7S7!N*}g3UYqfzbJgq>n_> zI96Z%jxbs5hg+W5`m4OQZ=*Wi8E77O@r~GO*To%UgS1SXw{F>s&-+o8SlEXw@oD8J{Bi8WATpcXnG+G zc6O;x2g1Q|0j*}!ez5H3n?;uZ?{BIErA2_ZQMy_F*$#84 zqv~*%*cEKvW=-3>#v2ES@6mCt-u3Uzq_BA}|FJcEBCM6_cw3=)u;IiPJi+`py^syM z6F18EgbSbdgz07;zCahaBlo6jfg=91TM0AzUzb1qK=Zt-S$0#DM~>jgrHO#2Ti6*^ zR~7@_st4?9%E9jKN*;HuoN5awvt?t(6G!a+AFl5;Njo_}B#je#Qfz(y3pVeDMC$~Nw_-k(h*XQ<{CI1Kd z|27Kq2w5Du87xlz`TpPE^Z$RTv#0FGg8rY4tOmW+Ed~EYAS?i1*cG_%K)|X&J}gEO z%RmictOyuI`v2T(169ZkyQVE&HZ0cyVawQhk#N`#7UvR_IT14m$(=jm_f-K*9X-X> zEWa%v&85@lM-s7X(6hpevb)>A64lUge%V(-75}gYDLGz0X|ZVvy9vgAu`)I$7 zj?Doakn$GwydUVoZFmCC+{yo1>k7B(ZsAKT$6rAb_L@hl6Pam#iY2I0mdExRdKXL^ z=BC)?WW1ZXb_$ZF*v^C13Rt}9KSmj`1K#zC3!fsqt(k|1k?pOs*A-(|UJry5`poGT zyzqmQY!5l50^Ttx@rSPi-V*K=iI3h}K*qb2w(|O5^FD5`pc(vgh`0|O*Kn=!VZcJ{ zEq1ZH&1LF$KTsWSQXb+s@jc_Pqjv@$kaD{wbf`TWpZA%>r4K$=IKyFzS9B(I@p&t) zI=$NUf(y;_Ze*q`5ApC)iM+YTqXU+a@os$2ZBF9d%M>S%#k;fI$aw|eZOCVH8R4y( z_VI@y;63?4eAj~;;QeTA?#9F52I=9>YVR7rd-|*5_yNG%tg_rfdpA=bZ&Dt3@wFdOS$boV9ol4k^4)VkeBSD+ z?`wjeIK#&u9u)X>4ZlGmglV0)XX`}sya}ch=3$c>8#i~iMF1-q?}p5>CnVn5p;mHO zyu&Wrg{=m>pU%8KitrAb3gy)RytSEgpRURbghkD~j_v^$6Wbp6Eb|TUKEg;p$_{v6 zmYwFa>$HHhR}S8O?u*U)Ys&fQa)U2KEp%M$mX+d4f2iIMeJdj02X#_i^&Up^cz_e1 z+KG3QtSW%_gPPtGa`?PgbDmC~>2`qc9Zz0yo`S1edE5e)yT7LW2FXd&pQ1eW-#Kx) z`O4hWTT97!zd5CxN#bpjE+dP@TRr5-UT(lU@qDZrIq$sbmRFM*f$)_^Kf!B&_eTS# zLJrXX-%Cs`Xan0@v%mFLRTP;+J*(r^3c6!&Z)tGOvJWu~5=rBBE_!kOGaGjG*3kWa z({4ov)$u0fffwIkkHuuB1RIoWtiK_T4WG9+$FyQhrvu!*SyfuckAmu5YBW=GGmQ2R zCl2hRC=Y3ZH1qSAzvusyHQ@j9DA50}B&$L1)gP%KH3;edm1eCNuxikQEt0Q)oybwm zeGuO+3#Qn@rW_|aum|}wo12{x^#3tT4?GVC_`wT~YIZ)39)$e4B@KC%K0vD$us%NX zzyb<^a|5&wVNbE+yF$&GuZOB4rRfN$B(Y*!R`OWwy*cGO?HBNuV$5dexaZSP5BOOt6`)06{Np1WqFu|vLpvT znCt&nknwKkxj6S}3xs!7oDe-0@A1_AA`8J3dxSUV4#HbBkn2PzSV6k^hOlQQ2EvQe zjn3#n&%zAn6f-x{|eU%iJs%lNyfXit*4Asy_1ej(qZuyzQ4$m9`G(tmG(h+ zkAC03;V$4^b<)C%`AQ(%D6Gu9_?jQQi!FVc2{cISJibEdfcMSL`p~d=3#hz(m6Vba zHg6}-r5(~yxXRwc%l-!sjhk-NAu{!iI1ef?Or<={(K_-CMAO?N&%@8{D$ z-|HWs{daFKt(v7Mk0DWqhx^ZvzW?|4{QqC>@c;bdLI2N9R)cyrWpt5hkkA1=7OWbi zHl*}v2=xC=zo1ugpaxkTEL(RO)S&LV_Vm_M;1N4*^;cOoZ+|l2fq-wEv##gITR!+y*JhLeRKE*8@IKl6Blz2mgT7ZD;eV6EB2meg!EN z`i`PJ`kltUREEuMv2&5}?)u$rOX6*1&9elHx70&|+9=??zgpos!u!~=Q^rKV8}9lj zeK$A|-g<2NO@?EB@X|@;U-E#r{I!S-2EhCJ5;arq*XEGpB;RV~Fl^o`iv6|gJ-!ib z(Q(~A7d!?xVe=OIF{A9C+DCP~Rna^);KX;tqVMN2P7X-k{Vrkb(wDov&Qs(*~O7O{f*5D36%J?LMh@=KB9NWV}DTSk+469jV>77>jpC{K2c= z0dJ^g6S#6}Ox5kD(en|cde`h%(Y+W5m#PhV9Ra*M`8S8#0p11j4>pv5-P``6H*d2# z&7qH{?w_xU!{*J#=)5O+c8u7Aj%$oRZuVONoA<|f*@IixQXg+lG><`?_=Zkj?^Lwn zfLMdGZl79+&-+ow=eI}s9O3R9jS-E_<+#=UdyxFHnYd7z=l!%&nW8+he~Fh*oS);p znv8d6M*ZCNf5`5w`mPctEZ*iJ2EQf&?-Alv6@<4=s&3jAa5&+@MoiaE2JippTxY{Gr)kdeY|gSSffyty7< z&=R`p1mBl=mYpez-~Th5j$hU9&P4OonWCLME~39_)5Dz+!f*Rz3LUOt4!etF1E{O zm*O9gs_`iDb~p0Vd<}A1Ls=gC4^Qk)NSIqe@{;i$_;KPbi8uGYWo%fyFV(mNbOPSn zS34ymykn%Ablm~(ujg}X9 z|Cc*;F2my8=y!{+2k?%nk~xa--rJIP(;4t~`4#84$T|>?Zo3{odC3ok&ns_w0eDyX zJ>z)_cn_|XD^xgV2I)M?JUnKB&HKL3ouDVf--#ONINrDRY87JGyxnXKHd+} zJWk@o_bI4y$MQUO$o7^!mlE@mRK4$vm$72;7L-4JzaQ{!1})f80kLWz}1;mI`5oA8*zJodbMB>GSF<{{(VYiVCZ;+>M@vlNSWioyMW&wzK8 z7!LvAt>5K+9$9;{3|t7^=@tl=7wh}PfU~#iZ?H5y=>Jp9oRX{n?~?m0OM-YUAYs?# za)Wi)ySEp2Px>9O{Z8aZ$0X-50U31+ zDS7$g^WN_!*S*@+9^NeK{wei7{@EKL;nVHlW4W}yy|w5IMS0XpF@>D~kGK4N{~xQn zrJ`R4Q|x-O8Z^A#e(nxZWQ+Z7!}ir!HAupfadS1OK|g*fe^3B5$kNqFE)~=uE5{wS zj;4XI=4kJ8dT@gj*Ly>sgh{UbjkPl!5*J7x;6sd4Aqw{UV!bb6}i&h z%}y3j2|wEoc2;cOt}Q!N7B2rmypN7Mk#w%-W+683NQHd12M<0|9q$up9+z<9`+DTF z$U+Ma=-$(rnq3n3yy<(&dwC1(;8pSg+Qy;yH%JScH4@;SIGX4E;4Ni>(o#*BL$c zc#9wz?=O!zQ%JnqvYJ<5@gBbQc(5MurjM(4L3p21c%OG3@Q%<_m-jgo2)8rr&6IoP z2cKHect{8Ewvw=QP6E7>bP2iZG%X;e&#x*M4`Qz%+wLE!jk!5Vq(jH4T^Jc5#$fYS z-^8|St2*`Z?m+X<#)(fqcXD-bD!4%^g7JXOZ~XpWMfav!ae*ED$)<8rqvJVlwI?vQ z9DnsJn&x>ESSZUQ@F(L>_J8jG6CmR~7|gzj#5+hjnG=h*IYUZKBjByLgdmUb4liET za}w}=V#=*(a4-b7!cNdICOgk4gvVLys*it|%la)Q5leM$pI}PA3-8Ja2zx%JN`qJ8cqi>2Lo} zMO{92D4+(3lhvScjwvrv4YDtlT8CAG-Yn5RRs?F0-z@*EBA8<3pQK6kfGM`VL2hlg zT_7wT^M!Ahls|mOhSx^=;vf{sl>5kC^#kO;!tAH3mL=q&SL?07g8ho!s^)#4E)P!= zN#l-1xQp@KzbtNdZ% zOv9caz`G*sOvz`kd+T?L@tO#qB{X>Z%5vUnY~BVZhx^_voF;xk$EkOJ_bar<=3T;8 zXK2{@h3cyJ9yE_qocJna0+!t^<$$U*pd_8Rz2urSuFgnKQ5AWRLa3UM<_Kqlt$OgP;-CC<+!3WY8Ob8ZitHk4l!X@B{$1AlRHzkR1emoy8_FHSh!btuZ?xEvfl zd+~4oPZM)8=>Ip7)u5Th4RhcBL(c!N4+slk)u1Tj&#|eX29>{aeX=)fYmqi;YB z+Ow=*euq;a93`>zq1F+9ctbaX@P-S6(5Dl+PLgULprh&h5`CvFpxI-Z!cUiB*B~AX z__L^RlBX+e_cg(}q(R>XeJf$#?AKQvy>lMfr`$jU}Q+-a+ zq$!rJXhZ;u_q5FNOE&@Uv9%ptN(gTOrd@4-_vQ~O?E{X1@XrFxS4<>{oB@Razax zRL46M&0`EFJ~4)UkAHzDNaJ%vrJk_k^Umd(w%)|x32zjgh|tcW;DEGsWt3(>ChhZn zPgx$lPu^tsHwGcRCCPaI$o&nIc;D)%;K$-UwsF$x7T{fXuQD6q-IIN>rVsEwZlJI& z81Uv9a6Nr@k3URU|3xes@OIqAz1JV`uI=kvoVUUfisO8rlahzc`{=WsS$hqC5-+3U ztPO;vAN=74DZUNq8cQ9ikGCV5hY(JDH>;DM^)_%osZSQYyYmsh|F_NSTCzp>BwT!A zQ5Yv5{_gEHW9}q*_7ybW|3@FBERQRudCr0(bGx?^WV|N>Bfx+Cb2)MIvQ$1S-gkCx z*_{J;JM^z~LwI*rN41Or-YK@nLsYwa1i{5>RpiN-Sn+@hWH2_$9F(iC1f{t^)^l1JM(btE7eu+LNpHxocQ!C?BA%d zaX=+>dU1PR;qyLtUS~%G?@3rR9WKd@$KT!}tW`M?Hk(fK{lEV@%JPUi)1{LQK9CNo z_XaZF6Pn+JNW4EYTk&G?{(tP9c{r6_+yAeZT?tZ8HP;d}L)S&k{P4-*JGG z0{Z{_oFe%WusLBadm%f|%N@RXl9Y3OIriS$>YytgR{nn~&^SBfYGG3oHr{;HwF-$_ z*bi^ihX77~mTC#6rcT0euwQ*_{$YH)LmH}T8i}FE)?*%#4$}D58yb96&|auG^Cu@? zS@U794)?51`nUhbY2n!8$Djsj|5pu?hb98z&>FN-MOqE327O(rlNAqYP~Out10zs_ zRLqpJv_K7d_dTre7uX=Z@vHTd#@WmNF#6m?Z`Y?M_$y{RB`Y*iYCLVg4 zqj=kqx>T|7UMtO4b{ycnFJ=QYi8rA`{E`E}+sEQr;6h&p;!~TGxcLYj@o!uy77g&G zX>C?n4e-tsIjF$<99*&UR7N(;3A;f`qe(PwelcE=$&6de{jz(bAodXZ9DZp3RE+)b zKF##ef|Fm^9_!P?JA`0Wmm1X_UHJV!xxDC$ic$z-d@(yY_9qK7$ZgLC>P@v~{18hI zWzENt_aFUhE=|oKHK*Y{esahJ#e4Rl>nd1y|N2~BnFR2@xO!F1V#n7xUnrc2tMAen>TaH^#ve9 ztHP!4$>HPupjdy-@~_8cJl=-4So5*NowFkJ$Q0fh)9@bKLMuh_ZrdNLjD@#QghuHp zfVb_J7e^-XCb_3E?gPAEv`c^Q2b&Y64nK2~cF_@o_TxNt0PoiCJKi;d%?Wdcw_eRx zH~7;L+o-Y#Y`k4>TN_pgj92tC|BZBop@!95*FU#b-`CM0Nw#x4*Uo}Xc{JpjStw94vX^XIGkkj!OraM6msyn#J z0|qtd#Gg2-dJtG*=S^=Cv1TAv*8cnPRE<);QhZ7 zA3qIm*T=3wNlD!wZX`iS3NudQP0Ll}A6}52lQBr$>^j7D{eLpkhaygXiQeT2b83X( zkQc5wkE`(e|0O#%Y*iHBj5Kv~E8Jpb4f4#ctdb7>8DE3GOR(qz-u)@>@BROJ)9~i3 zTk@Y9q<`kUS%`)Ancz&PJpk{kUuLUJ;+;-Y_wxXF-*B}X9kpd3*X_9S<;v-ZREoSP zCm3S)%~@e24e(ZW_09fs*bRn?m)>?3!p3`(EC>034}@?q6y1KHimww6sO}HzRwB>6h-l!f%l1I)8!>+AN## zcth_-Sn`q6c{q^&@>GMQI}LBr5#?~SdMEl^T!4l5K-aI(7=ZVewJ-Z7m$yXttS@8( zystbLx&G4;Ja6H&)P8Ou9l7qX_`U+b+d6Br>nG6vQzQF4e;;szhv|L$)C95dt}U(# zzNZ5rBh0u5nU@kjKf}hGI`|_bV3_@uw;nKk2;$_IaMR%zhpiACZ|}ZLD-j>>gWn>D z-@JB461pn0J`Lf|ARE2*Z4^J8KI8GW+`pG4AI^z}UBQ3v|JRv@H-}Tt1{CiD`4RK6 z@cuI*5xXDYohACDXcF&jYt)6t0p3<4hZvsV^A-)+C1-&zbrC|F;LM`7j?hUHG^E zUpx(OqB`L*ig$3i^*k)RjV|p=JqYl&d+~kyB;LQ)zwny{`u}>y^B4h72Er9`B}D%e z9cdgSuQdmF$DXfwQULJ&uCHL|;OqvsWZZfk^$)kV+}rr%nn3nM#cO6<@w)uI>kF{) z-gjX{lpM!?cvmrf?8nJ({k`J)+nz%3?2}p!56toLPX4W|w0fa8^3$z&Vyz#3_3rtx za>IL{%o&gO*;lOj@YXF-z6%~F{`dYroZg!qehm75qiHpWpSDaGtwAvt7U^KspcBa3 z0#8tbcHH@qwhYvu)|}yi=YimWboI%FmP!m{-nJX3kBP+~Z>r4WW`X|Sir5*QZ`KC; zxLv=%lj#a~9C21mUyQx~Z)MnjN_Y_g>1M`_1t%p6OJLU^3*w%a8su+m*ZEa3>{?l`j^auNjoxB`m`9dNAImV3Zt9RI8 z*@1n&2qxWd+y!1WvPv!$if6@?GG0E zf9L~WpYFpIGrmEB#Q9nBp>WK+H15V!|8F=AZyv^O5{maepEFumcsJA@a|r-=>&ffN zOyb>qfD?KP@J?_w>DsQrK=#~wxuA5Mj;wYI>I(#TPrM+divzsf&AK;Uhh5=wFXXP? zY{$l%oATI;-UJ~z%sA0}jls(gvGE=yF5UJsll}1KW%?My$FUfKz@I^isA*qY+MGY*@g{F!&43-4Wrm)r~nc$398yqjFTwXQj}vklzXp)0(~(nsNG8#dm_dS~Wr%Z3nJX53!i; z{rZ1XrVlBc{4TU@XWVF}!P;X@6|Tm8xHaWCt#EVZ0e3|5Aj7py9KZi}YdPcbhGbat;TBwc`Ek}%|G#`1-hz9s_@a0tR;To_@Gf>< z|6o19TXg%Mb(46nxPL+BDZqQ#s~nLxGzKE{>3+~&?HGhhsuR8h@MdgX`Q01foubEk zSWUteHl6)$r+hIs-l8KXG@@@25OZeS_T8%`?_9>l+wQmDC;l|{!&`#s124b!W|>2- zt7x!8akEoP4}OC*E4x8_U%Vf38qy_o_T%^e6pD~8WIR?_KyZc75+VR_LgJ>_S{>SNNhN| ziGYkV<64^!oRVFSz4tcs$ab%-A^YLIgy{n>zedBc!b2NqaNOOEqQ?^O@eUL|GhEvq zibMno2^hU)q5m(a{5-07f9Ci9?^yHE)~hq?)XjhUf1J*nJ$?-Oe~W1~NW3YmJ%o zP=g-mzrJq^hS>Q;uBJUcuCVpWQoFNXu!mULo|62UVIs1I8P`+H;r62kdj>hasyz1W z@OQS`|CeX_z{{^ez+tT(l?L}nj@*&m`Wd(XzbY={F>gQxR#~}hW647N2FYGDM%i#& zW5&-QO<>l1q<7t;du30}AXiMoTkK-d)CK92cy|vda$@04-ON{O0Pv=G-g|2d@D_ik z?y(Nw?Y7xO;R=a?=#D@1U1}DC&?Ly+1px0)HT)XR0Pm&BdOds8UE!8zT98r&Hr``< zOc%bYA|kJuarX4(#N}n!c()d1oS;;)AKp;ZUmtk+aqawOv&)7C^JTtB(YM0Ko1SX? z;CYJ*oF`;@iMyAD8RRk<^M)LQ8ILz)%Bqjdx6Bov%1?SRLS9I`rttD8TzCwI$**z&pb9WPvBZd+t#68V1o7 zer)rOl$wH#x6#@6!6_+3mJr-d0BVe{Ylc_!YnZCp}oM(xGu}#^Zghjx`?|?inNVQ>Lo7*)+UG zjdlD{yd5szBVys*{*5ta3h>@>K*Dhn?;jr|%P9cwoYyNQ(l{8%CP|`byLk-a^LeZ; z7vQZX&a2@E@NVLQ>uP?vz#{tRkMtbF##`ZQ%hHa`L`0k!*YWhqi>9O4czeMfiMO2D z4{v3r4^N!@_7^nPse|erar-OK4Vl zeI_yxcln&U&nse(1e*TOvjFc)@8!2_2Y9Dkjx!W~g*`vY7$pZBMtESZ;*+wlZbchv8UB!o0 zgY4&(a?A!b=%f}U+7#5FIm+9=Om2{_arCeh?}%<`Q#YmS6K@Ix6xA27v zs6hq3qA|~O-C$vzfiwE2v1?G>;K0!;JrW|yjO(K19*Il9u0g>^Y7EOAhS{$FuV?xQ z!O1Ua_?vK-EDg@ogpwBKe8KJi!+IXwTkGSCoYxmpzSN69gB-cze$;xi>WrU323%*& zhZ=We@8`cKNUf*gEt55S>i+-9AvUgGiWdv-Ly>vk=1k5YgSP5U;(f>=$z&AZ{mDBc zLVYj>34A8+9kwI}xwn*W!9#%eyGZ4i8USytMy(UuX1T$g$A7ogM`Po?&hU7@I2Q@| z#EjFw;kueX3>$A7?d=4AdG^EGk?8|3zutHQy&P8>JZt%G&mBAP@!nx4_+ezdFEY-@ z$0K!+h5lcSr}g(i^%;*hq{yO=r$5JP|2}VFH4SfRzx3;9^_Dj1V?B%2vmwLV$o+CN-xDN!ll!2R_H+g0yROdojp5kqyvAA{;W z>%R2T1|EF8ADqga{d$f$TzrHQ)9{>y8Ki%#-ILz`4;rK`tog_m%IJC9H}$-Qn z-q`(&2Jq(iyiT+j`XY=#@fO_{ZaGf1(y(Pfpy7R|F2Ka3CYhxP1?n zm`5pMPfnTxW43$EXFt3>m_G3GOLe+i9sNuY4$qXBzcmLR?;j7YY`R^j2Vd$?t}y$9 zzxM{sf1#pwe&+Z8^sTJ<5O*>;QFh|r{vW6FW{)3({@-p|4N|;U_5iIxytiN>tQw@Z z>sk~U)Sx(vIUQzTh|T;SB%%u%qyguC7ry2ggmmX_9L6vK_mzYtV%(8DstDB;-0XF0WWFF?bht4f?VCS6~I>+bD2Jd zaq|1Q6k!Mz(BPvRc@{aA^yBvb5e@a$Duhk2do*zQOt|f0Tx4UA25p7ZZ(xYEuW`Hc1>il8BX(4_*A?EsOV5ML3LEcvcEioy86*Ua zQ`Is#R%wNew`Bcp*TgFJ>;D%peMsTtcj3kco3<}B*r;}$m+UTlyand>=O@m0hi!tN z+gZ5c;~j7&Z}uCDTQeSSN)u~7&ULHIA4#6Vd(AYw6&#OG-QGI6yv0BEhKhwZRFSY$ z5a6A?mb`8f?>RDO95w*Ft5#c{8E=U}cHJgl*gPi&d2rVy@CCp-tMb&aG?+oE@qE5^ z;GQdd*0+7vym{DoufH#D<>gI6GMRDQr?iYVEWpNFD4{{g=m7iS?a1^Yf|H-i&(dY` zi-h2M5sg^~tnl%UJ@w|IlCnF@vw!i%I~6R60=&!C3sNWX9(yk19}Mu$e(`)^^UD}yi5H)n``j4h zzOd9p3BbE+-szLp0PkQ8x9f1WEBtiWec-YXHr_AXD4ef#NC+C2eAWBa2~ljkbHAV5 z>1oe?c)w!$xP+76eCdyOjr?e^r-)3O`#Apc*4o(m9SM4x$X1JiBVEGy{r~2e&Re%Q zbY}eXmOOOUeDM0Uloisa`hS~gc+dVG-j3ouV6~GU3-7zphxsJ|-VHRUc5-u~|A@Nk z6@a%i`AITQdkjMOBntEEn@8Lq>|+sSv8 zgo8f`LF0DE1o;M+V&g3}Z?Dylc=p5Fh3P{EC%=GgH!hU73&L+Fe#|v_jgR-m<8xl8 zb!#HVW)}|!JY}JJ-%i-twQA;n|4+Zpnh)t6OXZEh-230}|JkF(|Hmvq|L-uZ2C3ar z^FwRUc!HidRt?IYM{4*Sn!jxCt|RMLfEtu#ANQ;f)S#^&HJXcBV-Ty}{89qAL5jZD zfu9QQAT<$vvWg1sAX&R5?L+`_o*WPm1N{FGmfbDaMm?Z>?QW- z#EZv&rTt>N{-471u@@&l`&?UsXE6;P*+CVtr3~Ws^TLF-V2SiFxHw>Lh;S7PJ4ii} z%}>H-{`db-Cu=?~L@&FabaARdT0af%xqCgPp4gpikg7__Vpw>KE67oY0N&wU-aM0d zUnt{Fx%D$D`i!O}mPyaC?l*UtNN4)p(3T0NsL!1b1=2h!)I0=)SJ zAeol{Z{#5>8Qwlc%wdy zaq^S9@!+@pH5z;?<3>e(IzHZv^TxJY6e8fqht?C?&g0J@>5<=Wy`|lp`Tc)5Yd%c+ z&$V`)pQ_&W)9_Z2?&(1Bz8#t&f`#{2;$ZYBz*{|+yloP1&--xNT!6QRK_X|~vlwJ= z)a;Jkvtp3i+j~MC0N#P~bezq=>TS7on`g}(H+XSfc#>0=pAep{7g6(0Ts`~RNSA1&75N z|8Szk@JNvjeda$-oH+jvOFmBaYG=;@52S;+_u6TAEB$N=L-9V5xl6zs_nc%zk*UVfrY<$o#%7vT!&tIa9y$Vflbu1RQM`W!j7VeQy?C8R;|qYd z#rX04lX&y12|vCD@YZ##)QcO9LDmKd9hlurM+V>K&Lsl8-{%;8*aq+}vuTj%IqwEP zpZBCr=P~vW+msSm<#maSykN#P75eCTHee62UfXm-bxG`p_j9I?%{civ-=R<>s zKb%o0--nMkS5;hoX<0Drv%}`kHtsrHydkeNt^*-%GahfK^%P4!G|y}QNxnTbgWNa` z?}Zjl=TN*k7!Rbd@V;Z;DE$`Ty~<*~{v_Ue-Y>{52Y9DPzpd;09)m1HCIm`a=}79^ zisnYJdV9NrJE9igEx&zy^@H8u^A@_;2CD*Wys0HtKfXthksfB;x+l?8m#f%#H&mQk zfAul@_5VUlAJ1^|dtDc?zgJ5L9{hZ1?3V*R-anp1W!bic!E;@12S#w=SMLDchay?t z&u2W|H7O5R^0B>n^Pi~wQ`LLJG`ttcdI_O;o4m@9#KQaV;J8@_z0=Zpzv93IvH77ic;lDQi)qX8@s5|< z;IaVVE!ufV?(_xx{eLK_k+fU6dB)=nky!Kb?BO@c`@hRuj??g-*H`hM>b+uUvji62 z*L%(%>jro~Ua=!<67S{jd$-pDyrbl+%y{0%AkwLfC7QqJ$Y@BAzXibiW*g)%`TieS zfMygY;||9W70%6a$DVsf_?Hxo#*mRi%(&F*r>)|)*mG}#+mRuQU$GzFJDEOUoc#KI z@-(#e3Bip5GB@YT;^Qq8a^Um5v@lpRYOJX!0Dp4QDib(-^_b3#$9v6>tt|O4IQCeI z!Z`VF|Buz&veSPL`u|PSYLHI$!_Vjt8@)tX5vv9{O!&AIgBlbaZs=zTYLI2%ya8WO zgS5r2MjxYs2huivexQGej+__??dSjv(wC3<8-FcpgLgNGo+5s9g@@`NgjNx-huDRQ zu2J+CT*wb*T<`Db#!e~hA=YKQ`m(;=2;24li`p&z9Stt*Mf8)Mzv4DL zR#BZ|+^Qk)%jN?I-#@*N8xK8MDn9Fn(u}V`&{`wbd??RVl>2+dj{7vc7l+l4pm<*$ z8&bf+`>ceWY#G2?&Q@J?67SUyc76y2crVeEyk#o@uD5i(l3!gwM;529<-Q5<7D#>C zWVXBwesiiTXtkdk+*f~=wFf`v+3HSqCv{@OogKJE+O`@G^+A`SoiKh)_QR`mJC%*Wfqg(V+4 z0gM|VC#U*%UfkkA0;^Xt=~VPE$Kjm{VhsgT1(*LZJ?#LH~O<9Y~kju zBV~)f|DTrmgwmHNJ>w5ZOB*z@M2EB)fNDZE{$;jJaw#Di9EJ^xd3Sa=hObAoFD z-b)u%g-qftBza3F0pOi{;`_oMJPgDn+CPY|oQ@PV2fq&kcsu6*{BjlGeYz%EVPLTv z+&foqpScq@-h+z{bUGSwA$`oa(@*7isQ%b^H|0yqRb6C1yoZ=RUf|?cyd>vX!WkNz zO&@)dK7rpLm2%gYUH;(+tHwBl{1C(6|A*2Kn|r#=e7vD#7JcOGvQz#$IdPeWw?=#A zH57087p}9h@ZQ|btNR$>{oLD8b`oz#r+lMKfVcO}9N7vA1F;K$j@i}Fk+Z9Y7On?) zpSodebuV_y1j4 z^D(k5n{(cUf6xE3Q=5;O3+VrSrqv+B)a3uX|L1Klu7*{EO7-U#p8_?gL!HKH4QkK@ zZ=&Q{P=kggAm@=^G03UY^4p~HC1W_11}}TRJAbqi ze+F6c^NV=7K@2>rYuPqlN&F@DIMGFw&^oml-yq4}V9m#Z>c{8XcTepgc~8UJz_*fu z4zcr#dQ`FS?%m-OaTefh5oU1B3gDfPQ+j(nz`H%8KPzu62C0c#lOBJNju>3`u@MA# zKU=xmZWQ3XGD~CPy@4A{x33IcYJiRRLjSF59$6G*KQm6V_4DAmwb*zkNbT#~sKtJG zqdtz~voL?_diR{}UpQtdG2`*} zOJU8&Ip@RKcT@lE|1o=RcKQM6|F=x5LB`3oRcHa&1L=%!HS#CSd5{8T+?gLzhWog&*C2)D=3mU?8e_Zu|18so7*2ll^J}VXs%Wsq zv!HShn<3o&{4vCO_~6>ZaFWT>KJgCx52VcxTfMRzqAp=4^!_`!Trss|$;VBjSF@P? zzyCD6mpf%~qj;+%zg~!i_wKYxc?Q7yrSl!fNxUhtbFY{IymR)IEl~ka>_|oRaH|J_ z&s*~67al#)2iGjL<*HoL2Gf^{MZBZ9!-cn+_wc{Q9%8dOvR2rM@*p>vaSwmwb@+E< z53$z^{G+TIN7)YV3rrukaq{zB(Y34ommqv)Uqf^D5`4T#c8VO~c8B42Pn|r@9menf zp$A!JPcKnsJl^y%)_fc`P_>RvpV}bZJPq$<3!9Ikcq?8kT!4jlL|&Cj9Kc&tmWw!v z_a-yHL`#78hcEj*+yBHMzc^(+NQ8qK9A!-qv*)_haS8U z0B`Lzx9_AIw!vbm_kGJ0+~HsmrNB`U>apP!St~hCqI{EA0tF!Xz=BZ(v%SjKHh!;IfttQ55b3`wRX*tz{eYMTm9SPrQpop zAT49j$6eyJ&t6m4Tl!AJdue?E7mByvL92OKc%Sji>^%YS-kBfcI34ev-xo8=0N#K0 zH7y$3Lq}#on}>$L=7hx?HI6+?+hAj#fL}N3+~A15bs=i_w^c)5{CW}G46 z!>`vB*prh_aEGkSMfTgA*v9nn1t-7SwSh_TErRe)iSh&4ukic-IoqMUlKy>g!S3qV z)K~a(Z^-Z9B8MY+Gav79)_h3r32L~J`)~jM-|27u&;K1T#0F2RK^9T7f1)+$j59$8 zs|KxV=&ExDHRvn3H+VG|V&}fv{@e=;vC4mP%`ZqZkUez&j03Cb$XZ{uZ1t2rSfpF! zZIX5yT)ZGAb-tuKJloVu{q8?}AiXYa*7r>@yoeGrj<#+O{IM0g25Hssq+azOXS)Vz z1Jj2NPJXdwCJ`$ngy7jPtt!Re;}5aE$4qYciNwRY6;D+koWUProgbA@><8p$e1qhZ zRLYW%6>k*YU;6w0U(htXS2)hyi{kxDv_%^W@0&|%=6eFXRaN~(C-Kg09TRi{c+b&R z^%0j~AeI!#KXUeTBuOdG<9Ko({L*Ht?)k-Sa7Lp@J(F#%Ub~R zA~wvpklXE*O%Jj09_0{#UF6sgZvm!{37q`GwdzjvItanRZ}|zdI()qO!t*>g0KDIX zQQqZAu&{%)J7n`bHKiGkH`KwR5Bvg{@gmQdaT#@`TJ1jA4bsI0g@-lYvft|M9Hx&vocuJiJCe5v z3&Cztv#NR1@bMlml_vNNAA!d|##5@U;(y*kzny1QByfJl<4rGS&Bt4QIX@Y&g9Iig zTc_b|I^_Ng#oH%vyCxRi?yXPxg8|->>yn)(@eUfWYgi2Mu9SM7cm#Z$n50$0vDKZ9 zsE7*{*aN&r6y=7>b=%;?+*$PPTijtEOIq+mI5ytfjny8cKIB2RFyoX@*mvLAj*a(k z{dX_kr?DU25lkOrIQgB{xcTtTdLcNR?^gqN3_jj&#}`_3xgCM+;-zL=uEfV%r;4_8 z#4T3;|9tZMKl}%NX9%+7!|{MjeNe&_-T~9_HmN-D6vf;0B&>mjw~JVuX!vCHb{^)O z#9M|pa;X8pdrf*xTs<%NdP~6YPrMf$Atm_=mVv!DG01o4UA;E=8MQ!hwV6A-uJ-Vd zlRh@yP^&;l5Q7KV$c#&lzP0`HQf$244Hs(;zB={rT7Sdc|Igeh$G^JnIDFDx z#qG%@{PX{i#qale%WP--3=%S7&Bu_mShHo$)DRms4ewPJ-E!y^? zLWSUmkCVE?7UAPP+k1TU?v-Qk1&z7iXunNFuKK z@OZi`enM9tee&Ea1oH*(S`~BQb0I5cs(Ob^!+T|caxjWF zVTG117T)p{CBO9m@26M1>L)iR_6HD_ZUK0&j_n)Hn9V@8ONR>PThWoZ*AiVCz~0+e zhw_XATHy57^7N%XI__|mDmO9p7k2d~`%_ay@AD$L%sBTkK6h&l?EYW=Mb|$0o9u@- zH`9kAPJSB&$SDio(%?Am&}Fn?{Qkd`kzpPS@K&q%c#6VG|DU)4DOh)B#`pj9;*Bi% zxV7BH;d<7;`~Ux!rRTr>XMz5I*R&dBAANpm|9`UoSMPBrW7VLi+=9JQpaxxj@58?q z)F5F_lk#LxgScawq^?>qkX^M3zf0HBk+=yZv6W~0;GL&lFRoN>gI}e7QSy#*hc|m4 zmM&MtUW2TdAV%*f=SQ|O<7_?_X9}ud*PxNN+Wj_B5c1#td-z}a7w<8B{KCmkzajD3 zz0)*UE-Nz7^b!6Ld$fIM9;a<8oX2CH+aiU(#7-A0HQGd6Ipb%L^x3TW2-h6DvGUVY z|G#q@-fNfNN}n8JC-Kf2SLVdRTbcANOab6MG1gdQ2k_o=;?Z~*!25RE_Z@{63}k6b zw{@%y9l5uqIn3ZpAN*X>4T)C;_y7Oq3%~B`4pTV4ZW`vs#(VEVzCAw^_z^y4+^MmJ z9PNDAcvp?y{L<&aes~{X`nZRapVEdsZI3!>u+S#n7pHFG<9#@Dlf=)mBzPpmB=-u8 zzr-$bbWynP>Vg@McXJABJ~-D_8D;!E-m+sF-gbhqJ}BNf+QS@Jc(-WSeNhE?&)=oL zZW8Y!IZYMj0B^c|&$kz*45WJZ=C^k&=!jDM*rAmfeQ;?*-rad>ZSZW-aQK9qI~=Zd zSZbVvjkihj#_+67{Kzh5+=;d~A{GDe_15`sJl4h*?1%RXrjK(t`F*-`YxiPs|3B@Q z6ZeyBe7sHRd0Wl`yocA`JCe$Se|igo=k}hex;W$UhL*ADgW9h&`GORfoJ35+d(8{G zLnz)Kib{!Cc&`k&7p)HPE|C}gHMu!)##Wrb3GjZuns|qQ83QR0B0MC4)!SoN6BIV4 z_rb>dpLiDjRbd|osPGW*DJyZ zz}wv1YxkdJbfm+79#7EeK3GO<*7fxZ0N$;JOPnp-;cwShWD@FBmL zaV^!tP8Wu;S8o%WZyOsNWWT+)PfQ=jaq=twQuFK{LkONAq&LL6;N!j1u=>*nu=ghH zsb?j}jsJQ}eQFXoq-Qqct9QK_Yd#F(=UdI%_wW7x|4S|9|Lm^?Lu~Z48nn^(<~DSQ zU3SKb532^n_uMu36OzA-Ec4`*Js4u6Z!E2!d_nr*Dt#+2F9sr840{%XFGzVi=x@Dq z`ryT-Ka)(P!3Al)S{A;C++orJow*nPp+VZ?NPc)DO#tCy#wiA0jGZ8053%)kT$a}m z32fK@$1r`=;p7*&^YEsO1|j&sN+_~-#dqBO|JJ<@OXnRt3r84kUD|&Zzd?eoMe;pQ zocaAfbeTmTDn+L0;0zMLJ8Bx<8y54Fqj;;RO7mjj{rO~Z0|5-N4ZeYUCh=CkTW$~q z@V=1leCE3=1KB8~-aa3E{~z{}imsxSM~<%F^Cp53%-KM7Nq&@T)hypiM7atZK&NO~1;Tj}%4a zqD_DA|KB|g@AWT(I??J~d8U+th4&Jh$Yue6cMBv^Gr2jzk-ts$KET_j>e}khs~O0Z zC%?Z|JA>C-)M!G-&h^1gu4jr~DYU`+O*fUAySu~gYAT`L|4_Y2msRr(WCRcoW?Vnx zf*JJ#cJ=ldqcprNWYgFIa0Rj;q5HFV52C& zo0!P&KZ$pIz})ddfH!Boc!rP-IK3s%i3B^+k%nT$X3xw%css`cf2(2}Y|0nd5n$*J z55i$K8!lm2@3TA8KE(F&Bj1^E(q@kmrEXy3{aL%}v}Y>&;eDRz;}cGPBG3F8882w? zvkE7{gM;{Zm)YJlT9>5BSgGahf~3X49zicEc+`0x4u|Jhdk zf91FBcVdvH)gX6Q#%Xkjb+a@T!m2?F#zb$t0{#Cb*{J;Wpa$uG&8_1BHR$7U-(bD7 z;0#jo{`0Q4=!i&{Gxypneef(-=P*0LHn`PWulA#qJ4|1B>25kdb`7#i(#va;r6PNo zaURQgPlpI%*PsKH&m=@PvS0si&-4+ClV5kZk$b(N5KMG=^ggZ@e+H@D65hw9lL>op zCq33Lt-@U|fMU|>%BsH4{2H{6MIWznpK4F-ATc;PI!#j}agNB#i!k6{O zf74*;+~e65srYyoxh=|kejpQ`v&UaEPltuiTgYuEUWe_S@eL9rz?zSmmWm)%aK#R& z-o$BmyL`_xM60({!fPrP-qnRKR&)crA4$3lt^;^Kb#Ff;5AfbuP*E*=n1S^24vz+9 zf)}J7THlDd)CcdFvqeB%6jbkk2UN%o+}=7EaCy~!Y`g=-3f&jw3m})7aSwJ}uWgIQ z#(Q(*;~|nL`{5nJ^x=b(-&jvj^~rlea3!Z~^ZRIgydU2nW!t_x3r8yCCv#lG$D1tk zq9yU`uNjZG_yX2^1|7w>++Y4+HV5zZ&bGNJpqD&ACb!`{3pEnsx`o+ThaR{^D0l!N-ZbdFyX( z#l~Cw^3jRVT>^+cGmas`=^+q^jrSKNo#mp#?AIVkGkx^oC z_VHukZRI~Z=R3eVw{yA9B;G1F*Gt<1yfr=AMBn={ke7Gw4Euun|GYxJij`dGgEJmi z){IEB!Ctx<+rQ+w!y0*%fRTUr{=c6y?qTUm0Yr-#w;)jY)+IIUy|*{5Z^EytuwV5a zV)}T6lV8cIdx3?AgkVGMF69Dee7t`fMy~$^_TJorpOr+dz{fkQGCOM1y=5~VZ@Y5V ze4IAfuDbWozvut|SNiq;>0b(lSng>x$j8p=Dq4d)2erhpYLIPjZQw0XgQ&U#2OU8T z;^JNHBnxWLjx3FW^cn`TZ|_{GgKy}_u=m@7rPsk4N&W(HechO2YwAQmYWs%`t_R`UxUV#So87KdW%3o;?xjJnTEHw z?3Dl%@2V`K7#7~^4RjQxeX5DU*&&(hdX?_An~^IZfv}FT3a|*3{a6wW?bePg@R~LY`j1CG8y5&h*ialV5+c?!5v7Vfet7f!=yme7q%lzxh4@cy}J|DA2CO-yns2=2&%Y>74O+ zv+SdQb|-D>cngDT8s470t@}~DKgvE8#ll;7LIkb`czf+ot8)N&-yH0;69agMnLgOk zcL&`6=O)@x|AdYt9=KB;RMZF8nMT;@a<{>o?!5mq&%qsD^*m#z#Ao{45tN?1TM=td}J7w!s{E zhuc>fyTjFOpVzeNV&iSRW!1~ehp0#$GcH1_s!l{5yLu}MKkvy%XFt4A9|}16-LlBK z-gcD+*Blij{rG|3Ag$DSY*cVI6E6DsTXD|^{OV0FTf8YCbkmH-n^hlqzx+HSr_TQ~ zIH%#gDfVSOTD=zq2MJ^0eZ21LmuCR)=nYxClX#~~Ey{ra-T|I#E>dzCNHj0S`fVj0 zX|tPi<7$2%Y@_*X@H>AST=OJ0#*&?4|qpiH1pAWI-gAWk4sAW&eFfW5#9fh7V91mpyS1<3rr z`9Jf&=YPgu&3~IekN*t+asGY$5&ZuAF8piwP55>A=kiPQQ~8N}Klpn1-taZ>-Q~N% zm&=#N7tcrM+s5a^w}H=^59ZV4Q{ofnzQ=u&`y%&g?gVZ+cPO_P_j+y%?j_vwxn;QpxrvnTlrG9kN*$$) zQb5V1BvSTK!YO`~jTCE&5oHlYfg(a7bN%A_#MR2xz*Wh0jVqfgnJbQK7gqq6E7uw> zV=iqjWiD|p9`Y!;pWH@%My?_klP{9f$VbRgb&x7~%NL@s6XB;~vKijtd;A9EUh|a|Cj@bJ%g1a_DfVa!7LU5yy#x z#13LJv4(h?c$t_^Od!&Up+qm@dZGn!32{DA_P-V|2-p7Wpa1KcZ^tG3O7cntJ=T164ZN4?jcgs9GFW zKLWL(O54~w5qgg*Ezu?(=pCvw+AFU?Z&9@<$LlxLiYoQpVuH{cR4ue{ItRT*)dE>B zA?OvV=Ji#agI=Oa?UtG!^a53L_j)KoEvQnpEl!1=qe?}(rvqw6mD10qFsKPtiucMM zK+jM$=Xf3jJw=s*O6+3MWvCWavqD@hKsBfmHP-Qms!=7vTaW}* zp-QOB>?L#`RkYlRuh2bI3GTV#3*AK(b&XX7REa79sX`?PK@~r3nJ`p=D&8{MFQ^<< zJdE8Ws0>xyF7d0OQdCh?a?d~|s3L!_Er9NzinDIXOXxPLNJo^zpL=p}8M=b1VYBawP#&s&2>*_NE~Dz(#}``AB~%Svk-iLFMAg@5 z#2m^+)u03T-{=CW29$g$P!6iT3?fURY*c-&6v>3nqpEM8kUErws!xu}C!uqw>Q(E3 zp-fbD|JwEfI*Y2VTHbQ#45~UaPc%RosQT#cdlO1W)d%$p?a*mdwNG?-LusgLdnEQ6 zI)$qD7aCtesi=Avuy6uOLDgH6QX?oCRjty;6rdzjy?*nd96E`rS6Mkcl991onE9XGRP}Tfa$`v|_s;1oXyHEnEp6yzi3&o@A>8gru=m@GB7b={C z4x_4}Ger_QgsR8oFP=jOQB{A4=L!^usz)1%r=SC_M`7OjiRn-EoCMX6~_kN!_0nzz5$OKTmmnc?*yROH9m#|5I| z%Epu9TTziW*V{Az6_5q!sBu&H3sJP%U5ax%99P^PNUsRkQJ|yph zimcZwG`vx9F1Iqz3l*6mM@XKiI13}`9;i6OSEREE73nR%FS?`Rbk>&^H&mq24OhFO z;*^P+feR{9sfqH=s7P)PP;x>=(zWHr8&PpGA<1e3Do(7~r|F1_M7a`Y2UHyUY`Abe zDvsWDxV8=z2?_M=_Na(=v5H-biX)mg&)T8l&{%w19VaV09~7RT>fpdy<3{KyJa?CFf+ zF-OJjTlO(#sEFKC-)xGCT{h;aCaBmcR_A4miikg6`pZ!fUef2W3>Dk=ge$ovNsC?6=KRL4`x3 z_6cQFtUun;uY`(qcBNv9sIZ@XBXSNZ?1udJDWJl(>?x-_D%K>v%#=gLYDdG}vr%CK z&S}b`Vij-Guna1!o+MDEQDK>78!3f~mEN4|B~f9a8C5EQiWSt{K5gNnt9x?i|aq18VeK|zJ)OUJ8RsL+T% zQbI<>BKP!sPE@EbkkTQcV!=qyVh&WyuQjVC@^X;5Cr6q2!g(Yfz67X^C;(B1s2`~< z)CbfO>J{o4>M<&V8bq{vZ(C?u|7t{$$}T=iTPTt!@2 zTqn6=xpr{*b2)R_a4qA~zvOC$1Y)aN4 ztCA(je4OK)gPa|l&73uyw>d9!rgJ86(m6vpy*Sr%T5vAmoX;uCDac7AeJ6F1UXtoa zWuyX9CMl7$j}%VwBW)yElZ;4JimB8 z@wDh zxP!Spxb3;kx%If!xTU!T1eOVC3MdN95}@#pfR&eb{Ehtg_;2uE;7{d0#J`(Akl&r( zj^7llyQuO@^7HYH^9}NK@HO+*@ZILS%$E)jVE%_W8<8Ko^Cyyk&VJ-a4`?nTptB$O zKMq=l2>Xnh=euuW#bl5TZ~um_|8B*n_G8U&T3u-Kgp}yC6u2MAhf9qDzEb zsOoDJH6-jr)u&UUuLwI()w}JdFChX|Jto4Agm6@K&+gJDY)4gRd-iui7^*&APm&~T zL)C|<0cS!esyd=Z69^%wY8MXeB?P1DeShg6LJ+Fn-8B402t?J}bdKGGt*C0Xy&p#i zK-HT$@G8OF`Rh8Y{c7%1PLaNRY2==I|IOa(utVLD16aOlL9jeM^Z~sQHMODd9(UL7%T!Ia%Zn?bQOIU@fVr?G|f;Fmcl5Q~wR;arEvSvTQ5>?mE{y+BK zJg%m;?f>6PgU~!jq(LPW5|xIN5-A}>DMM*el8Vr{8);O^(16O&oJx^WE2&T@C83El z(JrY(RDNq`t?Rr0S=ZX%`}cjGXYc3bFOK^@xQ-8RpLHDPd9HJX@TT z@-%+2K%21W_B_9h&_*oE>0Xut>0?p$EzLd91}w^Q?OFrrVNvF$tT9Lzi!wwV`l0n$ zl+G`63|fapw?Ty;Y1M9W1)B{j?;cjYZdG9D*S&EJ_*LyA8Q=3tfRqE-NU4 z)?(4MFwSO31B8DvM6tF159sGipVo|uh2MLnLqA-!u!jK#mo$bo%fn>4hOuj`g zv;>Pn!WXeZGFTM6HOCN=#-gD4!-kL)76njFHA9kE_QN%rmG zkO&r?X!xc931iXml=gFw5Ei*RFCK#gvB+)1#Ry0Mi(JLj7eV}3SmbbDSrM9tMfMTJQqWv1qMoUP z=Ae<3;hcg(=m{1XJhk5dJ;tI<*ZjDk8Z6p)?4v(ajYaypZ6Ba2EZQJ^ZW4NgMY^wt zE1^m(T7P511?V9btvmU1A5?)wK>vgy1Y?no(0o>?9E-F*?(&7out@Wc$PefN7Ojmu z`UNV*A`N3W04l*Eb@A)j(0wdgGdO$^D#oJKALGWMdsw6z-Jk*8#iCUQS`R=)SfnC# z@;6k7MJvWDjG#MMw7ljC8&rTr%F&ZNP(BtZ*>vked03>lqB{k;jYZ4mj<1Arv1n;a zkvf!vMe+su4p250$sNDi1Z827tcLDfC=-j8a0`b+8CWFUxyKnw$0Dh$r4OMrERyt1 zR)B6{(PI5~Y0yn9k`Smig>GQc!k)2}&~+>lFZwnDrDD;7K;s)w3Kq>jaNsPIj74Hn z2iT!&SR^w1bSHEbi-gPM0dxh6gd&>PSUa=jp(re3xh-n|MPkvc<7z9R2rPn(pQ}OPSVWRA z4S~YYNOHQX@-h@kBK_TO!g_J$_!0ZtG+Hsb0D6l3ZBmbLLL68`J@E$3#vio^{otughey=qy5IBnd_vcv1sP@ zohdAuxvXRoi)QY2_=QC?x2*rfqM1vnC$MPd4&NVGG;`(YcPyH@A#xmxX1>+-4U1+z zZ8e5PGhYH4#iE%Hr;K3H%y%ZfV$sYO--oei<^$PZuxRFc!b4az^ZC_5ESmXRB?XIg zFFvj!4PeoFi_|%!&wt4R!*N zZ{^WJl2%~Tp6;?eM)+6kF6cegZSsp3HbnEZU$5_EMO%*;V|cjp^|oTVhL>j^4b(58o%w;60B9 zZ|WiohIgOt)%kdMuk77Z&1z_YkYQ7#`kPTWwC}A$Y5$ANfpuIT6EK@XFrceRTow zgF8DrQ;_Banx|ouS2zHI%dACPq4%I^l;^ua-9hkJd~_w-2>$v1wy zhWOoE68Ft6;TOl4-n~iu^y%=8=Bzn^Tu$_N{%4N)Ux3DgsQV_E2etf=mBI6%!6(rV zTo4ZmEqZQkiFlCCna}}kq=QucRH9$}HUReJdeE}%a%=pm{@rRh{hK`18L^)wkUu*^D>;|3Y<05!B~c zZXrgpM?C0b8mWtOoUkLj_EO2%EGi91{ob9tl#Py0>`cD>5$gQE;DWRt^y!$E-S&#qLCuAmH=3z|ETrB zM&$ng)eds=b=*(vu=uR6il%|X5I7p=gwaL|vdukrB~yn3m#-jol9ME>NtEQWfE z?eX!BO3i6L7sGgX^PxH-2`Ma@7LC zd)1*39dQKj1ii9X+^+)Q*1@f;pWcw+@J~0ZO)Cb#oZTw(^jbT?gWESMzxi1K-mQaB z8jO#3U1Gb@iH&@)0GhXl?Rw~{z4&-dAO`KS6bDBB;;wUe70K|YkO!S5D$!lh&Ao=*J!Kj~=kyjAMsOpiCcI>HWrPPqE#dP`m!ys1YuFudb+ zV;1A#ty#WOD;UB1B)gY36>m}-`NPzaRqHY`T`imH1K{ap91uUUymc_XW|4dO03b)& z1T=j>@ZPE2aSOp);_mrJZT0wge@$67A*aR%OQCuBM;DY`K8lZbV9ZT>XB)=D`wObW zpP;^&^}n;_kj)8u+3njpTZr*?2v*(Rzv%34NuM=pVd>;TdS%HCpo{l&le7wP}{PP@QeDD`EulH@n z5W6Bi-ov(z2g1VuDlKDZ13je`3HN<#B_w_z`B6uh65#>;*Al`c; zEpYzY+6^(kd&|f-L?4pYYcphYS?60_yl+EN`is9k=pH{543U*6n@O8mtVr|4%`67!uSMe01M# z`5``VrGt~T$d7pbC+RjW;pR#Qb{jNi`PvijAeEnC^?Ji<&Ga5L8AYECxBcSAyZ_w( zCqjca^*AwxcXaWPJRaUFgzGo%K=9rhyXEUX1aBovSg#qu+n`(Em;f^W>w<&HW@Tj9 zGc#^>dffo1A~y#W-01`xE|>OPT44n)bUjLKYQ)Do=jLAZ*F}8rB{a{wzqSTA;^Qqb z5U<)dpYia{M0G48sIT}=Z1iq51&hhK^6{XsPDZ z|F&a#yh-cm)G@Nfd(fKtdCLG{8oa6J<1xH18y3sq;hnclr_3C|`?E=X1QqY{X`wes z2;S)$nOeih>MgI0PYvlI8Sd5jTzl{701&*MNAfA@1Tq$FDZ4_fz`obdwZC}acaUbh z$|^0_`QZI%-WXe=%d#naydyWPU~wlg9^R&?j&Oqd>Z0vWO(Gvi&no*77-mY0ciS=7 zSiLi8;N9G}H{_tlgsZ)z{;Fp(^?l5bH=R0C*PaeIt2(oKD@21g^@R@%?2vUqq8 zLc2Ju5WK&3J1S7|Zeq>2y#>MhrFb?p*cJc>E;QZVQH^|@_+5Te!{Y&PIZAt2=3yuB zTxOiI>x>nM>#JPr9EOj#-Rstsda-=)1vJmMwY!{62!BAzpEKJ(rH}Cjq(i8V+XVHM zuiw%ozl|RlW=^zat|!LZWr|ZsE#nqg?rh>MxR3bs7VkuK%@rx;zaULzm_8kwpEUKZ zVhN_Yw;&DP)Hj$gyz^kwC3tw}U2(T@K=2lOmsCUDoRD2*GPV)Hn-Zimbgnf3mN=KP zL-{Egess)d@_Y3FNI87UFX3?~P`L2oef4fDa6c_!ulFW=yu&%41)F>E!6j&3$%h{= zf4;|e@7#2IiIy71!}|=XBb%T;yGtA#o{9XR{`BPv{Z+(x^Oq*R$VKq(^BF!aIFGpZ zCS@;asCNEe@a?Uebn5s$6|@XF-tu?Uii)O~_AO}z#Yy|ZcFX6SY zh(jK+oNFetn~6Q>v5C?n%Ki+%rc}C|^B!>rNp=h{yju3Z;DGcA`g9CjIltsx{!9lc zPJ=h~rDP26{@Ja{cz9d;Y|T+b@E$y4)OP^Edo%xC(ZdMd4cz@aw~!7pYJW>pgIzScYD|IiBDD81#Sbrc`(<)wq~trzjbSl%>us-u1#KHjI5 z>nMlsFdp7Ys17fJ`nHQcpPSTyEU}Lpg&S59<1IBOVxj8R3@|OG_44ONV!TPcd%Y;bLm}g`*XQUNycf{mO?}HA!@F+ZZ6!Rs+wHcSs3Lf)46z1K@ouhIsjv&d z`}E@q-_+Lua3h#b?YU2eSvDJ5-EJBH3;b>fcwXuRwp;TXyz;ET9@h}*I2(MtB}sbe zt7h}VW@sMg_8;xgzu;Zqu3mW}hVk&0Ky}<9s81sIr_uLi0^q93Q;+BZV!T(UmCJlF z&H#bGj&)O#hzBInj!+xQP#5#h|Mcp3EY%wS=kpfxY4E0A8-d~NCg`Jxhqrp9(-%zy z?{VcOaVp;Pj%tLfB6zpko&UgsY><}Qd|07|e4Kc~e}Mba%K`A#Et|XTYA1-+waX5? zWd+I{W+`ym>c|hxHJ={hgi`Q}^EH9k{r3A%gddH3ON+F9YDkjUT+}aPJK3?Uyxv zFg@O+Li%)6EFY9TasBW9KNC##>AIltX% zjd+kcd3|pl;z6wG$cO%>0+6G18ckd;$uOtWv%8I51K=B{o>-?j+8c!GcPBM5oD<!`P`xFXw9v5=EP1mf{3o)!WfFPqro1jb-iP6YQNHv1@K!YM>%P7FfBE9$z2&I( zKJx>Nhqo=NV;ezzP26`wj(YQh16eNC9SX#F&x>$66MZKOMBh)2NS;HC_vPxY?6Zl? zzd_noNuLh;-|BC^pPQNg7t`QPy{iwyo8w~YDm=VLwoPB*Lh#N!A>dENd*s?=b|Qke z;)}XAjjsW4N4|$Y^#f^T((C;f6 zZZCdV0nIaCe)8)se|)@wWte}Z76amq>d+;qZ~QBGvb}~Ml+O2WD3Tz?d-byD*pz}S z;I;h8YRUU_ydZrm<(T7}Zl-r{(hWLwY{@R5?jRwX6B0CdQ!k&y@Q&(oSHZ&@u2=OD zLh!zKZ<`nuZ^`pbQ6UK4J+_a3%Jc`oYrOrn$W>&x|CaI>(Y66F+0yg{KHUj~EmtYl zZn6dz7o6_diyXmiChVogpImX^ht1KvwmaL^*688y|0n8ARj^Ai9^N*nj;jRq#Z6CE zE1u&AxI(;>g6;JCm0|IDxefIMR5Xgr8|pET8jSU)bcNA)|5JYz)~JqK z1oZ`Q?9@JEDFCt`dWE0OCGH?U0`u8qg>kod$ z$J@?yj!?c3Tn>aZ*A!C{t6iZAoi?fJSKt|Z)N_uTIu<@VEJl(x!x)|_Wxbt zrI#fnGe6#R>ey3bB;b-d(?Kqw!JB&HKZdu6{{;;^ya#tgL%j&zTOp-0RJ_$+KMUza zI!I;LJ$eCxfw1uRjW2Y2$uK21cg4p~17Mx)!I;|yo#4#s3xIOU8dO?;eYlr`k9U}H zxP;OuKU|LHIc;v?68aasubz8ZEH}z{15z-mBblH+?bbP$XP*!N3yfth=A0zP`>@LS zR}B$4V0ZVqQs@vd-kg5YD+W`dkEf*rE99k*aBg(;ipbz$n_Q`+NR6=`v$A2Ryb{g3*5vM)S%Kf2 zklcduY;H0h-s-3h7J~W?>=dYQp5{k7YQcpm#>9BH>7J|}eU=UOe2pGql_Q@2J7TU0 zRZ5>`diPF`qEE-YN8_C8$nloH=l}8kg)z|oj?DjxG#*6#Dizg(sPn(kZcBDN5BhCU zmy(5e(32E(4?Dzz#2>3HYeGCoF9o)5G!2Anb2UR}tN6n=WjSI;e<2;D{JgETvpYfW z)A@H^_gVuFz0kPJEci?830%r&`@#j_<7nPVlFgO7_wYUF*lIyr(ILhgkS?M+TnXy? z%5~j;lcxZ95?QQuPZqEaK$ZTUJuv;lC`gAJJA?Kjt9-YoK|(B)6oU z@%VUO@Lc{fq?YmUwnuebB&bg+B*TP^T(KJ^7xSrgfEe#D%^lr45xgB&`09V8=Zc+? z=Z<_^l9(QE(inX@I71em8~t3)b9pjc&lZPv*6*qV#Ff*0fP6&&I3ud2;N&L z20OWtgkN4RP?4|i>jEDDnR7WU5eVad2o(VlG0Q?iBQ$*ho z<1OQD(DG(Z9(bfa_-p(-@d0V_$H_epcFoabpuXWhDy6ZXJ{^X-U$2fLJ4i@#vXlmI z>W45fyv+eT3lHxLyoZ&m5xg5$N-n43T`jpQPz}MmAan5-FSS5;*YM|P10H`kKA9Zw zdvpL81WszX%OJP6I86!#U9bk9JbD8j{0rXob6o7wO$6XxG_T;c-I>~(_;|;(lsx`? zmhteeLv;|<_xx_y6%g}=oHeeFtf4-(Pbh{%E9>VJ*LyGI;nAnq&fo11Fa8D#_06FG zn^gCSHO(EMW$SL$(_DwZqIjE?$7=CCsJM?!x3^mWUV!H5hi<86-HGo($(cd7RnE`G zUDN#U{$s`ddxfZu6oUHVyACJC`0#`5E0cBCtbPFO*W>;8t@vEoyaffoQE}zloBG6$ z*w;gKhrd^xV0sVQN1;#0XMub{!3`muHl?+{J#d3bnlpZ=5@ir_sr`s@-a z-or*tPd^}dJMU8baO_whyn>V(cxt;p-2X%Efxv7EaJ;%E)Tgrp+!e2|dHC5H7&zXV z#gc`O_w|yRuIN_+@CG#RMAz5LKQ`dw9kDq&|D+q^;e8d=5lK*=jceA^SI>|Wq=Bye z6}yS?W(`d~@??GiD9pDE37kvE6+1(db>n8^8Ez4=}j!jg3f#K~J z-ZKXeZ@*jI3(g~Wr>%AsR{o?X!qiZ%OHXLPkNqnICUD zb@aORSZqgbkVcvlWg5KCJ1PBhIFWtXeGWXlQ%*lWm4M*QvvA{fD&F_gzd_Wuw;W8@ z7D!kH!cffbr^`0@!y=m$B0?YvXo%3Dq>Od|@u?@R2P_VO)&j5V!sqev=3OYE?@%TH zzeDqCpLD5=2;(1+zMoorJzt0M@a9Byln~S>DaM&~*FylP|6p4fvzQp~+*7MxK01^S znp(ph%Grp&-g0Ct|9DL%FVo{)G)kWi`|8a4XMQuwTS_!|#~4b^e7%Lb_r?W<&&I>M zd-YB3>j>U`iRK@vn-jOA%e5aMcyA2+CC6(S2p_zgAs?*i54R-nuCAIM03k7_46aUf zfG3)7bEIfjH zPjGm1dR#6)*s?`Agolq9Z`ataURwljmdD247B`6Z|4Gq1TL!ennI3Oa6n#2Io+LQW zzw~$h$D7?4>VHQbv1@2NDDj)gHLQc&>!QPt=RwCjla}sAJZM+^taL}jgEZbOSb7He z#7@+W+{miHK$utmh}sbYfB2zi&uE`01^9lvA!T#50~Gx@Anjmu2*fKy*JRwrACNjd zJF__C1>qz#udpoAb2SUT2h}a$J_<{5Fx>p#it2bqP~X-10L@9{6+5l#KdxVSPV7M% zGTSGlw?Pu`<{|{|WJglCc0eHfz`P(SVXHr^@v~N?Lx=+Qq#G8V z$>;#a>7A=v#Sek3Bggm#{qXT#`LR=Zk+>k7i{{DnKE8bS(@ETAAJ)-MS+&`Whqp4S zgN>lRW0pc+w!Yv4PNoW*0%2mj!*C`e(0aoTh*X89z4A5dKLuOBY2NV?|pd~!TW|)&f6gb??al`=Dqa` zgk$7oGh&g|TkCCh{f+z-a32Vt%_{5w4Vx;y70*5dJY2(i3{K(WZEZ4s@e!{ed=kww zoV#QN-!MMj*Onjqs!w6O4st)LBblJS(Ye1NA#r|S+2?z)HIo?cdS#Bi#%_1Oy2lM` zLyr(IZy6lC7V)injOp=yzmGm0Ze)Mb*q`(Nt7!1PY(M`t)|}Kd-{!`{`|vUs(PIeS zJYUY)QSr{;-lMe^S-rhi5G%gNI}pwbtY6T6&>s$d)?!x8LjgroG3y%P4iGBo6OqY! z2<-mO6Ms1pA8)7rnhmvVf-sh+(4M!cjtjpzIV}6dBJCyP;cbuVa3rWtc;8n06V6C; z@+e3+Es+@Sl&alBLx_7X&%Czk^@~TiPqlv<;n%gC!2#aPzyJS&P91Ve>lgpI-a>^2 z?@P<_xiGx98GCZ!;ce9BT5<}(yQbXgCv|h;dBe}e4hY_IXY@QzoeqR|#^=eNv+#$D z^W~>XZ{ZBT3xGk(fwOF14)~UVKk+kUm1ICnR zUW;sis`cGVVea^AkXJL3)`tWL!fI&VSj|KIY!8B(7hd}N+bzSmu0Pz2heubd80qhk$n^Vf|WZ{wKXgErEqqwP*s!pp>& z9i+81cqf+?6k&L~xXl&8!&}ejRFVpUcWOr9J}Ta^s*7(mBY2N#N&j%N350E3R-bei z@`pR^?>;%QgaXdSDp1!TVYm=gjq%)E%U#qSr!rc=OGfbyE|;JIKXl z$O*wa`up)o7G(YxJCT;);vNWZc1}0HB<~MrKT|E)C`ADsBJPU^y*hwDwEykwhC|?| zrQK$cmH2okhaMf^J0u8Cp?NY~rMxzJ_;|lG@;eiCf${K8LUl9|)TjDL!hB^JKXACU zzNT>=G2TbF?ce|LLLu;+TyAAsNJj@Lp2ha@-fX7Fn=D43j*U-WHn$@;NF&XOIt|`e z&3_AG?k!_}OArt5jS0?a8xXt;T!0@HZ_~cQS?dtI`=J-B?*|3KMPYsy*RJ!2-=&qD zS}Z{UJEUKq3p&#QWUM`ZDApVT4_C;hjceoM-CkS}wQ#o}{0PkxXdX#x{Fmlr)NA?j ztsabr_ghrQ7(soZx8ptq@CX2*Q_}1eBg6xeZEgv>`6RNu6~FIkqX9AAhDL5ym(6D} zeRFcxfIc0YU3F~OV`uPIqrv-%T#PJ+x2T_+03P18UgbxO5xkeiCkjyU=8jTnK8WD$ zyR+3W7{U9o%eJ|dddTwD&DM5SaSGr#G`C{xdsH5Z zL0A>b8?oBr@*95#$t&+n`lTCl;D2;6$WJ;^9Ypo5&42J__fCEge6FP^;yQ5$soK%> zJ%{%m2%l5YG5Pfg;d%i{L)Gkcz(wZwpf&XAh?paglQTT?hy^rw->M9j!0V$ zyw6Up9ata$Zl~Mio5vF4?Q5qX93XiY#IH*-TPQ<3{|~*(u)DgPi|GfX%dhFvF)J`n z{X*c({I5fU_f2mVV+`*cnVJQ7cv}P*Dsv-vTOT+mO2vE4ccUHq5xnO|CG=@<2g1j< zMBdAYdiD5|4&*+pN@vWB9jxy8>C2cqD_PMjqRr;F}yj=6X)aM?b*9RMg+loL;dS) zX9RD-);UTi5WKbcZdgI<0^zv_R+-cck>S>%iTk^kBksLIh%eTt1H77hZMmP87{acJK35>6R+Q~Wi^8@0Pu244Sn7y7NOJYER`X{n%UefIg6-9xPwZ@< z!8`kw<{k|1Nw|4SSS2u!pS6@MutyTc6-cgsYu!#&O z^0IAIH=uwTztXP(L+v2A{##kTtSxZS+qhVP9Ut%7?>uAH;X<%0npX!)1KoZ2ct0AY zn3fbV9^Ow;9YpnAP^Fyv%E}L(pD*^+`%V0ajdLD?=IRs!pT4rYxoyM;q@#AO8EUnS zW_rBIbn1|M!5Uoq=YX^x4c=L4pjj=g(yKDv|Pd)L<9_ufDOp@oJ$p_A>vYx`;8_u{so@J{qlq6j|TvF4W^ zmWB$!MQGkv-fb}O!pD2b`k?yBORv23%7 zwGq7a<(I3SpreDFue0yy2U+GnAT3Cz4vvLYi~byt)}_Hab5qtBhPPO7>|#8;P4Da| z|AgROXrKDjg$8e#MpMbnfdOzaMdSGi7c$JA(h=LUjsm_U$~ExJ?EubMEt!{lYyjs< zX@UAy{P~|ZjN7w;M+oLZ^J3mm*47!~<2~iC1Wo;7ya9;^)iFs>AFqexxvnNY;LH~5 zpIl3fcU*sCk8kol(0FgB_QAL(gv|{3yVBZ_pA}4xH+h6U9oElk zZ3=J_Wvh=AL5{aj`sZsU+W^}h<^DP6@bNx=XFRxKLJ+n`^JFbGhUypM<9*%YLglM^ z#>3kU)sae2U)=T4U~7JUus67j#UPIu?_e#yy|?)8ft^kXfdzMn@h0hLoSB!U$n?z# zX$^fkUKD1X;Bo(Z{{O#nuKa)Ydn5C|A&m#!c~kSx8swGDQVMt;H1w*gCjs%GCl%!V z?uZAqH;(!rLI$KlzU1^nePsB-?vGh(Q+?rI!R03V_fvqW{;X?f6WYOLC7bD&IkrGS zXQSCK4*U*s;br%Wr~ew)zig2HS}OBxWeMYTkm9J034;0#Syi0;KFJ4W z@yNQ!S`*Lz3k412xE+c?B{=x#J{R#7J5gKMMig({WqJ=H8`GyF-@^Lz#F?25(#W+kfq*fb8riUvA$;mbbPF7lv-L1^R4Sq8>0l z-V5B0vu&0Wf;Xdi^2!y;X|M6|zL?W`wDK(D;Vp*hxIj?fZNr{#j@mYgKM|F2MMt-z^h1*SjV@ma6KaU&fA(vI@T#zS|Qe*Pz!(5IvD zyY}tIt26WeMjE_t&-2@e;hhKXSb~SQ>MP0AN(67$zLYrX-rIYxm*4_|_geuKQS~N& zSZ&L*vo~1C@bGj5TaMz8k;*KY>Ibkp;SFiye@4~{(n#IvVup62u zbr{}t-w7Y@IXvU11-lpz?*dc@QGFqo2Tz(E;|I;;PpjG%665`*BfR*Fa4{$=aNkGf zBW_MQHg4S+@=S^8o0GN;^y%1cf5Gu&$lve({Xd)0|0{nZWd7eq<3aZu5MMyQ|Cbvl zx&qIG#CS`NI3ONmlpGa*0`Z_zV~yII5f5q*Oqss3h71=cChsh2^MSYAY;I_BrGUNC z)}2?kwF9?$(^op2cHmID**>@L_#I^QV4XWv|K4jT-!ZwtbvXzc6zfn7gupJ zy$6x{>D19b$583d4$@W{yo)cK|L6X{#X)V#czAnkcPw_J4oFatEEVquk$V^IMDTvF z^}XWvLu7d3vWjXOhcA4wEJ?85nF6|_p|?v9w1bd}6{cg(b|C5bF58Zq_>Wj&xeQa6 zav}ICnipWUYBW+A{}H?P!#1@=FyrAZi0aTFs87QLOo}Y!17($LTn`=+LHJRp1d>DK^oKGeQ#gqKllG>Hr-Of!#guq z`KLF6_wO(Eca9@?`#tQNwI9J-(tOFO{s?9etl4xAGwG%t_O`d1qnzd32D7TNCp zo$&@FOvg)t`pO)4UAumi4`|!nYzEUxKJH{e!azr2Ja%)djVMQ&C0uN86Mt~nsMKv5xlodb2U)+-sbD>G_pe6TV;8D zP%lh|(_pJ$Ne5q8m~UUDsx<|Wntunigtvn&YEn+KDYn38+3eUu|1$p{+PV9UteOz) zhvv!haMePDHxe>0<1T! zP}lq22C@{5b2RO2fsmU{**7gS9*=G@ev=`LS<31P5=d@%c|RC^RxrqzFp-X^ld>^#G@iv6MVckkK|7L zJ|zS{M)T$m_;3C!j*s`kv(3Bjw=v#;q>t(lBdE_&Bk=Gxc|M?~tGQfMj2LfeyU}=A z1n-~`YxY*jO2U5*q{BDb-I(01W=TQE$ytRV{?=lOnf8PI}x_WaJ9^N7o z+m38T@Xj>i9ri%*u97|#brivSyg4yb)yNNK;eW%j$<+roC=8gA@TCB&UdiY>iFR<@ zW4U=D$qtC-sgL`5;txpcf`32x?j{7!NAvs_EvXv)jgNP2Pb?w!a_{H|4*V*hvoVmnuRxK z+}nf(?*|emMzQ9EEObN#5AUC-aT#8j%M{%2pPX~Tw$F&H-Se~03-_1p~ z_ydyB(@j<8QjFJ}^r1R76V!Jh{rCQiQ9dvc7+wC-{6IQ(PXpW9ou)8Jk5eSF6#^y!eX_{qOJ>hJuI&1ww&BQpP+(|AzzZLbGZ z4`M@Zkd9owkA&wz%fu`?Nr(q|eoi2HA|CYBWM%y>>N`lbhrA85ec+B)LOZv1`M~b} z8-+6yDL{1Yl4FutZJ;^-V_$8ZEy#N#yYaUU{(#i3r)F!DCj{R?^RyD$Mj|p!;0^-c zGhnfz62^PPzC(445!81kJU~;pkQaoo%{Jo-As&#D8U}aFk1hi{eN(JhHxhf$iscf| zIvN6*-hvx*2+tCM|r`!9BB>H)5Lfy zYSny;` zgEw8w7eeqZ6M>|ucn5@^D-lKT-Y!|DlgH%?pYFR;;CRsoelY>Pn-@y~^QKs{jy!Jz z7x$NMX&T9E-o$MPq`ulSE6~>_bWV1 zTaS;oS-e^Iu3e0WcOj}{7eReR54$X_5%;c*p55|kBQf4m#-ue@A|8Ojxi>_gco8=z zNv7O;YSq}7-n}_?(x)SK-fK_ikeTMhlm_pLzP=q8-rE+asNvy#DN@K)`iHYb1Y|6}OM|4(tq{J)>Z zgX(TLWl=qdI{#OtnX=<~kcx=cuDYW+>!MQ*t@1`Z=(hOnQR)|@mLKR{`b60W9ywB` z>pj;G9@!Ug(I_+f4TH;` z7KI7MbR3XQFZ4{4+synPltG`49lIZJC1=h&V)xPDT^lCuh~a(MaV;Aj-g?vKD_v%!t3W~TTE@fs7OEqQpuUmIHA)fc zyg>PLoc5)c#CRJ$=Q^oVUJf=lvfHZMBp#5YbY_JNFUn(jyc_7$p%gLuc6GuG-j+0Y zKLx)#FuV=!j#sVE;2m;9 z`h7YDm_Px!G9GQ9|DJDq3E2)DzoWDAQ!PH;qD3dvcoDp@yvW=f-}O!Sc)tag#C|Sf zJiLWb9j^)Mi&o$KWu*@<*m4Duv#BD+`(V+mRqP1f&2!-~on+zxiL~FdONu9l>G7sp z$J@SJYJZluENJk4vSfZ5hPScM%UO7MpPk4q8$j^hTItqF-JIZU3;uZ=!TV5HVeIey zKCr^4FTBzczVJJ-xCfp$C}8e+QgO?fHbCBXHE8=@I}npvqAFj8k9Wv*Ax)cVA^1F+ z_ozetqi_d4-s{r-kGyVC0avps;_R1M0dH%V*WiJihH65)K3~xEx7zhvV@wO*s;|Sih z+3hY=ygjdMG_XhTW>^23c|Xtx*3bReuw<4mJa~OXh&>s(z2#I?RbhM^7;-e!>*TWo zxoW;eN4@d!9&O!}7hEC)=b?G~V_&oSSK{McYJEiW?gz%3|A$c>#RT*1kx4nI36Qem4h*?s{BLDS+FR>^e5m3hE#i>(ESlVEpEDuhvfd`Jd0@$&m*YLa-58{|R9}iR7MsHNcqpJ*dKsE*+K|CBuXZW(Fi{8oV2hUKz*mZXa1N4-apP59<2Y z5WJ5U$$a-g@ILoAQ}h*rw{(B*t=xOwuwe-Q;WR*o#n;9-@2;W%xfjjs``Ft+TceNa z3Tu1dvDK*I=zM&b6yL$CT5Rxuvl+fg0!3F`YbXZBIC zKwgkDNJ%JABF6jRWbTSZODe$0hsAzrUBr0To_xOe@mM9(;~l=0J{=!>_{ZzKXRf!j zqQSdvw+(|Z0EmcDBDKsz3v*&AHBtG7( z2_CV+IgE!lC#nM?s82O@JKHOF9uUP>DjzLHjCX*O6ZaAX@0NzAwfn+|m$%5gK5`|i zE0`W{(x5k8I+XbRMRHS2Iy;1GS~|KTERM1NZYA0=Ne7 z@wRALabbQf^7R%pZ;=C}wlxJG@0NV6>(4JT9^U4tj#mWrMb0j_ADH3+4-b4jW5iF4 zcd46-|HEY!z^8ps(jkC&d27r|!bBS6G5!2M>`k8z#XCNtA1}?|eSik!_jZk6#uW(Op5whYse5lvzMRYwNAT|AdX?EL;RE+h$n}=!`@!*d&WNA7O93wu zzSRhWHlSIZk?wli4!GwH+NoT{$9wk$Gx0v;?kzVoPuJol`I|33-p_dXD-XLf9^R&? zj#`5HxVQ>+#I<-qxb$lE0f-pyk2MnQnF!vblJz=2Jz_K4 zg!u6A&N%h@fE|Lj))&Qel4l7)@UAKvb&2lsg5%3CNUmV@hu?n}ofd4P01FFN zqo3DXfsg39(={CqKre0fQOSR~Vn<-}zz3ZgA$UES=LWe6fN%JCOJuYziax}6c=Mw= z77)~TPew#;YN3FoABBaW;#RQRQR$S^O$RXeSztw%v@@>TR?C$h9Y;FI0W_~y zY-*zKU+}hl5PjntU_895P#snT^(9MxJeT|M%u0_bj&@4CuD z{Ph;srS-b{ZHt-y{r~u7^y!GyOMBezH?zEDOM`dQcgPyU`-osBHy++sB*;ZR2;O^G zJT_7B?(QS-DOCCEF&X~O*=8EnNCCO)x03GEA?|%P3P4D65;NP< zOpy~G@6vrg3YH=69fjt7hHrQOn#6bS(}wTvU6o=yyh~6WCkW~jzj96{^)e4wEZ!qB zVNQ&<`W~(ID-gVwhFyQDllqi+b7H{7G_j(F`3IyD`g9Zv6i-~ZJTw2>(BR!zqaudk zz0T`27arbIPx48j2;S$eym?LCd$V}HGBy#xn{<)oafORFJnwf$#L{Hs`+sI{_3l2W z02j%n(}kU_pfqhuTQ`>jm|n4mP2x6w?=4XrY3G2P-kL=7?q=_@Z~K?SiH{N-Qs@0< zy!n42s-uFSKAXbShaHi;AmBhv~p_hAr! zxBT1FOZbo2;SQ4Q?RP>jmNzV#Kf56Z{}IbGCqXk}GY@V@`hNuf_x|h)s)MM$l;l^l zPF~{$UmiHDgX)PrC@OBk^-6jrFbogcup)%mgWUAFcbKUQGJOX*zL7p1<<9zrH=|}c z$Rjj(x0yUTi{Wj&okau>Z|hGRzbhbkX9zz(PQ^Q8?$@Ie2;RSqd&1)0O9d@F z{9)_V-=06mD4_DP@~kCzla#{8(2as!-DDB{i|A>8~qbPsujS!6GWgig{sOQAT zdufuz4JB#D!@C95Ax}_W-!1Vi@|N+)ozHhX*_a;h zoKgC8>`P2kF#B^sniCD)txP)w+&|zC+qY>-HhiG~HJ(k<-?z5{FlM0Me8T~JU*gBpw;vyGvViV` zsMkX9IGVS;({6`?Fh1T#KR8bDO)=hp|Y`mcB)Ys5D)JQA1_Vn zB6z0`?T+wA@RoD)ko80GW((-_Z?p4)e+62<$k+FWopdPKC7&rkzvX4pNxN21CY}AQ zN&GPA9)2gQEP>ygNH{-#9s5=Y{($Cj%V^7(+`z}%xN)2Q&JM=Idl9N*3qgG+I&HG= zA%_!(%AP&FmPL&B)ZDv~KiDdPnT2V)$KwL{`Vu)8OI4xnwom1ifwjPG=wm-plZ?+p1?Yb|Kv$tp-M>KS4IT;`C z$567!!ve;`n-$eTRNtliB$3)rJYdiL=yR#b#CT6ij9gdP{}8;8{cti@m>BQ8{jB_Z zUWqgP{J-%aeL9RU8(c~|7WjAn|G#(C{LlVt$o%g{<3S&NzgS`(BxI?$2+xDAlxdlL zaL!rxbyuK5FycY!dnao6kpU@aS6211veU4edFVh6O8^}4O3-y!a1hvq-I(u`{|>C( z=c5tp=md6DFHcL3KZ-lAzioc<^&>?H-i7APi_lPg(T49qp5B=&TX}eKf4~3i59j~? zuX=;(@FJ)$AjDm9ml-ektoQD$q{I~AlKJ&bS#PyoJ_1`s`jQ&6=~!a_;Z%R@VJ_2q z5NVn|9mnFPe@KXU0|akZ8oaxFC!;XDHEUEB;^D0l{k(Vp!CP;nrZxz{`?|8ww-pH9 zTORM`^&C76mxYxkx)1on3U$wNj`I!z8`GAM!K!yaV3{A!P@ofdf6=1zZYMt8=97YF z-v1PWyU;wZcbV5dEyTZK=j7*G+D|zc4{tM6$0>sPPS!6DQCH>zb+#-^M!1OamK@ua zQl0(?1b752^jQC#@SlU_jR=bV78E@k@`DFkP;q#@1{OJ-a(|0YK=Z2_&S<*Iek;H=o@_ZK2h!Hw)iRIEpG*) zIy?yKyV<$wy&2L$X1x~Ku#rTJcU)56`CtTZHI|E;_Hxt`;!TQ6HLf@)%k+4Y66n*B zdREzeAZ2Dia-qSybEtIY{y*ySR^rN}`FMDXEp~+2kpZbTpX)^+g7=ox%@W}V-a1CZ zIZBS6u*3hy-kpb2)wU1g-<1lPwt31JnF*l`mnoT&iX<75vB*5nREiRcP==xzQ7BC- zBJ(^)N+Oa?QklwcslD%aAMf#9_uAj%ec$i1_wVTW=kD$~k2=r#+~;+j>skYQMUY#5 z6m-^C(Y}Cc5}a_Ht{?dE8gv+@Z}xq36ijWF$WSyw=3P)t-)uO>1`*;8?Ax-x{wp$X z{~v?NUDwEucRs!jUzGf2d#H|{e8>d$aPL18^a*`HqCb}+{7d>J5Exz5FJx>$<=wus z6|?1L0>y7mn2boPBUt$QTID~tw;U(pJy@#t`|}nnysKNBxsZ7Os=7164D;r&#~obZ zJ#OVYe`{s$%{)|AlpGA*zeumFekBTu73=x#vHTf4jQGN4%g_&2LHV_tHIIT9%XT$t z?~pHVo!xtcie-omBE((4+Y%=D3YoX!Q4!2DKl0-pkFNtQzxXRv=CzfKpt{Iduk9^5 zZ@a-86^~%v$9V4FRVg81?@hJ#oy}Z2#q-8clU9ePWWlIe`rr5e|DR8f{{z1Qyn_rN z>Otc^Kb#3W$N{;{n~-`?*o|V5Yw!*-Mel@LEZl=8q-=(xTop8@g*}t>^8=x?(o%Fm zFQXytj*-0?x5GS6Y`Wl?4v*Q1(bPUWwk`IC+kbBU83HH+HYIcYaH~Y%&OG%9{ z;!+~gDy4cLmiz{!etaEbDEZN=oWK78zW<+jT=8~@J^Bt(Ba&JxeS1pB4;a4zh94NR}cGZZZy1$)-F z#iTkT^WNdSRyb~%4I;#8IBx&a)Pl@=LrrggjtBYi*2UMsfRf)eZmiL=6B97p_cXrL z3Z1vzu|v-iVcv>^S1#1ml5jw}=O|r(U@pb;#_S`pj)++4!+#D){fKyf*YmeJe)XuJHYdmF8T4E!q+j1l3#sO`oi3PCh%CiRgOUuop*L|dC8N`mta&YlJ?{j z`sPHBcE0YFF+0U~?_N66>UfYa(cWNt?^jSp=dI^{@?ts6Tc*l?lUFhc@Bdqf+gv^^MDe^aOC;98!ptyk^Y{7x|AFcK z|NOUrdr&A*51Mk`BuwZ*p4D6uNIhuNfxU+g!#ya*!1&e~xCaHC$tSj1ls>G%16{qt||b?ipT@1>?;dv7`xj3%4w>s>rD88Ymc1a`sS1F!e@ z0X>0HT1deid{3(naic@#oh9ZRbd!S}BE$uc^klG@{0nbun$IV`lHU@Wjjv-jN`BZh zsC{!E7U=8v_!}gk^ETZlktqxFKJfAip9T#&Z;YINs}mIu0`D&&#ha0MZ^79Whrql=ei*{f!^~(}@Y71hxhQC2uQ#W06$e0TUNdyw6NrK0 zKHXYV2quAR)2Cw-U;9A*?CEC`TaJSY@pVl&8BfG+`)KCJW=l49s1hHy+Dl%j|6jf! z+?NXjgXUG>_oI zJ*Q4<4G&0FTgp%DGYN!3*lJz`(8NHGrK4+Aw@-rPXSrV;>0X0MJ4>H2+2f#o*n{b_ zJ~Hp-$MSc_c-Wx^e4I&6+we9!jt$*FId_{h|Tkv&Mq2%}BX+sX{S5{!j<+z9T z2s&@V;lx{0XS$bXTTpq2GT>_7U#0x7x8N8_tK+~@sPKiPtQFpYM7%$xv-J^pzd623 z1c^88%Qb!}FmF}vw}UHZZyWdZy>N$l?-f5BE)fz4DX1KE%^Zt{yjb#L=M*QwBL@ZL zMd8=LFLH6)8)rB0*5S(6um{MOw~kD#&Bjo(L+|i$cf(|bn~xxGP8QxuhuY_mA8$e( zODOq8ck4&HuEK)oEpu(v|BbV^GiQvfE_>CZ@|IDjYY$YoN%8alK|op^vr?`z3|4=i z|Nm$8Cg&fVw2E0p)Pug+2b2+dPz?>698wPw+#xi~5BH$+3cI`G;T~iMWdyE<2c&bY zqBCsKTSK{jkLCG&wZg2ksZ!9=geAzVr5&9Avk~TD; z&hiQjZo|d~QIjwrO0O)T zd#4ox@vq;@*m!Ufly6RCat-VQK^J}%&m1}q%GmVl`z|5#cIj#67nWs*2yqVIZ7K@X zka@>b?R}-u-Mzzzcu!|gpCRzRxXxG- ziTA4tK1nl}cgpi|t`*)z<~gVMR`%W+ZLel``$N2e(rkU^G0=n9;=8YRPl7utqgvr4Jt$hxg>LqJ=^np$BPwUaN%EgIeG3jeX-*pczQVJ9iH5LAJPF#=Gzm zYqwJ+@T$HyR1-BY#9pGvQ`zrf|AvANgqj= z|2yfQtqHKM0eXD&+}1hh^M9nA(Z?^Ulz$B}Qi`-X_{6R>=KT0Q|F0$Dy&xjtM&PX^ z)v1WY`!Y-B;wPB*Y?pHU3U8lx##gFf-oe+OZd$nN4VCXb7H7O88iGF5bIycLf|Qu^ zZ9jW^!Os4i!$T+C!NNJ3z`9e&yuIh@B$T(XL-Y8!OFd^ddY?n)-F!W1z2!Rc1;Sr|x zf!-!OG>A=%hI)%e)g=QaK|f~r%#PV!@R(=0RL{j7_!q46^2tEvJ=igK@x^v_h!AJu z7%r_?jLbVNPT|#=8S>jfzQNa#j*?%4ooGuzITo0UoT#XLfzF#lDSAl)=A9TQS~jk^8%QuO{OC{rpK; z0`I!Vnp==~@8^cwp*ePP<6GI(_VE4Jo1+2iz>*xwLJMdd(_#Xjrcf`9!93ot;oC+L+?IgeL;S_ z33Vi)0=Y3{KMDYQ9_BK)={bBMV`riAfdWd4hK^BVd-Wep; zk)^xZHa__8`9GPAp#Po*yu@z!Up+`@)vhMxl^(PXeg{d-!^0S)9`rg;M>iebL00go zvn9ekDB_Ue=vnv<(uX72E@GR!Aiwi^a%O>%(68Cbx86DMBX-lwLZULgASM5`%pH&8 zK*qE1@hT(a9b{|l&Rs=6*dQr<+_HGD@~M7r#QA@%WAuHdAo3fK8u4||qU0BTQ$Tul zFBaHIJiFI+9lZy=x85e{#a#=+e^h)a9VOuzq(wwmx*V2Y95iy?YG{@)Db9@>=KZDt3qvchn$0ros|=K>E3H zi96Ma{CJi6%|LJXd zmbN-sf)u~RVs?^N$5CPWOS^x+|38N2fAJRl^}aHVzs2V2IKRWk<>@4>+epSc8izsXh zph4!%)mk&GLC+3B_&A$pOG|zaWZnXSuBv=y`jj+_jS{2c$97M7)2NFNP3! z#~gD~LE`<;(6O!(<}D{K)tmtHuAKDvauUA0m6~v+IpKj9)Ridv;?3142orp6{(8bB zIK3xM$M-}pxau`X1=YBNfP(`u@@mMNlK`7I9g~glNk)jT^?*hoY`}XQGGwmQh z-hTKx`cd*z8M~9dz=s8Q5?MSP?~~5^)Xht;F6>0VddqzolppP+r})ju{&dpnuyWbY zvUv9Q{J)-v_fo999D(;Bd3%nO?OB-jf?~eE zoRMjbf=qZHRz5vF2`2TMBf4{X!Ge;g{;<0{5FFDp!TrnUEje+u)}IB~A%1*ZtWsT( z8y_<7Xvfs7Hfi$X&5p0*1WJDPrb4vJ_VD?CaPxb261ukxkp6HR?%pTH&5g^`Nw|8; zeQPM)fQ#aJV>n2xqlGO~8s2-;!@IM!tFB|{1!=X{AE7z{|M2hs$n8%6USgU4R}T_e zpESX_(t}p!|E?;pbx1uZ*1D~DFWiFyPwtXQhI^1*Q}#zG_!}fQ*B81Esdzze4nMm; z?jH{Adv7SK{d^LHyfEXE&*%a6H%(u&IC}sdy5y^Gw2+tB=itdQJN$`VLR_I~zwjPw z;yfK`$sYPE@XQARMw#&b`9;XcCCL@JKZ+?*Tlwek=?%dw?5XL$CMs zBl9-&IF-=X$OaMOMpiB94!uC;UHjSk!u~4quyAeSZ?Xf9+;M z+tUL+r1CA!$9RBMXQeJx)gbf6-npeC34gtn5O-Zgbzz|unYXb**Wu;+1P3pPq>KntP)91m4{0FIOY+E;2e39R~B>`0(Y#%Hf1`b7iVJ{D8EjB38ev-xFd| zvKwKXh=4xEZ9cFqe-ilEO`lYm?EztXZjM^*@BllQvp;H8AoG6J<=93Gf1F4MAD8P9 zF+4wp%-g@B<)+nj^5b2JuOkE{zra&(lxkX-fPcum=lUG5po^+F3cK!mt-Vz`8RBF&pY5gU{Z|;;u!MY(nSVE_%&KKP{f(dFyQ^t&Ynom?VSfzxV%>+o=Cv<^#|F zY(zbXejD{YLJulxGoeH3LHDQTs_5Y!6tVuB@I|->u~i!{kHGUkb@3+e9|V6(5&$S?$X` z733at>WgMlBZTzpU{;_>(dCI+9TG+fHL}FK-G9#$_zTk7c0uAUYcX>q{lI;3&p| zLuxPjEp~~+y$lUPl>hy|q7l;SuorXJyYuG~J1Y@yx^*Qu0`H-ZJR6XB+cg+x@W8xF zCw{)T0P~K@uaX~zc}whIpLZGag0MmBdj~bcAjRjYo}pcn;Fitv_-^4IpgM2#aLZ9o zpk>@vTHlJyn=|*y;>-m$h!7`ye0JoC1~P9G3H5T^Ci3IWimziYN`Ciu4h-*;V+O)! zS4l)%LFau<{tj&x%=`Tfr{2nY=u0eyuQdG8@&k%rVle_F)-gXKdgbWv%Udi&ylLC{ zBnZ5NazD`^@jh|e(^eej{p%}ay~6wCt_PRiz`QTlvPy2g?FBU?%NKOUgh9e=c@J;3 zOoE5ruG95eJz&D`wK7J{6I6`u=5pP7g^%~f?10`H4brPN5g-xX`|D8sx(8rChW98P>>PDtxmIh@Fp zt)sQ_f@W};JfmG_dFn1-kjf&S3s2s@JqnMA(+rg#M#```S zM2M3-T@B{#k$Ioa>7={9iu`!n;p;eul3(cC{COn@cj$T?LKE^jGQJ^v90^S*u^zI#*O~-$J_Q|&Y;6CmD&TpMbS{)T*GY_Nx%>P&--qgp$wF$i6NW`p1;;pDD zp}zy>y;mdqGa}X`yfU!y(pyxz&R&C&6WJpNYY+96sZa?`a-dh6-~NGJ zPi+U8K#D!pk~;}|@BNsggL3fMn@!lFWaVx2+gtdYQ@%h;n<##BqU1-Ww|6>yD_>3x&8M>Ks+(CV@MHiuft_ZZJ*#?tmSa7tjlpe52Zd+=Bw1 zIx!tS&Iak@xr);0VThqJq|KX3i=Mx z>uix1t9BjOdQvpVVF`T)S#VajPB!cX#rL2s38d9=(o@dlMC$JoBrYP}%&QIs5_rEz zWX2-#ZY$&w?t*#$GT(bY1?K(vY~0(+FmIR71>;9vdPBUnTN+;+35CiH)wg=iOoD~g zmOSQXyTKJ>hn>!Yo?z!E*TVKJWZr3Kj3+1kVcz&SixXqdw&o-A?#O65d#8Z>cqilQ z=tjveQQneW#SaTagTk}&Ncg-($BCcVMy)#V>&A!cj8{q6LB7cop1@U6Ja5cf(&|`c zx*9C~x&NP&h&NM1fINZs714K$NW5iVP)85Lyl=i#Fj?WPraoiv6y~j2+4^npvNz-$ zsh`*u8w#!OWiQYDJPCxp{%EAV+YNG0Z+Ni(i6<~ny|vEvU*6ubEi%gBV$DxLKHv$Pjiq~N7?31r=Q`!Z*Sos;>~!C!s4 z##as}1_cw3jKaM4rj$NycJ+qRd))5xmxe;d?y0xljZT8_isz?o>$-vK{#MC@w>;s` zIOG@i{LB1*E5YuY`B^rI5T_b(BE|h9GVhS~k)@ze^5dP0uOl2KKSmSTQu;+K$TQ8` zc_$rxbE5J3aE1%a+v(V2p*B7eZcYrmWAxVW0p-vCK_u4Ezs^|c&%=rAM7$YXwkHsH z2MGkzBk?Y85PGu=^9~g&J+;F7W2e;63U8-ag;CF8|3CCaW4}}Ee*t^+=;H$Sv zJ7Nnzc7yKL+XWpxo`K=*>_RjY{-xI zCVU-^DEa*=W?gbG#sb4^%#D^bbl$q@DRz95wO~5)IPc_R^s_fiW{WIug%0I!PO?a= zqv`Z5wc>d=n>OovWw(!6Gx&Qx{wjw7|4>EYRcqS6=K@GBJ zahKp8lr7}CSPJ(bXWByo1+hMmxNPXH?vW5^mbc7GfDH#`*0fDrXzcf89nHI*1Bo{$qo`d1%sb`AstYT;LoU?|T!ndC{4l$D!^H=BF~#;>`fCU@9>3td zpAiSTEd9b=rn|s6>sLwBX)j-db4A7hTt%ermMz-DP?V`&UJ?^457_OhRK!2DP?vmkW?;$=TV3(UD-EVFS? zh2jS!>QvI|(4uM7Dv$epd21sPZ}w+mfWX`1P#YT(?^Bg;#jn7;#d=wlS9pirV}B3> z^JdC5w{g+(feaLOOi`^3g=n8(PhOzGfk*fBgohcsL3${=M=9h5X8kec5*En3HyEy> z$}?hvzT@Lww(&m2UPk6^Ji^N*Mo)gcsql5|M#<0rb9woh5G-g9b9!aUpbtZVNf4B0Q0tM>(v=z^ntc~^!)6@8ww?z=Fxk+1_!>Z6Zx4d+YJmp z@7>pT(+dQg$eMlQip;z4!^iu1j%-j6K2EgGT-gWy&w|j6{`Y?#VLwweh#^1TH}Q2i zqU7gf361ydVFtAQ_IEi*_UI z3Cp|5hh;;d5_N$Iv!ikjLo^nI%w%pHN<{D83>V7YtH8W(b^J(P zc#3}ZhB-G9|Hfzs#q-7_kXFa3qZ{**;H$TP=l}nGAt1wlhv)xIL_LU~rP`d(g97Iy z_>g+glH|ST%5V=7*3W&F4)-9H`R%cE@DrpFXFqJ&_Q(gaX3{!f?iB(BZg#U~lg9y} zoo}}*%XEPs-5sZ&CV7MKXX$yNvdBHixq6E#Zv`tvh^tK7^gs>1c8T;SD3*`e=p0Rc zORPP<4k?uU-m~xPUjx4&EfJ$-Awt3>_Fduby(%B;freXkRmThoJ*X_)u6)aV%I`rW z)-h@x!3j!!&;P zKmsRDUGp9J_LlN9k6s&mWQ7QEd!gv>Lo>*{_vpMy_OKy8-Vg9~n4#o%k5BsT3>y}7 z-5qniPQv`ZQES~7VVL)Kf4N)gg5ommU4*1?hrBym?}F z#0E??$G;(hiFF317qUCh97BMs)=r!(8u0`orEb=UdU10QJToRuV|D+E&0K6dV& z01mKk3f<c!NfwNWk9-^dZyIw7c10+kGr~8VaS35dH%;H#w2s? zCO_Wi@O7}FtL$&dH4@t->KQSz(#;(zX79v1kg#0(XLqVuM%f0(rf z<~=>vi5a3rzk3TKU?`SqszC9)F@hx4(RWu${O|k!kVaMV`gwT%7bogLA`I;DgdW79 zA-oBx2W>KV_lAdXd1yrNSTi28D1?fw-?iY0jHh^naXX4K=k*K(^7YA*P?{tDQGb!Tbjou)0L1XKzV*9%ixBY^*zx)%p?h~7h!D5u^PI`?eq`R|G1|%ZQpt}u4Ze=&DEY-Qb{)2Siv>e`>X0!BueVG!;#Aau z&)!B3(N4UNt4HO1dV%J#z;(+1_I4_XbwGjcAz!2ae*f>E_D0S>faiZ1q8=nk`~9B- z(ofog5=cF$q2uG3EOgpQ_nSieP!N>kV4+I>1YvoinVSKEUGrP-(vj@(yy!#O12`Gz(;jkBc+=buxv{1M$DLm-Te% zeX?v2x&2Xp#@A7elHYzs6S4bYOyEgaY+(=yUyxo}?rNWCYy^9EJnSqyg+3rf)~m0M z*jY^ZOKcr!b@V)ccYpNp?_iZA>)47u_4$JgP3lAp!YS`+6NOyEJZ>Fx9<=sQU0 z=KBpI#~Z=p3eTJ*cl66!Vw~UJG73`u{6D}!S{)hYhc0O*{^l)3#9QqC4i^G%eSwkzzy%)!1>o)z|inwx1Zos|^R8$5Df`;J5xfd_ReISj#KL& zOZ~ZeD@nwAvu{=hfw%CtQ=&+`e}3-~Zi0EAx_A7*3UBTa$KEqA??%JUfn9n&kS=Zj zQnU+({2uJ%{Aq~;>qS)JC3kd!wXBAs@n?O&jEpEa@IIr6NDx`uIAAQ1WxSb*rSXjtP{7-(LNNgzx`lWUMXb7;FHKti^RaHlW|$ z5-G*;V3ULd#cxg`B}uEJj`~OF zx(K~{=N04}TNBg(UfaH=U(`h3dn;CO-9Owz`QP47C$SFO)26tv6MygjC%4V|f0++F z|0@vnAi3`^j0io*J%&*ZsRx_sSd~v-yHap~oIMDD_Z!CJ4!~#v@<4S|4 zRioff^Zu7Lz(2WzI(hO6{Kjdd|NlSr^W6A4cB150<+L}}uLBDP&ld{Nze4Xp+g#u2 z^~*JZr^3HN#koj0K?1k3-QR0c{1S`NB(aWkqXR47Acc9$6Y-XPRlAnJJCXaX3=;3d zEgpLh!@Rd2;i%1mdG|A`X77M`<9uh6pB(XqmR_{)*R%|R2Cd}0WukFF(IIUs)&!pa zWewMQ==p+2A_6+n|MLF76a9*TCAlmRA+Bj^FuN)0I3n)`jIiBuEcx+{#MjY;lHcb7 zk36IESm0C4jgcbZ6T4>9JH5r(nn10B#=Qq6=sQSE^(0oKrk?V7*N|4n`UCdVseew8 zwh-}_NnBzi@Sc#mBaOtnCX&k66Xs1fY45wjyVPND$N}bU$rh|qamE|+7RiWhj0l20 zUs+ZP4#j~A+h1khygESZV2cwF^aTpRc#b5%HFG_^^Y(yGT7;3W>L;1oN>7nD^?TA%PX%25Zk}or8HZ zcNeLjD)EMJBa7ah_ktisBNM&H{y5;+r+Th0r2`n>)9_?q@C7V>=lhQT%gu?$1brlv z8(APWe4IC<0rMpWyVDWE$qdXiA`R}9qi;@xhUI+2 zVBYx$2AnOj(FY`qi=SnWjv(cCZ&K?x$$T~A&(~XIiFixNeYi^CT_wI#5{b9o{mkzP zFz?Ls`)XDWCw@h4HuQ#hW47JlxYFbel}|Pai@pkiY__bnnfHXx|CKiQhnIJNXqAID zT#tM}=}_dcv1sJ({j<+r@8xS2=pjB%D7&z*mI|47Z(rOOK27rDy@0QyA0@wcrCmaA z46wjNZa%W^B|7hQ%yW(=O^slutFQ*k8}w&ym%_&}!wWYko_AsxX?57wuy%XFUvK^U z{QrMy>ilo~zVLvgLeztlCZ|&gJ!nJxdL^VDq&mqILIwAr=9=y0IdBiUBi>Cd=?;H` zWOJhareoev@tm@%l4v0GivG^K`dl0^)8Aa_<=YPSkKWcw^!5ey(q>gG2FUaOp29=x zHa0Osb@;fdS-H48A0Hi;Z>9JiWa>g%9akQUK*_PcU$LW1#Cz-T#qR{()y6*+ zk$CUvPt#?Ec@I4mbz0%=cxX&M-%UX?xk0#t*V-G>FB%(P9Muk4yiz2VlmS#BUbah6we!jBdv~Z=FDT+ zw|}4iD-rQlOl;jo;H}4UM*)d9uLbvlFwA@8XCdza+B7h4iAV#7N<(i*$k{4p zIxG;%v+#Xcn1%yavW%HipS1(+121OoeewZgjyDb;SdGkE*z)_Om`P^nBR_wf0AB}MeuqUy>g3*F!Exc)h||63yo*I%3*mH{Kr{`Lb}R{RZ&@xn zcqYZml;ZFIk07xQ$BeTKHBrC2_f{g_3by^W1m0`=g5;5S3vKiAR)Be*jd~8P98UDU zQ-b8+2c+p5Q@&r8_l9PqIG$EM3WU0QSYHcXzyV#FTl05^+ChE!7Tb@HeE{#QL*&5H zF~q}!Nc!xMlGQ8_H$HA~P1ObNv&g)8Z}izN!0!wEZ*0r{M?%B!b!S&Bg!?0cX-Mtlwc*_d~ zEE9O=8LMwW;$8NV?zA?{J4;Q$bA@+D8SXF#JpaqP32Su;dPASOilFNPLC~e7YtEtP zaKPM7!H#KN2bkm&>&X-M1q#ijsun+yySFO#I?az57Dyf+=f?h^NvHt%>}@gwW3u}x z`SDi4*MURHZ{nWkYitS@oMZbC?bU|PJA1(8#W;NSR@J|FUM>gy=EUcjQN!--TPc2X zay*-~IvVatiif2BJ^%k7>EZvUzX?45s}uDgwPCaHl^(QySlmfJ=nw{}2T_ZttuJvc z&}3dCZgLIoLGeFiUKGLezhSQHGF5>O)GHXzxtlQ%QfZcxJp2NF|Nn&9h|K*q@J^(- zAiCcd+-4nW-S`;Q{d|Iw)&L-$$P$!>}5!PgOqlArgU z{$XGE{eQ!u+h0eVq;T1crX}AjUlmd$HL5k_5)e+Q_ zvFcL%?FtyMA4TdDnG$|0;xe>l?`kTl@Mz zFJF(SjL`%_5BSU4uRexvZ&@3v^1ZJO+$bnjV@vl1Ph4b~#ZMvgKJ>1r|C1*(^b{XQ zuT4WGIE&1?IJ~f{{3rP>u?O*W+(XGP(et>{8w)J3|0p-iqKeL&pDJ=H3Fh5*CTBY* z9r_ZBx!SnKWBo&l=S^}Ql21~%{JFhFm5BHDbH}F$yxksL+=j&aNX+dEoiOkDO1pv; z-dtbSvE6}r2iU7!YnJtao+$*SNvsQmFb->T-k0FO!82cR)~njVbZ~FqETbQo;A;$Z zvq#=R3fdRm{cxHYBE*G@b;q12J%-rTRz2q)UYa03-u(DFmY@B5eszrwF?nH zDEzFrB-Rc>)25H~jrxMKjPsRi+>m*Do(r~`zQzm@;_km~SFxT%=FO+CdM5of`SCuE zuY(sQzf%u;oKnZIAkL`Z)B`4T-UDN2tt&K}!6E7`&goR>UvJr;oFF%0S4{D|t4OS4 zeOattP5AH2Tib|utMKOL6L^P`H-eVTWWOPDW217onYQ4=Q%_g z^6L;+HNsvUV=tWX;?Z8p-<%vKt&VUeJ!O@Lf9L;y{{G4N2k`u_P1J+5yQeExdeF-J z-)O#f9a0Z^Vl|Rs2lpT+-;M8b;U4r^?PVzrK0(rFcz%=fg)ijH<*9SgJP;aN{lbRs z4Gx^st2gT!X$4Vyj60jI`h$*ZPI`2W$UP|E;L_y{Cd^PLKCU~7|4GRQXBd!okS8zRl{wN&e!P$3>xe5f< z`$z5O3KGxaQj!{{v}{2T7}AJS4#gO8C8l)Fk4q8L(hY;BCM?y#|T*UZKaF z(J=2-2b;B4c;DSm^W6sK?PuSK{V3xL)oQ(6UZWTYWinMBxZZ{XIl6**2UOa?3!e)I z+hYB|-88P<@>9r{x3tnP#MnhML;3i)oth6`P(MNL-rILGT~w+eKi&XehcZfj=QR!| zzJ$AXsE(CE;eUhoMxHCx$2>{6yk#4>Weuw!#SchJcBIt->2k|&`qRAu5pS@=PwF4u zW)-WEc*{iO)Fi{a?FTM=Svj0ga+5P$Ih+U-(mp5I=mXhXu!?S`PygnP&JPE%K%>q&>_aem_iomlF)xI>H(l7#pWB*Ac)dl|g(uScZ*3#zeKJY8 zky?kZbEEK|tG60NyfxV1FIwRD-k0){Rw3~g+p2LP7v?QiAelwX`!c4)2iNZd6{SeZ z$+8DRCu^5B$h^XVb*!Hb-8|C<1a@AraFp@`e%Y4s>pGFUH(lan^lC$9h!B_R9LVe6 zhTOfoaXb^cQsl>b1HO(9l>Bl)Z02MK6QDa(uW`y8op*I?jrR;_1vZ`g@+?Vsy#>aD zc2oRqEsEcJN0L}ac%Ravrkj7~f0A0pe>w=B|92AgApJULT|y6%xS~&o)PwrO1I9MM zJt)MC(e^sL#8z`Y3Fd=uvD+S~WvdY82iafVvD~sF2+D04mhPFuf#&YcR4ukv@WoR7 z*eHDfV7pj;>Cggl4-$OC_;J@OEX0A2lUr56W#I3Mc&+VKf6?O%Lk{Ra{m1#g|NewJ z(DHj|uX@=GenA@cKyTHLYV;oT{k!~n+Ll%zsx4NLR#%Jo=kiZJ(SaG`_ev?g2Vr7J ztE0AJt+7J-?-L|FBHlZ*Bj^ddFIMqwK;msQzV9n9%-d8R!@9ydaWGvX0_HuClK*tZ z3Fd9@dEy*R5Hz>(>2aH{IPmNI#!*FhN!T{^x}T=QADDay+@L&<%=;P3;ftN`v5+Y~ z?$gEoeEI9hys4HEBq+JXUT zm^Z83&DuPe_t~Yj*hQH4%)zs?4hDWukhNTyRdpcb^SD5)cM=DNKkvcuy0(H|hx}pT zY=1C3I*}&$FZciZQ2Usxtzm{f;NvXLYew!KK<2&0+cY9Uiu`zcRbl&f#tcn37hTf9YoKswU1=TUS41dsf^<36oUF7*+ZL}lxx)?J=h}$-hvno#oc|f|b&ud$% z2>J2ej;|vbCBN_XOOEaAD~A&^7cW0T=Y8dN7(4b3JpYG$wiHN2=e_Bx)KGNqCW_yj zT>M5_9myksyKi%!TH&oj#9NpB{1SopX1&DqNW51)?#~s)PJvJj#3X+2Jq~=F647;g+6s~_g>rXp^9P^&cl$_eK<1sY)y{re znHeI)sVJpGO8}X-`f9aKH!AYueF0yG8cKdHe8B@4bNK%MYdIM|OVD}CC2-i%!Mxue zi*zo-k?`)V4FcBs{aYxWH-?_XI{Z8sR^HzF_xb;SrZ4jS0o;R(iF%Mp>*Za99whhP zh#9E|HD%3vl)4mXO23n7y#e>2{ozXbHZBU9+#lb>q;K?tw#tl6)b0p|7A~v4RAHS0 z=0b~x)`87nN%(xTXkq}67{jiQ-GV$IdF4dewr#~iGWfW4_0?ZvIb0Cu+)Uk7E=RAC zUk~!Y*Kq|UKP^#dtqeM5z|Qb9!FU$E2T|$PW!t=K1MH7fLvB~0FR>VI5O(JFUCQr4 zq}EX#o^b8YD|U>Cc<)NAxk%uBxtI})#QXKj{^?gR@7t@fu`9gO?lCTnt?;H|J(8&7 z2d(E3?7hty47HdD9xY{<0#;U8ADh~mfx={!$dR1^pgito!OX^mjs_0osB0y-ii1+(DGZmA?aSMCKilUCPd4Qp!1%8D0s{!unkBgUe4y? zLZAOX6z$%B*Hen(=l_fMNvmW1q*3VRGr!OO4T*Rg+wMvx@P4HIh7pPP=1_jaUYPgB z+?(nvyhTh8x?X|bAg!eFL0ZGj4=T=7&^SIC1bt{LF4m=)0(7^ZjII@L0b;HJbbibM zAVvC)kfb6q@AACuipgGBC>B=?nv z!28<#Jq9G+!Ut*-$6?-qPcy!*T)jPWg+uZ@{D5@lsj@pX>3)z<`(lznK@hY{BE_(3 z%@pW+X|{fAWD6K??5_Q|><=bYV-y-(k$D@WHN|9I#6r{fINmf}dz*S>-d=p>o-sb; z$6Fs?2U>nNGj4x$tY88gbzgn$?L_B&DQV+&d7(DYbo78L#{~NAE$_Y`&E>4;rufat z(i~}ZuyN>?>z@04IH6C(+mPmd34yoel~eRcynV|qK3#x$hnO|qUg7=2W4CrI%zLcw zwB^Zjevl@0FAFXt2r7x1hfIFqfUn}^&Z@2!aD@7`(7Sv7fMKhfT9gqoZ_Fu{gZX!{ z5EDMmsLau4&oDCY_qo+a91oEnZ$cet`85@+JDIl%3w9<;m5#Qd^FFhYvu_>D`&LJV zhu~Qf=KnOEb9)CxDV{eboy0n>=go`!o&U*q<|ob!p8xj{^&qpd<&%US^pjPQ6R8K$ zahlZ~gnLkvckK3Ca1ToCj6dNB4@fyL?lrM(^@T(ZNsP3~hd{=2QM-T0Oo5-JD&Gal z8bQG>u(RGG04(?Sv=kq6MLe%B%P8Sauw;VP4*ZF$$-_$DqIW`^|D)6*`z-F0Uk@t5 z*Aa=5pP0mz%a3TVAo**ix1{s8fE^iMTYUtX_tCkI*Nz@c z5C=ZaBDn%1q=3xZ&Q{CC?jrf|cEQ(Si;^EtRm_*mJF(#Qz%GF_IdtBN?c0l$SGR-U z1&hPyucGfDf!3R=wGwg^KOnu(CasQFu5s=i7k=*`cN6j6d)Qzrf%kis0X8JwR;!rL zM8LdrIS$@g;eB6@*Ki}ud;5;$dm5*Gp$#oZwJ(kYL$#{on|(J;0T-d{q0pmEU>q9l z+B)D5HnW)N#(N_3X3)>LnsSN>lEKH}429aZI3n|&sBAD__9s8yboe?xq2#A9Q?R6Z z8Vf2sd&*`7(RuTokl3dP^H#MKUa;XMVFy`x1j23FO7XlgFG;K;H|l}dpBto2h zr(oX4gBq8W7kr_-1=GB+vi=__)t$_eC>jka^Qwxsbo9lKgmUODkakJ7MCX0x?ZXhu(5n=`_iiGwj;f!=8fw0O@Bb&vYGnOSxCiYg>OlwZ zYe^H9Sj(+4d`LYAt5>@Amoxl=^dIX}Zo@rDvNOj=3En|I8YyYiV!bO zs#OD7JEy=ic9zCRi}hgjF3$#o8-YORo5QHRDe?~T*x@R5Ts9*lijQl>@(f+ufD0`d53pOLmEF14|lCl9n{+ zuhbR^ryq)5gSW@fQe@ir#_3ZBhQgb5Smf;3r1m01$i@Zp@&GZtmNW?hQsO==y?>Y09%1;2NYW<YZ`UI=tGKV&CHV+!!; zi_O*EZ2*#4RCGDCf#68*r_j)y$h>!zUE5nj#RNIw+n{Xcea~h&C20KO>SI@GtB$5^(wK=@aBZN?CgZG5qvlyW3-KF+Z0%(DQD|M)d)^b zF^XZ^13;jY!|S~Vk$Fc(2)*kSW`aWTaX09{$uSln^Ujx77&!8Q{CJ1s>$r=O-|_s6 zEfe(cfHZ75+ir`_`$%mu=cddyP|bVd@x`aLsJt;l?^}-Fctr8MG4DyM;{^4yf!vVa z-Fq()Z}W+Vr3BvY(au~*ymN*vcj?2t7b7F1R(M+*g85LGcS-LH^)yCb=vpc7XoOh^ zWObp@Q9yADEQqI14p=pUwxz504W0*pWN-D%<_pNYRq_Qx<##YasrWb_wL|ku^T@pU z+2$ET+Q^T$621;Tl>EMJI6kv)01MoYKJzcxfzCVlm&wP^V{Je<_-3W>FLd5n$+!03 zgvu#?{#Q#Ot&Zy_XA3n_|9=0EuzHjAKjHb`il_(K-R<)r^q}qwVw;e95KDyffh>6b zznmK|bO-K1spn-fzBnmpChXoY%qZ;(={@dU{<$U?iaKvFo@p}$?w07?Y0|C(!rBj> z<*p6_j+G;qF-Khx=k@jd`32fr86hWpoHCUz_a<%!#HFNHLO|n^5EtUF_n-PZSc9*l z9VNf_U-PSz;7jc4DUu^eKhb;8lb4Nldcp8LNXsks7;(HK=mBczY zrDzrZoFE+};%)1f`1=b|D+AIGm02Mq-g9yl#l_n!XaZSM1Qata-OQh9tk42KlHUIYx(vpa`jluJ5Lie^Cs}V%v-I``WUk&q4 zri!##;mr{CfFTd&ee{D%EfcFR^u17wQ@be`N*AaMiZh=Am8(RJTxRQl#+2alC(R%b z1)WQ2P(kMX;|$H2PmdU(llZtBqF49Rv>@|7P_ajoXNmkSZ+*enVTO`lhsNTnP!lYe z?zRlR_yL`_t-@oUXJKuiQ$(6$Q3L(%tq;F!-|Ws4q4)ub17k;09ot2nmrwk;LHYm@ zZ)>()3;*zzN)$liy(jB|S$9BTWhXjsPQOZ-5}3CDT~l%Qvl>12XRyUlbiId>ElX ze4Kdwdasyu$h<8~D?v*e`H8*qxwM`IzP%-L=DB_$I`6uY$B9&KZQ$dY zolnbGqhGzn=sk{BoqJC4n-fy&XpK^RdNA$p`Tsxdjhue~&;NErJ;*72-C9Bqf^0b? zkb02FqwhLea1Xl3catt3?m!(K(1E7Vysjl07r$9+4 z9lOk_8X#{Zp=ZV)4BFy8s-=8(Mx589w$rlnf1`&w@o}CpADDUBjvy{2A6C;Dlq8Vf zfE0nRV*n*Tz65nARSXtb?x!|7{}sIl>0fWWKGfR=zFxFloRdV~L6(K)s%vKyQ+yAy zB(V+^`K@c!&i)>dY>9X~dWAL-cylyPi6QZh7IC?@59VFrzpLXe%sVC3WQiWWyye(_ z-K^=kWi#b&( z_pPaeM(as=#SZr%L(Ldcq=aN?L?M|n zg^+~IWG0CsW13_NnUW+^)7g5)Jz8Q)j=fbA7IB|MvO*uJ8BzKHk4q z|KwTsrTck2y7#)*T6?XBw_C9BmXuUF7U|4*cn?y2h~VT`EG=TWjadLl7Z@9e(1CYm zLVU7eWi#Nv&0E}8OUL#Wt#LEbhWWpHi$JH3Q{ReM#0vgY?|n3QJ3>BuDBhorhRa~# zeNia8^9X|XXwhXm3f|x#r(pA*oU=o|=KH=FVp z1R3`1*moot#L7D!mXyJ6knFPf=F%H@;W%pC{w>i4mzQBrZyAZy4Xig~JiM)`KJ;+% zV>zVq^HZ|`_yB~QIDX<+?~Er8hc_aN6Plu%b$m|ZH%Q02HL~2+Y0mq>$tayZhN6#* zyNCVR-eN<8_x`r{6)4^&r}nJC!h1||g?K!IcX!0JI0bLV5R*BJP7wGxbM|46J$Ch0K6{t@!w+6~jv5zo zvu{dz9J_jZt@+dxvyt)eUQP9J2q(XLx=;AWm;``9@96PcKj_E%+f(V|J#P5ZTbiEf zKSUp?%zM1s>GbhRXoIkE^uPT-Be(tk}GOKNAh_ z*~A8efz6{&M;n|m`~R&OO(qqE-0%l#oTbOXOTr!dG5deX5cSneQ;b)GworX6#mTRK z?~I;M13#E%m3ov-AZY*d^TGJSnbax!$-M>i?w%k%`hj1AUbAlQlwdEM_cbVxojxC5 z!=;h~{w|O@(ctaot8fg(dtcr78Z5lk%AAtEAb4+mr}UXJy)|kmGUSBd?IdTQ;2G!( zUkRRQcvj~RXVhz_GaV;`-F#BzoeLfUhwf=T7o%WsQ~c@%xewTQ?<3iNcOB-2?@;3o zY;4Nm<8r{nd-x~6`;RWh!yEO{kCPw2%@X-nNP}dh#ePp^4*wA=0pIm~hv3aCcEJ18 zg$B&e<)8l@eItS2_ms_hyb1ku`p_rXQ;yh0s<$Hz-mdbO15vyq9v831!dvi?dKf!0 zf*i~juA$&9muj|O7{NPLMwBE`;0wpxV4Z{41;7H6NwwXPWU%FFduxIBL$L8uWwGu^ zFi0C%{;jj@ApFnA|3AK1GkA8-Gi4t595pUp^uU6X$FT7x?a9f|ea3irucrE_!O0Jb za!eSw&kv-Q=lDm_vAw0E#%^f6RSS3_xlhq;2!97DL9dKg_{;o1-hy5qpQ{aLTrd6U z{~c)XcKMYmi{c$C8m54S_xsFC4x$L&2FYAu6uf5}7bg}YixbS5o4i~*ePNBQBRfm) z1;GC9o?3aKWMIK34XY}@1Izwp=IBGp&Ab*#{t_jnWN^g;9&7O=_vxBveigCfS1$OzJv zrUv=MbDdWv6<%~Ikd{eJ=ENu@LY(b4ny;^AZ z@QpoYBjCjxP;O)|g8BXaQy)I+!v!b57l+$!^dOJe+bmCn9|_|3{~JF9%9wh!0Moky zrFZM_&mbWb_U?XnvTpv@pd$Kwyr~;_yW;N%@(>N)-undqIYCNr`|EXBcyC$wl_eFy zd)3s7AC&1Wp}Gi{7sw7$>D*-*!#{lBz9%b>+FbR6qaNv{R-7jT=-l(SNm>nH?CSoZ zokv4}S83_S=R2_R?%Lm!zCVo%M&qsrY7dpA%AJn*zjfw>XU2MFU z#ML@vuVy^F^Qb-qaPnKNHY|5-u^JXk7xMr;g28*uDq*z z)aU>Hf4Y5m^;@0(dwa`48oWKekKRKEC)>f014GF4 z)}fAs#)OY|#wD)N zyyGok$MF>%Rl@lFzw}oR#YEAy^L}trG)Z1WC zzk2AvMV=UbFkup<>j&ZEjm)|D#36Vq?^&j^pq-BD{e+mRDgIyZ?(I|hd@K&VHk)zm z-~RtU)pPzY{kus2?@3dG0>h*-DUVooLi%Thx*(-Hca*;;BANaq<(n`mXf3u>hEGve)j~ zieH2DPG^m=IJE$U!`&sib#$yCJskZYb@#uZ|9?cE506&!-A(C#R**bs@IJD$@f13O zbo%^Q0}F3|=3Rbk5WERLSf?n{TMGvFIxa@=zSbhFn<(K6+dRLyP)^?;_OBm{I$1&n zuXE@0jos=&E00Va7(U>_b+U`c6adv{-25h_?jxLFexX*Za zpQQS*#>tPr-hK(^5<$>8GT2_KhL86}_CyJJ?-t;rnW)J(gOB%@9)}y>j5f^s{=dAJ zJ|Db`{T@pFz5nkp4c-BZnDbD)Yvj(TW8wYg$+Lnj2;P+&it8zO4;ExUmqYN5t?;(k z!Qu-~6#+mV|)3U3Cf`s}EpS@1u8yHvWp^ zg!8F!Jp4*?pM|k!Z-thzaS2~zJiH^RK6r5QGxaX1xVBpWWS(4Gcug4}@1KRx_c>(t zwz@l7>Lwkxw-CN6gesq3H}CPL*T?OLi6-Zf6(nSE;!cCNANg20innK;iy9W*56reU znj?7k>bs>-@K(|uV%mt{9idRObg0({4(eO0ua@oyS2pG)oXsPHbyi1RKgrw&u^E>t z9I`_|#w$o~MF=+Dx!GT$F1+D{Gts!U&)teGvGJC>+`Me!BIDtGiRwcfC%^D8^VW$o z0${M**~?iLAMaOo;;~0`T0qIc#h)xf9`=E&T*SOyWctDN zb7^9nIb<*rcMW=W>^?BOQ8yT%7Xl9FRA;2bV&lDh%38HSkPAlRT%TG$t&70MJ9vo* zb89f;;k}IN!v`n7lQX;c<=O;*TijPoPYHaykCxr-IfdY@@2dDXYB?R76NRS)b05wB z=`8}iK6c49u0%E`@*s^U3-L06M}l(;n;HtIZHrQVcg=siN9glmbol7Y0n(olqz?_=q1+#WP`sJO z$xK*y4{E8;yhZSC+n{olg15@FLBKNv?>U3Y;>>toxYUH?As!I`H_g7kbhCyGG8&h? zIs5q@$Xk&k(HDs9AdSje|Lqz!-nVTYg`5pyhY832#`V~)J%70m8}E4bs=k%cjE8qE z)kh3Yeiyg(ZCUzU0Bqgr*&6SLkN3NogR8%0qFYWyJs7f;EyK+nU^X@v3ds*W7j;UbqN&n#GPr8nngA=85ud^RL zVTZ@5ac4|T6;qDx!>rzsBg>c69br7Y*HC?g;N+Ls#1&PGod0hb?W3x@A0O|RkLuM# z5WKgZ{o3pP5x@T@h&x$!0F!x-H$jp<9}d;)_gUursoq{Rcn4kIv=GJHVqp>y3vc#K z>v~y`{(qC%nmrV}S*v4jen;@`Klr`3Y=b=YJb{;2JFQNvF9^G>UTKckJPxhk50R@7GN($XV#fJVAf6ISz&Alu$X-?SE#Tb^AWpL zC*y>!FDqT(dk1>WaYuu=szRKKpMP{sRp^A zczHyegyA<+}u10-UbdDTsx3g?1K8sB8v@tVN<=)Y0_)}yjLMB@W~T0 zxJp($@p|uFU^{MMuv97pyxaV;ZeS}m-g}nAD%Q7H;UQ`q?=h!S`z~VR-K2AmMU%{U zk61&hk0&_!ZE}im_*upe0vCLk?o7hR+iG>rGe-n(uG>qq7uDde{}bds3kqM-ocDOs z>%*q#oB>DPpAqB{8oZ-e9yOqN8>)?PVBsBghqS>T!8?+vEsTOU(|bvl5d?1;8_hHo z7hiap6(LIfR{-o9TqyPVAsI|w+(o=CLIO#vv%|XH1%uxT4QE|Eu<=&q&MR_ZW`kK* z|BYMtRL8qz92@T?(=x0J8F2TO3f0FVocs>e*W^A86aZ2WJf^Ep;p5GpP%83sq6IWx zy05-x5FhU%nW9s9&no6U-p}atVQMAe{NnEm(g8GhN4AJuL-Fo%t7ON*+of)~@ks>l zJ1nw$DR}cvcaPjfHb@s&#@t#L?F*laip;Vr z!9aLvar@^SY`iB@Uq*PCvcY21xTNkqk!m}!7bn`5$qx6vWW4GMz$Mh%qXrxA(r?XH z*B&q)-f~nQ1vvSI5RFc3n&SsN%OIY)Xneed&Zp%BBWrIt1LY2tp${;7613+iJN1i` zuzJh9Uz}*6)5r7evup32`gi|7`txV#-;w@5oTdiFIhq-vHAv;%Wl|kd^|<+hby`oZk~NZ2Bw1sKl3VT!QRY< zhNR|D5E44G>U@wrX1}gB7;kncjs=dS#tFus_wG=(#QeXO@%VuKwh6}T|5d3zF5=`@ z$u=C)hm0VbI&4<97vtBUmDl+WlM7n`U%8|FT2=g4>;^C8?aA3zKksYMc{+W(6x%$g zd+JaBA4Y@s$@R5=Ua_NWZwad96Trf|IQU!McLeW7&vPaeygMQeNP8oA4|24V_+xzF zne|J>+!qJH>Y2itA{}J#jsMOiiO`!MuEilfD<~AOC?2mrc?lcun3rb5cCT4rPHNog zM9!U>;n;Y`N}FFl+|PJ;M^k;o;N)k=D;w8)l^=ZN5tAkt;Nv~&amcX(!MmC({mk0$ zbc`V5NnCYikLEqzk#Y3-sA*mpAanW82r`rg?-NA(U1;^5di@h5I?|u zza$qQZ#El|HPGQ!&;`pDrO4pp?U$c^#`CW9yl;^D^XT)z0bfiBPX2>;2o2sb&$+gs zc)vbT%!`HhX?FcoDFkoxi8lfiyfqi!4mC#>CkB@mKeFZYg;$bqMZ~fnfxEL;PmeW| z0WasoNm=gOAV%0-)rP*CUqJ(Vddpnn{ddvF zjE6TT)rT2Qe*R(4p54|E04{zDHMV8rZIEKksbnr{P{C(NYi@epv)VzzWZ7#nXPEr&r}WmY(s8pm_$ zuKp`QY`pU>kC&<~WjwqEsXi{@M<$<_sH{yo^HsN80kZ!;zWrrv!gKr@)ZP{lm;SO9Y)yZpd|4X527R~bU~TljKksYM zB07Djho?39ou~Bw(GU&ZNeaWkDBfnR?7~=htN1?VKaJoWZy}Go4>PH4{Q0W=W(4og zQnO!_^S$AU8DYQo?0#^{Nn53+elpNe3>l3*Q3cEwxITqg!T^ubrjA?L*myTLju}`O zF~bX}aqWe#>^8MwAr=$N5A(fqq zs8;_^4buL%{k!z~xSZ}S^SA$xpusyn>GA>;?BY4ZN_>w}wo6kU^ zeGtL>ip%gjNiiQd^`%s`s4sFjQTVClgf23WSR7-0cc=#JD;DYwSse!0@|-Vlnqkl0 z?(^;1uCtj1=BCE=oF6-;I)aV&8tHaUZdS&_+lJ}`FTcTE)6Foly(K4Q!IIC{@bTW# zx4O5#x)mG_xqHs}BmV9!f>uakOzeNb`TunK;N%W6x4ZCf|Np9tzo>BozxbDgbDCq0 zApJ+p$A3O!yc)Eg>cbBwKQ#}*&bZS8z(cU&(IPT_4caC;o;||X26lLLk{z<~N088+ z2gR5C%IAH9lz)ppAMf*q>!BlmMv!bYc%KpFvPSXlJn>r;3-9T?AEI&y-sAPqAqw85 zCHqTPAb6iE9=`p4n>XxCW-e8<_JO}O?;xHTB?I{f2Xrz#}J%CjXU?F<8_G%^F3R;09_Ohr}g~%~jZV5A;c7TsY5ocneW| z;N|D&^2=5-K>&E2A7kn1$H%+<`Q$zqs14{!DNr{FCtyf)qy!P{h@;6%HgH*7EK zD#VT)l=jJU@3+1oGLT-AH@02&26$7Pz_MOG9OMQkc&sbL#+%!D)z!z|OmG1;uI{3> zX$2?t?5*Tyf7QY$#>1P3>H{x7B~S0}x|agruB-8Zgid_CKYyH7&+lmkn&al468rE^ zZ+Y#v*aA+R{|BV0)9J%!ucAp4azHvV_GYHRJ0-I9JBs(U_fAW&@NPHE)IWsaof6tE zO2IqUHn(*-f_Fllp~TJu-f;i+X8UXEzHmp)2x0sK8N5`u;@~rR1MC~CR=rpk27XHc zIrj-{yaT0ol@C-g!9?l5an?awSANmO#@pUv^X}s|jE6Vs124Z^k=&g^+=Adj?7dH{ z?f7^Dmz#UD5xkQvC3}S$=vbUk98J+!u08L^-UNDmd=$K%iQL}8$*WE1gLny?6`c8; zXE{%B26MV|+Hx9kZsAR(gM>@wTj&Key4hIfXjvX9o z9P%8Z9K5`1d8K(5@v`%L=NaYc;d#kZ&r``$z;m7_jwh7IgU6o7m}eW0DvunG2oE>+ z9QSALe(pBzhupQ?CEOX@i5vv>N%leZcJ{~Yx7bVBv)Gf_quBk}o!Kqecd~1;uVEKw z7i4EtuV%Mq(>x%VkSri(w07b7iw(Gi1|dTgxWRwup_L^*ie*YY*#7)_T@T z)&kb^tZ}TNtRAfPtj4U{SXEi&SVdU5S>{+iv-GpHu{>m{Whr6FU`b?&Wbt8fVlijY zWzk?!U|G(>&jK-jVgA7Unz@nr4s#iE4s$AVG;;v63$qooKC>3H60;=pLS|N`8Kx1Y zE~e*9_n0b}@|n&uonQ)Pa%Zw-GGf}ow2n!JX)zNg^b;C~`k)r50jh?IpmgXI6b^Yo z4v;Cd15$(JAyJ5zJCfUn+lkwpTbEmdTY-ByH$OMT^@ZyL*K4jut~*?1Tsd5+T+v(s zTrONzT>4yETuNM$Tno8aIcGRWIJ-EXbKc{dGhq3WcId%yvNz6oRVdiuJpp zU{r~IIky1{Leu| z{VfkNN7bZAd^Kc-s?U9DCm~Z*k!!igkO`{BV=nkW#;6+Gtq}ObGp z4(X!moqhRfNC#DY8jm=k9jNLh48=j)QPth5D*|mpRoC^YQfMox-g^C(g|?uobE9r7 zv>8=zc#^+E+NkRIz{UXqRJ9j>SO96E>Qzvf2DAxPZB~V?kS3~H#p72(8&TCf^dkb& zK-J4z4zD3~RJ{l*n1s|&^?dh;4zvMP&m^QfAXQW~%^FWa>rvJC;DtT34pmRigiS*# zsCv9Vw+32^szg9xggx4k@9kq4lW;q=>5frxi?~HK?k0J8TK9MpfO0#g>o) zs_wBK@P$^Piqu|U1<9l8?xpe(XeFxdI1MU8a;Un!EmQ%LMb)h(Z<-+)RMieGJPoZt zRZUr*KO~K+>Ju3`kQAz_cCqS0lBlX&;-?HrpsHfHv)CH6u~QFZ0siF=R;s!Gzf*g{KCRczf62rWic(Hc7gNElUx zPy{!$2vwIKoKJv+P?eu`?f|q9Re6V=&q51Om8<(p1`t>_gQ7@6cz&UQ{`4Z0I8Ppvn>Q;UjjVYJXe&3St+k?617>B)&zJ zoqw_&u@hCcdZcXP8&vHRGWbq>jVkMY_PfLmR9RJQUQKLAm1VeI81WUVEOd3$iEXIb zySV8Cu@zNjpK7XzEvPcB{(YR-j4G4kM?Ml?qRM!`-g@E-RPB*m4_7R_< z%JAhy1L9Lu86-bSBQ{Z$l=;SPGpHCp6{5=c^3-#v09AX!c@v<^ zs508Z;|}GcYWI?`V^AKd45s8Hpj=ex7m1famr%7UJUtxBLDf#9?nWpZReD0hR!|nI zbcWiEpiETlxbw;n%0Sij3qPWvi>TUW$)W|NqiU;MhAMOcRhuWWoyhVX5~@_W4zGa{QMInwbrqC=DwP7Q4bUl6tqru*g5pu7yzRLR6o)D$e$}sG=+gKy0X@%%4K6sG>|aK`f}EbmtH=swn$pAtqE&wiQAUswlg#AR?+Ln^qtK zswivx#NVi*ylqRILlx!aMB*=0QQqYu{zMh!)feIqR8ig(Abv*`<;*VPEUG9+91&+w zML7|M_zhK*12l-!sG^)VK>Ug-%E{lvFQ}p%luVpL73Ex6;v}jl$8ZuSP(?YlkoXx@ zl>5VoWK>bETOy95igG&*aSTUO%$}Qx?5dwi&fp!o7{yrZ*0qW0B zYVUz{iBQSE`~T;`&kUJ^ORUIY;FA(xG%ggTZZ}l{!>4R7^;tMocva$|77lT699fM zk1KxWAZp{~yJXQ}u8E(mV3ABs$i*`J{r`kuv8&Lz;BkE*Z3!OJFT19?YFOdL0rHST(*LWEnXaSN_GkEhLH<9#Pt zD8x;T@$lBB`nZjg-z_(XeQ(zY0-~6(bM)j1k{NpX>%nGiT z@7y@=Uyxo)r;iZLge{qoe_n6lqQRTeg`#+8_1uxb!h3X;;@Ou7-e4~19tCfk!R4D? zA$UIs%4ro^>kaGf-@G@Y#T#Z0DOHE2$RKVBNmIC}6oeShU0!@C9FQ_D*i?MO#=G%s zQ+`Ms5w4@gSx*?>`L)#yvwDBX4c0g+$#{4_qxyJ{lb^7ZTwaX>a(k;h+xz%m_;~B6 zSFApR;GKNRP1EQ;9Xm+VgPvrCsm*)533U1hu*hy}zVfGfbJE~VnN~sZ-ZYXej)iyQ zYzOZL1aF>uKT9ci2i+h}79e=<9?@Obtl|ypq-|X^{>B@Y7y0aRe1Z(P!!{;-+ExbK zo!&CXriO#f-S)<_g;to=+pKW1|ScxlZ0!O3_DeLf~{cYN&o zbG&6V2Mykoc|sI#)hpIwSa?6a)FAc~!8*n_0GQ^zGrjp0A8)sv`t@oE-WF==3r=3bU;mH1 zwkLJd!1j5MH=&F^AKFR+iQ@mh|Bu(gF~;8`{l6eh4Wg`+pfzZdj+8uB4a(j}Sf_^6 zpbZ|bt8O4QXyduoxE!Sa?;2Jgi+SM%tMzP^7!C4)>;3O;7yCg5-XEP87&=}8r`X@i zYi*7I5n+X~DyPgaAF*{0%s2~o&XJB%)nmsDWJK`y{}cMfKJ9k9GXHB3y*{>AM6LO| zL0W(YZ_3giiubzUk8)UeSD(_`Xo%pgqU|O|!5c(5u}33#yML*1vj6A>CrR}YOLcu< z`R_M6RKAlzd`9$+5Mmw(|9yvJB}XK9P-?qeBEcLJ@7}>Zp1#E2q=(eFuus3HWS?N; z&60f1?@J!z;XO$8!HkpN4l@la$wLAl*r0Fkh%`RlGRjsXIx=m*3MgsTDB$=11V^_s zyHix>e}hD)k1W5kuOc;n8YF%iyeVthDBdG0D`c_ozCD3lxrN|;V5her1#ezg`L)&v z-naTQHzyOk;U^k;j-UB`;4u5U4QpqS+gn$9B$9IS!C@J_u-g+6K$}oLBdN9*6Yuz2 zLyD7ize!uDaqC)Tn_Stkr?+?qw5!9?84vH%R3AJz`Ry6tVmquM2%hN#xSv^ukN2^f z$>UXv+rZ)&_Ql(_Heo*1&>=$H)~2IP!};?b?^AU8;Bd76*&Fs}dW(++Z_4Hj6z@+5 zj>%x*oooH{eGr286}cd03f{wORaC_gyi;9%ZL?YG4KGhy@NoL2H*7W636{?wv$s!< zExoa+0KCuyKUzB@0MwS2uS>?pn-u9=Q@(=$GgIR%vc;MB4Y2V}jM6DGInQ`_*HL{W z;N-XWNMWr(xBw_lyseqM7$5J^`z#!V2;Tkoj<5R#(NVoat@nEuXwCn@Nicmr5_cW3 zlsfmPdh^oYP1$XP;+=hF?+PruOUe>Uk`TP*RuI2Z`u|+<$UTb?yk~k2o|suH+jX?_AFnhN)}X*B0VS*&q+?d` zzR}^T_S*^%Q_3TDSIM$>amXBG&&i%wW=}ogm^tL~jTq!6sZ;)|kIs?7kxt)Ia)dyaF z4Rfb1*y#&^0;Qb%bH?~JD6R3yx(3r_+aC zv!2S|{(lh--jof*DBgsr&NWzg6FmK&^&xn_yq#l6!JG4D@!mHG-bxV~x|z$oV6$Bx zY>9i2lcYa7P5$~t1~dL;`imZ)0X|7_!*8HSP-+|hICQZICf>VKr>Yeke~`+kalg;1 zZI7+M##>>Fe?@ga%UW$4-2_XGH{--Pq6u#Qd~EWEbGS zK^pn6R-@v=x_RFq5gya$|Bn`;!JD!p9>rVqaM5Zkyje0yNz(}4&Cl9& zD0l~zo;28mj374;@CR30d%^G3QmcFy`oeyDY~-8~ywzW?{OQel0kEoMR(&0f08tq# z4mppo@jidZKl7RNPtq}JoU3Q=g!)Hpyep2R8f$bi9^M&LA9(rISaLs8FcSdsCt4SK zY{SP}tm9f+vR)f_c7NaPX?^?^q6}Y=AB1$GJw%5cha)Y5kUNAnrU>5DQ5Nlz1PLAX8b2fk{WlyF8K0uaqQV!m40s< z;a0}Oo5|v@54`-wRPGb`E(w5YRkfjDZG617=dR_QK=AJTJ^DmcoQ}nbGv252mr2k6 z!O2-VeQ*~ZQ20AISwMp~<((xIZ`sY;S7G7pkaA$XB!c&C?H#HVyu(uEvMLe0`EuER z=hb?_w>R9B5-ae5IaG*Y)5zM}fzLo_S8O&o*I}^!(TNBk9OCyu5yD=33sLGw`E=nI zX$dvXRy+FlkP$ZCtc2%>1@AE)-VszEc=?^sY|?GrCjfGtJ0B*hvi4S1 zeXLk|7k>3ljq$T4Bwm{Lc$4V#k+hI(RdV{@^Z)+oy%_lmvyEopvWO@c{QX#a&C5Li4!{vt6ffZe}2*rmaq`xYW+KW_1PUxesIi$L&;49Z(AE%fy$KuV5NoZE(a(ABqVaMy>B$Y#M?eXt@`knX;M5j z&b{s2&gGHVc;^{wRhb@Syhp4P)yE~g{JfN}^M>*Rz1}{7u7mh^OYXgDePJPjcVy3X z=?eTEq=e+>1rwq@^B?b2`h1*9oOy5|_fLZ)LW4Kuy?PYy7b2Hbu<#BJH%+j#W%E5!w)VKRlFIG;Jw_+v^nPJQJ}E#qeSVOaImuK zd&BR=yD{;e(k(UJUHXkAOO4wbpnULm0XE*|%QigUYQuPV&rp4s;^ZgXtvx-lRRD;{ z2^z>d;N$(I)d;rJYy&4HXN`)w@bPX?bh(!N&Sc*A|DsCt`IwRZu%bKa&-(uo8oVh7 zMWA^1AMjg?g*ShJUv?IP_ovBSHWa+uK6nMmAb3A5xgvHp$phAZ$1?53=?CW;uNKoq z@b-*ao^p%n1ZWPF85_P64#syp-t4&12ovvy(Exry_ZiX{HID0G{(X~XY`j;bhWsX4 zFdp7ds6M1|^5f-hx*rpU+}<)E@A=vWA8&8H64NjQ??$rb2A^>J28nRUs^rCfUps7KWv!5t6hy%GG z-TI>~0jma)77Lyn+J9AhVvYTu8noO8TQEFUoA1&Qyr-YOF;d&$1~}WkZ*-sY18&OC*bX6h+i$na>sAt#BAce}saj~{xBhxbaVj~1N#e6&~S8!r$9&gzQQ zE-CnUC%qXnl|%48BJVL#LZV{?`Lf`}fz9)OiyfhbP9K|$AEhHl>>|}$j0SJY>3k^O zY|&}zSa|PtB@!1QBgn*nfc+G_W5RbO^dNYzHOL9#>2d?!9@o$B?DhkmX;1g&B6z3B zTp}zC2?I-V%Rf83i2&!vl$z_Z^f2*0(lwC!@#z=R8EV`Pr^=3-o3Zh>y^!FxU5oMX z4yO9B#>r2>bX|x2P64po$h!OT34FZgrrB>T6KMmwZ?bZY7UG}YvM}L!&$a%w^S(hU zrqc(+TDHt8`cMDAoCa^oag!+C)0wtvSa?^xuB%o+@UA)Z?9bxF8J!(Al*I{w#Eu^p z>F%IS+(lfg#t%e@wrV{>@Gdwm;(sF93%D&`8(7#L0j8KUTRr4JzRciA?N zxy~1KRBsv4t(Q8U&;R@XWa;y9omc(tj=$GiETh4ja(*g`_Z9cG8?f-+V)lINRs`>$ zMqwvP^+xe#cD0ntzU>Z<7a5P#T=4@Z{f19=Ab67+>n}`PGyvpa&E@Xb!@-XW+y^%) zVB@_*+2Whtg|DRV)HvBIYxa0=#KwEqnVUr_v5eRM@1*+B!^!UzkHeCnqx|5jP#(TsXQ+=4@%>hzXm}WggCXCR*+D9 z_lbSJ2>1IT9VkyZ4O@3l`ob&(xVx5xkEa zS5c$jEyn62kc!}~?^^g$|K35cYx?Yg!*TwAte?JS*)KAD=F6Jr7D4G??-qytQyt*| z3S7M^d80Na-uw3swRD7%Nd#(~*J!kE%wcT2`8L%bXXj)*yq%~%IC1iej5<`WBqRXZ z7x9KhSK#CQv`4Ejr~$b_%Ke1R@;o|5kRY(>ZRorCkGD2`KD^zE&7S;S|Cgr0n{viK ziuc&fDJCqu3j+^rEky7h?ql6T!FwG?4(SGhH|eIB`)*4Ykl%IMGT+}H9Nb!_eG9>x zr!A)NrO`Q%Q;|32RS^#IZw0+eKerhZ@1UiXj`D$@NjcQGkxh;%dJ))o>mRx%YxI@z zMv%c&A38YsdH-7XNZC{XSVSgPTrbDR`!(_R%)3{uAR>W}9VsvayY-j>u$F|LTya^BJ^r2Iyqxg6Kza$Oblv`L(ytS655V7zk>_1x3jNr{) zo?}A6d&?E`YwF1C?bD3b(iPIKV7(`NL0Z)xctk`Q-$d}vEblVe_bnO3`R-L{Rf+^h zT=EOZj@vQu{uVA+zVio(-P&4#q%8+a#CvCh&AcH(6Q*NXNT}xRsL^*?`&M;F)0eQr-?iF_o-|PgQ z-wf`J-w*(J)n$2aeIvtP2|0#x&k8_XT*;%Bj}btk;lsn3bIO=CNHAj2XiDTq(o$+% zu=!cfLMQAR1hPImOa5TI8nl4wLjxzjm`jHH=5z$WK-9u759{%3&|9meRmB~x;KPs{ z??pNM21)vf@NXs3?Rj5=^dHmb!-oYv8SJp!|5W)= z1o(Ml_`PHJI!wGzz16pyXr25du$!~kTk>bNt z0U(oGT{r^c<83gbw6qGrJGpGHti}gAMv%MXB%hkq&wIQHhIIPSIJ#ri-x1_W8oVht z1)_M9E`8*{!h1XSXp1_6cT!&+8)XE^Y&^GYCxW-j)1wpdl?Q;bp~#BqA%76w>8#i> zONL*`D{fHB%mYJ-ja(xpk$|9XA3jsAii!7Qp*_*lc_XBsYJcNgf-dbN1z_VX*m#%Y z%PiyJ-AMJpi<93e(XB;SZ3KYk*67n+H}Ub-opoQ6FxCp5ByA{GDZ*d>C!`H_=iT`) zXpm0R=c7L5mSk$dpXx0~gE!^sOBC-j`%2ic@V34|jxj>;4ikAVM8TW9V3CR~f_H5} zWsl1RXK*s2NcBpMKPZf1<2d%6U>`h+jdv)=jdk!GLU;*zkPe0PA^?22okM4*BaO0!WA zoH!dTup{9x{`r5oiJiWg2Y1Z->b;6iAA*jNPYAJpwztUA;7z&96~+68u!hvm6 zYfXOgMohe?PIkXgsU9U+QRB`qRjvA9gpK#1%l)e-H5m`@X{rxrocyd~`W76K6!>4p zJNAUwbiEP&?Ct;G@c#Hp&E$3Zzx_W$_4!!IAPtfdO%0;lW{uV$AEupxST*QTkjuRc z`>Wc^b7x{G4N{(6`SJ$j5j#9ltk)H24|HUS=|^*p0BH{2NzDl|yda^vcWZJPnDaEh zcpYhwvIZU=NIlMnS%dP=?7sHBu$SadjU!3?zOJ$#y9UjDX&PU%SPb*~VcGvb{pW>L zAG0|5?J23;acr6&9KGfgZ1xWS5&J{Rm1n(FEAV+$sJ6lfzXpB&bl34i?EF9fuVsWj z9}~9xk;6HEMv#g$cvG%tNAcb!yI24VZ&g>&T!G*{y}&wyg7=9|=QrsTymx;W;@8{{ zYC?N!Hs~J#Zw5%#{Hbe0-dvKTzRZHJ9_AoO7HCJ*D`eU$3M4=2Bz<=N|B%<_XdVIi-< zR(!lo5-yXy4z>cKZmrjQPW%-l!cHESy0Q7c|36ZXJ|CG24_B}GyFq$24c_%`hb>XO zODnGOV&NVBShuPN!Fz6`_dW%0A*QrsAq4N2kB%HCi8_M3MH?FCd;`Fo| zNAS4HR538@bXlFE5eZEC9=g5{kj2DXRLv+v;n*NahZ^_j))(d2{};S}aV-|tW5DXY zjOt?+C%?fXqMMg*5dhDWI$WQ>z{mR|M@ErIN-I!SRWjw;jK4T>_vy=@cGm0Wef5r@ z)5pt4CuXgY4bsTiTY(1ex($o}!TZ|RKprf-4aX~@zan^l4~}c6;BB%u-&h>Mo4D39 z&#KT7?D=u;e(K%;pgYufI%%2=4;xr^X6-Km5kvj`!$OfDVEl~%=eE_Dct43U@-CQr zPdY@6`x4{rF=dZky~oad=$;}lUiEII`WV8=Z_=cJG#4WP;(T}tA2s6Roqe*z4Ip@b z=T>G}!i_)nCLHc~8+>&0yvLhvACt=rD1#Foq`6`tUMBEJaBg99WR6C@{P!25eF8`g zT2E7hnr4kB(MN2V%ErZ5HR$3|HmlW04JuW>%1Nm~Rif_}$sl`>u4vjUKKsTJOsvie zeqk5{k_HvbG=|Br=kk8>jl>&Z<=xS%UTY$Oq2Zi*Qtt|Y^>Ns}`F=l3|0T(S8aHj( zIhTA9y9TY}Z5_;0V7wZ%kLqJBPJSt$`0eJd@&iRLIkk%fNE_>OLH}GMQ`P)PObgH# zEFo9T;Xh&tI;#&jEF#VS8l*>`kG^`LD023nN9;Npyc-|9ut)KZGUpJ+!ux*4r{=8) z-XUclR#5O>zAv3=8G?7LGiTd%d229trQu-U&p>c4{|oQe5i-0^dXo3|)(UXTvtZg$ zJQDaD-`jZez8EInoK-zn!mV3LC#Z4Z;>$V?$7AE2K3!pJvWoHWMtz*a$#0|6r@ohy z{D4D6xcAZw{v&qaUACR{sTT0+-OA6tiuic<5u6u;K&g4ZgLI5YpAR8jo#GdNr?*sS z@P2Y8Y#PP;meyM#EW9~aECf~v-Y3Qdv?+M&2?+J^A$UI^FV4*Zz1HneO z1$Eh@WO&s!*=eDe>tJxLHS_D`kzk{FW7f<3!esFVo(Nhfput4`}zWF3R-nlpLy;no_Lj9Yct75sTZ7^~n00v}7Ty-?dkee}ydNnlSyJ#mY0+u-6KRkZ zUh3D`X>SWEw{9xwk_!a0rdwLn$C2uN>iW~FN9ACNR9OW8ZawY{ndkoV79dBT`rm^AS4~M#`@` zm_j0q{f%o``EX$D7j_M@>plQ)Qf9mw1XF$3x-{x?X|^!fO@ zWM`RK{U5y5Xz+d!R`Ad4ZTh~4OR@0g;oa&!gy609u=F|wZxQMtL=|FXYX^ z`M0v2ox6fTf$JpG2Ystv9Dg^KM@*B4%ZC{Itw@@Be)P;#Vq+x2D zf=}-|$0lsNOR{}CLKqNlZmJKw{BqX5DzYEv2jOQvvNQ?f*B>;Qf5}hz>e9S>kj~1PkvAf?QGrq(LfDc=M8i z_f3Pd*Oidzt>j^a==k)#;8KeH@&48z!2Nb^N!oidoZ9hwKqJs-?*~~!8`GR&Nv0{xM~h31q5#&r?WycS1iD^jOVG|GeLk9JGRK{ zBN?u1F~4&8?hU}(%WZ$UDFVpHl}~#2$YJ8W%cpS5jhl@m6>3~zv5G5x>O$kC%=#DvW~Ztk?OsJFaIkqKHkF#TVA|I@D7Lwy}R%+9h(z1yDq=qqcrdF zCTyb9N9<(U@_*O=3G?C?(*FaR8r1QDjRUPg>W+%iST$(R3Cq}R$O!W4t#>!eks7r9 zrlU}UgNpW(-(tYPOCR)K^K4n*5DLC`x9jM%k>PKWBf!KNzmJa+ zw_w&FA)l*!gA1N%O;O_(%DonnPJH%^SA#^UKJfC}>tA0kc3%LH4WC5o z?!d1>2k+~qrZ+c(&fQf>+{@?~LFV&5=~dn}|7%bIoj#UYc_{xKL2A+9-Cq1*0gAVx zJXsP8@9TNrNY)76L+*Zk6ufOqk1G!%c$UJ@@vBZ$6HVHy>Yeyoo8};hjVE zftR1gVEmh1;R3)*_oriHQpeLng= z`xdDEeL;E?4c@PU!Zc94*OtN(Sa>^#Ax8AFYB>h;Gc|X0ilTIHa&$$~obpJF+nlyN~SrxXTcprUzQ5*|zX)yBYB!c&y zJug>M@Lu6N0TB#W<>}MLIX0-l$26tilj29Ng{1CnM)*; zBvR4IkfHJ2NBi9OeA#!O_uDz|@A`84{aPQ^%KxtYto=ND@0mB=55Z#VXPGmS;h)`^A>nQULD6*)ZSD+_TT)g9rrVx)%1mYtHGLNk-no+;h;Z;Uu?g;5o!;bf7RO4YyC!V0Eu%M zo!xiQ7yTQgrl&LB^kz}sCH4nW$1be=j6aEqujU5#J|4`w=78OUUI(piv|)V)1n<3J ztMp>S($+mqDgSL|#h;XQO`wwTB}wP;KhjrV-cVebi; zcf)89A7TDy+&b9Z5A)uBWzPGO@K&%=|JZ2JKroQYe2dR*#Y4w)4=J~-sRmiw;;V;^ z!@!T&l#?Q|J5YIpO`Ly96$kZxA#sVqHYX0PM(53Q<{ryJBIWVkhSb4FOc_t;C=r5^So^q*gHs0%7WL1-q%t+?*l62)zRgees=2b1JYYacn==?BSYlv zs!}0?##;c=a{dGJepGr}pTPS`?mBB(`1aQ1>}%zH&~_k?%WW#?36h%qw#hbUg5|G4@haulZOes*?xwEB*DCgdia7t%T91% z;6RFEO)yxc7c;qIOFI#@8k6q|Q0=dqKQ0-u2u(`+|JuaPnT zTWIJtO}?Q1@Bfim$D5%34gG(+w>}B)S8Nx*6M0XUo2^CTt+aV-(0Z76j$ZI30`CT+ zZ$gDIZ~vH+a+_j}0Mnf#X-AWS!Djj`664SC(3`dXSp^(b0Oxl3coaSiboLaTb>iNJ z+P%kXCJ(5UKGS=K#9f5sQ&v4f=Pg{DH)VQ~^1AmYqz zTc-`H;CGM~*5%!bt^vPVgWH1Z!oW=4@rW0AQ`8>xMJg;;>+`tYA`%xS9p$fYV}Tl< zZmenKP(gV;=qpmkWsLlKq^_@|H{k*wau4H@gRpy0-^#SCpC;X4B7Sa@AHcrEo}FKM zVpd#C{VT{N^6H>*XUu$bZg~f3CkgL&X>a<7ysy6=Rz&0NoML9}3-kU|7@|htP49lx z^%TszB*#;-p;Gvgq->SJhfq*%0 z{+8gPFmNWh`m8IL2`X>9oF|a&%Tc{}ByO+LhJE`#px@qVFl_*zDk+b*15(EmjQslB zCF=F9xPa&H`1b23uz9;YY*ak&&<#WeIfB`xvAg#q&8{_GP1Jw>f035FI{wT&kKOY3 z>n#Q(yx(d!uO#y3c@n08#(Tb?w(L60yU~~a5`p(iv8Pd6VcsipAFD?dY61FK^_@134968FQ7(c}3; zblxG+^x+0|l*juaQpYKb{JaxFdIGL-0T<9(3cRs-uP#+udmrZghLKU~%{wv3k$1t`9r9?r&xSm@S4mi$v|B?2-hvh9q&;BX ztyWKDJdbVy-vV&tcAim#l}mJ7UCyCc}%4V!nwcO?() z{BAHExGF9!4}1R~7pB5I{l=2|7bj%ap|4U^6&d;8{EwrCA9()XP11utR*KdVd(g~z znvG~ZXv4;>)}I|p^s8AIX-nZABvQ!34-p2WixKb2?Ny=R$q4=0wh&N%*|0gj1P^7* z*lgazUk8k~e%lly91cV)G_8EA&$$uSfXB%Urt*Iij`Ad z4{Ap0c!rVRmvs_WALzM&%HH@2hD_`p)Qi8bRUFX;G`BXpZg@mS4;qPYoHwO&>4H~J;BY~^CK`oyH3 zJrcLY`0nvhTXfz|2i~3Sxleh#?-A?3$WK!bAMDl11tec(%6BAV^M+r~)p26H3j}B| zJI5wqA8)aYPZ1q%)TjCb($Z(it7DtFw-eXd<>M{JB)mV^u3JOoo%KCi4UKom_Vj)M zn0LQU=Me($ceUFyiecUrcVBdhJr;(zw+ppz%nbn%9lOgU?%|<3L8Cl0{*Tb2bZ3=sQBDIg$pc2S4k@B5_kaD-7=rqIY}GV`l{Pt0<569;A+g82ODPw`{Ux z-~zMOJAy|354>x$RP{@bVc*_5SM~9!i{3h_=l%8(d3C71rYrNxT<+exNO+H{NJ|oV ztH}7MqVaaopea>?c{_yQuMl`^3i7YN3iHM};u985^*ouhk9r;(8v?xiB7VGkfQNQC z{#fHJQwx5Tu9&>#9tLzr+I%kdp+E4vmi2+}_17Qu^oVggCK3~Fq4Pevmn9&sp7MCh zAa%H6<=3>nm-RpVQVjPXaoV_3PVgBd>9BKZcmo6I)`t%p+TVr(ZS|9oVKyFezWnCF>XdrG z5$k!9u`3i5)ehEIn_HpI^JV5-_79)U=-ol$4qT|NICvaAJ~lmocQB9gde9xDj!2CB z^hTK#u(Cy9JuJ7vT0Qu9-6A>=hE65k?I2VdOQ2+P;aB}3;amUTJ z=I!4Xr0*f&{UtX21o0B<{JujQjrVt-S+$EW@5*8}nG%?{&9~&YIxz2BYxd;5sND(~ z7j$g|@TYYBJ)QQh%f&;t&PEw}?y3i0D_^^bw}pZZgZ1C$OVQ`~n1S05z6s9gy+Go= zMltTYydIr5({=|TqXNp~9gEaKkCETE{1f3<;7e@vtoDRuB{uKG0M*D#FmIn+wpa3% zWV~XhtIyKCL&2#JxP$dbL#sop(%Kd6hi{-o2GY>IlQgZz^fsi9;Qnz%8oaM#LR# z-ZvPyQWmW`fjxcnQ1dJ7{eRq3GUk@4pOTws1Kbw@%8Ht!4Z)B8A?yTHXA!JU?!afXDV2)s>6cz;?PF(C4u?%J$@#yhm)_xT=}_l~2lo)UQL{wTC>gn7>^5C3*% z)qo_Uv#v!9h5%t1x6K)acqo@sgO}lO9f&LU+u?sc3~b!TTxgtwKF?oa2srt89IvN^ z#928sRnO+5^VaV4nN6voJl@$z9qJhQebkUhFtp(Ut~p5^_ithIX1TMtWDN6`2(}nf zlE&tZQ#|REJ*r9l^S?Zqb&TAv!o!P`|Gxi+qx>JZ2icPJpl>(Dj}v+jVg8rAZ@vPp z2iaXX8cqlIpfp$c$|AT2T?&#}Ckn41`35<8@xtbi+3Hij@p|C^Xo{Y>aS;#g|M5DU zowgA;YV4}$RtyDSYrdChh}ojf|I%hgPZa3p^_GyhrI;5gLpj!{@v2dKH+OZ2K$P|m zPOL)_BR_!y7hPrAxxnLLd9mpi*gdFJ>vPH${dOSzec&ofEjcU5+_e_yd_F$;RFH5wsD<))3nO*ZVdQtbtv{(@9-!t62c=h(c%1v5(WdfP!u;X0W! ztFe!_T)U@Lef;$ns^1_DCbJH8T!QP?_~re7YZBhG`U}^IytxLy(xLG#RZL@3gL&g_ zJk%oGy`7#fnlprXx8i>#BqZ&I_P44FZpDRzH#<@sFQnih=9rQ)u@en|(ZzIBcQgbz z76<=$nu^XfI67p{)f;nqZb%%xy5vjIdGz^z^P^q2;<_o1cMwv?CXDZ;{uERU+QTP|2A2SDCUfAl|q1Avhfm zg__$6I<9K~uNdb0SigpVqCJI0TUVml*&%Q9LcNd8Z9xKSi-$m!`=c_i@JwSQ9 ziFKU7$WLmr+de*+6F^7SRyMa{^EL>HS;_V*RlP1l}ECF*YGE?_imY=Xzpy zLaGerksDWs0h-gPxo%nT_y4?u^u*uRgKCTGj+?)Qf}s_`iX8mtykkertTdu$^+u7n z-K_3E^=i<0D?e}_7SE-;`TsOhhXO`^OosgvDok9Uw~9-iyAhlBmbI4jJ7C_Q4xNpf zNG9X)mQkMrCX6c7KmWfcvyOJl6B_@`|2V4nf#-h*k{V{GO3(~@`kXHx)w9)vU zzb8odk?{WRnVL@Ioxewj1&#N84P%3wFz?BVD-Q^~C0^c;359uEhWAJ8w6cIqHGc$( zkbAe0W1dG|Hv3cJ;^84j>*EX=SeOI1F9`*{- zK4bHzFNM-nzk&?UB(IM5E{UyMGL~16dr5dN>5Zxpd7D1}#Eizs1G4A35gVj54 z41UJuEiRvs5C!wDJhEGCj-0Qz{GxrOTrWlSym92#amlJo>hJLudlKG@%qG4>-o;jT zn9z8S6`N1JfO$*)yrM<8duw@h=@$pgTPN6$#a?+2Bo>%s8)6*}Dnc7hmYl^y-%eNX zC0u9(Ijbut_Z$lYi7PGk4_l#k?_%Z9vNx|5^sHk5Jz2En*!t82RNrHog*`zy;2XH;a4rVe@vTmx*GB_ugb<(-_@duz8<+6|&{f zUFtua*g$3-pHkjgKZnoW{Iu{&)G`9wbSV6V*iQK^ZHJxzT#i^Sm3GtKlBx z`mknI0ep#NZ!g~QhH!~psh$2%-WnRS_I=fF6#;N@-h$sw;32-)d-A>6&0zBtyXKsq zA%J$*72!S14yY^0%M>S^pz?AKeoaa}X*8kkuEEG6=`NiAeY<2{^a zKH&uOF1UaG6M^@;n1r=GFmI!Ly7JsQOK8uL5UtN&!@+`NfcuLeJj8GDxPks{6W~2w zJ3b~73O1R2H$8Z2FY4l?Xz){%QrHi@%}8AG864eM68b>(Yz?kOm;#^wzm3%K93#K9 z(D>iyEx15SrH*ni8NAOSyuatYGsBr;-@P@ey1Z}ESeoh=C%dZ2t7B?USDV0#KI`kx7DK@G_jB`ZkI`>${ju*<6RZEOcMFNj9aievs)f#* zpK^5FZ~DD|>%huS@W|7{KQ3?qZ@+GHuJ5#%YwzikKUO)w-TT|J(n^8sRA8@8S9X;Q#g@Nyf`I5U~dx=G-KJ)`J`!n%@@g zEzuV}|Dxa)+=HGURXuhU{s!qjg)@F`zP8ZrNuhfExd=cH7R`oS@zAx;rgt_sw1Cz~ z!`^)%A)qiuzdv)y5%m%~?r9)rbsPsuk+}Mnum&l0on?3J!Cu}ope0@)JJ{l??IQztb^}Zr{drF z-<^c_3iswuMBZDQIQY?cmnqCB)WWj zldrt}nM#4jTY`}~GBNTiiH^a0{N@C959{{-k;dlznlqs1Sw|Dduy^^rl?(e8JI>pr zMe9W?_4D>5ua1#}<1XbT%PUAX65b370rN!O47t6$XuKJgZXbFH^Db1>*U5)@@5sGk zqYm>9zeeY<7-a)}S4!Wp?sf#2t1xA?ID&^(`Uyu}vupuZ8ZLV{%7=pb6MnAlU(vg_ z)v+_i71v*x!pL{8f&AZ%3 zDyZ~9GYDo$(jPUzKD}joTx3=MIa#Wo|0lf3tK(>t)icNZW!|nNyy@n6bcwu^kLIjG z<9+GI{nRO#x2o3-_>F2a`T;aHM@HZQsVLNX;_ad})L!?pNhmS`OyNEGcQP?UsvhZ7v7^ftvyLieJop(st)cp<$eE+`$Qb#04 zezzP*l)=+#khvqfU z2oQL#WC!apJT$Q`Md#q_X0XaD-Qfm*C=j!G_G8y0^t-n|`RPpZ4Sws1B600?H=l-& zpx?cX91BRBe?)onKThCp9kCesG49%t{0%;Pd*oDpuazJ+?;DdF+;_oyZ>rf+Rbcxu5m>#baLF+-4 zyM7$hgfFqmOq=9x!aZn7O6N-myn?*2!i`76XD{?9Zs$?Cn~|VtFe+uz1`lP6Ein`| zJOwo!+FlPBL%{ucvkPaOolpm)biMW)6Xvv_9En@Qvqs{Q(mvGq$xwV#`6T7_pe&@0 zuNe82t}|)8CdUi(3a*?qH^c5h&$P2+E)>?o&;L)ea7;p||1SUh_TT6q3VlcYZ;;L( zB(Dyx5l#Ldsmm)!4-($2mfMDiyf3x?5JuxI0{J~Mg?aC_J{dsZy+f2OHyP&rOT`}_ z(Pa;nhhM(c5g7^eJXgth*yEwvWT{@3q^Cf;b7Ke{e7vRAEk`WwGdgd+HT1$^uV_FA z5~pr+AoYGYI`4pcNjD>&P#$kVq>d1b{Jh6M?Hc#w1z)y(eeYq2&D%K8JzT7)9_$Uj zzvuYl8f@NWqO2{qH&Fe6gexYqj%YToJzl(oH%J{J;myLUx%~AO!rNPvKh~{AZp_RttG5qN4F3Fg*+V6WSUhiq*#Ma0~ng0Y45 z+`}DVAbxVgkrpu*)L#o!(&#;gS#<@81`S14Cin5wwDQguAx^RVwnsFmLG>DRv1v>>$q@ z+due8!%rx7{pkzd55ND9-PlM(`6=isPR$L<2nAJ#cdLDUjo!T{epFU!0X=#1?X3c;2YP5eaxx^iL|g;Gw#qQ+8{bR{oqgfkL(m4Q=iO>YUL7pB4l^B}|K@+<)tjRK3twW7lk^~-Qwx8H zJ&3PCN(!w9$%Isd)Y+Hl^Dw$!%7c4QT?GgXhkH=Kj@6TUOejuOM^3HAMLz z5Q8Y~-+BtE;|4~4Nt2OtD<@ZhE*TzK+$ro8fRjo1kh>dp4+^(q`L@s@ zLG>$0CwubhXgho(MEb(={C|vuH@Csn<@f&+2Be|fSqU`WJ^nIc12FH0O8jF4-rgU& zFPwsTr!uVnuIl9o?f1`F|IjK5bOl{EezF@6y*_<~-qxoTNYZYP&$JH)ZGOJI`gQ2M z4Q3SV=Va(XI}&%NZbcIVBRX%b@N<3^#+1j~2&qE{BfnSR;Txs(yugTQ|AUB=*t|u0 z*B1}Ky#F-Z*!i`AjN>h(+2>qZsDFbLcbm*Q9&XZ9`Fp&@n}jzPcjGQ%_Z~Ke#L;+r zU3)t;4fEC$4AHm&^Zw!ChWCJZtEIcS)g(ATyyu^`#EC|M(hqWc^JaL6Jt*ynVm>l*d~VspAGle)!A- zW6Ymc0rM-}@7TPsd1pN7q8%-*1rzR}0oz!xpWZ4S0I_W!Q>eas9~>mFj)&Wr#zikJ zcW*Be-W*>V-Vk|vNTi9O@&0!2Og=L_Ai2dIjwA3E|L~Q6AIv-D*$1Jc=l4Mw3>RKT zyom(Gr~GI(S>T}oi=;2iqOD-Gi~YL!{b2BiZHebz0y^)m$A3m?_2~c&``@^rO&T}a zFQN0c(R-mAEkk*{dyqQpF!H+^udx2HGB2z~Xkedv6XtboiG8 zHt#1dc`n>JR|hgUX)E#{)M4{pxn+d6pZedug<~eKj>E_7wYlKeTm1L@|33|ma{mC& z|9&JrNYJ}%9kB=9dnO=<)`PCsFxH#EE6AhoUw+Mndywbj&fu+Z53=NE#zk#(hE$A~ z5~|#z!LWs#`P(gcXuY_vikDd%=;kWB!gwSY4C?Ck|B^u8K{`aE@3Qa63NVbs-FH+| zKFfrD&vItbK0Yym@_LX5QpX%de(L^$<@HLdzy(2BHSUYpJxDuY(SnyG<@Cx!z zrNP4w&Zw7$vZ#lab`mQ9J+5jw&c)NGM&lm(iPOMr?ik6_l*junQb#aGe(BMdvY(`{ z0x3^EeEt%L&HG6XOY*n!$KVWI+@oYoY~CJuA*!3ZsQ&|LaXIAGVL!Kyv!H32w+{(# ze%9OnJiQg9ULk|VJJ!WbDj4Q{#5pRBz66w?`4?xZ05Dk1l|gqM@-Jc zyh8&&P5A3OL6>q9bkDa(fh{Z2J3Mycp<@M$0coFF!HZy}jPA?9ASIg5_e(lD?*gl{ zs&eNUKspk~)Y$h6CyUOz_0rqTi>Z{yyBMjX9V0*4zFa5%#Z^GE&!Idt5}UVensmeS z?GTtq>)5ku277Ztc=y5a+Xb0azc}eLC9e+k_|eJPxaIDBf`s>~Jemn2Z>`{Arl?8motqSKsZ2+E-rrURnrmPR#5&6KI5oKG_$}TQ;ez^ppEb?L!r0fVz{fS)rPLo__n?Rq zd-u5AeE>2-_GVrj!hS&7I#_LcOaE%BUqS8*BCn2l@tQwe{>zuxKoZ^}N_D10-gtr6 zifFu#6+b;T1M|+&SeZlM-T!W5@=chxs>h(2{~8yFPHUmG;8Qe6_++nDt_!aqtHVyr zL2W>oD^ciPM=+TC5W6sJgwC7W2uEC z&szqN@D`p+)gbZ?9=g6Bjkm=!;m=I)3ergG^(=w+f$>2a!rNPM8h0(5J~~5(c8sd@ zbwq>3fbB1&^ze{QxWa(?%{H)4?ZU3m$HCyu>#)5~8PR#iD5ZZrsL2RMkvM%WYrB-y z=)C*Vx7y13P#*6%q>g@!{Ni{%cCNX+3dD@>&Cbrp<{j~e)j#C)L!h-~R5dsn`+)Sw zwJ6oZluWAc-ppjyF*m9EeO1iz0cn2{-mAM<=!m?ND*P4DczdO{ONhd}BXpe&2%8fw z+76%B!2^=}K$FwDQfKJA&;g?@MbTia*GsDmz#mBSTQOmEwhj0g1^kI)4h9N(dv8IC z=$jJ)KFwbIKUV-1B<@8a?;c+>^vwwz|DNJ!p_Ip47^#B>Bfnu&?pD4pJfQwuGQ;`; zY~E1_?Krio*Z^U78LE+o$Lrt*!WpU`h_)m=OJVjzU_cyC7PsK>~! zrtl?i$?jEPzhLIo_c_?S*U%}9y*Tp_R0asCt!g6UaH5Y~AO8rT{`udF%sOQEZejm# z{-@lTpER?Wy)ihF9<D?1>xbE6CCxXTqEWDX#}vBXyKv`cVHYT$d2Z*X<1rwehUuQ+Mm+Q(^NYu3)pqdl z_wOR7*dQ=_%xrj*B0BE^**vv(_Do<7iIa2qmO%F}x3_v1zVGMfraa!akvd*teT+U0rfWFKb`DQjJeLoW~%3nJ3?k1ob*?f z|DGTXCE+cBSFt2^Z#CPiYG}Nf0&WMU!MtS{ON?`1-bJH&i%anQ?_AWI^tRCjGPR8{ zzUvSJe!Z8w5}|>IHjI8XxG&rez6zFVe?A%n&ggDC;xUCjAT6oHm2&ejfjA^i$!_FE z)h_hztt|@G_fX&o(qBj&x)}NON0r{1hXfP{baqd6`3*;{@24O^$% zz~iIml=4|Zz|zktq1ic9`RYUh2KG{RQ3J}+=Cn+ zY@^={4@i9)?^KfE`Tw*+|KN`57+{;PEqqo94^1v?r9YkD4wxjwOoQZufYYFctm-55 z9@O3M=qppe4D69OZ=aL9#u)$Qp5=XGiw6vpcZuyo>d?o?4?k;JlKzbwcuA;*D)wOa zpq%%dDoPe*;G^5;saZ0P*ojFUs4?oSqWS^JQk=Xx%G!hk|13ZMA45;VTTb|{7V#3R zwZ26gjkofhtdkt@CAP*%Oz$epJHNc0&jjWzo`0NmXvqai+^Msr=6(!_xE^*QR~Zit zeQ|H~O>PHUoOiyz#~lRP>JDzY5r)oN$6;%Fq%SjQLgE~(6L;==i++jK!Z+@C$Vhp- zHzRfEVC46G$jw1_4-YWc&EU!C!sZQ{rZ{)QyshH4hvLXNViz^~^=eNe)$_(hkXgs* ztMb2}w}_!5;VnB}V@Txv;(D?c8t)$lGYN>NRv|Me zZf`p%d6tp3_$mlAt`hmYu^FBBM&s5jfk`G%kHlRB59f^s(0R9B7V%FLr##-9kUH8i z^4s5aWkJWE2MpFs?csv3c@G#a*jjMh0Ya?84*(u}?+xdCxMhp*9;#oQggcQ}hs+l? z){z_k&Ht1<_WzR`e2HC2(t}jCbxIR@5Mlm*9cQ@$tp~kk=yr*O=YOZ)F2Y%G4~l)4 zY?tT?e?fYrHu+7I3v@H@4sP#c4DcH~J9AVH578Y~Hh+if0DYTJ=y~1?1a-Nl^-m_y zdyvPzj~ds5R)WV!oYJ`O1~)tO`JbbYx6ADX<-KCp3#o$_BR>`Tpy7NSZm`InbFq9H zy9e!Ke^sq*QUd&Uw3_%#WA7lvMjf;-ET{fwkQB(Q!wo#$BeMJksTgJw-pZUCRf)VM zgd`czc+*@OWzB$jr|F9N6L=ry)zP(wc_&P5e!VHp1v)WMcdhAt3@|_0amiI44~ZMj zb?Sd@2Wp%Ln`+Yo!KNJi)ZV-3yiac6e;>blCD1_Pfbwm6c6D^#bZzD`T`wt*w;xgm zGe&-nim)?a_Q`o%EoIgPCxVr>Ap7U9SzubVmg47kfA#?vO)n8(9yvdCs#?TD61H*hfou#-y;5nvfeL4!AcXof5MX&Tq;Eu!pU zgv|+|(mzw>@PL#td$(?~+XZ3>oQt!576U><4bFS6$3x?L^!%hc-~s87^;e0kK#)=P zNMi5598SC`20iut%?y%|xZBNM4=sM94@j%7X5ZzQp*-G&NF72L`T2V_+-9xe2K6kB zA?5F|dE4G`8lQ)G+Zlzt(0){p-MtUr6*tNkSpx6bsjq?>Fz>sp?C0s>%?Zoi5aX9Jx9}PkHnI zeWVVY(7)$bQKGQ4?+Q1l&E3KMupgWEwQr?gZGYbeC#ugYObwDT|8J?cT<2#-^^22m zee&v{<7Sy+z5Cz%|Ids~$$x+^u^c2lNMi#Fp4fxFGwx(X>p@G+KjYZo9>k$nX_^7| zppu}@Gl$?6WFx=Fp<5}=(1!=NFErp|0NZ2f!Qr)dNZX@|u5xz=7-E<@7b6-3R!i`m zDR_+DgKE82dh)+u0Rl)|x#l}zeP;9{c`r}bD#U40UJt5A>KMStFZ2B-v#NP65PQK- zz=@7tAB)WF9iL#Hn+2ea-lco}B=!ojLcivQ*t!g=??H3g&egPmsmiPwhpgL zdA!|`I<{iu*ZJA%w4Wh2@Qc&ax58obR$rfQ83gkd+sLrRGQI(Isq)YNCb8T1tc$-! z^}KOWWYz(x0h+%nNH!AQ>d%hI6M1J{7-L4`{pk1h6S^>O_PM*vnK19b6?zisFz?0v z2j=7@T%c=dyJ+pEV?fe%hYwjYc*uCennoU#4v^Jsc|Ex?2;62|t@?Vc8|tqmeOr3l z@kAC-jKsCt_9!LGpm%TacyYg)?Uctm3#mg2Bfo+-8@0QIxxokJoQe2F>=mR(j=RUx zqlG}_O&s%sZtN4JxTu)5&MT#;e?W>PuZ|22OPMUYd{CLfL{clRwIVao8{Da|L>D5KpTm>G?pS+E{M)sNqu&v-Hh^hb0Br7VdR&v zB9zPG7dK!$c$C|87Mpj`3%_k2w-kd+&%vJ~@=sCQ1hIR6TCGxFk|0C%-Fp?8bYTHfuM)lEqkk5kM&z6TQKn02W<>%Dh{Vy+6zZaKyK*EvodJwUWM;Q4@ z|50mi&EW*m>|HHPCj>n+$Nj* zj`hNqSX!5dmn86z-~p2-P;3XF-?CetVI%-7eUp-jXF=z^<$hr2g$x$3fW+;td}til zfPRVPX&z!)$aqWZeyx6?6Q|B5ZVcwM&iW(k>H=r(6 z{%Nh9x+>df_fb7>TsN6@(8WDh_&fh|lknDVlT0J>=8Ag5fyO)UiK%Q0%=_&%GwpPk zw@X6l%VwDO%f~u)0Uw|Tl;^b7=iQ!^rs zVd%Uso#VGqiDm)3NL+~b!>1bG(0Nz$j;i(gQ6BFkq>g%w{64?Rml(Up39j)9bFARN z=AGF0C;wJ$KCtJi-M!R8#_KILog*^NjZ;1Ea5C%AyEza~duzFSbCK}Y%G|S>$otH6 z89N$pD|30eVVHNW5laezcdX>n<=-%GMZ@#=1XnmiJa4+Q|G=lW#LjGK(3XNfkZwBO zcjrh4@WX3bfTMvRStnE0&lR0_&FjslwtBLF%ShZ=wvH>(|MEh$j!#=M`{O8&cO6nk z4@Q0`xGU?M=(#|+!p>y=mDs#x75RqR4iPq4r24JIiNy!;O#c5zrCgJN?slM zyAEEc{`+tuCkb!OgTo0#-l3HNY-qgGo+k;s7yKy@Q(0kBa{xRd%&8*-s5_cIot(-K6-h(oy`Wp@V zDen?Hi`0>gk>BV!{MJ8_oFJBOiR+LYb`QGwPPB&I@j6K2KgfEh82c7Gj)AT`WZ0Ja zdk`aeb&Q|(tsl6#yn+-U;k|kKY6p?`pw|k1G~TbLcR$gCd3WZuv!}wm4S)CCYlC?| zB)wP-;Dv6lw9>%VBUo(f#$JI9iZc=*o#r6AmHcgU%XU+&Re{@!2iu1 z)_>w|SB;6j??LB%!+GoWyfMn-EsE4pfRUe})kFCk7F^&h&7Ij@QrNs_Z7vyxjO2ms z)+&n?C$V3UK7O%vskpzJ>UkSpBCn1Qh6nXOr7rIv@sse@Z_1P+^2T@e@}luJxNLaQ z3g$g+aK(eb8~iefxeD{s=n0biTd!ULzU%|9ykntpZ(C&l@*DUL7^snjR|}m%BF~32zXu zxRc2HOK9dQG~PZVKRl1Zyw%L*=diPz(gcS{OT8M-r@e)8mgnuwEk_K zN)3OP6-Ztk#}kizUv*-+d-Ia;*4sbjOyq4i?ahP6`+n2#i71$N?QNU2gv|*+!y8tvwoo6VdfvEZ^6HTGmhzR)`fvZA8d??(p8rKidXORSM|)xqvg}$X zg4ToPfo<)5>k|EXRrA3lxCdRm(Z@ar--GNoY5ZRA=M0@a&nxN*zk{TcmDwd{H6Eh< z3Hh%7(E-wGt$Mv^g1|h(jM?`Y^h+#l{L*$uJvOk2#L3`9c5jqLf8x|N!(Sq!i1K<6 z4N}J;jQp;1T|Hx^&Ix|BGBM5SVfUcIHTCI{ZfRisjKICNmDsn~!y9(L_~ejB^(#nn z>#)i5D`bP;K??I;L&AH`1=}&K_=!Nl6hGus8&AATX5hz*+CIUfcv(IbVW^~?f4)*dTtz`qx zkT{)JnqenbqVsO8uRKwBhw^w6>*&PDPjG(IXIVc^u<2a-+7;T^ykj4AZIP0`0yx~E zZeM-uODwC%ZEo}8l~lijG(ct@+q}Y+9TJv#3zP6Rc--ql*YD%}&)k0_5fv5pXo{6JOlZpJE3@MYso z)`MEuyvNd$*?MKJ0JB>Tow}@z*vDIZEP5dE*Fem8x=HTU_iOst!lE?3)Y7VF@5(^fV$L`)4Z^xdUNUx^)0cmlBygJ-< zO8T=im%FzR3GZ!o4F8<}*K+U>MB^sL81nO=(l-eYVU=V9InhK@jFumkM1>Dy&l9tga|N`<;@(Rr`lvL^V>YgXWm#5o?w zT2ie-=e_k?UY%qIv^qBLJ#I(+gw%7u{k+w7t>X>Y z-5Y3CR3ty8dfvFrWY#fvp;7w3{eP+${|WQIBuNi46%2_YUSb!eq@>V#P}q$kH$C_g z8~6y!U4na%lE<-w{BCOc4}RliFQ~gfZ!hm||Ct^G_Dqxrs|ewt-|6PnlaX)fh@n60;rMXE%Tcuxw;?5uu>(If-Z+(#A z*VS7%0asn~&E$R9J?P5@!=t`O698}X^qJ`?GJ4R@2X}8LWm5h8kNZt#9jo>+uK#;L zT7rbP$*in6k+;+oP7;lG5YxfU)-dnvm$}xLVczeX78L|w-X~lJsx}F_Ko1^Po9s@F z0j9OA0>@$Aa;0lZn%Fx*Y4t8<#~Xp5Lx0CF*>C8)xsLhorkiI4-AG)+hn-dv|MI=S zotq!s6{JAk#5#;I@_YB~SD?TG2Pl~q*vD;-&D&JxS?%7~i{RsX{{v-}WE^kF``Iw_ zT#ot&Br@wL*q@*_0J9>G8RE&i8uF#B7B5%6>L@_kpr`CG+ z$H2Ue1Pg@-n-j;PWL^uxyw_Lo=W_QtLlHWOF9YGtiSp!26MtadTWth|FEVt3eS%zb z3Qz#R(Ovzy^bvi7^oFi3*Y2mRfDVb$8C*=yv`)2*oU;^)<{a*ur!}Gsr^$@dWk~1_NpO7$jJ_d*%GoIN7 z@4d-<;R;$!(+QYPc+@eS4+P^+w1N(tNAKQt345}fY}mj@Bu@2s@j}rLbl&`2wXMCk zC~y8J*0CBRzZDzg7{3H?f@+iGfqVmO-glmu{@T7T30zu`%W3K+c&UHw z?N4SMYYp8A4=4V2{+|kN0l@RWEJ+Wt;!Bz)_8_iMm9N&8t!@bb>E;gF z1}^A5NKI6-PC1kfWFv7NJg0csSD>#T|2S3+H@8#XB~~4&1GoR*^GnL?Ju@M|0rn~G zKd<16-Gi=Z8c3$Siv`Umdp$iOv2U^Cy6@Qv~efZ-b z%zKVCa^bybCva5YW{b!R03LA+tj4P7yw^b{T3+sK;208TBPw@|X9E2ayFYVluvHu7 z@g~;cgpuFMof^?G7dgP|lJ4HZUsbC zMqV8i7uOV({Cz>XGzsrLH)cDDyfeO3$e{85?z&Yd z6E-K}Iu=veVBS{mPRy+fc7fj8UVc>r-@Tn^Z#+~F^S1B|#QhZP1Ps3GBb1Z^fl=Px zX|tQ?y!VaqJ-h_iz-}b&@VN@b>jLPDleWlEPSIY<>)ymVIx+IAdCpdUBbEaQ=A|Dr zKZwoSRj|j`H2yTGRV;Qg`H8(a2_G@)_mAH|_49xDd-Ccyx+;5)BXxOkB1OX6Yzx~_ zB5&(Xi?wLH(^LdArD5J%)wnJZcpJ5T$mfH3cj5(}B^$dy>PezzyR%}z^UZ}%W?|mO zzx-?l`8vV8#_5+gw*>;Q|5%Ai2|91f-)&(W%4}dO636Rgc;1~4op-xCt!(96%HwT? z)X{~J-)5#3t2c1>_T1>OyUZDz_wlPuegYl|K!WQE2e&dd@BW;*Q+;1AP<{7)a*ez? z2Iig#r2cpQp9+S5I7N8=Ur*A5?0@Sl5_?dE6RR>>55m!`FSdqPkn~>!)h@t2C^^%5 z>;XLgH;CPdc&>Q>@_LveJ{cDSMzd_A4++3ukczU_+NazJES*dwKEvn#b?L?4<=4BT z-Ws;Ich0u+VF&t1oOXZjw}{W^J*Xp8q5e4qz97v3siO-szcnx93^~A>F(#mI$;YsJkkC6#Thnd>s_#L@qvX{gn!ph%7`}XoRUqMQ*YbTEk@rsT zAw@La)!$V%d&0bXKHs@W;Qe5KacL9GTRv~2tIWCskg;*rdZV*3pwHO9FAnA{vyR0< zL$MR2MovW!Pr?VJotYHwT}S5~QXTF2*o7TLB5}_yOv#?_L+2flI^bA&nDTD1hY{<* z$geJyduK{L2Y6P*Ro@wd&3lnixT4^86ll5j)?$x6_WX})*fHfXyqoHI<66k9V~iSaSP1>$dk*_Q9V8eXq2?iJ%@RB8r+PDT-OQ2RA(oLX9K~M)U?mK%jmrC z{@5>9X2K4pk+|ynYHP3m3vUa1>-5nG%Hw?xsly5*za)uk=V=~s0BKjH{R4s6yzQas z@#AeV!2YOUY&ZXMU;p3DF3-s?zsTkE{GB6jam31fLQ-jmUj z-gjW$L+fu9lJbr(v41`A+XZT{aW}MvdDHgXdCCOO|4!eJn68xW1c7HVq#ykZ0Mcxx zAA54q=YJV~n!@>HHXx70=|0#d?yZ2{z0ds*dv6{W;}`z_kGb2InTd$BQc0AwC?%&- zwo0pz_Dz(c5>1P?$&wVJM2ak-m26q=XtC6UBubGaTWPU{%I{3?xqasG_$I?y?DCLxz0KFIjps^Th%H?EiH*YLMsmVqvTX zUDObshgXAAR~x_TbSg4^dNHUlT zaEOgub3;4^_Ww&ZZ!r;vHE6haWoPCO{2COy;Kh+&QWP-4j$3g^`^xGV{2H{Y<;m2T z9Nw!ziEJN4`7NG3Q2%ll1*n}?c{_BOxCTkjs!H06cmV(WnL6qt#6#?b#bsxo$=dM! z3{u;QJ0Df^eSEwA`NVE62i_jf@BV$>Vo<1A4-fA{&rSyZf_Uq;j+C?T7TFUJJPc=$ z-_|`Jv~~AEo7^m_ijx>%R?GczZ-}?EVc`5*5bp)AS2s95iv-7Ci-u)Cz{gwmhp5M# zQAv=`j;ovEX1B>3A8#v}yV0Ky^B&%cY#-JH`7!Ob$vBKqz%H5RaWy5xc;8GX(cLH> zKzfDT(nrU+_`GGkz|{!SD!#{?w2@064SBz`|CvE*bKvcMEhviZp$W# z@o)y|Ik9xoUWj*Rlw9Ili1&nj)~i;#_@HIYCNXmd$4eBPo~YH50$6F%NLvx{dhc_#_(vEx*Y4Ch#%z{lIG zj_R@IH1FZ9&-UR%klz;B^WPi4P(e(`qz76Di1A)fZeQN>eGAw!|MzmLJ@MCD1#{0$ zN~AgP{r-QXE_Xf(ibC|4$Blj7qQ!x?>uiNG4DX>d)46zfuk<=T3LxI}+cHmCc-PLU zIamPkz7rlUn`!BTHpFKwJ_YyQ42mNv)Li;Mn$>t<``A69$LGoJ?zaa(Ip!H|=MlON1HEG;JnD(&?b1>hh39GJXx(7OL%<`jZ0M*>SCIha;W)@rT%J7Q&ZN zGu~Tbk7oNI%5Un;+1GzoQ$YRIMt_Yi;uD$Rp{;JvBm#yF)o*h z0(q-Xe|$$UAj(e!9i8e_ zOaVQTN2?kh5aX>a+&7gLZh=}FE-%>D!bSh@UlMgtn#T7H5{XM6qc_3^R_BlP|9TvF z`&etP!|;yS?rDgJx5W;nvWpP!8qb^QEWF(nR@KTuyhZ+$%Ov>upxuk=+v5@#pkE!K zJ3zb}GzNMezy@hmkl8+;*->ErjbOE~nfQ3mk997!Yp48;Ykqj;Wri_6-nDrHYQv7a zhxbCZ52F0~_UMMslB0q2N&OcBDv9y-%v^F?d|M!RK7RFcJ2~S1|EhAyfaT+QzHg8w zsdDGT?f%1=zhlPwe_al|y_GKNVtBtC(lNlpTjfB5a~;IHYS>|r6Yu7u>wZ@I`k+Tz z=O(8>yk8x3kn(|e-@B!<^BP>eWgL{1o~}a&qy4Y!Z|mbvP89XBKl`dt{>Eh)?$T5_ zjz2j`a+%w4=>+dBZ>g|-5asvkXpW%GROmOXXwm)~#CSKxyw5BS3%w zzx|(wmr4g|GxkKO91cw0QdhFaMYln&;4WP|5^Qi-%4L0 zyc(45-f?`uvBP`i42?1Nm@t;m!sBy{OyTfgO0HJ$gEmBlLQzBpzE2hWLbV5Ps#k-Za0*U*7tyP`(&(DnG`vz%- z6L&slpRx%t`sW0xF$dm(We$h1<*mVXH9dlF z$A9AHDLsBL{v|%%*>)A)OHFwXZzZ;mEQ0)evs4{}gsDJ0UA}UbC^6oq6u&Y-?NG3= zy=7W zyYPC;=H}qhE_}ST3~O7n)u`YBJMQ%4=*2%~;x|b5<|UnJSj>BP>#%*)66BY!?m1s= zD+TP(wCtAtMLdK2HbUCCG&Kk;G}ErH{lmo!^0vB-^{xL0?*G5TosWnbrY0GFsyo-7U=v}RJpr_L!p7aGDZxi9Tt*XjYFqa*7eV>Gp+#GzoxA_cs zNZ9fo-sWr{TM6>Jr(+xY_$viGU=*9F_Y>nyN~PqtlQ)96X}3cq)QRyvr|f!n`l1oO zZ;&z+x$~h|Q6`%lHHNn#2i^gb6-qF?%eSSC!^3;?(`Y*ybol?&iyG$ z1?Smux0d-lxlF;wTOsIK$T;r4MwmjWL{@{MY{zb#XlKd)WV*anzvDr-f};4QkS} zk-)1#!7fe-TVeknJpV=b4p@UU-)ar1!5S2)R3qfz?1TCT7O#0_&j8l3sDmo3L5GKh z+n?&eD|RbpT`er8gDvCh<_~n^*Pz7gK*b+1RIr&HSL|Z^7FmE_gZ7_wTu-y(y&ANO z?PCu?enZKgPYl*mfZnv=y~=9D4brwFznA7sSr0y?=ueSDxHy9(uRCpcPb&Y{AZ6}+ z^t)|1DRX^nh&AQFd-E~09K(BVii|iO-X!fKHE9s<&}N4g7T%fP0`_Y{ynUJWlbD`9 zsP1B`#(gW{6+5BF1!h9LYtD=PItcNe^!1O9;2}DA>s&E^*#msMbIK*Jr){EwPIg?z zMem<&8u)leUA*)=%bNG_KFRj6g&@BVW^X1mzMuf#&m+GtDih<~YqK@|>C-R}YA}#- zhl>}a#AxsDTs-%M@9~~Ifjb{pHAkkUq>bSXIPl)Y=*Y$JuJj%d#lzduz4OZ%i1&^i zn@n~>yf*|LCC`I+x7K-t)d%^Y=8IJF@x0FA{P2$kniy(X>;jAv`&)!ddor%yh9eR{e|H@ zx#^||9^Mnajn}V)cwcXOcASOx>iF9>W)SbXsDdI&ln**u7Pw=!2LlW{bq88PycgSk zHL1{P0RB_tJX-vsfY8s)(wDOE_y2d8osDerq=IqmxKEpNzB%s0$6Ko=sJO_1_wY_* z`_LfBuWNJF!Jl{G=ER{78-GqD#{2ea7!U8co;!X$hj{ngyC=fhoN(5Oe6k4Qou+$f zH;L|pMg<-z9Ph^f9*-w2XMLQQZt`ezE8KfqE#~075T5_1+^!J+vI-w>5#)8g+;S=q zWyf8eH@y8v5I){$Yw4atJh*yGVf(mAkl()T9zu5%X<)mMwbIuA!`_=TDYmeMLHv44 z=IpD7@?Y)bd%UO2;Lb-=FPSC~pYdP+&jal}VG6JYE#{~}+wRgdADb3<5z+O)sMEI;RshHcDSzr&UR1elWN>|qUZKj++pz#;ab zhW)vOSUPyv@91{s4*m?%D4ZOURYV2%*l{g23i89c_%#Sga6o4|@!k+?%Jwl5|L^&g zb)M3*Hm873{fzFdtXkH* ze>O-hIq=?k{6YYRx5BYWQh0cqp)L*5aELWs{k@Ha_qQ_!({v!-<=#4Z@1A<2zdTK* zB&=Y7yT>eL7C^jT6q1+v!v?8s;hvOmS2{R1DzB}bgOB&n?!=1p0xCGkj@!B3BOo;dIZ7Y|~6@|CAK3CGRwPAqR9U7@B5bpyw7QT27m$$<0e>ozabnx=a z)(+KU_;`1W4zC)`r-BxC+|?IUUo&}pyaRq(D|EW>9^Tz-AKnD{<=1shLY3+t5Dt^%jdb@ZMrV7r?4_ zKzcC+5AT@cpT;eLc;~Jo7qakH{184<9^&nG^Ppoo{6Kou?a!XQRt%t5Z%CJic(u>C#u{I}=An{yfh`0a2etBmb zAM}aRT(dGbIYGBI?NWw#&;Jw0oCNWHl>Y-9Fs1{;*>ClKhT`L`3l7fkOQ8Z?c3igC zpR)(Z_;}meoC$O1!MV3F+sAT({3Z`nDeojxfwR-MCdE0#c$Xff>>QsS0MuWY?O%1D zi^GZPwihni{o#AONwc~1p(ItJ_TTqYTBcYUxU0O1W#x4;1N4hwhyBG zl-5l8s-i#vkDt6k-9m|LkVZ~b?l_?+v`@;eZSV{iGswXk9qOSK{9l9WZ*k{iO@xTn zKmGr54!mPBKE1|<*aC)x3?AOvxo-ClL%fBXMmtz|f3H|Rdke&yQKT8t=Hi7KE!(>} z$cq8)ysbOc1&7%E@~>_8s5ihTWWKz4@QDuSZ!PYG7~wCm3+k7=D!)qwTi9{?a_#Qv zM&jdLm@(6T5fAPl3A25iBgk*}qmI;xyClJpwUSX`e#Cg6>b1XGf0~Xel!sc0$#AiQ zL@H5{p2`2uTab`4u6$f>k)I*ZG&X}=#({UV>tGLt_wLc=iFkO626~8HfOxN2?QEF@ z@zz_BZ0iB>Ui4ZiIrxbedam+Im8c86L3-V+@z)^UXK!i_tcCagAIw`Xp3LAU$XMm`{-3?cC`LW8jI|9@&z^ zpInLY7K|7B^y^pzx^Bh5N#!77ya!!&e-d`R#P|JwDLIuZ9|O&8gLB{x5}ceY<-j}2 z*jgIHo1R`MjfZ!U{}X`+5bvUlg9R+SuYG>?3qZUL7X($*d3&QvWM_mggohK?hz?a| zK)go{I*(n{YyflXOFtFAp##c3a-o?PKHd+1eIKa0PX!|ExH&K1oVEHFyk|aBBKPoM z|KG^=p+b<~P>lEFfIvx5;9B@GZZ$F939H=a(GEtSSF_&##h)yl+D{-2zX zCvxS3_Dr$-+&_;KFX6yDa>P;&!+ZQ-=mb2xB|iC#djs(fZ_J{yHYf5UXJgp_l7|3eB`zJ&1b#d^56M?p6KxZJqb9(+HusNq|249 zSPk+D)l|T%K@C%u^-91Rv`6vvk$6~x&WVJ^#rW%*K3yhRP`Ta>4L|nG=2Z;?Y>$hy z7n1Em3sY{CpPkqMCeC}5zPO7HsxQ494Vi~O#Li5$8_4)h1t>et#TZE;$KltY`axsM za2_0DXR&?M5#*=Uy|0|9MFqPu6$8W5h-=VYi&*#Wym<8G%4c)0?IJ#dN0cl&&=@4(S@7Wlb_AnyRn!7cFgbE_yjI*DNWg*Pl7KHD5+L5&z_e$ha0Zz@xcum?wH_$-*yZZR{qTbH?B0kxi1(4ZS%+NY8o*h`c*$|1 zba2!2@I%FaxgcF;bG)*47ZqG%$2A(xD!C(qk2m#LMac2hyodJ`whu{y{MMK++jrr$ zB(NONzLJ_kjCWnU_xZTv@#sEN%R@dlxY$9mxMIKHZam-PO)}@whmG3TY5%O=+Hl|< zuNXZ2FW!=eWbyD`K3;dcJ;YnyVPiQ9@4l#4=7%BP$*$p+b60qx?ibqUHE(7Bzcs6c zgCO3E9Vg9vsMr94FBy&AE1`oLL5(WOKls&qb^YCgn;_nm?6~#slSn-t_;{D=70y#| z=RLe#**-21 zVukD8=SMtI`$^3ztfRDFaNYl_79z2{F%=RHmlwVTKhoxnbz;<4#bpNYUW1~oG&j7B+@2jD1#HOCwhcA-{eRcjGR5poG_af3?hcbnLW|6sRF(9JcaRo#_#7+U z9?thONXJI*d{}*8e+k;Jqt%Z9lWt9T#c>(RRW{H&2mtgRDzH9 z_*%;Yy1_J1!H!!#@}%lR2R`1R)%Rc8Pvt$lF&~==@=Ge#{IZ|d<^d?%^R07HiLBJz7?yAbbPFWvfA4y;AD6-|F!@`(Y?X$ws&hj@Qp8nVY( ztN~arzoM2$j{?Q3q#jhG_;^43Q}gjd5DlDX$89Z<+WhD}KHg1gb0@d+Al{gdCj|NB zO_`G^7*#N={Xw&*r>7e}2*?r}0{$G@|ruc(Nf zPa@yrP2$!^xxazbKg(P89C$N&q+2k&-S4|8;^AGS7%}t>;=N-b-GsF{@uoNF{b^Xe zFV{cNv(0x!74o}ABw88Z@~OrabBK3~%i0~~QVqZ$+dFrsR1{GC=+;%~i(kFXKWBKv zBQ&7Qj(fQ$-)q%je7w~r9f>)yk@xUk#P*>=ke{<5@+-;wd zCZPcr8<6&5;<-1;Fl2_{b7{VxoRH>m=flq4w_+{4-txcw|Gx!}cYlEWzY9kVNr?&cW`$dWO|4Ebr2k)V1 z{;xs5&T!=;bo{Dx^Alq;$Tb{zr)`SM!SH@((4~%tcZ^fvyEzc=!=!3jEX4blqmkoE zi1*%$cQhYvaz@48z3cuYmJGTzg9_Ck-g=8{Tx)jAh&+@M$trkydSKL zce2u=furoW12pBAjivZ_FO@K5EIrSAc-OIgSPW{IU3-WQB2X5iti zr|+V%4B}mMj=7bE_w3wdSGPdCZ*_076CAe+{a{-nIfs@E7No>WeSoXCvt}&Yy5u_( z$nTV=YpPFJ$9Oh^ac<9)o5J0E)Y^#gY88mr!`IPgxD z@fXDKcHO&I4G-@{H&tT2A>NNgx4vTG-Q%OFb_U|@EOb$avSc;-XZN=CUJ&nqd!LQyKp*Pw;#?Zh|c3h&&fy+f#@vFD=YufHK zH6@phbZ<4~Ht2rlv z`M>`c;nGKkl``uCX*lzs}&%3#Jy){5Zs$q!#pSK{b=FZ3EZL*;Azw`gR+w*f~25XQ9M-4iZbut;NL9SOR z+ITf6_@v;rOuHge201e?3f7<{-$lhNU=1qpCoNJt?})mdcJa2n&H$tum3zMOeQ2lr z@A!^(CTQ+Hax&hF4qm)@q+<6k-~T@}ESPX%B@MK)c> zBeoAIg8Ww0iagzANC6wqJ#W?(5HjWbC;H!hUiI0iuzxTPHD4oBJ+hJbfVA@XrLTv} z9r%6*>88z{50x(TL+?Kqq`PzAeK1(+JchThNS78K-k)B1Hk3lVr%T-xiH3OlA4@th zAL8wH*7xxa87I_QMk3avfdPIl7{Ac~;$0J-7gW>11lN~6jCo{32Pf0at8#YX?;v&M zzgNs(K?C{hIQ?lW&olJ#hgknBG1kl9@*duA**?4p@@rrmc(UXK1(5uGe^rhW53!PZ zrO!gX#G%cHcb2<8=Hh^K_z~aNxh{N9n9KG3)>|JWfXbmoMs>6u*&;G!IVO9bMbPJQlm^9>XH z&{Da541T>8E79TpO%;Cz`Q-QuT8$MA#IWN|eEshHISC){LkmS+ojQ0A?FT{9<&Ttv7_z;ioSMt91L+mbLgA}(!Vt9oo|M&kSE`3}T-F+qF z=ve>n%7OO*;ShjT@3VKJXXD}h!{kE58;G~kP0JP*-oD=l)h0l^Uk_Eav}>+JS1rv> zvj4*Xj*7+CpTpJLNsg8K?{+i6!yhFZ%)Y?;{~Q~C{Q8%V6J?OQf1WO*flzkbl#iC0 z2UGF!Ry%+9cVs*7;XRq{Lxmu}J(Ts@9`JcfA>qeU>idZCZc^6MkI79!%eLRyEpI`5 zyrt6U#Gk#^9em&alNWO5LptTvwPe^J!MXQZ4!rj@?=r>kp7UtMEIhnpY-~OaL%dD> z22ELeZxVa2UQva3&%fqzTPtNHO7je|J3&qc&AaAkJQ)j!s-GNj&!^y&v6pcpV(byM4pFNgVtzhl4M~GQus7@Bofvjm8!~A{dKyg(Hg^E>-6l= zm@>IzWHSa(G4(s>q|k@Df%TR-4NUN6Zp#-hT{?JIuxVOF5Pl6>xVNkJf)WjMv*UjB zzg3R_`gAN;nGLl2MX&AQi!(?2i`|k1qx$BY>?L@Jv_W~Qclg%g?K+~ zutVq&@2@h?3&umdhb5xrKM@0o*j4KmBIPUejnUMpw4DV)91~+hqpT0$9;nQ0z8aGn&oKV zkNKUfvYwhTDe2;gnJ$F7*rW#AkKQuOj^ya`j zd&VachWEp!W4d^FhXp^MYYp+%aGtS&h4-Tb!+TwD2ANvc`abNNJ$hs50)0<-duxoq zqR=0(|G#Y>rg5N&34EJA6d!vX362<9h6yX;<9&5_`y77}8pvkHY0jS9cJ~cF-cH9Y z+>Y_!4N}+HJ{$=03qN0fJ_4>*EB~pwdPs&C?}(TaPD0P((dXAcTYf)Ui~HaH?c7K+v6zulFF{8jUr}c0OZ**pq7x_C1UQQ(_%F;;Hy} zJIN-ut{0$z$?UidxozQPFYxiUdh%sWCJ)};>df}Blpw#T;?n^J@OsNzX5=GJB#H4B zWoW*dt&xDX%^$wj-b%bddO_B=bU?+)_%H5!`a_ZocRpqrMU;vCbG@Y}2i}>FU!1`3 zKHg?I7Z2~*s<&igA>JR>x)`$d-j1%zk+6bz8@?!On`7gM20oPf^Ya`7d3| z+P~T-wvQZw{BlCpUow3n362l+$7qNV<9%}GtniQO3214g=%Qr_TvTs^d19?|-tm9` z@5!ByNOwHFnpYvXWRL}NNPmtfFQ}zjU z$0;CAK`SuNins=SJG5GA(sTwo_2{A<yNf`=VNHERQ>sq zu?8uC1MlNbE$!G4`{48gBRsrkt}?H_2=Tt((lf-uTh!-q(hG>UR+zC<=yY4utVB#Y zn8pB62iGej5O3>Y@ARp$NrQM#UCK~b_p(D5T*(T`P+|!yWu4wiI#7&D7IFHQ(^~@}5l>HP(|`gyE_C_X)0+SCyyf2Ov!2Ko z@*duUY#)0F@_Qn_@Q>C<3P|><4wBF##=AvuN^AbM?P&Me;E?iZ#QlHV{`Svzukio! zR^0gxu6!&kvr7ugADf)`ap0X(Dft=0d+oA$26%Yq{C@D71pEKQnpQp5-dkpSex4n~ zds*niBGGO;^lY@hXU<#(n5UpWkjUD5OHC@r0xC`Ov{|sb4uW8-MQIHU09e z0!&e{tNXblKzyG(91Mf2yI!YMcGt{RE;^E!VIkHg~;w_*%zL$l!ZsB43 zEQt5}-yO9ziq>fJ@xB^a1qO&L{B`In?ElwZ{8O>}A`^6y>@LVU!4ITWry05Z%M-h^ zEKMr5ET@4+cAQFb&9_yP@P}A)O?lUY?|Bbz4Ym)W{HFK4l&+|PGswg{5#zmx@vin% zY_uAPK^q!$^MlWGam7xjr2acUZT@eNmJ4y^BjQxW=z)`CGsqwgyie0wb1}S44}3=O z@V53lr)2~2)<5`jWdy`Ka=cYw1jO6bK`KNk*BZU^N7iQMBnD_(P^Ix0;{8?Euj2J3 zCUCwlYv*Z52cv^blK&d~8DvtALWdYUAU(p4%YURPFy~*Mw-9>a@{!cVdw4V0K8W&@ zyg97%Yz7Uyk&WALz!CaJKn>4KHG;RL4E~=d6TLxQ^0+Ldd)lk2fUN_?Of*IM7(-S>yjx| z*twhU@s@iqT*8fy*p?|(O8>0hZs5Q>|KftN<1MVYw_kJmI6S<|U)%|dgLqd>dacIV zoM=gED-wiw4@IxK-T%P`eRSP)QT8|n@S3kS8U*p)abC|R<^~g_$(MCMOpgTJg`zM$C(Fo-fzEzk9W4sfP8Zg@8K=R_K`)9-=aGKizLmdAj&VQ@th-Z z^-jq1u^um(i01D7^7_=dD&p1KuPKrnk8kGxx%V)aKHhljpYh-Me_rnT|0g%t|A%qZ zpyEv?bZm(AyS+jJuLk-3C^&X-MUiQNntxCjtU(gzrdz&b)u7qUjsgQ#=;mt@Z-&<} zfb*%72l`qx{XOJ)-MEPA|?%vb7n+jaL%Dw(%5Z9pPyEZ7dKirOncnuxg@ra8W^zoU< z8Ru^PuR*W5^--a(`Oo?PP!7C{=KpZU@E*vL5y!*3WwX9_Da3o+cdki=}-O#lyR9;&ItJ zi1$pYuVpyId)|7@n~x#hN7dsN`RuVmYkzLq?PJ0K=94}@$$)tOyd$~nYXK7&eYj7z z?4Sdg%nv(K-s0me+we0Y<|++LV#i7Kgm$@y;p5$&I%kH6FYn=v`FKf?-}je2J#ryb zAYI$$_B)vv?-}-<6}ojXXlikI=oC;(ID-tL95&30s^@#WUw+8q%12_STk@wJV|Z`k z!28_ekXabsf7D7v@bETX6f^J^;_XxCdVz)aZQI9Jsv+JB7bzayMrvpaVI52{rd$_;^qG?G+Poh4we@)y|&#Ju&!ruX;F1 z{=FCP;f?uNO_1Lax;N=-FBR0TOu4AAofvNq_nnq=>tj&T!DGT7B#8Te(!5RU_HL5m z|H;Y72JU=>%i6LhCm|eopFJJ&clFjNHc1!{Z_00>2Y(>m&dsl6S(_6W-U7J`oI_Vw zp>5^eYMl`8&6#ar2QG?3;Hzi?1ERZo9 zk5_}1imeM64{K1g9>rxdtU(bi&N|6(h$Z#kIppYKi)v0a9+-R__W#%1ceNIDe{-eVs~M{wYMLFn?|8RXFTmsC8w&n2$kvKZoR`E+zv zD8##K^QDmrh_^GjY;K0%og5CU&cTYc8K8mF@m_@V3s`nNSyh|I`HeuD< z&bpX_hxev~&ncb|Z@qGd11!8nh1C6DL%fHB)D`a-SfhhdsqZI;Fu<|TY2z#*-pd}7 z)IkmtByQC8`@Js;BzRcPe7+kW@1N@?I3+^7hSSyT^*`p9?N@pV?JIG zx&xZN_Wj6PCw@*BTtl{GB?Zt(O z;ZrZR^F7|QL)`gj8!qbhhj(xP*Z=cu*Z)6>!3HUYqXt#Dzx#;|u};RulksZML5cUx z={7~C(>8nCguohf;OX4iF|Yo}*CNe># zm(8ACg>*m*8oz06GJXvj=X)#n;z!!wIOdcA+x`{!HK23El{iiP z(AW?g&4Kr|*;~CZyxUL_89coA3btN42l1XiXX9lS-utF?uGk9k79u^p(_iI)UaVZ= z+w}$xu}vxo*%0rQLreYqlbHaVh<99K)YK}zyQ zK8DGM@IBrnPwssDj$SFW^wL;^6vct}RmAEZhIfK-<3v2X+uvVcR71R%Sy(G>f_RfM z`>KK=-WoZx+gBIbqkmp@AtetPK$9}hGZ^CiYxScf&s|KQ{7irGBnI3dO^ThZ;*XEF z&jhi1C40gzNa5s!&Vl!3X6z&k?^yNo z(s+0)9SfQB65?%cm%oFBw{?p$%^TwVL}5XdpPL<8=_x3<=L!SdlRmP?4C4KA#9eFs z9wxX|`+doZV{|ay?$C)ziTHRIFU<>~zlD<%c3fjQ#CV7Kt-aR^@qWLm?E1r6E)FM_n{|Gf;K%n366p$;K5{ea z*zf;Ea^QU_LpvG6TkrLz33zz-X6$etf_OjMJlxO1TTFcR#L+*UoJg<9@d*#3W|9_fn9{!23Hkr&(gDTfp{cVu$hv_Te)gWf^op+M3 z1{tl(oxc&*pbfWI_7A~3NIr?nh#1JPK~*ngbpLTq26JoYx`s~gLp#jh#i3i7z;CY! zC4D3kY`8srVpJ9WH%ND)-Q%5PrT)fs-`VwE_Y3|Rr0qJLv)8uqUJXLoK4J;-n{j%V ztXnD#^s7(kn=d15N<_@wX`cGei=t3bQ3b!^65=~ZNV0S8r@sm2`xzujfjb}J`*JKU z=CEdv$>TWiMin0WVMFYOx4-4^@NWM0+(aGX&6uBkl7)94iYgwBxEH#C!Pd((lhA;q#VC&-VFrM}onajkErg;NyL0;a>Gxn$+JoYnOr? zx%c>ZSIYEHUG$ju@XlcSAj&WCgx=jPwo(AGo_njCLX3BN{jHjW-WXIv+Qh_R5i#Dk ztV3qGHooC|yyvXo&PRc3V?gQ-*78;|i39JOKZ<-Xy!(dgr{dv#Cro;mImG*qdL%U% z;=TH+YBK8s>5O?`k@_`fRNUEl`l8v%VE=irVlKqHSIT*UZZs1tzBp<(?^PraxP1LW zY#~10mR;=+nb94&Tbn{eRl-B^zIN@IBsfT>3Cr^vm564T_N839y)Xu-m|;j4JJao4HcucuFqbHQjcBzR6t7x8lxW!s1R@Yr;=uS zVwvD_n*NkrG9AP(pe{N41Rw9yU(@>ogrz_nJI?Q!U~1zKe)azC);TV}n)mR|XZ!d? zklzc^Xn21W4KNU9U=u=&_fePp;xOY_^aEr3xQS|a2v=`Sdp8CrOnuDv4boCtFjqc| z>TImK_K)Em%Ypaxor8&3_0F8=Hw6!G{fUfc5fJZOi??rBc&iG3H;9LLfBtmh`SNHd zGZ3|X|d@7Vw@M@5B zbFTCbYk0-(?!ifcum<^e1d@DU4XR;w$17}fLkkv$-O1RQ3hCPtxoh8Giczzz5PZx$}{& zQ+l}epZ;Hn1Miv%U;x8Au5w@+9^O)lN6b$^yl>_s3>Mx=nOZR>5bw(!vM=PWxT3+s zq03SdlR<}Njp;Oq_r=9dQ~Lwq2hzVQNi|K8;MUcc-<7-Z@m^~v^m(;~6u8ZfYkgDe zeV`p5Z&bllYQF^U;k}COqmm%M+d^Np*Xc`vh?tH?GnW$MeLel9{O-p|s7cQX3+Hdd zco*trNgV8Z%l8dZ*BtJAv|dC^+Qu$OOBUq7yXtd@B!+kDw<={kyl;l=-E$M-9jJTw z3k&Z@&R=@OA>KE1D^I+5wH7^msBOuKm}F2f|Jkbn*dR$gx-p~?!UXh}Ulkp$M}o`E zXI>a?!N>dJfc8kau@tz*j?=cfx7PGAKHieGDI#`c-ov|u?Sn#)pMK-uaJV-O1X`NFw7oB54-?@&V$I&J+N$&)9z*g^WZEp+`9{$JiAed5lClK!cM^GnB8Zv{B;zEf5y zjp3bfDOCv%?-jLA-#&+UAG;ps9R%^dn-OsAF5H}`G@&${Zg)W~OD9atibw{_ZZ62V z4e`D^vgxUBC=-0VbY-LK-AG`&JME+*10V0w3D?Wj^rV0TJ1%c)gvh+-_;_bcnYL&0 zPu^>gir79f3G$0*UaWWL7!8O`D_D0^ix_X^Svy`$`WcUEY#X2i9IYYj|4*vi4)x7_ z!uJhQxDj_g+QU+^zU&^u8{xqF_MU_g3~%cX{)%{bi@Ke2`2z8NEcJ}Z!h1C$^PnB# zoxT6jkrGK4^wP4;ex~5mlR1@M&a@l@(@3H>}`u_kfeSFK_&w9N@47Rr&NF|9nNbRCFQ}0nLsD;#H z)O2bBHJs{CT}@q1T|m{MDpAK%1t{Ms?=nBpc2ew+*iJFJSdf^zn4Orpn4XxL*kmy=(P7cgq8*}*qSd08MGHi;MfZrt zif$717IhL`ENUpKAu1xyS+$EfFP= z@gf4k--X``w+hz_-x4krJ|UbToGiRec!RL3@Csp5VI5%=;Yq?GLcfH1gkB0g61pQ) zE_7NbOK7)Hv{0~+r;vk?h0r`9bs`TWkj1}>cZ)w4e;|HCyjVO>e7|^-c!YR>xQn>8 z_(E}Q@oD1H;zD9WVjsoY#2UmZDW=E;?fMpUEBM zMshXzGP!`9P2NL}C2t~olby(m$%bSNvK*Q6KWiN0F8t5W|NX@Ke*=<;5LxE_Mit|! zdRvh7n414S?GX}yDMPeX16hYDgT%s2#2-`htZL^Xewfl%ww#9eVoFbBj~3#CDV zW{5YY<{ns)fp}p`+im40#1m6XZjx55I#L1u!h&iUjH&oXlW|$JQ_+f#VVoFr_a3lgS zCH!pna%3TMvxKCo}foNdr zGt(U)GcnbBvhEV1j;WsYhJDBkOnoxS{Dr7t>Z3?sE24_2_w7_NqJpV+#Ri_pbWC-J z8#^P@F!k2@iVdQSsjf*HhY%%9b-tUChA3j{b=m3nhytcM5*Keq>^ zTMUq?m}={N@CcE`)QcM?r;sU_YTb4EC^8vSEskyKhzzElt3D$mlQ8v+vU3kI5mQg^ z29+bym})wGim8Si&0PouQ_KzH zS0Iv@syF=g4w1lA-PBJf5phi2Z%s%<#4vU5{C71(6jOIY6Cx22OtIG65n)WRmM0M* zOtDsT5J60_nqNc!Q>Q~DahY3#rm9| z{0&pAub;_ZF~z!vnEVA(tZQ4zgP3C7a!DS*6zftzazCb6cc_v3FvWV!i2NB-tjAx- zy_jOXl|k;o6zgdL@+VBOZek~YWGfZ#&2>Gsny@cB_j!#T2v1Fup<`;r+^z{oB&KZ0 zFWQl9n6i3sKN#7HspZG&>W~ObE%V#(0NH}6rMiYzNI0gJOcr~Egkj3EePbySiYbdc zttMnMrWS4f(}--sl)1$uIRySE_-7tsCRb&E1Y-)ciZYRnm|A%D;Tt3fQzrCh@kk)1 z7P!1Rglu4|>8uy7$saJqdJvfW9#gFMQ_1fz#d>a%+>I&L>wM(5m^zx0tw-*{)R9$z z!sIuY%AWCwMDE1YVUpz=@@q_GK7Mh6+<~b>StpapuP}8mSn53aC8jdwX_k`PF?B#V z1d!V>wXb=XDftDa(vR(XN^Zqe+NQW1ato&RnkAN!pJOUj#$S;93{xo`ncv9GnA&{> z874o))UMo-8{{TT?Of{UNq&N<9ZJ`BkQ*_@=#g$AKgLwj<;qs_BTOZx8l;dPVk*JQ zJd50bsd&ZU>0~CRw)g%VB-djqwt9yJxsI(=e2%ByMpCff#bkVXO@4r>XxG6W@_kH2 z8Cy$}?_nx(#8QrY7gO8r(pHgcF}3yhg#dC5rXqZb%gEK3+G0W%AXi~3TqNfq`3|N+ zpBA=}Z)0lnF|?dqiK$JDj$AT|sgT8Mf01utDp-vC8 zl9T6=D=@X*ey1M!8m0m!E0mD0V#@z*y&3rmru=U0_99=#ly5?uGx-vxe5^Isk;^gV zt#nbBd=XQg-;0IG7ck}V{B9_@3{&n$jxHpZV#>{jszxrsl zTn=}TQX>-ONUiSZPgP$Tu?xvS{>q+UJ5_js6fFI7YZVhXZPA?_Do6*WOq+E1eEc;? zx$YC^G{U5S89S~x?^4gVulQ?_KfkQVPqI|zx&40`wvQo#{4P$5HCS&!1GQ6aNBW`PTYoTF~s{pT3?P+jXPRpyz$$uf@ENFt#E@1#9P&? zq@&D*3Fc3@ZZy0lXe?|IW>s;dj# z(Wfol&zL#M!0%w{;X!!3rN+N=o`^dW7)lylI($D8+|xY}CK`f|w`-Tg`d7hl2ZZ;Ga=q8E1ZIE?{!Db>y~W3nVt;nPW?E16XNZvb^hT&FDCGPbJ_N593A}r z{6@}H1OI@uPXGRiQ$nS{2s_Tz_=bUjzAx@Z;31~2&d-Ishqor%M+QND8YjEL(F_`} z6Vbc+!-E)aOUaz2XZ&}dce=bi&ChUgy`{BK-@@Y`_Uv&vqb!)@bR|Y+8W!Z z!Fzc7uzjo`$nWWvh~=+rq=3x+>%D?b#CQjPj*U-*XKzz$dTkGFAimyG{hM&dDa4=e ztM}z`B3$`kRt=<0-k$N_`F}oW|5^RN6h{qW?TuhHsOOfjHeL-1i+X%7#;VA4OO*Ua ze^`S?uBX@!!W!hZCH9uaRCjb%?;q{U2i~mB zJ`C?+<=0wxc#}8zh-5*$E2r#pTnF*4e3kO+EyR0+va~L`#vR>5eHyUnZZdeF7QUGb z@fM_jk1ws5U{1!Q@u$B;f&$Wg&HeHCLu_Z=t?8n026>hpCx0N`Gw&mQ|L>LF*L~cI z_watn_Cb{27H1(>p=c^t`_yQ_Gnae3MXpSH^0BZ6cV>-M*gO+~y;Tq6`5teprQG?b z&AaV}{FxM!Sdf_OK1M;*R=!W|tt zs9YUToeY-u?1*^=m$xQmiN{u~V1nmyBR)!R;P?OMM2)_Mu9c0?J2v6O9f57|{D1r1!#1*1%>Rk!SjY0?=$U)F zbW{8_{^>1*OVY`Sok!??{*SMvu8y8vh_zPk-2Bf@!JG7a5t+AeuIX|t-dnHB823Zo zW4g+RNxTOIqW9f^yf69-)k_b$BX09W4zbpx0ER_jdv`+KK1LT-J#uIPXDcV!SAiJt zo^_ROeLHsdo_;U<Ki zXZw$Hvdt;L%cpfWr|dA2VUX+mL$d|6N{_9VREPn$4BMFxT*mG}raz?;?kd3-q|rG4 z_IbU0{}_R?dAANOp$Kgt>A1gtb?!Ek>eQDvr0`{u?HjqPp$JpR@&oz1+C*Z_rLSo<-59TKYYc` z{^F%iQ!V(s_p`U`*(8~ScrTy5sANvXfV9LhCRWxLH+JJY0{@yK-QR^;2U!Vpp|4K12flcniWB`(JYL2>tUmrLK;3 zm&LMPpPB34JQTc1FLjW46E?>xWAV1P(q^}SyywqLUrgGZa4i?@Xo0+I4h>C$#Hm7SBH>D+ziv)=PgpWDR`6KQX=!N<*`!2;@!CWtduw8 zeX&n2j>LPveUZ^m$os>MpHl}vK;E96DUTnefDA!%&kd0GRR)*43rykh7Ad#eBUNI- z$J8w+Hs8SJ{Uq>n{HYzpzj0f3)>Mn7WAiq8`0&Cz2ioi2&1fBX`Dt?QBrJ3xf>Rml z0^*nPc@Ni}*)+615efgw!h7N>K5qi=0l{8>Hu~@05>(b9mUaK+f9L;E(J*Kr1kV3U zDS8m;Jxx*%;(*^Et%>s?VD+G#2~DhFaQ;sXRjSJz;URa_vx-*<)cPy8O#hS(-vK9P=mU~UZH>ZM`@ zscmaw`2EPX>Z6o zk3oB$3FMtbxR}U3<%X!bcpb8Sm;yeIIx@Y7x3_+1Z;InoXaQMIWQ#KWV}beU&-{kX z*t`o02+RN>f;DKI;DT>U+Rk9}{+_!=(*Gju@jiprftO$RuhK+l6*K@vEPrd)^xqsH?**fZs*Rckb~P0SexvH|fc|(+jdS zv3M6|iQAlqyzlEQJ3!)n>`d}=Ysg#3Gp{JN#0^oiG1uaQD@du(T%i)k`+!=nQO(L0 zV8iWUy~HsVm{S&Jn4@ufY~o&DIfl)fFH_+A=K|W}eGIJwFTX1V z#_|>=TwvLdxwgm`eBKLJPkM`}rXW#O!4H_f-o?Lr8}0Sf@zDg`^Cs-4t`6pAow~jI z=ejpP1#i;P5Ma7Dl;E>Kb)YW3^`KJSKRHW#j*B!so+r8$={KJVKI)h@_vC(?O zzi|qL2dlnvV0Z6tg4wa;QTK}(St~*J&}44 zY5srj?ZkxDgT}jcO?oZL^uLsvC3?ah^hUVs_AY-F{n6|z!bPnfh(V9Z%2V@FLBZ8k z#?tce56FIQBmCQP0j8(B!iAnCJ`a9;CgprA0iN2p*tu)4PlfpK@XMphaq1 zt4G6WuLo(Ob>QWfqS)s6UWE$?Z*O?3xQs;~4@{+NN0`<8MC8Mn3j_8YRLuX|eNMGvec+TL?5Lh^Oi4~>bO*+1e%-dE%k`asd*BoVC0=&fDn>;X1;=R05_lr5? z-M)@3&ic3q65SJ9aAYC{OuSj9FavLIMfIrO@8@p;dkuZ-h;}hx+JAem?mxc&_vC`c z-Uj%9^lvmyswAuR=}+waf5&>HG9rlfc$4dJ!pZM-%Vbx|3>PrG(I!zXjn7*;By0b< zg-J-w;}@rkh4AP9o*u!;k%g0V&zrx4x;oAd{W#L{=lp*W3f`pi_{h9_vWDkl@iu-q z>?;g;3;(?2?*(~-vu|}7A@AqSZ7WYXdLT!G)~M8dP613Sdx_1EclDVn*5yJi;Bx5Y zi5Dwkz>Bs8FY6CtckhagF6sl2cLy4m`FWA&r++-Xbt59GbJted<4vvuFTcYNdW6rZ z!7pZkp`j3AeBK%2F%?(XlaMCfno7HN`~is&yw%>WXqN7I69TELWB0+Ce3d^hNDEW& zCLJ(I<~?%yHUk##>WP`vAg%w`P@U- z0%(u-cC?NkIQhjtIJ@}zZZ05jCFnf|5udkyW$;UoRM(^MbNEN%LJhIPh zp!@xQ{hid+q3C+L`Nh7u#fcCFZ_I8YSua>YO?Y%wSu4C2#eEHg`61YAZ?)FYD`y|l9&d6TsyO-Ob;s_Tnok60ZgYtOR(#%WBfpEJ zMpKcXop0su=TI^K`^8nW6@RDy`9FxtIxabV)BJD##~a~jZdd^_D+CCMy{3FrUb z_2(pW7q);)(m%&MOk;pyQ_5TabnHv)(`LsT=XMc+F&d|5#~hvVkMsW+;%`~~PNcma z)PmNr04KlujlBgNFFC<^>E52LuJ}DjHe#f%W_~cES)M)+d@3)k=B2~TX^nqgr>S@8B28ydIC z$G`w|VXq)h9yrJRZYS;WUX9jq8YjP^nS*y+u5bbEjpv{EIpFiwYIZ6!R!c-eXHu31 zQ!)R$tYo-k*ga17ygjL`V;AGIMXZ@~`~Q*@yh*3}lX-`x3@*gtz5P~+>ORPO0%Xg0 zK;9y62*&du@8X$@YjZAmAYyX$5u9qUds|Q6Is$o{i!fL3=V$?HQ4(cpqtSrH$;yNS zVDtW3)y4W5@?M0-`5Y0G$bN*)dq%b_LoAl|cn_j={KCmE?W(F2!xK*6*)#9vYD;|H zn!K4hmz5F`Bd%Um$Cp&h|7)F$Bt&QEo;QKYI)uB1-+e8a>)sL+yh)#_AoDIUt6;(6 zUDxfbR|0v9^&`0?-shOD#n@_5Sw?R=3U<-F|@~<53M5!C%^jC z*sBi|xj^=&en)0~eBM{IKaJ=n?LvNX)_xfrx`R9aM-|@N(6rKp?&tq@D(kplba8>MF7@cp?m{jJMR; zQb9*?)PyDEy`HE2X&_GvP!_*_$c!ll$kpEQ(%*>9o8_lZWXNtJP(8lQLf%o>+7sk;#0iQo1|k5DoHAND^w z#Px;#=l?V+>p1GJukhdePaE?+UKVivUq;b`NMD{J_aG5tb8f62Bo~@`waL6p-}3xQ zR#(`A>Y7uQt87)#FY2iUm8tH?xulO72}mkLNW$~ zBL+DFcGx{=(N_IJfdnE5MdN&KUwZJQ2fGJ-X_jz*aFF&cvCL>4!#Me+oK8i=TsXll zk8R-xQt*3_x3;bHH>Lzc84;R&_=<}8pCQy^{=xqb=Kq0hRMoM0pMT@fskuw6JOyvk zr_{*2f7oylv3Otml)a!E@^<>j8cX6GsedSd1M+SS4L|N)4nJ?Pz|&wsSt@wKmzo?8 zdCS$NpSJ$h49r@(w|#~KlJ*xq1pygs-jlca&sf3RTUuzGmPxG6oqwz#!)K4$j%Cmu z?@_dlNSyqRcSr8*+Xj!f5N24+7md$b>BFX|$^HbyZ{7VD(o6C8|F0erUF0D}{|`vp zBvMz0!J76*JO1qd%Te$qeH)O>yZl!lCl+tMBqilp$Xjru{~(Dsa8kDFg7d%Ow%3cq z-?$@Vo_@bWb5g;wJ3O8nAnzH@qyEE$7Lf7!+{oztXdt**qkEcw&0B@zx)LW`K`uq( z_`bFYAGnU)y)Rho{8^e#d%Rbob(G`ecYOSATizN@pxkif=fiM(-tR3>bPW$CAgyZ` z_b;Vp|KH?fsiemL2lKxXb#(xrz!NIvbKP5(f;Z`7mt@|VxuqOfyl3P?HVeQ3Nq5uG zMmNYiWT&+KDahM$`~;UVCww?@;3-1G~ops5Gy7)!KnXh+n=YQWFOWg)0oaui4zZ*ea9o}Y9zeWzt@s^?BP5OE( znYXdwZgwo*gZ)Qh)F5w8guj`@yYt0hy#eHXEJ6wSVC8{GZnAaQ=#dKc>T-H9LEaV} zs=oD1Er99U)rQ=*Xt0zwZBsc9cK05BUc}RuNCZM?oCBM%x>X%EZ%v2S%jIZraq2|MPz-m317i z6P5gL{>PiVY2)W`{$EMagGk@6Cift_Y`~AzgGNt{JFbQ+NZDJn?Jlqf%^NN`rW~lE ze&dWbQVUTv1{7TZ0RjKN?r@F30ad zUNy>0$s$q6H93OA4tD%YEJ0J`iN$~?{qG>Hpt6qHh$%(bgCOq}6ue0vWGC~U$HBvg z#oMyrioHGLjW}7EZ-Bhd%&=?D!1+Io)oXUkPd6lahv-9^q8zusAG_HMfl(knr zHt#sX%i`mVw8vW?tphK=ib-|e&|6%Ij1ZMRcj>~PzKL=kg2``I7i4oC-E zl)|;V=zoKBx|zB;dUgUN>m^P6WYd+`{k;+BLe^yw7}--{{Fgd%R1~Itp;|OSrw#u4{-B$QWogZ=r(s zCY1Nr+aFcihVd6CSvgJ5fagoPACO`)sH-F3hjG~X19S8LathufD^*piys)R%YXg`%Kzy z$hn}8zg@4T0S;cPyRYC1QZ(A;uE)n_P~4@esth+ss}?7|PWpk}gG~BlqH+!r!8J54 z`hLv&OaFL+^rfMYby5ZG^&kVZj#ixf_Qq_AhP>a3vGC?V-e2E#YzA2|Y-fn0eo;dk+|9H0Q%REkC z>2v$)vRC-LZ!dRL{*WAp9G9}IVF<%tLALGY`?8_(1Ksmhj-jp&<;9co!GFI0r%b_n z>PTG@xqFv&K3a;!JA!CA*$sI&YGfvpcz4fhIQA6sR_I`}yyoSG#NAo}hjw*1fCTO|tKKQ@UF$h_Bo$P>ikJ-leN>=)$S62mx2;=OOnqF6z=Il&U# zsK6WThS+ArOPq*G153M3JA^^rqfW2(`3^OMR$k`K$%Zk2J+V;C!QKb+UyDIf-%~*X!wO_2=V6t0;I+%6H6tdz*CjmeV0W0W98H zUDorK!uj7m)zgo(_qNwh;DjsWZJ9ik+;zzf@rmLaoM({+3>xqEJ3`(}gX_|Khnqn* zACqeneE(mx#l+?u1NPn9EmLc5ZJU7m|7e`}?0(s60odK%SF`41BscBd-r9uL;e(Uk zEZgztIg^~gwQS(2z;%4y+m~&h*DDl-1oZFbG%&zld+RN<>DqB?J>4%(Vt%Zns*VBi zvX-*U|Gxi6%VYoF+~EAL`9D2KYF@v5GWil45ici&)q~s>IS~PPi6#CL2wo3+5bI>t z1wpuiY<(2<>psC9QM{?}La`miGm@K`R<3G+^%+d*gm1B2V)_Z@YID{{d-{ZwkJZ*OTbJ2i+K^u8w)eYBxTm%+8?kI@=l#s z))e@@8GvPG^82-7LC~5*U+xNG^FH(K;jdHN+`u1=i%h8NUYLf>J9txRu_2&6-Y3yI z0&wz^(q{KHF6II=XWI8Cj^Xnj&AMl+dngd8NUZn$Ld_?3(lT|2+cW5%HzAd}I&|KR z5wgnWZf~vrAKsF`6Hlxm^WJG&CyvGYM`U}q9pqg<-D%?pd0)J*{96g~KKRnK#c-D! zLYPtv=&DZx1#XIC;*hr-o0y|RcQZJlW8G@HDi&PjRP)K@#pYeBVe6g9#tq8JaplAF z`S)P+&gxR!Go?m*ysOYU4&vmuOH|V?ub&I7iBi6}@hd)W=lQLz>%_JrM}LbsdKlsl zNUUagoLz>W=$`i{6YA>F`VsN$__jIT>J+?xna=u=dGB{l6~p4a<#>-n2;|LkpjcYz1dblG4n>SMhYn=NE+T-1V)-fL^KRui8H>%}{;G0eB1MyGz zyfa0WUs*|PN3@d-%+D0u#k`O5cM&Rs1oK&R)Bgsk6qR+%42qqGA4r31Z#4?uvm)+M zWZr{%uA*4Ht9m|2?}NN~`EMzc_TI?6vtPKXb1!#8ijtiKUPIp1Pn{|z;QYU}mieCU zhi1^QpfRamCkCX{mmWHcp9?S?F=apT7N7Tx;w=GD9nna?2pjm)iU01cWn+zc-i~c_-@QK~)YV~~ zb*5-MF6+PZ|Nr(k8vYCHL3;nwgQS>WW&B-13JVJ?!|Fj^E z9GhPY-$A+_Ix$9g;EtGSuZ|Y4Oao%;MKVbP(%n@u8%YCF=95e1wQxXku+!UjVm|gI zRh{TfgKvBcQb8WWG40{RGI3S7kF0mqL9kMw2`C4&U*sLc4=PWy;ZL$mX z@x;tB?dl3)cLO&WPxri*#-IP2H@f_^dz47`J*dKyx;h3AT?lj9GdKV1Qt)QFU=l*U z#D?ee$zk!X(tTrI1bL51%$z0helm7W^a=Nh39EC$&s(bL@4MfLeTm&{Fxj`jh#Qd4EE0E48tVrSlQ_GLt(vZOCy?NqD_saoSknSoODe)111sVUL%PqnojqZ8Jk5E^K zM$)CX9>?YeBpnLgj63JgegBWNgLF~ohAbBEd<|!%+mLsC-OVKqkhegg$@Wi>x6I3n zZ@#C)ueSg2-fz)5ZsO$E5cz!MStA$7Oz9g*5X9%5aB_ zS7f_fxd@+k{hOy3vgJO~J@2e9)YZXOJ=Ilza*nq)1@8q`PJcHiUZ(Gt!Q$Q6@=^Ld z@|lnhctCnx z-r$5DH$HDaul+U)7AhmpleaC>s&2xc{}T;ss+gncfBw&;vX1&ATS*6`!L_#*1@HNs zvoFYtla)ob(pbC&HP5imLf%i5ENAArch=RLM96!=3fA&(s_w|e%zy^F8)@KL&ATrq zkoVF0z9XL@?*OCzM?=}M;JwD~-3mdznEzUemiwgNljR1T2FR>g&>_;CYxIc|qcRGEQam6I?;+iJwf> z$#q9wiT8&;ge%CBn*kSxA#caTx05&E4$?by6K}!V7;v@v`~lTW?C$+RuJV~J3pcoo z#?^n=rSnJ~`~MD|-cK9HO=ypI7h1>5-1*$)l{(S#WpMp25@uV@CH(zG50v2xuk9x~> zkavt4tA!op9W3?2(hc(FIumNw(&UabIln2aG7k5D>pcW#zjST3dLOf2k+#U zGi!5bk9Rm)$61{GczQ*Ggy8)SNB(GMUUhulQmG@hL&AYz(kAA0@7=qYzen=goA6}^ ztN4Ro^nZKn8uuy|tDWKlW@OWI!A z4_A=YTlY`=hAYS`-alP+gk!+w31@kcx7a=9VO{*WRCjLRjmEuf``Xkojr|PL{8uWI zZ;NQJ2i-yIn1_>J#fW2JlLQfbWa`i`K7ikY^k;Rmcu@mfGuw zAn&9|apBMTZiqnYy_CrrxPqMW-9@^+<-hns8aKSXwX{p)+~{;Pc+;3C|L`9#NV|Ci z-+yAw4LZ;`WkF3N*M4l?UMbwEl}Blhw-Z{2J5GKFO4Os>yokX1wc+}G>G-_)L%X-V ziVH>72FMHA-@1)|iDil;ZU#H(o;TrF1a);>ulHT{X9vlYf;TZ~7aN&3Yt&^GEZ%xM zH52n7Z*QBDOcL*~_1*{1lkVP%Z)|pIc0+34^G2)~Oapq01^b^u-s4s!Vug^m)^sC# z>FyYyU^{Z?mLc|lG&NCb5n{{@mZ5Qdgh7#|QrO)-Z|m=UW9hWVdkn4P1WtaxgtS@f zgo&U;XHSMzEI#l2_*&%bv;*Q?sXFq3ipN_Bi!}W2hcnRqfE3S0T^+aHtshbP)4fe7 zcyleUB9eKh76&O~@!tRV@~@ka_v-7C^GTZ%^*&3_H$vVI7aT}P{^f@3R9jo9|1u5q z1;ae-b7*5w-Vv_ysZgQ$EFWhAiiC4-(Iua#qHi79>fM*YxSgi z-pTi=tHZaMN5(yFZgFBv!JA{2SAonM>C{ug;w}Gbt9J+FEy=t#io~0+!24Yv5(lVD1HXN*Ge3vC`7(dKJOX(;_omeF9*P08p>NovH(+<~Eb#Mcx(YX# zM&nK{X{jic$L4+5{?SI3NZR9l0IeevCqLGvjY6l2i9j`{xF9$XpZD{;l<3+J3nV#o zXlAg!370qF#FxhhqQ>Zd{x7Anj?-Hr)&D#HkJcvr|9d`gK(eCfK?2vk;z&J+6FxzD zVVxTRs|RWP;D~57F4IrTtn;vhJt)^=dejWwVwXiGlEnwz5DxuvFpXBo~D7_gR0q-9}%~4gFrN{dGtFclO}c#+VE^4gKs_U z^`J_$4kw)ah>0iLCu_LCqbGgmzg@=fK`))6z5%y&NL%Bb|1Vb810=@4P^6 z5Q@g#DYUqxC5g@3e6OXHdNu9wK91I5ij$w;iPh`d;1i_NUXB5mO7MAGnB|!7=kZ3y zj+EPMUO@%#PS)a+P4DQQchM8->QL$GZ|(T=dCRpFy!keq|NHdTxXDRPEZ*r`c061J zSCGFN%1x~x@9?aAiR+Me*Ujn5;xadcarQ=An_fE5o$?jqfxM3oc|ZODdH?26w-Q|& z1FF+TljRw(yLVB9O~rs8H>g14x?MYhr1-FTTkraz@x6lfc%MP*u)@i2X|ZRDh7A#n z=YBT5at@!j#QP96Y`MvxmP+hB;F@Izi}|a0ckAofy$~>H^jl->eL&>bTHVcyod?% zR``<4{Svn%l>iK}vN&>nALw2nfY{Ina2IqJuWpxw@7ox}fP?`@w(yoq2U{>O=A zkar34A`x`oy<2Ojt7GQ}_37}`|K9)qzYp9r_D|vbZ%5ICL>um;k>`K$c}`4NJ*Zil zH$o2%NY#N#OV+?129rpJ^3>3EAc9tHF3koV6++5B%5V!*Sdc^=s>u(@XT8t%Uc=l>QoF3v4eO>Z%F ze6M*L^Gh1My_JF1@eU`yv6X!(g7EQ{VjkN=Jx%z$*Z#cvWs{B#^6{{xg~c2EBX(+3 zo_-2$rT+ucI;gDUV!uqu>OaR@+EDNow%?#i=B@8PG9Qcgqa6L|XvlkrJ9pk%$Xox- zQ73-Ldt{AW#WJD?^22f zx{7pb*&zF@!COeceT>X|Mh0QP z;%)PB$JrdnTg-bRlEnMsSLGK=A#V%6==b^A?#NyCNaMz^bWkCF9-*3td^-$`X1cc;b<#vhvF zZB4;j@H=xWnYXw7@p)LhM@|lCRYKl@^}Jt5yic~DOA&><-`zeQLRjFA2#kobY}}j< zGP4fUNkQH*%}%z5A#cBT;kEJ-G2mvBre)JJY~CyjG8ot+xWNrH?#z1C-3)Bl@ug;M zPqsDD9&aYJj$)krB;Lu?*-vqSb>fn;95?WJue_F@wC|u5QXFkNu;u|34=1kk@--^# zrT_hZGb-!Iu3Rebr21#srCga)J7|^c% z(OoGXd;T9>o9niPhX=ew1}Ib&52t-EE5q+AT`-qvnVm_YLmVaYOXqgDR-3!`fvLx`X6M!CNZE zVlSC@inBNy7Vna7uiJMZ?_W0V8s?BUx6CFLG06K=6t}3yX-`D)?#PP;*|DK90ph-xw`B}c!QfLi9&iMWQ!`#HWjBJ&Te_WVaqDK< z;|ay^(79!CKu$1 z*L<<`3VhzT#uQ$PGSmOs@Q^VO|BvtFm|%38$cd9=czg#QRcL$M=zl2Hv{4 z`QM&`x7d45Uo!74g?pH>c&p1e6pKOLn(ChUl)QWD5~61z@6zRrCwD^LJG?dY)FJPU z_I=IxM{Fj#(fud56ZOk%i1bHdzaV%w2oAq{E+p2Ehe{#;3EH(&U|53 zeLORcYx;DOr%jN{heH-6?ZJNr={uumum?vM-S;2{cIxVQH=CEXGh^=j|BV#9m-+5B zAzxzWxpNS)c&i80@U4Wr=l|5}A@TMwmdUqT`^392~$9pSU zM=(x)MZ0Qc<9~30*EQ1i_x~5XJK`G4ro8Xqt{?-p?SJrjTN~Z;Zred!9WMP2?(*4l zE65ELyyXqF^vJyPzx8us@&2+{XTBBWEwxq5*%b0_bK}W0g}lFB5NWI3>4oSOvRW;L zyc2hnuCa%_!)$|6Io>vdC;5>A+7F|_AO~Aak_R@|wk5#}UR~k_{b-zegH|WcPwWlS z&{79)Usl@V{S>Vu5GTKp@89kU=o3N4J(0&V-1yzw)ZQqohr<+UIXCR&Ma}URZy!uP z{_&dbc@u`ItYd#)tNfqiEnFyg%W*zrA@j~bsyMKCKN;~E41m1*jDEI|c>AvZsGtpb zuVILuR&nt{N(DSOT)3VNg1`N&S_^q^+3-vF2;}`V_EP-^w;0eH%pOG%PK7S$Y@qUQbF^Q93=+gq;PmDzH;pv5k!@uwcqEiS9h-3S(~O?J9Gy)B ze%ibDC`{w?Zj066^oX!U+}1BP%woNZyErM>RjsKKOaHgGF4j|5hv#Mf>A=JP&Hs2a z98LTj&i`H%JxJ+@br!h?UCPno$Lc{+^A6a@8kXt5YI-4T1bfgcW8s)V*n{>@jYB<~v`od(eQB*%8LGwAX{qqjmJ*-cQgt@ijklI9_4%K9w&RTvxpgrX?_^$ai7Lo@o46#aG31@~)SV+2^453Wyeq%f3$d2tDoQ}$3UbKJ z#1iuMTNXOL3-VsUyMo(TF%~o$eaU1yfz3Na%|2YwhzB&Gan+KQ^?m<%;_DyuEr>y#9Jk5;WcN-+bf^# zpjERM!h1d_m*qw}cr2jZYzKMQx1UqyfxP>|8#inR@bi`%#Pd&;WAkpVFK+u~!UGi0 zxOt)GjpOau-CM@&;Le6~wAa1wqjiYm_0^f0yp}{|RTQtmE99ZBl=3Z@E$MR(PWAK<3Q|B6+ZQUsb#3HU@cz zip)+>@@6;g3}J!1&un~{!v=W^6^5O2g1oQ2&Gtv&=0sTi(L7gcI~j0WltuzS#J zu}o2^)wI`x7|=SNc+*-XJ(P25C+%v&?z z-cl^y3o8wp#UXD&XZ9Kr@3wE-t=B=`vmu^2K}lZ7^QHY|m-h~y$BMMaTN|yT z11CS?^MeXsQn*03SJCB&{{`>R*Qp=Yf4_svd*{nC+q0Kn(S7%pF)gR64xPOlgiGKK z5?q{kQ}9-0*|&nsyL@SxAQtbMftp(Y@^=0BVU;1|efGRbsV3yTbag0?VY(N>b89q& z5pGT}OMm|@3VHur{?R`Sz97BlIlG-M7d-zzDcI}Y0c@@&#Bt(SGyFIa8s`)s!x687 z9dFNm-+2WM@&;%f>u~bhUVG~Bf~QU~x?D$HbvugK>X|H?xqjg-t$*(lcZi7}A7qD0=d~MVepEseC zlmCsLH;^oM|K>P|e>f4r@X;Nw?;q*^_LdlRb!fahVLp!b`-keM9^Bks4S zgIYJ<{SI(IN*IWo5dPW>Ov6vuGHApAaVfv8e#O|AO!mnqjY_@TKmv_(4jWn2?1~*9 z`shx2uLu`ZP3LkQ=r{MRXlD1VIcYC9O*lOv?^f3Gt8Jxu0mZM!)8u7dWCZ<$N&o7Ivd_)lP|IIHZu}fyajS1UIjqjPXzjUNxUDV zI11W8-fOw5nfCd4A!{#5J70bVUyxoJ;}r>co7gx`b`Ca!$O$I?2sj||DSNd=rC@W7 zmKISs+Q|+0(YV~*ryo5s!;Uu-J=Q}6w8uLFt-}Z>zdq)BRP_Ps=pxA3Rnt-Vw=g3Nn5r%oJ;cUZf{ zi*(5Q#mgyo0C{VA)v0|NZ^BX5Gx(E;~3=4aNvXGvCqw*;B`jt zo#Qbe$Nhoa2{!B%p_FQ2c*q-Wa2$=BXRFMyCK;P|L2KKuCSBU&ErQl@3MW7F27wG6 zZ7y)Mxg+yb3_kCXKA&d3d(j}MW8dd=)_eE^(v=s6rd4n0pZ8Vj>ZolGj^{o%*S-BH zcx!$-@RZDZ-SPcmSiIerNjDWk-nAE=y(aN)-m+i82lB2GJ#ye#m=`ip6|YkUA8&c7 zzv^8L+)6Lg0}|Jv5d?+<@aV$EZ)Ak{+;(A?@wpft|#riEy%El3MVa2 zW?R-c#&{vqANEB3zLpN8>}KL#LEg&M=S{ZuHG}jOQVss+V!+DByK_zoV0Uj#wi$Da zx7iy4!xYb2FuaB-rF)}fD+U+BjOJDx{e;1)MS#hOrj-iO?}7Mu#) z4u&En2HM#1*WQH28#24I+v$J)7q6zSjw_7^^-GQgB{%(<3;yv965qG2KeM*-{Ea(aFIX0?fZelBl@en@p3>e5 z(i^QK7bm|*Pgitb(<1_#!gl7;v-mwogeA-~>-H}2-0p2dPbC#A$kp#fji+tse+7Aj zx;kdQ);%A)GMdTs_Ygrm>k7Ynx%j-p8yVv+-Q5Yw)K5L= zH^JxKwW?IT-?EDCc}tw5t`637g=M!g=XeKG@HP;-y_(Fsb^N+47Vn#y(Kg>8@2<7M zzev1YG**f1hrBCeq|R7C-k*f-&fNTz4)pfzHGKnlYbClWXihW(9&TBoN#9t&tJpZb z`vx}G6#Kr}cy}JK7>x_Ox)G`3!;T*Y<5AJKX^;0Fw2m)0`Mu{8>hx+N;rYk# zdDq1=tbTrfC#V|V+Pdo`{(wZ#Pp&z*mHv5CT}Qsy;;cVkZwaE{4LTOKka-^+-z|g1 z`^)aNdK_>-Vzx<+(1pCKp6=1nhrC_8sy!PaZ*|3P|7Tt4K=tc#Z2}ySF1OnryEE1d z7-a?OD}!PILw(MH1ONE`U!9Pao8cxNz=+0q^*m6l=f~##@Lkq>?|Zbzy9TY}E>3>> z-9JAcSOhDi=zc)@ol0FDvu@GM zdt>IF-U_7Ptyl7-m&`lb&Q2PO_oB$zX9|$_lzQe6CGY8S>Bjg?UdVaNuVtShZ=Pqw zd^yNFP+9&8`$#k3{C!%OCj@@IhvXjgJZ;e`tRBQG(=xUct{@*- zbzjzmm)Pf))|zkOC068eXLa`?FNFK_5|xGK8DPgwX|-ATVZ`l8pHu6C7I5BC^(nF& zK0(U;q~L5Xc2Ch1QA{cqN_QzLWNPkSbb-7*2j1?))|y*SNrD z=X05Z5Al0YZU95ZtB43-&@J$`=`$5Q=*Bm-9u;G{ACTg&ex<68mNm@bzE|f4r0o>E z%~dqkl6mtNyjg+8dyCZB3tEtO-ca{4Ey&xLhRN?eBM3{gRPDw5kULship+6eBR7!RghL|o;+L8}$2**Yw;4a{J2LNQ#+MYacsm$%X}dt)iRX<9NxVN>B?L@E-WP>} zN2^wOAt9T(JXbBx05#rMD%BwGB)gnx(RnQ(HzKz^O)mzNv=(U;{^M&b7OOtC9Atub zZ_&8GGF2JHe|$mu&Z&lDF@Chi+XStn5huSD3zU@CsuRIz^)A6rH}QFA>fDr>2YKs< z=PfXz=Ibr*Siu}^Gg_bz&bRp@e^P>-Gbe{`vy`Q-_qdMTfU=p^y1{lv;O@s0iNEv zI3Yvf`6YbbN{@t1QWr*m?{cRGo7C|SCn7jstn1uD(_u3mo<|>Yicq#eC|>!*{Wh{&t?faVgI)KJHtKeS7QK zIvwG8uW7G)yP|bG#>ww^M5?gHLT)f(ArPKjg3o)&qWaVmO}l_ehT00g>-fCuG`2ck zi!!16?rmR8T^%{f*Ng?>+1vlk|NpOtdn*3-VGoL-=t1i|PK1+tP{eH}b*vt=;oX7n zaiC29gI$~9YS@E%)Rjb^!WCrug%7Vgws|70GR+l}X&E3t;97+*od1_vJeI8FXaRc) z!aB~m!*7r*TB=)d3;UA!L+4p#lrcR24~+{eKi{lz7CZhppTgz_8azR21g+y3PJXgR zDV&r2M4)02p64=#--E9AY`lI*ZU@kx_7Cb4Z^G>5e+3+hkn{cVQuFVBr`NxTMp9SD zd#=Yye^!vu6uhmKKJbuvFR6T?ip6_$b+mOJswIe`m7j!-Xhi-B!9-|y&%uxX6KLX0F=DrFSv6L zmv{Wx-P<W1M&{(T$9!YdF!2a>mI(~iEK?mPM!kI%bon`Z5WlTl#OxHer1o40@F#jH!xJRlN{t6aGDHS>LJ-oLqBeQZ-` zkGD5k$1F~MS(1mghv{*HC0>lj1m5BEzRY=|R$ zttZsgv1gOY$v=;`L{jix1K$B8^RD4AQNrTQzVMOZEaYwF{zIL#_huU;9rO(H4nCxP z3;E@VyylXgS74t3G&JN>x=D+Zz*RraGPQt@^<_JWuzMSGa&s8`qk9X+T{xU0!vl=a zxNjB@33>OhdB?dv+}fNmFY(v8f{gDJ?Io7uQe}NMc>oWrpxxBJ7PMunCaP}4DdO8!`KbE zVT8?Sk%Eh03lJ>7S;{XN1HP{r-TWvKyQi?%bTEj7@qjTjZs|pR`G#EV`1N~(bJjej zy&lAb*5QDY9}A)G)#rmmV4xvuEh@#PkB4TowaU<^DiVCmt-ENR-h?|K5gg^~d8Izm z|NKvF9Sf`R6ucc|%h!-EvF44$ot@_T|>{{E%r}A zr*?D8c_4dwtPa11yxm6Kg*zedSEUP<&hoVY?{ZP2fT9?1>*%vyT}JE`WXG^gSc5MQ zK+w2~i#ZaXUSRXSk-O}E77aci-HO&xg_9p+&YG1>@ch4ICN`EZ4t(Ch-r&TSjszeV zW3_Ep1O5}F1dI1em{_;d{|a&qb#?FtTz_`w?A#90E(+du-y3zwyvu`gHL-Xv^cq_) z0eQdpxu%80Tj2eU?%=g6Hx-WFhab;~lf zeKFv@^%fVVe|(KaEAr^=XRbWp9U8aSLCN8F6E<%HBaaF58rtjLDrg=0IQh*SHHhS2 z$_<+D1nZ?Nz~}AB<(%30atAo(w65#xcYNNPmQ*qx_xeQlyqEA&S4UQek#O3duea=^ z;B8wk{P*R=7c0Fruy_wnZA>+Qyq_>vTc|_cZep7129S4g=od2+Hcv!*B&}@_^1j*q z!g4v}ec0pP-V59F%L*6r0=TEN#7u9W!0G2q3gnwYSEeBSb7UBy|` z^*rD?8Yg)CzVPA(Y~BWDU$!oPh z`$C@o^N!mwVfCOy-f&$LIRER9**Yr29wc@xcDEtC#A*jtIyHGx#YOA(#Lg?!^rWT_{sF(m-N?zwv+2X z%P;=hYFTMH9C&5xe}B6+`VR7d+pYdp_YZ^d2mK#b((sBMN7r%3n=iL9{3UjZ#yZ>` z)~wnZH+PARWTE11D`mBp!aKrp87mU+U-;lr7sy+|cC>Sj_h(lSbO7?+n$;vVu-Kl+ z?p?X!$cbnmQ>bL719?00tyb!kA%P|whr&sB_y+0sRtqQoam(CGH`x~)7Xl9CI2N`O zOf~;_f>iI(!JjR3_=uegxem1aHa75|(elE9z$9~JE-iH4;cn5p{HqRwUXA@PcX6X% zVlg#Qr=LjJF+6XY>);$Xp)&t?OC&QD?_FP+A}G8c631DPcz+lezJ3z&R$tv|sX52{ z%EA??kazTf<9AAr+7k)R5n>M_qQOM(V5c4A?f)_tdr67}Sk-G3RV9N#$chWCIf2Nx zw~}=16eW)dfnajn*V|>!>ZFk4g^0D6vb*T7dqna@J+phX1P6M4c zVdL{fr#A-xj!xl(omd*a-qKE3>biND@p-q=RtKAtVH989eD`Le;%$AyY8!=jf_eor z67Qha>VV6Tclo0B&N<%q#QMrRA@2Z(or2b%?1^bR;vYSXi3X`3Y_x(QZ~3HHr|`uj z5W#a$pJ`z*2s`yz>yRHZ*BcU;2+N~F;21e>=v_SaggA2iy@k6RpVJ}ltK>TFqU6VZ zzNA2xTM#tYMLug+Md$t2@#DFa;=@2S(=u))8~WE<7ALkf@~Casp^FXi{~!tWINIvy zG>$w~d}8kR|B)Cf-d5qk^Yj1Q+1p-=I3^_C(-*Xq>mcv+hw+wkXKy}ko*GNx*&DFq zj|>WQAU=s9q(6f5ztUyHsEd%d`u$EtH3<^X`m$}4t~DO$dzA>cl_Kw@nHQhDzb;$| z0CL=}pjYj#|G2&NZI$k#C;jx-y=Nr<)bSN1zcsFb_x8ZU3CGl34|-J4dHTz9;7f{nVz?*)-cFNHHOK7IH)9*ZonT6Jo_pvQQ2|A_4S%ut#hCW@swlH1@%m)66W4&pq&hiR5K5g`IyZtNr z>p?x_I?(cab$X{(t}zaXy@-6`V~XB`bf$E|F75IG;VV;*_IIP7AT9N%xIdNa%kVqM z30vCgNHW={@hN!z63aowdoQ2+B?@n~#bVq@yo1#2dmAC|;Z}n^YLGX_+4C!eAaC~< zT7pVDiqZ_U-x0XLLMAoAh19X!kN;G_fSTpWeW^?u=+LZ{P0 zAdDP0X4>>ht`<4o;6^BK86Do=Q6X=e;KJ(zBNPhd{dUwRP-1=sQT`MLPu!g}r2W-eOZbXsTmmW?9_c^YgsfsCe5K zsq;{H7e1-rK;pexw$_vl4oL0JzBcNR_buHpB`6q5^2;;ya`Hr7Y4AFTj?I#&q)Exq6ja{@Rp3w01mcj$-U9G(g&l_Vz zV;%0Edo=#sy=A51y*q;GCxv%!^%-^~-si>Jjc?BD zk8n4l&i`S@BflTNJIwI&KPH^EIu!M?RxG>v-~9i-HNyXo{ylL1=cDRD`_{f%OzA=I z+BOIx^`Q6boSfO<4syaX%31~Xpt0O5+{y4B99ChX_QXX$8p5H<8Qt@`fDzB&T4!+KhL*m_3e28fo75W>u z)#2mETmLv9O|KApcJ(X$@jgecBMl|LnW8<%(^d%r_hXv{XT8vQvv8cw`E|k_cy2ry zZ&iZMyS>tEtN*KUhTlO3KBKLUXYIx7)FS6^Z}Cv^c4_@#OW`ejy^kM>H!sJo*0m;aQ7+v{$IgKB~d@fyMu4%K&Kjfdy7QJy`nTc zSR7uJp!N-U;3)uCT`Y5ifFwE2l*P6>lM}gno0}gA+&n>lymQEPY(>e>XIIIBCx>t# zSu*bM#6EQ1{jauKrUbf!?6#$Z+FLa2AoH`lk1d^Kc;1+swAGQ8qVo35wfXMNO~uxKs_Shle93Je7Z?$~=37NN+?88U)8A8B{92c4MLn)I5nRm(?5-I2- z{qbHwuH!sPe&zSXcsU>7Ky6|wSBV2UZ-tBB&DxId1+OHx*gjp4&U@;6(~0QA+Zg`* z|IlyR>iF`bZK&bcJZ~;4-cG)c{yuvvS#^{biMQv_tTF-eUY#rKGI#c-&z{lD1$hrP z=zKe=??5DqKkE^I@Bf?L`TTes`WH| zo#ePnQmxiHT*$nu&#b$gH%5QFZ;|VGfRdkEfz!FS0)n6`y=mDmOLX2uyO#BSk$d59 zn8mIf%B10NqA(@z`h)k3KmVuGSjU>R&r;#*E&eTm zmLq@7LZlv4kw0d*U$;nqw4u0L3HG3gsEiA;a0j{kUg(O(C$_{Nzk>VK!wBH8#kFsN zOUH@beAzya4M;#)VvTmf5_mv5vulUPKi&v^!XhA5<*g71C&%f^Fxi&9N4_K{dx+bF zuaG1D@BBxj{oitoT*q0I{913V3v<0C2(D?Ht%$jR-h<9&M-ONwoB%%N2a@+2)u7&k z#LVnlWT3r|@pq7-`)R9V%~t;l^RL*66r|$q@$F~=h4+C>>;fd-6CN`Ik&ySgYB!tZ zkoTU>jwF4^`(FHA$N!WT3NPfRKi)>1@<}lt$9R(=H;*lO$ZY&D~Z?;yZD+Sx8MmN zXzb30OnLYW5{K~)3kwp+(~9#AunPkDCYcJiZaX8+t;+k(p3Ph$46c#m9-sLVRFsL_ zgM`B++1Ku+zaFGWt^_QslhEQ1SD8$C8bZ)BmQ^% z>q>p&D}yA)fBrvg6>W8JN=qv~`11tm0xI6VGjh);yqTZPN+9vhvP<-M4|(srCfhg1 z`-tnS3kr~T^v62kq@6ZI=Fe-&??T=$u6j1qK;94A*uuV;kwA#__klO-fRLnVfX>bB7wF#w(uOXar!eLiBj?Qscw#;@D7oA zvCIFiqvUTH-_l-7{ zhDlQr;Fn5r2+#@w+hsV2F-ge0H)k*0a+gc^Z=B;pVxrk8WZoI8O?NKZN`JgJlIuuE z$*;`vj(FfsL9oF;C&{b?op){5%|#_*CxHL$9Tr~aXt;Y@#7%t3Gsy6~G37MYF_SO* z=k2YLB2>J+6DoBnyuYcR7f0gVbX&zy5%M+*N_jEIdozbByEx>%B>rLD>aRA$eew5> zw?f{bLl?~@;O(t#j($A9OyJ9j-B%0Yii5xycKo$47cy7is^-_pCj2+ErOWb*g>r-e50my#|Ikge;)?)o`&1Fmix+?0E=}&{eH%)1wd&?3lE5Fv`X5@HZ0fEgQOzDreJh={Ul>9`PJ&nBs1c4@#OUs%|=)9-W ztHTH3*_(X$c>a(&diPdfkqPMeWXM&AB)_(*)PW<2e|9ASL-#@_lUy`Z^ z1qs%4QhJb>p_Cj_54zRWz_}a_NKE*;E_v94LT#!Y9>X3qu2vXJs<9zn>)X84DxU!A zIMT1;;0{txb^nTJ8xokjAz>xdf(KU*xR$=>MLrP{)J~SOz9$TF$#GV%f9 z1V$KtKyrITTO9?tr1+*|^9Q67RJ@P8x6h{V#+gpaAn`V+oKe^ec^5`E*)D~=W$O&z zq9^8?)@0tF`_x!NM zX@|M*2!nERT>Gh)2Ri=o#wmH5yOM-S`s2++u0s|jzhim(Tzdy_KtVnCl6*HhZ?o|O zMS74oX339={0Q{(e+-`#_sOFF3kDiN`7@KQ!aa! z3j$Ah?$~Wl(0RXz*S#&~?GGeQ{Rp?$M(^JF?v73q`W6g7Ak}!#R!4$r;;;<-f)w1G zh*R+nIQpEA!ka%oQVNOpi>hwV7|1(@>!ZUm$Xl7CL0B2`KH;A0cj@IW;v2cm1FwS! z0RJqiWrHzwXUOuA>$uzaJZC(^N5nz-N_8qwFJe-rCLlL#BTIKs4@@L9QSA%ZV`WZ*QAO z7-akd(lOfV@K^X9?0R{=dy7%=_P4(2LE-&5(s2nAZ^aGOE(MTxTDx68HE+dCW8T>Q zT||kiT3n-$ce?i=HU#p1UE5Nax19v4l^=?PUkC!e;*VWpCXw&nwoCSSswfKsA99@2 z5eea;$3OiD$rmpV~&qKSI7F6VErV#{1A;5Bf%~ zqY@>*^vA~^S(@TNZ`kAS#P8@mNaKYRQC8C*{P6YpjBl+)Js`ytdu^%r{L1*3*en|B zD06orpCCz7@eb{Yyhpjjeit87K;mtD(Yc`z^45|5{%nqS^sJg@(A*9(Vv5ta!IpSO zU)|$#7Xf&Nb+es^yw|rs}c0kOo@zqD(Ez{R6i%yJ}=xn47p)XLBm1{vfy8;1=o zq5pV-^x0<5!du?-$NMU|j;AR3Iaa^b_Y;6mkYc1O2EU;5-cj|XLA5>*1aWE?{Nh0W z1!-7qpr~J2IKy9JF?VUJLw)d)=S{&5R%}#ddVgZllBQ%}1_76eYhQr@ez^4mcoXChX4k z8J#zQ$tk;?#TPU-h#N7jLw`V8?yBia){XBNp7)7l+UgL+m-zIz^^muy`E>Fn5|i@rUTId*_nt zC`8FG@s$YMWHIF3SeXhi)pKI=L;=&oLxwE&x7{A=NkoOj`9pQyDHpD~2 zk2Z|KmlMVP{_GPJ+f}9))#df;g#X5gpONk6 zx{e%weDANO`@iUq_eOFZ$58T9eQ~blFbM~qt9GRGkD&9`aAslJ+7<-fuE@OTJ4M6c z1Q$_sJ)a}v^X8_l4w;K01MF~f^56Xbcgm*UKfw8a8C4HDh4Gi7^dQ$*9yO#Mv^lQ& z#OT^0{ej;fo26h6Y93?VyaM*1FPHr{yGQLNvJMzronnRW{|{|`_d#}?XrRY3bIFqg zY%fdP%ILv^+Ks_XlPi&X%1gO(u@CHp|HgS9T7SLZB657+msyM4Nc!tR1LQiMqvXe& zni*$1h66tF{&rX{9(^=0T5md}&PDkH-A@YTtm5eRATe)dYP$F%7{3R7qOA^2~Y)5k(cfya7XT^X~HEu;IbL2-SQiG{*P7~X)`nz{u|fmSMVt@ z6q)z!pEup|@bt%mCJ2c3W5tUCA)t!qw|hAagM!8cGBVPEfaDbrYQNvXfRKmKPm{iyKgUV#Gvy| z?W^IxCwv5a8tVy>j7R5P25)b< zUEH*4Hy#-B&fKysL*`xKeZ)Kr2!r+HxP=M|m1f(Kc{?j*I&vJOzwUjPT*qFN{1jrc z@(vSm;Nznh0j6K*1JYpy)4i2y{-9h}Q(-#+{qYv#0*jgfcW;J&yk+4KZFT5(_b810 z`Tn0Q74NY17*k63ZW}ROj>H>N8AS4eyjgmVKcC}mvBxXN81haW_x!@gZ%5pG1|KUp zL;#5eTW9w`-s|_Z)Gl--0a8Q%m-^Ho;I(qo)P^s}x3@k$sA8?%APf$Y<8Ztc^7{Yy zRyXgF^=?y#>5n(14lb1Z0>Akd9%sgZ0`mhFQ9sdnXOek~R!y|qd)1@f-V*pM^f+bf zJBB}dQyrqM4q)eT(ID}^`5$eDql>=}=YM6Y9uz$-dzI3IL>4fuM(RQO8PbG}aQ??F z`J}NJ_Mr7uD{ldB`2N4!!^~;d?1}dXnGI(@5x`XFTR{^z|Ch;~#-Bez0vXOvdHe6+ z!Tkld#NG=cUosVDj}p(t34o|;(--V)Oj=Pd@ zV9FcUAEJ%EgN*Y}@c425IA{v3dYoKO!~Eaz(S`ZTQO4gv(pX2jX=vxV==u47ITde0 zz4rixx9sBfl}Nnr<6@i+K;CzDd?=sey)D}5wlL(KAnjllE@ z{qep;u7ejPKYjt`({FbR0{az&yA>+vyfwCZW?eT81i?#=Uc1eTev3Uqe!ut@>@>sk z-aum=c#nIQ9~0&ukXEAN9Th**M&Zpja#0hB_oEu79np~Y4~*WrC6G7U?9aYlxPx4G zdf7AkP4>j@vgXedKL~(yB~tk;1U3@cgXwH z%F1b;o9O5Nn6R;1%5lFLo;R&^+$*b@aR2iIX+V$JA-B(Ul5%uaq6Jh0$Deev2qzP;T6z>7m(!hhpzl2_&&-G|IuyEm5U?K%46 z-A=AU6D2?QDT(fls)7I`tVtXfMd!^~`6gm#d?2{59cb-tRENqN)A8X+g75zY&)&YG zv5q2%<(mJ!|Bo)ld(cgW}&4yXSfk?zN)Z70=xmq#hKrc~NDqR+0YU8`@VE z!5%aydowo@4oDl{>RhW5hu{BuX~a5r4>ICQ)$Kf)aiY_*o>dD^kifGK1ji+M!N4s( z;SuLCLKqrOkSr`ee>uRz_&Z2*+UmID-Rvb%I)8~( zqv9P`aQ|c2uvY0rGw-y>^)d^*mp2UZX1*P9Hs8#iXr-1^WHLek zOPb5iG(q0HpLAZlKSl!Q7oK0~u`C$eIxzY~^dCQX{`CVqHIWqoCFD5s(-uwce8{|S z2xJXc0Q%!SO|BykCBH@Ciq1?o;4St^q1`=u(Ru5daGUKiIs&dN+P0}l5q&_)lgWN9 zOE|>vyoaP|tE1fAd*N98Jnt1$yw9ArkEigiQcGTo#9QI8+Pe|RyP>>%}TEsoG+{I|Da3}~$5>ct72KMzQ&Qt>{${qrdb?|1F?T1dQ;J-@$V zg9Fm?7xqe$kazuk?^BMD_pgqj@}drVqMQat>i7o&nCW+FoQ1rtR$m@84}mX8J8-<9 zd}T1$E`9Ex7 zRhtN&1g5{(2tG2#g90f*=b8-U+gp{2ZqI*Y2!niboG>YPV$nh5z4``WJmDCT{^tL3 zavcCAKmMfbn%)i^c-B~5d|@j(Z|13TF_y>>U@sw)ar6`o-Fxe)tp4gThUbl;wGQ1@ zOTPc+|NrGl^Z)Q)2j~CQR6QtpP#s5^|4jJPZpfP;mKA^Ol^wA>BtdPomH>hY<0^`f_XWw~Cw*bvopoLaxIBCBGSi zQ~0)C0f5_fgWt>>owr77)ShjNLO|mK(FkK2c90u(*jMg&*w661e{QF(4rW2Cdp!a3 zyjN23J{vB7hr*k6*(3`R?^HFuM<#Rg|A&(@;*hu5YmvT39}#uJ_Q(!D9V#bP0#eofNj{&X64kh998 zMy^8)&l~fb#yZklqO||a|C&_1ldPk}DZB;iYnhRF52{z5-UoRfxm9~F`mK1$ct)j+Pp1SP*Hd1Yo} z2|@5;LTPZ&1)aB&h8&o24+Ycio`)wi(H~BXz3<-Xk;BaJ-TU1g+Ugj4blv+7{5bJ{ zzyJR~oXP(;|1miK>rnNe^qw*WN)IyV+RTI0gO=U>EaSSSNZ&+NIZ_n%pbNL<1bAQ% znmWrh8Bk+K6yY5tfEWUJVD@DD3+Zv%x>lVBVAaC`%PF*u_{y%bI=c2JvJ7NZh^!>X@1mLxSyJ8UXK5XtyJO+8c7_d2M zlZyvcS9Eu6`^OGa(rQnmN4PK`lH(#4Yh83~L*{Kd>XM~%hW>ajBG+MrlHVPk+`(f3 z0^s-Yo#QJb(0TjxslBg1WCV<_4Sk6$M!&>jQWiV$CB!oPB^L9LwmMp#-mY={^9Jd) zRJ_xU7-mp-w?+?hBJmbC4I9jbygxTfC(ZHp>uf#w8uBh!7vb)ZYe#(hWyUh$A_3HN zURCXfymMs@lu97)wwqCnmIORdaXpp$d<40BuLA6)wUGA;a$G}X5uW!xGViGbqxxm> z^v7G1T*oJr`~-xSA5}8Kfz+v~(t%^>yf2uD*xU);4;noM&FX{Ee;{ob*zhc82@Asy zNGw^j)v;*uKH+Eh{LfposCcIuMa;jPXzt;}gZyP2NW6nH_mnn5-ZHIU7cPXn&m6tD zwifdKq59NkLy{da65|r9evJTNzzyQ{sJ7@jwVWq_tSMANF4UCo@od%K2;cZyKPO-lFPwdxc* z67Nl|s;AyU-WQV^GUj+IpU;^&3wh_Sa2nbiYDaXxRiGzSP5{YlxRgoA8~1k6M_I_b znMul6>I5DLxbNf6>_hI}hllN(7sK0Ig5)?u<@Pn;ANLDl`pk9uvgwbvAGwZjl>8d* zvHQNT!GZgFCZ7}i(0P}BewcP^SpYbH3Zz7fqi;^iKG$6}(b~`On-d2b>qt0RzUpwq zfAjzU<{1Bf{O^MEzdltD%4wY(rSzZ~p7rq79|q&)=!4;ce|2*7bKT>4;GhTmv-&Ki zp18V5pYId?jS%cXOret<<#7I2>0=vw?O;a)X}gw(CKG_hf&)A8um|~wcZh9CCV}GY z#+iG=LEzx>l{b0~k$aF|P;_HMs4zH0j${6q;H+~J`4U?g(j4&o7#;Q?avixS`KhI- z^<)iIG1h1$XmpC%BR!Mj(BeJS^h{O z0i^ETZIu9d3x4?(`RFVOWC?BmaDVfaSw2G>^idc>doP}*Li z$A!*~4Tl+?_jOm=>d@=me~u|@eg~;X#XHOYO$vqgclnq6NW8s!ig}pf4l)1}HaW-J z`u?o-amf2EUSNTBtR3;xIqQhKX9%EahuQOd$h-aY^UcypBycOPva|mheDm>$5dRN0 zWZs40>sg;e-jq1eAhs9j4#>PsD{drJ9j8Cu1>`!6QS$4%{c~pR9sy7_T-iHz6`l9> z-dg(wE{DP3r?2`?8fsB_V|3SR*A9d-Ja3FBjdeWQk|6Qt{C^!4?@V2nGz#xp;e0+M z-a&hIsLDd#nGe37m01BQL?-^f2=Y8Ya@0hGuFK{VkonFce`sO6;+akji+8BnP|HEF;R>zjWbz8=g z=DW8p74Hmwg+L1Lp(Dq5k$BgVJk}XO-fuU`GR>X6J#i@eun_VN3BO}q*J4L3TNrzD zAe;ccD%cdXLEcqzD}oB+NkHcE?nMb(;Oi}Xx2}@8hRj>gbI16*7-4XW9G6^q#3H%? znfD%R(9x1af4p(zI(DJtXWWz@lIbG=hG$sV{m!BDZq0mqFXO&5xLLirLb)82;=na2suP5Q>}M*=PUv{y)m*l&=2@=YM0W9+cN`(3sML_HnFTh}45F_9P03 z!2zkmnt44A_Mo?q-Sijxz(?$Ad5_+>V?*3y+E?0BLjau9*jI0);Q2q>3iC&qB(TRl z)JDWA82CPnyqj?Wxu=A6AGmOPfe1K6j(fbNqWi2r@-s+Fhxt~O2-4p(NR&FHQSuwv zP;jgAJr4XHd)g=7jNXHuetNNHQDPAA*U+#^El0lxnN{UkRKmgdJILZQwAIm7t24?M zIe&s=M8*4Ra#IO~H-{4U0wmtfdA{D-koT#xmCbX!JA1uea6{e|Q4Thr6>W)OD|$k$ z;4OAss6YWLyu@CYVH@wiNCE*T#`5sX;qU)*cw;X4AoDI(GxV*;iGWgaT!=g80xvsc z-dk15c5LLMKi-r&HlgGmSea zhg{q)_mM{g>?OyomwS6IeLFJm9dcn_%-rp*I-`@JK|;CN6TYU37|sz$F22{H_x?N>A_SI zs2eptV5l4nItt@t)c(=Ee;MuMo#qq)o#eQN9~NaiR>-`au|fUUIO&h~PjVd&DEURp z8!}tm!~yYwCnc)2=)A`oCl4Bs@Ze}2-b5m!0sZ#Y!e`|LZw@j1fP@jHu?}s^!c=z= z0QcSoRJvh&;lpeG;Vbx-!9%QrII4EFMk$zO` z+I&9PgC1=5_11?2(g5yv{}E$rV(jZnp+|ZN@I=J?aWRipsc0G~5ag&wT3B|t1mssDkcIx{y=j-%Hc-_Wpw%v>a*D14mZd1Gj- zW7gxu{>%CE^Z!OF-i3~<-6*_EZJHM$@jkxq@blY{_weFaeJJ` z-U?VC^IoyiALpz@f4nJmEJw-D*>k;cuM7^{^N`#sJ%rx9e^^Ni)U~^Tii&%yF0iBX z{u%T%t6gG%;du`Q(pCqzw(f}HnR(tORJ;qci}NVFZT&BaBk|6Y9(&gbd0RdhQ5S%` z+4(=8(}cWB6R-c+I=hQlU9P$P0Q~*`4t9-;&mr$!i8j)$StM{y#bN&_TQDfNVw(_X zip;zF*M(=w>LP#RF3Gx|Szw9GTVHprpQa-H@ut+FgOZ=5-H_~hcN{ny)x@GRh|W7P zXp7rE$opHtPzQT?9s2z5!MZj#*_ZL>|E)CEA;-Q%>d)gX8>o0+o4T}+!uw&-elaB8 z0zR8gPeI-eyGkqOcsuk}epQ0JNAFK2f8A+AY^!doX?{!q7U*Y_3PSt}-@1%!QdXV9FB{`%Xbo|mH$F`M4`oq1&>^!gsjh#NxVgP%PYa+Ov z8@rQu_Ov&@$UXQ4se3{E%CHA@$o1*2DkOo#w%Uqg9KqnQ9{2X4e_Ub};|p3ELPUTs zIj%b2{^_TG%>VBjOJ@f6(_ar-My_K7B|jz4gC<@5IB<(XDr;&>8s>dq*(CdCeaBe{PLkat;9CU0~e33LVQ-W{GA4D=>ySUvlYdB5;JQe5gO0(8i6rlr5PVs9h!UTJpz zL4zIr@$M$qp@x#*w>P)V%*Jp4E56n2`i>YSf~bK0p9!o0*b=A#d)VvJG9iBv81%t45$87~Bq*lw17~nfKPB@#hjA z@aZjbT=UgKPf7QXd2hNTLn@&|-e%-Fj8O9HJpjJ9>j(m=-!d2dC((HaUa_C??ezue z!x}r;1JECDx&B^VchLVW!_WU^92zv$!6TW__PKkW_hu^IH$FSvqwqdcyJra!@6F8b zBrGBC0k-C)b7yabUv~1$9Zn3q->RhBYelq;U3PqFKLK#PQmj4$d2@`)Hzr>p0grJ1 zJzo2R!OAV&%ftS0o?ky3BEH;Q1Za}uE(&tS)v(bI?Pb=`}RP(tcKdalcil;D8WC_l276ZW9TKHk}Zum>Hl z#~euBy^Y9!uJQNwAOfhLxzqN1$vAQR>>d9fH%Va7wRv^iGd!5)yk~?HMZUy(TB<*F z$`=8j$#JncAJ)})AorlPi#O?L$I)L8awpfZ5+%P7jpAXC7#w(T6dzZjfIc9J99%!q zujU2fBiFG07_CR`K|SRyA!l@VGyD!RzM8f=t`Ao`c>j6D&JHTxcTYLFP@37k$I;d6pAQ6MSr|Mkn1>)lAj>k z5rTgkd_mgAG5bgI=)4E)^g2aWcmW5dk6|WJG|c~*`&-2;ofw`srhvveuue_n*IRC< z;(ce6vjK&7f_v#QB;Ev0o)k~WJ4$o2Hy7l+cf04*F39_uj`RBN+U>-gkLTOBpC`lowuqvBn@VDtrrH|FK3rAWMkqw-TuL*8sgU0>&TAD=yKt_^vw zE$DIjT)2Zc^T9EoJRiQj<%8@_7C0cenmjg|xK08`MUBlo1A{^KnX`^qw715azozcV^+8IAaBc5>+`L`JBdHPIUL_{3x0dsQ8sP?|vsLFbH48yU-vGxd*vC8^G0< ziGWaY9A{PYV%2}#Vz<4M^R)gf{q-OxavfGE`NdmHv0akD0ZTc{MhOe_9<)?p#gD-A zhk!u*YTZ@b=(pH03FakjKV2Dr2f2l|IyP8Z-}m_Q3({RwyosK#{(jzaMxtL8i8oVT z=7!6VcT#coI(EqWq}P|ORLJ|=ni7qUdNZPl&C*{U+X&#@lHajjkoQDt*5ZYCNg(IV zkYB)>U=XY$y5rtqWZqn3SDd%p6#)U{xaRjR&rTH}Ut-mDA_lWk=#Mu$xegVS{J7UW zVE^uc1IJ>*`FoAgd2e!VKlotEAGA(7O{nXmUt$j~x__{w@iD{mR;a6@sg9^8E*}ie z&YvJzQ}MnJ6vZgr+v3S}6(rtP<@+!Vkhiz&<;FSQ-(9%-mO|d|p_*~_zpgm7fl?dn}$6dYg{in@U zWZsEUTc6oy&>!z#l3u;{WX_!p%kpI%<`n+5hD z$++Xm<$jv_y1yREzW!oDyt4AT{b(@(xKEcRH7_0~nzN@2`_+;Fv)1pdjn;Tz?iQ6h zdmZ^5Btnr5DR(7Bz$S8B$2nH)h&*x+Iwrc^?%7xRdk3i?xsDK&{J3T`0)1Wy0F~}7 zNsIl_FR`J|t@s>>Q^!ovM?`ds`!b0A@d5OzULf%q>7jlzNY$Tc-lQI9EMgX#-+pdg2-sRbe z6~)ygke#`|DP}1i#P$Sk6F7>@n`LlYg0F-Kh#<#RNQj;{;zZ_scj-}L2OaWeBG*xd zlAlk)>Xmwz1wiz*hng=Bpz{v7Yq<5?{zKsKYn7k<-_Zvo4$rJC<2PLl&)eODwmQsy ze6|+&vxD4C#k+2`#oryIS7eqZ67M2qEm=u8Aia3jFUSgcOF7mx0m%F1xP|y~rA@@O zmU?>*A18n{rrS5oLf%mat|JX4zvbr(4dcfJK#j)Drf+WOyl)qX+E#cR0z&Ps-$XCa z(7m5opAW;oWO&{fTI(=9pRDv}{|NSq>yt^--JeTmB{&+tk*YOM`Ka1^tb*1G3VA^%M#oh^> z_ui|X0{49a;m?OwvzK|GcWwhPzCZ%FAa-1SF)M7+3Ip&nGpf_MArS%g}h6S zjGAt*B!Q^l)&3eic(7XgNyy^`$Xr9sbj^g|{I5oitEp+_C7wXuoYWQH8Ea0Yzxh9y zT*m{H{7kMc6uW7O1A8Sim0Rr5d0)GFEV!0!Fu^Z#@``Tt1{&i~F-J?L@LI_tShtRVcvuJe+87^EH)NeFh*gaeX^z%nZ) z*nQV(O`zBp-va>AZuO{pD%a}pFz5LUo(9P9#}t8 z8{B&s`4T&}^kUOt`2PQ$fPnE|$6%he#7N`6b!>e`Ce3jo`8CDE#Abl#5zs`0ivj{v*bWv0Y2^e0F$v+qx}co5esMma&*?q=@zx{P(S?%Vo2V>5F994lEwPXFH6ES!wvu&Sg}5W&A*)P5 zC=G9r>Z*DF@@n5thUeX$Lt7mm@EsrYPtHFey_bsj!*6>dD7@FEI%y&C&i-Dmc^>j! z?7#lw9Pc}gV(aI+cgN0+KH9f75Sd(dbZwj_0DZfoa%Uj#t6hEf6dU1ybS2igCR7u+>NW5K~cvJh`?79J&cU_lrhw@MQ zR@*-|jINM_v>F_|Txd1R8jcz2f6P`!Nvkt+=eGr-IJ=cj?>W+11+_o_8ya zbxfBUI2=p-@A-cQnEo*sIREdb>Ot+--pxP%KR5pepW4NS)PtCf+_2H=Mf$vFc4z#a zozTBqFrxCi42dG#t*P&(qk*rEf4_@$#F~1gv6M9NA5vhZ&DvJ2hiU=NG)<5o+$bGHyBvSMBu=W zTN3$qE6{h4+BZc?9MbT>QT?>Sq$B$C|Jq;pmOss4{OAA0CuyrgPf*P5{htq{@1x@V zWSjfbzqhxFrCE`9=kz(s6++(Qm)9?!g}j0DG`3mAa5gomOFF2{hoYjX@I;-A9I<9 zm8~cK#(QlFz7-8lrZk=%hP+QGdJ!X^kO0;Nx5q~(7{tHPo;AQD^L}*iWP~H+eVQC6 z-N;t8q!*dD!kfJP=AQJ&yO~_aQk49z^p&k!%Z3Bh9^*qli_m%B6S}ob^!E{v+o@By zU;+9Yq>rBG&j;U!7@qfr6x!-YD8%r^gw4iY86PT9wA@d$8oT{ znZjFNFqR34cW|7Rsvw;IOBOq{Q1kwIlhb=~mJ#tm#<|5mA@5DXZ=WoKyvKC${`Mpi zaM#$NEVLaDa!lV!*5)D4{~toHFGyc30y4;PR;PoUveqE;mgSCc{Qi;t=KuHPI;2tZ zd&(;6eAiF_@aKIjsJ)ENdrAFEzlsiDz@zQ2`C+^s_4bxaDoe7>EaU&YB{`9{I#!+( zn#w$I5^%u*_$A8&4F6~TA^vCl5BV$j3;8qnAzTJFV`84?C_(b_QcxQM=dHZ?Wcx!k|d2@MFc%ykk zcn|XK<=xI}#JieTfmfWDhvzrXC!SY49Xt&@cX;x7(s|Bs-Qv2;mCO~zh3E3*a^SMy zGUQsxwUlci7Z>MG&X1fgIomnwILkQmIMX;|IgfJsa5{1BIIvi-7_zKnS<14Ig^T$o^GD{F%DJ%7%9TQkB%1Z54)=BId%4)^ox0kT1DJ#{C!8O=bl$DCm zaYyV*%4+%8dM~UdWu;WMMir|;St$~t)?w8tD+OE6msmB*YMJx`PV5TGO8!egA6AvJ zlB-$q6stm6$tEgPV3jE=8GC(6>~hLVdfD_MtP*9lWXh!;t4LWbZqh8mDo|FE7h-&{ z%P1>}{YI?VrIgho4KHV`JY^-$`luT#M_Dawn~}%LQdSEtrFCLuC@WE~(C1ib%1Q*B zQN>D8R>FM8nz2hLE5X;xH)9u5R=8`^M64ubC2-hjA6A00;x{q6i(N!n@hviG!HQE> zJnsm@STV|qyV41dT}WARMN1W97f@E5)~&5rQOb%#p;s6yLRqnm#iwC~DJ#}0M^~&6 zWraPrp$RKUS+UqGzlp_BR?Ldsd$0nO6%)H~BbJ}MlACRMFOKD-tbP|A2*UDGR=?c- zANKA%oT@c^9RAkcC}keDB2#3DObsL+GYM%hWJn|=BAH2|G8YX}BqX6!qNHi7Oo>fG zlnRA1ga%{7`)uuXzWaKwcb&C=?;pQw@9%ZaKXo6^b)Dy~&$-uguV<}i9W)>;LZY8* zH9ry-BGD|jd>?@WiKbr(z9%d|qNyC>3}HSJO&;(VAh09Rgps)jfend%2!2^lU`3*D zz4Fxr0up__e_;^;k3{1~j@c0AA<>wHNi2Z{iAE(2t`l%bG%`J(1OEq!hVNSG;(sI2 z(6P{T{4XRL+*&t-|A|DOReap=vq&^BvCtMjgGBvLe5LTyNYr<_Z54hBi9R~9JK`si z=!5cpL;M61_2R9Z@IR2KyW#m8{C6aJpHaIX{|$-WxyYTte?_9VYYhwW<4DxSG3AOM zL!#IHh3oL6NYr`Rs}BDKi8=!R#N$Vh=#}AFKm0HfwaW#h;fIi@wZBmvKZryxul=aO ze?}t8{dW8(B%<7}5ZaM#J3<3_sA< z*!-OYFC_Bb@a7R=4-)Ma*7GNLB9RwY(s6M$RobBkgywx+^xT965Nnz zw^DE(VHXm)Ei^bqa77|lQqUoS3lh1U2%9GCM53LZZ`%pZNaQSYahR|JiJZP$BoLgC z$gz=ijNphw4%zEJ5*(1oJ~L;AV2?!GHMj!^+mXnQ(>#q}heS3_KYtNyk;wYuWaE-4=BFYDW@z0Qm^8HkN z9THJKH;J!BBFfkK@HI$OP_xenUyVdp(w>##tB@$)Ro)5z6p1d&ksjlpAkn4YJ)-!> zNR-?3eHdSfL^-)ShwvmM$_^Mv$3H@%i|gIa;~yeX7Pnjo{s9tYzP=-ezmG&2mvEQx z_mJp(uznW40*THU9+SY|MWS^6tP*@V5~cO1^5X9x(V1(h{P^2QbUH@nF1`$jPT9sS z!IvV@Ns*aB{4FF(86dWPCaj?Vpiu$Dc(azsL27_%tN)O?|K)e+G&6d1%byPa~0!;x9q`DJ0rE z5t)iVi9}w{jW^>{k!a8Pq)dDY5_$T+yn#P~L>`*GV))}o;X^~}N@q$+FcdF$XiNF51gkJgw2(%`<% z$1)odLAi@%iyGWPI`}n6ub`_DJbF;IawR;2H1$l@n@_&zx7fcsi{)Hx6$B@!<03x= ze9am~zXxe8&uS=omho<}BYAAYm>)2R9hazqXOMD4e82Mw`yOQG+LvJC9anHl*=~Az z0{a2!pTDP1KjH~u`W>XgPWtk=QpnjL2+tsayuE37Q|8!SA@4!F9XtX}UH7h?*3U0Ox}>F?9Qg)%i9n|;cdIt!J$Vo>h=aTfeY)qxEer=Y zA7|rUZb0YlaBE=oOrs#UP91k<;HHFi2RiT6la(#qsf@?lk(x&e#{AsWo%i3EH_nB=JZknj_E#0nJwdvchBu|} zM0hvq^esT+ty#YR?lQ>ROMGOC!dw4|kk$_h?}KN#)iQNSXWm;pm|2?$c*BhsnnK>= zKSfSizi9;7?}|MN;n!O~EzlFlFh=K{yZdV%-!nnbM;$lBYg>~35}o%APwV{9WQj<^5#ya=PedO zUmhH5o)>f`&++!6;Z3=bg76L(c`zT1x3Kip=SGmXbw}}$UliW&&isyq`~PE>$HHSY z^+*?fWW;??Oa#^Jo7|ls?+d3#*35P`g3{yG)w{*v`TrqRyWcya^L|{k{grMF+#scn zlg)PztN544Thw|ge3g?KkM|R59x52~+g5+;=y*IYnEvc-qxl@0_hG$0d=linzT|yX z*wQM@4N_b)`}yH1FQ(uB$5qjp$1Q@t)ZdpA_t5aB+!;i8zq%03j>da!yz?Iq$XmC) zmzVPFZR0!rS0^CvhWISmL7X6S0RuHJbsjfhC<#-mn1K&?`Qu=yMwxILQPw#wowOkO?P{(DjTxw;{kAA#m-)Q6$i73Y7eTACGM~wLuXdJ&}XUGd~ z`VHI~CSmj5W|=SbaNYs%dei)5{z~j;Z*c)O-mhNGGCyxR^I-c}tBp(j@A-cw=>F%P z|M#bPjdwQ!4vqGUiF^maTRD%H_qU_hl=%Cu0XGH({~0GyBju(# zgFgOLsbeR5KI7G(IBFgzG3KYZ+x_z$_(`Gnt3U5sK7w6?O0CkKnvJ`GrMoAen({Sc zUShk}o)F?({)g#TkkXs!%j4mZmYF*bvnc)lej47C%|3*;YsMm8G~UZzkov75@11(N zS1G(7ts&m<@Kx7M>1lU8Pyi6z5id?n=@*W$9TMvJd`lzcgtd# zaKJYnFrGh_YWRP^o4fVGliQ!GF{?MunsaHkG4uETqM`KV;cFlvf{OQN8-ah(=dz|6o#3yhuM?wM}{lEVPV#kmF1^xd@I`e3@ z{zy3>4K7ah(eS1`Uxe@umJR1b$;Dt!3?DP1$=JKeMg=2jso;LvYy3L>*GV zD6kmblnC@rowisGd8;IEAM=0P2yUqVoZ;OO4g%Egn7z$J=UuZxt|PEV5cpHaZHe2H zsIm}!aUv;}61O{-@pvP7NMOuQVk5qO7RL)R=4Wp7>%!(;Av^ARN_aQ0Tronfc#OUG zhVy(%ab=S^EEAni@oT!V;-Lua2$~Myo-lSwBS*m5X)5 zYiHdjU=2D}U@o#0_Wuuj2i~#VG$Lua9xjTEjt8==v(aU+|5r*D^WN9r2u`lObGTa~ z9LU5ccdYrBTkPQ?VPV@&34!I*aR+y9YF+X#HR!CNvw)J(auTEcnIEF&aT;TO1nbwq zO1A~T5+#E?_eET~Sb5ZuWZzn?+6OAff@pYC9vMb>_jt`GqVYDKS0!@|^5)HnAEoeicq$Mz;{!i$A+?;(+1ik#aO-G` zTx~o!G1OI24SBCv82Co851#+`Hu|xNKsY$&ANi4Va%`m#ohw183C|S#XqKLJ~r>2H-f!)DDDGgn_fH$o_vDc zAi00QKaFMn1_`%^&OFABEL{C}1sO=goAL}i!n=EZyC53x5A1`+jga>PQbfok#IfT`cBE_}B=*=ezr&vctjk9K{!f@6mY& zm&PwWyio|;ppN^R+8AYJgw9*84?nz)h4FZYQuA1jF~7~B%QTlg6ab4F62CV6#$G{I zWvvr;{^11XU;HIMDq4-ryVgIQ=e<4CACQiFMqeHW?c@&`<;_*^02H97V zpz&U{p;r70vEh9rRQ*Y%4!A#c8xrF>c+ z8bOA2WF>ofILN-O4~!y;FJauVIPKyGZ>|;Hi&{*C6#$^C-la zpJ?l!o5k}5K@RzBNZm9x?|?@lyDyn~fw8`suM_sz2c(~0t5Gt1-+}2DCu92bbVog=Xf8W;Z1o<3E{oIz?UD5_iN{`r980z&kwnIoWeVcuQQz;uDvxnv;;;@>XPof zGn;oXJpm|Li!S&Cc{i}++ROAdf|LovfM+TZfXmh7p4S2N+f~AcxgOQ92mx;DIP(cS zzAFx$w;jjbzytRgk2jH;2iE-R+Mn*R-XsVnd#tj|C$M>MdGmQd+r$gx3$llAK99Zj z#%T;BJy!K*dfqrwI`i<~s=aOBf9L;W^>7UFb9fIjf~E#h-qS>Cki-@RF|-E*#+PFT}nipTWojNJ81v(Q z=lbE%7D4bK_rn{rW!Mc;`1z{xwi98%sk3DwIbganvP;l; zuh{;}(cza6sG*K4l(TKSZ-UNSKYY)Bl^8-voCj`Ms{yz_X31jna z(GxZDbqE7_m5%=5!8O>`yJ+%}(*7+>&l^W?9!K@T1+Tdc(oh=Sl%pXK-uE`9FG1t| zc|&ZTDTTMf=50S9@Ai>V8#Bn;JZb0okscG$mx~z}ZL`55ZKnMs^$1P9o&}rC+&Rb{uN0yJL8IQLEHIMZe^Bdc_ zZ(WG4Ab5A+_C-}*Y~IA(s|M`7g20CJ={p9`U~iBrM%T%oy21P(C+4_FUmj*BMSSlc zoqKvKgoZcetP_Oy-E(^vqw(Hw{7vs3$h)EW=35GHye#Y6HIVm_^MXP)UB;yN2Rmc} zP2z#2hM>lI$Xg`jkAwB6M&OX3s-I~X4jz8b8tRHf=S>s}K6wN_Z%Cq!o0l?}{#y#2 zw?lqzuZuV1@fM-xVTUol^wOLws}2YNF~P5QHMp^P6CRWlSGop)cEj`Ys>SH2-tza# zL)UmQ{n|Tf1$}vxvq!eo-S}_+pCS5ttVtYoh-0CtL6p;;kQ#L5gtRnT4Z0;`$GQgg z|Khv14~@YZ^xXbo`#SgzlJIQq@8SYGk^+aMUA<@=c*=RUWUt65DRQUDWYf<^ur%mM zxY??3aHBpl@Q)jM4N6%#S^h4K2#TrWyjpYHR~e$$px|qoGYzX{Nm%Lr-~Rb2Y94_Y z^D~RNewRC307Mr|OmJ&q*P!wHi)B6pfc z(k3#ugA|9O;Y~Td4B=gv_gxB&_vvX#`|XhTTi>pTamf3_3h$2r@CE6iZ_AI(dul^E z{N_{IjBp(2s9!@o3wd{TduPp`X#{0udF#vJ<1IF8dG-fvM(1s=_GF`0DiK&y$8q0O zsU2F4&f5#ux~ox@@px~d=HZDkKlAIi0t7z@fTIhK%{=AAijxA9Z8Bj74;-it0A zHg8KcyE_A{FPNTpr!swcq~0W@cEV5W!2bUb4R6YMdFX_LJw?xwLrW`Pd@cyHm zB!R|z!)WO4Y{>gg)aD!t@7@#LlbrDNmdKyEPgUM+CjH(NA-RY<4wSul@_GdFwiUH6 zkN6IG$B9SQjE4i^Pujcnmb;_gmKh96@63bMdogufo}kaq+Dvrb4m)mWTQT6`WQ3Z> zc8vM)ym5^_3H$#A;o+`AE3kRLBp0_w1x5iq$xUl731WZV0$1a(Vu!Ii^YbpCFOP-< zp^&p_bJhDG4R6YcsR(Zco*m+7y!YI9l70ethyVGpg0lDa!%H^z4cwgA(6?1+{k+Yj zuHj0}oK zjm>-QIbXukYrRa*doY5&JT|nDuX9hF0{@-=_kX+F{QvRagZ)1nO%0-)8I9DS!agAd zv>Nnw$V?|$saRJ-e53LgScA@QaX5S-1`#a z-Gh8V&BGgGey1*PmJU!91j5oOzi#Vb*C3@C$C6_ak>Ealt^0k`TGT&BM1<+ucB8EQ zhnc{J-oJ)l&%xLk)I_VShEuQ??c|=(n2z}>}2qem(V(q5DEsn8X|T#qw~IOw7+p3 z3lV&xj+^9CSTTR&zwk~i8~TvJc)Sa!dH7(=uZ%0?)r}YdpxRNT;s&sJ%ZbNk?>!s| z$kO7XAGgraAO%KB9TG}ldfriA=*uHGMok+YZU+1RI06lC%BlVcZ|?59vS_@oE{!KQ zLEa|a!3Lv{_j0A`m8y{U`qiq$oz>1HHMg0Y5>Mm6ftq^PkC69a-)kCQ31q-(w4O8R zSSVbP?{(+1xR(RurCemXdHhVgiRrRL#>F~14LXpW=9 z0w8yBtG%Z#Ht+s?t}w2Q!{FitvkNwAPcWN8`;A<3BqFd2>_=H&S>X^Lb;?8lbLQ&9C}0|FaY6kI{oS@?mjc zYWlhnKkWa{>^uP!=aIqkzWID>=ZAshn(42GR&J<&E$x1$S66%&0*TadlP9_eH;$t7 z4)(vc*779d@$RJN5ri>6zFW1r-|Yo~&>NeDMs!r~sVjpEb0P15iyvQk>tplAy%syG zb#a{Ot2fS5oW49#!urq8J>C*GkA^qpyDJFql$VY&XuJ=l4&LX3{lD3wneCLlxBKaz z>)YYpo45LaXQ!Dx$ww*Eevw2RxLUSQOBeEXYK~<;_ooqD7tlTO!!sPL)qEV=a}K@# z=baBOJj^13)zop%`-cXj-O&602c_=)xb=+J{|iv_xQ8*no)cepe3KRg%3{|=BiCbB z?+S?{EkpV-;NXaCz^-N3{lESTJ>HWwJDHyMWEFjRB%geAVj}MJfBiqwd@=H`a0R)L zrUp^IJcZPtGWJ45So(I4VzI7lyO{S7tU*86w8ll@3Uch?p`y3kyGTi*-@Y!6 zP5=Sp$@v;^1$kBVeP93=8LX=?uXEcL2BMZa;tximUt%wDu0C(uLV}6Q}p-vC43xL$7a-U*5>>AWM{ptGien;TCWBnlOB=#eA zr9z!`ftmZ6z6KS3@1QG>l$XU3CW(|s?BY0RcvC*5hVagQ)4LLlcmBnbx&*j_bg2xU zq41ts@jTHS@-{qu+$*5cm1Lz~rF=jQenHymj;KE59aiM?R08t;uBx0?w=xV|4YnE%A`IjljEoKV4l(*X8QYv-S_*S!`EA=<66>^yOLg`^EOO*uCavytG6gM z4;_s8Nv=5E#=ctsEN81a_0t@iw?T?k>bT2(aE#4DZ)H|BChww8(S#DSR;I7skyZ5N z@!f#;e}h)I9hw=6Atq+s_KJ0J!u#J}Jo*o44zy!?-lJ{h*^eE&jD| z6((<7hYNr1yS>bRK-xN2`topMU7#@ccuO2R4R6ZVTM^zkVbc|8ybb&gllMa2hW01& zXn9`&hKYXTE+idGNB?xlJM+U0{cy-T=jn#A;A?8ywUy|+B|oLh zm@grMUh25hVLTSW|8jdvAWG5KvV`$&Z^=;e;KrDr)#Vgbyr}?a9Vt*%qvP&vmxk7< z(BL4@%E}rUQ-;0whFdf3of%1B`s$54L|-0vVuwRMi+I5Yqz?e43QmJvq=cz+_6--|8KmJ= zm#!`zCEagrDm*Sk2A={;zn2<@fmBg0sahZO8pINFXWSe%NT;deTt;ImPO_ligB)&M z<92)t<6UCesCo2b%+Ci57dl(;g95?uenKSnC01os)Yj|pI|>|2>et5om?0aX19xUdA#1P;Xop|V9%x80C~6F(|DF4KnCw?^RiiG!ocsn<+5fL=)4b? z6fJ&ACW1fIaqxIGE4vZ&6{OKo$Bp}K7>{=>H4lI>zmEc!rsQw%13zc&&2pjGyd7KA zy%zBt1UxG|+J*b+SV0;;yRl}OEz|SH>Cu_T+P%(-e^-!P|HE7Q&$GcL2=DHDS?XxK zHTwePLm}@G{VNYCynEVIT%JMRSz`fsP5)h_b!F#Fzk@{Ztvqz%GvxjK_pQ}$`N&|y z_{*u!&%=PT_ZidKNp#-3H;9%dbP)d;xBktQVsm};>P==*9g1{eJled;D{@Bx$T3^`_lk%3E#XBa6;vZ*7=qqJfp8QywOGH zeXsnqwze2MrM3N0PKv(ReFewh<#i-fbdjZz;U{ zL@h5*K;BhaMcON^cae0yW#u2MNdN>svwKS+?@3LcCttbApijFw)-5^=3|vcy>$rx_ zdv$9@8BZq>e4vgiD_c<0|1aPFtG(&r_Q#F!c(0@8@dRUj7oJW!>>%@l2fLP-1-M}I zURULQx^5j}nevQLGzjdbpww)}Z(cJHI@K?;thm?77-Cu#=Qw zV(U3vkqCY-NEYCMD@e!7b!zDnWN>=S$0*S(447;@<|uaxy$0R(>PuP(??IYV$AMpU z71xK*8zfV;@XeN)jCT+6J~aYL zmHBSrwdjx7i5oh$of+`?e;H~Xi!kO_qB3*GCY}$} z#*Uc8W@7VJ+msSm*BA)mci!4~UITjtiL<{~tlh)>4@l#T>C40LJCHZOGS?vS)9_|} z=&~E(ZP0y26OH%DqM@8R$h-SsL=T1c*LUx00w8ZwCAqMYRu|HS0?pR*4T<3Eb{*kO zkoTH1yuLo7WKicgOFUZ@28=zll9uzL^L`!uyZR#JZAKmUHuSNOn>0G_^mFI3TN$u= zcT@8?g)zT1XD7<*J^6uJXxW-y$FX^<7r0#CWE23bxum;VoUlJ{*^tPm8m{Ti^ymM5 z*-u{{=IK@Z8;{I2NPINB31^I-A-qevyfn~wrwT^jAA-D}6t@HnK;G992lo#{-r4T* zEF61XNx5Z;68kz5!Nn-iHb2OFQN==CKtVZNwj}=0WHE_MT;j_+`dhoD5U*=)joYwE1bN@AvqC?akM2xpCOMPxEcA@7oXn zlpZ|V`%I3G>TPxN>4S`2OwSuHtYOwxpUQjO z27ma$$j#rgI{ycIZv{)UqOy#!t9SV0eV?zhJ2L&++w&oPdAL85=VCwh-}C=Si_Or# z!v22=O%37_F(FfG5T*ZL@X&@0tp;`CZ@hk`P^?=)-Z9Y&YY=;9$ahNrA8A88uz<~m z^z?pnmhpH3Xj{4n^a+oWvLo1~w57?Q?9eN@r|m!S28+wIzrz4krIYi)51UlnMa?a7rlDxZ8sfpUqA%S)NvkF+kYf4MdwXu z;1E6&%Xqv^sCoQ({_pb(ENwr*f13|%K2f^)_;qaF31?k08adp6Qe0`%j6U}MKZlgT zjvgK6@Bh_A>C59LD?j;q%v}FZq~XnxAaN7neKp|GJT%_&nymiXkau>aRtAN4bx1+) zRmi(o!QSCUsuO8$ z#gO+KP0=WC?po}{$$@B*+LQka`hOq#@)%!X&L%c@{$HFB4etfEO-%^zg0-hu(0JEL z+Yp=~?|5CC<&?d*vtynsk|A%Lc$kHI+)fhP`Q;pbw-UiE$;#rNkoN}ftomL_GVpE+ z+qf_(416D%-|F0k&inDUFPU=7h+v93?#=zNYJq>*|G$vbR#3%&XK&R|^EihwKkY3$ z+)ujmfw6iGmfOYH)w{m&fzZ6+U0}=dHR4Mwv7fzdxOFOR(TQzL-~T`POkW-!A931s zB>uPm&(M88GC8<{6sM^{0$hjcks2gzuyGMu4N`cOyix%+NPE_Om+po&h@0Fn`wQNK zG%d^Ns&`Q(E!pvMl`}B`=;*xGz5{DetFfK;GC4B1v1P4P@{dp;kyDzxbUk_vdhTS% zpV=b>mQlxjJiWC#@h$rPzZCC{S01*Ew}Nb><{^eLKfTw(Cr|9>1-Fk0POognu0c{~ z7HT&q?gDxPS(_H8R$*Ua?<($9)0$!aXOM2vna9Am&fgQHB@M#&rvS z>u#ZlH#c!izd{eDagCByRL)6 zyHUzlI3Mo+d-wW?I#^kfEY9wfC#EF;2W^{0?U1)hPVI+tGGt&Dqgdo&6$aFuIyc6j zL+3qD>BgOk2_dkSI?mkm@O)KP^yucOrdx$P&~7{>05yZxI^a+$M$<2yfQ% z7k$KHQd8A+;@l`yyqLweJ18b1PiuG*^RmfoQtmZDc$D!c#pX=R4 ztmrj}zxHKs{}Z8q#@$+zeC|^O7ps^ z1>Cw=VmMyEY10`A0j9$qujEcvVb&mA)oMe0#1!-Q{}<`Z!|Ty0>I>4#Xm|@Z&&VLW zg^zLZqVXOfi`>nCyr0{Yv{HCK2pzs$3tzDlsFzm}_+tbHZ`n14zKsW)Y!tpYLf-ds zL%g|HlEF3(A-sWJ7M^Gy^)$n3&#AK<%1V~OXLL)c;D4Y|H5vNxC(BWm*o0^lyn`huR_@U zzx&rfT{ne4OwYR|k-j`KT~yu;ADrv|C24pI`5b(O@Lu|%kPD6XR`R&Q2grNDq3T~0 z-kIfJ>|NpU7TJMLUl;6D0JGzupmZc29I4y(C=K$KJbO1{lL8qCayZFd5eNf8t}QEA z9nq_|ah>mtf_5PgLLC>|V{`Yf4PFt?3%)%F>;o4h*hPNO%z7pYm z`d%m}8t+w{9e>zh|9_#U^5lESTXOMK`#N~`R%M5Xq7{n>X=?KLxwTXApjP;G@m0us zq1xu$5xDpE%YWDS3px1itzD}33tx2JJj2gAz2WABDRo@1QG{djPjue?Znai}+Zm5H zA2pAC81ozFQDr;4oEMzGwe--b*Vw${BiNSO!M(Tnea}iaeZ%hm?;R}KpAq(j>DS&z z?CHy+{r2rUKeGSp|FL>FhWI(GLGm;;NPN<*8mU3tztn}%YS4+iS37IuigmZiSZsd{ zYf#|z+F8m0>F%%lRFAmYgW=*kTL_v7Ao9hp9(&>_>Cf`lCF(kG1xdD(PPGmLG8>*h z#a%?NL0&tJdI~NJf#uY3F#(3r-HPbuLkX<<}u6v@AETAILPA7&kJg- z{by~7*bP$LwY;Xi)8QaR!7a`-9QzeJHffL2wY$QZ{u29hK7D!Iy4mwUA$o2FDM!Ow z?3sEo!dpFH9ubZA)}Xb+r~FZHMhZ41S@(Pw52U#uZMC zfxPWxRl9C$kwN>G`lpwL!+>FB%R%3r=)B9vG8Q`(2>ml|)GMWNbUr$7mjlP{dk8Qd z@4M7I95Lp%*=zh+g#{0gdHl6wA051xzPP#BV_pPkCa&U;p{M_U8fUj*%TcE1jmxDk zkF>?bR)mXlD@a)y-b*tQ{Se-V?zIS_@vh!oXUqv3BuO))=r@qJXZE|70g$(MD}Lpe zl?}+r6Dt+KxkX-hh=)`y#Fkg-X>Kn1O%z$ z++QDZ`uzia1!+IMeAmt;jK`a0$=^I|Fy<$d)xGMi2rmc&obAbU@D8|j8lRPM3^W97 zxY)87yZ`s>sL{7N!2AsoR~~(NyfoFu(0DhU2>GT0 zdG|UO5xXF7`D6P{Vj%DHoOiFTCv63>V{6hjevJpQHkzs3koQTUuKMBCWZ>eviRAJz z6et^(%Jj>l^VWY;o3s0_&_Cl|KQ0#O9zf@<>g;m=(sIV*ZAi^S31faGPVf8HIP!ps zFZ181^J6bgxY!$8L{g6dx%-#iA8o3^-kk7vQ_6cV&GgkfN{hZcG(`?4geS~ZZy6fi zB5FRn5Z=dr`SPRjPCvXiU>oG^+q2~wg}2TLR-;77yF>Yn;KWrcP`zv0`4cbV0T-tP zw*>6}J3jaO%&5Y(_Z0`CJ$&}|*+8X&!#Z@{hq+06duoJ09d%r2uWamrQFPv+eO(jm zYZ#ArG&PSPjQQaorY;${#sk(6#hV{3!sfkg?*M=8a0sYeUEuz86ubXVc{^_WAz+y4 z`~RDj^yOg!)|||RXK!=D2A7rPGLBP{L!W&Y;RyWgfB!Jrp8&kXuB53!GT#E^Vx7EmDp*$cUIiSjU6?P3$vzTb#^C}F4Nd6qsZg`4)iA{Oa{5j?`)7Kze zCY^btXjf6s|5KvjE&W9KCBl2Z@^4Wz-j%$v^EDvvsFfR8J0R~aQ|}WuA@40;{fy3~ zIe^^c_qj=@5`b4p@0|w7`+N9Q6pINN9Lmqzx34A)WUKVbX#POw{oK~E;g&oRT%?YR z3)+m|cM+X;_tBL;?-Lo1HZB62SB;NL(&`dF1~9JS7ElD@a8e-pfwP-9vaQlWIiJcoPh_6*xfNyJogz zPA>KN`aWCKiuIILKr3 z#vNDQU|<&r^0#bRwoCz=xBbuV$+D;xrsq92Nnail4}a%Z9iQX9f`+%0lkQT4_tE>O zm!R=3nti|e5aiv;#;@85c~}01->-lTQcK-4r~7{#z@{$4S5amOASWkUo*VZ6XMZ@o znAIl(wqn!9Z_mPj@|cg)p$T-}7x!$8KCDChXPjr{!U*#V=)9+s!zNi7@CE4{Y98M( z=9fG#Oma2c|G%}>Q8!H%n|DF><^mq4K(J^vUt#fJ753s}%1F=ofgAHLPCnC_M}6d! z(%-|06li!$%1((Oym^kfEk@(5^Wa%|F6518AAL&8J8G@7vlQMD+&fFK^M|~HBR)l} zguMAr*fvk;k^x!o-nyzY@bnf{-SUWTblxE=6vd49&L z-l5byCNSnF{BVbVsTmKr*1GIdlQ=eSvs7CJr{j^pWHr99v<&<1E$;eD$?3g+n4fn# zeR*^Ue10E(`@jC5(OUig&-uXqU!A4~tr#)zL26JT-!f^m8kC|T(&r*utov}eSad7A z#AaEW6>f)**qwg44t{LZ4zwpcc>fT7L5fSmHB%6-ATNoiE30iGg9pNr&v}~Q8>H1L zRi^)PK-z~F95P*;M6ixJ?)h(gn(uA&8r0&iy;#+g@oEr~M-#^UJRb@tZ&u;~J8UIi z#wcUgps`Pr?#tE&f*a;i7nBsSSCF1-7er5-b7J}xWLF@4dAv^GQ`~TRZUw1E!&~9b z+J7FgQ#AN0g~q$o{QljekoO4Za^W_}dtpw|R0`xhs1V0*@!JlBY5MFjkWK_WI6)gV z$h+k+XNR8^8D!1#tZ6F^17^4`wj&?WFR?#klR9xcL|{rC=N5d!h%FDDw`9ka=M{Sy zk2jKs7{>fo^Y}yx?&krA*VG?gOb73pB=uWf>VaU0L*Sv=5FIPX^V$pG3DQi@8`nf< z9$ca(GJjW)sx-Xiiu^7i6k2DjeD{}3nA~dem%t$-nBe#-&-JWLUdO1$jo-I zD{f-w6Fw0{A1G4X2zlFDPIY{>Bm=%(aur{5!@z0o?sH8q(0OaEE)h>%Oav#X;|6+< z5A~;`^Y%-=a3d^;@pvP7_+ZTMsqk~xRcbsS@ps`~4?1pdMTQw|_@LkotoE_*Zl1#4 zLCRfIi3ZOcFES&|F2BLTUL^|0O5VV-d-Gy zH{M&fX$rFy)@l<65HI01Bw3dLmTi*AiGsY>2E~88y^#zI zrR+tw`-K6G9hSpkndrR5+T51Cf_raksN-IDhEDtlMz7w_!;k;;U_jpD)I4f2=J!nB zyjgAy54gWu+5g*WY~IFa`>u?1g#j%O$G$Ev?CO1e-_g6Tox7Qy_wQu-@`!Oi{fayF zzyAOKv)^X4e+m144VoIH`f=+xQiEJSh$^7fpzsWb#Ny?}y70{7Q!ii*S~O_nYYkVB z^QzlhH(j>{1HbjyHf1LQ@qLnuy#z-|aeJ~Kzj7pl$o)SqU4fU_Teh=jjr-ASP{4;6 z3!Xnh;5v0&p3If;9i`|s$m*)6f!7wsyTk@j^RU2}U-V*mXAfx}P!#9BhE)!`2Bpux z@#M;YQpfMJM*7Gq98V;L3qEC8XUS`0$lLMWRg2}mw!rV0kJHW6M4;HjtDgXQJDVPxXtyVW znAtO({25^&85e+CN=D~x^GUPB2J()hj(ZxtH7xO8`v3lO2VB&*F&=MQY91dj=9j&} z<~^@F4>;C#XVi#}4N?W+;m1!Q@8*)XmN|lStRRb8S4Z!+Xa4>_iOxK(N>BIi5TraH zy@rOja?qzs2=BL>%4E@aD?TTF`2l&C?>S1M@Gjr(I=ce${%xxrzgXH9_`6qM4vR_z ztiS3G6+zy=lB8u{*^$8|{^gvZ+TmbBdU^Tsz}=`Dd(ZA|>PmqpNEuPbg_qb56i%a8 z@5-$m{ZAYik9R#akB1oZ(+?#4OaVN=_!H^y7dmcl5fzs|%n&#PT04Gl6da)AcuUKd zA9>t6n4dSDdFRF5MwpjmYIT~*P6N_(_b-d4JLX z^M1n@q=N>gO&3420ScohZ;tFu1b>c;+^DATKE53&*^)u}_2=&8=fi=T6_2q38J+hI z`N{V`<%mFqI*#kW#Hu}No~ZvjSSb~D#2;cj-pGQu&Sc-cEOJpH^9BOAJlQr0?bp=UZ7X+^{rzacib6|w<|Rd zO^o?z)E7KV?&JnpfeW4`sAKbXx>|Xm#WMnQ%)TV3;A&C-xBsWrJAqGA-~Ns1c}Lx( zFOT;uems2F|Lgz%`TJ+&-@qEAO;dx`b}DfrH7HL?Pz9|99b6qQF(Xr~o6)&DpA2iz zIo?&>8{j2&%SN54C8kb5LNUT?rX~^8R=&-8DFC1U4|Roy1CT-7HQ(Ycqj0dZ5LeN1 z1ic0&9bYN>ZXOZrppI)vdF1h$8~qY{$GBKo+mi8WP%<@-5{&tg&oBIbZiEMv^E;&T zN?_NZ_R`pEP5J(yzN{-j^Z|Aait3r{X?f$v^ef0H?kT$R=v&XBzY(563VE-m;l1Y4 z2od3ZIOXk1G~SuR(+x{ugLI>0K&uJzzIoNP`!wX8{k8QYf2#v15~{oL=t&}&e)C|{ z5ahiHpZBHOjSQ?L)Rh0oL*5C)h40+ad9O09J@ECH5OAW7d$jiIIosdpm)MHfO;3m$ z8ISjBY93`6^E={D$Hu103oh$ucW^Aj=G}U;g0G1!9O$=9SiISa&3lcC-dImh8`JY1 z-a}s=`eVkY-sH^j)}rCPI`rH@g!e-CQYAFr1Hz3L^dN7K%Gnnb-Zm|d@<$+VE1)}c zQOq8!i5P9Ie3%G^uLoY?geypcyN8prT**M>v74WtWH^w@oOa#sh|W8*T)t#*MhJ*g z$Aui$eAzLH&O4PX?E7K^yPF{guhLAYa4tE@CO@B3}HR;jax1EF71 zsn$i}JJ6A`Cx%>}2*c^VnwU0Wk?zS}hjwy8B$)qPwk{IyrEjKlfc#QeE$*MnSy8~}; zg;w1kmBHp6V;=u={qhL#u%myP=Lh!ft+>)M<#l$y(4^t5 z&fBve;q6;%u>y@Z*NPtZc*tAK$?g}0_va4LJPPl2w^_G6s;TNRDJ9`v-q<4YSj|?&-&nE&k_f-FrutEC%ZOaEQFEW_DYmwt791iq&l{16w z(QA;(*7f^2xQRfQI?mCS-B1FL-v1kB-@mBFfHeroLl0wqkM?#9c@*$~wj%>QFMea6 zL7MNU<(rn`4$iONBX+A2`x1-O*+dE~@MiuMq#=EIWPf&x1i5n!k{%83_2=(CKzJ8$ zwXH(q?HF;o#24}|2{UwQpzt=&{eA)R=8WjNy?U)H2$h+zjw(n5p$ktwDuBG(V(c7d zJjvh!%YGl;pJ5S(-m8a?AvA#XOWq)`g*-IW$Q$|3Jw<*)lUi@5-C z!f^G$ibUWiT6>?uyF1s@;0NR_clt?|?&mOIcf?JWPZpi`3Ed-K_rcd&Y^mc|!iJPe z`_Oq8>rL`y+Atn(B#$DD`IRehl6Z=Ez`*v5colZ+6=c)_mA?2NN~AR*+w~7;W3M2i z&XxYsis)u~-ncaS^4N2FP(0x8?JYpVd!5$ebx8H@nSVeHjraR^!Rt#Q?_3F^gN=~) zyPlHdM#wvg>(S!%7o5Rq7v1USjfp^$=+0IMc^9nsX7w5Jw$v8f)-ekY)oJhzGSxum z-KxJxr&fpvf~n(zSLnoKeL?5_YL5Vi=MKi>jpXqXV}6JIs}|Y7j}yh;R=OR}iOm}~ ztgBdmzz-Ma+P&6Z#I{=oJ&rf-l&chQ$eN`H0r&A-Q6=+N-iWNYR^cq?`r zs-p4sOA9J%hrAazeBq_+ywHZaUSfCd zXes2^L$5*0cHy`9EGGgd>bR6f2E9=~;G~VM5PCu9D=hjICM>PVZEFtgw z2cBgU`^eya-Y))mY2o0A=G}1N9(3O81TMHHFC&6z>bP0g^c9V$AQu`eD}fS9pQ9W?ylB4>oW4iT$r`ddug`Y&9@6_W_8^N%?DLf-71pUxC}lfg;fuYSW9!oihH zE;a8yblzqqw{Cuf)%!Aaocn{KjC-5Wd9Py2JMX`X@pvP7s9?;G&p^EIxd9*89TO?y zI)=@g!I=NI2JpzOWUuwsX-em@Bh>PUq8N+4Xp;biS&+-FDur)*}7M{2G$_a zZJW0o*{80{-Lm$Y)O}A7tKLw3s(ZBp z$~V7?u8g_ITg+&9o7hV_A-vscCh=&zHT`-Xt%1B--BpchA@7l=XFIDQ@0FYP~WZ~Oem&RM#h4-NI4v}rUB&0$F+0=0!H3iXc_|bXGv)I*( zG2r4Pl$wVO#{3RQ*&cnL$qRzg)6(*rv3Ymxu@p4VhyXPm0f`nB)tHMDZTqS%lGZ<% zp7#?|`trDSlTZlK{(JwQDK5{j|KChggEn22_@_a7+PrZQS`A80xyEJ;`~PIIaI2@V z1}&@zW~cQ3zhpvp8_Iiv`QoatlT;GG(WaF@_2CLK)VkiUEs6}x-W3Sk)_@HXo0G)) zB=j0&csn5M%u0BIGdE9B-lW>2S!~^Ee7*9FgYSR{a7FzSWm2aZnX=&di&-YPY(bhu%eFB z{62h5cQHC|>&6>xGW!^>dhbW_z?fgx`)$h0*YSek{7AWnh1k6Lqs428T#?`yp`oHg z7Mr)_>)@j~noUg4JMt}kc|0#(CvZ7=j<+QZZ}Vke&LF%cPd%KE#@lwW&!20M_x>3c zd^O~)$7hmh2zgty)@O1}dV;c_gRc~P6Tm~xxYa3;ck#2v*M;F^a5_Qg;!DMFkga{{ z(O4)t?-RQ3S?8G(K_+!v?^!}CH<=gMeNb?e zx{1x3<$L#|s0EQAR?%*M=l~s?6De=yT?X5kzCpt6r!$XltQCrXA5OHO;ceENFOTq! zKN!P~#=HN^8Sf^@TSfiYDGKkLE>BxG$opCFie>(9Ji!LF(^7rW31Id7Uxvky_seb{ z&dN|S&~Xs1e>@xpqW>TE?mV2T^?w|`q0C{M=ed%Ij7hp_prm9-LdqDTP^OJiindvW zP%@KHDGgFPbD`ZphKL3gDGE)7Jonbx=eMut`L46}?|QE5dG`KY=krf>&iiw&_q$%b z*Zp4iTK8(iH#_Q~^Zub~p!&^76dXa~0>oyF0+`Tw8-FC?c^>|2teCY=s5883D@CT&_t;7QXv>x=$BI#hJLb*{)HusSSum_che+w&zJ!sL5 zgCj1tJivSAelu(NSl}^W7xGMCj3_f~e^Koe2~5rwvR{MG|F7Qt>}0A9dJpQHR5&8R zD+=_GxTR(*E}96S_n;#w15;bI>F*NTjnsk1$Zxlkam<7X4(!xUE8TDqy9bHIvM^5? z`-3CXq)u^Z?D@Z;ZEwoC7mPn3tsSJTj#BQp!|s1~kakeUGw|5YPV51R>4f{CBdWm+e~FE(p{ zL&e*Av-?vDZ!OmMd}zFPbZ@sGfV?{<>MxRc`&ymlJP&yr;QBnW_v{0vg!1%6@mRpr z=Be`=^5#+IlPf$)0?(yVj08LI;ODXpd3*om{r`mcvRnJ*MZq`{H)x&LMVLl^ddm^y zoxenf=l>-kb=YC#w=+-5wem4PxGC6ItR9TbyCFWlilf61T(4a{_~sk-3bO5sCZ7e4 z@sGEx)X}1;j#b~wGm?+Y&;Qm`ysd=K$xwJ_?5pHO15PGp7y604DeMjhnc`PhMU z6!PwN$#vmu+Xpr``hSlXiUqsOgp+yTfE34nbHMWi38b+GYONc=gJ$nfhg<*U^p-O& z2St0}=0qJ5H}0xIJj;Q;IB`8W6u@Ukf89G3sbeojehnvmSv93`z+~G-j?3ZLy!9%# z)}83|1H;!wpPQejVg6rmQ6nL25981O0yNg)P~EQkcmB7c;=R4!Y!`+1-O`9fXuLJf z5PB3L@1nQs9*}vfaYVu5gSQvL2uDwS$ZY3x|-ab_We>#qnz*d&I z+#fDs;N5lZgX{00FHXJ%>8jVOiGqG4u3G=0^=?yi-WE-o(oS^9djhFr3r2oiJCiG} zz2XP#PnFgLBx3V^(au*`lpY8Ou02!2!w)g%etGCprj+Uoe4_%wPc+?@Dt z{%4H&-+`(JIpnMvr1YTNG#xRt9<;waqWH6Xxlvi?kqh@=4=RhW?d|o|GCKM3Xg5j2 z4b0e^qzReDf*qN`rib7Pa^lclEu};fxYw1j%#0Tg_C1($O*`R+`gdnrpn*!qVRrgyjm2Ex9Yn^ z-#Fobl&C)=ejoDwb$aWr1@IC(vSRZy{xmmG9{kSHe0?m4h*LWs1$o!0y%dy6Ab~~4 z#((E8!Govr)05q3ZQil&lew!xT<)U2h->0e>*DPc8ko@D7-y0%Y@K)zb*#MJ0NexQf@mUhee!*34toG8vwf=jlwv{Oy>Hz2Aa4zc*zBhRun*4R2DozcBv%f1AcSR@~ythR0j{ zH~;^0{iffazyWD5RS$Ab!vCi9puPMnWzc$1q#*Z+^>F^bn=$^p8ulO=%eu9Te6)wsa z3<<2rG4o|=aC`U*0ndv|pn9e)3hQpX{T z{C-`L$mOcWfn&M7JDaqydFLJ7Lz2u02KUP4r*8WE4g*nty{@kA}SM#gx8~d2{+V3bVqyw+h>aU!}~rfDKsL|F! zUGx>?v+R_DLUa0CK~m~y#mJ9az)$pj7!EkU4CV4)hs|5r^@0jM^#FKq<>7(4Q#9-# z@jQ5MeBvYH^Ik|>9UNz$r);d4@7}wqc<-Lv8cX3F8I~e}#(Q9$Q)V&b9T}U7uYtT- zzm}f733=yfpS)_{2+7%u0`jKcN7<^v7kTRlsXP$-37GOA=zjjZ)88kK z#yh_yvF8!w{f1+llf3sv;XSD7W@Fdw3YI4bXZ^8&dv8rXvW}3qJ#Hu{D+wNN=@(#N zumKN@iwzI#yobIxF;*vT=gkxW0Ev^1T3ja^i@rF~&rq%us-eHTx0E`xG4i{fv_1Wf z0S>5mu)UPugw1<_-MOzjL=OP*vgzEl3N+0BsxK9sWd1NbZzeI?>R=%p)E2w`-~K=S z4*gV_!TH~vst4^ObX=nJphecpl+b#RcUa%hMLBpt`jam*w_y)zUuRERv0uxmOjTTK zi;n{+o;su0CJ+mL*Qt+M!1;e--)AfCToO>j@6;9Mg&#=Q)M7V^M8CwAUF;3PsN)-X4< zz!%L2zaPpCn6Z#b1TH)ggXuQA3 z<(NKzyyc#?6q9*Bf16ui1bM&oJQ1BKxEuWHyxMY0E*6-m+Z;atdH0pFvU6S}f#n>Y zVGn-efzBxjrhHFy-a$;ePx-?Yq!tpl<`e&Rf;2ks-%1I3EGG2Fn^MOlMt&-7uU~)M zivyol)_?oSf_;fqFF)?`_A(xPuj8(-TZzs4aHO5-LgfyI=e_ADZFN|&7+;e9d;Xs* z6>oR7;C~KCJ1|=(kH*__Nn6=#$XoWweT_Sick?r?w^oq%lBrtj#D#l+;&|l`>6Njd z+oQ=l9`arue)sXB3nY-2ba8I|6dvH$xZ(Z&<#>x&c3IJV@D0*XBu-!h_j4eF&YLwF z*EdXuUvDKKbM5{Tq|rns*&3{-tv{G@WT2kKqN zqfaYX_F9XA8%UhSi#3{G($RSrgf~Vdc+g+>rqq#*k>Bw*c7m+&I8d*z4xY+j^9H7s zYp?8#1a1wxPl~+5emRkeL+4(U!Dq%FkoMA6hk36~;%G$_`Qb!oD&8){praJt9yWVq z(RiC`vl+@m-iP}>7?bzj{PfN~tAxCVzeg)+Dma6Z^c6E(OkzQi-B#s3$os`FdqRIY z3CQgp-RoQw2GZD5nA zzSA`;0kGq9glF0R#@?HC^w*nQx~-^fg0gUzntZU|OxKIyySLefTAJ#xy%~GbfGPFA z{eKDodj1jiAaAN3@faV0N@VE>D*l;Sfo)z{WPInCx`yvu3iO-C9J%k6(h%tP^?&t%O!xx)Fg1_Jc z(n#EF5vO6W5PAH_wF#FTu^ktpNH@I8nrjmA3i19~(5eqzUqinq_^-uo2Z;#D7&(Rh1LibaXT z0V)0E%lBm70(l?C#2{}LP_A>ecL#hgox?+>iU1KQg~p~ns#6=JTyWq;7B?Y$2%FR?~k+3`5hR}9blH9u{2G;n>$(So1Yf!*7a ziuZmo;{Xb8?yl=g(RlOpy-{5Qd2eDPh1`U^dzcP<6o$Ol&dt@YQQrwF%+?g1dqDt~ z`9z|`A#dAdE2SS4kbogieuZEq9w_=8%(PsB&O1(kYs*S_dW#$qm%mo@$lp8_N4n-TsJmvu2c8VtXbv?c5b*VxcVp!-CL{nkML{{ z!}DfZPFo%3t51J)`ulmyeN?=?dE*l)yw5gAFG1sdzl8gz6Xdbcc#v3cw0Z*RX4 z=MRSG`bXQn8!@|g`t{-R`}yq*KmUhU(pHDSqcVf8v-6u19#p(NAAG$|;XU%!X)zk_ zDuP79QOJ9buy`7o_m}dcM$(XXe}GL;3X?q;w#>i(oGlixW<|5>LEdVDOtBStB*2oB zV(D-W56;vuzbs`#=Y8HT@JcHDdTR<2m(%)SQ}Ymd_wH(0mZ+pjf4nJmJj2K@ysee> z%w`-gUhphJau}O;#}mn&=aT(_9betWhL(Cv-c0tLfwRQd49}Zs7mamnZD=Kbd+WdF z|LJ+~M{SxCOyOf9`3z+rZcd6kV*C7isr+? z;KZk2+h5RwC0d(Fro%l5@@b*>)61R=mgYUCIUqK%IqokkuhyHk5BXxvg&#=Z~9p?!c=1g{LW6;TY3^e*;(G1 zLC9M(SS~oMganihNk_A94FfoVH(eR<^bxdX5uf>V5nxpfcviM}K zMTd892}m8282LGPgj`i|6abBSY5Epr*u1-fKN$>|xqw!MCbz7s*u0g(4{Y`oA7yyn zN*1)$Q8KnvK;Gy3 z<7BswSb^4&`%8c?0q{k<5*~%TMSXmn-W8KT)$dyc2^L|1-(`*Vhjw({+=n+Ajw}=f zi;%eXJ1O~>wxRRZb{biDhL`>ZBrc?m6&U%s>{uaNcM%8r(|rrgu4D5SKcn5W-`oW} zeBBdwxw09xO;FlLl4sbI>1eF{F+J zjQseRvfKRzaUhpPAU?JRoA*YASKq~2T|v#)?D%8m*t~PuD!Wq(EE&FgDMRV)m({McSW*#Y-RYvbY zUCO7`RNX~@2NL&W;oPRg3iSEEpj|jt+nfFdBuX7Q82Q}`UGLMOCIFV#sD7)B#_mC1 z*5p{fblnGvKRsZ+?t+nDXWZH^t3gVh>UA4$&L^=l%Zz z_6}_{-d}4TMn8hQ8x*_QMUn^ zABK+pbRqy9?~Z~9$XjyyfIb)G&9blLe7`c>AT{gHHGGWDJ6Gw#2Q6C>pn}BNT$))~ zc@&+u!bB01vlIRC&Oz#s!N^aG^fjfe0tfbQ-cK-;GJF!e?XcGw*gIcjNM=pwEg>di$4|bz*p+Rg(_2V&hc(f7zaO?-vIq`H z=e>i1u0h^0r#SU^A@99|MQvb0CJputiNevlZi15O$Ky==#y5IfD^Q1rC0!STN82S0D?hyYy$`4r9 zdZ~yfWAiQ?ebAMt7zBjAo1RE`Peb=+KIhlA&V%83N6w_vRL9b}s9Ax(UvKfF;(hr1 zv45VujeNOwB^vL-MNpZ||CH}`&+ zqd(r0NFAXV`PJ`RFi;qU0~YxUB+62;dDlEpyd)MD3^+FGUNPgu=52QNrO;O=#y{R- z?`7KRu*LhC_n9i@fLa0MAG zv0+g;>_OZg&2Wye2PMBvJ(Fi>2UG>*dTkO3;1Y9no+Io*F8l(Izrgvww7qG0Ay*hM zxSr-9Qi4AJKi!pS@`p_ntVH7Kaz@6^EJp7^LK@9Fd+D$TJwxi?$H>n!>FM3}Q~}Tw z6`jTDh~0y(rC$3suDc#wslU2x;m?Pt_i`zJ-uSNTzx^%-G5mm(mq%M2hL+W1jWP2( zNFh|bkE~FrpsXPMzcA9HO8diQ_N*eegXFop-fm z?V$u_`n$#c38~{IMt(JpAEI>Halq%|n3uCNHt#;EB$-P(>p_xUEVEPr_9d2yFG^@k zH-h1LGhIDSQysTmMogdl-Tx1!;vN3W#h$`DXEHk95CMF=`|*?u8z<6uNa@qR@Q&MfpZD!T`r|!`)DeS`-!q=4Lrro5AT`7N%W5xd-c$Fl zor(En3}z}_omKK0F}pX*^yl8%y)PM_cThBKb>tn=tBFjWzk3@*#XIbwr5Aw|?_fzzm6MQn zn#lXnoEbbgxXI`j^J#S6QO+XYrQreT-bh^Ail%Gsa_HS#?uD%HX&(CHeFCXN3L`(q z#-wHL0Rq4*ZN!fC05!*3{q8aQzCX9{;CJmYO@)6soG2crY4`Y$2$)3T%1-{W+4mIv_7?lgAAjb8 z=x_d~)WM38-@RVb!7rb1fa~(>vXF3W-jT=Oj`8m|17f@hUp4BRF}pX@_Em@Cy#g4% zdq?7Ft0T~=_+$b+oan#j|0&ZK9sdaD|07gA=;Zd2E94$Tp8qe%S+k+_Ah!2|zwD*U zjdFX}Sd_vZgx_S&Uf>NkNRQo}0LgYBC8Fw*#7hF$SeyNGFYG~8A?eHZ!5%cTLjRWE zV?3zPd%M>x1^p7+t6CYMZz=)`khtW0m1+G>^d7|1=~X_mj{bTOr49~^{3?ca95|+n z18WZ0Da7ew_aO7x-*FXoyu{0sZ_8a4wqW<5$fx%VGLAER4`Q;Ut&UUOk4+Q*zCjv6 z#ruTRcszyozUMLv(Rk}-wp)io-VXeGd&#`BF0b*s19?aD{Yr{1w*!s+Rotte5WsJ# zqYLdJ?|8PUgRdcPUfBn8r}FWDOZ9w5zAHNKH(`bG-sU2J8Hpq0UgJt6qVpE~6qC}h ziT-#~>fpu5Z#HXzXCRLN_+NZt`=P*&Nzqot4}F6)tvUOO z6nwnJ0*PD3^<;aNF*@(O>Hyq` z?exF!?sWH#5%qwJ6C_S{W5>Yg26WynvK_L?`-xt^&0YSWmY^^26;!R66}@9dvCez`pS3hz@?#GV$J6WAffJ8{x-<_GrPpH zCdeDl>8AfwHw-AhB{DtgLSLM)sGeARjYky7AaP4Sx=(xm%jYdBt7C;~>G16>N*z}) z@-sQ-s<>8Qys}R z6+fMB{x|>A@znpnQakBDV5RCoaT{Nsr1T*9?oB*sJ?NvVuW+?gxe*JozoZ!UpmhC9 zoaFgG{Qk-0VQD+yyf#ikku?@PS}1CE9QGi~D7~dB6(kUJF{QQcX(%XCRlj^T8GQw5 zRrJ(aQc(nCBXKQuF}rU6%O!Tl=INk(EkBU28_X&D#bflp z{(%1HpY3|Qdt>oOY9kb1$mRkIvU+SKFB{!-a#U;Q1Olx z8Jyq$Cl5&C{LTd;qOTxltTdOa z%hDh3ex#0H82P=abVzsNzyZ5Ob^ROXuz4>hxs1DT?IvE`{Jz-sDGf*LJUr?n@9)O& zyqRv%SjR%#@)h$dNCGnz?^6?b0+jB(zDl%_etQwxoTXS<& zg77*!z;!%#V(dEs$V(@!^o6{MdhQou;q(8Oghsn89D0K<8a4&{|feCISv3 zakagn>b~LVywy1;_AgSVKi*f6I#e+7JAH2JI|mX!aCkd;uSgJk1?kzg^wPeg^_J;)liTV^fn_CPH2lZ`8PENFjnKqU$Gpz_j^P3G_wyPaMg)?Ai& zP$MbAu|*F39^|2yzpS1t6aiI8+_4Df1D#RmJ*df2XC`!3iAYz!w=fxBq>cv|`SIh= zEq8UrfrxF>uD@Pl4@ho{T`k%sG>F~jOUGSr(6EA355L_PgeZHOermy zUqP}{@lNKE3#VLSPipYt(0F@Pl##R{Z?ojDfrXIwiU1BzPRM(~_a{3Xi*|uuNAwb& zbH##XQH!(UA@48CpPdMXylr?QyYrUdfx?~*kzwQLm)MC{QOhM+MSvs{m%U|;kC!hx zZ_n1XoPpEy$9oj1!v!NhP#DOqaTy1^CO>}Q`H0P1LnyGl$;W|M+0*>d%>F368?sWqg1SjdvEG(|%jXyXxUMYZ2r<>&kiX zJ6u7Ym6-i5ue}SLWzS1ig}k$(ZjX`g-riC*&=G;Rw=9_1c)s%DLHJXr-wj>pytgf# z7Q4tI0s@h^>Tf&kW}VS_$BnYz%A!Nwn~^%AG4dlg;2L-Sz=3OfHr&q{#^$|J-D~w5 z2M1zoojP7R7kfZr5{L=wE`H1KylJkZZ~W@t<1Gjasdy(8-zuW;&iYWwi^jWD)LkzG z^2VL7Jx%6q5|!224tY26I^`1J(_34&)iv+qj0J~e5A6ztyrrL&zP=85h#w0koWVR)=n8-JFrdGab+M!ED#?v z?m7Z_OCCISeK+Lov7tD0dLbS>{n(&y{|KFTo9x=zj|w8-5fW!oV0D(s1)X?|vr_qg`~UPdi~f)K!1;d>RS!znTM$I)L9a_ziJ|qN>(=E}0g~lLK1Ifc zd9Vk)^=tX92nVFtWC_EkDo&u$bei{FKLHf{XjvEtdrXTi$am-;=6&R>DRKL5d!$|XTbk3 z8@IQvmyKY>JlTCD^Tj&X&l(_yY`OcZEW63UEd;_)O5kRnA<$AG#s(>RAnfsj;)#Dc`I$B zt&XHIwU=kl%+LSaRJ_kVUkQKp_w6mSE1kk0Lqyz&4okWf3hSV;Nc3Ahx-^`N-Z92kYBaB?qA;j?}*sZ6rCml zjF7m?PG(+h|H6Cosv>>9X!_$#Lh4wDk>Ba?{PleOI52J;H)4Mun|BTij^&1#F0imE z;PAfHfVuzA^lg@VM7xRMc{6>du@24jJjK6{w{TJMK69aFn!;Nk=z9t@uT^>PqyPI&PhT73%g&U(5_@h-f33pN)grpJZ> z=3=Af^IJVo|5)BD+SeV;6#+9vf8)*$^sqPDp}+s{f4FE9Ukd&49zg2w#>lTIAUN@T z2@X8?%AVohhRxe{_v?CAduw2v@5Pd>i+#K$)7Delh423#@PRZX+Un5u)A5jpFG$0+ zHzyVE)84uw6y7N*;mV|6>l-TBYWLzBsW~sBqBd5&=^of8+LV*UfudioQ58-5=Sa z!c2d>&5=5cF!B?TV|$RdTmW2M=NmHg9Gkbcn|Hdz84co2J0H${H?eu&x)5M>HJR}r zPL$tITOE3=F)hZiXaC#({~rf#I{SyP2MJL1pbIMB^C>+@ounay)`QqwkBM|ilpCE| zVN`q(_MrER9(|dD_aIOFxmnd;<_wgagF5*#382?VYZbW%tqjnXbca3Yz?qHpAAf}c z&Z!F=8tv%!ApP%Z?F#=T3>G4BUDLBSQrDsPpkKF(?yvkze;cH}NFCoX^26WM@)A)L z0IjJnjE91;d(h}ixa;8rFOb5{{$p02h85&P!@{e3#u@(}WHya;C>zRY{ar!gsCZ{h zpPQiYHgKGlLgTHYA-U=YaC zsgQSu>{O~0B}w`i-w^kVwfeHHU7NPa5bnGNCM6yEnen8`l%v z+icyr&*vxh0>?l1lbkCEp!Hkr#$@seQrVoz8}iO^`r|9M2M-K!?pK)Bp!1H^D&43J zd9Oy|O!Ie3%O64K{rGKeT=Ovf@ji*v@dzWoMIEM-U$g}P@6to2FA}kNb6aj=ZhGNP z{Jk|WpvM`T_larGo$0EK|9Ok*WZLRb{wkYQHh=yffscxJ#<_5I3h%NfnG$HcaVr;R zXhYua?`t)4A@7o!KMTkYCz|kQJd2Ci3$&*;hMU|afE`BGVUdux<&ZYFE4;nMK7daS z+=T~Kp&9zj+UUGxBlg}q^+Om`B5_xyI^+&Spz}U3$G;9gLVvs^kvhCF@=I8F?%2bV z0-&>A^w^4X*t`wWXRnJqcPIKSa^m7|reSlUpd9z`_eaL>-a<6iaXOSGbN=fs1YRoM z=Uk8Or|>T5bQ4G8T~8v;SV7)gUy`fHy!HFudP+jxj*nJ4)(Gzbf=Qh{{2c^v?fWHh z^2>>eWz}2%K;EL__A1;$VZiBpzM^6`I`6)X_UaaJ@67>;lVp*OsO3Yyz16pEwL|U^ z`kVi|kUF|C^7|R}dgqj&09dN@J6f;=n|ITBHnUI1Y>Dr*mc%zN#h(9*9xwX3LBp2e zc@Iw0R!5`YpQP`E|K|UH7N_+56FC2iQuUyG(Gv?PJ?J~9tP)xe^8Gp;yBZEiOl_wH zF2EkNOXR?fn_gN*uNrF4U8r{f?S<=KG9M;@qKKoar(q9riRk`8UP0>C@a;=93{`A*_bdWko82QOb45-(~2>?*% z6D4DY-Gc%I7uMx}T}RZ=`ldhZjeY)~LGhMhA;Y~4--GyBX{$rD^Rwu~2=e*=1Q9CU zxx>%rKe0=Gy+w`tn*ti|50_@Mc0u0PBk!e>dD|S?casC&-ntoO@MKG@3y8=K(RU0d z01d;3#5l;CGf%;s1bKV3a$Rc^2?Le2b+yt%=$F{t5AQ8Hd`bjdLE`KMW%etxpz~e} z)_oN_Onc2>6P`#bH~IzD=LeHv;@8bs&aEW4gx6OngmtHVfYijDa9 z;Y2|y-r0N3&VPHGyg0cL;wFp6yF_7S&n?J%eZw+E^4=STcj(>Ut?7_=p;2Y+7sy+X z@Vzez@-7VdlVJ>bi=7Uft{`8nri4esc}f%P#f`-=Rqd8df&f1rH93rrHKeepDWy@j8Dlddk; zdxqz2HEK#z9rtIS$G(8aTm1L_KRplrNN(^FD@E0VE(wDG3#{9u)bBSdcAV zZsdjcJdp`|(87@M=T@FtM$gil*GfKe0dfhR4w2gk0O!A}_W|rdG6JldQ%gypP+)}? z2TLemlRCbCrr#BHVZXsN;KYLG!hjixJFjiu@wEv3egSUZ-P4~M=&uK@L+ZfFujHPn z&M9LY=5X!^T@BuT})_-C0PWd&LAWK0>2cQK32>^;c)Vo^4G7UW$k$%{J*d7panEV!u0 z1)Sk<(p+v$057gtJ*dt-7;UWF;&P3|K%5SJ6K65l42eyyl{FE19Ut$Lq?c3AFwt>jQTgBG< zo|g0fhR+8LZD4rbOd&MZ@hN8$a{iwL74M=eo0KTLd6Ta%MdNL4yk*@h$os?lW3go3 ztQ%gfxdwUXThHwq{OkhcJ2xn1*b#t>*o%P@$UADIA>fB!kY>3eF%V)G3Z%SK{NL%K zKfQHxg2lhLUl@oXaYDxInJq8Td23m91N<}k<6VW+ft6p#TDR;oJK+P;uC*iyS!~|? z`GG!#qSnOfZ2|h{4Y2qBnMgWwxrWaepLYjsb+`?(1dSHY-`*0Z;$0XO*FfQIx02X^B2;?m<_qfKK)fMcjAJ%8yLjXth$D7VV-akM4-nD>t zZ*$cS=&gsmZDQ2x6SdKK-@W%z&ft?UutehS>2a?<_zIo(wj9v_LLdF{u14zEijkkY z4nF(0x&YW^7+i5|DK_t{!b`8c11-S9OP)9G#x`LtPR<=!pfl%h#PIL`H=U%dj;YjD zgVulF{}-d;U0{BTmBL%R*K#o$Zxt3zYD`G*ng-v7=2l+qI0kZY0q%xvB4gc_#AA+nY(}`UswNOHz$B?s}#)oU=K>U9_BbuLIUNH zx6he=4goPY6VIQKN`IGFN*&D@`Hk3L zQvUUvAFThwF>xagd;VA6)m5O;X98+UMunO`VE3RJ)|+~Lv1=H91^MuL6-{;6jw>p# zCd{uO<*0a%)8d)w=J3X_fKvys`Vit`}Iu8jskSvm%Do1GYW-4IufT5e)#LoP;}mW zR=vinGwF{vr49j%{CJr>CEO%%;9kC&;mga|ydCcZvK($R0mP=t@{W@(S* zyel$a?9Ilz05V^GeU<)rMdOha+&vZXRCV1>V!}Dg!4yUaS_rl?&f4jFd z74K4`^xKr~J*jEB9F6zS(&?Q?A@8+1uFT}Ux7QzkR;xhX`i)Hm@2g$F%1id^{2=eN z%&BXSA@9`9FNGdK-aG>9J^<}dph}!LStf*jd+WmW(i3`5g~1XeuC1A4+NlSiw5AkR3NhR6FbUU9N}(3=Geh zx|hK3|5;D5+2o-2pp<9Ed=K{ugFGbe9&c>^?GNZZ=!xx%xF|dN>p`cHI-Xn5GJpNO4FENj+N`K`?>?cT>eE2GFI|9bP#Qx%?sgAU?rIQ7J zkJwpE#rt~8t}eo#5pOkT>5PJ9`@BU0tir6#;n<->?7l>$nTpfAuZ5}LE7{h^*@R;A_S5*;=bYt09Qq!7e1Q)3D|Y5G zL8jh8cNm^`QCA>MbvQ3iZIO?ke?VG^ig#sN=1L0hThFt#(0HE_;?yjIyxT>}2xQ&` zVJm-mL*AucR#zMjxPS?zHnor22|&5@&C9Ql_nza|v*U|N;GFxEj{MqC;52gLyp$R` z?=Rw|mP(<*z#fS!ar7qETtnwwbMsI`)j|5>J&M%v03*LX@3%iv5AlPKLw^!>AH(K7 zNqA)&kmNwTST|x7IfcD~jC}Osda+S0!}Dh9q^*wlb+3w)%I4>PMJnFcywAR-@XlxV z)kNc6l(}_HE95c*1}c`sMJ|9T7LEpd3dN5$3!WU6_(Jb@13e1N?1JA&j_ z!n?P=t;aQ5mxlu4r|z2LqUgN)6IRKY#R`LJB(9>MV9S!r=)9k~eR;wkNq@WtkUCyq zmSPQxCQmT@q|AKrshDmz`f$;K7b?fN(xcYpv`9BzD3gY&vH1fL-c2mM6WJXm0BhYQjj>6!-Ti}KIqRN9a=4Sr$v$edXP9$M<7Oi zx9u#{zBLE|oAI?t8LHSlsO#q0p&~^OqA$*WQHB8tvj;Uje9w*Ny~OY9 z!wb#)huP#eNL8qK-?>*fMY+VL@-(eR<1MH!>o);;ioG5Zyg8oSNfao6-~Y>b;MNoz3j8fqhq43FFR?lWG1t8o3j<#y zF6r`-SGM=jSCHebdh!}_^v7Elsbdl&ztM7wfn@l2%hMa{5`zCXcqcoq+&>_WJ^vrp z&tvf)&trJrdPj0;s$;{^x{kWPPmnI7;(a^O_Y#Ho3`eRy8t>t(GI0U8f{cyk|3l_& z_eUdh5c1yhV1kdp9H#`o-9Wg~sT- zV?Oc4G;0fk?MPh6=G$&E#pt|48aekqSV4chPa$>SG4dM>nq_TX#1GC#n7YcW!tUOS z4;hB3$$1d)5Ig<`_6KP=gp+rLQ@^dsUF`)3g!nSWh&mc-1$5xybGS} zTZP7(^e&`T1M;>gx*B;F@)jY6eNZFM|NS;zYJ9g*xP+^FCRV9w`XukGDHgM+`=O zIG6fGWp@04(`V_rt(&oVdkiK<9&B|X4tk~wxqicbyhYzb>d_iE9K+B58^UO-V|mc% zsvXDXc`v2neN%_nM&W&7gPtB5?@6x(mn|UggO)N2$a`;JHpXu!ka@SawMP}W0QJP1 z&5=6@;Bo%qErO8uL~F%HJIGsLt@Vo;5DI?SD*1P7q4VDKeO&wGE@3c%#N{OAi1Pl+ z?JaEs$)`D%^v8QMQim=^eioZ~3p|VYft{8??j=iX-it1t{3g)iLaf*(d8RM30dwum zU=l?`b+Uoea%t!-1-tyo6Kb_D1f^Y z{Id3jXTR*gfsy>V0+Tu}BP=;nQ!cqZDuKj9))yXD9Ks%u&R*IPxbAjxHP(NZ-v2$J z-I}I4o-|wS`4c_AL8?y0n^^6VNxsCAc{l!Cybz6dN~6?Hd&pb7o@t!S+qzG{{sQEE zQ#o3_G|m+Sze^TgaGC(d>mRotfxP*Z-DkIClR!nZ!m(*BJn&=Rlv%d{o%da#1%f<6 z!oUZKd&YnFU8pcR?{cptW?T5_k2evi;|fN8%f4L1_i^HYyu?P1`#0pXond(1Og^;L!R^4@XIeSGf?Pqx`+mIH0SfPt(lJ&v-nE=6 zB_WV^>6e26DUf$ccFo!Z$eSrwpu+KlE7-c}a;G_g0HU{UXx|5Uvoa@re|V7uRuGbU zHnG6tEqB-0$4R0OJnF^fYc7chgDXf}sZ8bB!~gPm3!{plsw@He|qwLa|ATbVqw!~IO>7@s%S1)Az8*&f&0l`_v; zjf(d@hn{o_?>FuZENHyP{EW@hA@2c=&68x_t9sks`$68OhLHzs!d-!Dde0J;qXba7 zUgGpl$Xl{axx6O_ZjgqZ*uVNW9*Ei9@_E9C&ig>X@o^VPVIYjenF?yEdlAsPH(z$h zwh0mX;~jw1fy2np%XZ3HOI83FdM{`VWW^qk+CL5n`1$!0J(zp$ElF(`6bKraMn8EfE%}@v5f#WZ=*_% zzEubOiQA3#^7p=L#pKN-uJY-$s2tLhpGoP zy^}RCR&N9(_QP54Uyjo)iKnk+`MG>s7KBqW2*G zZzBsDCKQSE_Is{?)DeJ@U!l#OnZ;B5zD#gzO_)8X zO?yq`+Q`3;`sR$q&5}r#%tF7ZfsnwAO%(is)VIAQp>H8?HSRO19qA;X9#DI3qcFV0)^oWP ztD*Bg8xmKO^g{^D)cuV!NxNASJdS=zjtmj5iug`{yi<`nj$`DfF)`eE-w+43ti7g? z=ZekStXjdyy?88+Ozh;t?A|uQtE0w40seyA9w&Bm-i?(D4ygVS0)a@J)2;0}67SG?3%cf>@SmYS-Vc#F zgfa5FRd8~f$t*u`%emDV9g5BS>-)Q@w|f1F%A5NPZv1J)?B3%p8>^%4ir=NTtK0u> zK5q5vXsW~JiQjPHnfdOmNyWQvyIx!2zj4(lam#@|GW!7&{Gl zrwAXY$SZaQdbiJcJSimr`7O`X?nB-sw=Y<%%!Dr|GW%x*kA{NyM~bV5nb3K^Iksl( zBD*j+g~VBMxF{>VN9U~zcte#J(%=059;rhgBfr)&x~ZI|IACqOsXr$goAMNYBRS;$T#ff}AO?4D3Sfh0lKE3td z{{R2(_3{6QcsT#Brs_d$-H~~e9yBt(RsgLB=}aBzSYw2$VS%cJpm7lFhLdKG8exMz-rb+xWrxBKfUH2Y0 zE1ioV9xJqILA-SuORiQc(-1g-9+K7=^%hZ z<9%|`KC4xb_qw%9mc&EeZwzd|uZ6r9yR^(TwYq_H_je-JaQ+{WvHa-_c{}Dkcyl$0 z1UlqaXASp;0vD@4xBg6_KVoOq80`iozxi(O zxDP*XSyi>u2=bPxya=S<8(7ShdimH>sGa=A`#H}#9p?O9G zeFga;VJaE4(;x3Jqzd=s1W6M+xU%yh=gm zeX-M5-DyAwgd%aFXO6LSiJ|lE8Vpa_|C;`IQ|iFV@AbBOVY5N->n#$dFGuvTc}qpy zy5xJ_k61exdc#^9dqC3rwN=(|Y9+(Z|6j*xtK*qSo$}ga^A9KLQt^JsAL>u(-f46A zMQFT%AiH50(Of?d}*A@6OgZit(w zl7N);I;)@%JeV*y88ZHt?%i{1JeD2qy^SJq8MaJOZxzsa8!Sl^sG-BXx0gsASo!s? zaebM0haV6HE;;&|VDk>k+GOdQ=SQr@=?PXYXvVyI%e14pe;`1U;k$PvzLBOnx&|Vj zy{-Ch{>Pf(=;GhQ`5#dApyv-~Z%}&B>kZmsXgw&URG>XcxZEiB>|SRA>_PS7Z{63! z9(2DxTT?;E1H9kwj{llW04=47t>0k}(#(r$+7nFzBZA9h^^W5~cl75>mMrv3?Au4$ zmnDA+fes{&uj|5#?tke)*281R+NS9568jFRV+Tflc9o;mS5EMQ$=IoP?@nP4NOP$_ zF7b5x5v{mimpmQAp8t7Af4%cBVf-G{sZ3iPrh)uwi~fH9Z!Hz?XSu!Q6yD*ne4=Q) zvp0FXy$pGOXsPHT^X^*aXhP<#mb2GTqT3x5j=YOj%_0D|CBIAFK;B_Of$h05Bw%T} zL$cT(50>;TS34Ag&RgoHt=?L=gQS4ODT;ZPam%7#V)M%f$1ZTv-z|1&q>ciN{6a3P z?i+c`4{oY@9lm=On>VwMW%h|4KO&Dm=-+UfhWY=RiI2F29>ZT^nIbmQR>y~L+mREb z4XJoP^{|bi@V?*rOc;&#Z=QQ4&5-xS-Y)Z4$h$R5=ZOL2%~N@Q_YpYwXgn%?w5pf@ zwBApAXob8_diX4!Jw*auUb&wnCBwk!Ua4XWUG%%LHAlC4aYze;1SD?Vjd1+QW9Ymu zUK04&DNTR8?;&;MVC3hU{xQrYjUUV%sm&F+fz8`S*h1BG{QWR?&b?`zBK&cB1a9YR{`$h>URFhBmv+H;0VnO`>B8fAL8fmIS=(5>&j@bG6-++oYiFKV2g?CTS zK|wU$Z_HCtnBe@MH~P(hy!S@oE$%XH#lOZKh%dOiu?+IIS6*bA4SBzi-Ep`#js)VB zA60n6mlK13^YW+eLSLK^4?U{RyCnqtk+`z2yYDG~ME~nR7`FLfQbT`hZ%Q3l`LXY? zZ#n454;)hBo9}jF^L}!iCAjmaA2CGd)e-x?Cd~Oi(x3g|=TprL&pT3iAx(9Zzqs^Z zA$&RUzy1IJ7ro^FtN$yU|2I(epl)I_52Xj?e_keo)`OJx=k8>Om)L`@lX5Yz2aT(p zFu%7?%gE%Jk+=}|KF})jKK{2p0VoU*{6YlBh!r(gOSc>$fxT5XmL53;AF(Ss!Rk_t zzCj8yP7Rt$2mt~Tcjeu?>MQpD7kg(OPG#5j{~gyhPaBy^QKp1aLM2OuXh5itka>>G zLs3#TMM;t-5g9V8DA`F=)GjF@iKryalp*z7yY|()kN5apUHi|y-{XG%(f7X3<2lZ+ zKKHrSxz@VY!mdGKQBfXN^I5M3p*|vU^1JKSqc!`1FcAB!(l<{DzXmXMM9vg3;ivAS`wOJ2uGTnziPJa6eeI7)s zih!CuB7@0V_;}CSlpQj+E0Pl1Gtznb7!&>fr-|XrP;<7&n=r_v4}-9sT7UNcS25t- zZtu1N#ar;j?HO2jJM^u)u>#_4-?@e>0pbl(O74zAysxAb1MU`gz}a84I%x|T@D}yE zE`xY)y&je^Z!Z<7TOE2*^ECpD%c-39QNo@<7VS2beXb)8M(J^jQ%sSaXa9ls@hGaL zG3()7NcZ87lb>PHoCKMt!eH9$p@W^9@$oLPdCe875>6SjPTKjalZpO+VNozCyo3Gm zR$-GA=?Tgia;6Fn|#6mO@1b23Tuz|F6oQ z-hKt%(|70o+iU}GGVuAFqbLROR`DJlHQh%A&rMWr-+C7T)a9qERL;Q0+g%Bf99}C9 zROxXNKdwBvm4%J>My`){-)vz$yip(4IQiB1=6zDSDgxY1Fyv301_x}SZ%=vis2!NG;UT-mAz`JcSe*neX%gS9E3-3isu09Qd zc;}S`zN6t?-F?@Qb~tfm(*w#4xNLPsE4y)S0vWt2oe{ph2|}kJ+R0Fv(J^dtn1hRp7rql>jNi0M>C1#Z}dfg zwTUlq2*by_s{NI(NTeTSpSkT4!OkYk-wWEp#S-Lo+HLN#fB&x_$CQr>K1I&UCI9vR z=-)p}|AhU&DMJnFse0{%)*v4_c?GN*BxyHc94%gKuxq#H(|xc8jV5g%&Vw_^ukjUU z-QiBpr`BHYa|ANT%~rV~DE^V6$7v<~IhYC(qLstz2O`1fqU4}9N$eq0D`wU82?ufT zg&ybfIX^~29=ithJ(L+R4`96-w1ndWiQ=^%}2_9v4lM>(FVB@{w*wT%u0q}Z@pg(a(pO}92{|DYn zWV~Dt#IPRT`g9+9@t0py5!4iXUWm2F3S(jeYD#AU{kqT%JlQB9{x zDG|Ui?``?HQS8kLoxt8FPlUyRJw5K>t0*0(VC=cNLrcx|DS6hz8}+drC%?I2n*(>4 z3j;-+hfy)2_;}YWw)0au8Ab_Mv3uI-HvH-x>y?&nWZTL1coWVu=VNcfORZ_}>n%Rm z#Po9BAP9dE9uRI9z9W29_@eL`;lsjvg@c9Ng>8h_3hN1L2+IkJ3L`?_ga(DWgzgE| z36%+D3#AF|7YY~h7P1#I6IvvsAS5BgBRC;AEZ8IXQ1GT;m0+G=hG3##w4lGBlc1%b zp`f;)ilB_3fWS|IPXaFm9t$)HR0|XeoDxXptKd7&m(G{K7s=<#=fG#dw~9}TPl->8 zkB|2U?+4yq-bcK*crWwj^JelM)-^^dj zU&5copUS_FKa}5--;RGhzdrv${yF^O{9Jrvd_#QQd{n+0LI#`_oaZ^yITJV|Iej@D zI4w9=acXfYaY}LWas1%;z|qU`h~pN=WsZD~Opb#byEy_loH?vHj5%~UR5@mH2>nkd zJFVh>{`}vcSpPR5$jQYadDlrEA}XS4-GW+4q5`Vc@&w-{&PA0;+lzeS98|5zl~yClqsllm z^(|2jRYoh6e-US+%8)x(oj40stDc*g5@k`f^8C^i;!IQ-1e#EZGf)NAdHE4#P^B;K zl1!9FmEOxbNum_0mN&<$5hYQzY;RU5Q36#^SBT+dM?a-&MwcgArd7pj!>+TIX}s8SSq zvw?`9YHo+M29Xn0bBe~^5IImKzejBaaT==RjNA2z1XRtIsB=Spp-T2ObuID}RWo~^ zUqq%*HDgcmY~%;3WUP3Tkx5iZ%TrGx6R48>xbGA)jw%VtsWD^>RnrqTOCjG;CBAKW z8S)KPV)IW|A)}}wP3)3KMo=a4xbiFV6;;A#<8zQNs1ov)sYX7dN^p@}9P$ZO0>n!d z$VXK1brts^A5g`6!F4+F9#uTvd&H1oRB^B3uSMRWic4gMBQk_4WVp!!d5bE}!rU5U z5LFyubN3@}P&Lg|9zkBCiXb8Q8hJ%mia%e(E=2}VHC6p~BhrtmAA8EKA}>)jX+3U+ z^r31(?$~;y7ggiaWUe7EQ1!hwJ6#H8hMDSSG`C-@&Hu>)#C_4MOFV^LpS6;s$QB%UO?`l zs!z9z4{1Twi$V2Hq#0GT^>*Ygs%XoT$Q@MCR&$WssG>E$NE51Py#msRD%z<%!_j~#7AmTMLV~Q zTtgM@1|j4ss%RIkAT_9>-A{p3ql)%9KXL_Cw6C9$%c!E=LyTNP746zqqzYBETP~4G zRM9R4L@H24yF(2rM-}ZgBcu#fw8vkNQdH62%0Nm`MSEHRDMl6TCU)c^T`5I&YaJ%8 zM^!}Ctv=#9RE6(498Fw{s<3rA(}QRP3{&`(^2D!*Hcz7bcV$~S!=j%a`?9|yh~B0!b*;?{Jc zKB_z?U+*TaK$XXxmL{Ses@!u%bcoAQ zbx`G$+qi(JjVj0Bvd_dNsB+LtT29nL)i!AvPU2!zZGC0Cg187(b`@8`iJGXgjamJR zxDZt~&OKqo1*qCG_ZBBn167-b7m$eRsItCM^NOfOSBh8R3)e^ys%Q@aBZa7R9oK<9%^|u{isq$i z5I3OzE*()^fE+|s+9ORaBneeVPuET&iKt5T)|NoXs5%1n9zYUMbyz?y8aaTfaSkyupiPc8k1 z#GoqPBEJ;bjjDY!zZ^t%p=$5&%W)(cReSC?97Li}6`OFr1BpacjP<7dNCc{OYs@J@ z!ci4H=4^+Ap(^UmMlU23RgvkxbdV5KMR;U3BEhH%*ZI(n1feSQ*TWUaPE>_FU%-U~ zqAK{*9w#IKRY8F~<;V_H?OdkUjQIa|{-5=GJlgwzW(;ePv{?-XZOM-_V$x5N#EV!18E^Gl{Zktz=0L;{VmIlH7f37o*o|pZp z;5%`ba1Rm*5>$;huCu^iV&6uHKEiof4D6@JCGE-8sP({JgFM%_``n7QITTj=jiWwt zaPr$f6?#@E7+#Pzd%-hffBYRJy)QQNWC=Sc?p2TWYc(-(f^_gp{|B-+`|luCG3R4s z%WT)RRloQDH!$E$o2H|92b12bVBuYp`pQlOF0t=>T_PMu+aUFu*YgA7t>&KFTnIcs znbwhC!VL*P#dgHd1>!BSWwfJw2Ng5~xUAUr7(S5x%OzBCCN|zeJ$WkcYQ%sgJ?_D+ z0~<^%vGFc5ql~JwvmV~4k4l{U7Vm8EG}j>k>O|CxOZ)Kgo@-iHI%F3}**hw>xNH<3 z?|u9SO?fs9uszU_~qq zZ?SI0wke3WO|6v>=Qa-@tlqlt7&QSH^d1$qfOw0YEbQqGpn}8Yv6=Bj5g@wvRc!u8 z>>VTxE98Y^gBXaU$Hm{vG&!&m8}CJ-ts>4ntcN%1V+l@vUU$qZw)ltuo<#Fez9aZ} z=l>EuknI>q*)6p)^h$OU=EgBPn#EFHmYLhXWqZ71Z!+iO!jm$SU4PF1uVcWQwvdA2 z-81`;5*FV3AJ5}6hImK0#eb&Zy<;dPYz*S9=ocBf!J#dzr4UvGINx`=m6EDhBS+UfHr}=buhW`?tcN%1 zV;fF>yK>2D4J9HVOul-Rehxm~t4hx}5(h&lhx#JhMB5udYtW81p@mpA z$b04<1%KH88;_rIjDxlrzJN?EY7GXC?s>R3Zs)EJ-#$9sp3%mJ`8>d7bTh|X{u-*_mpYB5l zC%+}GJb|U~25FP(9V&=8ehn&kva(U3#hc}Xe-?mNo_hQ(o%uoo3-8?O{i0-ucYV0wBO2aW6LO)h5bskh*S~M#bO$miE=@}* z3E+%~EJ%fTCr3&DYJhlG-KyNa4_>jGpdlu;sudgWrW%X2Q!!$H@$p{S)nggo?L{fupF6dS$ixHbqW07a zm-n%KgG4A}&WE^mW+m;49az0LGT=?yy+-jC=_ypl!dsEzwB|g-J1jE@y-Xt>9T%Q(A+M^_r@*~ye~g(Vp@icH_2sOy2_#>)x7GdL*z0K|K-$rtV*hNxoB?mz`63i=outDQT}VdH(rdZxW|r5JFa$AzEES^DfC zHs0roZ3ywLtcN%1BO52bm!G9cBE}?eFUczBh9f@SJ8s?FqW;sLqUn(6T@{2sIZ-P~ zO-?!C$o6q!@^K}+2C9e(RU1#y%N ztA?@&ARTKeJRpQ!gWmt_=Xpk%+t;AjGtBvD zkv85RfAaSbyM+O7+L2)tZ;S6ww6O3V{brfW35QsCrdPZ_mNO$E+cxpwPABES}< z4N`vhu<_KqJpO&9mR|@y;Oxxt8VoQw()Unr?!(@$n8T*B#H>!uI?Bgh1we ze2UZf;9dQ@dRsH#P5Vj-#k;?Ixh59gt!fu}tRUVZU2BGEc<0RM9Df8?Z(Him>=a6J z0~HT^WbZU4fCHBlre{ICKfHU^*9Yf4VCY<~Xr+XeVa}xnBX-o8{@#FXZ3TIP1&%wR7N^0xR z!z-FFe=q3NUB!teeWRA(Mf%54BBV z`bWy;v!j7mU8vx0+v7_vW|1JzyFT=29d->emhsE@iHQA;iyE@>M)a_2P+#=rSx=X+ zUJY7H_wfQJzoV*`(i|_6z|N_N`fYyrL#*+mw|P!-?iAJf=>9#G_)F{}A*%5Q3!>P5 z2B~euoR1wRi5c;GfA1jKGvH18@E9Fplfv#V!@_&wMv><(i1$H4i$gTTd(t|$aRlOR z7b|XXK*klkPaQt-JcJD9zVs0gg?P`krmU25rGn2_KT5ZVM}oDMEvcttvGKM^{V~YJ zEA}^TQTB|IXY$y14+=l>_@K*rcyFcqc!iUng7Lb1$rmDE(`7-`=i&Hx>qLy22rY4^ zaQ(0`u&rcb2AQk5sYo)O?eUI{V$MfE%B85?XMWEhw=&>O`;s2TTV=tqrC4~2)!DAg zfOww|L0V~eTh>r@1Ym=tC-Gpv?E+WOk?T~y*bzREo_~H!5aRvK@r{Td#C!J~lYw;; z5kPxXVRNlBHr^3i3k5TU#K01I+=Z#vpE#tk@#Z%U8Vp&%dU)@m`{2gOkD8srkuL{7 zZ$UiuWm9FI_CWb;p$bDk0u7F*b&~Al`kl%|!|jZx71(35zwZK;3BhoJ2!1XmwBy z{0SQ*AySh=tQ!@WtRAXyfzMlHWOQqd+x!D>ZA+uV>F{tOJ+5)p;}yCyu<;I(5R7(S z&4PH-eeA%=&&)RCm5dt+DDXW$qLz-2cYC+CtG`GHWljG`zu)O5+y;r@WV!kIarXbb zg&@VG5A(2Z$NyY!Y0H2&?XD9PZ<`7&9W1HU~{|&<| zxv*-G8PB%CSEOPCMAEpeVRSkIUGqJ1otGU4uk-XM!nN)~iA4 zbRQx(`8Dk24|)(r0uOt(&F_BCWq|(mVEue&-@5OWT{y+u%C6d85x@W6Et*rgyEL5b zYmmZ7Hd8)&7in@0|M@_AI|JUd>&sBQ4~owvV&OfK=jHbk;@xC5v^o;veXQlev4s%t z(ib+Tkc}?jO)-D1MLRs+vUFTU6XL!0lgQ)N?NktY^Xw#e83FFEA^)h_f<45h$rn7K z4vPXRJ#Kp3RFLRDHb@8Ceq!sbQ)lFhfI%bPQ=FXmLu|o=P`{t1 z;gp3_9K?^Wn($|kEm7We9eddx@7SBn`KaZ37kB#42hvUqc+>9VL-CF{{*e<4@68rT zJrZyRS@1lih=zAaTSTxO#CwU!mSLV47qCjML;F-C8Axg`QImmqPZRL;*$h{2!-dzF zJiZeF<_5;Py@DI5Sk-C%B8%0jUqpcdJuZZw%1!Raju-H(NsdxtJ-jvPKKOC+yZrdJ z_^~%4;E|pCm2GqI@ebx+?ryE%MA@qGsHBJ+AMYw#i9o&+gKUp?q!DvIj7N-add2_l z{~a0drd=?J;ytQ!ivtVqvw`W!3n1R-Bu&I=n-icfC^iY=opJ4EU&3V<0OD_qzbGez zlIlGfk`Qk_Ckavt#QWLC3(MsjBY>jF!VwQGY+SwPzJ5A6E((lf#GHL5@w6=@gCz+?rfXuMA2FyXS3}p6CX%F5bAE9>MS$#9M5k;#I|@NMKN)-<13d8}B1$=IJ0@ zVt?aE>s1~)*|=j?`+LE+$9^UD6A1yffDOho|ejXA5uaNBONgI5;`&a0=$U8ew z;vNQgyXxT2y$L(W)(gc5?2orIb3VA{Kc8NZ```XQ*6fI-{yFUbJ^rT#DbenXMr%;w z$Ql8x8pQF~_?kCtkOZrho`k^~w1_((?3deOgWU_Zx~N`v2D9=`_#1VR!R{r_;~!xS zBB^NWp4mhNikqjuh^dGKTf|$0GF7l^ioe;Fy~^vv{>J@S$jh%_j~#EJoct(@JAPgpA%XKE0Z6wZ~mqjif+A=vqW|yW^G3Qf2xl>k<(YQ zWcwO4Qp}u>c^wh1%}0OFAl(`8rd@)L;=M{?CO;P5VN1o7;~?I5iL3O&A>OSo$XBD_ zCw7-~j#rvKat7(z&OYaQ$zWNFuPqhgeZQbtm$C&uvCA2BQ~zuvFfKg#OjZ;d*LPpT zUR7I&{f#R!Ypy-K1v|d~WlgbIJnP~8iSDBhC%^jlMS3%qi-OgM52?&JgpYTg_2`TZ z)-e>4c<7|CEE6-x(`u!;zqYVF-h^BxeY{t56aO=VbYsAqcB?;%w`Au4FBaZg+y$&p zLcGZ&pKKc51&)@G)hBAD-weHo)5KDGZb~oJVsG{KS{}b*$TX>z^#r}A=GUub!Y&zc+-`~~S^?&gG z{Y(XlcaKyB4;J42TlZvFLcE7oF5;zaP9!xh^&NtEx9EO-rNrj~xFiy0BcI72{`ka_ z6o@xjdc&oftyB;{EatGlJmF&0f{p8(b&^@R9%4Y79!HunQ?lwdcKpJpHVFF`A|9t&Te7vo>+^U)y!96plIA;5L3%=(x`S&ZaJD~?_2VUW{~ukQcVy_DC~&36J&GyV zC^`=tZ&Qww$t&it9^QNDKGxvmch2#b5ZP1|D84i;j(miV_q>AW(rYVYD94SwW+>fh z!kv2)45iA8t-i27-bzgRST(WpBs|{o-~E4R_r=0LVgK*@KQ%~+_VN^3gIv4yM6qg6 zPDRwJ5s_j80nY615IDpRJv_E9ahA)qc~c zk3yXM@)LQZ)ICX{@A~7OP7(YXG;%Qh#!7udij8`P*w^z+tU*>E$uQ~hXa5;w6LUW9 zt$X`!>Dk{ytPca;w5QZiyi;$9kg)K+$D#6+9}cl4_Du$%5buC(wF@&K-jX-_)Me#e zK;HA+V`{s|K*s3hq&CDmVAI)M_8X~SY*Ie+<=RMabHBIT&@=2I);R0n+8dRkpn)ED zbnD)i$b0N~Vv>X@U=MQM zv_Yj17TybPX;>_Wc;6d5z(?Dh_}SOd`xD~r^TJ!m<$*KU7VU73TuKH{tpz0&A>K!} zC116Jc)!`Wa(abqB(Su2mu{1fjjQtI6Y_@|M1d7OE-*>wlT$Btym}T7$&bK#4U#I| zhXzi5Csk&@C2EQSud#3rr>*#Sf4y~B<5f!(#l?cK_L1A>_a_dnqe7s}w)ixwQh@uR-PQR0O zwh6cYk9AnC&_H>^{{4Rvb3Qir9=NEV_TThzF6up_eTQQ)Awqh4y-{7@BehD zgbh-~i095nDv{vYv5Jkdcd&;{qofY!1D>LP;|gT!-Zx#rjt?65JSSc%&vO00G2KTn zPJVV{H|&>;h=Ad1#XB#Ni3b1Qzbl4+=%oSHue@gjj+HBNmGa>)u@esJ5tgoTW&auE z=yIlfoK3yAs{YRb=>P`2X%Diac-y&fNMhk_Xz-XX9pb$}%GoR!;+?{+0JtIE-FnBa znn<_;Z9@;+H-cmkWc@97ImDZXEdRh6;;q;bE#p9l1gGzBPKY>(jcaK5^j~?QqJQK1 zO2{#_7qH{kJ`wVsyvBNXhtYkk!^ux_U3z4PJ_$IVn_SYJg^zd4m(%J+t%j7Mw$sl! z4Dg58k${ktw{j2I9&h&(!A$vRB}A*M9{#<&wSxg~0pg_!6z{!H+oxmUU0+{cTMY3Y z&bFzb;jPuz{_8B9L2fEfd>--A1##3}#yG_FM|_-qk*s8V>QEYuYwGFcbl{ zAF1iI-iwVZhYjB2Y-e0zcD8*zq%ZGqecLSr2d2 z$4s33YFc%i-`kM@VUA|>_ilW=2f7!y1_f-Td`$GKCL{Q(w}hpcDss2}58VH^k~tq= z1OtTY3x8K{KL)&cFSt%e@h6TWnk}eHJ+`TqX+U(c^yH z^GW~kkIRW3nzjfJequemtLQ#jaq<)AiP4>-EefU?if`XFg^%~d(e&XKHQ zg;j&XgEflOEeVVQ_MFD?oZ2D3nehoS{Lq>Go%3w-BZC=lLCe|Pc4;$W|OtWYE8btWO zq>r*WPiSY5Al@Mic#F+HU4`Nun>INU3vWBad0KNJ-a-@id}w%!X1i^g3-R9W{OpBc zu^X7Lm3WdekpR~0P2FY-@kYWFVj|3`;38+|(&hKz^OmhEY7d2A<64j{RogEs3exFu zL$Z4)!+zND4}LA(@WzYv@GhkLz{@Y+HKH$SGYQmPS-bn%Jbb)GxipoCQSOwZ9b+rj zJ;&cc(vwt|;sJeZk2hJ7IUk6G-)H2{^%lVlc#|e}$)k854!Ju63-9}%bw-y$yiY$+ zY@y-pKIhs41mfNMVsZUhOE*xPeY^1Kw*(O6-DyYRuG*J*gNfH$Vh@x$t?GEi_IMK#nDZfkob-)9_q#y~V!&JEaphMO zZzY$LGFW(@)NDFy0r7sJpsGsSoCrv$4{L|3x68-opCJsof|4BT2Wh4rE>2VW%0iIDF*ztDj+$An0vmV~4 z4_lo4E-lcZw)BbsyD0DMW#;&Ji>cVonI&&YIdH(LoX@WjbJB*+iIa=g%xEI5X8ZmB zx{J*Dc!I2XsgwL0@0|>I3!jb8LGiwku|paQZwjaRRu71`C7}sz3^n35^-jB2^5btv{=KRQQhyZJw&&_H4M>RfH*i%)%RTP-g z*1YF_kovR>#;`Uk|sQR+dee>%n2Xwvdgk_zmhB|3S5a? zR;^6D-V)wn;&i8t{rCSzpEBp;a$f`O^_Ktof3(1{@K4wvMKRPM87tmov<7MPC@Nsp zAk#-HH=YqLHnDvnu@Sw-(UAt-_X^I`M5uNm8-6GbjLHFrC zG;#9#&J)}paEk<BY}akWlDBM_;~lHf2?Tbh@@<^x!So&mx<3? zG}aGO@3Q~>e*`9d>^wGS((=y^QUn9uk{|b-Lh(MBUI*{GAQ1ev2N3w+Pv`AHZjQcQ z{yy-}G0A&c?n1n;b(N0L@Rl_g;4^`ER}}GF(0}d@Lf5xU4;Cc@YWU^@S0Ubr&2;Ka zQz|$+Fx1BfB0+gT<(lU2*wy%$pb9beGYM4E<085B7AL1-$5%^v#<#CzJ-pNDKCa^A zx9Z81+(L6vuv52Ml;b`=-XHseIb}S8DV?Vyh60&*z2(l4jwz$L<80smi>ET@4kV}N()*BLc9~cglU*UyhnY+C^^U6fmmtx z;V3>bcpkWukOT3iJeen7u$BrklH>{-=SPCp=)pIq{&AkaF65=had_PW8dqGn=4M$k zHr}}<8B>?dSPyRs-A5iyex=f4ANUWFz>7lvWrw@)@qQSv_0_0*FlFWu=MQ%)m^hpm zeqi$Xqi<}FcWfwgK8#;od}IqRNP~0lFb2G*Cv28N@y>f?HyaCY?kO?(ZxHYOa>P;^ z-Z^bqj;kTwms&cHS{b+l1zTe0CjuD+9$Rxi3F7T~dZ1TxJrxkzCvM%;iv;F7;>#L7 zVB;#;;nis%Ec!PNnA!2?oWYJy5?rn=zK!+pmZJMOh?Ad;HGfxa2ML(y*EuSD#K)U7 zZHw~;!(fUY*k!M7jE{Gc)O&K6p9S0F9XFRb9~(EHiy4Xk@BBYr562S!K7MN=fuRP; z8Mo`BHApH*LKUk9xrMoTErd0QpXwjv4{OlFT;+E!;2NY~#M<$Jw;o_%IPiF;HyK>& z^>?tB{7C6`7g*t}5APsNSvROA9R;}F?jxS>!fudcuPfh8kr4&F^tgPT2kwGn*fmJ? zqQO#0f7Yu(GwD9maPrd}-BNuVeh|LLXjPP(0DcWRl~Yv%n(ZmGnuZc(!trZRm#=7o z;F?CZuR+6^%=tLl@VRT?&jV>O40z9$sB=T{cC~t=f`#{sG)YZkh<6>250!?u`Heu| zG1?AN*X;Xi?s@@yyL7I8v zi6gyoq9B$Yr`L7jdU%`BeE^*N>bk~HZ=4hboj;yw?U{v-cbVdv zo32moDIbpqwpI2w;qD+2#6R^;$lqssya}RA`sk<%X#R7&Wj6!fvahLYQM`EvE0nSD zHhy3{uodF1xJqW;4v6>E){WOh;SBQY#KqD51symAdDXO(frMe1^;;7;-J^grzWwihqoHtM>0-+ zM|7qIR4x+*LlZ}`^YrlXHeN;uT~{AK(cSPxRbvzW@|H@FS!#cd5!-K&Chla;N8+zD z^0}{nUvIIC0q>c;&o82QrzqzuVc~so9nUU*h_?{mk5C%ki5id77eKs)ZkvUijqv~< z#<}ly&n1IGznzNs9=1q^jq<1k>JGLt#zL$ z*prP#P7cyu&q&}jJ#Mq*uCQ81?0CL)Wz&vpupZv14?&##)a@#H&%n)z?Y?crqn`M9 z_l%9U+_l?HS*ci)Cd`9BIZ-jc+dA*iYqrN*U?p=tYC|e=p6&au|Hm3WSn8j{{-4ND zgOv2z-k>#T{x5-rST*Q?h1|IYp<;s{vQ_!MaEN`@TKH}){KU>mq+?d@Voy+b*+u+r zH+(@_&Z|EH)}UYGWpkwTs9>l!PSfy3B;c$6Wk0I~d&n$Zdftxr6$uE?7^MwQg=yCkZHhT*fVGprwhx%p3*0LVnsE@}u`Ed)r9os)0Ua`C3M&8x4 z_;|OtsNC6h%7gOm`t&6gx%fjY!F|2nH`o6I*IT|`$CQuD7jy_#7ic?3iJT00&+V|* zK=D4hF<%`E?{d=^pN|ml9lE=mX?P#yjp&ep%Uklw7jHYw^#oEc9S>C%lEJFf&79s4 zZ(iN{`z9->VEKZTpRH>m0ddUuXml(#-fpUC@vjJ?fSVq7qjKHZ_2t-jU%30~W&9S_ z!`qeaBOfO}y-OPjXSa)jTJq~h$TfVtcT}#E6!@u2(bhz2ozFL7Hk#-tuvYBMr!N^T zY+t?QLQXT~!yr()dPm}Kyg3-~o>MgTcXHxWx=RfU??ZjRP7q;(6O^LfH<8cV){BTW*N=nfi)Zn_45mp@MVXt?--x`s@GS zKcgIUC!I;6AekQL;_i1Nr4bwNh6e_6h3>3}cO>0MBTjy)$i8#o@G@r7iAjf!W_-M> z^cN-kT(Oj*_^xrlR)LAvTduw@RF!RJ`v!@Cd|=MU(Xe{O-`86tPGi7ZevjG;w0d`r zn9s+;+beH#hYZBqG-RtZZFAz9L|O73h_`=v#n%*0Pk_AKx$ICB8N{^SH1LFYKl8HE zO@Vmd*`RlT%P0!WkFcm|9->>UBG_v5wiTZRO z<2d=PoqSS6^%n)A^Gqy0Dm*PpWh6nh2Z-j95EIC@+PWpAZ#8Y>&& zFu?P1U*yUjsnubW!s-+4_RE>5K_84?Da8e{e+_!ToR8W(FRF9S?-?X71Kz5?dTdd= zjV0Q&u<*W|^z@xS#M`zddX*2vd(DNHA2lG}Bl`!sOdolG*RqLZccDZ;d9>625yV^L zMcaD=Z7RrlC>boMyaOLfXVUO)zocdno7x61V#MHKI=dXbB;@D|LAjm>~~ zcSPoYqT#(PszY!DUXXSxKKhrJxF@)HxI(d-D-lF+&s8`B@!sSfGV9z@DtO|audZ=8BK^gaP->`n*6&!kk_s#0UTWzw-erP6)NSvHkIuy2Z@-h+V$eZQ8Ei)tid} zZ)M*Z$5Fh?9rQG@@ZQ<}d8ioT-Q!cRp0@XPjnfs-p0}tqj#g`2<_RoJ)MVm5kwKcZ znbskQw}8S;p1aGaAT&H<`%m5|@Ga|j`>KB&Z_$V^b)42s0%P>JfRmr|67OK+oxP2# zWpar;%gwz}A2~Sr-AOz5k}M<&c3ax_bOht$9jqKuRGSk>`Dyr}=SDsL-W%c0L{s9^ z_w2vCwTd|(PQ!J5DS zv4Q*8S$!{9gCcS$gHdn>8TV{U{9+Cd@GbSyvolhOV5&MZWUbUkikv}3X@Uk7kOO6A z^CpLbojqcc$D*-kgoiaGeAnI(0b%qwY6#DhA2QhSviIdv52&)<5R3Z2%g^1SbM&hi z3CQ0#JipeA!vK$&=EeKpE2lY8th=_h-CK`8gH(7}lo+WqNGIK;c3w9MX7-UEyXev+w{ zOa#s4j=NVvyu)mkHq2N+1(z$+zn}082dlf=8((b3#&yjt_q;Ny2r#9`9pB#^`&t+~ zUi1Cc19x>;4{y{5UVcB-+m>;_8>DC3u3aLq9Ut$M^A{?Rvrd#g(Qkv(GnlwyN20Q> zqh=G^<4sUy(uc|C?W%uvkOUdGg>Ks*XBr~ z4+-R+FdGxg!^hijxl%}oU?Ao2(IdgZQTUUSn>YH^2ut+YzW?9cz?_e&dk4LWkNn1) zp8;=mSAl#KZ!Sq~9W1<&dh>E4i1+NHBgbfX-#>TfpfSWdIBL&@;A{`jsW~o$h$n(a z71ww3LA*%@?}#~zsNlZ!qr)!m!@ne-9!_QSmY?*AjO#s6UcFV0Ydbmum3qWynwiVYW54O*P(v>+Mw|9*$BANGJX z$ZyfFD=%RUS{-#a>tdZd;9H@h*1($xRuh(u#laesXuk}m!# z@w`6G0FRxJ=<<<*{*4s9@D;9!-|=UV1p9Z>vNkxf{|u5zAE#=%pAn*e53ynlcxz8- zH==l}olqiT;a#-jyHPg8+imBLS2Vnx&QJ@ULcEtW@3`04LJ=_# z?`&dC!TkADP~LRvjo6QHu-_tw#Qy^uSCY8a;L`vRK&Hoir-e5hv zQ6G5u*&pq++dnD-UY6eITiAts{^%@xC_R;@$}Ho~#PafA_#0 zNHGq+g_#9LQlcPb6< z8|~%i^C8}?(N5v#;H5*E!fP7*VS^Mg|8c(u#QRGU$5g%=yx!tUHP7DqaB!?|BFzdgFGPA|R6U&-z3keR~ z$w?syv|D({kJ4PVuO#*re*a%ruhn|?=nA&)|7))^=i|2Msx~9?@9HhWfcN5U8A>SL zX~>~zSa`Qu6wc^{c=za;4$<(gy{BzL+k3l5&G_K)#vPa^pLTMQP6Rq0^Afi}yk}HA zFDzH5f>z43o&(L{0O^VKm{Es~>-T+I54Bf_06uzL{5j8*OIq0R4|DVutIT3OyuZQ=;NO5Om$d;f{S#<-Czw;x@#Sp z4zJjm*rM@u3+(^fN`=H_rpVw&-Iuc`U=2dvS*}Q&M+G-O^mp9Si2x3f`oo6i*!};V z3h8eLM}&bRJI_LAIx%pj#gCniH*&SJSC7WE;HlV7u@UH8LHBA~pg=`{B|{28QP z*vr+qMHUnl%j8*K+nH#P>?hMr<=OuYQi2t8K4z?S00MtbkV-M&t@pA{5*=b6O-$#< z!uv^~`zZs6x4MF>sXN3wVx8Xg%@FTSs}qMsue$@=kr)yFU+{_DO54J8i1*$p(ZCvr zx73O&ob!kgV2q!KvPTjd@4;tUH46kpzyv)mbKT{_GHL7~cIfl+bOd3&1_|}?1}DF` zJ@YosKLMBXn#TuM7~)EsS?;49I$4nvKW*3bVKJAJC)$ii1;tyh1 zZ__OQ2UAN#z*Tx&vYe=QfG0NIkt=wj6D(N|Z`4OPPJTMs4LUyOMSw$rO7@;ae7sG% zd8*oMwotsEb>|HBF>ydzztCUH$dc{*e*$36M`3SS*!-;D)q6Sv-b<~gR8hP|@9*cv z!u#v{KX4?-O|-l3 zaGQB&NiYdamv|Kay#OC?byX3WeGfKLQXSVQ6wSxKz4g36fibvl$@bMdT#z{*1%PzX z-8b#O_y1Uvlj+^^f=Wyy0b#QW7nX&e${URty!=CFQofu#L4g4jOEKV=8!-{4M}}r9>L(> ze`y55;p4Al@{N5dyfr14H@?FE#Ex)=*X)E_INR4C!dd2g%nYPeR0|p@8S<*2LG`wrZ7I=Swc-yr-am_OH06~#%vc7PLy_qDju>j(I z;2pnMxC#{*?>en4b2}1P)T>7P7ZC~rI^Kt+i@4{ob{)29; zhxZe@j|({Y&A7T>CeT|H?0su`DCj;u-aZZ!a$RJ5O61+Tb!&Is!~8v>|CuP}jTgJd zu>S|r8*`cS;aha?b>@NJUy#mZzf)t{z6cFgtwfhX5o5knF|r&UPxd5HI+4^ydkAl^Rik9p#TNODA;%!l8E+Ph3Z@0SZJt#_v z0P>AtbM60eT_tgm?V{3rVK9dtm;F%pgpe6F-bx!!n{GJCdU$iveaywlPwAeB{a8N< zaO^KGwSJ3__u#hRZ_Df&r60q)RO`f4|<6D8qm^ zSm))3;;nT%S`Z8G^DfqzG7#^doYDm}ylv&Rg>TdFe(G-&MR5mv7v86OO_IUNX7Zy` z5bvtNzJbjUZ?}+G-zNtmz|zZ|`bN3f)mz6zXu3d~Fjz*9Lv)H-_x$7Qt-ylGIH?BK z!yEPCkCPwYXp!ZZJPACJ7%R$VPo5r7^u!oWtX2JLWyuZETeis4mi^?Za z)v+6-MJu{@#hM%;L5k@s&cgq+#F1{J>^X39ssZ)|%>%I_KE90t5i z+Ftzr#Ey2nrDcFe5({s|Ej{_k5btC?VLKY$LYnKZ+d;hD_W4iE%kTjFm!hh7!_QlG zJm0@z7Q~xcc~$$392FF(4MphPf-^|q*rCmVjd$^f(wK@5LSQaE?$m;;lfM5r|L-`w zGULk!*26oW?!yizznonj!OdADaBWDb!;lAm2Kk1w_pxALH09HQ`1zZAnfS!c|H`UY z{Jw0DH$j(49}g_w(ho?>GvK`@SNiY%|9hp5=~#H{>BWPy5bsD(dX|RwGSz4fe~5RE z;MO zFAQwxaqlwr=!+#{SMO~Gr#!UzSZ@Ytiu%CGPuTLNN{Isr+z;4x{H_i@-jjCkQm3-R zDE3R=7Q8mV@BayAFC=rc{|`KnuE3m+9h1BGi$DCX-f|3h8;7R8MJFddz30WT@Ltb< zd3PDa+W{dB((qm+X5X?G;+=NXvWzp)12iq(y)TMC5o~YT?%4l95NM387f2OC^BtPLP|1I#>|qbjL9sdq>>_~hzu!1h&qap9F>ZQ zlA)wBlq8DZKA!uu&RW0s{oLoj?>V3KeE#vgTi05j>(Z-h?`z-FRc`S8kJW;{DK_uN zn-xyn*x-*JxyUB}D5wc@b8@TDc>IB|8O>k+-yTR=9d|wB1jqjQyoE3s@9mlr3nbqB z4-WI9@y{d3S@8Q?+U4)F7@&OeXNJ6Pzn=Q~~MZETjY;XW|NTE)3WasF zok=5ZPB`G;%Se}p;}B)jVRmMSh5z~A|54j-0M7rCWIf1untp`TgK}?5uR-fU*OT__ zlY%{ny&QMT5%wVQH{us#;5|rDE?i4LSGWOIo;enchD6}@lGC&t4oLK6l4&vg?O;WX zq0NQd5I~n@-u&w)`Wa;H@r$CH**O2kb+vjs=gc{yE+rL~I|5<_sBb{3M(QZR$giU; zY;V#m7f7gaS#H}sk6I^*&%JS-Mo)r0e){74)qqdfJ!p^A;WH*LjcI;B+AtqTQ5|<| zs%lPWFYX{E$awE==5i(R{@Fb*gvQ(GnUjm=KuVAe!lIytm1UJft%VLUw1m}yo=Z9rdEg^#>?(6^8Qpw!41-n_X;MRrTy#wxK_&QU}zaLRmxfH-s{PD8`*C& zCGlq8e10VwZ~08&a9hY*Xs=`pk+-GEy`DM9Tce=(tIG{H(DF6;ko>nq(4YM$ECTZW zbj;BC(aLs^&QQooFAxf3U9S4aI-~Qhsa*9VF@+PzA#rMa>!Nl3<@T0z^+*w&v((4C z5~(8h-jMhHjq*>3yvGY{_Nl=6U&jAi zS>-i15Ss0^@h7}FQKv_!!5;F~XW+khQ>YzyvZb8KTpJ4XHafIMdZF{?EPN=R*~kfY zAaSGpGycZ=(YyD4(2&2sh5C52B6V0{%HfHwX)ldh1t<&3pC;R~da`Qa1Cw|cW^Zy4at7Ce*pJV4AgipOir#~Q8@9>h(NSLy z`ij)ykCESs&GuCX2f2WU`{uKQPyb-{l<0~l1*s?0@uT0`{-}SzUSe@;SX+X+Y5yK1 z+-Az^5ZSVM`st;`9i$8yZ?pQEVG{2Gvmat;yd~ReJx3t#8jb86B5xZO10e>ugA5<) z+WBbG4P4Z_pf!Ij5%{YWwe>;X$>DeJ^+Mk882Rkb!0nWd1 z8rOC4o&R!yl%>pt;m`)^>L{GA&nb^z+(Al{@ix8a)I{Qa`{iR%G~P{t`?+Tz zZ)J}+14Q1=^F{~dA#b-X;XQ}D+`yZG@SGpTi9oG-A+rPW9*EG2JhdD?-V(Ut(9X(G zV7)?G!xNU9kZc6-lRJ6F!HM{-S(<^oD0+& zxiefdyURLae=&NcK0T&h94(BWi{kfRFw!^y;o>A zL*CaVU7K}Rz#F8$sAt`L918fGqK{jwLFawIsotUN80X(OfyjLq7_-rNUoPI)DSCqX zcsn6=WMJgSUC6m~PLmtlI>0Vm6M)TIZuD%dbf7&xR{-yMd_DGnBv2(NtauA2)N( zjqf|Tz|oM~Q%0%3F?-4{8O~bgZZG`ysJtKD-4x9KLOPA@F%C38AmLajt7G)C2Tx4V z;u5P!#@nW>DwxE(-R!d@8gI@Ibv~Jpw`6bfej;zqLDLUBkoPZHML)qVcMyBVOM*2# z5iI3&ujGfk!(RjsDs#63i+TP8mvZ=s-La8y11WUglT4!9*kalL#$9ONG8T+S=l#Ab z@5!Bf>f`+bsiO}gze>yLpjaMm(3LBg%G-*~n|^I){K67nywI%Gp#=f#`9C~Sw9+cE zo91~p`BGNLY<~8=a}kU4zXBO=>tniq?;zFTtdv0G-SMzrqzLlfn_Y65$h*GOsA~?M z-hLBq&i!=V9lV{`omw1~2;L2_q%cC>=QC}V+w-)82Kl+qr70mGPLd(6Y99Ue7QO-L z?e4eO|Hj!k6p4wHqx0^ITyFR1IrZ@tK~6Whu=1Z&D-db{JYq1 zhwu|x2A#1KyuB6YWnLtp`G4U1f8LbUk@;v#3G=zd?k!Ko+sf%}5UG0;^b*CRO99@y6LG#!DIVr5euKASHlgvfl za%8+M*EatB_SWoM%k^lygNrpLA4A?hd(MjyPjBC8<|Woc-uW9pr?akd2exCQ@;&Dg z!P}&}W}}ezG6{PRet2=B7vGjyVIB(Da<8%K9Jo!NIQ`uxvQ zJj;*op}zT_2dRS|Bfs zhdpR*;*{)5I3OK(wq*H5Zx7&=dHbMfY9jFJdy`fKcaWhcxrCFM+kuB?3GQM{C|KIG zy@iDp{fK=oe*0KbZr!Z?@oBNt0^xxs1pBluB#B6_uVhP13qm5_)l^|x5g-#|6iWlwl?nj z6Po9}qJXkG+S&$7PRA_H|C`8o+Xvp7B=H_@E09Iw9e@4+i#_DMcFNb0$a{-wcvcAH zU7X!{>g84s(7h_;_P&Tj@SybP+ar*-m-^3Jj7!_Ws`H+`V%tN3@b|?2Ef3InrxAp| z>78N+B1qg=p}T`UJvwhyU$I>IJJiSf98!l8Mt-|CYrM^a^FNOJ$h=htHgBz@Uk=-t>^ z1UMiKglawA*^bVe$C2fH#zS^6h{P3sZOAbHm(9sNukO*|57ftdIZ{UzMt)zjYEG{? z!vz*X{8Y!-v5&VLx=IEbltb}ZJarxA6WH_rSzG4j+@2bmACTBqQdUQ?i%)<}+T#4L zM87{fJpQS^y978+SEhCj?~Bd zE>g!MjQo0UTnUIvh1cFzN?q_##O8fQQYK-aTqwThG4JctGzzZ&_oPc*I`x$1dE=5O ztRt&sK>EMy|7d%E>iTmy|7(!-Ah(t$O{68Z@;z=dS`QNZCA4*xtwcLzuA*)qTw+1c zlhZkHiIwu5m(^GE00nbmS1vqG1cBFedl*-Z;|p)8b;Z!ZH%Nt+R0o|40e5u1wS_97 zFR{7oS1+qfuz_kME}N^*Y}Y>Y9`wTS>r!6nm3Zp<<>GMpNF7-Dc~pi}B){hZYGxDq z!^X3ygCnWF4Uq>WWZ7--4hrR58CNOTK{m+NHf%aT^8*r&!a5G!@)W6q&mckG>SVlK zuT80tcsrkZu8hX}%jYKxEO3df3>Taw@^&-YzONGUuDIxDFJtHd<_qv_3=a~)iKk{u z|G*_S!%Q?-h`t?6h4~*};}rtr8f-QuFrf1m4p-Fh;#dk4k+`usYqRiO=)Auk7aVuh zqdwlENF7-Dok`oQS-6H91m3vbP8W^M`}n22`C|A5X-;*qK$RTq9i)>->he4H+G(Em zs5@nKoK4H<2}oY#twzS%CG12iiT5+V5+yX=>-XGQ;D@|Fc%`ZmPj8>gnr?amdEd+G zytHYb2Pmw2{ge~lLAo!ae%~nMy;E}Zt@V<2U~iH+lwlSE#5RR8HUG;FvQJ&ZvtDK? zSc}B9o|r$f(*T{fy83&e250Ky-H+6vhLK`93oO}?^ zH#!mgV+{p6$gUyV8qJq9&l^W+9kDNZh+mL~-Fpie?*qC$;UwNqPK0elQASt1U3 z&s?cJOys@XronLt@-`X{TV3ww0hqRKyRfGy5lrNHj=YAvn|enSV;R~(k8$t5!tWs< zr10k^#YFV(&2*sWhlI&e5QfCmY|DVl?Dj9EQ zmg^}b-e-1cDx&fJ9bETV8S>V5KX#kQn;}<~V;u6n@>p$q`%$>}zIbN4@cBf*@1f?< z1bIK-dyt`pu^r_8!RNod6$<7DXFHVD(XYKdATWMvU&Rh^L;u9RW7~87#9H*z+o7|8 z{6+@UH~&9E>UfWlU(=IFc@_9_;<+nPSw)+$PjBmfpN!0g*WL=+&oSlLV)MS9BdPO5 zWh>2hZ{8b})xmkRD9P{Gf6xDuW;Lq*376QdWIgC$$E)P_!w_7WN>GMn%1Aum_!y$lrG$&mF8PG8a`6P68YIc=RRV{4cq1#GYw^0PdX< z6!{5Xv70MXh0FHgY4jy_#O5%8Ge(f==Kmz54y^nf zw}zsveA?EedM{#RD|?rtq$itp0kSN_fX1T#L+rLESP;Wf?oAYXUN>ZmVQ zrF#*(c!5-#jJJ3CPz-5_U0@}sq48!HNj826d20yVe@W!cv1CFt7xGR}O9AG1chIu? z3$q|s5)j9;H3>uBh98;DFGJpZ5^q+2U=9W0d@d)J!cXy{{nPgx{GbwO&juoqxa!)e zrj?=Sye*cg7N=gNKHdkBIe zXV7^w(8t9zN3nq&NSuJDgq*k^I`489oXF>g)W@3{siOiTKZA#E!wDtaU_xSzs&yMS z@4dCn9?x?%@#7s8Dfhgwzur2(yiMuC3oDu*kn{y9tAm$w$GM=m#qO;|#@kcrc{+)= zp__{;8t(_^PCV{|yt8H^^@zM9ZGLfOLEhUQubObD^8gcb+3%l!N(Ae+wwG~1-sXHx z5>=3Qd!FrZ+w&0cyJFbkU@$swvp}|rLxpSrSNTtzotfnGUT<{XOjDe;PM@fcw-r(c zR(_l%$Md8PmAVe@9#Rv>oZi6(xAsc!eu1_~ZdOd9)6XGi<^O%ZVK{onil(YF6o^yhH?*CXpe0T1UFzaT}N{{;=~n9zC< z|C2(TFYG~SI&u*z%xKQIf!AP6Aj3HcEL4XC1i~J~|Mdgi;4cEu z{7eW5vWD;fXZT?&uoAro1w2*X>3ob8Fd}h0N=qbMzd4}}RE{;AIWg@5cq;nME~es- z)Zv7YU$6Y_ispCl{ePnmj2*Vkpw>yM&uRH!iOgC%yqxdGK-uRFnDMxSYag)i{U7)S zNjQadM0n32A4uCy#@qi)Z6R@qCGxJHlw(BW-SP`(brkY`d$y;N$ouRZS1a-T|LX1i zdn1>-1CA>rCc{=qK)68TiU;J)!DDtadzJw7c7LKzd=dh-CFpnPB%||QVg8{vFP9Y< zAaPa8QvdARgucWw&bGhpnxsD7q&k=|@{`{9RU|iy3ls(^$a7r6=1uQZGRD980DkY_ zi^>O_*hlPtPb^+?|)C1FV6ql$awo%dP$LZE8ZJlg2ww;$)AnM zkhkW1{y34h%;Zk5e8~G%8+X}B6?c$PpS?Z6CZX2r`xc3>#X5-`|Ra|Z+PKZd`7zovwLT3G4@dn@1c3#+J`8s!{g=2H~Y^n^42Be z?JIeD@dfF`?p?syNRP%l>eS@63y^nq-Tn>4(_0;g+*%yh(Lz#K`acb=K`dV_ZO1Nyq5wR_x;~tK{iq z%VZb4;En3Xe;Bb(Z*jXn9B{a3OY_|ux0kXyMA{lsiwpj{{!g0KsQM@DK|9HMP)J4N zdr}W7mfXpX)`Nm?FK<LgkxE35_plK zT3QEtkWK76nKeHMpk=nSEV(xXR976I<0(U5V$}~GD*E)81=JyN^i!+ct$EOU&=&)N z`P*XDHy~|6>KMn!j}eG<`aR+Hg#yj|E>f#-w#2w_er-Dn-csJf(kkN#^>+c&B5_!L0 z)1AK@F0r-ch01$;+<^8}L$E+(5~wIslPo3je&SwCH%$Qjc0uQvZifKvJr|RBqS1Mm zGwiGL8Ds(5kvPE{9mlKa(Rn{Id9y!Vjrw?(A$7E1n#k(cn9sgMn~%2<@z63(RiyA zy*pt5c?U4`^bvWd{5qY!1@iXW!6#Lj;s%zj%qy!4O#+{t4fAs#?{9kx6^0@25u4F1 z=MqBz{gT;1B@1-k(+RhqA7W$$Oi0{NmTrmd5A@U93qPuwYHX;F_Yb6wER6iJ6;F>p z5QU$&I1>IzwHKSWOVE{w^k{FqTE&(!-d^l0NR8_F`)jK{(>!k-QOfFY-!8rS&OfiW z&?n=4MBtk*iT7FON)|NU`Da4uEFkaQla1WO<1PP|UGBv9|8o~z=B;;H@W%B(Z~U=xZd2A{6m;(xy*D$l zBQ(!D(ucA-e02w|P5$$7q8((s1IItX|Mkzs2~UUP%xJv(*9g@-2SyjQ5t z==IpKf?6alHB?XY8zcJW#OUPuo`zED<4vk#7e;>a&2_JfuW$hlThZ?`!q~@KV*Y*{ z-K*{J>kcrrJUobfyrnFmt55&Eo93VY=iEeD9i8gi_wP9M-~3P2b3Z9LIREb<>p{n^ z<9J9t=;=wogVuv;R?1dSv6g5zWIRAeX_#XZfF0mJk614VC5Q=G4ESecphwI^J3_sy@zL z?B2V`c!#sL%aM5VS>|)1@eYYq$>oQ(pCj<;qyV z1|-g{H}L1N4d}dwS6ph0Vy8adcab_qF!JMgE4}@bKR1vX;J5r>iOt*Imj8743O9Te zD`T;0Su^Hd9cRAW6R=IuJnzWel-032dE%`PJl^{6{(sVtO~pUq{BKUygW@g(ttIuK z1y^MOv>x<>K1HG$&i^-5_aC){ODy+~p}K2M@C(uk%f2x;xq=Qa)lFbo5)gRg!m=OE z|3`nmTPyaN0P4rSH6K?A1%iig6KfUGm)K61&ua1~n1K)y_tsf+_4`@$BX;|xgLtmA${*>?*gYuH>o)s( zo+GrsgLJ2?4&Je*uY|(I9i$l*_7?&W&z^4aTp9|ThM!nH#-a1Ra`y0j z#T(4v01`L5b#DK?QFPv(+^Wk4x%sJ%_a&qbFO2*IkG}219pV9&=g&5^@nO&Z$IrE0 z@#FWxhv0v2y6cS1`@U~!W#+o~G|&5~7iD#f2@0NRJio}>l#F-GrfxqH@2xt|m!t8H zQ6oHg26>wtdND-g?R>jj_ygp<(l|Z01@d0Tp!8PzD*;pn zUHdaN5d!i`y=|Qb(07pSoJS(pw=je2NF3V^&9vD;bl!AIqbt_PQy=d(qz-zF{6>NT z3~$u%fR&!Ff6*&o^B%DuE8YZoSEz6#j5cAP-r^Kwmyd1vNb|gLVieY)@}%#=KVNUz zOU65z)pj|Fw{-e-J~ZC>${wnHkoQ4dCPCuy7U$iz7#?_W!faro=l6muXjobh7H*jY zicgtHOF`b-O=LT?#t1;>=Id9YZ$p5>#owQ6pP=*Rd{lbBahw@!MB=LJaZ`5h(RrWV zO2^$|Mt!{5kvh^a@>9%rV>>y=4Sbb)O}Y1D^A5GB={E54#K#*S-m`Tb_WZx3IsN#} zS_hhcy~RuoWpyxwG7ca8=jB8uWV|DL4iu4i=d3!yi^lu<+QampAa5nf$2*C<3F8fn z5sC%o=_YofboZ%*0twCfjh_dT7^*b&51k@ zpUsLQ7T}G_tbgd8>BL zyRP-|#0Og}|1NCZ>4emn(z zT^Xjn`M(XRBM>7$`Y+kb^?7-~#Z4LeJaE|a|5rkkY`2jw{`k0JsrCcxJ4kV2AxA># z{|`KaBtlso?(PFFN&kF7%9@OKQb6+G*IUZ!EL)AnJCE_XMIz)~ptin_$h*mHiHHN_ zJrjNV*iQK3^V+g|x$S9*AeVP(X&L0rVsO-y=>q}0_dEak(slTOG&`rH%h%C)Z+_6@ zHlNN6#E>}eS5dDsB+!@G<4Y%U$&T)QSgeL51|udO<$hV{D9OFLRlS5cZ4Q(#4lb!vLfT1sG|FK2kD$cScS&> zvwZ!>vyk^a!+8S9yx-vplH^=O92*irluI^Tz$5td0Z`d_!^G;_;Rx z8SjKy13S{@WXbQ-E75pAIjRwS1@h*Z+`Wo;ycOLI!V)2GgYPzd?-m_acT_f}(IEnXF!H_q7K zu5lOj@zzG_pu@<|w4rYGR}UW0u~kz3*%55sv3>qY7RwIdkEq}ehf(nLmV=jy38!M7 z)BFX}%q+_4a0{=$d_8WFw*?vR_}Bi6-`*xZoVdExM-YuSv%?FwV#qt#Z;25(?~+Wx zJpO9fy`RdC20`BIQV-oY1bN>){>A9`CjziNd~H0a5uVau%9#d&{2G1WEdAUU#2fuWOo`|d- z$ERdIIq~Kl0XP{q(Eo}J1y}F#Fov8*Ut+xypRHMoX9CxdxL4wyB8*?qd(f+o;pGx4 z)YpUDkvcjt@)K*U$h#!U1BO-#xf-cYVP5~&h=^@|-(!z=+OmDtmk0Y9B-}dF%I<>q zwBLgSDXe38bHdhtZjiPkY1bOet zELPmG{s4%0U!o9Q0(mD`9_5C-^9SZeOZy2xz5Ge^#m!-0kS^BhfPp*eU*j7QUKNE8 zOyC0&m#(_uqqZ^n4$^|~@PXGp>f`+yslyT@zrMFDca1-BgCRqq7hOlNc}KimJtAS^ ziVsX+!Nssq@QNMIUwt)^2WfvmVxz1M{X@fB0&g$wAor8;KDBn+Iuh??y7xuVc;9>5 zw|XDseX!sG9dZ8unzC?*84gHImR|R6o;d(kvD6=$A36>qo}S(K2kszqrSo*2z9)d| zK7J~KieX@5V(*fR+UUGjt8q@7EMo?nkhrknnBI6(bl&0LJ+ca7sE_wbq>iH)`ROMq zzNUM^1D5MuJ{f-jn|FBit(hY`_u<(Uwo2%+V}HFx`wr6$qwzO1&wKV3Wp%6*DOo5= zSv=m_N5=ak+ls~a{}TtKvddRQ(0K0`m%8B!dF$UeBTMA1sAJHs40%@v=Czs$xB#Vf zOxN`!5&>VQu)qZ5O*cuW<2?XhPW(bU)Wj$Zw9w%{4_cw~cFhalbw`I8v>|afiunT_ zJkWVxr@uQnSV4Wfosl{UF!DRy@JG&tj|Z5UyGg6x!RGy%H;M0#-9G%9A@PH!)=|*C zo10gM)4inq&B+bQ>L@%~x{>L8Jn{X1wq(3dG?uuNy7yauJ7F~5S9U)=<_~$Nd2X>I z@@AIW`D!cV{b+hd`IearSjpY|o=Yzg^uF^p_y~F94ksE9K;C-`g~C7n3I(bK20?W6 z=)Bi|4}5&tk{PHYants(uO|QH;Y6R--MgJzsE@Z8QpX{T{P^?lGOE1c0etf|>0Sfa zyn`e!YSQiY#na>8U0rh!o45OXF}UDH`wu6|eWt9AbCbdJxc}b&PhE39S~jo;9U$vL z=fe`Nl6ugOpUXF(^&me^?Q%}ogO(_+eqaWB&;{#NLW-~l@$q-qrf@g`GXb`jGmjI1 z&nnT+VQ@e?|3q{6R1X2X-pU>LOdt$|+Ad6_ZbI)ts}(z19g>+qI1)#%uH&Jw4tG0yl-1!8A#Z4Oa&bU%CgYuMd|92udw_pL5{>sg*#}EkLf)n^#uG%| z_v61OeuwkFkX~WGbD9&-ob%pQ@+$!l6eJa0AaA#tM;Y(l5P;~aTBkq!@Cj1-A&*o= zbl!oNOEV2CnLsBJCv#Rxzx&@Fv1?Fo%2S{|-o8j3!x;G$bEj8YKjsFjBM0L-%CLE# z4Zc}g{@xWY|J}{h$`|{1%hJLqfrIA?%@0WQ=9JZOl0Tn8 z1RC%8^}&(riQQXzR+xCa^=M|4{u1PU$mqkXTt#Q_`i2nSjg7}alyOsv8RX3-*>tzQ zmjJx3?O%UGJ`9X+trLsTL+Ab3ck4@z_e@{{iF~diUPR{&+UbhWdDaKOJiho72X;MDVrjuH>bBwJXy#(~b|B-OR`Fqk#Jl_Lp7m(F_dny(R)@UzEwc+D@?Kjk zZ*UuSZrdv#!P1!RRkD!x@gJEtB;mEU9qsRCm%!Uwthd$Q^m>5K zJ6_lFJ4+VR-#7uM+%4lX=-1v@Ph9&@y`1{GcQjH58%BO!>NkT6y12pEn~ld^)?)KM z;EtD4d1;S7@pOOP5rDn-_H2v4f7Pv%=6QdqpsbFcO0?PD3cN9eJ*anLH+vhL|KmHRi#2)e!QFns+``*< zQ0mF7^$zwRj-EYRhhGwaL#dumcwZ<8>r2|!xeR>=*|@%nzR`^lgd%Zc4V&^dccS;8 z{j3f2LKA#cx5Pd`>afGe&+_q}vnPJ=fT@(F7PZRQJ4msOTzRD#9(c7k=4Y(RuphBg zu?iWgx$jK#1JaNgWp(6E`Fy31TD*efPR2XSxZnec_fw@ea%jBg*<%k5K;8iyPne1G z|Bs>e-UpDkS(X&wn{v`>Z{Z8VQcF6m8tkvl^uLz(h>Bm>IJMf6zm$gHD z7=4MIez|Z{HkJ`=LE?;R!fr&ipz|(F&}?41lnQr{NF7BO`CUGF&fh_f2Qbj}+po~Y z=KYS2<E@t}F$k*$=~Q7T-P8kD`bgLEU~oheof|JOfn zkZvuyFN?t_Wo!?{Utuhh>mA!6Hdva=!!UklbOAA)5e>8q-zXgS?gG zGiIN45&+N7#^RY_u56FUFT>n&W!cxT)a?;!CuGBcD$ zmX^!5gS=x7o?aNvasl% z`9J3Y_=n%F4XH97U;=lLxD_7tBg6363@!d_MCz0A0qW!Z6{!O&zo%+1o71=Q0Hx&? z;dCk3y!CYHcKR{<;j`^NYtFrGLH)gueqU#UyKXe}sndM-etn#>I&RJCXWxuF```Wl zBmmU>6VCrWWIgDbzg`Qe2i2Y9*o@YL60GBOuE8bNAR_}uod1P;p5}4GcaVq;g|oEr z+5(}i8%uKJwZ~dD!wg^_ z631q^-u3Kx^d01Jy;qDJhpBJ=KZewih>@SC#f?ufw|GGHj7;j&>Tj4mJ;{1P*jQ7>8@qb^CW@Ff`jK(|t z=Ev$1$lHl)oeYt8?)>#<43PH$`|{R=Zd;IFS>oWZCmtMSZmAN3ysgz&WdD3d0FCFY z4K9U-f_=;GtC`rrI&b5ejyYUe?tS?rt>C8y8Ah9e!)gGJfVS4oKc) zymMH8e_ix*KmPFq4QVBlahy#-8=*<0x`@k&G=E}aS0nZD-ig%Fgpprng|cm)KM&B@FRfwy1)F#KyStmOK6b}n z-EP{=OUc(;&I;%VzO|(N`TrJ$b#y9hllkZN7EdzX*;jS@NZngJR6`MsH)p^LF#_b> zhhr!u^1gh2@4F7jd!=QH@hvYqu+;B@@GL$aa6GOx`3iY|Sy6D84_f_CY)DeP_pZWpzZ+qdz37a}! zK?Q#7`Cl_f;78OSSA1-m*6UZ4e7(hv(fXR&C)(%jLRlRw;yW95UH|X;KQ)j2e{+NL ze*jqzx)CPhP3%D{;UjiyEbVY;J?OGD_ZMH-gE*M%6!yX%WG!GKLwtjDum82R+h;6+ z)}f$Z{yA~rg6yUEWVnNz7`rW3+DZTeYYZE@^}>MR+o0!pC(+L!pJc3!d-ILqZ=Bw$ z+d19c=sk#M>?q-V9QE~}$4DK^G4i`wu(|Sp3@>QoIlp0t8uk)g68H3$`R= zJE<68^B%q$8RQRnGgg0GT_Q%oD|UD`i3g}`qIuppZVKxdot{?yX9wv=#{2q|uqui7 zsiIR`(0C7hKc^H6d2ir!jU@7}uFT{Xg~wZ+k0gczyQ~3EScMk-TpVz#eUat?c^g;7 z;j`NaV9zG!k8&*GpmNt3@4zk()Kf~Hu92hSa*UuHiDQkD_?d2qeg&yxyXlM$@>NwdDOIRE>S@y=^*s3GyzsB~6E;~ius77D!xIaqJ1p zf4O_hqKom4p%wMnqNOlN=^;00poNm7o<*u2G*MUCzgJn^yqf96A-uz9z* z&@o>5@{Hzr|4yc?4m;Nar&Zwx(&66w5E<{>bJKrcZ{bO|Q3Z{6*EQLp49I(RVBjkv zZ=J9|r7L0g_H`>Azv^KFI2fHJkMhO?ZS~Ld`jEE)zxs#5b^?eCYR%7h6AH{Y2Xb`Q zp!2@^S?+#m2LsrP#Hq~EKU`UgzB!Rs8Isa)ras)b|SK1%A=IualTN!nvFCWw`|o_}5NeaUJKM zV#bdxe`_1x@RsHWq|wPfis~@Fj_(+GlTBP=gUEQ_6z9|=@!n^+juDMF^XI@NMv%9` z@~`Pc-aU^q4M!mFPOrX~=Y`F{bMMkywLEcPPc{3}2axyUsx8`Ao8cX#HfH7D`a{7X zPu-PcD(FjWK>x9xSIZgx#(6E-n8X%^zQjKKS$KZ*7WMJ=N9uTlk>97x9ODm`yx`O! zsn{E1l=BX~bKbes2m2K}MmK+^-MdBmFG&BCNm(63RuLs!iHo>0qzGyIKfS;~B5?@@H#f8vu@9eYfDytR=!a0&mO zAII#=&q-%^K>zLq?r=k`3HN8_zkSm(PR@;>i$?j4bLQS`UeddORw>#>{k6${`V zTV_k|7zbv@Okwku z;pt%Xf749!1CoF&Wp${Bd(0a}FLv)hGTw!!O#Df_g?&%aq45sUzZ>4>+@Ot}R6poA;(L zbx%+D{lAvgm+lMYQZWDf{TxbO)&i|apZ<=y{3@K$c=An%5xYW3l4m4ozAj4{R+UAq5#O`b!L; z7l|9cGc~$?1bvC+9?WUURii%M8b}>{82Rmg<6q!(MHI{%%muaCV)K?7bcicb(ZWv! z`rvMr)?@MxoKs_)I9)^YykGyKtd9D2$1%^8Mc!d#yvv4}7r)*@yn8F)`Y;()|%$t5WSd25;L)*h)e0e8C|MXc?J1&Ok}=G~C@VU-<40P=p#;lxz9 z`6y6Q_L;_A@kIS=k<^bC<*+{r5=ipV)G_loLE)OY`=ZzCF<{m#QT`K zuiFcONt!?2>XV|Z4#D(Rb=k`|h`d9{c;7l2&P?JRzV#S08t>ID2cx$@-oo4J4T-$R zS(uj*A5Pq>`NNPR-$0mUrQ4YZ?B=J>s-qdt}`K)Og?DGg8|1)OUKDiqzqck>4J%!GL{01k~n4u^<0T zIq%73QW;Zb9jLz-5^txx_}v1WBQ(!DIf=45rggg+cSq*_cm1CPfSP~C*(TGI^`Kgi z#7F8uXSy_a(0b56 zRp}|%gN|;#GoRZ?04`RiwN{)C14)g_}L#^{kn;G{XdzGjQ8DT`xaksNgR+IuX1vu@mBW9^7;;WTN~uB zC(i#F+^vDc`~M^4Ma7GyO~Am+tVrvXSRe<6CcZ-6HjlzH+29T`dUD0Lc=!bAhXi50 zU32J9kY+2Cuajk91pP>y@4=G|yu9eV72Tuc4D+aucP3JYGDdzA6OWIL>=y+lbVZ-1 zDc~(i{}1oFj46o*BkU_k!G+eD!G>>Wo_B8(Wp&((j128aCSE~G#*y)^9`<)4b#F!f zcgxUtYnO%J{|$MkJ0=(rd7I%fOF7^UQfO?`xc;9#U{+}DOdb6GdVKk>M;{??iyqB- zAIRI&>)7-#e7!|B&OpKXGdgdLZ#v0a-!gy;NSrg%``~^qbl$a5W`nDaQ6KLuNF8{L z{8%PF26!=xg05vYySBf_?%whlIwL;U&F~UR@AurQz(ZL~ zrahqV2;=qCqF9i2cD(34O?dzo~+H)op?0)$ANaVkKAZ^Qm(&gjT@a9A$ zj)DG6R+Sh!@35`+wgg#IAMedb9T6D$ZBrWm5w}GY=nYT2;rxTmyN%!buvx)gJijZU zJ7Y8U(_6i4At@ZyT6NUCPo^Zd9!ARQklgf3sWg0%cLW*lJI5}3BXw`9@hA>7-hB_x z-r$71?OM$@(o;AL_=Q{QAK8VzzjgcR_w{L>U zSy3=`bCPv4FZTQ|lltbJZq8o(VFfwc2Ye4P_ue?3bu#%8wEy;2oG^uTe0#fE0Y04g z-~IoTG>!kqF>nXTOxA-QY<(F?>OsY#+5%`jDDs>6y?by6dB`?l2XX#?x1n`MARLg6 z$fSX<)u!ORYPw!Jya%NAQm^A7;ciz%z?ec^1nYJ zbNG`V-pGZA{lYHnB^KwXyNavEkLJ%Had#-J;~c?Kdhr42WF|7+_3Xy%B;LQbF!7`D zzNb2%-voJ=zQTJFd56}&$UhEwe>i^j<)pqTd{yl7jxl(9L3TZhxh3SS@5!Dee4hZW z7#dsJ*M|bepgPrffWE};sfyd!@`eG>BXQ9c=MLJfKwn~?EV+PViKaf@yO25v82OE{ z>Mb2C5(NsJ=Pk!{v3VbLXz21^>5td7;bUdqh&}(~P90pYeV>l@2c$vD>hM>HUeO2# zblANa$#~y?eflr&jX3y#30zzbI{M<+;7=#V02h024<9f1-~0Ev@;-&U6Rqb?5_xkx zUAi>~@(y>rq%qdC7qsbGeCmY9Tbh>ZJhUM1H#aYUMmzyb%&G4_a4!@XTRE=eRYT|9 zB(J>8nu!q@B5@0+Z62$yMCUDqzhXpRM18y)kvgO?@~a9wdadt>7@*fQY}Inb<}I9C z8CA~bhu^s4-MAVjHt)bfFC2bP2+i}Z0NxbUVZ36&#|yqe8uDf!<9#ppKm)0JTU@)! zhsHbLkx*Y3cCjSK0M| z0N5v|R;<1l27-QyMuhRBU!3sCFAugf`N=)G>>Z zpUI!d6D2WXp#Guzo)z;?ueP@XNTJc9&A{f^=Mx^z4?Eku=X6$0kEj9WoiU z(fSpO-Fpcc?>gV6ViIq0dmmmj-k)x+a_fh@TQmGSiM&r)$|eyXPPF53Np=S&sjIJjwk3{@;%vbvR<=H#NI+n@NuZu*lFCeM`Z`i81wmE>4VX z_wir1?K$d9LP}^?m%5mq!5Gc+?pdI$j?3QVGSgB2UH>Qj{ZsW%xWuxP^`K^@+;CD4 zT9c%-2CWCVGYY>i+xGO`um?pSjjybLJ?NsU_EO8s=HPS73#&1B{oirs*|n!| zi8WHuy`y!90KmwLHHUda0n2;c$sgy@=l{YZWlTKR;DCh0y>XembTc1){@2dSFPPp< zeM{_hqzJ$`im<;Ege>@!H2-gLKDU)Irl z4|3-{Pf;B~rP;y97T+M9yp)XhqlHIVB;KAbe}vF@U-7ZolnHq&_O7cT^45s-pCJxN zhHX+SuPd2@m2WKcw!#7FSm!47M#%d?XJN;0$a~Gqi#zzFP#~3jm_3#geL$M)7E~j& zGJv&6T=Wr_GTTvf-cMIaHE2`e=PiCBbv(n!uW5hE>fKzTfcHv7?Zg*s-qGxdsXzPd z@x>+~9rUW$ym2COzbp4B&^&LP0EKmk1&m#Quh@azn~jWjV{^+N67PFz&8yIO^O-*n zx(0b)nn`{`K2w=Yfdy$(;7-+k)s^V)kI&YyHU$n*)7(p`PW}PZ|~)1*Zw&XFqU%Pw5|f1_xzy2?dWd-_^*A@PW$g+KOh~s z(NQHTYl8M4kdCFS4ukJ{Dv{-j^FIq2?}t8b-;uia6I~BMG~N;B5i=E#cNn+lTH^dq z;{C9~q9bUf8GO7YV*4QEeQw`39ivd-JT=l5+>XBY9?4K< z89l=Q?2x$7@b}Xa&(Jp~!dXt0^qSPidkCpR1S7v<-K7e?vm(Hz#VU7x0-Lvk0RL`V zc(-(5pwITJIlN#GdRKXLau@7DGgdEr1K<+d`8q1glGzH(O?cCtaEk@cs(v{2 z!yZ&;E*GR*3Ev>?AZ67X83L|;sA$gOL+?S`o^8%~$-V?!LgLIgmvQt#86SC= zY3renjbGqE`$NF$j>@CqW3H%w zEzQX5$Nkvul9AXOpyC9X9Xh zX;x={i0=jwNuH&mW!O8&mk#qz4dQJy&-V#0dSc`r|2(xu|K1dJnb`73x6UQ3|!UgI?NDu$2xo*?B#>R64D z-?Z2ED34BIaKlyf&-6GpZ@yMbd!JRiL2R{++rDz_9V9ONx+K${7c|csr%z!WK6~WzLSr zW5FJwXPrHe_u-El(o!JrRxK|XWy26~E`;+)NGCe)yCP+*zs@cJsYu+3XO-_fq|tdl zpC4#!(W5@zRY)DrF!IYueK>HeQWykTO4G(TMl#_BJqw4J0Oh4Tf{cjKMC^I*zOiU5=~n?LrC3x|TvhQW}&>*#xL z%}WpPo)HY-84}lH6MVR~0G;=g*%6%^($qKqt08q@D14VFTzIn>~Fnr#Goi;t?`=u$}mo{4&SmQr? z8!I&MHsWLr>sRm1jOB6p0n&e`;J^N#S$fcaod;Y&O3>Ay4lM;`v-3w(;8l_9b?&U$e{nIc%VeHty2zWZrxNb`83`c_PE`l`zxw|8cZD%5mn` zwQgFWX_YLPi)aQ(uN}f{9MONvt8!J@-A^`AT5L+sK757WAQ7ZUcP@Tl{r*3;dO1UR zC}h8Mrzb|)A3t>ZVzQxSPyMdO68P5DJR|SmjZjb}V zgd+SXC-Hed%d4rmUhPI%-w}9aqy&EjNqA^4yj`lD<#`iI7|dgx{U)`)Z*Pgx@oqcR zuova+mYuAM#rup@!gY7Z`*`G>Dk|?jvkziE z-WIexHsQ?gp^jhiCxO|(VXRJb-V1!*zu&($i2dS0DO)|eTp$j=dhh#syQ}JyG0XS= zk82sr<8wJzmQdQC>McUY`(cog9m;!Gyx&|b-eZ+6v3`*Eq0Kwnsk~*KuT}*>-j}op zCEM-b;l#N|gCf_uwfQh zLmOA-D9Qe~5u0~mrFp!JI`eIB>C^Hkz?q**^_eYNWNEPJRi?rPTYTOXy64wyF|(tj ztStF5HH^Q4l*!97=%{yK`3C6`iLpH7Yjj+`X8z$VO~;5PjOIJkS42?&rZPpzwBw>Lq7)>u<^C@=@4=P7`V@7s|I=7EPffE0eN3up=-=L z5CQfs`h9poDmL#B71wv8*|R_tZ5%S%e^!Em&0B4P|8lB5^YIR)<9YsNI{@cbw4D|muPX~AxxU)QOf+vG{%xcxw{@edc(eZv7 z{oyFe+oyu8g~fZk{C?3jPn-lFJMcYm$ zFdy%1S{{#Z=BLP>*F$!d0fM$0&m0}W=Y6Et$fw@V?!I%6m%Dr8NTbesZ#? zquSR6Z00OZUS^p9EL?!)PF7vkE`FZ1!Yx3W2t-fVrhiNc+1 zC$~x-|LrY>1WkD)ko6ZQBchDuaW(1E`6KY{t^dCNhjwdB{1f*7igY#T6<72ov<7iZ zAd9hTQ1-o5hQEmyj6H<|YDYrj2u~nHUJF!d^ixP+YUBej)Sq z|6gc%;LVTQ_uQNK5eZ;9BczbR`4P9DZ%SLQxLH;TC|Z3BIsO#C|Bsd0R_CtqmgW2Z z*m%bBNHXtypAWx*19>aZ@qW?qYY64Nx$TiY7Vk+F;$kAa#C}E=*-&{uJ-s6#6Y}nB zi%1BmafZ+LZ?E;`O9UF0>_Q5V_rSW<>Q^A|zIToD%|1qe@_;pp+Q+eZs}@|m^e&44 z&d|oi1hn#t7Gv|aj^5sV!kPJatJCtpo8QtDLqqr7l0ZVj=ANSwKJV)>yOYO97K4`; zA14cr;`jeaOV)idpIOWDD@gCxjO8J4`B~bl{6D3H{EIIs-mEfij|5R3Qd#~~Yj z$h%c_D3r>3*}Rsm@sPJv<+CmIubqL|$Ft^T!wF#ARi}d5Al-McPl|xN3ojp&dDj*J zTyEWQ(v899JaH7u9tWbM0B4H({E=JdEb_(C+`wrsMtmpyEFV zq!Fby>tXRe7dyC24DvSg7)qh?KD_h3%2vo*;Nm5V2_Y9yZ16jo{ZRrSJF~S>x3?-{ z72jGw-rI^TKO7DtgI_26_xQ}lZjfAr>RurO1TaP$r(V{0#`+sJ?_=xzcekHqKHhG$ zJn-h%-jV2hOHm4lKUmHF_%=Ro#Xb**bK0M7aa=Pw_@I-4{$IE(tkATJ^?7?UmdA}H zzOH@n0e!eQk)z}N%%tm|ueVNwtyqA?J9EOuT^90=+}m)5%G+p(LXIQky|K)xRomPJ z5S+iLPQ&;A`_rHMYC+!b6Sa#ZA@4J12Za~zBm+ZV&d_#cY~FiUM-{ymodxu0opFZjEFWz%YD;FQ#pBQb@~yFV%TK-Mcm%Ff*`2U=wD z`~O!mt1VMy`&obO{n(75JZ?rtTwcBJzy6OeP6XV!5UCtQ)QHd@fl`Zee> zV|f$|Po2Dc^3Nq!g^u@|7Rdu>gLKmC-cl^y2RA-C_y+P$Sz|__^1iXWp&}CURwO?) zPkZVFri~YQN$*bt7k79CP+xBWY@*lX;Oi~@r9H{7OUR%liSzm|A8g)g^UWUnt|5SW z+Bku`vlU~1VDsMU=kzdFocS)X8nisN;LK0f*}`&5ssyOe4&V|H9>nDxUw*l6CUhO8 zarBTncOicNU)|oecBdO)`4wd0BgXPDGr0W0@bBj>=g{$fefFXn%6s1QDMKvYxj}Qc zeT2L@bU1sdy!E~>v`B-zpX^?-TUyB(yxzXYYR!g3P;YTkR~Yi{Dy-{phrH9C9(y2B zKn52JX3vy6Ve?K;)?2Y^2LYU>jhk8HyI6e;oA-~GBJu@B%*T5_Ef2i;&3BTo(Bqc` zKF=4;3R{BDyRk}HDA#oz<-2L+{fjaT^#AFnrz36~u{>`=3WIs%Enbl0_2=`J%5=Q@ z;Vu!%+wEA?5-i>!8i~QfkoR$Cu^&|4zj;am^C!@Bc-57gVH{5E^_?k@dd z%*T5-Ef2i;nSahWG}}lLY;xc7dwU^1?>9MBPL@*^KxudH%Q6rA28ob}xNE$yW%v+PI@j z<()GBrT;HMBGwPcF(2=Bv^?vR}AIB@Y zs5OY%|LDIEwGXF6$e_a_)8oub>^n#me!5THmd=nK(8ih9wp%15W3M1V z%Z{pJo%~GK|6iizfj7S^nqe!pu}c6#k`U;vdXHOE3JZ0+E0UckQ)Tmyo|9!@1xfj0 zV;A<6^)Ino7|g?L;63dLQVlxZgEzT?P~J*)$_N&3x$#c3ddNFvwx%wX_j{pS!d=MQ ze%>L8t?74eE0?Vh9hX#Iw};iC<&;n&%a~@dFu}-@C-xV zlv|xewLxScNgf?lUx3XUk^H8){Ok-#kTz~O$th;RO>Ev?mK@S=Oqh>1k(LME{J1rD zUfHr<0^HQv(|BqHKJS$9czI5j5K6dCW_Yy?KJN#4?e0lbTqM#k(2OGTOM?l-&}9>)5=1 zY`yk2X%F-9Zl>jdH^1*)i}ydcD*=qV;zjjB@p*q&R2$QF458c#s2%k@$H2{rN?*ML zZp|#un^4GL9&a-eXrH%KrQtomhhA@9Y(OIJ6Rw}LVxI05L88xXY~E~+6^pj8 z6ToZQxX=?N=Ne_Ox3{cSCl_r!%6#|U*lBrK;>^#P^JYmyFTn->9YJtJ@U38{V3Xht z!SjOof|-JQ1-Afe8YUN z`JV7K@>TPd@g3*e&r`uu%#*{jk0+8Rl*g0DmdAugpGTEPiid}Ln)?fPA9p+V9quab zQtqSN>D?YYgkmvGPHmg5%SCUA{#z2)lUYT~-Vb)GAqE0b$4*LJQzE@v)F zE+ek_T#8>pXNZoF6!!aX#R@#d(Rdh!egZ!WqH2k<*=XEvGT39;XVY1Sc19k~l5klBFzHlA2^h0iuotuEu-VVh?A z!q&&u&US~bimjCGC|f#PG}{(7Up9L-Gqxpc^VsCr1pc@6F{|Q#zyJ3e^ZyO-vlH3i zo{*XsB?S=q(8%+M;58yI8hLnb^&#@0k-Pr0J|Z_7x&97MBXXgU%M&dQA}1O-m%9}Z ziD=}sv3iJzpphdu!b#*nBL|^yF(Nw}t?zwrMPx%GyW5EfaTXe_BWt`O641!jtaBgo z8;xv)7f_HHG+OhXFdO-WM%Gn7%8+R^vWoKmhD@Q6rQL;J$RrwBsOr@sKhbFQs810x zfktM{dB(^%8m&rM(Ta?r(aKE=HX}dK$W%iz4*8BoE5?nbkx?`rvjWpMLMj?G@G*3}{4e|<&)IYs0L|&qi+N~E}$O|-5%~d{t z^rF#Rzv&9(IU1>~`1KKahDOR$D(XlN8Ywl_@*~}7q?p5_g><2j!bZ+mq!W$gNk%ou zQ#6`Ai)Rpdf=03(m(`FCG?F$k7e;E)h!Ar4IdYR0ss3JQB!SeR(F{*F8M%Q*(;WxH zk?UwQmG_GqsYav8U0G(xH8lEZ&c}&Vq0xj$b`x?HjmBOSL?V@F^y8A^LF5V=ecye( z9jQR0(KQ~ckjrQ^B0koNTtcJa&s#c?ay0sSb<0xZA{u>3usw`iK%>uVzL+5A(P&6< z{X^s&8d3M#kuo%*Zcid-(TKX6gOs8XwfRNPpb@oKKuXYv`qUnB8jYwAIU&VpM13X% zIfX{lTj)p;8d2{!A}7&^`tBc6h(^>`rH}$NqP|&zHiAL13GLQpkL_Jyn*^frlFR>#Tv`8&kT3C~)jYf&@ zb_o!*&?upC`2p6WD8Y@{Ip1wdcrl5jz-i2fsr&cqMo0Mq@oe^ zxJe`hji{&dA^Xs%e#MhmBpHqB_-y!)Bs99!eUJ}HM5Eeb{{|!hjc#sfJdebqQ4L5H zL-wN44MF!FBo2+L--Y`kv1oMd#)%>%292s>@@MZ(djlsuU~C75{O1eE~&O70ce!FJGlt)N245@f@O#w8XZ=e4-j88I`s7`2jYW9 zS(O7H5N|X(cwp=d;)O<;UcKpvCmJ1?vr+}|K%@OU5;=%F8l~U45QMm)QCd#jQp6RF zQn#gzAuec?Vqkg>aYm!$NefTJ35}Av!+#@=Xq1?@YYyUoMhT%|$%s7~#V_jFimXSY zz1(i%h#eZmKJ!0^tV5%i5`qX~i$>AW+wu{c|K9&+{vMA2@Bi!2?LkskHRv9sXPpfn z)*fWE+NOKQ;U1)bcSN2g+=Coh`jCeW-a#sgIh>()-Vq$|jaT^6o&?OTCrV7<9^~>h zMO9+(4wAS5yWW-SWFXFo9J-T*y$6|nchxUd^F zl6jTu2tIer=JC6e1QO3kEHZ_>Kdz2%lYqSSn``|&BjG1@VvQdr*kbeUQf9a6bNxl~ zr;Qspux$IrbJ)Dw*^7g9r@-7VZNugf@yi+%}?aDvBcMIao}tG z=)qi5eBM0`voo4Alqg1Kn?J4lfzLZKoogt*uao6@KMQ0mk2%g+UI~Azw-z05>P8C6 zJNDfbE-c>O7pvtjLf(xTlKoWPR^L>5+#zp!KSH6Gzav;1kfNJjkOa=0uiHcA{n;#> zPag7KXZSd`8jyj$dx}B55H{~E{97^w@Bbp{(8lRsZF&0bFgEWai^=AF!OX{d6D^NC zocZ0`d9U&0LUAzs{Lt8-A3pDhVqZ!dNtvS6ptHZG5dZ#vY;nTFmAp?`o_FjH#`4g- zHm|A%;;1h zHt(&by=@aE%*Q*5mIvPaOp;afC*j&VJb80xcs4%ov&moR{hP|1Me{6*%)-D%*H$KuZh| zUacq}>VAjYAbpbZ%wKodfkG-7`B7+!e~F#@y597(@B)^<#BOY5EDx^`$yc&}KajSN zjyLsYAIjS!OGFrpcTVz3;S|VQXI7v&mA7i$(7qz-2~xhwcO_(fooP_*x8 zzboW@_PTh1&$(8xrKQ>bum>5`hGlslC1La4({*yrqvg}2YTCFqS34K+eb~IcH~Lxd zzhge$yJ>m&;LNWun{CaTbTKfeBcS&DC_e9azCqJDxek<4tC8j*9{l(J2||i1d-#{J zJa58E2J=V~7Nx!3qDRM@diNUTEw|)_AQtbvqa!ynAa9NQEH^6e&ca*$S0V4Q2US|B z*PTF7w`NZJP!iDmY`Vt|@{X9j_S`7s{YdldnV(#dz|Y=3^ynZqZ{Jgjl%cSxx3w#+6maAabvvLE2@-cBaVA#I#46z$-E z3@vv2-CM%sHBa43jjYd`!8`_D&N19u@@IPso}~KE%Zb#-F;LzCMP&k5ykCwxY{`PW zF9y5{qw+Rf7oz?U@^<9i)4IjX3D}8w9%vaz0*j{u!_6S?Lx)seG@Ne*2aUIN9r*=6 zPSi3}@Zvc(Z&yX6-T2xxDUCLc*Q#JX?`v${9~(Zz3cE8OZzozFLpbx(C?{Wh?j{a6 zo?eNlh{ET6ELpI^MOKGGDJU=az;PdUG4rbB_{j9-MJ#{*pXYtX@+d9Mn{tc(b8|wM zjyLuBB9wRYyhwg5-uEAz5zmFZ)nqw*fP<;C>{^5z&=wja6W2p+Gh*p~S!2{^1# z>80MB=+<_R8-u)^3H!F@Pm#f<8$}`cUD&*B9iC1eoth>E)5cW{9oh}vVe@`FVR1vK zfcbc@q2=)oXMUbbTym3ciGlbH;YvTw;qxAjT6buaSBKIvXyKT0wi%Z<;c;qlX&LLk z|4)cwERVJ8LIyeD*<1hh|E$sf8`9Mv>Jye|4cb<|L<*}0dCF992E!VpyyR4a1*}1* z?2jK@2y0MOb9+OSksH`>8>u`bnGD>{yGT308nkOMC^-sOkiKRm{^#aL0uTEp{rB=g znE!VgVp8}rMadY7cH;j z3O3tN+*a}?gB0~Iaz2o^xqXwmnq(b(+P$KhfZz8t9 zJ6pcK#`3&fO&QDM$<{}e#ea{tTujHC`cenV`}M60VpzN#j=DFJA@Apl)^k%EB=0)y zH$jlM)L_nOvji6qB|o+zl06x4nA&~{fV|sXcXH)G-u6}xEn{TJV71|4Gmlx=yo<9! zCi1hVNG7y#q={*+3oh8arI#%1S^=1kcM&ZQ8JziDcz1FoX+#t}-5u9`b`w5tll1ML zUFoX<->XlTceOEaK>FnQ=VBsNEYF*e%wQhDKTK5r9&fpbjyLr!C6xE)Z#zV>cwg8m zs}lox8=QWrK;`|~uJ>00C93GA~^-@5_w_I+SYN`$-}J0`xX zH6@HH7cev^>Od=I1NZ?`v~a1h~vyorP?Di(6AZ zpM14MPa>4^tnozX)cYpf@q|FPjXw=o{{!iS*)e}$a|u>CzQ&2ll_N$FUWh~@UCA;i#);FTXhQN=E=Y(F=_D%$opb$YgZNA zVqbf2ytw-o84Sor_f%G4^B!yad8$lelJu4~?&q?vvm>&wdF!7m)`@IlKHfiQc`U-2 zUrlb|>{kawfd?X?dmsy+_hL@9#I6}#P#W(LzE&T9drN)Q!9$7#)hxe)Y!75C4~Hkh zQOs%Qu-d0mb(mWyW{P{m}sk~nd z{!o7mc}KtNoH$qN4sKlO>Z;UE2Ek_8Mynz3(}Tv9p^*3eTuSrWY%*|9shGA+#^y~L zlnGg#3~x@*#<`B)duf?~&3jglwVJd6^X=ZEd9dTmPj`G&l*dpMH0ByFb+5kXh|*8n2GeyCgG^J1J^5%isThmdaQjYb~ZCFYNildnp}n>bFi%-a<1QrLlO= zd8AkB2YI(inO>ms24m9dYOw!z*3uM8FLeXw$teLza>-!l?3(7akazXs4vpV%?cLy% zpr(123_jdB9=_lxHt%_z-{d+B%kg1 zd4hD7Httx5Zmd!i_9fP{@`H0>F&ESI|Fe?+=HZ1iKal?&!S#pD^As#L_^+3#dik$L$)BY4v~d?c2OTo-!{*)gI!RJ*@p&Kq=5tAxe7YQkbafV`VC0wt-uBZZa2iXrdkQUi}eGrU1h z%f4L|Ta$s5Us-x07(uEyJ(lzD?ot)>Y3uU-;RFLOP_i?M^oX z)qAN++`yWfEYF*;kg+@z57ezG_}l**)A6Q$U=rp1J0M*Vi}xCy4>wmr-ZkwvwWz$W z$5fg;g}hgU4kiVudxPo5?@y~XB!iZeh^M{lmdE3iu7u zvAOdN>|buC7@j`4=Ef-g<1H)CFW`RBEY0%$Ki^r#@|a|69w+>LyamwlrhYLMQ7P$ZCsD>L(V7u*t|FV9^4ln%zV6?Xn6$V z%&(4j$|L_htlkA%1X>O7dD})^J>%EAnbPl(a_Q?42KxV&fp1NlFR*_9U&&w|sn7Z5 z{n!7qK=Ti$2v?BibTx?j&1kd+4T~tv!>U2VL+{*VU=6a7>58WI|CbCdNtSypG)^z& z^c^|x3rZ+Y52nHzbm+Te;ld;MEW()Aj#$v^?8~y_SlO7*u0NyI-rwjH$m#8jgwrISf9KUo44X)bqQg9=4+6S((=HYpKHhQD|g34 zfb_>DjYiM#d8>Cn@-V%#k@EY@&TC?)@mG){qANCx2%l#82C3`1F++JES^LL};3Iah zdYjSlrhe5Q<;|U1t%k*0J8pr&T*&*>4sedjo0vFa{Q>gM{BcWiubMBAU%KESS6DK5 z#9z^RAMzgB{L3luR4Ygd((7rOt!AZ**|iQ+YR~tTq>d{r}7T zyPv#m_W=dQ=9YEjWS~;E%J(MZJwIo?k6&>sP~*=$-usaZ{0;XQhmB(ME}BziyRKk@ zNy!jmsTvzp2P!ya$Sh-@w9emzdAxF*^T@Ipj z72T~Gue*nPGlP)SDHpm=m*xBa*l5P`SYu!rl6?42^-CQi*f|6Rd zbs+D@AA>uoyjQua9bE-^U)yqX&zDU;Ag|DG*AS@cRDQ(y!nm$1n*Dv z69uJTm4^G9@Odwuyp(xw{YJ{N)o(su^Tp?Ff970H$U+sCuiiUPGL{GTq@~)a6aPK` z&k`E|a0R)Bt_D$0o4lU&P&|X8szxw>&xSw3yl|>UZ9x& z@C8?Pm8C1f52Ptk7U>8peWhHmxze(rpcQEMACwIrj0E?BtXENHuxn7;BmJBjkqJ^g zZJgJ;SqtNSVAr6Y{L~9`9&s{V|NoelM;FfgzH)or?%faHAl3I>x3UO-5AxSy_8`r4 zUy6l-#dBe9{7>xUG-!Q~`clO5HHhyHV|mzzsA@g`dxO-PjyLrvHI#R6>a+P+yk+-k zXS2gg?1e9BN>twR!Ga0TA@9^XoqBA;zJRAV=4vfpGU)G)S%yH~*6U^^zJt7P^!!rZ zLx}{#Vt!AawPW)Ry>M6Kz1{@rBW+wqPq*^9fB8UKThnsa%&*MHJB*gcL!9|($*UW3 zJ`w@@Ghd#yiN)t#AlSL~>^@)0@%-t&r>F7n{}Wyr>gcJSWqIC&9>(%;?!u#kT<7;r6HBK&V+!y7VQ6T|9-l=dC(X17}b9@fe%P8 z6AF=Najb}U>Ai+8}Gw9f*NcY8~SEtU7`9-YWM z$U7)JF5>oUUr?dTxmdIzJzux0LDm zI-65Y6l2qrM^g1o`2BynYnzvD8SCF5m0~Q9NGsm)jAMVQw*?(<>gla0Z{&!%CKm5n zm7l$0koWj3uONEf5?j9McthT~VO%;2khjj;{AUA@cXxKi%kz+TXNlp1hGsHwyxGek z*@L~k^(y%36FJcd(mL9>{r<%R{UO-A{UenegxZ*IaneuA!w+YER>>;Sis7OlZjnyI z5CNZe{$>HMOC&pr*~kRYAIImt&-pg#=NBE8Uz}`gs%I#V#m1S(ysOMLsHApjwe=$}KI@~B{-3R;s>ym`b)$kI_m6zk72QRVVK^`sZ3Vgwwblx+& z{F1=1mqxf3Y>;{{uCm;7v=w};{PM}}2N`Vp`19=zLF`NHjrLuKZ|@r?ZK93K-=Y=k z5QJTW*8HqN8Z4Nv23@D+VTCh4@tp1-4XGkPvTf+=s#g4OkPsVp>%>tuP$oo;tlu&6 ziJe_qM(^t?SpO0m#9$uJZ>OmJy@RxljyLr{c9i#b zrsnJ`LlwwrQ3{GX+k{%oA)B;k&oBv#z`M(<9Pb+-z)zY-fPq<3qdUN@kaBo z#+jevESCpE#UeoFexG2oJ3jC9vny0j+4@mpZRBDPn&3aZ)y{iO!niDt<$2qGXDpAT zZ~9`({x(Q9bi5@+PG+OLHF|gHVeytHvDJQqyj6{UcTst7*>-i_3dlQejd_~hj4!Y^ z5ZrVVp59t}#r}decZn#!%(e~N%-%DZ+c7~u1EIqEy)W#>m346E0B&dBL4 zTY^t&>g2Hg;zWeOJVYya)&DL|*3$77A3D1b<$Yu}Sb)X5;fnFQamc%+%=H_U_cNsx zg&QI7-i>qj2~GNf>^iwqatNWI`MF^^nf`HQYX!<9#)JOroopkM|%g4{x0L73V}fHoYYRrlyY-G<4$k z|1vA9-;hoPQa*#A4x z)gZ+j9xZAOl6#{OI9%sJz^Xyq#BTX|Sc9%V>Jy^YpooAyNyG3Nq}PD+fWul}Q0M%} zT5VPmP_VX)Zh|%FNJQ9|{zI+c{oFM1?Wf4#bzOhhx4YPTkY9$kTGW+{k@{%kHVFhY z`)OcbVs|-{v`>c;neP7o5G{`#IP-Iww5@G?A`E_gm&l8|I)GVgQBl1g?Z1WW-%eS# zBqeD|2Y&?_lu=Kf>C&WSRPhyc;34n|I;8j((zW<$Qg@XV#7MxmSXW9OsFil z2YKgj(9)#x4mm!fbq(@1@2Yv}=->+$T&b#Q;7tOGOE2-2L*CC1O6n&ah95|Ob63)2 zHyO14YB=t89GmyYW0JK+m&Zu=Y2z{sP19yeVe=lVx%=(?PUhqNftJT8&ir!UXgie4 zih!E$T{~nl@p&%}dgmvUv7NHF?1A{y=R3In9SALb<(Jj}5A^@W4CWzUK-T%Yf^?wc zEl)D4L3w8>oHE4X-L(F=)kDZz)Jx5b$~#>03UL#a_nuECw>*5o?AIN?B&CwTTSpDv zT*$jOkf%c^w-v1Xyy;N$oJf#ST69Ku6?TJUn8DT>)i6d%rH$)%;QKJR1)F#4$;$;2 z`=&2*|T^CQQq$x0+wL$9!npnegb))DN*yL@}93Kvz`a? zCN6K&s@dQRuI606cT6=21WqjPih{gn94t=UI?@WB-QT|Vt!yM%thQYHUwE(oxrF@r81wOdNy}p$&is@tvs1FJhybBGA7U?k#P9zlemvSJ zd}9OUPQT6WxBKuLqzByBp6!!o{qz5P+p8GLqj2&3y|?53e7$8o9dFr=%W5d^$BXm~ zuy}{6#d2bqtE-oN?Cq;OOE|JLwT%NrgBX6 zz<>Qe+N&}3PuTyv)72o=T;&7Q8bs~?A8ha@V%4Cv6lbA)Sc6KeUc{Nf8dM87ZjQij zkjT`Yir2g13tXg6&RZ&x1l|QENed`{r8wTLDKk6(?;u4h=#_+!LCfsKQe7}o3{^NpMVyB(vvHS}1W>qaid2pQAchC&hAjsQ|j`v)@ z=?av0rL!`E#XCVB zuB=Rc#h%#;)FVjOgWwC&V*@3=-$Jl?o6nz`yLIOn2^|;py5ZfD=h(bEX0GiK1s#O+^CVwD zwoS-7z?}p*k6Aw$gDXg1wy=a&$oq*Nah{`? z2H(Nv{qq7S=QL+N-WzCnjN{DjhRnq^?_z|3=OS6>KyQ5B>21AoveEvO1t(n-_ix0n z-oqO@T%w1{Sf2L-CC2htb^VB$?%&;87dqa`Q!45x?@#`>*|2zn59W?nAn!Kgj&3UN zWgmvNg+bmoZ{I4P3HAkXDz-xV;LVB6x9^#Kg1jS!$18IV!tJe@Ni7a-GWg_FKj*kD zHgA{TyuY@kjgioC4s*7@7-_}kEknHc{+b>0@ph!;A%!zPy|&4cUroZ`K=%t#A0vF; zzC71*7bf^qMy2n$i8eLhE=~yV#SVTUl(IZ;!fOWec#*tc;cxYJrsJ*DSj&&{CLYR| zg~fYnW=HZ3$lD^wXpG8RUs_^jHsn369Tqd!+!xI6J!~;No(Nv-{u$E?d7CWr6*`jD z3a;G_wzchr$6InVzc(RZ_y2db!;H&MjFHfBLgf#S%{9gD|97Sbm+1O4AMe|=JhtP^ zkNc6^_>)XwaKAP0a^_q7-P=s>?t4DcTPQaD+ZFtN&VsI6#LEEI~ z%x-}-s3a)ruw~NrV;XFbW=5MU8@V`+=;U!b*(%8pl?%l&3Pgp1>n=Ed``j^-aQHJt3TV!`U?#7?~-5SzavOSrZw{Vj*u)hwEI_OYF{brH7wG-sS3j`s`|cK=szL&O?StKtO8lmram& ze38tXmVK?jsLC*`JwFoYC10CvzlY6xm*T*P-itBPLfW``m8b464r24>P_&bHb%yzP zZ=>bGjx#?ele;62DIy?z<0Z+|0DRtethv9n#q6NS9bfoa&l8`w{LMG_2LxIF^A-o9 z8Ovj4|G_M=v_HJP=y=al6#sL2D|PpFj`(|SEZ+BH_Wn+WysPcjs8f0Sp8ME240$g~ zsQV^2~k}|=hS2K=C2>D^ntw5 zar30Pcc}l%2~x$nelP5qkT*9ik0PA;ebQRHZX1s%Fq*qkfol~$?+Cu1EkB}nP{{cM zJSGhctRT79dXoYQS-*M{8O&qXx|g)mTRiD_tABc3h*odCf{R>OyqiYqpB#X^`R{0$ zQ+ZGKw|wJ;2c#X??D*zwqc1pN>8P|+HVMr4X?wC1^1k_GO2;%E9&afpAiVQLB*+3@ zip%d}^EMN!BF%a~MncCWtsA@$`!63zt9;ntq;-k;s<#O(j|!am?Wmka*e3=7zODK^2>3I*WBY*9@>kHOZo!VgzdDkrxUabOow`5-TqGYs! zrJ9rH5%}zF_LV5^z8385t-9#$hMil+NQY?SvK4N0usf-@dfgZN?Jd4_9luA|w^0aPAC_J3VW4{J8%O%&P*}hJ&jbwRG3#wm zye&Mv<-h))iTi$ZYOwzgq^m)C+k{V}HHhp;62YoLaU})4cCZHZ={>Qb_W$48W-J!L z6{O&!;=ycrf8chvaYL;ae8n!cSjlD1SIU;|8&-4%8l(U^-U}>hG*RAP zoP~w4c(<=wrt1oMTWdCKqVnENQCn;edCxf!yPo}rADF*iKKYnO5@4@%EvJhI!@bvZMv2Z zHg5s5%9R1t%*We;mIvPaeuys+N}VSH1Q*yXmm%WwwtAt>6ESNqWn4(NTeg^i734`v zb&5a*%U5s0DaP{P{Pp%y<=^xF{OEY=aO56Ec|YJR7r^3u;Kr-oAjmuW+?}&j-Zmrg zf)^q0{W;U;ucZ0`3FjI~#5oDf4Qs1>4jUxr)h$-r;#xtKoo)1@bO4(rBjgmW~-;R0DapE3_P3|_)Teg%|({yO;BMlk6)ID zHR0mqzy2R>vYGfN?EgdPYS5DK01vbVO&Tnf!m2@!GfS^(!5Rd#2d}JzHApUE{e@rf z9i)zT!C&_k2Y}%>66{0p0qHzb;k&Xb@CGSCGjvmEE9lZ`pY3*l41RPwgbCDOH%R$} zx2c_RW26z3IR}N;Gaqk7S{|l2 z^V=WhWUP2w7_`@fI~rfX=RM}GYP0@e4CUF}hui|Z_-~LB)T={p9PnfP2FZi5Jd6#O zREO37SwRNV@m?$t^XL2j)cgOr+)u@^cykj2)*3 z3&V-{r?))H%lsJ3^^E0tyMAXZ4>>lnrQF{aq=V>q>%Y`^fmUx1?J_Ye-gDg}Cru%5 zZ_gYNYJ(Kf-SfEw@_uwC4t#I)2UX%_Q6d&e0Gza~E`z+6rN4-7+|~;Ec=_k{Oq0P; z$B}AV4Q$?q&XWT_VfD_TjXU;xmT#>RHt%a@idK>9n2$G_M>Wp;YFk_D0-p*4ne!5J z=11Z44iiycCMz9Bv3KZbemnh+=MjfRKw9r-kHY_tdv9`|LnZSz<1bFM7QZ(QIIxK2d5`)r zmWRolrk?V&|GxkKPkCeJUtkT|LRW)G9yd+V8sz4#E{|1%qGa~SvBMg)(P)I1x`K?g zt^HsP`+tkyE!WTO+yLy>U0CH3mk18cYYmx!{lC#UyAX;;D-fTno%BUD67;p6>aMcI zu0dUILrm`FjFEb2ow8kVm?o|cT|u|&uD_5Hsq$jx-Tm+J?< zM0u;OoR-7leXS`!m>2TCMDf$6@>YGt_9y`I-kw!3yhwEe=7^gCKCOUjPgJP!+-ip!fI=+7EWtQhXWx-e;qFU9@ zOw#|XAj9Z*8?pDDLwQpQT4k|#C+OyNi9+5k9UeAR-g(!IF2+ONd%p6=NH+(9hFkHv zJ=YRJ_qJzJxsbO=^&y7{|5k93xa_WjA{or7<8U6f#OD1*`IoOl>KI9ZHqI+C=#d=> zoA;^BNoj$8%*T6xmPawp{8s8E=nbA01~x_gaXVb_c^{8jaeQ`OBIWk4GVe-8PH(Xn z{r1(Oisg9|92m^whB89Eg9H~Ro9K8iZJu&Ld2<{&EQ7`S+{xOFa*+3nec!fHd5@i5 zQCA9iv)7jnE_M$D-bZX+E_s#+BEFrbY=FGkujU_1+RzG$L)N||T_b}Ceh0#~*Vw%8 zI-G9$lrl!zK^ym~&q30=7n}Eul8tK~`Y<2wCR!eN^Rr2{-8nZz7-X+jDJN**^A@ko zNgO*7M-d3KiHqaBhr5`Gy`~}Q0}NRHcuPj};5JAzA3OS|dWX{SHY_Abp}dbE8>F## zA5@e5p#phZ<^^U`c~32TJJAh!+blb$GV&|{EK1k-rp2BFkb{MvjUeyAJ&W^AH@1TF z#3(I=dt{&&ow2ED1e^EL>h(E4VD;9ajVqmC8(cAp&07UAL5i7>_i|bub8+VPIV*~D zL$xr7?5rs76vXF!$h=pBy#n5Q6E92d1o%&H-Lyvb>^*Uhn&9Yjgj?)g zmOoFt>InkU&iBXJ*b;$8;rRh+Rd|9ldHUfJt5#4jSZZ7xvm30OE4TL3$zaS&!y}?n zmG{+g(hAzR$KA3n>h;+D|3_7)Q1%?=`vz${Essw)^UHKzzGzVpe8f&aM@UZL6XxFw z`tKHZU`$dw1SPZoN5PycLT@bXF}UEuzA;~iJ7=lwfWDt-9SK1!y+oy2uB_?KA1s}oyR?)pFQ z{r>{S@)#Nw zX^b{*W?I!f^&U3w(zP=pG3m_5+ntujS)BP@YI}Xbbx;`0OZ@6}kN0&uG#2Il;T=xL+qlPz1LbY?EmIMTchk4w zh7riS>0n3;J?}*=pOI|J2JrvbyVG#0-Zp;tn<$cDo1#=mhzwCO)V_$MRE9D|8c1d# zLguNc&?K3aq#~5DVj=T9G@yYJrDP{$=2^SezK{LlzkX}~pBK-w_i=Q;(S3Iv$9;b5 z)48s5jkkv?f)!xi5qch>4lwWYWzVXkjp4Vq{#Z7lAL9eQ?h)B&RfK+V0%}xY>)9|# z_>8QxwNrR&riae^Xz4TXfsyujS0Xu%Vbo_ZV>Dep2)`ih7+0))CpK?ph*x11%v*rT z;0_lxUvIhiU8d0QF5UCSy1C{o!+WJa(H3X7u0s<$H8NG&}y$UmVN`9 zw^EY!mE~>WP{X34n%^_*y*F;(5|zN+>U6*N#@SMrBblLZwf3Wb^FMi3qv@aU{O?22 zgZ3I`&yx?aP5i5+(0b6&sh6X9a1WZy=Bn8V?;z9p8F8cV{D1I6*O1n{9ncZZy1(>w z2pG#yba9X%LhDr(SA}eaU$NWwtf|`B2P8fcb78%N-h)I94(qSBo+Kn8>k94{xQhv+ z_aKgb<1@|&Xzvia0m*??pKpZTam{yl&@2kE{C>6lZO!%*Lvi}}Kz`QMv@_a1SDQZjGLS3{C$yuaKyyZ0%~+k7zU3yJqi z?{_u~@GW-RS#PPv&)9(#!_#IPR)hj??)IM>Vcxe^UA^~Ar5S`~Oy+Uu_y7Wf{I!** z(0M!gwr!L&pCs%+*3EW5jQ+)i&YSCcw`{T|?eTU&a^NxQ6TiuN!v>EB{+g%v5ME>R zKEOT~^yWb%D_`@}tg80hxaWBrgiyyT^{-Ci8ae zdnSR#+o&@)qY~yV`%;9Jw1bRnKeU1m=3Oe!*U&p@2eQox-krLkz`0EE#~1kQZMwlu z`-vURKun1kVyfi>ULG365v|dA?}{>eedORIp#xcW6>^FZ;z8%leCtNglnU+f)<$wH z!>G^0&>z=gga-$1)a$SM}?jt%isCmlY;lI2#sbk?+!l04QRX%Fc(U9!o0_Gigii6 z2MP~L0$TzMM zblxZPl8(%EnVx;dH3BW>`_jkJ>E7*j!zi%sl-Q%7bfAso-J4%K;!eh*UOmE@_}9=Hb~>w?gOn2n z;>|$qdiS}E1aBa8VcJls0G;=zCmc4+_a+I#$huu864Z46gSU3ys#_U1X^;0Hk^`&0 zL%$gEr6l0jTV6TlG(J6y*}bcU4xXvky#m?fMX4Xuqhdgk=o;R8w36<52Z~dd4@-r4H%zMsl6Xr_Kc9I8^IlQAQc8abyg6}R zHT=mx1TZ{~JI?^~mh#rrdMe!vTqAe%cRcq7=Y#6MOLw93E}UPfIecxB5P_`YReo6I z7lhuuiyxh0+!0KByq_XDukd5uf+W4 z&^9_EH)!yb?gu0#Dsza}q_1Owg+j*rVMgfC9~+F86SS-u%ut6`{m$>IZ=xFECKxjB1qk!Y&o3k8Fv zV;-H_(nKi1+4uX3@g~5gZJ1Z_-3xf7oAf#Twn05K)DC|7xi+Trm0PDt?vs;9Ss5!~`4l?}aYCW0&sU^xQnB1dc z2g!3*_wCt3biaed2~wG3Ro!igKd0C)Eur9T#O20I=I!zJjm07#JV6kuOX=Tc)*e27Eeb*Y~C;DiiyTB3>3T#E5n${ykl~G6wr8=+@Ak(2Iid;^{$=7d&{%WJ=HL8#~SUL#as5E z>~sI&oS|S)q_tMK9lkj6<85Iq7d!m@KbDi%iZ^?M{b`b>-J0mU+xudBGvLQt4k7EV zo6PN7Uy05;dUV=Fg9fkvzeaLk)#qh=@_xnwH(23ufceKNY~Im?431Xko6tG_cM(~J zwV2&La3u5SDNZB0=Zzy$mm@dWxBSPQKiwNg!P~%lV=tMvx1GjjG~Pz(qy2s`?_0sF zze&8gB-+1jgD+0Zh-F@qI1YF3z`&;KoFU-O4W?@+VBYtfWkaoan?ZgDK~wdoH^?0o zzLLp^KL0CSi(ECwG({*t)=5V$gDzb~pa1tisVrDGPkY^44atF3pONQ$U0VPTU~(O- z<*38HI3ZK_{dYU-b?EnnDMDy2_RWc*FO0WFm(l;Xw~H&N%TXQl%c?i}-}Qg;tVYv6 z;X^DdMGvyr($h!kL2KY=keJwy;m~@}+$kMbDYysi$XWGJ9qvJ{T7D||@ch5#(RzaZ z5eM+NVaQp)DH!N)Z_yu;AwtVS?kp>)X#%}E1g^XvUhs?3eO~_@M4$iPAFz$_FPkC| zkabf6$)a{!&=0Y7A0(QY-q7Cs{~5`FRUgwS!!G}K++el7^|Au+6Z4SS{BDhrCsQ)? zHtf!7V*Lxu^*H6+c|R3H`X7*_sm$RkGqwKj{Lezc`|zUMMe-r`u5P_58t>b}$}(GE z-e1a0+ey4L>Nl1b!MwGs>V*y;Z~#@Gm{&=h3kLJ0TP|3_yszaFwef9DU}-!5^stFH zaDIB=%!ncS4w6$#i^2Ey6u|>ocRn$dqaYofcfb-H=qaQ<-uy@otoq_3KU9s~;RdNp zT%{IEuz4??wA=S4D+y}In3o=($3Dd3gx$J_gZt>7cOVaSIlil2_qucI&kk}K1#h#L z@HJ7mdy}3Zb&^U@LF4_HV0?WC%==xP>2DHm_0G5*PhsBbPtGX5+u;Btzw7tgTnq*} z0mn>UZX!Y-nO8lv>}~=RM+rN2DtUwQuAOKL)NYPu&vfD3Y|C0 zjBnrMP1@r@cntc<)x(*yiIe=Q^>rBwQQBqcw3wg_@E8**0PvbMH-Oa_^;P~ z2J^NgFtNKzI{?$Uy;~fUg8{*(OF|dsUH5+b_>E6ZzccI@ahK3}pUYaQ^xd2Gcn2Xlu9i;1Qi!2w)Qm{3htzP-Z*M=oY*J(_v1vDm??Oh*cT6zdA9{9Y(wK6H}Y$P zKFnKQ;szk`UVh1+k<`8Qqvho8@;d;rq9vJ(1;M~Y>f1~;eC;hHRk$$tdlO(REbKNH z_Xas$Utbx@pz}_ZiE27(Hbp2z*7--5R+n5u=PmNFHss53+T(o>$$?ehDXBsm4PG9w zvC(?TC0%UZyPSvu_3*Vf)uMJ*>qYE)Z=JtvyQZzKL-(7LjA`m}5c@tgwBGnP|I_r` zPc9Cg|2Zgn&^P*X@$2SX4Qhgip)L7kRw^nVYM50yD&!;M7#&j0KbypOL=6(jSGj}vA_PGv zpP{DSU}fp-2f-cahuG?|0F&@_(}cCix~L2Wb^#~!LoAo7oh64Z?eT6#a&TbOH{A7P z_wp-c-Fv1|pqCMWYb(o7KcGfq8#bUSm9x?*Q_aCkI7J z1_K2PzRW~9BJ^bi+bR9~Fz?#ho%gqTgL6u^x);`=^R5$08N@G}CIlht1_Mv0*O;L5 zwh+9SdtHY1c()=s4rA1(k-Cn5U+Z2`9^*RH|Pj&vCHws=53>* ztYoa00!6y(2X_WzpWebb>@T12{7(10aYj_;@cK=RFZ$EHms9XQV(EIE%==*FWd=0f zOS?-x2*bQBKvWosccRCE_8gdZc|OLSO=uPp`F(0Q0ACYw*@|Ij2KaS3O@#QX^$OYP)|8F2Uu*D>4T ztN-SITA4xrvkrI%$wSeDY(;OZBln<;lzl7EdQgf}OJ5~C|N9Oy2$1Ig$?k!5*6?}zqD-v z+tiHpp6~GnGKa!47r4<6vDt<49n5#937e61KYUqmGwaX~v9hh1d4fM^ZwL7V$$?d0 zceHJo)+0Pn>-&2Dz7sa@=5u12sjau6H9y#Y2##a#AOqdU>z-V7r~5-}pc8dDqSM+t zBxC;UAn_EuPgXTLk$HCtjC7x<~lXIpC__{i5l7}ylLXLTC$EVS|x1x%&JZI!Ip&D5?{*rS= z1P40r(-s{`j7_x1TNTNHRUebOR#V>;9{BOeJz~|x=DqaoVSAh1X^`W$%ul;EVDr8% zbpK{vSQp*%p5vu1hvDplF}=U1x40;HTVHA)BlA98Rm_6M``XoGOrK%i-j1qqB;I=K zx+M3*ybYVwBj)xxg5jOY(!;gz=7gJX$r6}%=F(@Ti2+SOz8qSzV~sb6_{1plWDK2m zweanrvo6zwE6BP|otws&xzKsXTKaKWKBPU~O-K%``sAi@rd`_HAU1#3k2pna-rY6) zLNnTF&^Cv{BA$LKE>7HYzR$S-72Wg3Wm1{r+_w!fe>W$b6uhmD#`KVRU-OPwhQ?b) zK>f!E%=?UITqTLOcfVAl3e4O3hjgbWvm>a9SF92y1_Ae@rO?UEL`W!je6LPq69`q& zA3hE99@{>Y^Wi_b_pN=ct~<=93A4z$vAWkUOxL3GcD1OFvb;ijyi<`JSoNv!37-$f zbA#+Gh8^2DuzCNEe?1rjUwbqCtR?V%0DJxyj(GlXZ)q>x@4bC;smqbWIQ~s0_TT(Z zp4DjjCp`ZPQ1l?@ReC<;9_0RYFE?5b%H_NpauM!9`;T~P5#SyqLTGs^2KS)rEIW&( z9Gt;TapL5;p+IoSJxAi> z1X)+q=5O?H7JdFdZKG)sSx0;G{|6+;8I1a*yYJ)|EXRZL=5m==yMAHL|K(LG0kSpe z(00RI#%YgQ?Dak((#+)obbp8qbXiMPj*HDsH=Aqz3`i>}csqWa`E&n2>Gqb|UM@Tu zZ~oP%AI8GGgI~UL{=-{X#zq0=9a-ZQr7P|X_I8}*S&It-1sY3xhm_zCq*rBo-`Lm$ zrtJ=`x^3VMp6-qD*7=V^tXf=RTdL9wp%ht1h`Q@9`4OG>-kuNNpQq6tZ-C_3k5Qk; zr6DVxS9ma0kfWr!8Jl-v;3KJ!>U7ALyCgtngo+(x&&j<9m%7nCZ(KcB43$UVkN?%pD5?>W(UFFt55PlI`vTJqi^@xHchg{lV3ySPHADe{dISY48JM{89O zc<{^hl`PD=Ft;<$SE&iCSI!GihOZzU8oi)({|)+pRC=NQi@o3s!30_NBy_YpyAGYV z8PUve-k0`xzd&+WVAN-xeT{ke1|C4FJcqyuM=P>WGo+44gwB-j(a?|5}|^N$tD__O~7N$`~0M!H(1~BeuA+Bo%a@@ zjjMjmP7^jD>(2B%y1%gzowtVihy}YT?eSJYa%f`Im#C3tz|w~Ydw;R1Zy3iOkODs} zp6`Zv`xG*-84x6W;7-yhAU9 zcND?Ahiq(qka(wAYn?j@^InzQ;yTCa1T>9i+>DL{fgi8R&OL{(y{#+#BK%XY3B>1k z?`D8+Zy^LY4@mT&^BxpQ8jl*7CTJk*_<0I>z*}_QXL?-qZ>iEA@9#(s4~+VZ^4)ig zW#GZHU!LOoTd;Zi+l^k?&yWsv>Gn#t+G2Na-!Q&q`@6d7e*X9MqAo{V!m-oeqyEkR zG(Go|i-YI?H55JQ3=j02+=DpeR0Pm^P;;?%|jV=x$r$m7Y>%0 zjc#`Vq942Oaoz|7or6J6Z`Fvegjxa~K!5Ha6{6tn)`|P`1Sx6$pQ&eB ziN>4X)8(TD%)4#L{c9xNk>3=onqc0Lu-$zLUKg;aFA~grFAxZ`8K_UI5+Rog%RbYO zji6#7nW)9#1EBPkcH$A}ybHPxcplv|OCYZ^9nIp~eGr}Z>zfLze0$kwj`vd}M-N7Q zpE{O%>O)*$S3;wHd3p;sAG>ttr*(AC8`nr(j^|6J z;$;2~NUJG$yWSm4BX@7-(;a+hyiM$inCxKQ_X+70B;M+5FCPDZc^|rbeoOp-GazWC z*v~!-1U64TnhLbux>2I5+Z2O4j;oi`}Q<}E7ODgMa#9`ugG+y=Uhy@QnW zQmDY;&(S^a)PvOJkkd>0$#Uh-+1phVyiYriSCDzz2d46(@z!A(6!L(1yF9&0B=Kh3 zaF;;<9*_*)*mp4HI)hcs?(1q^27<%9>+H2uh|uZ@zjbwsjezs!Amep*AHYx?x5X(Q zowuEBaytK-SppNXE>BGKPPYd-@3?WB^}1=a$J+_Xk%&>>`t_Z+ru6VYWqI?7>U3=0 z&)q`!RAJs%JUq5rt)pW8-zjobje(c$2P7Q#TIzDR^nT|1JO2w(@OIhN`hm>*Y>68W z8t?F>CPslUZ(Bx=Riyc!%scu~PKsWpGf41y^(Nz0AaE4%;5n;Igt*o+@$hmq0i|8b zcLi5?19^wwc}Zh*-oKu=tXO|$hMh zN2Yo%VA*|~Z@>ndx1#WkV?t*$An~pv3^Mh#*qf7KLX zWrt@>W`?^sc9G>fmsv4|!oU3YA6okpfaiZviXP;>2)U7akZ`@sTC^U->;BV+2kt@j z^K60J;U1LfcJuTBcn8_K>q%K%kqgKr94-8@F%Sgr`W;oPPK5LywqAeg)d)JWPn-(y z@dk5Y4K29x|2PM^$6F`mHUf44#T`-b(NRI-FE>U*Sgx>RRX~w zWgYt}K!jpG*e@5n*a#lur(SFC_6B=;m~Xzhh0gnStWT}omRZ7HWZk}4dx6-^=)5Q5 zc_lSxXm1CZf#krdZol%Y>l>>w{#JbltB zLifCJp;YF`V}2w1cLymZ(Rf#v1P@BXye+q{e@o&$l@rc)3g&IP z5X)5(?*cB(7iaI&4FrBl<*%yAZaD`-2BiN>5th(zHd82HQ0}`;<{j5-D~QIssjL6K7Rbyy%! zvTd4a-A;tAeqE_&S>6b;E#p7z^6&xuUXG6n|KszP4|tP!Tm5DUpOJOkAywH5m(k~c zfx@bN#WcA0&Ovgl!l;j<_-)9qDlWjb^ZCxpYq5E6x%puE*W?FKZ^o(2)*|e;x8VBB zTvW4D>3{xzL0t~RCl~B?Z2mX@)7q&2f2;?d|0O7TP{4$nD7gpe*>4a->p@jEyaI0+ zv(+6Qy-QVtdr+rht78n@gL(#B3>V5=fY0HH?W}$Q;H-9_h?+JLI`*K85yuB#AXPgk zxjPg-2f0@?@zNFa0V!DJjVb>3EI|QTCo3}UTl3Qb^-yBWqgV2H89VfU%=rJ~{}_hk zz^adJxBEi385bBT2$p8F9!Jedj&jFTWrIjcE);yBlSjZA`wEiO6A$T<346NVL7Em* zm*eVFo!M1?uONw2@b<6I?;`Wwy>UhqjrXIU>ty<2-a0|sn@PMs#Y*d)hj|BvYkL=# zx&Zm%$orFN0YJ6&W%SBjM93zrWcAd>Mqm^Ddf~GXe2ZPm@qM$d=)AN2GT+O#%@WA# zxGraEtay*k+k|b%rnQsyPH*KPIk4(Wf7`3%e2oii`r5*R?g-O-SfuXr!vRO+shUH&i@-Ic>BeiJVEAtgtbBhjrZwQzwL-H@7u{H zGbG;EbZtevNjpeqhsot|_f}E5!|&D<01m}WI8130Au;|`#Y==np!v}*LafspuS^2PS)OgveU6yn0MFe8{(wXTWar1a;#w9kBm4)UXi@CTDghlzRiymf2VR-_d#Bzs_9t`06ad3|Tk4a)p7|33T39xm)D-`qCcn zEF{MjjQY3@SDw0jo(mLzU$X7(JobRZde66ZA?6X(PS}vfu5M_7051Y5sJBDRDVBR&v z2-AbhvG?A%;NFxwTN3Dh{*R(E$AORMH^G~ef7k!X(;5x`gy;WF6g?W+4!3Dfa-+Zf)e45XK-h+y*S0#CTrM>xI z5Xn)3QQw@g&rcCqF0l2*Sbx~c3Cu&LdtL1sNbw1z=N>lI-t=Ta}=Iv%QB8kTPxscGMJ23CkT|Xd4JKa}uik>$Bg|;Sb(MfO6GFrH@yat{3`tnoZj&^f| z4rJZ2G4}RrR5qJz4 z0eOR8o3M9~GdFK<@SUXpH%R|XqAmyFVxhDA)jzzYD0qj!uURDXwl9Vx(0EsA>)+3X zdAGK;@{;ENJMW92OEB+o;O$U3Q8{Sgbl(0N;Yon#5PKzqDjAvum<)K|S~w4(n$ z7qHoAeC~V?Ht*_CDW%4hk0GHtoh>JRP;q<9sxAEizenl5d*i6hA=LIj`tRwjjTF3t ztxaUeyj4dc#nE`**=WvP2J=3DCSVtdcZ-v{&{ddsLcwq)KFbAcDcjcZSu+5vQx{(q zqeFx^CEvY#Gt>a2(y9yhUiAT5_nLnHa6!L8S}<8d$WvjCup3#oIM-IU>mK^%q){>} z`QCBb<1K{bXu_y(;_Yj(y{EXq0rncpV^^?wZxp#XC$cLKI_JrZe^yeDxtYOf7KLwf zaHsqEAGedb9F{h(!$Z^mbZ(*Mheb8M;0A>UOSJP>;Q-~3O*WB>n3gXjOv6g}u-ud5lk2l3os zlSk`8#_z-0jo==XWcsO11@1v*J0$au!ab<&a6e2mW>Z?lJl+dBU1-yK6m+EF<&;Kl(#ktC@1(0gc!sFsD>;Vav)*l2CedvD& znMz#_$&k)2xA8$GI{?ql)P;B0k#>~n;=kuYqc7|iy zsQAS0HCLNpi!Xh2&wD+UIY#812?K?Hc93!uyd#3Ies!$-z<_zFxcH1em=|K^`FsF=z2#x~ zXc_kg;4*K(u2td#tX)~W^^DMYJG-3^&ptX&utnD0yzE&u>xkaHBVzTtDh4@dZgWD; z5s6XXg0zHfoevlMaiX%~E0);28_pFRyj}YQde^>#casD51=7Is--komKhXUJQjR9- za_k;ym|cJCPxqFg;C)^YFHPoc8n#y&jkiDNlcfwFE#)x+*9+UdT(H*c_&UY1pVyo5dToT?fp4|4YF=zZi!Rj z9rUxe9CsMhodju*H#r9#$0&&EV)M=#$f`DidCPAUo4-xXx3~QF zj!$O)qI=%BFe-D@3r2|lyZ%oj6DUR*@cget(SxpZKd2@5AfL9SN@zXkQ2Gi-UbqLX zS{gH=3?E`AHLZ44TPmvC={IRKt#bxa7p92yQ~sd9!7=K}VIm|sB7RHdYCSlZ{Ml$` zy$={~tv?$|K<`0$8Tprz%jXH?b!smB{$Q&fcQH=UD+mCEE zam9l>d4%tJCcja0lK(d6Yn~^tsTM-7ud%AOiEg1M-AO^S{9bA*T;8Z*Kl~4T)OLVD?pg5A(P` zP)~S#hS`h=$t#IC1?JWRk@sti#?yR&_k_>RU!~~0-$Z>%PKcW)cp>XD&#bXs?~Hzk z{S~hfs+U81yk8+Xeq+?P!>Y=|X#*Y*N-wjkufgUWIM%Q|!=wmec7Jf&^LZ`iKZn4W z@5j$@XVCqC6nKHU99l8MdX|5`|F?yLceG2T1(|oMTe2b=@44-1v$8PnpSt;bNW42D z%Eo75-UXcF@iuPGK)O3PqT`1@(EX-X5okh$#tQCj<8G-3Ru-T0kNW$7BZ{mIqq*q3 zWmQhDba9&}SRm{6DQl)Sokr*Va7J=(>}lHLy$Q*YgHd06MO){+<9JZYwS)cg4E7E( z&RU^mBBl^JzV>!vtpzskLFVI}@2ytQ{RPtJ)5oaFF=g#{Z2a%jTZ$CCqxOWu{|$#D zy}h-;#Z3W?cgxz%gK9AEZO=_SNxYBVo#7OQ=l^o{{J4aN&R`I_*3>xQ52kxf)t4F* zA@!!6TF<`K1B>gnJ^ju;fFKh0rMLi{_vtK+)m!(?6Ugf(N~}!%LeP1u=e0{MY^FWl zE=Ue7jQVCZ;vY(;;(>3I1E*s@HgA)(#WRm#-WTpz52lsXV0Leu<6|KIik0qp(%oF z^17On;j-%vpr774=l^T>)&$z){SnFGhfyE6DnC)mg$EV_(uc)Mv3Wa3e6HncD}a*g z;zmRGuy1dvJ$XF4y5E)VHz!(D<|wH=pHk}l@A^M^R-@^ka1T?@1YuoDs^!NN&-s^*Yhz(m5BI4l{WZ3#Z}DKCR`Qu;ZP){nwfOQm)AFq>A@9OXPIY z=)MOX`$%05uSot^T^IhmVn>yNcWi>y1M&{CNxNPZjkoEOAhq`}@2;mdiX`4;?zj9& zZ;BZ>a|c zT$*nOTzvpAS+4qC8=ZIlc4_5KsRe=tvhK6V#B^g5I`8ZoYWkx_w8#4~k|P(RzHirX zH#gPcflIj@p)eVncVCHH0C!(86g>j<43A;+-g)5D<6Afpx*w3dsm#$m8YI;U-$4p* zPLwHlUsql6zo)lk3QsDd@pfj>SDS`;8(f^aLgKCZGvEdb%$sYZB=XriCs4ZoQj@Ph z0Jwu2&n`YfgzQ&;{>*l$9yE_>t}in30nQ5Fe#U5`^DeVC);3?UKyX3U?Tp+J2X&+K zt`M(2_*I$qct1ySyuhgM=Xj9q&S@@S`kQObKqNNr_7_4PHoe8r+59Cj@hLUf-8*%j zyZzW2y625cp)LoXTDZ^t#6Q>nw^8uEw$w46+`V51DQrXI{bn|O%QDjZKX#>p#Jlwr z=b9Y&?CqvL!&zQNXP|D`BJ_Ljcx(^Z;UE9ic6a-fsC96ipTdR_$ld;cG;&7%Ludf-E> zIzt7aW zy#b)qv|TCJfe6{&ZBe|ZTnE&-h>&Nf6YwvNstR#aL*M_c8G{1g$Y zx0Y3V8de9Ea0@4LS^0pMCbkEdTG4qw@)_gHtXv?xLe|xt+j{@G06OoFT$RI@f6(3z z@&S?qt3J!1>PAjpJUHnXTl+*AoA=DeB8E2JQpoqN7`QEi-Mu|(hs-@zGSdBkB-ub+ zjy-FpWG?|8Yk0y6JFjw(hp-rwx|KRanG3?zm__{=lAf%7s+#=2W^~E`#^ZB+04|+>9%1*UoA7ZcFuSo730?>9CW{f%!;8dM|h0i+J zCuH60f#s!JMA3PlHY(=r-bH)7g^(OB81*UDXa2a^#RbCR+kf2l#O5vP`i8h;dpR^> zoAg?P9sB7mTwb`;i3mQr@7}m4)aBUx;OnpZ_y5iRG(Go|i-YI?y%as@{^R|*O+N9=37aJSWc}?0q{LYU*iKxMwZ!w4xMEd3YP+b+VT+*u0SH> zey%PEJxPu%s72QUhFXHb@5-s&Q~0f zG&uhwIfxkbJs-^#U4(m(>#a9{M`a2%C;6|f>!kbToBfrLvY~!So;~&s@{nJy-f*HX z-S;5RbJXR?**G9`{O>JxdnkBkUT#q&^R`S9#-s7}{nBf-6h6ed_l$>;c<+1^_~|Xo z`>oNpuG$iN5ItX1XXzUVOb%SN{^Cc3!VXACW#-iYyNTKj3=Zc&kmS#SN3rOk!6h$1O|Ib_CRH)3MIq_`u-yNh51@C*iax=)hd%5|n?E-;zO+!!ZIU@8y*SzUwUkw;-)R668 z>I;(c*tr{I(RYxA@7>NM!MxLub>Z2EI!c<*c}pC8oU33#d%T|@Im9vQ8@;OMV)TIv zB=EdC6|fSUw*b$FiK_7msC%MT?#omSX15RgB=~fX!VM%PLGJIea#O=VAe)(K z^~9S9Me%3FZsw>39C(w7bKJh5@i$|jq$xV@2mBi{%s6qN1zAUU*pOMuggzh@Yza9b zphJ7SGm#uv^(p5{Dw|8-!8_0Ud&`$$^X>wzdGihx(DLb}dT|QayhoB5Y=(LNdX&sUn*TR?eeE8DdHYy3 zv#S<50zRg9%f9al1f2$TF%QlXA?9;APQI$O;O?`BDg2G_>8+fSGdon#d0&_J-Ul(_ zfB~{@iLLlaxkdEuoxj9yz)+m_cwa$sVAa<>$|L&J3J;u2bO-j&V$c7v4JTU~Vcv}= zKvn8bDsFFiEf#sngN5$*-nf@k=5SfmP=Yrn|Gxi6p4MpiCp`b_QS_jkbbBXq4=P)& zB7oL|&UU$RWyACT;p=mOTi_m)<(1)`W&wYLWMTLTG28|yTZ*65xeCw!uMT-TTqHuL z!k%t2_p1gmQg<^a4Sc~v(N5Q{0Q3Rr%d+<`*jRBO7g?wFjZrEy-3)c7w8}D0dDj^2 z^`HSH$4ZR)d?$ZrUC6+Lqu?0NS4Zqa>?z*ojc2W^Av4>Q4d&cboP!+EG)xRuq5mHA zmC77B+Y;jbzGCM91@A}hjhSTLQDEsxG~O?^KEC)I=B<%+I-A7%WZZA*-!Sh3>r87) z)=DEyRC@8lH%ETs8g;LB;jNtk!1)o049KS_N-oT zC=p^!%xY#|Qv=_8Cv*4nB7FAtM0dc6N9epS%l3)|R;izBtj8 z;Pi5-^jgyg9oXo%i6Hu6q0(+T-nmPc31y=5ibl<&kj#TD&(-bQIZ~mv@p`W5Oc>X^`(Sr&SZOq9%Xuv{x zEm{w{UhVe567E5EJ(l+r;U2WccuC`+Is63a(8b4R1Fb;6N7))z)j+VFm(}NeED>tF z_sjXKT@`S({*czX-xuu4DbLzpZH+q58|OcI`D_^u>_OIjJKA?|WvVIa`Zt$Hv^o5E zAc|x(@ykO9dFewm|0Q-DF^z_a%EzlV#jq{F;T40 zrT-q(L|u*p%Z@&SRzLet`zoypSTrsMwTt_L)U3_<#jWVP`*da4 z%$DOoIXqdt>>C z8e;k>Ts4+kjrz}?{BQhANwTr$jXb*Ny|j?J930|v4sCb;@HV92{Y2wt4ViZUTkC2x z-c?prM*cAGw_C5xlX%DEITy3Rr?);#M=5W~w+7-7UkuIc1Hsb1XKe?s5}}*ntxr0; zs(=BHfqxLcFF19a)g$j4I&YbCyvfg3;D7_NuA@^pR*#6z`~1*sO1=*5@s>t%gkscJ z$c8($&jEhCa?|~7+Zl4`o;OaC${eHGM1! z{q)u~6HcB11={01jO2*HsL$Pg;|D!yJg|Pb)$NBjHgBjt#&b(XHT148caRT$u7cd9 zQGc>54b(sRg8t|KrPSpJYW*zVk^QH8>r?Q~eRWTb%-g)mMi7nnlQ)4WNigsIXN8SO zytmx z9h)~Jfo-S=zV?>W`OMK8e&`dGHS!y&Q5}3Nd*tc9dzW9LE=SO)PvRE%<3#_i|6|FZ zf!~Mce=~|6^ejH3liY*m=QfF<^`NBT+9*8SgSG^+yjOsGPF=zxO;9`p-MjTCO|I1o5L`+LkS0Q`9N@o;Yn5wbgR*Go721yBnb`XPh& z1BEMQ@9fG%=Y8t!OHRX~MM4R(?pSz*rr26jRNj(@YHk_!(;n}WNRIUw^=-<@PfnQS z0(12~a*T14B95TN@Tq;aOy1yozld{CAM1Rp05T zC7~bBfdP}vBNayIy!~90S;E(` z+*45kJpWr#^q`6hJ6@4{&{?Lkzj-)sd()=H!HSl3M+=J>Ke`RvJ zavbdYmJ?A@=LcS%GO2RShF`JkKJoLeU?teRM&W>yzc0{uYO`neZY$J*$BVs}Khb@W zpoOfFDjpDyu4a+G7#_n@Zqyxs~tsMT!sUh@dM2e}_# zlo1@LgG4=TRQ=kh=s^XHXLHxBr~moCh{_y?=K_%{NJl7mmm9QfBJ-{!3`wH#7PY$t zUc$WjzpT|J@g5n7Xr4c;s4n~4{PTlz$3eb1XS6h%KUj#|mM{Ad{=^QqxVO7$B{(zH z5h=^+2kd2fv)CHYc~58xGG2~`U$KL%Ta1j0tDQ&ZJu%FE;i5V1@g75RjAGQ6Efq5s zQpW|%zaG94b`P6(Cx0blpiUh$#n^PDgAMx>J8q{=<;q9d^v_$1x*VR{Sc6$J|Lh+kcR|cT+;JI2vy?g7UXtFmJW7^D!jeI>#oh zT43H~ntA4IhmM22Tq?WN^8G>JQ$7EC8Swr8nVYiXJ1fEa57h%l;nQ1!CGUslh0q5i z7V&K2Si>Sg2wAt$BCY#~D?0DI-@iY7+Dd!8mm)c`FzOpl8w)*XhzF^sHnOiz!RF00 z|C8bKKrJMg7t`27&DUFEmr6#jUPk}j`x=!wToh_ZH%P;K@52^WHr9o5{X&kr0clQ{nlrQaJ#fxA8(}?uY>G@s>k!7-G~H z;25^tni&tq2gmk1CSdbk$uyO*#<&(b_3QJoLmRQXxAM{cSE(OE=$`ji3+i&nT>gHS zIriW6|Nl=1&HuOmXK)X)qUb@j-b%;GJ!r*sHhHujG{MPS?*$)Xm#Fi5Y=(Q#U5$B0 zJ9z$oz3P^Qh{XxeWwiNLc$zQ37xwN8FD626b$)~HUFAS2`W8p}Za=V%?Lw&ULMMkLWH_1;*pL|VwJ%|g*A%#)jF&Fn|jPU#a)b>`zHCRe9_l^!Q_M+F+CcPEhc!*>lmA%sc%3 zds#Hz4^9ja&%?ZpyAH;ZcuS?Y2b;jWv)4ZUvT4%^VEBN0&9T?MK<>J;?U6zv)bO^i zd0e0ZC`OvITv+P|x+d*@eJ7&x-hHg>tikjGp&MCu5ih1-*^kcqwZ*cCOXal3dl!@7w=RhHV~>If;})l$l89HWUq#RAda95;9Mj8^{n94MZgwN}-}i zwp2)_42dSGl%kU|l%an6)Y+fstlxU}cb{ji-?P>^zxDZxx31N?-p9+e@9VzrecvNz zonmE~zW*oC>BCVyQ%a%qPyg>kgZKSGr70BeQNti*EW8ET7N{2>csuwQ_EYe#O4cLK zNAPYiTcDN!JA<6_58D^oM}aqSq55CS$uMyuebyuE9tcP|bHmg{*U*jNJX5-h{VyZx!< z121H8f-g()cxWpA_7>@;#$d-OS*EYvTFvzN5PkZ>cR}Kx?Jc`#@UAZ}S%>0n{AHaI z7T#Sil%gvTyrL9<6R_hWHj+GLVW~ zKWF16x4c$Cz*j9KH(5$Q-ir>Fh;awwZ*Li|*|%eMPJ-$2{s`0QV`0_}(`*0s|Njh5 z8TlKe|M#S+L9KhrtXG2_)BMXHYsoczq5UfsRRTM(QIk1N!@jbDQ_9E4@coFBmo zMh7GAkK@-M^@r+_(I(kUUxRoX=<_kW$!n?Z-}nDLXz*?^IAnq1owK1w6ASN`3zJ^z zBY4mIe&PoOZ(Vb;_hAI@I*sYaa<#ibP?+ZKC8_&CKwEeM>pe1jtH8Ot`~nQDsy3e6 zPl^PpZrwvYcG!52N$>3~K0ZfMp~lUs7Twa<#l}0DGtu-#1>@n3`iR8IZ(Do*ncszi zK==^9!HQ~pyzAec=zNagZMidk@iaY0?AQ)`xHp^6^mr5O==AaU!9%sb{l7a6-jBu3 zh@*IK8!FJi!h7Jym$pp^-q2j77-a;xL`>XwAqq65Qd7SR@&MjrUTMg+GtpnIoZbkE^*$6?bFfU9=)f`Rhf- z!+QzU$0eNn!oxfL-#H3`q~Va*&3EzfeqHL)l2h>rj@p|2>7plo^{y*+xITAr0n_*Y z@t5iIQF^q0Q04CiX*U|YAH9ijLGk{r5~hxY_X+LTT3ZC~?rJM73f^6p`8X(plY?Fd zBC?>};IU2i4hgnMkZyV|?~`lacEPjj&G7K}4Vy8nKT zgvKcpwh20BVdHId`qI_y#~BZAKB^CZli$Ig{iZ9<34&X1jy#vWgO7IvTejQ@1n+Pq z?W@O{?qd$x{uvj~-ZzU%`TyYUEqZ-CS5T4tTfJRr@NOz7`-$?(&fb&GmV)`2JbDyG_p zqk#O)?j3%u*ozbFGUpEZRsABNajfj4>xxfcFHUrPxb|e@2;K1~R|Ly<( zDQ}GY4buPn(A1zVry65Q4U$1FNQcwy30O7g&coD^H@`{@R78u{QyQcYVxdbeQiBH9 zK-K*G?m$YoydXv=0&soY%~{q$hUK(wdmc%x0j4Jc4EH!kfn^qC(yDqV%tyoKy6?AJ z5@tzq)VPMvEB(qew_(Qn7aN6HD~ZC4_EB%5`tZfcPv5zHo6%Y#xa?AXEVvoJ23-}6 z+vxf95&Tx?wS(dVI%?4GgB{Hs%zuJ3;TL^AE=p#Z+uZuIg5*tucc+@QJo<;D&GjEG@f*m(P;sv_4=&60AdaT>~{PpoaR@s{VFwpt>@czExl`dEsS z-@43ZF8_EUAnYYw-PVYYx5<3g1%e&O2-0Ur#?1yF?~NxN#5Y*lkUK+fgaQwQ7;%$HMj4l@5tx$J30U1F$$gYm3;C=3O_}0@1-fpgT3A@bPz_Xj? zbNP7@V8rUB({K|RZaSM8kd=8C`L~ zHwoByFTS(1<=Ich8$pIseaPVC=YR0s2jYDq(9yf8$x)Aww}PYlf6h{uBh=ZM%PO zs=~)xQeouut)xeAQc(SZeo6f8E&VDsJ2~0UGdR!C1@AU>)#!KxZ^^?RD=REr!OSgHO$+t?p!^a4BKC)5 z`1s)`Li%TGf&RP?iCzyQ0pF2A6HQZWyvun$K6tQcj>Joio7);2Xgi6Gw=dW8ao$13 z!yEPCjgz0$?DhT2H3Y%7T=?f=I`GcinkANs;4N7qr9AbFj_N(N`AETD=I{RrKj`zZ z&tlZV|H8lhKcn@c|7|`<{~th8gZi9z9;VbFO8;MEZVO@6pqP#k&yz@lbTRXMg9=iE z*67_7+=0}f+x?GrNlJNw`_0!sj`N2D#SretH9cf_u4lYGYPbqmdx1BzXCpz-@fnAl zJC2zByy$0*=JRPYq(Ew%icO8M#*eL-@#66gr$3)$yaq{_>O&MKzhSq^tZG3bcv-bN zH1{L^BUahsS8hvZGh95it+B(*eHcs_DEwVP@}t4~>9ou}w0b{X{hbvH?~&O}#WxYWzoriSpy2IyQEO2Ug17CB zuYy*#9zeCV^XKg?O7$KqzsG`w z_oBw+g8K;GG4b(2lm@B&a_Gtg1n<_LXEnoy+`-bS43$lH!-4dN(fy7cWLUw@#W5uQ z4tUJtGwWEVU{#Rjng|6lb>FIjkjm_mix!884vFkst-4u z{3OD9m#x@91dC=ux-_5S;~lI{IQeW@GaSEzbAif5{Ov9M-@VVl%QKlC@6j>(d~9QR zbovZ(Ksqw^_NBqQ`{W}%w0d(*r_aN}+pPCnN+*K%IiWCR3f{k2ciB+Z-nO~*-5zj4 z?%rle^_Jj?0GqZXyBujF!}q#31>|tnfO~5l5>!4!f&rcf`lqe1@wT$u+sNTOOL|3( zGqrZDuY8A%ck;N*i}baOhxc}>j|80j;&hKU+N2VJz0aa+o4fGwmLrM7*ATo*Ha0*P z7t!%@qKX7)Fk8m_n-l5vVY3C&Mg}MUp8x;fcHE5hL!<_U($t{WX3oda8q@@v@?zB> zcDD=;6Ql;6{RWv(Mv&jQ!pFmq8gzYMs*H527uabton(9?6sT;y{#xP{86NEks$Q*m z3uw&cMpgz#ftVccHQtsEm?OvquYcT4vYaMGQ{$3{J3_qXZ^ex7Ef(9xI>>l6NRsLU zFFz}d;zRE?5kX8Asm+r2C#Fvn9`kKEZ?+6I!^RrtquF9jhMd%?V{61 z%)L6TzYS6d4c@O7ur5UL-rO$6gN1h_r^{9=1n;?;rMoD2@98mLO=*yN4WSGDmR^8x z^mkelITUyh^S8vkAj6g0XRZ8dZvh31(2%I*Q9yEBxo2YxHs0zN7wi^0HcgVC#@W2w zvwaN-8}GFrNh;o*jEA=x)dyaFn$OkDH93i(@2ut%b2fauBOH7=p3i#>PgS(XImzQU zNS;6MuGuMjm+A2qo1)K$di4JM;$weCkij%~znI(}g5tf8?GqOk-tq1aPP!v_51#J{ zqu^~B75Zc^f_LXaC7+E=d%*COF8+I(VLPX$7yp4cG399pwoxPb{)CD)jNm=@8?yIH=uay zl;7aQ!uyb${8$KrxAcCa6BNAn9SZy5fZ$!?p_$5}xCbQUJ7)wP3V&i>l#c1x@D#pY6 zDb+^>PJYjuma$wGCIW>+PNd^w_;}xU_m<7peGGpLwiv0ugunhzuoTsEDqP3({XbzV zeLkXfN5ZR)|Eb=AGE9K%l{DWcO#_QnfuwF7;dd323-cWTv7@nq``FYMV{u@}!vG@WNi zqtrONqhB_$v0?ZBGbZs>PfHmOZxO1GpE&uoALy%GGKAorQFLADf3WuUq?G-|<^cTT zE#h_0mgHS#{=$D=}!C6zp7y)FAZ<-YaX6J4kmzlSxT8eZYO~gaM8FA>hMWBO%ZCWO$Hx?9iU1 zo1pwjan+hFG2nCP9?roId(1wUl;g;;HRC4F6dRsu<9#b8GJr~%an zUVh#4_Ph*jC4%qbEGdUf@EfGH?+3j#qnqKR#I2pvN%%Er)#p+R{$o;1|A^i9i9R3U z9)_{vf4A7}r@{N3(1KbNZ}KT#A{O4`^-b^CkVovBBkCV1c)x&-NfQygXD7KHKpZ|` zO>tfR!^sd}RQh_1?Hw6zS9ry8NT>pMnH@Y#Tp10LQVLH#3B<;GMtYZ|$IG9jWNKW2 zky1^|Wo*2I_K6cur7<4fvs52}IQd;sAJH>sA%YqUJpt+e0p6oV@7;sF@u#;~NG96- z>HJKO_p3GZ`FJ6jskAHg&j>Pt2JgY)&OaBVQ5HzMw+#tk;hiv?W+95;eO6fLHwEv9 zCENFPAtOkZ-eX!RByV6~f2sAZS}4dZ-B)*dkPN?6ExLa?s{+iWMRPSSiUv~Rrr&bk zVB>AwVfSLU!Zc|CHEz>`&n5vcvGLx%`IVvn0mj37C)LL`ocvz!7iH$ICxZ8mIo2oj z@T+$d7b}l3QoYYd+$&R}=k}IGKzE-F57XmKSWKsnic2?@|MvgkG`@ZPjKv}GxRccew07^OkVlP2)&NAUJNx7!kI+Y46rop@yu5(+}t1qYVAA;V=! zvh}fxE5Y8fWkS3kqCsYGE!V^p_Vm_;;m9`*;nSoHYTV&_!8iCdu>1d@m;+}%Mlv4W zc~l>PIQc!^^)jP^j|f-|1q9d1;N!iy;K;+YtY&!mIe5%S82{}p!fJ{6t7q>q{{?Bf z^!f1eQd-;f=uh^KzqBEd=k1yC+xB;$2Z?zhb4{UeF!t z({nT`6j&^-T5;($8Mb(IN}}L$C73oYV4e3c3Tz4r&T~=1##=FS)v*eRY0^e&oTA?T z$}Lma)qB-S1IvL4#_Ru4A38YsX+`F7c5)Mejdw-UHX=UW-?-Ec86slyrc2Z{2C%T+rWngTNURP4OD0 zuR$B>^pXBqQu19q#Dcd_9kq+f9+Pf zlhZpz>ZHag0x{pAbJ%#VO!;}qeHY{5{hR7T87IGIXKwKgL?PE(aMk;@X5r&4lAS)1 zj^I62TK&Vg2EYH0U6AtN-j@eVk2ir%AFaG~)%}#l@t$cDF>kV9JiLpjK7Qilw~M6X z48ei`a{uM_BpDxXoAu8Pq55X{r8DqWSckvDRdWAwrtkkhiPGmIJ)$do{om~^ z(KL8}fccYAynmg$A%cas(>96ZE(GtLk5mdNco*-Jua8FXp6ub@-B!F0#Od8X)My?8 zwh$*yiGC!*S3P3q4TaqRz*_F9d2%GM-88?N`y4jj*`xMLr}zFK*-_)-^lw)8z>#=|>@>ca~szl+N+J>p>{0^!3MOTNV6rS{dmX4p;dYu`TEdd$xS z9h?yK8c3(3<(VFDx_xxjny&aey%j}+_fW`bNfd93?E%7Ac)t$xAA5`7z4i@v4F&JQ zjI>Ng1aG#ESH{(5zCh|nIca}p2uP2UD7ZI-oZfn-aVV7KCg@Y@lP=DU1_@FD`g3pW zFn=vsW#bR|Eq{^{sd4MBsGokk6TAQ49HAS|eU0((&Zhb>!^!W&*s;lX5E01iw8<27 z!^b;j`SAtXA8BU%2$VJvD1!eb3FMhid33fkIoY;RB8*k2K zCUpdtNfH`onC{7?_8S{-K0Z?KwL-?j8}-41lb@)~l-o5^L2xj&crNEFKHhrP`72xz zydy^LuJ)+IpJFGpG;A-s_mJryv9Waekf=k3c7OW+R5lvCzqEC&M)B^=Xjp)Sx1a9I zVSfZ~|IFp9D0nYiqw~!k!8=3b>ek^>f57=-Vj|Tp7~I~>u|JqhhNnWe{Cv5*3|QpC z9Li~tfVblNrtAr9yfrU`MwVZlB=J$>iVtLdDprkQ%1x^AR`P^4jCi z2I*8*8oWpIxe(SMHmZl z%-W~O^mr4#)9E9t*;46G|DVc2gZGH<=P?v-?jFziSa?G#ec4YSc*}~dx2NC@F9_@n zL-5vkowGz&&L8BJ+>rm)7Yru(1~*HMlHuIEb^2u+%7KsZSd7oADB%CRrjCho%Nitte_o zYtXTtrE*v`s3Jgic6PSJ;60~h>k6a>hHCAmJ-2@uFo?D*3+0iQCqX$@9|!H)B;y4=dl^)FC~Q*PmtlDwDrNqql$s?yk%vnT+tvM@~`H0 z#>V@n&ET%Ypb1hMHSUXy?n?JX*!_R_fp}h)6vo4Qis}O|ze4+*GM`ao2k9=)BNH3& z@lLx@P<0H!d*|Ye;A$BHULi{j13UoVS= zcW!|w0DM1it$30Y1X>1fwci>i!;@xBJeTq> z12fZw{wK<#!4gBxHh&fD{@>S~ytL`T1ZgofZf@slVe5Eoytn9EY5IjS9^T$mA9(pG zM10=mSVRQ7vh()~DB2Bu?!^ro++o$HzZ{QuaE^!a$MHg9GZ zGJ-^^Hzy6=-;erlMDf-uII;)}?>4hM3l#+K!{x$L6ufnAe`VJ}8l=_Z21SwE0>JUv zDAR=vLEw?cogFpb$uPUock!s^E1>TD)k`7gqk$Z0Yo5+!Y`pi&Uz_}lEKV$@#$8$@ zQ+2Ex8}9_q?)E#o84vGpst>&Uj`**R~cyoFbuE;YD04gcGS}7etfM4fTN!2$p{N<#=f_I}OptZekb$WOd$WrN9`eYe4 z-f^p;8kNKv@>4+A4~NSi<93kQ$uO(k3=AG{CDy#0erms z-?~_^BY1BcnBKm=ijKvJlVRWCtIWUupKzK^A0h29<@OeCq*)nYts@A06L=@^RG>+q zTA)NAS0G&=ULZ)oU0|ocMge_+l>&#*YcO~=kaIoALb9^_u{wb zH|JO9m*W@X=j5B_8{vD!*TGlMcayJx?=)W$UnHL|pA(-Y-&#IxJ_SBWK3?8mykB_- zdAoTVcyIGw<~_@Ml>0h&KKDuPMD7S~Z*E6!3vMHBP3~pf65QNevs_=e2Dm!89&lB1 z6>(*8rEo=a`Ej{$ZRaxKTE(@TONxu1i@^Df^Bw0?&L+-k&JxaC&UDUr&LB>A&Yhea zIrTYLaxUT&;$-8PU}M*dW#) zte;q4u(q+*@y7B7@VfF^@vi69<5lLB<`v{+;Th){;(5l?%u~a2jpsbiah`)bAv~Tu zwmfD$Bpy|s#XKTB5cd!6PuwrK+qmoa4Op+U=Cht;O=OK=^=5TswO}=3)nr}9D#6Ol zGRyLXWq_rVw26~4oCy^aV&|6eFz61TxAgUZnLUurJP-P$e zA`u!um7QrqEc6;xwhF5%+SoP%o-1GHoTGr>NTEu|)#vL6y1krrS_Asy55k8bMvC+SJv@ z26dupd8%DCpWj)u>v@lI;#vp-TCQ&jsi4T=hLwt;i>MMh+O`|YLlx1r*BH8hDnZqt zV(2`o_@}iVLFZ7#*Y+U+%0(6L**n{y98~dm-;##TqKaFWMH9+K6&DBlYbXm<9R2H8 zL1$0}oi{-17uFg(|jn4eHQIRIw5j%b`qE&3iXl31y&)P-%D&Izd(PzvFI; zLB~<`%W6#*bPQE<3opKa(or?@p@RoXL)CP3!e!_vs(zl`$PT5V>W6JTKa_$h%6vPN zj4I0XB$R|I%4`mF1XYyg7fM7GrB{FwP(|6b2OUNgWs?(h2vw9lA<#ioQI^o51E`{` zI70ELqP+VD#i5GwsuUE9D$1KBPzaf~y5CcYV;-vF&u@WUa$2G=r-B@jdm>G^!%jmo0#PqAFZO$QAm5s?g7^DbN(ELaIB? zLX)TpK6qj~G=ZuhYb|kT994mfbXcM9sPZSrlAv#>^6Pu>1R6utzN3#cp|7a&-T7n! zBBRP@W!Y=!3suQeZn%bgP(`^A81hCH<^EJ?FRCclO+sF%qTJ30?Lk%Ro^mV56ICq+ zhb$luR6Q0uBM!Nv>d~7R7sw4&O$B9NAy-s2hHE=RyHVA!A=w{tLDfT132w+4Rrd## zrXVL&)t8s7gLa|nUgDY_$Pra_TicW&2UNj}jn6>#sJcsjG78zDs;0hu9I{2#oveZ` z$Ocu_wtUvmPE=JbK2;4_qw2P}-5baXRh3VQ;-DR~yO)udk&^A=vFg(=& zS)%Ityf2y1R#cVs6t0FWP*s}m4BCXM;_I8sppB?1N^R4CHlV6-U0DIN9#sVreZ7z=s`9^@e}YU%2fROLKrKLZ({>g;jn0}wz}wnKtC zL_$@TN=F5>234o0POC%us5;d$)D5jh)yeGLmmxh=WxBg>gLF}qp~w3JT7{|;karfO zgQ{bFmm48%RHa`?ISOf^Ds5lAJ*0`MqZP)} zkA5dTrN)^mC-Iu)Z^Vr6)y)&GSt!A9>;LajA2|8dTud)@Od^8gUB_Pxp2VMn93J1e ziUn?kAJnJbt1rgi|4&%M`sHhG1=CNl)9d5uhP>b>*Z!;^3DDq88K$Fn@8cLyz{2~z z+s2_v1aJAxhG!^vpOn^6kwNf2eBttEh429I?(z2uUt@nzUzB*D^CuZTnQltTK7SE( zZxBw~y(R{Ha%n#u7LSd0j`Pnso5Am-VQSnK%_`e(1K4=GH6IXDWMe$Mv#CB@aq>IB z@=f`dnGjIQd3M?K5I)`^4%)AerMAK%{BLylz44E?{C4z;BF{Eurr$w2NvDq^t;F)w zgg>vh@YCQ;={r%p8>Mf^W8uBz$${A>1n)I{+1bWrx#kQ@N|0tgy! zzxxAwVKG@Eg162Gcai$`d{B2V;`turcuRPHc{2AIY`hmmx;Z}58z-T0L1KI*3yIjf zx6Gn@TF;RgZ-G>X>SGg5eja?XGBc4xz<=*kNb&*t@m6-zbt0ML@7~(AUHIhPOcAEX zdpDgvDhdN@Z=U>9z4>VHrc9)ucz-WCx(o~NdY5|!&k?*$7rES|;B7x}uh$&Gn>3dh zLd**QP7D0h>K+7uHznmCjDL{f&PgFTwcnROR=AjZp9*rk<*MqgYN_p*gAJC(iY=;{ z=DxWdjR`4zU^36R zJD2q)!Rb65x3?Y~sEJX&#Qf*~9ir0*(WYqO-`!ihGAaKcFBEN5n3`+&=H9D+R2yTDBqb8RW z4UV&D2P$93##>eS&alhNandnr+^;)#q}wiF<1JqOxxKWG@$gom`oPOC?CXc7?m z{$KRJYLEhDZ3L}Bror5*ST*RL(KF&^qz3K!X5mPwK{_=9OWcqeWalQ4%rZX!+|lk$ zeQoUZN-VtRdv~iiB6$1l%XFjQ zy?^OK{f!9TuUY*Z9TfwB&4hq{)%0F)!DNJgW)?Z#vT(UpwMI5b)=Cq;wJiqZSbJ>xhg1|av7pfmHo|4-1P&&Rv-HX~YpE=W%mroo%CdX3_3 z0++17!rRmA{ib~g-qkx|d?Gn4GOy$_})4cfoKjF;LPE8LXrtkj=S#NGA3@=XntN^+PkeRtz9NEtmBXv&0;1Kn_|7abLfYzEI;D zO;$b%R>q#ay)$@a7gQigVdezG{^R?B-0O0I_UJ_l=g_%;>@4H36TbG%Kjo0Z+=~KB`mzxB#DI{NAP~} zcrKQLx6ALSni&M|q33rRm+V6N|LHeNbQS!-Dw&aCEd=jMjmEk?`WJxMRPR#x=h2|N zK56>`FKoOcL%gmhlD?Blsd3+Ytdt}ivGGnW%-+|a!+3Z{P<k>V;w`Pf69=N@X>G3Ae>mwaFDk9bU-}Qecm;pfgf64!< zK?;-|mS_!ndYGV%RfFOlw#k2=DKYSH{Gd;%L6LW>?W&OxPu){N%;E^kdV9n>@&1y|C;278Sd%-@~bBd1|^|d3jzmSelKh|PA6 zHlpDD{y_WY3IuO&ZKBSeCV#;9YvKDNi(J8AVn#DJf_IdQR#<*kDwrKSW*!+A1Dd{$ z8gg#Neq}D}%9WlD8#1Ym8s~9=w^7|38}GPbpQ6y;j5o!8n(8AKC%+Tbi(*vAiNKO= z+_P*IKHjA#gfFc?@HSl%eLk`rA8*3O(I)wiub3Whx_!uN{mMdKu|ul21P$JlJ@6>r zTA5iISa=s654tRl;Jx0jZ#@NXcnh0p34-^aw@=ck9)Ixhz*mbq4sO8vjb~T&FEVVy ze!1Rg?JSvEGPgNu@5jdb;I(a&Mc)_? z@B36A2XOM+B)?eScLfoA8!`RZBZ7~&+#PSDuglxvgbmmH?Hcj7x9s6{DYE^&i|PA+ zSvq~3em#JDRw1=x7UuZp$V&VbunJgGk7aPkX$Vc%ZoE(nU3DCwsQ(~q~*wo#QMMflTO zldmE_?73jd^mt#V(??>Bx#Ya`KmETL4c?Tulu*3SHX5j5;T@E;uWB`dH|y$Ilc4O=&9*DQqro=U4H}BS zv9GH*bguHKn9RaHb9aP8{&O-YClo~Wsv^!k{IYBB^QO*9Ctv@Ka@I>vw zd`Gb4!S0j8NP{FMV5i|eq72L$#*~km#R5%kl_TP-OfmahM_Jj&tYM!?E2(km3G#A= z_psv|rdR6^vd)JY?ZdXC`nZRapHJcg?@S{haKy(-#O@w`4XPd$k7@mZY>2Jellj+`;sC6Ex`a!SR0jcF)y6Bglm` zcvIe_NAaE;%FxBa+xOHxkGlxor7HwAD0n*v$Gv}#j3Ce1tc!Sa!XI!emS6w<(g|cu zaZR)#cz2#nJEXZV2w1DlRvuG`1?{GWhrD-Sj|fNdNyOU=M@bFTIQ`zQjo&%3{~VT% zt$%U1pYiY>rutZflb>RLt^2+TB2Zk`D*XH`KHhRxiZ|yrwZS7ZuLpQ)@f)O+Q{|Ik zPnrMq7R{6N`4HC9$xr%w{=XCr-jt&uP`pEluB)){HX}SBw;_0kaOh}J@Q$-iKU;&~ zeV%k>p>>r%5Lz>`-;mt}Y@E?4D@E|$-;%nns4EJT^DgmhQi%m~C#;sML}M>_ny`t8 zMa+znCa7^g6E%(2YhdG@tGz@gt&#EYHm3T>!pYA^P?>kxPa@Dv*4%p}1s`weWoz!r zo3+6az15qJnbOf9@pq_m%xh=<21$@kAKA@vlm-bIdoQ5Dn{w6(iuZ=|YC2eW2l5+z z7(noLI>Nh(7H^gxOV9V-K;GJl`+lTT(gpBz9rr(k;QeYs>~})b0r2Z1khc|#1z{V% zec5{k8}Hw%I%B%ujFSAQaRv}^@eczDlJeJJAOr}U89@1j2ue0sun z@zZX6yfy6OU%orr2J`m7LoG|1aL3-U-8_OEL^MvVjc z643Hd6U=zK1>HO{{EXNC4^n+>$I0);o-+0yJ4At4rI}l$<}9X9lqIXVR2PnvHn_Lq zL`L>{{8#J*@AgA1)4EJQ#qLX|kG-+Erv#99kPy6=(BMruz6`~C>uyG$PX@dzpL4L$_lWag|+ zEO@ecm0H)7A?B~~P5)b?0QC=~7HZt>=Py3j60rM!Rf)Gtmh~~-BlZ>5haygX^=Yp} zeRD*C{N$$HHnRA5r`11k?n`ci6IOrz%I{6b2y)zEbzeX8uOJcV^&$O|e~0g%5#(YT zyea4Lp?JF`kFa9leQVbPT{i@8(LOhI3f^CA%eNjt@a{L%sEcX!gVlBN8noxE;WYwX z^>+}wi)RvSUbXKBXZQMW%RGz)+xD<`9+oi1#QU1eFS|y8kEG4ixQW!q?xqshc=x`4 z%_&vIcz9o-`sl#PZ$nf7OZP`npf?fQsY}KmL0UKmD?u+>;i7Xoz0+y!n4cqB?Vl~( z(fnrdQ>L%p59#zF#-E=vP@hYw-m)}!Qx2F!@wWASz=DPM%@6T#2!eOSeXc*Vx4YQ< z1$H5LH(5dVKm726e`r0e)X%bk)tqySo+5bLed_5mTTDzL3Xwc)y|g(89@YZm8QY;x`e9R8QU@eZ|Ln z3l;Ck^8>r*`QvYIDLWH9Gn7%s^myme=_Bfu%wfWTKZ_HKXz-?-n2O@fqJC^17T(F? zjarEa-Us%E|5~31n+0ODqEDzoq_g1 zZ@8dOEU@GX)%&iCJ(ezJY3#MX_K9RhjT^nM8L;dkHs0y32Djs-8E@=;iRvQ>C%-Nu zzeitVi9q@Dp2)CQ_;|a>PAnHis&~d@tlscr{QjRn+`N4t#)9ele|mig-R#_HedXW& zAANc=^jG8&t4LFWC}&2aHE3S+241WhG~ec+$GhnggG6^FGs*~Z#Nb1VB~pXNAG`S3 zuJeOgYSp#(%5H&^J}&=}IY$QHQli8-;!cB5Vz$$hRk2{1^jn3_mQ|RK*zrqcnQ!+F zl9o{8nx$GYc1&W|EVjMZa=fx6VMhC`$EZGjd;RD9#D7aAoZTV{IIe7BDLakdAX)hG z##ga)z+5pam&M=0UqSLa%ocRNcM;P+Vz(vI=VPAL{4Tb?`~MYa@TMGsj^b_hQGy2x zZx7bAWm5>=L(#8HD0r_;yz$c)!COkOCaq+vA8ZsjeK+x?1swON&7Suc8Fci{jaq!q z1eM%u7fV*gf^|-<$){LXW8!TfF439j_?Bcyjl18IU*9%|jrZz_qBTCd84vF@R3BP6 z`Q-+0xU}TBD7ZCvUO4tBKHl$-ot?@<@Ls5@y!i7PI{N>f7xZjegNgSZ-`OsU9q&ke)VO;dH4YCs zu}6^Lj;pY)I^*H(LG_`Fli!0+SN5N=5Cu*HU&x1|@$uGkk=^q3T02~v#k+VxCqCX0 z)`w3#OwM5X>b=v3J|Akwg&o1)4bsbK@TOc-f#Q9(^#&&v-odX2YNQant3pqbDAhYR zs63$t!Q0f=^G=b!AFL4YnP*sbJN!X+v0Dd%H|rq(Ou}F~IPPs;_8G(i76(7x)#m^v z-cm&bwjs;+q-p!VajsCXK&&`6-nEd}MR69!!&{Q-;}%YSp~J$jE}a$y@3{?zzxd$e zUD;%Rz7WAX>4A{M=Fxi0&+(tZTF&a%HWAv)-yof%(+7KbvE1M4y_5!T%DpQn-frCo zIk50P(s@fu1;Km%jwn4^yvw)WQi<~QgD-6JI;pT}J8Uc5|5O_3|K(>xGWOM_fMY)w zJkx+;LI0SI`Qce?yr)9@9JWQiCq1FYZ8+v<(ES2?aI*fJ?z|_)jMx89P<&}AMX{@9yv`vWngxSjd&uA=&R4HLT8jQly)Q?{5 zCw-*GT@+|eIPnd;2A#=1^jKPa0nBJ0HK6)9g_ED_qwDj05=B7yy~hH$j6=AGL;u zs5?lNY4E1p4T$1B6#rTP3-8W{8;Y+WcwZiobf(~KyI1Y-V+8LJV;|vIEkAfwj>>4c zj0wy>+*0)x!F$1%YjuiZ=fSvYRrpP>SWw%t|H|yB8YbSuDFbSQ?_QCrsc~xuvX7kp zijB8M<(IQeZm-W6s&C;}qj(xCOTG- zKw!nv*G5d={}T-9^Ktu4LAK4`<1LkF@TOdLiQ+wbt%M&7@6R_sMO9q5O)=f6KIbajecT0?j1xgPR4u#ok zV&bhV$JT0dVt}MTjpNgLISc;7;KXiTLyZ^%;=P>e!wM(AWx({x=qpi>Z)Mr5T91#n zOqfk&2WJNyb?o@rvfuc4`)QkXTjyM6`s&@ViasBeRV$B-{CzobISt;F+gnk*`Aj1C zu<*8;kU8)K!P`Q5gCzy;&)MzQ^$@&=c6*W=kg+#mhv4V_J~Ozf_v?BgWbLiobDl$? z0CG6-j12eemRJy()VAVYmNq8dWzkps`l8;D!l`l2Z|6PT`5*9RtNT);)X8|$Ti2*Q ze#8Gcza2|77rqq`1=81Ntv$=}@zz`%_ zuj%tK0B?Vn_3!@we}4T8{SDIpYtYmn%Kg=74dP5Uk-(}!Ifp!_mmxLCV5x5zr3QWE zd-Nm>IfHaGsdcyK3c#}VuzsN@LhL)|YS-T8rkjk?Jtk~uOet!SAvQuQx zo=g_!zf%aT9&B!^&yE3uJ9wlkknJ2;fBFx_O8oWWJ4r97aW@q^hCBbm25He`|0#u~ zjEDCFst+Pgek^w)Rpti@gGFWbZ<`O|<1Hq$W%DWo@4B8x?5AYu=>J#7_C>JoV0yd> zDs=i_n@FPe|7tXN%LO`hpm>|Fcp{30x3y6WY=+={&O|knf_G5y`r-xz?|B|$-^U^@Y!D!w0N@U=^HFes=1e5zCKR7GBpe($6*I=y27Cf=e7DLRV}c9ULH ztl+Wp^c3A3X ztw?EOBj)FbmXFw+riJg;^fEo(v1jS?Ve#u$__MQrs<$c)-b>6p?x1+za=9deh4+!{ z+&#MxylbmE6DfFC6+F5%hu|&p(x=X0jUOyLWNMiup$_+5f8zHU!F&CL@)cW^OCZd{ z^2;aPSirq3RP$-TV$5HQ1J_Y^k({R_4r<&MX}%d3Hf+3a?gP7gl^G9jTdI$8ocv-> z2aZ>SHNRehj-}C>_hc{z?Mf(3$G&M;1iO&VJ1|`m_NMqF?UG061 zO+S$aX~8;{l}HV0vbne92=a)XcwBr!Y{fp9wOy!h+}0dCuQ(j({gn*jh?7P+(WPKk zwGsYg9|I~r3kB&-E{3r_9Jf^Y5l-kfsgfG^);*2meHiv5cGb(M43!MVn}c+w`q0A3 z@6smgy3Id`U{=iH>Q1R&n6(-Gygn1+BA}2CSo>82OC$>&k63frK;yhYJv*H?9=xQizH$?RTaPnKWHr(dWW+C7X`$pTa;p6?3UF($Ah7MTCUnS{{ zI{p-UV$vsN?#Uje$2-%OJ|BAD))0;y_%njkronspp5`$W?{yuI7hvJ-94~$O3xapO z@x0d*yvcI_czR`)_2BsBr3f$3O{)x_+-om^%iz ze5_mbvQ7vSZ&7>qpF>ygliaCslX`=Cj{?x`CTJ59sA(uli@rzs|qHX;b#OI0A4g7Y)OlAPw))jNFs68$AB8L$68O!X0jlV3BbMtX0(Ft}fRlu!GA zu=ci-&(+Zg#y{Son?)(2czP$(SMSxV^!fNjBB-p5&iMEKzyJFWixD-_|F5B`LF)G- ztI!%Ww@_9Ns|L9*>gV)CMvw}PqkAa*|FzcCPlHGe+P+_))G5#x-mN{N&+fAWJpW}m zxN4XTI5$Py{mgpvY-6U-@8r|^ARi9ss1>6xS%$N8rPlpAfdTtJ;3@1 zqbBWnrGGMB4HBjLh``BjWxsEB5>W`eKQv+#a0b6Y61m{&5t!Bi4|JW~vEefQ`ahvw zHQy`6nCWW}A(u`c-~3dy|BfK_Y4BD%_01Z^d#3EiVl2ERSQQ-iBY4l6T-rv#`?3vh zd>w-Kk+1L)%`#tjz=SRTbm%s)^7IkSho8vc%({>_yspvk z??;MqU1zkDYCloqwDped?M=kSTm9!uwhaT~{f_EG1t-7D`4fu6&xxS$P1tRd7<{}X z)2oYjBzM4H7OhYS(!rnJidC|$Tc~iI>G7`PqR+>&>w@<0Oa6=?SJU9F>bUtGig!q5 zwJa9i+V0;Zb|~KLI};XR;hn(arJjf2-Mes|A}!wK_dl!!8nF0mZ!ta?3r5P5s+{DylU{p%Dl@y<$7wQ=GtAmvfxdd?gbbsocR zkfy&xI+Sfrza-ouo#F zUtBIDk*RS4{?*YHsn~dD<$WAoo+F9*|6z^U|F?f`PxWyMCqLh;%Y_>cpu&}X&KgnfA%)PYKZ6Tp%+Y#H$j3?YHgLA}wg5=j+i^e$`a7L^>f_>xE z4W7c)9lIFs5z9^WQHqma|C%h~fXA6DaUdHXJMK*o%$#7o)9;H=P*|?^vpjPdNFV6bu(1PZtDo*BoQC$@q`h zqSr(z&GZgfwkDakViv#uC)f#O$%`yw`u;z5h&~@~Gj9n8OaJu$1~hnU+vldBc#r7a zmdC=|z-r;b6$sw`yanYHyt{v=SVtguN0a>9_67RDS3tTxSBxz<7WV#({yQ>w94sQ< z$XNmGYV-L?t7Ac^Eo88JZZ#&}0;9Zv0;%=2Xk7Sbsj7S>Y`lrDLJ!_|WjwrzR3E%J z`8k&EHh%U}5X9~57fS5M$Ggz}s6xWo4%l1fR$y}lKHdg_XT4X*9AtXD2|wub@rCu} zn@@Rv@CGz^YsvrD@fJHm4ll#Po8`q8MMDJd?@}wzQ1B+$es1MK@Lsi-!`O+>7oNCs zOVJ=>C*XRn6f*vv47mBY`^|RU1k*Of3%*y!f{*t;%cs=W9C7mN^2r-F`$Yt923;|QP55{(SA^kk1aDAj z%JtM5zyBxjZjsWetY`kg$wzbgd|0K%QQzJo(crByWoVC9?|`!wOR?}aypWf(9l=}6 zRyK};w;<{6`)OqM*0Hm6CS#2+ym7ker*7ct@5uG_NbVQ5#Q^R}G(QDRV6+7qgR)S$;=E0x5NGe{zH zVmVxUyx{i#!`_{TQ?XcJ7;3_w(HAS!?ZG z3O03EYY-!s-hF9k7If-mq*2|h2SNspWAm;tKvYG*WN}mju?M}73|mk$e1^rxIpqfa zS?Ndq%+i5pZdp77T!`QAfAnYeAAGY{xH@`K^7E|Tum~QqfX%z7lxXtN=l_mPtqYYe zdZDIz8LrL2==UIrN(~*bri&x{9>n5CTpc%65(Cbsu6@LgCIN4y2(eZ??@Y`~Q6%0< zil%yZVBXHWw3e&9r##D4w!yq_*5u}jaCt)qCf(=h$E?8?)qpR}&u4+E@zsqkl=XnG zUSu0EiUyiDb`?a+t0QvUGE<|dZ8V6*$5m_zPyC{S%$rLtWyfMC>G9^q)v*~RKb{7j zO-_@{Kv=lu$I3o#)=vfv4hkdSN-w~pR+c&5o@{W9}b@7hDQ!G9XT1fX3`-VIq9ZEQ9w5gT! zcpt;np@ov4Y@^-WaTykXHJiY)B%t%|6AO$#4|nfC@3-&sN{Bc?T4pT$dFvS2^Ty~h z5m!e-p04meS8opx@KzA?dWPp+kthk{6A|VBW`^E>llE z@P?B2xW;tp+JKVXi{?Yavq0=c>2g$gEl868d292JXfXZQqqDzL6_K|~lnm`%%RcNB zF0Sm!8#|E!WZv|A(iu&On^5@-6Tpd%qOdFcu7o@{`Z*>CRa?^}|A5I*I)!Ku^TSRfpVh-l5 z?UYQh%6q=_{i`i7?`O8JTi$v4K+hk0w-0LB0B@$d)Q?Bt*IR_krSMVJg56dcQXl7H zz|n+;2A8)gh`b~1eKpoQc4NbEai5oWx>58X^UmD-=8`7~UcHUR)sc>p->?1NYP%Cz zK-I&c$$2q!-Yc)Wa#rB8H`%?X$qUD!5pmh3NYC78V>s*bPj;^pdb|IYva z!I=2J7Yg?vU4kBT;QEoj15%U;jSNx`T8_}(BMbMS;;f1t;&2Z#+e-cQDSV0Dq3%=^ z?N1MgZZ2Zpsl)>83_GK$(lHAr+Ki_Le%%M-{cm>d_!$ifM>uuEHtQhvpw`cu?reE6 zip9r;_hl9O1?U2#9~Auyzsu?vZp810^#A+6{qNgwb%heNl;)^ z(DIsg5f$_*>xIgjInAV{o*@2Q@ZV?eQK2WIJDSOUi8Udz4mOjS$-5`k=6@Xm-s(Y5 ztnfQXdY?WiB;Ge_U$^PPyy^V0zgL%7w^}voQJ6Q!;*%T-Jx|Ey%B{}jeU>1toBn)Z z7yN>B6XCr9ruV@a)v4W2u+gBQqf3fE^B^Ke+Hv_%isCm|d|c9$M?@wCGVgs1^DAE8 zNN)#8hpR&ZCBGw!BBjh3%z(MPRr%5)`Vw2=`#{16=Ivwi`S<8D5j)7>{q!NPo{&9n z43Tx@?Ei2E{PPB>Lj=6l4hZYwdEXGaybp=@b8EREN0@h@dg-fG-pR9h?w?`a-l^wQ zOiMkXP-Cv!7OySA@(n4I?>)1iB;8+jdszceS2qnCycP}GjL$r#JgAMx+rSJP!Fu{N z_6aU-t7U`f!X+KVE|v5p#O>Ng(&KG}t0Ms=zf{G}iBHrlpj>8!Z}T)d?`{f6+qt3_ zl6b_}>rTMA+nB~GZUEgIco#bK?2^Y9Fl)O-a_SSpd=FSxgf`# zp)l`PN5kvacz04h_zCk?`yE$gy4ee&`j!9V*$pf3e4I5?v40j6k4tr>Q#1hQgHjtT zOQS&@d%To8w-zGryR;0P9`3KO^|(0t&2INtHIaFTx4b@6Ge&y6YjJgiqU2|jbST$P zodsm@7Wd_ip!2o~%Q@x?^WIY{bNKBz5jQ7#h`rk9C`$IcF~ruHY5Fg)__)!S%Rc;)$h?nz+{x5A zN_xD-adkwX>c!t!`aFLdVZ?fSt|^u0Gm6|*w(j+*>8 zCy~U};dJ&{ju-rT3r2YOSVwUc!?>MJjmDWe0sivezew#T0MGwM1U=|bPA+D(2W@{R z>_)9*gF)&+HDaGncK#?=2@lhlSe^fO3343xWU)`>X^(ztx|KV$zt#TWuTvI4nMrr} z1QxyriI?WS(#|Hp?Yd1+@>~q~QKGeRE1ePI5__L9EnY!y0{a~oXTx*L?bri-#2utS zQWtf-6gT4c```MpH{$9*%P;tvd3@_PW>9faLe|#`eg1#wQ0R6U+Y9a5x3Zyf1N!+t zX2)X|;lM8P??HUT)iHVMdL1?V86+@oLjv9hU7!CwAU)IAB9FxT8Eu#R7|c6EoxgFF zx3Y(Jv;usKT{=_G>!3^SP>E61{r5o@V15L%PP};*>}Sl$*SG=!hT@!(8J8Fk+jwj= zPS+5T1jp`1&BiFlfc|RN zY4MB5yw4S`8)bO^7K@KF+O9#p{0^D7JO&zJVlZz2289oQWXSE02Hv-Pv^QQhMqFaEOpP@nsXk$SaB(rz zOMcH43=#jV%^fP5{p3%2JqTY1T7L1rmWx>+W}q`|$G^7@y$7{lj-%jI>xJxxPVGAw zh`xigVPoRU>b*twJ?H|Fb$ro{p~qfX+d-NU@HTKa_{;mb-kxB=YOr7 zTjjm|?3PhAn0MnF+c%HjxNzn~@+^1hYyw?TC_mQw`_7~C@6M= zuzdnw@1CIRo_D zTZROrYU!3QlRfVNBI_sMsEUUbA zFaPc>g?UFGuUU7E#~n&&+M%OSYyl({Uk&v)%!0vvdvuP3H-Q69PnR0sz6y{@-WabznMuH#lYh_uNqX}CCpmcjwOSN8BL*%|n0t|F#x@tQ zG}XT!du0|t8-Ba)wtfJ&uLCVVrObO0&)+kF@=c+0wTtLIX#Vbd&H44c5QC0s!Z9Nvc98aM z?#&6=2iCM=ZHcua;B96UIF09By<;;y67PFQp@WR@68px7Ic}AA;}93C z9?bjqa6esKwhPp!3-Jtobpi~Pi&uJzXTeYBBOxYq4?xY`P1kcRW5ARjtCVQH86s~B zzPZQ~k#pEjxVTqtHMW1wBJ<9OZ;N8$B|YBwI?(c~!5VQfIx>T)0L=vFDRkb|RKD!Y z8+)PCgH;Nk6nzKz@cf<-mZfg8=lzq&I$Z0&UTQhN#@mvBw<({*+NZay-o2HS^nL>p zZ|d63n|8pw)vdb?S9u#A*LbrZ=6%M*>)Ysi7bv$U&vZ1~5#0FjC~4^0EO;-JzFoS$ z1+;Dd{h-V_20Vmltt56J^X{bPP>Xyri*3clnHj!6N^=OAxA{s~gB1_y@y6GImfxWB z;PdCP); zxABUY0KR(*tlXkS;;qd1a##lDT{n}&x5_(5z+`SS%)9#wg-yJQD^&Z|w)fa)dk~jX z(Aify3-0v4JT>j!0y4{0Sa(Oo09pe<<+2P@#O`fPQ<%bVWd=)!i_0yL)zhLz=8Z8* zwSLP_dc5&r=sIXZ~n*EftFue$CXkp6J{WIiCc#HF*GXic|Fz@&(jVmAq zeRG284s6I|`!D$HEh6jq)Yrrqo&N9r|70-zV=(ai??BLlY@&yg@jd83ggP5i54s@G zbn6T}|8JymZ{7#@Acogz9OCdDq}|a~brSJT&|}djJ_X&Lpx*N1gT}M7;C4+DCi~Mv zKx@St_~CgpuoEl$qS$PK*n^I-=iPB$_=0u8#R*@{(taUj0+4>DNy(?bJ{2UrB{mvY z2U>mx5*<+-7ns2Mgw}4XCWQ)8o%nyh-`@I}d20_eZ~I`wi`VEqD0Yr&zL)mDVE&&W zu8zkKUca=swl*Ny6Y#dyN{Yqv7Gq~(MdJPL%8*bh^0+k(v7S)AwPYuhi_ zPFx(NV*I@S8)HP?$($0d!n;V1w+pTgwETYgdO8fTF$1R*&&^%?(Rru#?W{B(?SZTc zVq7_v(FY`t;ec-HZ1R7+W#&0?b;#Pq#kz&9@wOx2Z6zd|h36f%^)oXP@1BddF4V!i zx3@8vtnyyhNSFHn9*|zNYWMM(IYaCGVuNjC+(Aat%Se^;@caL*_=LIj9s-UZm!`MA zjs`U&Uo3u}I*i!8%kBrw?0>v~y@!j_=zREPFaw$QI+aNQNfP9ZuLCW=A-|5#pVOJa z(VLqpsl?EEhv%K23xs(mcrY-~lo4@*bk&d;3u6cQ&;K`xtYclHw(LLizbyf8i?4~Z zc;4sO%b1XOXVo%Vb;G>$Ed%wKZck+?s0+t3B7k{el(}!$i-b@aIOglwL zuY2R`U_{AJHbhYRI2|*%Z|q{K#evTIV*=eLBl=#b_oSA77&8$MNbAfTS3EjK{`0>s zadljD@PGKLa;H->?(U+moupFgZ#-rCVwwBQ2sZr9zg zc`J(x7FhFpjNzmpO>E%qaK@4j8sFRcsa zv6RXG#D%@~+&L?c%-dDSpNEeGFK^-Na6!p$PMsxc9Dcn;2qS;QA4+uI?bQO;-@#{Z z*=}`;H;~^fMAorHaYp4+eCEIB|M+2zl>ZLT|E>f*$SG)n2j7E4 zljS&(dXTE*gQGj(9<*?+aZ(EIL2;Zbp`-AC6tqCilGft@6|F?3txWoYmXWvC^|7-+ z{pZOilt&+f&I|6NShHyGG|zQi>M+Vi??Hi|mxI$)d!QZdKdaAvBw`2ogCmY1QHAV# z5av6Pb!1i0;ck$2A>i$(%6K2oTUVTRGZOCrH%(4in0GtdhtgHvKfP6gAH%#O*dlLU z;B|z?vc&}Dz8?X-d!9_%Wc6zWLmLdkhGGSQ9WA$hY97wz=JZ^dE!Mxv^ zzVuz?y?4v_+!dI2=k)KMKcS8g4|m*!_7^_j*noIcandaKmZT%o@bVETsZ0wP6^;Q0 zTgD?2m#h%G_cul>d;6MiSQA{_)VTZJE#}C)j|@06s_Y{@-rsR`_@d<3eo<;!Ns~D~s>maTUr%lJ`Fa7iORwn}9 zcH`hBo_FNE;*ChWPp94pa)NoAf<&oR-rrLx_a1?HyPNnHR=skB7(Oni*d}=c^SAmR znNQ7veQEPobx%D4cPaKep9+cwv4Mg;=605dyleN^pOEJIhE2f5br==oz9~UIoZxeN zRV*q^dc5&+wxE|Ja2i4Aa*3)KV2EVhrzs$bu=!oUfznUd{=1<^Zu;xK~jB> z6XeD)f_YKz1=3`HrTV1Kg6`%Q2PhODfi0PNa(X(^AZCQ)R7C;u<*jVSxwn;ZU$Kd} zxJ60B!V?FPdGi<~{Cc&U^myazK+CVdU*qz!C^I;FYp!mW1A6xs7F?{HhP$`iAsUy% z_lbBoQJYQ;v-F(od1Ew)tb>Y8Y4zhR|God8lm~xYZt(o?MbLvhLSoiFVrTUZ(vtlB zyhuH$;pA-5-EZY8hCzjUWZ)i@aoDCt816xG`yFeZY;u5v1|Ds?XdeK&jr*Q{^qmD( zNiMsqmRdn+oBK`Qj$R`B}dzxfSij3}kdgL^{5q_aKUom$B~!x}m327cK`9^NO9Bi@BDJ{{{2^ zERl758YsfOV#kw!xBI^9#`q;R<;l`kB;K>B)vr5X-mLKglhQEnhr=~d4lwT=2f_~^@7E-s9|K%+i;_Bf0_1$ROKexAd5b$=Rnkc~YHfU_)M&kYZ=YjsWFmHMg zTC&PJU&j9QRhaj2KfwrkSqEsQb6jn_%pV+v_=VX+XThkUdrY@uE651z$Uk!`8fcvH zh)fhj<~_3ixH@=^&2kIj6C`+Z;!eQZ zXK(l(a&&$w$kKwYEkcNpdTfoWyf z#MSUwpy<=|$bVxiaQ}IJL;aO#U?3Vc#CypGadT4r!TM&q=pxn(7YBT;9`1=k=B-%G zUKVOidc5!8>QF|>&vdEfL0mZ#2pHkHl~je!`*NcM(_xr5gGTi0>_6x?Ct|upw8S-@ zko|xZ+fG~^3H&M+*jsD!zZ(H>=aL=nc-|xOUR#iO$L&dBVT9*@|KDGCt@7@_oDaUh z-8&*swD3!k1N0}>mb2@gAGpuDG%9&)77V9$^+i5@46aTKA1(`s2D{~KmF{*UA5Q4p zJmxH!_5&-1ixcS$A6#KV<{g{gbYEVV^mre_)e(o1U$(b}ga6rZ@eo&sUlGJPa{Ax<|H)wbU%UU`kDv$nTJ(Lx z_n;$w+XRq$P{-&(?m>8oJvDwVVL#l1;=j9|Xoc@VTI`2nUVGU=>>VS|zC8~FpT5jJ zRI`}{{<)vj?*~5tqk-5v&Wp#ujxDb%Llqnlmsqy^^c~jPzp#S1xU8nhWfd(8#2uu| z%hz*HGfA%pG2!ZPMahp+g6oYK{D5>_&V0aWaY_|5JLQb0D!E>DL(ljwK5v&t??E@| zD5@B%Z#xSw#51p@IE41`3BEhisIW2MBXp30`@TP<=jlARo)%m z?XF!gZ;DV^y3S!csMIR6^fnCnE=al?~q!D;Oc(nkn*d;jdahv&VK z5!#N#`|-|*-e8z_ilpF=)vLFsC+s8pVczS{4NXm1*h5NNMXs8R2C;RyylTBP5 zm5$*D`S!1MZyy5QUeETu$MgR4E0Yh2cR{}N=aVq+D{KLGR(anV{}VU_^Db_{exG`4 z51lR^mn)tK0B^d%y?pmsApiNB$5eV7kk~;PAwe4h*z_vGe(@pmKDr<|tZTl4-Gqyi zrd(EtzlO{^`va4bM?C5A4#CxtgOVRVbj35*fd%A_oWCSZiOyT^HN#Rdd^pi`!`kzW z2>PeD1WcHIWC&6s`|iD$$U3HzRHWqV*Dh~)6Y%!DDg@zqGX^_sL*gw-BmL+S%-d-l zo8Kz$Waj4lpD^!PiNW_F)DDoV)bsUm*8+gKC{LY%_bkvnXqPj7pbb2ocAlsnKL%VN zzB`^v$X9Q>E2C}PZ!TkfaB*)o>^L8H8ToJ`x;~>sGm!Lnci`%XLCNpCk@Cc?KTKes zS;h~M|A2RAEjQL<3P{5$`n&2S{~zr&ZcL4-yHcuO9wduEHiDyC@6ypaa7(HC1pAV&fHLel=|kQKz+Wno0$M zBzD#Jv0AgBGOIySgQ5exxb|dgRD2Y`8e4UBHy|&u+8J-&Y zQ@ud`Z;&#cB(9F?13tz~$!kk&5CQKXzWr2q-q-xcg^+mvxjBAj0p|U{%)e}vw|;v< zSq;ovd52odUK1Or+px3LS0)Gy0y>U19hkRkpjFK6cF^r`+Bn-b3ecT=R48bU%==3p z)k44PA1o6t?%2G7q8T$XZ^|2f2JxJv$9o=E2U>m(jZ&SA%1of^h8iV<9XjvC8$3Rx zFmLHI{ueOE(JybsmMh2}9ULV4B{sHQMRIoR#!=2jS{K%TLo@ zJS)452~5tsxTR@~&O7I+aPBcoFXZt(MWo9IeFtgrL))i`SCQ=J|IqKm)v=Vt-MRIj z8>9mWc>BM2*oWuMT77O867Q!6w2gUT-Ya!4Hm>r1X;&rK0Q1%_@!gT7Y6}I-IcfJP z1%V$`aoa^rXTh#ZZUZZOda(Ki+~NwvLUZysI}z!+URk0^WY9Po(g?Pnt3y4;w72EtJ zrAy3$+84jrI8Jwh^Il(CwX7q-jb*pQIQT(oq#sfC{o;=`9TZS0F785W7MtOFE5scn zKh+PN5>L|WK{>cO(DHLx65QGA#sZ=m83dkJq4%JT&qNa`qI;m{7QLEWHAM8Fk`yOa zs>fvCgD^za@jLg;p(hP%1JY3f-r*bBT=2a4AG{Dn;%za1%IE~lTk>v$^eXS#uua8T zFz>A+@3}084@2XL&qr%jf`Ev)xFn6tEXb9$lQ^%`3CdCr>(gsRf?Xy{X=bg+OKb*^ zTAzM|0uscV# zuf;u(w|Cm{Y*lpLolG>U)@a+B;Iku zlht`J@8d^Q-^;!YRbx;nGT>? z=e)_E{^deU5d{v^5w0#kO&w0L!`%h4p+xCz4 zUE8|fgat&akNsjOK<8bom*C8EwFgQ$n0&`k`yt}0_IGupYi@e6O@r)tV~DKddI(Ma z)Qz?79ZJAE^j_~pJnxrQ;d_yIzvK(sdK>2b<#j{WD({c3r@1*`-n3uyrC7FGLHUtc zpVr9+0l9uz@0ZH6fa^wbV)dmC0InKeVDpFskF6!IvYR6Fekyw0C8G`lwc+B1Wn>kc zbCG#FO<7Ry0;I=#09S`2N`7I{DzVz>ETEv#p}{>9owt(->%32A52R4_vuQw}1(kQp zA^M#c4;GR=?}tRzaU-hR-1E#D?+^msAqnS9@w}bY4(>tX?X7em^)bx5d>^OQD(@zX zTIQSZ{I4^kXQr8A4f!gTmwuBB0zZE%O30|sf;TQAM-LlzfCRcCt`l5Qz-3c0m2D9+ zZ%L0YN%A%r$Q>8Ap}#~(v<#W|r(3qsizN7Z3w#|PQSyt)p1ar8!vZAN`$k?pfzCUk zQ%)!j=3SH$6YxP8oi}Fp(K;$0Rr23^6I;jL{VaK2|33f!cl9RaFW~tE%kMYspqwpztD!AqGaoEbl4y+CExwC zRzN%HEwT7IzMLOr$(99l_f}w$h?mWm+>3uftud3a*9u)ACO|4+Ac4A zdPx2~$eFl0EDtlBn*Qej>0<=EV>WI7gkNHhUm21@;(gy(RbdOvTZRAOD+QRh>5=Tl zR+#tg`cGRrT1}w)c?(_NHwS?{+6a4%ZL=WuTd4cThh4xsSR%0RUIf6_8=o+^hJ1O8 z_dexGMXiEOAw!wOE%ZBsK=(fJ-WmQ`VAvEC857zC z{FBBKs%s*^^-8OIO18+n8>jrL>nA9oGF+Sk2Y2R~CTqm*eYI*!%z-@8H-Ju>jgw&BS7=qn<^b{WZn~EQsM8DD4`Zy+*fIzbMuFgd21hz z{L*rY^myazK+CWDwcwtu;Vj_kXNuT_m*~88GbuQphxb5XGoRvaQ~;mD(nI9{F&>=a6<#=P}abt&6JzEk6ndMVG60SbztI{jtJsblwV~ zjnXe+-n*C&1i5b}qI<6kzpr3H{?GqosEDj%N9ydJf8YOy?{1|1_eASdDuNz#LSia- zwFm8h-~T5fY=c4SK|7_!vopWI0}{R7iW1y|bTUq*CBQu>V@y~skJAVeulstbJt+WS zZRC}AQO*Jl)6dP_7khw+=`H^>B)wBr7&;K z#D)A--bKFwM;gpKGsV4jlaCS9q2Fuws5bye(wq2iqnQQ$A#8{A^?Shf_8?S`3j46`8L z;k^HgKi$B@kk@G2*GM2itrnaA8<}@|Ox}wdUDS{iE{=m!+`~Q;nfJ=jxwIn-q_=~_ z*Rh0>-@Ra7(H^*ar=79Ydbk~(cm1nanD-WtT5Tv| z4AEa~8tzXC1ogXO73W!I!HMDo%fZTSz}a`^hToq^Fn-<0Kd2Fz_i`X@>p}=M^Z^&= zuB7OF`MVwB=ERu7`quAR(&N2^tHTf_zdur&=ok1o089OFbOAj&Z?Ro9_s_$J6LX!v zvredWBmP|Qo3e1t$GY^E()aQIOs;?5Mr0i?M$;u!n+sO&|BoTyecUG`2){YmJtnaq ziT4??H0{qY@Awnur&oEeo0UCY5A)7C+#T3^$ryS-b@oRSRS>vYmY>zcF$>CS8CU|G zx0@;S^4XhVR%UWKGd1Lbi<7_oB|an67V+2U@Ju`I#yisEZGfx8 z4kbV4s?P@%_p<_~9X@u+MDXUr@#f#ep<%ug{p~I1FO()o3e=PR*;{`eadq_M=jz-^ z`1kYw$fAwG^FJ*?4>~QvAdjE_$2XdQB4PAGilnA8DSP0XKPKuD7N40<|MvoIZCVK;il92K#C;iBT17Z(K%r98VJwkc|(g$1}@hJJ#`dD9k9Lox#e)`vDB%&{|clS|d zovG-7Zf+Aa5$i4?%CbEt{-Y2hzXRcmiPo*K?ow8iEc7n8ec`J=! z=Qrak*F`20U&>+nnM+xyS_ zzn*~i$tT~#@ZFnl!#oud@12Lr=!{|B=9}+ut@3W@TTcEB^A6o|F<`T-A>_v!d$8+* zKZs}%=wSac1NJE1Ir~Me7i1nkIT)=R2{uX4%5Et|=52dkxskbRJ;aHNyP9S{%XkZ! zcYlkUdDB7CsG4u~x)Y?e7jE z$B35yff?D)|FJ~YQCt%A>Bv7H+f>oS>;!hI#Mi zx%qA%JRn8e+-TN~HiW3}*sOF+`GXPjJ>>$6Gk|?+sBzEMULfSX6eN5IemL=Q9F?vQ zGVf~*e)r$HuZPNTar#sSqp3%bd0$+A+2Di{>G8(baRDX2cXlpsQyN*p7+b5Vm^nIc znKs&_iqsyc&ghekc{uvv#ETugRhP`}kUei|e&XtwnPA#2mb$h%p(fy+2ZaQ=KeSq8$Jf8iurY|C#|p z>MPu3(>-99@BP2AXz)pnc9VN6Tx~Nhu(wUnI0@WuH6m2IO}RqX^~%~3%Rs<8 zeHp8S=dCWjogRs|Q7LCh7tC7>vom6qw@O)PhzZR5`P7GHOUn5Zm}ELYTpxx9IX!k4Un=m;q8FAwPCg_kpEM$m-qMNWd$0jJA1~8)CQ3tMc5%y?+D5 zhl?v#@p`jq7jpMbd?v8m0=&v?aK0n+1*uVX7pev!G6`~jwHpgv)t zU-Ak%ZL^v9!3qpaHBQoHqx0?(01u`7d!UQK2O^x4(Jyad%y^sLW6j8(cPx>0SRbzx zPbmEN{eS;kGv|Nw--UY+8$k~`&v|hK--9;x05+r^bdF0#?I66ww(NROc>rEwQ!*1= zQx5M_+4M1%O~&ppbkJ+h%^n61(0K5A7tP%nAjkZ4qMD)~yztDmGf)o)weNNm8aE*K zpjUTvHe6t%hp@P~=3d2jHRH%T$mu=PirqG(*MnZ*>X<^w&p)SsD58c1*j6j~^6#Wp zLHiv(xpYFLAiWbhSFRky>xDl5w=teIFT7hx_C4q)J#lrc*O-zwxwy82WF_F8J-(QS z=goJVg%yeSq_=dWJ0CqD0;leBz4#WEb7k>2;7?i zJ!OqHWg~sSK&cjUN;w>y|9yPYE)bcwqF(G6dmSB=kBi$8&l298h0L3Zt+&g?iu8CZ z;Od}6$#4DnB17h%EWpm|dRgrjbl&W9F)e*C??cWpG4!oOod0tVIq6N4|1EYHP9p2* ztZBr}|11Q&v+7>2eZ1xB2~zX1VP+)WIZ+<-Au#Vf)z|n}c?bNtbFmrbou9weYE!5g zq-!v3`>DqhY%Txkqy)_X(eUEQ;D$cHmSMkltT!ASVEDQeGmOl8`la>OSFUuBHZD#j zL2cZl3Yj;?m}*qef%JG!;p+Hf^#7mV0%WB<0I>k~&1LB`E9g7O3+dYR_02(uv=!Kj-OEDb| zcC-11G~Pnytr7Xlzmk;>62-+)T(Yjb5s1t?i-XyZ)r0hSAHda-iIQJV<1~#3Ju6_0 zw)B5Ah0fc$M$rFJb{E9?z;IlC2RiRkj{>EO9_0W2KQi8#I+!#{JR}CKT^8w-gx5C1n zz-Mnl%^P0@^#Nzf`_yNKBfyd=!sua`Bh@S#SRy;f~;$w<0VGXd2?frcWuwvcs$|GAo?YCOvdYZYTo~X0g1>u1mn6>Jm=2o}0L z10-_4b#|TU2U;ngZM~Mlf#cq9RwhBnyfbxq%Fg^`fZTC$(*;LTbWS1j=Dj;Qjrl`* zywBn4K+BKY^L=1M7%RB4gF3=q51scT!}PS@Z#toy(PP8eJJ27o`_8JF%y&+l><6UV zMApG$+p;p4v37#QLBKn&-0TdV_x8KJ97w!BPOVVTz&ps}CSzu+ys1ZzGMdA@A5Kw^ z_Z3+}IS%qKeEHmfspq;(|EuuTTe(TMR^{N1V>zh{PLAxmfVPyw%UK zjjtX~lz;s#6AbefDwz?Ep|*h7AE)GJJGcX{({J>ym(BoPdC!OATKypKsLkL}$q4X@ zx-86U8!~U>-6d~^tr(y&T-=*Pp0UH!$h^1G>$+ayBt71SxH{1C%hw(<-ujCLT+M!b zn_C8*x7ea-Pe(~7#Mt3vEAkEfa6(E~F+@0c8`%#?8Hb3gL+@$ZHJkJ`-s}Xtb2atN z@w{pC{n(LsuRHWXa39RuyqhtIkhk*8_z#V37SMcPCEsmJcOW2ll7IBp4B&F7a=0(h z53;empI$nKgKhlrf10)<&;M=T>K;h>&_jZ_IJ3CPNA()chP;|j0m-G!louW%{#^bJc>VmxnWgrTJ#S1Ok#%&p zi0=D${{Q>yC+RQX`F|@x4=Sd7_XppDluLH=BK4rJqnT}<@PHKmCNW(bUSco29S+up zm)Lv4#kWqdIzoGOLbo>`um^NclP{{r&Vc3h8679Bp8^vlQvG zhk1{A(%OU_1(#lLR8<#7<{kGidfgO;2`a|LeW?%@w&X|Vy@gSaQg#pN@ji~LgBvBk zG1C;mhZ8JdaGT>L?{swD!E&)`t*1JnOh)1E4V>un|GitB-}Gsf$$mikSxH2gDb?XW$x;FT&B-RcOqU6(n<(`SJ2w-ko;-}^yj$wa}Y#G}A3`m2I; zB{J{AISuSxM@A?F7xzIY$Y?SinfI@}Wxp*X`20V<4z&Ert8>e*II)1!Lfk6Fk?6dm z&6VDqpY4QdXpI}$KcUb68QyhrNnBURo_DSfadkiif8+-e);1@c1iUY))2@B~-|F34 z^Dn%%Ao2d~#m)N==6#ImYP!9~*R z-uODu^7HpK%-b`=0;FVF^h^WLdB2{oKa&UZrmwfBDLhNW{2yE_Pw&5*{P*6(*6})` zYumr`KS_`Mf0Kjf|Lp`l=*IW6eE21H`~sH%QV+837?=4uSFYmPzl%}_?m=Zse15uc z4_cQn|0Pz-5i0pprjwX#2XYMVo(OcE0SgIrucIgiz?Uh%$>XAt;1_M{r+j^H=x-kX z=NCf;yOu0iA?gkP#0fs{^;IABK%D}d zc6iNzOU}#vZ$_Vj_y^;*7VZ(?fnfBAC-6e#xTHYocxHeFdV-7ldiU*!$BH{5@AYTJ zWLyF1@y6Fdi;~~ak1Hql?}Fd|7ylMvlr@x;e zd)~g~#MO~g+U9Ub?d<9kq}vF1U%Mb{gy(%wzHvJeZ^7Vob%HSOG^Yk?Lf$?H#ZA8+ zc7%cl{f=*QwgWapry)`Q8L(G$lD`#t3etGy6IpV@!M*09KQ=<1h`eKkORn;nvOrC^ zxLfgAs#WaByia|nmbFYJy#rEw9cNJTUE{(j#^EO~^=0oCLdM%||4(6Tn zLL&blLHAaVmaT5FbA)*H7%!%p*ny|#Hp}J)&wv=0>K{jop8_k+Hy3J{!a=`<^R12k z9*Df#xSb+)4lzT|adElV^H>W)-4MI?2ZJxb`6uZONccLYQ1WYA*dTGiiv?gm98MBy zLgzin;c~*dq64BZ;5aw=0sZxs7ecm1KHASq_5;%BQR3=2m9xi`*YETyZyo~PS5;Eo z@Vujr*>6MQef^!=0TY<_g7A5ILf)tDZRWY;;RyLgHnC4C+JVd%DVfEH8PNT9$oWas zQy?w&&MAWNC>ZO0wW72IdH(nBKc?`roC%u5#jR{RmtW|Fd^o|U*Af4N1P>?hb?iXN zZPa$^sDa@Iyg}BOO`lV_s)LeFZ-afs(hV^0JN}OGx-jon z+S7&~SG%{n{rA(B&Jb_U;Klp@Y{=nTpr z^ZxyH>_o&#HYg4kx2^4H&D#!S-YJg`vGU}R9&dadX!*r{&RNph$p(6#Ia+?AMCUzf z8pBSL-ws{Y61?d+jm}%Q@%Gh?D`&}`w+)eX__Q@vCC9Bj-oj77yWIL#2cEYgx zyra(tUhIW=fBsNRy~-PZIFZycS|q&R5eiVWkhQL`1N&7BE32$#z^x%yR~xkfFvrzY z@N{PsxEm+0W|HfJ*u7IdGk9IR*r0p3xU>q4(aaWP-dFb?6}(zSdc5&XhKQ@9=XR@d#L2b8i5&#I z%l7#H!1FG-WxNxKw}ZiL%?X(Ir_BZNglBJRmOEb=07rl%Z3r*1 zcbx8>{{`*2TD3DX|$adeMAl84Q94cB-*QM8ZLM;yL|q zn~-~ujt}o$=O}h44i|UdAS1i59(jqa=W$_95Fx!Dgs-CxCBM?GsbWKySU?Q3SXf&; z`V#9a_;!x^ayvA7vHzr50ud)j=FA&|s_u~e{2yyUTpgDyR%B&vuPw2=33yl62Ykcx zzOeg^C=ze`;(JE2Fz@QV4TT0U?~H99EnmXCYi(jvg800kliwdd09#Fg$oJH@9a1x3 zy=*}lFW(?gO*g!B34X-xN|X}oH#TJ6!`}`KGh4Ak*Ku(>Pw22V9!KV_R&%hfL4ovm zzrxj_ijv<6T( zPsG&`cja1ieC`@=VFKQFPB5n6d7CO#h#>KfY=5^~ALeag`EAQ8?+=&mSQW#(FH9wK zQg85ta+ZC68lN)*$M(cjSjx|U+HtXFb<7~JYgH*OzZDL8>wOQs7DwhS%6-YPZ$CTq z3>SCU=wx-SBQkFZ`-=Q4I;6)NUk6%#jVIn;e=E)k+8_qIJ+`86e_3z*0Rr03h}b-E|oe;6ulp z<~u>;`Tw0%+wM^=c4!6{7m^}<_tqFP@A4nPbmtsMkM}sPjtZ3g=DY@&%9dC_s+IL_ zWkYn{XOasQhvnKKi;!;1`Ss}M|Co(}v_nVskp1Qa!$w>kuAL*kq!A^S)Ze)v|HU4Z2WfvD_$Y0jw@%2gqv7 zfQg!BWu4{$P*HyFy&nA8+dLKyF^TJtd3P#E4@!Myg9LDKU*`twj%OkBesOl+5jk(t z|&{KjlQHWP6aNVn@x z{>(()K|bQ91$o*VAyr&lftKc^(@r16of6NZrWyWa(z`(#U&j`d{2t5gZngDf1MHF2 zClspCdl2W5310*I)f1%fk78Bm4@gHnGNYDa=qCFf@k$U^^hrZCR<7^?k^RcOx{5i>p;vm?-J-M&uo-BXHu# zI?`KW@pXiwc2#6KU9E=s_=KI-N=Jnz!ah5L|r=l;>#_ZH@@tMAxh1oK|!(8|6A=B>7H zeUr$oBamoh=5B>B10YjS=d8gy15VU@-zsxy5cquE7E;i56g2$iy8rPAGH<3o4I%tr z*`dd{IF*akR*x?r^QH^)iK{_Xi@UJAl0Y+WRex|QG>ptvzuFF| zvZnRh>Z0>@!>VpmJwyJV|HsluTpj8M>kmCCTD!a@LcqIDuktFM_i&@XBogmvvkixS zz`V1Tw3JtQOX|13KF=eZ;s z7@ohqvt#p1rA!at~~Tc^8R_WA0$Rp%k5>3>8Xa;5i#_ zb6$7`d_T0GuhAYpoKSpPL(3Ts*3I9HKA?%r+cIFu^l$+?#Egr3OU2z=#OXF|@1V;I9`C$w)cIg~W9%9}e!dtZ?HlYNNdcrW*72T6?r@9O-xzwZB6 z2yW2A!kc%MFZWIaZ~gmsqeg7JqmrJRl+n}P z@)qhN3@5)S(TV3@1PFk;KYp1Hgpaq6?>(Qdb&YV(y-e6(2!93{)S zAKyYgtm;Od*hQ+hDh1wf&}Rd52D$u5##$`AQzSo^2OxM~x}=h6h2YI7qETdo;C;a$ z(4W}s2Mg<-tGUWz0JhUh?mIz025x>$d@8f19aL^T0v)Ug1_^1p)wkxct9QOn4CLp? z2d9wZ>_Eqh+`nm%)Y)`3rMYMiZ`8+Xoct^j=RC*SB>zl z$;a}YEckdQt7|{+?lW5O`~Tmm^l|celyM_1?@O8xb!;dw8QhHsIvP+oX0~{2T$S zzUo=MqaPpdk>2`^w(X7Z`hc;<>*aNrtJ;4}a!Lo&@5n9u=Pl`|^|3TjP~p$yM41Bb z2b_kPDBh|OYHP6Y7OD%_mW$wB-_#yriQxU^Y%2RWviBys?w)bd8edrTbkmzdhc<#! zg33}poMS+$x+$3d2eNwGb}=E(;{ez*w?jCs0lWXd)oGSE62b@jkmEil@MKyZ#@>7D z(Q|ynH9>oLqdq!t^0PT{u8N4f|9AfIdeg79_;`bGy5ZEJCfMzCN{5C9{@xp1P{X){ zvE{;_oCH$mBjsHkQMvHn{r|tp8!i8U%pkQWYEVP{?C%DN)c+G_t(dWD&`{%^RXt-R zdaG9yl-eRSD581On=xbtxzXm9FH9c<+gdE2{T?h2%x-Th_wODB$4<8N|6+O#%8GyH z<%I?Vk?8On7yjmewDmXT3ckrDunalwrNf&cjR#(sL&>oG+2D1%X|D!Zl6?%|JnCb*lI?NSi?i*7?Ru3%&*gf1u8X*0f9J zY}xM_rbC?LzlN6%`9WW!h5OW_USJO-d`Eg1W9;%Z#X*!A99SDSb z8u{FVuPTGrdZo+Oz8eLis?E&bKeU4tUQ_9tjt2uV7p2w4TR`gw0XBSHw>>~nL)-M=s&a_ z!CNoT{e&cf_xSeGosZfAV9)9!DU*V0z*KTv-oVf(*rM_b*gkFtLakv5Y}z59OXM)~ zu~zIEgVEQR(B3(;d@we?D(nLxFdltnFG9 zZ*TY(Jr>?=^T#tq5xgr)TR+$!cwac*;HHD%ZJ?^Kse>l~mMAViy}4l>SR%7ZA)Gi0 zTz5mUlO@RJL~q(_AHNXrOXz5U%zJFS9|rH;Ksd4lhJ^pb6;*fH#WZ8%ZL6XlzUC(F z;SH00SmETCRx99Tq`DaFU##kzEQ61?cKZXOGO{@lzSF0FP26M5NgF!JiQ0B7bYi#B zg0J3URQh5TjdNM0P_{Vq;Z$B^f$rb$R>;!V zje;n8r*QT|uffDCrwRA_L0~qF^V6;u*!_Pqo9U9;7=HLCIZm@TL$JdP8}BWhTMY9c z+M7W>Bm3Bhli#mpbRr`<1duym{3G`qKHh!l9cGUZyl3bXfmj9={eNbtcf^P53m$Je zYJD6|KeOUb|G$m`?&`g(>kfW1R%H5&f6^pA8);|)awCdP4G@h zfd-c${O2v`jO17*CKvwse` zymha>{a}aS4GFH(s6sX;I5^I{>3kam=ar0FX?+p`@yQqYZoe1>ii7I)5&EyeryrcP z-f_Xe{Oal{wu{(!f3h={eyz_BTan{r+lGGJDZs{i(teaEtWSG*50ib2;^eo#o@d*q zW&*g&I~%dd4L_)16YqL2gnuu}lGCC7zqm+PCA^~LP}zjdE@dpe%>`u}jUk6E1js<`P# z&!6W3jse2^28Qr!(3n>1_RkL*U^CA>hkLm3zaXVM&pS4)Ub*mVPyuy5Htz_Nsw(|G zgEXMP`(^y}CKT^2MFavC-j;_$4hSN6Ux~;tAmJT(qApYk!8<$I&N81E3Y*>Gw2LXw zgV(BYZSS~%9B<*fPH0|anKeNOic0*0IDZrC5e#+#{xFY&I90KADD_r`5mGXI

`XsJ)rl@M`6u8coK~>|CaE+q#m31 zq$=sphr^7=`wLpfZ=C!tJB557Il~X0y-R$%(ex=U@8u4rPo*9H_JPihBteteF2qsZCVNo7Vo^$eZrKpx2YT7Iw-vNG(JJr zCdkKI=9C$Tywm}FnWVaB-wogiey#5XM~1*2nP1tXhsa*SJ-7U1A@=sxfz37WQWWEzy-A~W9Kp%&cg*&7g17)!$D`65q|u4X z+jy;*@e73aT{ff5Le2QMw+QdD7wsYlG5_L(-a1O{3v!TeZ~6E0|5(#41N|JC|M$}L zAd*`2Vrmb1qi)QD)q{)_JBtWN50W~)K#em0=Z#-hOhfh{rOq23*8FS<)^fSZ7YG@{ zYbktXZG*=KXpeF+y7L*u$C^Hzqo?8EF*rn&6eZL7!(*S*i9by(u$*T)jG z*+`!sjP0B66c>!omD;^)O+FqKwW8w$>GWyevO8Q%&wEi8eRXI&&AnfAYIZ=1pyADP zDXp8zn`BtSg~fZhAWI;H_nwh&!W7;zbyo5+$bdAqP|8N-k~y%*5pCS(YXt3n_caF~ zyd&8k?}taoKsw8135j3=^ir>Uud~JGJq6{**ClX49W?G3xA>Q|2iUyJ9%$CiKf`#u z=QRGUqXH*Cwqa8fr)Yk#KF%t&u;c;euQ7F5`-C;Up>*^BJpR$(%Rn9-A5N@pUEn9e z$@IJlm2}oIx>`~8@9u3l4R7w9PD)hXk!KHZV)6b^H*ti*yYQQ!5QVpDN@jl;!kZ;3 zd>@oE1CdhUi7XOEaO-m2xW@?Zo39?pS|Ge@PT#BTur~pr14S4Z zaY_}L|J4mybHp5t!Qmxa9ocSS_n;6t{=TB)>~KFC_dd-{^&1!V9;9ftU0e5ww+y#} z+=td7jgwzo>C{4JePP^3>;JaoR}qyvZAeECf*0@Kt|T)5BlZ@3b##wCI2QT$f^-ZG zZ=or-*^k&!uD67y^YUZy=4$SrL*ae+*Xj8b-uvZ^6_y~p4dgDKT5!$=*!rlmMJE`+ z_wIANq!He=WcRTR2yaRFh-;y*F$nM`WQ1PE=AAHlls)VRJM=;03d;|cFYCd6#C~sn z?|*-a@pvCa>zKjGFExBapLfDP=Ur5LHtL!n{(v+j?Y*HXID+YU%gNAJ$FH=>xw*(k z?2zrPXd2#vcUPoPyZ6iUuZUQ@ou2I-q-<|(vAiis;XU;_dUrjtf}B1%tiMg(2K37J z7i-)!g2Kd+HS7rQp46Ve0EG9Zr&l&=>^BCdMk9Z(zlhB{He#o#r5gu4j>fgdrL@O4 zVe_`>Gwthle#da#I|;4B5huT@MMAv(4~2oe>Dc?O3$^%N{Jh1PDY0)2Pd2GtJ7Pk| zfRs1Fqp&fS>3I|At;4Zp3jOw$eKfoUvU|g*yjLe)~N7xhATi`=PCuR3E4a*IcGoy)L!yKGFn z+j^G+o<`$r9oNb|tik5ZC)zO*)XaFiz0f-5=VvIF~ii@Igj$0%jwZ~~26_Beii{8{X^_x)!6?no8JJDku#>v)WlpI}uhr!lQz0-=~xnCNuy1A3HMsTVEz{D_+t|Y& z;<(EWnDOr_y*OYD#SCoZyOACgJfwCx5II3gKk+o&h|?JOnWdQBT#DU;NIsX<=lQcj zZ#1r1ILRzx0J{gto?PquPVNoEtsq6vI+o+)=X=lP%jtt+xR2KVZRn`3rMS8q9X%*Q zIp)Oay-fdzB}CC#M{>+-JER98yxC}YFPOYvMCE<@8>a{s?=*)(D+=$G(|c#{|8G|j zE0jcd`(%H({g&Gfd}kLFI-G6{hZ@cA-b8pWTlZQg6XAVu4(Xz|n=yFjHAnWudu-m$ z343%xp0mPUG|ohlLtQ2q`+7_JuWe-k1B}PpgIWhpekxBJZTG$T=e&zL_Z&6Zi@znm z-`qxVx|Xl*fB$+g+dqfUS%;&Yopbyf%Jr5ERvO-775?+7ymy2@62{^^*ynCf;eC3j z{}-iuzs=m(!GZ9$SU07;?367Cx#4>yZ<#S%<8LH;8sV)sBV}KY@GgtZvM!#F%>Vmr zYOXxR9*}~1+C20P*bOUd-4mNL3!p+1@Rc!DK8b@L`(HsoGp8sVQJB4n#!+5-Rp>-_5$?wC0_>=S1 z{yFc~`ZMH0Rs7xCROesK~?XC3{-!~HXdDD!^?3k`1(=iL8%_SR@JL=cO2 zqwf=Q3U8m>J?xbEe|3&VA4GU>xRTK#=D!gfZ&aP*sBQ%1TFmd-BD{H@T;5GW=Kq?8 z-->0@#$bxnwZOp>oA;{+53v)NipG6jE zAjbc5-iQ6yfA0*(-`*ma)#e=#j$!`!--6CM3SSm3Law*`d;gyamY+xunn%-v7Kv0y zP#>{#TU8cf^`O=g;T%d28hp{vLwUrqWJAs}qzC3ScH`fz zuU<0T3X&VGgN&13DY)?X1=l|xkQTlhJGobvj`=^{_o{!?0p{;Padg(<)w5J%_KID` zTpHfe@AQ#>`ulndQ}(eu6ZLpqKUp;k_|YN^QE(9`pz%WU5b@ zz$|s~Dt(0a^Wd~yUl873SWFWKi;RHyTAq8C{>$qvh#P$-cks@Ef@s`Y9K{9=Kf@Q-hp4}t3yMu zZs6(3*%c%g4R5LPXBJf6)20u^v3MI4kP|4pZ@#h`q;&5IgUR6@)mdq&_wLvM zBd1fX)v6|N`@Qjv-;n`HUr9UB0^xmYeydk2zcFx?es^mo9((t8@Zba*NiIZQ(r3J>-y8oPaF7HDJzjgTYze&V{Q=x;tOuxOgF^axAL>~$4|CRgi z{eLEy{s{zR{wLD(pe4(awoxCk)_>&WuzHYAqBS?=6+7%NIw~oT*vMm5V?oFYlDDm5 zn~|9VIQRTZUhvip@KvMx%HPNea^(a^fB-TeebdO^-D_Y3;t0NktvuL|*wqQzMKzcH zG(@0r(HE|%R&ZiJV$TT4-FQCng5e&q>(M%jaq@HTYT{e`^q&t%A$lv5&)L!OiXFDL zkZwcff5i5&(pN`+L*UJd*x5%c9}VxtFCV#6c?-XsScJv<^5fqhDUaBUz}f~1?+E31 z(J+K}*8B=5?uVO!+T0WyuPqkPPx7VlTZFgny+jU8gtx}P^^ZOqjeykEtmSi9v3ZLu zb_jfuGSeW8#*GSobUFJI`w_e5&x?dl6cPF;0GlEeagfHvjw)tEqp@Ouw3r zkGG6(i7U{ZVg3~)y>*<69V$d#v4eDPUK-x=#S-VJym#Mdkip`uoRT{G_SO~F+wW0$ zD}D^rjYN3MJe08YUbz`)wzSV&P&S8RpGOCp5Zfd;uv6;}w@ zyx*0l0S;XPyn)6MQ;y8LGmg#MpsQ7aw7;9-cn_gc}K?){dsmp8xaE@RmEW|2LJly#E<#EZ(m9n~N#kTl9B- zJB4>h&Hj;SgtzyiO-}6zn?R8Pi+5O2^*IXf zD=}xEQFwFo`M%6Rct4r*M$BvdCa{Dk_4DarQ`n~4;+-p=6eQ1k>~WkwRY`o7b-VB9@C;q~YB;&tQQ!u$WRci&M>tlh%ElaM+|Kmi+w0-~TG(geXWbQB9BiWDJ$ zf>=RBQIXzzFQTF%V($%Gf}$WcR6qqQii&~?*bv*d2Q%;D-nHf=yz74V4R`4u`<#8& zqt0gi&Yu0uOeXWVcHC)P3+`mD5m%S1$sNfZ&K<&)<8rwSE}8S4^O^I3^M><+^O$p= zbBA-CbA=<|oZ%ej9OUfg?BHzXQ=}fLL2e?I$VKEFauPX=>_v7WTai2@14%++kT7IDvKm=|EJi#LS7aVyhfG5( zkjaPd#`cXw2Wt zZ_JO(cg)w!M&?6i9kZHQ#VluDV4h|kW$tJ0Vs2w@VrDT@m~qSqW-xON(~r4?xsd6` zoX@mpPG?#%QKm6dpE;JP&QxJ4G6yham@K9g<0s=Qqn**hc*%ImsAtqLZZawv7a8Xm zCmDwsdl@?!TN!zb3`PY!L&6rKiU%7LYfPnqQwWCg>T2Lobji|a*P3lPMaOx1MobYNGt*cL57W;dU ze}4jhe*%Ah0)Kx3|6@M^@{~jbM#0I6*jzX%5&m5A#DrjoCJAdH8YirRI3Zyw7R1kS>JUH0sY3i1rv$MhZZO35IP5gu7AFnyLmUg@`#5Zu`YtvMVr%RM zh%K>eAij$ZA?0kq#v2!54h@A=XdF)h(jjv5(L3|WD2I9lmkq{eVl_A#0Dnfh^I}qai*!~dj#d09l#xfw*#8M#M zjR}ExCuSYQ+cB#lR>!P_cq?WJ#G5gTAl``KLA)O00`XeRJcv~>vmsuMnGUfs#u{Qp zj2Xl$F_R!(jxmB*9-{~GQp{M07h^Oamc@*KD2N#bksmVz;)NJ_i05NuAfAgsAfAn( zK|B)!fm9j|{z<2!!9VF#H25c-j0XRt6VZzy9*+k9q+`+GpL8@D{F9DEgMZTDXz))u z6b=4K2cyA1=|D92C+&|0|D=7<;GeWN8vK*?L~BCa9S#0TCDGuYv@06?lZvCkKWS$) z_$L)bgMZTYXz)+k77hMMg;C(2v^5I+leR>Gf70eC@J}j;0{^5qqdXwyMS*`( zZWQ<@WgL}LB}BQgK0Bh?`W zL}LC|MPmN_BQgJek(mFLk(mEwk(mFbk(mD_5tx792+aTD2+Y4v1m@p60`tEp0`tEx z0`u<`u>hiH1m@o(0`t#{!2G*MVE)}AF#ii8F#oO*n17cD%)fI4=HDp-^FKdgBt*vu zWr*`4F#mHSF#iq_nEyEun1A~S%>V2N%)cGRe-@^HCWe0oW`8|2I*Sq zThdphFG-)5J|%rbdY^Q$bfI*6OyH(q7UFq#dPaOWR6YN>7oV zAgw2@B|S=7Sz19_URqk3DNW)2;C|t@ao=*AxKFqbxOcfXxE0(o?pf{$?ji0TZV`72 zH(WAFc=2g*%r!i#wHT&Yi?H`rzEyOsTl{fynfu4Uh1Uu9onpJ$(9 zA7Srf7qbi5`Rq(~GCP(X&fdTdWUplVvc1>~*pBSkY+JS^dkT93TaT^99>rE>E3oC+ z(rhN1g8V?fAZ^H7qzQR~JV5RuH;@XX3^|LOKn@{$kRoIYl8dAxiAXdOimXEdkmZOE z;(@pzbCFrdRKy&agcu?^$QVQo8HNl-WDyQRM@XzL)+g3`Rx|54>k;c7>o)5e>oSYa zDrFsG9blEPwzCRY*{oDnJS&p5k+qiP&sxe_#BygjvF5O5u&i08EEARiOPi&^Qe_Qg z4P^CWAuKBM7qgSu!E9x|Vm@OwFl(8&m{*yXnCF?Nm`9lVn8nOOW=EF-I|#nF>sKrgS$}@cQ@H-=DzWpTOUrz~7(1 z|IAN-vLz1&Kg#Aj82l&&c`*1KM{&=A!H?pW4U->bK{kwj6xVE+{U|QkF#J)Rvtjz9IAz25N12}u^B=`A8wNni zylj{NDRZ-71f)1*!wg87lMO>4#XcLRK+5cF7y~JG*)RuEW@W=5NST=plOSbAHjILl z>De#~Qf#wf7^FmL7b4~0MRIG7DU6WX%NR}Swb|(LLusBnLyOb8V^x7 zO9!G(mL|k;S)(9oXQ@COn>7@oR@NYhnpv_C$7FFKj?RJsm74*to{(!oFZX}U7RC+Xmy{5T!_lOLt`hxjlZ{F58f z!9Te^9sH9Yq=A3({WS1TzL&NdVqF^eC)cKde{xM4_$S{@1OMbZY2crHI}QAktJAk$$L`4KY4d5_$Qa7f`9U^RPawOP67Yqohjg-T$BR-$vaZ~AZ||q z|Kx2c;GbNW0{+QcQ@}rYOA7cWZ%(m?Sdaq#$(vHZKRG`I{FC!iz&|-R1^kn9QuHBa zr)WdWN&)}m%oOlX&PW0Ov z?`^B4}(s+eFO&v_#DR)I`j`O(N#s zIuY}4m5BMbOvL!;ZX2IvaN4>!g>$4t$oh zDeSz}qz6hfxn0~=*lFM9UV@!l%dB^V+>?4>0R_z`V;zX`X%}adI>$Bo=D$FUrG0%&!Jn= z4e1(m1v-cJi`GVaPOGI=&`N3hXj^Ehv~XGgZ4u3pHkD>V)1nQd^`lX!pQx{>52)9u z=c$LN+o_q4csABjgrRCetC)1Xp6N z!t)mgWC~@{Wg?}HNfk@wO2tcUkXkO~E)yu@1J_?{WhTLO7iAe)xZd(bx>>qGYPOWQ zl!4SJslieRc1AnYUPT|?R52JLElX%uDi1b8G;8{yjWe##2&)zx> zC`OLq*&Bn0>Bvz$d)<|^137|cuPTZcBZu+q{tVe?ND-dhQc}cQ+kA|_3Gv6Xf?&fI#1GFl z*~_dzR^nN{g4H}^1)k-;P5Xo_$FrQ99q*83c$OXJ(T*&|vn=}WscEWhxp=I z`iD*)vKY_O&b*00eDEwaqm+tx<5>#t#7|@qo+Xd}CWkDpp81zsTta5x znO~a5BxE|Ct>k^NLTvGD#e{)n$TU1#u0F68nTlsiuWrAO*x=cciw~O+YdrH^GMkN9 z;n`x7;R=W)p81SAdKj_5vqg`}>Jf81TX?{JKVpVwUct?Yh$)_V+Q@!EP(1UHt(%Ta z!87;9j1FWnp1B>@4nZd2*@8&5H^@XhbG2n>ASQU`qV_WyF~&2eRu_F_0-nu3^Y}Gl zglCR%N|A^mp3QUE{t+3EXLBb|MMGmD_0RAdyMnVV|sAS3b2On&PzL=Df-Z_RIz5qLJ`Sp6$R z70)JzF3Lqz@NANO^b|xH&n6C;9f=IbGvnszWMmkgO%QlnB1(8>l-&OzG8E4YBM0*l zMLZin3LStb;FXS$ipmB=7G)5%s%MF!&8I9;9*G62uU{w~;n z$m5w-&Abvs4$m~VOlJ88TNTQLE;)vOeJ%{n)L3tdDqxeG@yY1J5q&be%ym@vNMpbs5RPvx|2v7a{3*R#td%G?IpA zg7x)FkyJe6Padd_q~O_wxz>Cn8PCprm=lR4;n~?kgOia&JUbJ)=oXTIXQeaazasH? zcG_jJ9ukLVC!5E2A+dON;>2BjBnHop?@w$-qVeq5{2(PH3eS$JkGXN!TNFbhVo3u$6 zS&e6fvimn80eD8W@}sia@l0xH*)CQao{?XCYG!@FGtx;yiO!Iey+8ow9Jp1K3 zG?mqgXFruc7O-0I?0d_;NvyYc)^*_!mGuVCz9s*@%4){5&iVD}tk-zeLQQDu~cE*!?Wj&wPvh3JZn65Z7Hi3&z@xmQdl*3_SB{JI_oZ;JsCdl z73&V3J?aX*%({(d56_$5VpZc=L$XZ;>lU8X`&5^+ZsOSky)h-M8+dk~B6p5;9nb2n zg*;gb%E%!c6OB?tVMu5S}$HT{spwh-WV>%G!_vc-Hv+_;+MK zo;`cee*&@(&z>Gcb&$Py_9T$cL-yd=W7GEokllFph^69>l;Byz>#`7J7oOFhfirV4 zo;}$3RDkTnvs>>KxX5NayIJAGMGElj#>v6wkWF}Yeer95Bp=VNjU7G;$-}cM#B(c> zi)WSfyNr+=JgeAZbP37Evny-Y%OTk1RT7Q7i^Nqy%oz)*(eST-e@WU;06v2x-{Uh# z*i?gm25BWvVGLa4BCYWBCt=reygXNX^Oi4J3757=QVDzu?DPNkvlR=l&mhe{`JpWU zzG8=h?t1)Ysw+A^iBb7|oP)qN>DS@>gl6=CL)Jsb#3r=j{_<%qH>}V`7r!)KDe-5J zF8ZcD)85|2e#Nx3{EfD`E3wf&F$SU ze@=dAOy^aRzc1^B`MTGY;b(jIr%T>yj+k}CL}tg_*R6W1LBxBn zW{!C`?>qU081H^RlAav~-t)8$hwk3*g7Qm`+`X$lM_~Vk(-H){4MzC*hXU_Q6`xbQ zYpl>md4aX5TZnmYP5Hdyj^}s&J>j~;D-YkA7f;OlGTT0B)#y5j^z zhu&Ni<4t`Px)bC5IL76{Z{U5)W#sh04rg?h_MCntZLR!AzmHtuAiS8n$XR=e-GZ+g%q5(V{!5* zBHrWbb{k{73-&$QgYlmJ&}YdC_<;1MqJTN71DsJdtt-ak+bqHI2wgQ@;EgQ2Os@sr z>F3*+$H~^{ioJ^C3eOSqK5+kfsJGNlzPE5)=M~RYrhAFI_v=E%H`|l$NnH0nC9I=E z#PKPPBY$|mtoI*~Hk@;QtEaif<42k?INdbaNz6KmADBd3O}LHv4){p(|;M%?|$pDkQ>-6nc8V;J%4E$qjt#auI% zymxP%64tRm#PQv)wYAT8={@fq=USz$%EWlRg~FYWimd+w-~TsQygIIH<{mwK{O|k! zdf7bwGs|KBKcq(w!tRaWJt!wzMu(^e8MU4D$9mB9Ez;3g50aOS`7i?}$SvVPKU*%j zq1vn7O?(|PUywF@+r1Hq@D)3q(nW_7n$Qx*H*qctt$UDm9Pj(WI*dddUt^uD&BXNH^Imi2wyA#{8{rWs_(s?oK$Y?((oFE7F;EmnA#(BTB-!qno_x3nj2aNZCeUuc8_xkr* ziP#sUCn=V7%zd~39qgz$d-?Nu0<-c%*g64$+l2F)t)!X-;tW&4~d$cw^5O;k+j`PSqsh%`ukmzV~J_ z=z9*v+puHUS99RKcETKQrQ5Ek&!@rqOu4y&y2=kvPXq7K+FFLXz`O2O$OOt&E7bO! z>&_z$#KXzJ(zkEoG{w}rfD&G=yDSYu;ZVfT-9Pi-Ry@sFo3xw-5=e-?#fnYXm}yoY?P+_OVNjQziIo3qOlxjxUEWFuxBcFUx6 z{@g(t+JiUt3_Q;JYh95(5$_E1-9Z@d_g4$oV!S8%cD+ji-nSQ5E&jCA9n~BY^YB=! zv*5Gq6^97meP-F3$CH7#=io_aRXZ(F-)olnG4F_Z+nf0B$`gFzFA=W$S@z`X<3q%} zSuXpXojt21j<&l3%!)z9cX?*rTXA5k8NaR+GuWB8cC+xtH6jpEf2a`tp> z*WT{#t=NM%_Mr}(_neENdPKaps67h9cpoTTx*p@L);@mCI^aEBZ|%CtN$%*DaMz)l zuFisrop*JY0`H}>Zk0L%@81*O2HR7u&^!DDN2%Auyl)4brc2p<=Hu%=EA9GaSxn5E ze0SD|n31<7j`v+*9UKwIrxRPRXL6?Zyt5xk=gbHdgZCn?>=|C)|Mr&fV)5#jkaEp` zLRvR(g&w@IPbuNNH>yw8CE~qyPT@w3caXkfIL4bJmu=<~TckeA+SVy*q=`>VI}ZdVnJmKHsGldMPFpSi20&tKjmO%=0_ ze&pMRFr55-{{O#i)+8~7{r`v_JqY`pCf0-W;5$g4F7zZ3^`QG!7hSL(bXd1~5!QoN z&PyCpt*39AW_y7XSmlnEq_}U>zqml4cRu_2prmG$yG)st5Z{FUh<-l$c%dcgZ$Lfx z@fYza_E}TfZ_T;w{8hqrT{p^WmR~16#p*ptI=uE}mBgK5n}l_sB93p`=p9$WmF0T9 z|DR`PGK)_W;}pBXVOH7V{{tJOE#lQ-I%CB!`F-7|Sk)f9u@4^Or&tF2x(N~QcE&eX zjCZN8#$t^3_3M*OKLYRfBYo_z+;B$&%?4GuuU;USxHv383V4ryW3grj@P2Rp{!9Vz zE*l`XV^{+*?{Kpwjcb?N`S`l3abBB0=MnQBKkArWXWli5;~g!m!$QRI`P@#L^(M6U zymwDMMshV2{dmidaJgpAwa`AlLArKbygCqvNn`6Xx_PVg;EjEf9_PK%ev>f~@1X-U z7ht?U6rNmy@!p$Vt)T)FWJ*$n&92+-C}n!(;X8vD2oj~Nwco=8sYF%!bryK5t7J^R zRBVZEzwGx^uY#EO&yCvpF(w^+eBBJ?A*PMN#Jtykx}THia9!eflSBU0ks#vuc6V+m zf7jT1-ihcZ*~8z(xV%MUcVsM#>GQlvMq<`sAHGZYc#Com-q@=laNaBC`A#6>9kL;y zyL;3Iec-+AbidPez=A$bRrayuVog98qQXkw0Fzj(vX00oFQV-kGIRw@RBOkM}oW9XmxF zA1lmYTEywzU*38l_~6)7Df;o2(t%&5YXtY}^WEENqIh-OiIN|~jm`eM|L;}r_zx|H z{l7+!9)!K^3F|@F{{KPq96C`Cigf!Pi}fI1wGVb!589_XMd7fnzA1ME`A#~Ghwj+U z`&fIxO`xkkzRe9bNSUwHDh!|pU0nIH?Mj{{dT~eY2B-DJJ!s*~XZ!Z8_`oj{uB%QM z^-+BdaSysVlfzl%R4H+%*j2(h>O>shhVAY4tE*&tz5frdowaICgXj$sY4yFm;nDVe zz6X)kh*w9f`2tybN%tvMy$5gX^<_A3hg~CRM7(7iR&T&~R}3$jhwfGNUZh|^5w<|M&_sv0*bf*Gu?WD+^jaw|y&YYVT*A@};){;pW>NB{F zkFSduwnVGZiJ13i%g5aMcFE(dC#>VQh~x8g&QahE>-_}TdfZuG=d}oXk6DHNC z`#kS(hIn-hpHbnJ@#pcDQ9XEL@8iRHzpeNrMa28`(;>?+-cxlNTru7)qa%t<;qul7 zLG`4WPu)?A%c~Ttt=$9*<7U2^1ia%?_XaHh-i_aaeyH!YL|+|@bGWjQn78GIu4_u6 zZG3#)%z0fm56>s&-GAbs!`m{iN?iB071l9K#PRL9)naTN)O+5ua~|ed7l^U{zx{L9 z5#PSgn{-FaI{F>tjQR6;%g7$Qu@_9@yf@!CMU*fPoqzP4v2G4HUJc@YN9 zZG3#4UECVGcRs|tUCD~f851S%=0uFJjwK?FFF?NBIeBL9d25s{vpls-boVw)RPp)j zv$D_MAPuM$ua1Fojf**{-NT7m58l`tQ*qu8%rnVEyf0r`-_84K=KlY}TjkLo-aE4X z@LtIK!+ZM9KfK@GUPq4#ute`yEuo*rMr|M*r3-Ep*T(?%!??awF@zvYe{o89& zB#`%bVI6KFj?cyY3hk3^?|GMm%4WviDi=Moe@FTHDuqhcJa(2|CW3erYh9h<8DAV+qE4%p&>}jQ65@N1xaNZ?o`mSB`kY z<*j~!RFB#2f{;(okL3aH_SSn&AAq-ATQuouvL$*wh-^Y_pNh>ZTxaAQGTmwX5K?$-Wtts+JD%* zK@m@CWp%uovHBl;i9`L4J z>9^>P3JfRr(|^-C-2^i)Pn@$6c-MQk&FlyJf2qQ(%GBMKX!NdGNeA8#^ZsN-D$Drw zj*qXq%d9;!jY-_ScLy-St{YcKT=%9}|Ec4kh~pb-B5T`j-uoM*8rQrFQ_97-IdQrD z%R~9HzCWCli&;mVpm_7r0VvGgqkHhizIO%ZJwGOzLBu=Gik*S+PPad5i}7wQ8<7

*uGpR#psg2CSAt5yK-$9I)Rs{-$;W2=t5gPRkn?M3Sc>?7taFgiME z>9P0xWZ}BzqkbE+N{PF7^?cfqmMfCS`=+ptdm@hS=@Iu(hv?pS?=u}r-%lxue!OK} zuD_b!6ze|Uy`}TTtE19Gck%q_zxV%%hJT6r@6dzvdh{Udo2T#|6q#u!OVoo*)?AIm zdeG|Q{U=~Oh5(rup;GpmDZ&-jCe{Nte5xK7}46zsRgEA0|j`MYB19 zzbsHoi|5nI4TyVC;cw58dp(-@X2Nw#E2*^k9O537KW3rQm**EH?i9OUSjQF-$Cqtm z-#Kne?|YE`_jvCut3^M9R5bVK>|2Z6`+N_YvOv5#R*&w(36+5~;cw=9shV#BR zi`$=wcg4NoDHv~m`ME|I@0g&)I_rV=eA4C8b-_IJ5?^BH`;S7-w>I;`gzKj1*W4^@3n9Fe%&T3H_<80fiQ|1; zSjR#U$5-*9qALVzExr8Z_q*)TP&?6gkZ#MBeO5M@+vj-)4-&7AFi(f)*Ee-r<-kBND|uAh1^`GVx} zjuzI@BI5XRJ54I>{*A|5%p9bC+&A((0hvCHKamTAc_lS8fS)uBrHSjIpS-37XGWp2uB;p&SHwRx@HC(S; z;=1=*VI6lw9N(}vU%q<1?tS;JrtNz1Vyo!=fB4hpebmX%`aExO>v%t9tb%S#clXxr z!5jPbR-AX#v2ZRCZ#U!H2Ql8&p5fiYNk`}0)0V*7^u;Fggj^mP_QRImnC32Ey}!_U z1bDYjZl>J<-tT4SvsS>px0Az?+T)^#XYc3R7c0uzweazEk4|8xAJwK?Cm<`(iz4-sdYi*eQ0)Ws`lYpa=0ErL`|! z&O@!`S}4~|c>=H7{R^1M&8W$>%fA*w50Xks8h>=N1^Q^$poDV;#HZMaZmAiKMz8qw z!gUV6rL%tN5T9a0RI&qCqh%6zinS8f5ia8Rw3j#tf*X5(iZ!l_@aqZ|-Gjasd4v}A zQ|t4m*ww}2)zNt+ye&Gr`xI-~gE#ht>^SdKGIbCU@54Hy{4n01G7a@H-q}C4Dy#$E z z{94UE&zmG}9Z|_->=8TY-s5}lp69UrBhI_v!kqy`ycb+c4a9i+mOts_aA(B7y9E&GdLN_t`2)xV89Ck+l@9kqNt>h0_pacCzq%Te;=557M*j+mH zHD6x1?y&Xh>9PO7djfU$f`QVKclCC*unrRu$0wM@`{nw(_uc!qN75xXQ_)Xv#kZ=#=XoD<60eS$i-tM_bGo~?K@Z+@Cs0S?yrmV2<%xK6oldO7c<=prrTgZ@wk>YT z$-vv7a*Ior4-Z}0Uw5hUD|Z3?>ZzL7z}xEWPKPw$EjY2FVfiHsbXTmM^MnJ$ygQ4R zdEcmi%`XrWk{MI4{qm>U`29DCorod%8M8xFZ7 z`l|1W>M1m)S)bn^kyeRWhvxioihsJdeh=PrzE)=7yw6z#$Pw|r9(BH(cS^?P|H6Cn z#Xr2m2mRqKbNLT%sSkg6|BRh9UbV^sy^{0v;%7cF?{9Hywmk&i<-&F06d$=Ui-~!M z@NLaPB#<{P{!blYB93o`l-`h{+r97Jp2NP-l3$9Ry-8zAI)XPp?EAcR#H%C!rrUsb z@qhRK|CtSaFaK7UASdI-WYg?$EaG31>UtjJ02o)EYPx!`(K9e zh! zp0rm3<86NLo$F2DojB9@%f6jFwAwYR&^Cl8h-2#O=m78Y=+cc7fcM1Vfg0gMEYMGJ zH|mXdIS_ulWux+d+7_!Oe!Fnpgxc8$CfwUdxDi;#m4CV+??_=CVIq!ih6^jL zzh>`w`#d*rSY{)7f?VE_Kd$uH(LT@n!e{a7sGNoj2>Y}DH}1jPMeS!aKAhM|?^Gb- zJ*J<@42<`F{opYe??dXkH;aIG(6);Fqe(n8>wSomNgz+KSmWpFQNVlV5bLp)!24>z zvLxmR3smFomtXBg#Jtz6l~vx%Z{m*>uDdtzvATCHG4D3lGF84cU*dRg6xQ)Y#PMY$ zbXc^m?>%oy+_Q1Txnf+sZErnu%dzkCCUuBeN6k$?986MFD=YIV`ac|S2(I)sR~ z!|QRL81HnaSZ$2AeXLFXa^OwQTsG^@3LdH*c83@3$P*+VJ5?eJydUTB+g-8YWE(&J z`xXl{`M8dM(>dbdXL9@)LyX7PQE&c;rSrdxsdDZm_!`kT~9-g>^)UI6k-V zel0%Pz2|*`XR_ZZQH;l10ywJItM+Q6;W_O5yZ`UyPW(T!9QOZaJ$lf> z1NQsz9#rI}p+?k$nw7e~lA#C1y4@az^`Pd>@AjO89z?0Dj(P?A|LrfF^A2b71TAMB zA1sC*w7%%(z0a{tXz&E144R<@+F-5BS-OR|2mL?{f;S#(d2VgIS4Ld5a?_VgQjX>_*e{V6uuIpCn?RWT+=YO1Q=5`{j$K_dM~ z5wDJGF7(lVCP=ggZ%-T9FF5c1jTcpjco%iGBN*=h6D3uQxBmS*`X7LI{WDkNw|9AH zLt4bzM;SapK|f7}dBD4D>%qw!;5~Kt*s-&hSfImC>zt>3BIX@8EdAwQbc&uJNha^A=AJ6-`@D_C zt7EquN!|5N_ny*&w}))qbe#9Z+wsaoyv=lG$zi;g75*B5@jia`=|@GlIk7zEkjupf zJT!%~@z8AG?GnURoesS7hHX+G47^L`PPMUFZGjr=FHU^=H0)aznaw7=lpizx&udQU)RJF-<&v|^rh^+1o9pv ztfNfS@y%O1e4~5sc`w!3bA0G)(NAxY^o+{4a*y_T-XsGt>zFcqtv(DVf4~2aXxAn| z{~h-K);)UAl8XU%HX1gq>m=);rXUfKzPvTa&8$FhR<` zlH09Z$P;`GOKwPoQ|wWBd5ucg{||JQv0Vn&Addzf?%z4Zk?;;unbGnF(>+i5__}bT z8HIE`;#cgXk{maAe?BE~r`TJcQK0$?Si>Qeev?Uy{>GK<;iYemNQPnnd-{@2aeO8x(&uj*+5+{EnzQxH zEE6g*@0{q(KF8lb<7W%kg$LBu(~lGL4vH}}O3ITw-kXJWM2R@QiBV%8xBK*-w;6xM zzJ&2&@Se7pm2+-lpWh&rS??38j=dktL%NQ3-<&Y-!F$o8vU;5NyA4hwiFm7{d){HZ zgPZ1e&)$niT6LQ@53RCabDjje#~ozs^9SC)xAvRS0=y@#jCo%<#R7ep z=y$2Bnt1akf z{~w2ORlGNevHyRi;&5nDUZ3Yp;)_|w$4xWF{oVgd&?f&M4h1$y(|hzFzch_Wcn^{( zXX_C4pb>Fe=dm8N!ZN@66x+^_z9$JdmoYg!!O#o^i#^bTUOx`t z?|~llHDQrK|4|lb?d+=uNI}G>*pvqYv^WbN@oR+Z)HgoPtFR`12T6K*(}Hju*v3o}eTkhkGxfyAC02cYgA{HoUL9T!68zWxxr1ce zgZE0_7b~2%>5c|%BHkz8HD1JcU!82wy+QiOtvaFxybI(7H_Bh}(BWImuTVGf1T&wX za4ZJix`(v=4+8ITOUxeGjkG}L$I))DbtUFKYNu5!IPHd4 z>_GRP)`Rzo2?NV;-rjA8#uD+irYxw$cyB}>ck><*Wjo#nii;vx1V109Ae(LB5qNimptYx3)kr$r6!OE5%bp4 zeBwDKSn_y364qfP;`lhRYj!*g>OJpzx0@V4Lopt2c^}<6d)9$I&zp2a%sK+Ao(NxW zF|`Np<>~`lao!x`P%R?f{?~JEV7v`=vb#4(PhPwF(Y(J$Ns@y8S-RJBnqlNyIy`{OoOv_cHRVZr+`)6G~Cwy>NQJ8#(uQD7nHYu5>$3 zAh4d5nghI#-Q1=k0NxR^+tj~nTB1${>5Y2L^9k?0P5E(aTEDI*{Q1Il0?ik%s+=MS z?=cm)Rn#;EO5VM<8Nxbti8#KgKI5D{-wz|Kk7)O#!>-shx8sh;->19O{cz<5UZ3yY zaVx~Dql(s8R~%gY_x?W-97+1`FhS1l(Sz2+6>h_O&=fw^kf;ZJm4EMu^`Ng?%DbOI z+BQG)lnwNt7gE_?KNLMsgPRS@9Hl%2tT69)eCRm|BgO8^sFnwOL*cq_N0teaZHTWyrY?_&uA&^1xD8UPu#P+t$5*XimE}>>`~Cmi zeIL)9e~;{D5L{xXdB z%kSkX*c~Ky?wZFFfj7yt(|FMU543LCC$-oQJi*ca$@b@f_vQz~N;80WdPA#L#!GW_ z$%XJS3r&ePNTt?(i!Q9G=i}=<9ab+o`;nOUFwZwkhOgxDzAUUmUBvM*Pf;d&WcQx8 z++_O&6&YeokjGQL#D0=LCrO?4-#V64;?=RJK;xQqM)w3cs|WAZ>O-n<-o>Vc`b4}J z7=I7PczcaaACB=3s`HfaeR*t_(#il z^?rjiZTtnFd$UEq-lFlwvbep6Q~Esbt<~byL2J{>N=xg0yk%w&-m88&t-^WBI<3(o z;{7eQH4o!Wp^og{AT5!8H*g5>UcOf<>L}F%eKy?e$j zlltRZ4x6LT{nRZ;8;FOKO&4p)!!|eY8-?qF4!ye9^_=(t=~P`i2f>u%5;vTb2v();c`(S6df;&Gy{-iAgwu9h9JuFvx>i59PpOq;ofM*O*YJEI40|8k2< zIPZ2%RF{bNK7%QzFx~}Encer^G^Rf`U;^(T86PFtHXdqUmRea4A8$FISHU^}ytPc4 zjEjM{T$9g%>|f^Sp1_FcBvs<>O|#xSn|tjcf46X5was|y&wuFNp{8{z)k7uk-kZFz zj(8ErmuxFL$5X5K-Fx^BdoFLa7*}t1-MxNn@u|Llc`H@SIwt#uEC0R!|8LEI|LeaA z_W$#G^q}Clu#;F1(tk19r@qUBMAU;)^qhRK9@H{ce-Ji78eeUix*K}XmnO{_A9Os> z<=Y<3x?aZ`HYaePYN7raS1y+6fX+%R&~*eRknNE*j2%_pLR z`~3dj_n3Hf*m^17cZ%wsAm{ery}`P1E`EyLd;W?E5${o>26$k+k2km|V7xECXRX}? zyk$45O!_(21Kkr87_Ih#C#c=SW(ZVd`U&cE#a8>GFrZThIp6#WD# zY56mAv+NOlo_F{%@#^sM6|52bc|h8s2k-St?ZXbJAYpXPv9goeBv$OZL)m{BN%ueBRLk|2i{}!a-=*ui8n|M zp%e0{+V}Yy!gUjJ?#c8|B<9_s|8m+yzU1+464uc!;`n54E52^A?tS-e@Bd^z$z1f) zTdhXlihiz7>hrvd#H_=1Q`*$uh2598=Jenl)NytY&U@siMH7g4d%4!m!gwDli|xL8 zTj~G#p+E56!;W1ZKgt7D_h3(6Pw@~u@CsgY6?n6|?!Aow-WPt{I{|`zhU%l8t z%sXl#`pT=~J|AD#Z$iHH{wQMJ@7p!Yjm938xbB@QtmBJ_AIyJBSd%a z`0$3*=y5@Po_E_q@#+X}rsb#R{eA!6|N373-}wt+|L@YH2Sr2`DPuhd+yCFNcA^vY zpvT&G-;tmP(Ok^bunp2tZ}Ng=(1Y&QOgZcd`~P|8wxHEJd4lUHkE4HJr`Vv}atr7| zZ?Y~!g5bPBD)wQzw{eLQ*Yi_Is-fcxT!@mG;UX$6hDf@YXl>GBvpMm$x zki4lgfcHd=F+;poo1wr+%sAs*w=gBrbV_I$U89}Z|T42cXAoM&!1vRvSQXTZRjSgKNF-=58h#% zGqyPIOXPMbBHs0_<1{edvG*w5`+o(d-kccV{pHz`h5K|pP)ko^^!ag~;BDf#j(5Pj zj9NQp9`HUB*Idtmr?;*djCy@Cg1CFrWpiWKMAY)DgzIDjJjpN3h@b!eF8I0ZbN)ez z>)!o^bvde2*Lx~yB~Y0+12Nx#&5wUx5_K5sGWsLlECFdp6@4a3R& z9=tcgP`EDZ;W`_I3B6Enl*78T|YCXshmr6N8LwUr;l99o{jYavWWG7Nw~}qo*+9%& zDg4Z)F^P5jJ@~p(^G{q8V%}Sy`<*>HMDp&vX$b4sE8_S*1uWvqpYDD44p9F-J+$?z z$mjn_uavZATrcSJv$wc)4D%g5M5*BK{{P?Ej{mR!9yrDFdi0>Ur4`rk9@JJggG1DV z+}_um#rFSa5{7kugH-4+t(}$d4w9V*ubaLa;ekGG-K1&l#S@G?d_J0$(u@vZ-gP#B z9`qwulwZGsA(n2VE+)J+t-XUWq%!lJx)7 zaZSYWUD8p~H*^dv$wnH}=o|->nDl7%2l9 z&RakHC5wpn=Z3e}Fy8(Tk96}6@l{D11{0)_m&24%njWanV80@bSf0SgMLLoOycIOp z$r=Oi(w(FQx00ZHH{6jPwvM=akBvot{@j0;kFWb!)pUzFj<|bEeR|+`^n>K_9xtqe zE#ml$$C*bN>Gq!YIzuU{sTkkh@_h2;LsR|d_4)mOnyGkogjFt)lH1nZy%+T09raW@ z73V$i>S-ns?~_+1)nL2};{3aLyQ!a7@&ev3H^2W{H_ih+s(C5Y30`lJA#3j@1-ut- zG|im|yshR3Hh66|N6#+*9q=HTm^WYcotxG08a}=*=f$eY<7X1{4wJi;@g{e_#C7iq zVI6TIjxRXbGy6kg?|Fw^>}*e|65|2s6VvCuAN#rVe|`A;`SW1^zoe}Q7`x5t{t2a-M{UBS-$Jeza{Y-u=O?-+yclOA-Q{E*K zcZ#hM)^SC|@vY9j`7>ow?|abm{8pF#mqb4x9bU9A+0VJX@Asfe@#^r3eJ7<-(mg>g z?7=&E{5LtAx8gjR{zSa*EmTRycvo&(-pzZY=YIbv;5~lyga?CcVS{uiE+!iG|Nbo} zT?b&i{jab`0dMv>{oEi^b2Nstamf%fV&0Amua8o=TFuATHLzdwUsF$firs4ZS@vYJ zU@IV%_Ay-j;WH*Zsh?}@3vdo(?NX2)a?)P+ltDe!^k{|m1P zWP$fF=l2sv18>=Ji*~<2&C!+_Uv57hP0ZUUx{~E)ew&Z4+frNS9CDVJcX(0#PSsVr zC9Zo<64sF*;`od<)VzQCsQ0{MQ#Idzyd=g1X@2`^$|>(Y&zoc@W*wJx?rvT>0K5P1 z*@O50WADwwsqEhV|D8-JWy~z3!H`5rr7lw%WU3HlZw(R(l}e!yAh8`&?anKgZ|!efRzy-T&!0Z}<7`c-`-Hp6guKS^?Eb zA1Qdx4NISohPNmwD;~z%r>cfLocO%1IPoXgy)DRdiN6c_e_{65f}wi|q$sO3oIC(; zyT{1^iU9BG18Vihw6vjL2?~pCgwgRHFyXDdbGMpEi4$vgau58&`+vi;!f))EVLZIQ zB0459@{2VpswtGEAMd4B4{Gm;U>|Q;%T>%l%4uhMya!on({Z)PwCSi9dH!!rg|~mS zTOS4Qz7h{^G`tn<*)w3gKkPOj;~hGuljA(!5nb@U#)Nbu;^|A$-()P&0K)@ z(AqE3Dgf`qalgVhm$jkc57&d&64%_2EAi_hdhIPX_cZIMG~>PzV`OKPMeM^^Nzkq0B3LizW?{X z(y{+%e<@gE?WjB`+{D+3;z0r*R|}(gP}Nxf2H1nHMcS-{`+pH*&qouWg3LZyd&1Mi z8p7RszViMt0?B`u-OgpegH~_3dzlA#(B2=i3U!OLq3157&;nz058C$WWpT01D`Ghk zC!uxjXLm1p1-W0zDoMxrNa1{vIn}1mpebL;eaF?_54E?_q%V z^gG$yk6?SNvp!K}p9_J+@q~NnVt{w6!jX%D0B^Isv-noZfcyWPS)#URqvNd-d!%~( zoGPL%5?8~ut%j!_9q;7OvX74k7!Pj^M8_kH{B}m1=xVm0AMc~(cb{BIpkaa(wb9Ms z&P%4p8)r?Uj*Z18%YILgY^m@L8JZwa@P0o~D~N{oPW|NvVZ7(H^ee!4r*CyH>jHT5 zXvm8+@3DqngnZ!L1a@yblM<^W0p9l-KBtQUyaUHA6}il{Awt96(RLC#-pA5EO&`ms zBI1#_9;IgEL|^m@Qq@$q?VfES!@0LBqGJ8Y)P&_knMI znJ|5Wgj-IV4lx0XH9^03Zx2)99h}?eMZtS=X{-Pm-U``ATw%OfQ~~0(ghbGc`PQNE^ak7s&2S!wcl~8E?FO1auXeI2gRM{Gd+xl_fbU08I1fEZ;IG_*_D3011?^8X?h2{I2jh1 zWb?ndjp^N6yn!|yoBZN#Nc}#XXhVhf)zBPP3f`kvT=>!OKDN!Cj5pNT_iuPRA$Y$> z@ZN~v-GSh}WZH1tPfQ!ynj<53h7BF>VA6fh7l&RGw;*xX-e+G>_CYUB%v~x>-!UNG zHxL~MF!I}Q^Q^IydlCd|7TnE z|CQec`hQ0%4~jNfaE#(XP8KUA(L9Ld{H>Om*WmuYowL`IE6BFU#r|LqQuO;z{xjf; z-SuA*uE(AtkY;}z9#H~IY-kSt4hL9b-FIhJ^GbpFzYu4|tv~ERKKObYH?r>qaU&9E z(zY{+`y~1j`#FDYNB8CghN~d65FH~J`RyBX=E}cB{~jc9|Lj<jmkj_MHUuB{t>N(uSaK zFNkGGTnF^6G{+PjZ|yUzDGiSq5AO^_#}17A2BRlN>l^9EyG`Qcv#90Rc<(!)sPK-g`u2r__r@)8qG)(0gv=6#@h(gI&4U!P z124l3Ql-#BE!cxLh$*(@g9eGi%>H2WbpllHHpe)=0#DNR<7?UmJgA~9>{E~LC#X$q ze@@P4EhxBj+rpGs^a?Vx_FU}X%5vgWB+hKLgu%hh=oMsp2WNod_$`L3Afpi-gBbZ; z&g%%ds7-%^RH0LS>)>;25Bj{tsOsLrnsxtSdj3EEb$NOQH0jv7%KeCL0QrdB2`aqf z_#U`Z@D|-NEQ5x(f|ArV7;mw$qna?@c9p?aaRBc-_azbxZxbMy`AI1~pYbHIyrt)L z0Nx)DjUO8Vc+YK6(@ROvf(E`lu^1^tzyI$M$GJOA56g-DNZc>qot;U7=v(Y{GczKI zrtu7icMhWCJw|@RC9m=OJb1CM%J~OS_vhT^C*H%JAg$*R39gAEF+JXQO$BJu(Ys@$ za?9@t(s3%hV>>FAQSd(2RU(as_q5i`Z5Z!?_8bVtd)uehURQv(&n1UCgNFpjHIeXr zh@U{}zCZ9$1K=&&U#l|?@ZRw>%TVBs7W6n>om)2z9q*s_4Jvb#Du|DexaUJxk2X)C zKajR7(TuP)gYocYeeheyK8*Y(&c|C^tfU`r9ejeM`Z5~&f1j`M=d!by9&en&AZ4I9H)@ry6>3Qd&b;o0e5U97E!&af#cn z<)gcIP0S>Fw7_kKbMGodM>9r#if&c;{gL$J9sfnFVtxbm*IT%`Px1R7i!uN4mZof) zbnN6iqPHDfkPd2ZCn~&exT*D1@QyOyw+IdI8ZCpDFy0fA%QRrTN6KF5LjZ57noQSg z-2|v>(tLr)IRYvCior*C_7*XHu^issN^z;*5wcVp66{#0I@*Sgw-smlKGUk_M1CaB z_rS%*g~{l(_wjK(WBoS9!`l|o;f9glHb*kXx_b+IM{+5nVNAmC_O`=$#9`K-^*^h4YgC({}tM0^e4=rfaN^08j4SEH+ z!S{vD(Vi0GHze+1N|N$-8T2Lgc5a+Q`oma;TVk~l9SydvmmA0GyCH6+i+#@2d zX*eLAp4Q{>enOowA*3U#>#4NqSaDuR>30Qrh6?Yy0)p)nym2pjm!sjG5LHU<|NX;d z$aufLTX$$5z?&uXth(q;0%Ug4y3;iqPr6||w|^_ZJAG;|TOYvt`2m(QH}7dd_q4RL zW>nCZ*bV*W4nw<3iAhM@4U6g9o72$oUilh9&mP>f7N?zRceswW-piU{f zvjnDT!|vU;z*2ex!28v@JU+{40>t);^V`u3JSnedj-o!myYMBqSvSCYUB#To2a>g* zyu@I~?c(To*UuJ8NGmTT<|1(_@o9;z!RUC4b-QaEA7nhd+YlYgG4gw$XFBSJryp-i zy)`R6*I*xSVLdQg^Qn9v)8j2Qn}sGF-Z|@((nH92pQ6J1c1nyd1#ePo;8HZaSxkie zV7&Q)T+*<|F5r&apY~?Qu8)1z$@F;Rf@stsp;Es5cX8rEg?Ie%pd}Q%MF7+{!;?*cyGx+bmt?$TMM7x>piXo z$;HQ;mDQoUw=ui;#JlV=;&LR;JzxEOUI=>spD)DqlWjZW&EEDPI-X8bOzSW?WhT|>Vt5^!u_b@-+FO+D~q1U3a%MiTY`uF@l9evIJt5DGYdr*1MgH?tQ z#eB7sP~lr!=X@IiWMgJD`t&)TWUTnO8D3(0 z)^1dQm)Na?H_v=5(}H@!6J1wzqI*!z{;5kp4T_1qNZelh%(s(&_{2^LCw;0Ee}mzc zSR$fB9V5RLc@Ls%Tj=+oqs~8G4@+ZvkeTb59rKQrGrb3;ETm0Gf&#A!{t9{i?@opH z{aNAU7o_3mEgyaFP(s7o!8D%S|ML~3>%w?T{}{dA0q_=5h^cQnO@I=K3%})*;Yl1n zyL+|+yno#pPlX$#Py#cNL=J?YClYGju zAL(a2yssiUOfm91v9qYmpND?DWvh-a(Q3wSkZ_XbQu-|~nI3Q4BHDB~?bx;{;r9jU zZd7>RtG}B`ac_35v=wN0i>!Q1-o4G^HYMXdoY^=k2O1>S$6uUT0}0SMJ?jN3#dwmW zZd=0^fcN#<^Cq7G-X`PO8VSI?J>C^e))k=R%^6X5vsa*m=!V2CCyr(s*`wpVaeVBv zrAG|Ix%UD@$5xE|*o&*z;Qj}@w{y%w4zHiYKHl=V|IE~dugli|zbX>`Q~zCY8g+b^ z`1xw=_v@|asPImHp!AM{_Z$@$MKrv7Sy__d2C2Acn7n%%Sj9#R1bEk*`Mg|ohX9qD zUsd?=3{TSA^(#de;GMD7S!fX8O=O+A^{!S6Tz7fe_RMQ^yiZSiCrO?!AwELl#3Sk? zn*MM>8t$VG=a2y74JSMh9dj}AYwxXzvA#jSdv|1Qzk2cp4gG)Q*SMa!cFaGV;2x$; zhvq98`QQEjSt`7f4rS$2@b-MZSpg02c1u<=-rSb|j`!Pt;Jq2aI}^cs$6iaj(o0%U zi%@%(%}?~%TjO#c!)A{X;(H`c<=Vvg*#z|Mt%G9S%~u!@?+=I$M~wWoaaeha^3snt z-!e$X%^usmU)_Ovw+{_6J>CU{8)?#U_xd)-`|{uZ|39^A{;&QX-@TD6R37wrnS2?= zgG8g))zCa>{nm?C@Dh7+?!ql_gM|Nb&CVJ$NG__cEAdVQ=*g+5Gei~w>DIUJ*1N$H zdp0~zw;3$4k;gr9^TM?tAypm6fK2oyHsfKP@!3m-L;)mjX@_=nvN?JMx#=mJQp)S= z3|B$sB04r> zrG6B{;k_Kuu^uBoHz7es{r&XgEh&5Vu~a_|6{JD=o#x${OpiD2Y#D7j>a3ork}Jqa z92MSah4VI3@YX7dQ$@o&vu^MtjQ5gIDKg&2dpBJo0KD7x>?p0?Lx4VOy1caOz>|K4 zd6(@1c)uL?=5GOb7nRwb-dU#wJ(>tzyHykY3(`Rm>$u}7A?pe1!I^O2{icbHEC?fJBaqA#cWAlaRcwhGC zp0B$*n&I5r3egdck>86D|MCyr^yAIG-hd?Giv4k-;wyv9J(XHa@7{VxchICGS}kn* zeHZd@;ye}J53NITDR^tF)?S5%_t4N{^6{4QH9N?7zfE3a=LPV#N?X{$YEFPe9aO(= zeTgS6{*{wy4Dh~HL9F-y@Lu>;&{L;M3u<653OvY#j(2cvY;EIE5wQ`8<2bdI__`Lo zIH@&yN?O{$cz8!5I$ALDJJMRYqD+{6yxGcFJ66^|$Ns2s`>Iptt{5;q-nggAH0ju# zQz#gA>2Lr4zuLF|r+ztTkT|G3DBIFj1@@rTU_knuJr0NFLB|v4Il>iWme^-&AA%d&N4ge4+K5nZAM?122)&qC>2af4j)O+i?HSPK9??@0uT!C3gG9lJ#hK zrwxqmhw+|nuOTn7BX=A_t^vI3-A$Lr9Vb9~V%c3=g$bmIEJ1Dffb_M@Nm+RQuPr#% z&ILY@cC2dZGhBwg#M%UWu-@uMBsw5*na{3p&Kf~qVw*Z99L2sf9^S_h9qkzTY06gX z$QRJR#HK!2`#m-QyMk;{?iuoVvzF=c?iQgiW@Wd9vUn1prTddaqeKa$@1b4a;N9EW z6VEQa2Y442Db|IY(t-*;8^2xYi;j1(`mmQv35l48#64E{k-;H=?%ogmr>gh2GalZr z5gi#A`I){Z6ltxb-@SKerrvUTLBq$19+hgVUuQD?fE4Hdf;Js5Vg`QC|08Ep;r+z? zj06R5?)24b(eNhaKe}E;fMO2* zw44R{e?f}|HxuAN6+xC6ZNP(YH`^840<@q_&HUR8|FFeg`t|AKsqs7_C2l&0cS-dE z^ey%_U-jF!j)gN^1zCmY=)uVEz3Pv(UU33+SCH1LtaOM1H0(k0S*fD;|B{MVvI_k2iIg~{ z{ma*HpFv+@7kE3yOTJ?~yq6(5gfa3<(=PR3JtRms-d5rn3ae?jL8|bQQ>^fn45r6> zYdUQ@Qev`h2Am@I|6Ejf=cNe;QSfeAIyM^(?^|2qJz%{3)$Wt=KD}z?_iTXot}mw* zpd$pxBYafwAi!HCjgSE!kiI?OHw!)>omF_B#U8kKP+8L(sXuIQ#VK<=Dibdt1|o55 zma{f04WZ+mpX6#`uNlE`?tKr@QG$`5TKS@0-B|kFyT08xAWagx|Mz^UH^<<>W2VO& z_kuPZ1F^&1PT&S9P@K%6!aLXd&}$0bUvR}NXn60PdgKG+EwILteEwf2N!G9s;LWG^ z>blTD0>n4D(D{cTf#iP1>Dxwt_ZPuQp)r8>`W(6IEZ4Q5b)`1zG&i8Tccb51{k_=* zL^UKX`#9T;DK_-t#CqZI_KbAK!@CpFaRehjIbpGu{&xED=KT`hu+R#-|1bA#t#~ef zhv^%nr$V&p_^>)|mD&?B-kel;=NR~pQ}EU-x;hID?+0FCXJNc$aiZkeTmPqZmRSJr z$=d3tTDAnp_u!kZ1mNCz2h2BU1H6r@`@RnYykB063oZg5C$g-T?cIM99q)DQ-Yeg1 zeMbDH`a4ektLM`5+tKl!vT*8h5@x*Ngf60Ew&kDmyKHz#+ggnN;$)y?yS!Ks4Tlq- zr?CW`%3ylDagS)!asTsjFUP;{|1o60|Iehr63a{FK_x7Tr4$d!uh5@|=0R$H-?zXX z^dtKPx&L1;ald#T_{1(}>Se{5^91O|=0P3@aR0v+&xg+kfCp(BM-RUM9<;X1V%xB( z7Q{i=D*m1a-Gg>7TjrUjokL_t;)s_ecZgS_SCDxJYDG_<3uU+p(h|{8gpprtL7I?c z9sNt}#ECw=)EOE)=$f^|WC` zgckJmKZiIg1*ES%OBK=X=XgUgAg4rF!GzVab7jg zb^7rxYN+s*>Zajt{@js;awP4BuByf2V46bG`u%^ z3!1}t-|+uTe%``}@8x#*2C2pUN=J^IB|xc-Y8D(5c+x($Km!86`z^1Y>T7^E*U8BT z_0d{TG*lX<^8g+1osy}G8%=YGF-V+ib}P%=Kj6K0q<2A>W*FnSH=^SpMt-)Ffi1>ld1@E_u z^ElD)4yfZMz<6K3ZcoO$e{4Zq62Mzv!I$jC;P#frsY{zrfZ>G5FRcSs0Pp&zHZIiw z?=sg0TZ_Y5P$(PZSOQggp#FX>#l%W?VxzZEEp(%`q_gh3q5k`KF z-FK%Plj(PFey+y-`p>Ypx7t0fKU6hMVEP8h)bkomIyT%@>=6J1Qc#?5Q{heAxRCsM z3p{%}z1)uj4Q~U#vBNOl=RW*)?^PM;p(z0G;4D`ALnjFk>zjVPWtg)&*|E21kq4?Pb5hbjxztZx3~i|>iD{>K>^g>fA9Zeg7q1A z&_XH?dcn2-CS{48mNDQ%^Pte93yfh8!gEV)gg=mOC}W=wzyDWiRF|dz8l+XvY-ELA z<4Jut-jFT=51MW{nVbMT$nJ1&iD$DWbULj%04I&^K}y^KV$Vggh$oOZ2Wv6EWv=Ka zNb5CA1b*0FWw;7b1<~;VBfl-BA*I3F=zoJ$GVuJ}SAN)MkZ{QZtAu*LmW&Tm@3UXk7Q2z7HOPGE@ z+A}MVCLLX^%5g8l$ao7-;awiPwwQwV&5i8~(C~inbF&_dch~g@^80_kPUn<&0le?# zOADui-P_`~3s{T_@TBCp(}|}5-XXzZK^XvVX`RhRwhfxl$saPod86nzNOe>a-VVw< zB|0N3x~=(eQ58I<5)hecEV}-2Wf(+_97m3@5IX zU3j|{od4f3Evq-@F`mSkV=-Z>2ybT?^tyaKbc2Q ziPw?1wG|}}n}49=J!|1eQS6=&hI8*bhz@p){2p5vX$)~pt8g=ZJ z0(b{&N1i_e@P5n_8L>VSPkQ6*cIyzpJ7R6>Kn1{CFI?ij?p`hEc`V<73(Dx*TLm4T zq#qS#6DyFoy*ljIWxk{L|DEF&Jgwr4H=HOzbo625cWT+y|HY_0==Go|H)V-+F0_3hcdb1-4Pcn>tsRsA|w}v)&-GM7e%@MnSRay}L zGPziS3AzW>H(3-vQOO|AN8}PxTNluoRmngDC2RGE-oy-IHWC*%=;7x36@7`#J8)6%pm7kx;XRD#D8a~YbJMJ1 zx&OiTRwG8%5(58cPa@g<~uP;175~0HTRhBUM25Gp0Y>|2= zh=%uV!A=9%z1g>flV6Y?V~@=(0C*ejx>&ryiU7?q;G0vMgD1tk4(ap*c+bqz9%i^wco*$$U9<_YRa<@3~ttllTaUOa68{?Cd9Wy!k)eoT!;*JiMa#Y zTk=!XHbtKP3erifC=i%|Z|?o~`*LB6!2O~>r|lKF{2WcL=P!uzFdk29q> z30rYj01fZ$HL|;5yki2n$asfk%x!)E@E)4+D3f<1K=FGmAFq3dC;2Hn!CwY=Crw)A z-T-*FT|TiZTuloS9$^#cT!D_a=BZO3_Qhrr`H;Brb8H&o1L%0`Np+;`%DBRC?yZC9 zFv7^stgMDx&7J<@+e}wp*7_GUx*6t$`y;2 zQt-BFI>C>I_qDT&$#~DN_;>J=|^51Njet$bYeF>yT-XG!W7SUiUAK_6Tjquet68E%QiMgP|E2_wIZ(=H{C zKJsDq@&81M)%+mmSTzk3q~rJ>>-$xie~CR$qYe?bYpZ^r|6fFfcU}2$cM9G@Bh%t& zcwb%QAq(UEy+4{fAmu(N#|=Mk*&p1gYEp}b-u9+0O+Esi*j*G;b^+jR8$a*{#=9zF z`{3?LO^BmZuj%UuI^I_NzoZZOJtodZ;=JnA@llcJ6=Y)j<^wpL0EWZc8qx6pBfqjH zmHgQc>Brkca6puA4h<8epm6;ZdlK{GeU&yHJiJwMS-&Spl2mxtdR}@;!CTI;LJSS> znA2}oz<68PPLPkch%b+BEdqGU@Ql_E4d5ZQ0=+RCdpzk&tD`xL_kvga+wK9pkL1+% zm``a!)_Mvq{sZWE^Dhfv4;y?;+>6A0A0OK!AB2u~h{eyy8x4$y_d-O+b&UM16`Osk zXXwX!uKJVN@*3C^BwaiC$E(D|nZEx&Y)P9AH#;#oDK~P1BteCDjpdOH3f}zM38H9t z7sUImh4G#|t4GFr%%HsN1HfBs#!8`N9s$Bv3eI;wiYFDXT>9xe!29`;wdFA0p`X_^ zuH(>xa=pYH+kc?rjbE$wZja>?Vg?d-l)Wo#ARZm>t*0-h)||M^aPGYy(P4y<_O>0(kS* z@K`TeuLX&RYx{}0qHk|$`%FUHN}mvgkhnI^v6if5=pQFqq>10PpUZf&H$6nhevJGM z+|0asM23F64fU2D@|uOcdyDhX2uy6yWd7o$hBh7NrZiH={@(xh&sL2we+K>k5-JaR z-&5#8@u1;wC0R5NTC?wL<1gSr-0!-!!RP;D z*_Ti^;6YVB>G=fyeZ zu8}K9St`7na@oZxc(Z+dae((yH+SD4ZUVGhY2`i0 z2v2gplcVne@Xji=&V|qaI|vX-Z)-K7)%e=v?t1hJQbRA~rRI@z;wmKWSnJnv4LkG- z@=d?@7uE#E!&@8C@eU(DOa1_FjV$`{-oBfQnEHi=PwZGeZq*Wh#PoRM#Awu^#crTuOgOp{%E3+0*L8=d$3X>Y}(ER7ZHx^jn zNh`w_2*Le7VW-<&xIsGGTvKy_UkiG}b2PB&9C`)$4Vv4XGVc-b6%uDF$u0PJDS8EY zqbJJYlC&Sgx%YQOM?6M;=87{fo?W0HZ`hkTLxp$44!(~Ryzlm0mO{f@)zF;_ZjctdP$J*n;{E;8tBU~d0rSolr|Wp=Sn;Gs z$d${Ez2GeMUXhbQsWPc zWzdV0hliE(d=waO_I3`@@fah&?i_Izt#JC?+wy36$~783PK+~s|7XmG{~uX_{$HNTgFZI$s{hM_Iz;8sJm^JDToYVDri*ElJ;?H|k7pfd zkX)j~GZq~pK%Ck;#ah2vk>ZNt^+U_fk5g^&!agE{Zc+!@TkY{lJ-;DQI2KWE>4dX1XrD#HGg{*}0kI?ZB z4(=p+K@W+lNZjc0q~vAF=y><5ew@6$*N5TojzDybVB~k9_LU5)A^muFXY^E=+@PWV z@A&qsVkPt6AdNdaLYofWk^tr36Qt!-c(=I_2^74=m**}+!+ZMnsTVNbj}rEhcW+gq zE{~=Iyw!`{e>9vSKr>5yZ@rYjllJ;$3c$O!+wkYMr2@Q{3O)*x?$U(%PdA7~>Y+DC zD`gjEjJG}{_EO>$zRmdH&>N(qd{w)MRg8!C8bpT+Mt*ETJNLK<(2sY;`C6H{&)6qO zaXu*vR1}sn{rn$iPn!;@kyq<~rIOuy85Q2GnuCHAy!UWiT8f5ulK;JDFy2Oo!wuo# z#7?%O#t{H-`AekvQ9cAnsdF=L;5u-$NRu5i{67;z6|HyTM!-g82Q~#$xv#Rvm4}kms?>+1+hVZ1%>oa=K0=%!R5qg*g@IF#^I$F9_6Pi45 z`Z6ycI^MISlH`wwr4h%FIJKg{q`X}8;sj^=_37>>jE6S|qJtA7ziPGhjSW)t<9#LB zOwn!%d-mq(uOG2gpZVwio=vpr7>qge0U!Oh|Nlp)&6q!e{(mKv2X&XO`NNH7FNRxU`w<;4 zF!G!KCc~s6iI?v4|9kiBtJzVG-T!-L@p$$5-DUdz-}449O*#(W_R$M@K&~K_sPOK( z_TXPz?9%g^mC*1ukX!NtUSjJ*LsVhB9cN0`xdOapzg~SRqYtjw^=&JB{nd)3cyik+ zc!_0Q%$AxC@XoV2+Tm%g32ikn+cZZA9q%0q->;B%r4Y9uaUG7&>ypgT@!sk0wnkXX zo8j;_LUdSQHV4z-xYs(&c*0>&t0EY($$qhzH30F64@Y%Jg#q(O0_ zNQHN&PT?>GZ%bDXMKrt{JHslmM;27EV&Gvmz;J zk4nI|x1?Boce)Mm_HT%_7AV$)Lh5E(mP(^HNSekQUTB=ZPrQo6P5uZOTk?m;i8S3D zck>7{-f%(((Xj<1zkYtG%$tLLycdq?)V)-|Zjf+S!;C&T%QAg&f|CiQNyoe;23xXz zKX0i(g?IbUjGq*|s|~dk(C`-HXl;Y>&J$cmzTP6Mdiur(fcFOW_;mAq1ZZ8Qi_hnF zE7Cs2YlYqb?-K9r8g~KS0dcBDxCu?@kz&=W)?{?N!@c?Dlq`5ae2By)6k8-UX`^p% zJ=L7K*6zu8cwa|!Jj2K@;w3r5+Kc*ZQJMlv?Bew&!%P#Jm@Ni!pd4Dp~)&sRt;#hy)s@C=b!!<~c5gmLO`Ne;n3Y48ge}i-(xG^qv3t)@MiM$7F}vn zWV{1K4puY+ydP(Le$!b39!M{JWwc?&id4(dzZrhsQgQx{u1bKn!^KO40}T)~9$cw2 zp^c8W{|-lqQ&1A|7ZPVFEF|c+0v&JPR&y@>Ii3uMcMzf@5F@|S*FA1}*3ggl$NLv< z*`;CQ%_VVl-jANeOy3|yBwnFOhse(dg8RW0JHWkFsPO*0NANBMZ?>;-s%Ut}cNdDl z?p=P%MGgt5dcsoB((`tpC*|?LvSK9|#A>OKmN{TT#gPR*Vh-3g%nE)4+iz@wM74ho85&v)ZE>e%_+aGGvAG z8ZiHF*QtK-4jpe+Wj)r_&^_W0Brc+@=}7rcboX9i9@f}%mhon99Egt982R-je_P_w zML*ti*^*U*v}w3|tNuq+CC@^p@BeWdf6}I7A%`b?_txM3|KB=o#{2rAC-pj)@r^h3*#-hQ&U0!;GH>nVJ4~{Ja3W8 ztt-)DMKWKtG0qa;t)a7Y?puI&#gGSo_%2Q8a)$eg{up$;ZOhb1x18=0Ly>;~%=<%XuFy2{jJe~^yyag|H z)EkWwpn8XaZ$Z6Qq}^wa9oz@-9`WJnssVW4d|r{(YOD#dN`1*QxP*@P!nfMB{Oxy% z^N=|8w}(XK2GHGmEL+N~OyoSn;Vq8nz~%foKS6D`ZIzt#yZ0KO;A2`#un$OkhIKCf ze)bvj<6YTClMdIP9I^|3!gzHwyu~@wBw+W}_`Hm~d&?>4_gWm_ zy|`S~F83D!GVY%<&wkvB^vDF=^v18PctP{I?-@@t9ta< zR4zC3OGM89psxJiO%)9qJhQ^$m2UUw=!# zdq)_R=5IH`zTQH^2s-rX7W035D{yHeO**_@?zm&~_x^vhnwGKt9Q6O2s61%mp@JOj zL2&=Cy3?E;&4bkTo+O_^>V0*d+#oGiOIf4@_8@nBQ8?K=a{7bfi(78?X4%(USsYX>@_a)z8Iy?^b;gDSK4$G zJXz~7|5+S7|JR_xdrXt~hJv^Lz|d?oyloTnf5Ldn4}Fz_@jkQnUgQOUx3}q~Z%Kg! zs4GQh;aIU1DRq#&)(YS)xGVlpHNe|t6H(K&7lL#jr8m52M6V#nZiu{)u}dIsrNkxO z2pStluOP3@(TG+KWIVioB0AzR@_YBIcVG`Y{q8O7%Of))gx&wo&EOFuvS~6s-aiUy z(~)Q;=C}C*`FP6)D!jih9{onaoA|DZ1r6_$9))w^{+}ynND{`|NxAD#KEPW}??F*$ z8UZ@!kB{gmvLZFyTUcWO@O~Oilzs>B=CuqAYi)+0sFv)3tXy=wTX*EC?|GF#yotnZ zOTVk>ScQ)FkGG~{OGVun&b>Pj9kbv4IlrIh`nNsVNdNAwtj$A1+j{KdEja#*tQ;v2 z)8ma(rcFnD=$!R-G34T8Jr&*~pGqbuc(?cl&qBl7YTR`ZjQ2WU#YHgQiSm~u7J%)o zUpr00-n9~-bnS`H=bl@UBrdjVnFGA_-uH+%0=(bL2lPcLYC^*`iHEE7(TkHW&h_@Q zqV5pKkhoVY(pxu0qwn7S47(_H3u3(4+X$kAHT=){&FedAcA}JiyxG~#>=GNrKHf5_ zLTH%HR>AbMx0c9#H0h`qs}wc^cW?il|1(yr|KDZk58w*&Dm&+L*n@0ei>Scw|1~U`aoNTPuGl%XMEZ^>o}^uIe8L`h(0%A)b|LT} z`HXONHWy8ZtCj2G(;)Qz-{8UdTjmGiiSv-SA5R;Uy_TbYgG7uoF!8>1hT)c2V?;+8 zMt=9W_Tm;ip}&GOH}FiwzsIg1aTU&+PVxpYfB!#qk|rH#i$i_X)5uG#HWl8}_TH~3 zOYFv{LUYmZKD3IE4dZ>M!jU{6l{6CW$p(0@?=$&&O_BiZdp_@60}Gy%UAD{=#v9ty zf4&IdeO_lb*W+WFP_$q`fB7+Vyie&ptBQXTPmDq0Zi#oOTk@mhy|~hedp*A^!{P0U z=#ay|Ht-Mi0=Bcv7J?KWN`F0g_C*_a-8uIaWS#Vd%U z+5x;9Lo;_21H3yb?9P5W0`Ts9@2I#79q;$&Z0f(W-6qB$aW{ln?N`r2$9wDd1J8E{ zG9KP-hz=u+{JMr4Hcutc@7`A(Q`$DD(cs>}6Gx+b*q9z~+!NY#EcbFUb_O>{gW^P! z3h$r%N#zv0vwmf8qTwxRDOm&K{q5X5GTw>DmoDZ7{r^$U^!tZ45ujHqb|2qeW<}bo zxElxKt*0|BRRZu{XEP*R>!b`yYHBl7EJcx7y%jiswRQrY}x7j*Qc!WBAGF+QVna z?hR4lJ=wg!o`N^&wI2r>-ig~6k@4PP^6z*%Ab3~(1Me*e-p_R3-@dp=6S{G#Nqpig zdjCJWSvUBbC2(&fZq~%=jG}kw{r>~ghKJQ`jE6S|qT>lhe%YM*5iREQyZ7m9^Br=Z zVIObt{B=Q2WU~&_d3a| zL-U}1^O0nDiH%Y?MLz$p;R1ygfC_To}gEWok z(8tJcam|_Ay3X`_&`3Vv>P2DfB^GzKvtVncGt+wzF29>59V|!t+E(uLg)7J{RCv#J zp7y5TotMndi-z~gJevd&9wl8ElFp>LPI?HXZMeccah$>jz|hCR8yV z-VKP3HjMn@;{~EU{s$MNmGkIS32(s0drW!#u|U}&rpH?`dJ|1La-u^D-(DtHka|>j zvnby#q~P5x*s=f(Z^@e}F)-e9&Ki&#r2ER%m0p$Y5ZTCCeo^azy2ew%> z9Rqlu+~RNb4B&m^z2Sm#9Z*45%a$c7q2nF*^1g$M8_NY z@}F@sqteUt15zm&XPR`_ww-fJ z4JPBQ`(Jn~&QweIQtm#&Y-BP9;~idX(UH0dTuwYxsmjBSj`!}mEh*^&@kD(jE?HjwS7IbO z-WU7JJHuBp-t5f`(Qz3gKduLg$}Lm$<9$SSD%W{}hHr0&3Ys-J$C(~)TuKpbI*RYl zTlV++e@5%{|NDGEgJkeu9<+k%?(AHO2i>}~Lm1727DmMQz#jDT-g@^V+3D9~D)Erxj-}%BUs{p27`v=I2k=g>y^{|=v11$T{Y_j#6MFyQ>h5j4=y)sG z`h^WC#Soj3xYGT4Blvi9ywlpECnus94{s$zM;1nYmG6#n2>cJO*sg@D@5@Z)lN@hZM8YGIQ@+kv7-)a-RWs$MydRc>?f`)LOoMmbfO=_d0IR!CB~d z`!qFwQ!a@i_9Jm~`AU<9E~Dc;eRkE$`q?fF=idH^4z_cD&QFu~zT%BV^t<%qvO5#<>$p$tYe9;NZb*Ju{6#^biCgYcb(Qf#dvscLv*xa>1IC28u&9|{#E(hR!N<@9? zzNjX2(DK9k`c6~SySKzb7u0u8#u9CiIM33Wa`}Vkcy~=jo_*cPcz7>DbPQtT_j8-c zlIi>O<1M5b$Hqg;(USed5`KJB78^ppf@~nvd@L0h!>E!w6ite`cD19gQ^m?q~eb= zTm?zd(T$N`?yTS~*^TsngS02hLR*)H2@-DO{x$i%``MUeg+c}A;{o1=(T~Ge!RG*9e5*r;`YS*guE#Xnbek6|5Znsj689Lr9++#M9 zIgE$5Dx!lGBR|9ZCB>?u^e?g6Y%{Kr^4Ja1;jo2AZE@vHkGGu8a+-APP;hCE{XIc4 zrowx^m^?oP@6wJ6F*LmUAGz4Tc1T{?+-2LoEC^C?nmMpTs|DY?Lxz9V;>NbIZ4S=!K^rZ{aBkv&zpjOpx4s%e_Xx)uqh-&lexsbm-P6to(g@ zs}U96^Lj)KDR|qSxF(8*ci^urM`674Hdv7H_V;mCI0x`ftVmE?-gnZP$ainuh&@;Y&;P9mCxVl{;~|Hy-6w^9 zS&_2s6{I}@-q&Vtb590%-&flsL+FB_>r3C;@@JvDcd?$?@ldfF#A`_0fGyW@twrc~ zD`aLaKUd3mc$XqNR$}BQQ7>dI^gnR#z3*);LD z|7Vh=8hDU7l?N?6d;eb(q))y}WzjrHT-jR?_Mq&~bClsNc7AK`SuvnN;<8;XeL@Ia zv3sUH@;$g9-Li1DBwRthm)QCgt{~^0^Gfzk0u`k4!y`#m=pHmMobD&u6iM8V#Jyc} zMl^2&x(8WQX6|eBbYi#)lA^;3Bfp;bac*ZP`ul$__YfI}A?yYTC*F00o6Vm2E69DH zY0^=CsO9z1RPqvQMuoSa{&YNLi5-&rA%lkZi&*8QFy1QRt}9@?9Sf?tG6CKK%K zd&w* zmL))@+#5J&U9lpSXuRU_2YBB)Q!N1R-ab_iZ2Eo|f;czYr_Rej$GgW=)G#OW8j&4| zOaAPziBA|E?{~IJZFzXc!<(X`0VBWhIfJK3!}Q~Q{XuEg^m7_2$OtDkj>Jl)#~bJG zNSltyW%aLr_y4=8@a7k*wWHv@rLSBH4exIiE&4Ft(`nbq!wF{#T-z*gL7F+o)cZFu%a#zxXHg9n;{G5nB|JQYXndYi^ov4k( z#jNb}E?ABJapL875i|3$7!PlXjw=}XMGNoqO6sB??^m2`eNHXdx3}PAU*WQ1TA05< z`qWO7j&u1rc2^Gt!TtX(D!h3gZB?b<9XrQr5gOj2igS0ucw3)7NXGkul5G|2-s^1V z?|8e60IgWtGk<}L6-jl?ueY#!6DQkO-Gtp+X5fY!nitb0 zr-27m$}U+8SCFv-Vh>G#2d(svVTT66`Tvk=^X@`$LHehxlW_mvBJOGj_y3=gh;9*q z5TrQZA06=ty@HfAciCdt6;51%#BGhVk&oDe?m;IHxO5voI?8Yj(o#f+D@J}l1HO%^ z%+SBY&iyjQ_9Gj6iyfDD_GCS2lKGd|^RBe%Sg0pbY(suxXD=1rV%yvnQ1IT<*Sj1I z?~mX7dtkg169{TB-t5s14VD0JJIey%uQ5C{=S|>i=_V^uf6gAoivaHx@^iZG0KDhA z+&Gik2tkc=cw_=}(3e>V!MK9)@E$>QWMbrJ zzxnP)(XI4XkUa)|M%BL94bpgB_@M*FBTSEXUMg)m%v~Kn+Jg!b6eku`cni0(JfYw{ zIu@`L4e##7W#cg3s?|ZOVZ7_|-|syG@ZP)6c3vDe0lE=>YDt9pA+}dyNtQ;ZsMji<8`uAG77GYnZ+`iK+NWla8r(_iGRrR;1bLUo_$4 zExC`vdf?+N&F2jG7g|8jcE^PdCmhjhZ|Rv2d5$L{iTX&~4ZXN|lG*5Zx6g!%)eSHn z-V_~O82KH{AM+4+Npb1j|YOFycETPKmR_FyuSB z2W^tK*x}A=&u~ku8=^xSBfo|?-Qa_*^m`Cww1&gQkA?|SNLsr?HXGAdkhn}5bv)#= zQ2jkYvZlgYdcBDxWr?le>rq0(d(Dz>EpP?N;ZsOnVmVYZ#=8LCI#sVCaF6hiYQXtr z^5Isbw8-t;0RV5Cx951^Ep|64`*GWF2zr-xz&}qCy+O)0Z_@ec4Dd$c963fdb|s-V zNDn6XDnhR_9^N^Kjz<{zJ(1?R@GG2typ5MB_o?O6aJ>bqQrmIyQ0B*5f;Jsf8uR_c zACoIc0u|m;xIrfh-h@{VR-oan$?ww$UQE<4< zH7k;DzW7i0>#dKmD~#az|FP_&nnwWM^SQ3R`N@Zl_pvLhKaac)BU0j&RX_EuypE1{ z->(gUa~3%;oO?SVI)*Uv+b>si?6?{I{r~cP!Ai%wu<>5*6Ce^-JI(ZXPXyAYW1DwI-2!+=x-1HHih-cg>|oBFf52O8CTO9RVmOf!m!ICYsp%Rz z-qRvi>K-LB9^Mj&j@hDr&TrkZkU)mFu$yz7T} zY0`0Z<4RrCxC?*h|NnQl&3JzT`v1dJ9<%l`lmVr;;Cw5Zpr_Tff50V@-(1-*cw3n5|y6*iZD8X>`_#G$o z{$I*u;*7<-5aJyqZvCq8GTBGy{r_^a+W}UxwhUK6QgkR{zW>ACn}^l3hyDLsb9*&wq>(g|1{F;!B1sdaQoG$C2}w$tG-yyFjVd82C5cEf zWpAPkkxFPFrBDf>LPfu|wzZyXU+4F%v-W=e+WUK*^Upc&uDk2H-_FbZ`P`prIhe^p zc%S1vS1I@mYLIlU9k9LOL2Z9GUUnG5d$aiG<+%{vpRZPXh2J*=N1n?F`>nyo`=rBM zS4EEu3L1ClgPq!iC~UmNGOrNZ@>vh>BE*LzPJVswcYd6EmwCL^wT)tr1NcKM;nD`z zfQbJGK5yB@pbxIZ*E)Zfw|wdFUhsAE1{CkrZH0PRc!^Znu_qtgA z>I@1RckA4ya)Y3D<@u z<$NUA|NDQPjQL3MJN4bYoVL8Ri4Je&XXZyxyf5Dg(Z#}Bz-0UlJUQ98wwQ+ZMhQ3l zb_j37byKUC7m>ki(Y8)fp$FB@Q0(g=2yfkjZ`<-AyhVRJZSw{}(B!z)ud5x{cx&v= z1}2G_6g19JG@Y7if!!bhxjCV`vsn-Cg@_MfocsbcElM{ViQ;c`{$qLzef?Q^BS#bN z?=4df5}pW8WP7|vS2E_~jlI^$$!OZ~79Tpi=NC8p&)j?K!gV@Wc-!6)c?;wHX~Pih za^iL4@Qf-5Z{L)nB9}BW=+HDYxbmW9zT^sOvcy>}x%igEJenXm9{$7$xPcSFgd zSpy&NCnvRivHnUv(`?`WJ4?qgxsF;?&CZOrQpdH!WSN9oqljbjil?9JE0idIzx2f@;v) z4=*^gpc-_4yrxlD9t0OH{~`P57j_LASnRwyp)!rK7>P^pkg!FWGPDxF;<1cE0XJ<9Ov#K!yO$X0>?v=Dz1iOb#KAT6>S8}HbZ zBlEvDvmV~h5g+k5`R$wXD3QIy{197dS=HP28Gne4OTB2G5X=7ke_Z}0hJ0Lje|)LK zNm_%nl@4#s&)-K-yoZ0~EyKe5MxoqO7;pEL3N*au+V^N$KzN^DeaYoxI~k+~eRn-` z)q@%<-S;yC!W%qO5S0z%EitY+z8`9k9xo`G*p0pa&uQ&bqSbMjVv59_UE#L3QULpc zbj0!V8yrpjSgv}{LVWDS$#4GH^-kgc!~Or_2Ntc3;rP{?kY-jNAISda{|WVs`ItV& ztpd*73!ne@r^8$0PDnf&^X?AQg^LZ zW8?k8)h*rU66@g|h5EqB&oQK~d~Xx;lapr&j{_6+@caLZizQF1-I-zg25Itu6hl7h zZ`YHS1mwebZ=u6meSb(eTD|Z8(J{oryIS3_%%YMpzU_H84B3f1<~r9?6{HM*(R6I&n+TmbaRXTu<(U@b)u&H#>R<86=qA{U!9)gX;4DTnO*~Z)S#a0Ej>5+=-z$$yu(0_pJ9 z>G`w{#e3P@QBEwpJDi4^;Qs&jimx=hCFD=1G(&hBD2Sxb1d%~;0m`=J)gIKd5lfrl z2FW43|2f?Mo4Q-aN3I0H5Q7hqg$~$wpRE9@oOlmW!jL$r&nZ8(2C(stHoCsAR^ON9 zs&^UUBNivW(E{V=8@idV-cq@*;$x39FoTpHh}FF|&h~f{%oy|W;(Q{}`|tA>JLvG% zK6lv>#e2h*TO3$;_sPxNqb+YO@7ID?Z@Z5B4jDrIf6qnZChbr%xK^(&Tp_}PdSl+< zgV_+?PDX8~G9bKf+;}k<;sSzxpD!%y_Qb~fgyOG7EAtOgwjyy$#N;er|H8(bv?j7c ztC02ZK8E-p`0w%8@|W`$@E_uj;Sb{X;dkP< zXc)s0yetfQc)_f*>T6~IpVtib@6TE}G zUA&KZDZCeXi+OW+_w$DHZsR5K+VPt6>hdb{O7imYO!AEI^zgLs)brHvl=0;Ar1I?L z3FPtOSPAVxGT7ib06l8;|}Kb<#y(_;x^)5$Suz; z!p*@o#`T`7gXA<;ya|x#kr!*&#W18bLM=wVk$32c(j&hCyjzb(V96=mD98MgT z97{PgIAl45gue+72)_`1Abdl(Qn*k!LpWY|x3HhEtFX1OiLjQiqOh1Sm(YaJpir04 zVPlNJ4f(=0dtc%0iMte1emLBZ57GErRueHG*Y=`GTo}dj$gp zy#&__t`sy7R1=&dC?N1hU{v6(K)XPrz%_vif#U*)1>yvP1$+gZ1*`;&1QrU&H#L83 zMW^(FoID&-4|gnTmfofU>_XM!F4^Zm5USvKU?-{`?KXM=1fuGp-Oeyz2dW+{Iw%bU zpsH~=cN*A^s)mcEQNT7--HYS<4s1o$-3>P~0Dn}~t82^$wxH_v=p|dg4^`ABBIkh3 zsG=M?-wXJn>Xz4T5nvOl>NE$J0Y0d@F}d>~;Ek&5ZM8vw7pku1wDSX=sJgo4=^22G zs#+ah55NOeHGl3J10+;k{&2Dsa7R`3asT>%kFWJv=XQFU>h_+`KqRaL_K#Q_&o zo$q_v1306q^4!8UU<0boMcsTCs*}eaI|A0IDs=0P2G*eJ zg#HmvzzS8z1>Y+Jt5H?(K&BP2MAgxghPA*dRON3zr3I`+Ri4SI{eT6ka)~_?zzS65 zJUy=oEJsy#34cCdj;gHC$u0myRi+iF2biHMLpVYQFh$kju7DkY398a=?w?hs)M$~a$p&%Qsq?)fTgHP8ED!E7@{h<#y$lwK-K=NCpmyVs*+q&I)EjpN|g6j z2lP-C|9R;LKo?c}8Y52tI;e_E6O{+FQ5EY+lm-@~D#m!k2hc**-k&o&fkmi_>Wo(d z7NRQh#J*dACaNN~G_(U6s0v@}b_P&KRT$@j*MJ(TLfht80;;ImUG~rfP(fA5?v-l5 z0#pTC8O{L8sM;kYVh7Ae)z04SIlw$r1=cK=1e8#&oD55H06X6=5fU51%pUwgD zsMM4g5a>;;16?0QZ5}s3NtPE(gR=<$fY|KOl-Kx9Dw00TEPf zTHv-^5l~sD6 zCol_Dt2cb20t8f9Dw_8aXHd0jmXA8|52`F$X2}wNqiRLg_cO$4R4w-zP9sjC%3QC= znK+3mkXN;p_zP904~qneKT%~;*jPaPfhyxIGqZ^ks4~(oH6o6qY8jC9hB$^Q!}ixz z#P6swxS7aJ{Dvz12=x@=S5(34?Zi=3!ON4xFQ|f7bBLc&1vkIMPpE=>1>y**;8T0V zkEntVIT43Z1)m8a4xtL(LMINQ3f^%fen1s`_mB7_HWL`}qY8fI zlGueR_)$P&C#v8#)QBCZg1=@&e2FUf<1fS)sDi(hL41xX_|pQ!c2vPHu@j%63jQWC zu?vViT%( zCYFm4AE65VDm?Kas<O=~vegr*qB;G>R zggNCYu@0L1$)fYWfBqYZ)S7qMOC7j|Dy6-X1mG&F6m2z=fm&24EWWi3xPmIV!Ck&U z4XR|X&)E!IM%CO@*&jePs^&Oy9|SI;O2));H*gVEQr~q`fhtr<-U$ML3#gJf(i{Vv zN0s>IH)TL2s%Ebe)dtR?O7u5W=POVp(ljp*IEyObVmE7`992SoTY7;rs1h{0=L3|X zN`Q-050s*c*tx9|IE^a)%F$w=1XX+?wZT9!s(9T#O#r7*#UsLN1Qel)t54}Ra1vFV z*A}b=3Q@(8SojAxfvQ=qVky9JR1p-W9s$P?wdl{scqyO&RljQwy#tP-YWhHRAdru$ zDYsRfKpv_lAN1XVv;I4yx3R83?B>H*oP8sB_1@1DUA$ zHlv&dWT5Kn`<|CTI;uts{ulsa(G!FK`G|pSa4ifP<*|*frn+q@rrL zGS&<@fU2Q_%&kBQss_!SPXfuP`k**h57>{YcVF~vfh1H7T;@CnB%-Q6)#@OSfU37^ z{7Qg$RQ1g@9Rc>C>diNg79b8)JvSrmfLK($&PvY#Vo>$UyRHC;MpgF$&RSqEsye6M zH~>+o>Znh+3`C;pW!`FWAOck{HW}Xo!cp~He~u0ihN^a8$tPeBs@h(Neg#5N)mrjp z0@#hJmJt2pKnSXyF70^%1Pelc<+*2-5(JfqD|k0?B|`uC-#@JOCjjmLhtjPocSv>8K1au!E$({#QmF7u(}aFlErk;h^uWe@|}( z)8P#-q@Z|vq*M5?@D5n9XaKI>wxauKcs~VPyH`MXmqnOY{Pre;Jy)96CCHJf)8(G? zVZ7JGyRL%qw$f`hU+iNB#=q9AK4FWEw*{Ai##8SDltd(Mv0U4n;7Dw|b+}~juCw)F zxyi|L#D^YEevY%L>t(B$$9vTtYO6mO;zf?*V61Qu}urcFb?%syzyt=K) z&w7UwPa;0{;N&Nj5Es>~$^7J`VAh%APp&fX_IB=^S9xLVf4qf|Eyb7*LtZca|K9&+ zwNC$k&j;%NBk5`oyf=c@phsRS#jt9S&?D1}a1FZL*GqdKoe*_5Q55>bZiV?sn(A>f zDEaVcJ80%X@oe4UIa7T&kI#p+yV|B0PLJpC#& zI_y7#v>NVX$cIRN&FziZG`z#<@P>D^6?f~g4icW3mM@(780CR-C$ybt>X>EgNd{CY-SELXizA6hv1DQxLE%Kejhyz~7(CCm58QS}W-~U_HSyupGPF$tEUq;Fc1iLSG=K1ww<831= zv1Q=veo7A#Cve*Ji2Vla%ZYDDr-~0BWIeq9#|KV+y${A*2FxXyo}73L7rxamc#8Xb zAB)$j?3wz;_IT%|Fy`Z~&;1S58-?)w|2=eg!{>`oypJ_S2x8&w>smOLenRPQ|Y`JSi`maQGPG> za{EC&>)mwoe?vyahdU%r%A9(q3$aDGexG~@Vx5(H_TgKzR z-s&eyaa#Q@jP2*%)gg5Z`S4mp9C`$8PW-q3|G&4~EcH{U2F23VAozqOT7!uriAT4Y37Bt`dgtkwKS}WX?eg=mzP=>(AjkNK;+sgWx+z z7sj}ENh^ckrMd6ZqC2sN*oy;u4ucC5DYZ!4_Cz1oG8^n6wnF)a4?)_4#(WH@I8;Q@Hb`UW@P>~Jqj>*p zvZ)7EJ@|vp5eV-mza>fz zLwJ{aRwjQcFaxX4mYn$^f{k}hdD?H$BZ-u&NF3;-yX!#$_7Hpj@#?PmRjh}1HsYfm zCqKQ!%r4n7<{P9@s^>)V75wEb4X4o`F9Yn@9&c;eFAVvxJ2IGB5J&6(qv`O5&%mR2 zhtBSlz`|SD&an!{JJcdf53b&4ES%?cKzK*q`4}R1nGAL~#wKkx@SwhoaV^b*@Xq1M zyKxZ0`(@W`Y4=hy@N)6T7NP_;-iFzc1wMZgDc6y>ZsSY0M-O1*EjTxPV#<=ta@8C4 z!H<)l(PN9I9iN!T`+BmzwefNW`u{%;4~}`UKi-6T27TBJnHv24yv1HRyx~h7DBg7^ z3dOPTZri%C6vq2D*t!J9d$P?@Ybmrjp?v;ZIp0NPT*Jn@H`(Ru;HD%>1`;QJ#*H zc6l5;8w>BwK?h9r=cNskI9DeBTr4iWtXldT{Oe4 zL1EFv^QW)wqnIFZkz+R&ydz<6kgD{loIR4Zk>zHPp@E#9hqo!>gAXUatFw8Y8=qhv z@7^md%QX4%hgib;j*DFrscb*Q5?tFE^3ir#E%!+^-2dlt(BTc=q(||V=e|D|3-1Pp zedl1jdm|$aV7yOPlU6oDc!!Ew$hSNtgEz)xRs?EzQ15IKu!VP!!p(^y@D7sH?EHud zc{9)oxUzznkB#@9=(9W4gv3*9k+^T)W3OK9#KzlSVErYv)Rt+h~S-gr;Q4I~}3nJ&O)+_-P0fZ>3#DbFlE1 z3|GAcb>=wf#ofujKB+J?2k9${b9y@#149@|DBu==B6H;WN@B__HENO9@OT@sC4-C)_H>U%JAnc>?hVr zwi|-rh{PuY^%?Btt@@qb-p}tPP`)8?Wp}iQNq*SNTN*C@zuv}^SPpO0hbm5fQ5Q{= z9Lkx;Tm0v>6-DpxFDDYT4x3a-_p*KUCS<2EjBm zYfoqmitbWU#;QR|-UnjfA=cFD6|MibtDPMRKs6{TgVcFb)e}s0kDYP@J*eQ%4~6g- zq<5YdNQJ*39kzVFMo)+tXmdSaeW^8e4VvRJ?|P|A9K`{N+v4FKak&|L4N`iYrZ0Dv z3(M6Y3B-pOPJR-D5j7&V%-5jnTkYONti^ATDx1plUut->eGS^~UdE6Q5C~kHd5kuL zyjF>F|c%<3sUw@1ZDR;jI`*jDzux@bWQ(@!lo9Sm_>wxBoR={okWxkpH#G`6+05 zYkh2fMF6x&CULE<8&3Ar6b*my7e z;5)1PBBC|%R59n->^O2e<~RB@namk zw=xSpy_L&Dhd2DdB#QT-QnDfz-hRnTXn0$6n1e9h$8t8t9fI(tW_oI+KOuu;^J2dn zJRa1r3JHxk2=C&albvTEycfGIbao0e1AWZe+c)W8$xAab2 zdSL3gkJ63AnRTmvew~TEymfoBuWPOl>*1}9__&Fa-}9C6zP2Rh@vb^KHR7@b|8Qc^ zzBwY)Jzv-!@5Ab|8S+8eT{GFg_rLz1CHwtrOq=&YHBy{_6YJs+%xzQ7`Z%LVCaOJP#(*D~#sN>H3XL6t+_PM3snsjK0O;WGj z$Ds~Av6DGGPe>elh%HkwH};T?rtC-JMh0!Os^hSS*qx%wzdHVLVz~yX2=TEMC%=ZJ z@`~y?%-5jsvQI%>!uUgMApgw9`qTDoKZ87EJIRobMUHD%Y13Yi$`z!;8-4^G#XDtu zPz?)jCyBjLFy2iB+okXfG6&38nt|}1R(=q5sS&zj=U^PFnsNz=>-Bi#JkJjs??m^rwGsO^upHi@h>sYY z{F-n1cpmx4Jl>75{kL9SV_*j<$4Sai&6(}-CKRn_%tt_)iN@a@Bmp|S;aB}pyj#9i zt774OHbZnTjQ5$TF52;y#-49u@lbDD6nx36&hJI?fLnfSq|?!#77%W zejnFg&c9I4Jl>nWwqCezz`zbtv)QT+qi*)cTLfgthwhB+r1U9Tg9Omw4S%Kr#XCLX zfC?7gk<><7_14^*X$)8Ik;lqr@b~}LuPyl|;@}CoRixLPb@iZHDP~u}c&~aK(3A$@ z{iXhwA$&o)p`dhm=Xq?r6;Es|9A6nrd4$B}Zwl!JTLpYerFjDjadf32OAHn;KsbVObG9evl}zA zAiT$Sc18fn(A;}#P>}jgY`mqYnsa)7#8UPnaf{Eciwh!P+QV>AwFbq z@_Q@dyM5*>^VK_`(|mZz75u%oxX5Zfz;=S|@s5kVz>trgo$X4u3;*l?|JiD@q=x$c z*>p7s{_+%BgA8-TwXteYC1(O{h!v5tq#dzaO{5$)ff}Tn#Neq8elqxHaR0&r=mn`a z+7c(>`~TlFj|{{2|8=~tMUHxzfyC5jxm}sqHE5yYz^daF5fniruE{{nX}ctL4dT~( zDYP$sJe@YF-Tky~eEiAmBZ21!b53w>H?`e1|yKtszLwEx+JmUN?p0r5eu&-l?YNhF9RBkb#i2UQZp&KP9`7|zv>EcD_Nr#) z-G15(Qj`vF_}hRe-YfOaEyBXv>z7nGjCcLFJlg$#i(KUfMF?-Dbn{&s)yUw)?^&Jm z13jn@6uDDjyi3)7-i4pHwEJp*Rql-`IG@;ksNxa!4wB1kSIR2>D2gf)S2%d(YnBZ5 z@)ob}vz_EvN0zJJj);$0IQeO}Jq+3mFpu{}iCy=#{P1^>Zq$0X%YVDg_IPtnkQnkY z_OUknNeQibi_qZ>f9w*)dt`pxLM*)fO8P=!ybEu+&@M<9XWY{SAiUM5UzG@(K+jvW z94Yn)_MqB~%JRaiw-v4j7QlG(9^Ng#Z^9IeBfR{%s}CFRjm1BOmG4AR5|Ow#-WKb3)j!@u1~=T3 z)2@K3x7W7=8(_SB54qof_ufJ^UM;aSHUk}&dEc62h&?&s|L$-pfBRmF6B5_klT`ow zA~xO|3bysXj$u8#xeyUSQi8G2Ap%rZBE@m@41wFt)B<4l8S|6Wt@R3iT#?j-CP zWQNkSt5=KmP);LpqF%!8@2_CvecE7j&*60rEQfa{;-d&Bzx&&+9bSCo|FFE}5o=?) z1b+v~MpUo#gYrYR$NSLM#SHm4Bdc8gJc-u-OVZ)(eKbi5#ryuH5@+8p7K<_}-HtVKS(<#_02U==IiXMQ66ac!wSOycNbf$h!Ix&vsMLzU|ej zZXayCU)qJg0*%8c>ybGAZj;;}`?2wUfAfIUpWCd5H|papPJT+KvKljbnXlf1`HLMg zrtnX15v(PmtHqzPJ>G;y#(X4SYB;^4m{z?d=8bF04l-z!zDVW_^z|0)S^IKfyx)W->%e&5k<9)sxziLBw?8E% z{vT1iS8=S?!NPk)p_+Dj z%l>x_?d|Qa-3PcWA-tQYzH6I*dw>9M{XuT%aN_X%tJ?71TS3-%2)zG)>bbqohe=Z~ zaz~pY8H(NiCv|=bECyI_b7BMHBMv9OrnTW(Ykx40 zcjVMNqu(DHIGk9+`@U&jJ^T0n6{3v!xGR5N3tHa#@BP1jHrp(yq5fZvt_E!#+7SuY zAj5ujKM_uE0#*&W_TFj*yu>aLAVfR=Uo$Cu%nmw1`di%SRJ0)(ET8%|wfQ}Xsv%K6 zc>=0I`3J{>5}_ItYh4nitpwGeuVcsEmS7LDt0e~}haeNPN(R01?#Z?4Dw(iV?GWa*tF>H z61yxN-u^eQ#-T&({LuSGSa=7$5ORX?=99fd+yB2Rw5CBH!n>w0V_wt}GH717&LZ*$ ziTZi$LDNwPZ>tgO9S0!1Gxx;pb-!y0nkf~(o&>O$*q;#JF$mY zx$*PQd6R5e4)1ovha^sZ&31F#VqyRSN;ENLPB43c1O9kE@B!v1(`tYyfDS@G9O zp>o;`axNX-TaqIF=YVuyUdA#kyp?}8Y=QBXbNfx}|3kMZYD++Pzo?mx7}X|&9^3nF z|QuwDl1XR?)gHVGsFDkm{ z%0e=j@Jwb;;d~Ej6!54YejtrX-O2|)kQUPk$_lref*0m4EIINoUvCkfmcM#uTPUR( ziM#bHFFkb+cJ&VXTGSvizSoxiX6Ef<Ukfdb@@U>W8h&oIXyXYN_cTD}#nu z)q$NlkD&h`N8u*7;n*0Utbt+iYMQ zF46jbMLN89B)$Vsyge?Babn?p@(q_fjCb7GG8*3H+c$?Cfbc%YZ`f4ew3Y<5FWGy!qZ8zH-u>48B@t^ToH0 zMEz-ZSQy5;(BfwcjJKeyqH(}+6Yw%&K&Lhj8*lRZ^R{F{2&Ec{%MvX)v1uzd-opwV zb5{7TWx2_T7vkd`PJYi_ohPmfG2bBN-c79ka}U4&Cm1I193M4d`{gad55|1(1f{<) zf-Xoyb8mS%ythk#I)~z2P@Fak3vcI%aUB@%8g)(D>n-L+>FPcZ-mBGgP}mQl+awp>1<4(HcZpYbAhHgVrn-pO}VfP>za(IlRPf zyQpB&6RJT2q2e`hj%2W1GpH%npF|Z^KVu7jVs}Dm*H8EpyQka=*NhjKfc3LAj8?qH z9%B0s%{McM45FZM85Wy~OB=C=*o)b!Mt=8Jv)m9nfcU`6Z{A6>3wK+YpF!?(on=Q> z#6KXt&_+1r)hrISuR$lr_!;tHIsM3c-rob#Ds*`7E_-N#;(atp2Ef95sq?4bFy3N= zF|;Rk4Y+LcwnBIp#`<(itS5s33k1Vdcaf+M(tJVqc*~plszFH*-qlujzQ{(HfR3Hx z4l$+Jc&mtPo3o-Jh=Rub88OV<5P^;N{8gtWPH9`Q9Nwyk58V7XE+6|zWFBvocE5MW zdl_humYdIV8VA@OZ^Er*4EfmgWAa098Epo+fDZ4F-7D2lybZ3r=f}cZT5S#wJcHC3 z=%T&2jM;BF&tvC-2`kp zr)v>#02}Y?RXgwf5!*#U<6c>(z35txjdz;Etr|)Z>*0L^@qw3L*_@#?XGiAorYv;j zJ@f~^LFx|>Pgbc2W_!GyR7Du_G5T_#WeB=K3QbOw>F^G=GMqv2UYA_UhlTfcpHd+h z?_HoO4R5Kl{ZEr1yyGVA`J?T~VBF`=KP8e$RGX!bB1#~I=77YGo3*l`a zP_g<*95&vk^N7SFzPl)PNL;1GkpW;eHr}mPS2F!2*RWjmE<=3a<>%3KsB)-~dAx5M zwc15g;5SHw0R9Z?AG_EdZ^CIl#(exz*3tdDIWeCO?_EM7b|~J5BolbC@cxu}ObW)E zui2Zn_f~yHmkNJ-+vex-Pii(~aFxHdO8}G8XtF;B$tcSN1;sY!OgREL$ zFNRfv)NX%y4mU`8sw1=piJ0O(cLh{~o}OxMD9a&(^KNKDYsM|6j;TS8CvLAcYHw>s8oblTeGj2I=zb-Hr-nOO_jA zMG+r(`6U`}Jg{zz`5F{GTla|lApZS-tAwN_%ImDzeu!0e+s}{>8{hek9Lcm3q?&Yi zN1oVs3mszHWoL_G;cXkB+XLerxM@CZc`G(IWAADR?{S?qjcxH{@EK(%`E&w_TKBnG z2gcj(-Gw7C-sGqx{i1g!V3^a}dX;~sCpQDYwOv2FKcj5F~2|G2&xZ>bda|GY(@)G;&@q&o%pM_grzaHX4BW%zIqcz81qrwZ2oHG*gm-bSEs`} ze68CV6z?NDsX|zID>o*7hVfQ)IZ4C2)~nRO6~en)_wRx6 zzAL8a1>>E1*ExMU%oNPg^x{pBcE+5Xv?yO~xor|e$wuNpPVH51BC+unoYHxCcRTBC zPP8FD@bb$G2~AL6$@~WC_UdmE9FF+cTRc3^D$38=#r6%-Q{~eP`B>+b{h&}Y7sgwS z4(~9|1+P)O^Z6nKvG7)1zn_M8v>0=ECv&C^f2W#&AP zB2ze}B!fLU*)K#0TR~zyyp0hbc=oxw|oAA+X{9{2P+v80* z;>3^-E286h`?CM~f2@|9rG5_8ARW3Iw68Jp1X_bCmzzmr)u4tge4X$RTlHbci1t95 z^~zRvJw5ZPFEye=lAhpwr+0Usj=EF1&PBAtFGxQiFUW(R*xk3gta|2?33w7*7_;;Y zb`5HN^u;)YdpqSc634S-Y?pZ#b`7%HUwKq0+Jfc!|7VDgH8}a{DTdiyOlN+GwZ4*5 zB|*ktgCyvbmfaFu$Nn?OK?Z&7d-{3t-z9c!I=ti3MCDPuHKRGCu<%~0I^7QAU79;Y z`+}6(ZR0BV;TjTQc8t-OP(8rW8 zQEh=egRE4!d%OMoc8VVo=k%lWVfJP08Kn1)lE+aKtcUj{#K$I_{1z;^8zp4LJl_55 zhoV0|$AABy&|AMg>p(C2EZr@Q(E)N~3tsThuCng?EessRhP+ zw;CsH2Wj$pe_amr1*z{-LYp^_kiq3A?)bbmf$)B^%m%*yKd<{l6MX-F`KlA!2+pRU z{MzP9D-~?K*RQxS&)YSCqJ+fV-ywc$(LrpySII^th3{I)a@E@f@nMOR-%+r2(pZrB z`~S{AO*5+fALHKo5;(B_q{GYxwm%?!qmD5jfc`=0lZmv|TP-@gV~j_9P`o2O&xm8; zU6ZZW1moS4X+Ycm|Mn#87zc#6*P|t6;jLuQ%X~VIcL#}@ec*v`E`+zQ)PipK`+x5a zh)CaFV+vB&w;sMIfQ@%z?W;9ArUNKQQN`Vv#68GX-a7&UR_UkSC#4<)TZmwdv>fMU?z{~H! zJ-MXULlU@E_@8~74(C|9Iaf38@10q}7he#+f$b+J$#?k~@*#iR<&zw>@W1!}{s{~# zYN-D=psPX2HTEfJ4XP8-l*g(;CcNs?a1FZI*+_eX^fdnmNjqqWt>g=v5EJnP1$=4+ zd4fq)|1b{2V^9s6a1G2$hH8+&bxrAz8zx|#hAn|F6}$g$J@%_;!MQDz+eq9j`@U!W zRoMOiOEIkn5@O3)t_HOuKDu%86E(lu>eJ2q8sx%`qnuJH3~Z2kbli+lVE-CKFzsQ; zN6MdFx+SHw21%a|@BLX%{^xlM0&!QR84atMiA ze3&3J6NQbp<*T&ftSr{UdpY968Ye$Jm&&yfQq0dFQ_pmVHih9YZ?$PP6d5$K{|C|( zpFUv7$9c2ejb7O_yqD17o#dL*fmUzOC+e)P>S6w(tgNcg2E@@C@?oH^qzP&;@CqC<&!udu+THcM4^Bi)^KA zLE;P(3GZkB%MH@%xP^VSvsbWO^vC(3)Pqj*1<&YgpWx3Gym?RZPV*3*XY=7f&Qv&sd~ z>h01Z-MFoap5Q)@v4k!z67`a3G6*kk1yfwQ;N`7?NYV9<+@>H;!WxgP4s5*nRvgIT zzrU3NAaTMnJB3H&u>1d2_3l1Fd8~)GAmYOcCqL=3^4!;=%;RmBx>1QklY!S;;;tOD zS!Bch{r?%pd<@#w9QXuXkcRNqrNcY^^U@C}-Y;)%mchc?zV+%WcyjXc$RzFlzaaVO zxnc5UGCKThnYX){Yf%oM!#am(DcfBC%S zX_-sHWdCgx3KEyN($PX*6C3ZmZ7*uXsAV~-NVZ-?T~ zy`8G$P7aS*uzmHGKE;?1i%+uV`Tu?Yj}^Q9|9?(U4Kk*yL20*l6rwfgx0sePRt@sH zX?OvyL7w5Uv?X?44d?PN&>H04;&zFe7i6$xrQ^bjRU~R6Ir9;GgLJYs_hTGXgWL!N zGm}UY@XK^)eYhL;5G$4VIN`C+X37{6w@}humLmYWLF#h|$R&50vD^$&2Jtb7li&P3 zQD?qzFkgeDivmOPJ}_{_Zb`u!x0Mgs{|r+0DaL$Uu|ID5cLr%hhxehVJ=`eXw-{0Zv&f6wEh3V?_c+iPrw(X zS45ShrN1@-ua@nz``V3-x0&i{*`Jx4DYuX~8;>WC2NbY}Sgo4|`aW_X%i(Q~_|V76 zPkxSAL}P;}?o#r+a#@yE;(1`bHqHVUR~bYuG=mSFafAs?e0=N61!r_CUj(cyj2 zmROGBy=df?5*FU?f^=!eTW&u6L2Hm=yn=qsg8F~mxS3j>Ph?P>=kO2tQzUBcjOHvD z@A9M+AOXU=sy(hF`k4th7M=a#S_3xT4V4vd2A^-HOd@es`)x}jXJO;5Cph}eJ(l(G zet`He!pZL3{brJT{0E1@LrbibqKEBziO8)f%|_yA?kKv2=Bp=d7bK0WH54Uk;1z?5>;y3 zTH!(n@3;F~G~kaDb=g1MarvnUc(jA?WZ^Yzyo>op97k9AQBERpass#NB)?!!P99uY z^fXMwoaL%_DdM9EC%*?zl2z?Hn6KV%vJ+E`YZy2ntx&P%#;SI<$D81HmLVS_vWL3H za%t7ukPh#Zfu?;Z-mfCu6|nFQ7HXLV-~VsgEvF6RP2tmisRZHOE?GP-B;W~t>uQbY zIYgpP2Xc$Uj}w_04LZS(6FHX42Z{8XfC@J_!m1x(<6SCeXV(44k1`*LGZayX*(Ln>XbpG{+j)#unX$k7el zA0FgO*@DE8<()Pph-25Fbi)Ir4^gHpH^ibovT*Vv{ZQba{h9e8*66~E)<3xn^#9Z6 z3^!I+v48)6@hoFL3LPC({`UVM9o|`?leAClz@N9MT0EqNg?G&v@-Y~1xz;(f<*f}~ zg1&|j-c9^%7d(5(;7#i|+wV|=w8%GHg`Hjw0 ztiSO!eJ93s+I=Zskhr~fUOhPZ7#r`>Q&XN4fc2KQP#@(u`B~qw7FNE*Jl>C+f0T?d zFvJpysm`ZoOxS*iCGb3E$cIKM^%MUo+6>Z+4)07WP!Fx%qdv8&Sa@%I`|vo7_d4}T z+6mJAex@Fh5Z-@I{2uRnNe0z}J!E<-NYsE~xsSyV-XA|%d&fX{|JoIPJr4SMtFyf8 z=j-dS@irBf$UUmDnc{}THQimn<8v1q?;%SiACDB)!`lq;F@lrdt?Zoh@^Q@1AXfkj zU4(V;m$ycMc!!gRtJogzw=J0r`Di+OG1wxG*8iK*;hiBIp@ZW6M=M4J3-83Az9(S3 zTbFKH4mU`v+qZf3OCJt2b&EtZcQxI&_)NlX;O52TM?APmC~q}yD%m$^v; z+W(J^xZmrHjd#xNvNrA=n<+#jZpF9uD=81L@xGRs`C4_5_3+L`eB8pxZ=|Hxw(&Oe z)qADwg|KJ8@i#~bp#1e3rPb^|Ia$h>k6w%RHJ2)B)!T#)@55aIJ5aoD`>tDnh4)^r zZ8W?mU459sd)s+iIpPr$@MX|U{MO;cnL1P&Atlk<*gXW(%zYL z*2CKy@sWs=U&Jh<_V>4#$6LxVXlz^!AMc5?vhyr!Zn8bzWv3YPQ6HNt!jt*m{eP^< zKTG`_>i<{K)u5v%4QtUFG&(R_8>N5yGvhbVc|`V`5Fe}J-&B7twAc(9**pU@NR5!605iI z1TUxTZ@t$9y&!cnUKW00_r7SF3yk;5(bTW2H$tDc2-{(s5Q>fW+G26bhxtB~MkFpT zuZ&|N4SR?s&ErWp{EYSRwnluAaq=tVN*<1vVIJ?V;W1mMU*IpX6U^*nHjS-e`v!@S z;LMN@%kSEEKSEFJLe<-X4(~jZQ~Oc8zkjS)goU@}CXF~4Z@-`uwEO@1B80cMA-s8Q zqB$G%Ji$J{kqvn_pbw<&uFHn;P8ka9h=B0cJvBo7X=4J0FMh!hMZ(5g`@!9tWj#KW zC?w9Lw=unJJ2u|FD+A5fFEwVl>b)58u>~i;G{5So-EW!4n>)Cmy;2Up|DW2UAtG79 z{?}Wk$F&*qp|^OpK4%K8|6f6ecP_DK0>yice9S^Dytgh`asbA=ZO(Vv=`Hi`ZO4ls zyjw)wTwI{XiE7vHI8Q1gQRhpCiJXD(J}9ws1B~|#HL-02t4zQnPL^^Ptg-RF!+k8` zi~c6cQ6%o%`}_v7BR1YAbng-jYgrF()JG9cemh;v7HP{ekN3pHt%F=0_ze;v+$=$O z<|g}B?^D(c`AFa|ys271tKQ4$@XmR9UK7RJEv<*m=9E#%&Q6PByq35btxIQh9M-uHiWmU+B?ediAs|ABuw@%T&6 zE}iINw(tMv%GfjHBcfCHjYZLa{Xa|f`B=$7Ge~Q?8g%m5V@I?GiKr6|uxijX<3sLn z4I25dpVlCG%hz`XL3fbykBW15kvzdezK)riS4q?*Zg(20p&E4eWs>f8s0K|hzbfHp zWdh2{S^Tk0!>&Ou?Z=Pa9QLBfBXJt{<0=X&v4_}vIZx1P%TkuBLC+B%xj6ax3-X3g z%b2f0`R%8r!}j5yARRvFoK%`+$@W8R0Lg(NAKI3`_IIVzW{_*>@Gf-gjz;n3o7cJo z3vY#?08bci-*H~r@|MVkp9{zk-oEh%99UDBhMa zC3;wR6Z|AM!FbmcX4CLqb|lZ&62d#;t+C>epC{PR8QJ0tEpJ_o*}1$D!rS=9t?$7Q z-r~B+FIuEb!0B&#OEwx|<4q*ml}(;R)swf<phOi09cj??ZAysU=`Fo`k<2$`6L?o^@;cfdsXe36?~RMx|r5AlJQ zpZX!redk{=U%g2wN1Gv>td&&{{M!|$903dJ;CKwmrKbXNYsYmDie6`EnMH$ z8a{g~UShuCro0JwSyLiVZwWTuorNMP@v=UYS|o1CepTKxy4ZN%9?g_or^tGn6CH?; zJ2?5(T|Ad%B*%R9ww5xzdG8Z`|Nms&M8>i;7uml5f0Xf+AsCLyhm)QUN ze>ZGiGvwnBKjm=r-xs9q=6%mo<21=2;p77 zX(d%o*%J&*ZQBVXk*KjpW}d@%^A#NK^M~-Zt&2HN9y114cf8$PWr&UUSG~D&#^-uc z&^Z3rHFma3u<>3OaNg87$bjYW{*3r=z{w9d@%e`5DduO8dp&PFe>#OfgCsa5YK`|g zvi}V7{XT|#Bq~|D8~uIW(v}YIl6j|GP`pp4FkSARIWTR`CmNf83< z|NXyv91RTl2#-6P;E_dZkZkDiJ~eUm8H#uA4gaNBcu%{|IKgXdU}JdC$of%cy*5Z;GE7H*S<@CJ`6`VLB9FJ$dsUcq=*K2uGC@lH>X*C%W@0R_r7tl|Ba*IUwMti-tT zy(q#+Ts2@!3jT$S_p!&VV?VyI9^Pq)kE1yGm0fnca-g62>V0}pd0Wo~{JA$la#wq% z-y^o~{|Rwh81mtjQS;3t{lEU7rTToVWT5`viLM5ni@rY(u0e4BFFm+{2df6@d_3`c z3aUXdjZIeY6}vVtf7Uvv23;7Byzjy935MP|I5*jeM17?5d;UeJ2E|)kEC_^ZP`BnU zr-}gRi5=?wxxWDHD|Uz0w69-QM4}u);&@(i8ymY~pF#5P+a%Onx`gG1*kr`V7M%RP zFRC=Cy~BJB$_krjR?d&V|4%Th>zX~=f&GWrXV)3>(P*;NJ^c`E2I)wLcg5R=Sa>Uh!3PEHudsRrHsmlvdq94LE|kFy@$Vu%mC z{5)^O9Lz~zeg@fED0`4&4*nOUyfll?wz@oId%O)lpJ2#Gt3+M;+#|H(E$ivt z>8-e5TTKJt2I;YA@sm1Z@TryEDg}P*21(SfZzR5sM0t$FHC#{Luk$arw>(|6uPWbQ zJ-mewA9(rg{qP}F>=N_UyPS_=So|G-2kBzerNZU1?0-OdK;S$>K1wBJd-gyxNN94h zjt=iL{cqo))%*PYI~-Ve3%rQXgYkZxI!tSjimx_0ghO~&yuLXT4|swXhcu42_>-tX zz@XA)2=8I#kU!fXyhW}DjD5Lf44%7oQ%If@8}BdNr=BQ^dr-=exT}=bg)4@!FDLSD zmcH!pi}mmxL45Gw=J6JJZ8(;i&%oux|F69_4X3jE|GzgfR4RmoG8D;J z<|zx6p`;QSGS5?*go>hM%8+PQL?y~BskF~T$&?{;hSbJZ$rK53pIhht-TVF@zq51q ze{%1A9M|_r-^=xR@Oislz1MoLwa&Eym5Zh&#)zN?c7jB?RM}B9Iu6OQ#`5!HE)6~!5 zA=Z+@gYr&aT6jU4G=n_%)tnv8gHHCPtt5HSMo+nIq#5M7eU*bF@EN2d%cNFIE5SQR z!4f4}x;D_dDNDYGum@eguvXg__8?nUWyh*#8emkbSHI*hCrAs`%{r{t9l(zubphjy zbF;y#GRI)N9m=hC5Ysh)!H3r&>sO=CAZxQ~BU+0N z;PsF?wF6#hvVYk@dKCNgQo?WA!}~3w;~_?WqfHX^TuuLu_d$!_+`e^GJdh?hP#J5g zP4{@?B31m{~se1#ifbU1dCVnoD_{l$NO>)OO}|L zHJ%lz15W2ZeZPl3gZx%|^mz0E+6zeWh>ouq{nee`QM)Vp-|@B-?fD_OoQen1ni523 zTHn$?-c{7;=yj<~N`0}A|Myeioz+{{O~!k@!ecfxygllbe~~sP_NW0v65j1+r;;UL zyu(u~gnQxd|2HMIe|Ci*NdKl$E|3l5ou*#ntI@h-@_!jNq9f;_7h|wR%uWtjxRsW9nF#@+B(8NC8!nme$ zwrgTN-M{~LUYt4|5jFf;ivkz$Hlx7%(L?D*GTz%&BUsV!#tlY%C*j@hrMr`acWYYQ zhyjdu#GUzLEo^qcqxjIasNL33kAt%k>EpzrtGv%hA1AI1Q)=Z}t_ddB-1=yH5gqT* z2k~1bv#s&tNZpMcTT&wb^6l-5!oe8-T-w9?8=|8Gqd)$Pl&f0ood5iBV&Muy^{8do zb8npeuWxlb@${enzmHR=!<^N99XvT%1_xbchI_bWB1?2xofd_{|M$QD(b{hS&i}R) z9`wYmE}iT_cl&g?&^#zy>+E*Y4ASOxw<^hlh81wDa^Zkix8FZz z|Kxug3cQOpv)YjHu3xr{6AkZ{=5$RG-hP)^7p~a3mFV!O7{=Sg%we-Wyu9`9bwXf9 zkS!!2kx)&#LAo)wafoz5x=3u_2kTx9kPte!G~+MVTj161Yp60>;4dR}Rp*s5Xa5qA zCK{W6I`7>~b9g^Rbc|v27c#xl)jR*+@m@cDOMBP=8}CnS-lvN<)Bgc!0}f}Zbc{() zZ`yx-VFqbUfp_6tnFbl}^Zp$x(C{{?DUv7QouurraQ;8T&@iD4#`|UZF5*5F`1TfG z6HU&|wvYz%Kmh4^i{J)_X3`g=qpUo+9nBhG*NNT7?EKK(JLl5tRm2$!Jh@K)d)FDZ zFm(4GyJ=++$ShBDcxNIyhB5lP)=Vs2GWPFy%dUPsl#zrTkZ_Zki-xD^|NcL!b;!5q zUiRc6?f)O3z`I}|`5qZ>MaM_W(eNIHA~ull7TYtnu>XH}U0H7fjCXjrr|Andc!SjK z{Ok4>8|eDYHeJ&Ff3jR#k^^A8H+!xxiK){77b}Cu3|!Ii=HU&r@a(a~$0BvVpOx<9 zJdBR_rjYj^6EbKIZw^F9(dF z;GVeuiP_5rIwmzEl?mfLMp)tBAa#!q z=4hq*qvKs7KJq(z9qnySd`5IU!|2bvdXw;ehksw*a?kwwtK$q6?wu*Rfgno%=l_F$ ziBP5Ed`|5W%Y^^-|7k7i|F8YPL#z{p2feWOcN~%LkfOO6H0a4E}wHwG#J> zQ6*w~P;kxNl&Q1&biacX{4t3t9R+DZYvVE(0+J&I-X&5*H8S2Uk<6>m@V=<62S|8V zjXqph-dc6!$b(6Eh~2oVp>(&fJrLI%P{?qwhZK(#cN~ZDmSJm9&4=+;es;I9=)MNH zfM0U?XQ!*S9yhqnTv!xE!E=~%)*&;P~w z|M#bQb4uB;@y>Hr8sI;gPxpA6T5qCC$IP8a%&*}mc3}5*puqdt^q~u6ywk^5F z!U4+*O^EzC-eOOI_tVCr!(_Y_t?zN8 z;mv)7*(M27-K zf1$nymsgzrcf18{OrryosrW#;d~42SUoE=N|F}TvbZjETT$lN?dTU34cX49VVlv(( z6Fw`^@Wze1?jpIjC}*!S3GW!6r4ku1-U)`uxS7rH=Pled_K&A*A*ZRM_#_zbpcisA zp)lU|r^hl2L^MId&y*9#C(!Y}_`A18glj)O5vhAyoo1z_^cTD%&x=d8%F!I&QHTx& zjQ%#auJ7U2|M%BhrJfG?c@|^iJu$8^dE&rUx}Th6HY-x4gU3akpFKM9zy1IJHE`3| z58)Z4JB0_8nLWEm_8`GUo7SRvP~^c>W|9ZB^J*{LL241|`!W*tApJ#?s}7{tgZ1jE z`KN{)AgeIjybDqA6}z_T&!i*a`~P-uZ%96`0R(YRp9=gXARUzF%h6FV!LLT@Cf9se z-}IM&^l{2yTdKAs&3TXqqN4|+zw)U_8+_=$53y3kW6dmIshB~A?h0{uUrzsLkfije z)1kxVg?wV?MuGRMjgsrgcqd<-5k$lLu6+~-32z^t8w)!~gE!wMB*SN1<;4s_)b~o8XCm=4x-~CMt`$iY)itn{yW|-y~`Ol6krdrxU$BNnU~Gzeu%|2 zy{AgY#Xe@Kg0zMF?@EF9%aOcYWW2l1RSBTseIdY0kc4+@ZRNuL|Bx8F(Q_E@(lZ&a zwujn-c^&29%A*d@P~A!HW*Be0S@)T=Z~}N82`}JwX@EBm-gBl`q2nFmAW=T3Wr8n9 z>Wbr%!>6av^MA}tzf`;l?YValqT>Qaf8P7wU%a^d-)E5Q?ltj;g0XLJ2{nw0Tlct* z?(sgkggPB--roB0{M^C@sS5?(P%XzpGTy2iZ}6kx&0M)-BMEPJ^V)^eThB(8Kk9+; z7V(+TF*<4w0%gKJX^J^O>?=k?jz<&0q($7X&tU{G&?~LJzC{CE$$qVl7Oo2B(I_o1D?@w@xcsz8sH1Ru=vBj-2YdZ zt)HURV}k#N)CGNQJM?B09q*<+8QbU7Xm9VW4AIeu(O-Q{ez3B@zq|L6>s|(%#IYwQ ziWeU2dT~pG?(tS$d7CO7FBA!l`@;Xr|1_5L|Mzy_{C|+bgDQ;=`I9~9UW4R%G!If? zZ!aKygJiko$qv#QB(&Da#vJybmzB!L>qH%Zh1u=W@l?FKP%=d(|9es%Pa>(AbGQw)NK!ssvC zUzzRZk$)dzm*fyxbZ=9U{|g>qn~E3p-xATyqD^q9VBlGyx+=P_@C=7 zB;yyaL&IBrMyiU0_tO&7h3hT5e|9bxf$=uze=Km6!2v|~xo*o%afEyx9pP++@m_lP z^Gdg90$`|(Sgo$12`rkjdn5w>a=qoGgqDu03Em8;^Yu^=l>dQ_x1rQat`%Xlhj%2R zLl2|BU`TL}lH>UvOGPQuKw1-2ZSLO9WQC45KmIiMZft^ogVaeSU(McIfsQxtM0A;~ zEA8RE3emxh(Vx?+P3<}C|2~8C4g9cbS`8cTfDuo|(Y7mekGJE|qg3f|%oXIZzPOP8 zJt^>hox9}}8SkDik-}(rSExJ8knon`tz0-Dolk688vx_oM(novo@o!HT#iM!2suLg zS5LBOM-su!!TR#zC<2fzPaIvYqzQ^=Ojaq{pySQVi z=O`-;=6^;+2NOnr+^X}Q{QCdy-tYl+d8;|>(_6SLwd@gMTj_suBKr+hI<9q0ndWCK zse}-*P|*4exMO=LNj4M8Ez2;63r;R=EE|dk|#CU^}qZ5xOB69P$Ci zTSBsE={&sm7C)kYsOpXeP<-*U&@T>s?mf_TTk4&d34SwDXR!AE?!gT7{2#q#zsGrL z+H>#Eh>j?X{z9#pZ8Wz1JKhJFefE8m#Kt={ZQ}*^p(47+TlK97RXW17k5`qzx3~WH z{XZS#DtHEYl){7RRJ&Wq9%Q7-D~aYoro8b6q#;)CZJZe?|Nrvt^$v#v(r)=S6Q5=W zpghuWkL9ZqMD%MKk2yyK{X&oHL*fZwM)cRO+n?bJ(&iYMOx4hbSQFf-URTb2cwMCK z>jpy}!vgdnR%7$2FXP^{w+6Wf(V>db-=6%A$U5bJ_n;Zv-rvzW*d8=p`QVw7#J;C= zK;&Orl>0`Vj)baD2W+AihS(z%c)#QG6er^i?fEW&hIfR;ZW|Kbw-n;`k?^j*!5A3} zsrA9D5NSVr47KLc2ALrR(Md=Raw02Du;6F@(`y(Taw2#s3TUX5N!Fb8jj3 z{y%QRQ>MuBX8Oll@)=b+wFw*XAijk?<}~ zm^LQieMNES{kt&UUfmKbLKY4nJABy7f1MN5|D~s52*&#`@0?0@ECCoZwgzeVX#%kd z#g%6V(D4>+>(Q!BHo*%cb)C-&EC!6w@t&72UOd=Hdw2^YI(}pHxB2ZY_b&`wsDFLY zM(m3pR1%tauwQR^lzEY5mv%heZ%(wh#!#grpkl-N<$oS0_MyPL%2)k==H5K^d&SW3 zZf3l6n}oOT^>0Qbyr*~Zu00Fm9sKoCrvrc|C(rR3gTEc2>#jrZ;=_o*mr(fP3%vLC z;w7ihRHFuXEfUhQ#UYjsy|An|bi(E&t_zG-ITppTqgz zpTdKhmH7YX1u47iWt-4ENblD93)8R%Rkp46C3%pT6yJkUc!^!fE||gB+!6Ff%Jdw3 z=nQ2uR~P1-CIYp?C!&n55NE?m=t032V)VP4NRron)ni6Y&JP z2URs>yBW^V-WQ~Th>o`y{e3^Xc6(dYzkARUfvoziJ=jO=>Q3PmR20MLeg^r*k~$qm z`uLiIkqbLWeiV2&Ema&M2PFNF9$7TJk43L}O2V77`I8q3Z}uyGH&?<#EbC0#Ooy%` z&`{n*ER1!Aw63e_ygWk$cMg9&#CC-M%JRho_2JK3j`bgT&i0r0|J<7sdEHl=;twHp z*Dnc#S?xl{`|#1*{>krY@B4pOM8`pl{v^L}NvD_m`xQG%%8zFQg0Yvkg11>nvsFjZ zJ>EE8>U3;-dRor;&-wr36nHnbaE_AkHaL(igNCeWkecnB;RhUOZ+VLu(b0&}A5W&FzZmY{-8(#O>$AG=*zS#sXdSwv z`IG+fwxCYOMcWh|`MV4G-bGvJCrj z;$W?nGS6Orp?kb>R@CWGXWgbU3LkIzFaOg}&PQtn&i{cF9`r$ssfg@BjB6Q{(LAUc zJhlD>dyq!lOa{q=igW!Vm0=J1ZnUR#ZqyO@^UOH*&pShJxzgiSogji&9f_w$Z^2jW zzV4pwg3ln``yqOe$pYPj3LL)I-jh3kzl+pmFLo|H#Em}0UaAUse87PA?jX%YbX>&f zkMGXxvfxfm@bS6C9-g4-}1xLFYmZ=MvZQWD;QimR@X@cx)P!om;Z&3sPYR<7O=j7)KE zTsPqiajP*`Xr3g3$6WGZmy_W9pPleTB1HpOTIzm^(MQMoEFWIh(bf{bAE^Tuek8qN zLdUyFyMOcb#k6;W^ch4)BSwFXYO`|qR4&jqb|p4>z!Dp8t6H2vbs}UXbH9CEKK2aq zN0O0y!e_Q;Xf8)DKi5s8PKWsVz`2go3(H$4De!K4b?$$jw>08RRzSlW=!MUa@Q#yf ziy`67Hc@u#2fTW_7K%A6_P`Nn>+Pt>AUZ<|qW8WzoFanOf{L?hHwj>jxp9qOng(d$ zcV1$wg^st-HNMOEL34Z~Qn%S@^lRn_`V3Md*S?Eu3GF>^A&BTu!{{$%o8HCa9h@Lt z(PlQ1VLv9`Mx{)Ip~^%EL~ksAP=q~$#ARxGWE^Iqd%STEsnb!&dA3L9!9xB&L4kMc zRsH{Y-cokkA$c^st*lOJke0VxQm&pQ;hkx?)TR{1`$7Ex`-%WZpgWLRJ=N|Eakb2= zMg$VUrf**vJFgRf_sDh4U(ez9|AJcZ0sGMLzE`~pZ@btWZ-msHIQ)F?b4GOcW?aI3 zpzJX1Jx-L0=wQI;Z^wjzOPnwlCf5I_%gP7xozC5XjW>sa!Hz?gKj}UoIf_%KZWupDWD@gAMAwwZBv1UVn) zg|?MDLr*t!yto-e1d2`jt|wk204S27F!!zoP-A%Dvq&5r?+-d*2VE?@agVfvq|~j*OGtDA!h617BZ|5}Ur!hBW;#X$+X=bf#O@KmF*DxcE5_H5V=r6fGL&V5LxCuuGEH%M+XMTJuq$7t^UKe7&2jQ%DH%6Piq z1Jd$$XOdA)4c~hE2mCJ-PwKZ8Rtkt z>{T2E-aTVB_2eP8^hC8f8s6h2hrCI6<5wS@BMq^eytxl-hw;94t18em*a?^z39RN4 za)HdZPKW6F62ZNa)WL^o1mG|;D^q5u4o)%R2KQ#8<1KGn#~^(*5l^nm;;Zw%_9F=O zKl_oyhc}{kd(#}=WF3bw`g^YQ-MJx`6C8KmZMkc%2vsN94w@G&3fTeU-IVt=L$$07 zvmPg#HpFh4O!s)>RH@YAC)c3#=luT}3cS0YpEM@pJ$~Sd8XDfE^N)K-c&jcK`%1!l zV{v5aP8e^U)HkAX?oMFj@H?IN{4P+D{@D{j$BBUdvKyqFN&q)Y@4gR8RR`a8X#H3r zjDC7cg~h1-+o@tifI_9I?){7%7~6CjQ;Fh1#baYPQaQw|Jm27 z029|hS>y2($t%!Hw-FXFfIWi@Ub@V2x#|Y`&;RVy=}_3vhyVWP^_J5Vcz0cjOC;kh zpz5iLhPPo{?9M3|Z=Dr7?IgUDi$#S^VZ1joRh&Gt(+ON@+cdU<*9BVR`qHMr55B#n zJpM>U3IT|1)a~`nRtLisOZ-oWqT|g{$f&fzAOugY`>J~~qVq4$Tk0N}(_Q_=oaXRm zMs(<4^p`!*ZX=e)3F=O643~PGi-~vtlR3TDrk5f9uO4~ftk`%@?M%JE(RP;Z@n$!o zP6ys)(|pCBj}wC^@a}Xdxk1L;?6{^18s4{;?*D9J}J%lIM z4fph`ZVEup|8cPgz6GXlr#ZYc5FN1?{oN>6e^@QT1^N^kTkC`#VdCuv45!b)c+XxX zHry?y;_j`@9iJWn7W$u@Xj7@ig=ySM+#|K#Z`4gU!TBo+z}8W0vxAbAie|7(A- zVL|ht%;fXie!w2&XXSl?l>fWSu5|OmYmk;XMZ11&b_Q;08{%Jkxj=IXCd{*5M9{80 z%y2x50J0Ll%7koD2ke*LM(&wG4@ip_hac7}&&MxC>WWt@$t32Y&mi@;pZWYYAd==h zXepv&J4SyS1_s?{B{{+Ch-XLOPvTvqjiT?7E45a zov71s#xQcGDtjUSGgIK*H>|X9K{^TV5TY0}8s3TmhJ7TwWriR7knon7RO>Z>@y;3X zAo#Cx25J{g77y9DK*dCLp|FEQP}IEkV%kFj&|ran&nc?|vx!k3mtJ(d1&goX?pWvG zO_92jxx31L1ft{3`N_5>#q2!I;Vp#dSb@>s=G|UD_Z{K{^Gx1biz>16Jfm^L(&0rn zpt)?9x7PC5e;urd#!IZzR?__p(sGzO9RsD!4}|j;@LoiLH=%%O;evD$-rprBn9%T! zxH1?v0pne7Jh7LAxA7sjnsYGT?%P8rz!bcC8?u6Fld%irr^ntl?n4A@d4t~L83eGX zX3NJ3b$EHp8}z(yLC3q=rqtQLGXsATshbMB!!c`zj`t29>1gZJ5Sqig7SUmV(VwQA zR_2`|P9VKgX3}_DDdr6F?o*v+6BuvR82iwkK`LgD?|+H!isz$yym1Xw>R3K_YvaQ5 z)>S47ygx@7EIe;X!rP}2&xnS%b%E)oNf__4r9=f1-eoLG^$jrI`^0%1rQbV&8z*BY zM>Slaod$P3Ee{jHNRq-+qXz_VQEIXIfg*L_dn|P$emRLL@H+kDO{I>JLx$xKQWxBtkpk~ehOTMkxp!?#1Opo0v2ToXNq83rM6My> zZD<-XtqJGD>Bv_J)H$v)Me)xtCn4;soW%uTZ*LeXnhqpVTLj$9~_DZH@+`G8|_iWC` zS4PzDy#>X7dj_4szP$y%oKLZB8U1fg^sS*z#}r%9fhzcL;(z&{hI2o;H8}q-rSPDk zMGr2KJt(h7pB>GEg!<}Fj=~;Pwcm?F2=*X8>GK&Z@DOVtFl+e!o--&k7<@PvOjIpoG)Yw-GkyFn|JC4W%!LqUFHg>s4NxqBX;6v z8mn8ouG5?cT|{(X_17=?Hh^EA3*;Yp!g;Qx26KqLa{P(Ov#DE9s(ZF$u3cSB|5X{MV@0$=@iiUTr@)z6~j5l89=Ok%} zwVJM%WrXo=u&|hXbHN#WP*@xC=DZ6e(HdLZ<3a>P4ZF^aLIU8mmFtbzst#(}-yg?o zpyRzF{?w@-BBgk8-I;Oy<5FAEhuF@Sy$%73uhJae9Ec9A{&rO0ZaTVf0!FhTj)%3> zfk{bYi6~Pp}&iXrEng4&@Vo zi}lmv5&P9a^R^S;UALp-ZO-@f@DWBlz6q(jZdt%(rHzjFo?9K4Rn!t`4sT0D2UdT- z?Ru9vKH>yxR`;)K9>aFyjXARR)<17S(MC)2^R82o|F<(m9~r>WJ>Iw@RO(RKb$ZjE z{Le;#_u!3q4>I0-H*?w0@U|H{qd5-a?UNt!^?qO0ys2tJcFr49lWVmpM5fnj<<#K(ce~^p5b33b&>-*j2%4a zlM_{q?z5kB;%N@=1Bec+{@BbccH-g3iP(&cU;FuB=XsThozwc3Hz99b;l0%ZR9tUS z<+`SsTY&C2Cva`l=}3VRDpb-J+?$mGZ=&}8WHR2HE6%Z^;q5=~kxs%}LN76$5^t_o z+$XCIoPkGd`x9J%3sjw1CF1Kz1Z|T%SGML5K+(IV>f`%h_jYc7At{ZHcTq**p&i0S z_$H+8facC>PZo6dJ~Qn2D`Fys=J0-s=m^5-&p*=UipUR6kdSs`Q}i9|y|fvgH=F9V zCPC+U*0%_3#{TONbvV54<(U+^$D8RSbvll_cORDX|1bZOBQ{O{2?rz&3J)5aUmrvE zpn*ofh2}v{m%kZ)hdt<2{HttI{%5~^$!}_tg7)OjiR-+|E~n)qqsqn2n!5`VNxP7R7ymXW!vvk-ASO$Cb86qVFILv*+r} zs^6tK44 z|2Ifq`a+$KU!@tFmiR3Uu`4L>9_{aLCF9*2$jOO@xBiN;VG`cadsoGh@HXH$a7qK7 zLEig(kSS%g3)t>FA=pvl0%=A>A9b@Kf==%P{mFP3?}PJOJkF{CLcI-J;$QIYIwODa zwpb0mAE~>M7P7ABI6B^IH=b_X`8bv4@a{%*VD&fN#B9j(kQ0>k=qrgNW8*#9`7VAH zjQ7>f{^R0bu+IzNv~PZzztctcLo6ysK-y~wiU@dUbi$B0?>%?(uI1(3R}+_L6Bgwbb^p&JgqZPB?yb9l!hIrVgf~xuS?e-*^|qYVCZzVAGiY+T;0F?2 zAjA3C=1O}a=(!pxcmEjy>~k-9RLZ0doV4%%NaI2eNX@z{1cNgx@GeLl8&ms}HWhTd z&!l>kb6roSIlNmC9a#N^?3#UJs=@{2v@IN1w_xMV8$?)q7}njO*c zo;z=@C*u7YUx(BMevz$jO-9H2R?6u1u7^o9hxa_9<2FWrWlw6yjXgQR^g36wnp5vE z-8(}*{j8*iNB?!=1S>2!}bu9!L_UzqkbF|JbeHufOPb0pf#_b}p@kzSJ8>dR8jxGTiWP@}i1>TdFeE#R_ zExn0)9yGiyJombNgYg#jE?P#y+kA^ZxB}zdmnCGp_Nohz8L>{2n00}Se<+?X-Vfj2 zk~(HT_J#liS1U<$xT=9gEHwkex6$#g(R-%N@VXJthSWKL=c{)yqt77CH@{chQ2c=A z@Fwf9#OQC8+qa|}a-2ZYXX~dOga%B!6-)FThNe@X@=G;=pPo>$L8_YXc1YtC{pbH@ zc~t3ed`xgPU3mZRDi;Ob6E05=k=`%$FtKn6s$nUo2Z?4=9^|Z&EcJn=orN4@5O{~su5-6PNJNcZl&g@rmDYo2Yf+Zel$|2Zk}{voq6jEr~vBcGLMcoPLe z?~?G&ZT7Dt;T`i$6E0=wvVo;*jK8G!F{dVDMxB_Mj<4r5Vx;Qt?%0gB!eqRNVRaNZD#P z;C|rl>nwr`U0Fnru`~hxFG%NY6`r67e)7x@iv~E5=6sW&E>W` z5yrb$`FJY{?^oaRvbMo^=NI*Q27hq{Q*CB)cRs=A|0S~?NbewmOZu%3);1Hs{-0@P zqBW|(vbgGqk3KryA8%AC&Lp+tt&zIxN9IAnI&{3Xu9iecrsUEb-k%X20HeQt#;?v@ zlN{jvg@UU=Vc2+2q&l&NwB3acS6!;nlg9qU4o8eiZ*k@d0W`eLMB3I4!g%+c{*h0@n|n`gE+34yV@~(2tp%Cbr2^IYC5n_vI2Yc_FaLpWnftY*ddut19 zGkv&i*>jqnNl?*TDm!&Lgg4)ln~zusNUJFDp0V2APR84<;3hvB-t|7msz`Xt#J;*n z!aG=EHl_y-Ncmsi3Hlsy1u3CRW9PbEpk9G(v*E@>;8^k~Z*e^VJmd4Pcj{0D&!kFK zN9EA*UOj)uS4h1Tk4Nh6nn*qJtU|}zeV=MxmvJ`D;VppZ@WSX%uE5~Q^`9J|Y$=C# z&UtLSmvp?V6N2&nb>Af$=^Q6YfF6+hzZ-Bx&#M;Tl25=gh9)^u^#6FW|X%U)j6IxAqXh zk7Wlg+^8i0WBr@MyX@4!{TSyQ&1Q7G&16Mi*mpgI^}%>IoLJ&P!uz5|^p-;~ z-p+2@mkRxG10Q-X9yYXeg}f|Pv&OWEz-;66hK?Qr5biTnE8V6FZuhcYpRGp6yGJJx zcd)h_pNiCV|2*UUxf&gBudp+D>SYBqhj$;M1FOGv<~zo1ra3@$Cyt9Ds1?(_zo-9< ze;9Qi+LQ2_fw%{I2Z`6Fznrato$dpYkq31;uEf}V3HTF`1S#-lu;7Xyn#Baym3M^Rb;#$^4SZa;k~_j!yF0kyG(dt65dftwRb{cyq~Y^vOcQo28{L$X!rHI zK-O`w*6G`cpfp0n&#{95n1>X?H*~?96Jmxf?s4e(zwkf}OV|2NybV$}oE}(3tVGZM z)pyh-*d=KX@27~48jSurdpC-d&vAg{JtmHi8k;fQn`fzJ#vc89ko9vd_a+r8mbb1? z$}auML;sVLSn71FuUoCC0l(h*-~E4R>6V6m4(I>%6dtss-SZLIgFHrgB+)#Gy`awI zBkVz=SLZ@SVGk;~KJt77UV}VzfWb?By(i$ewCk1bbc0G>1f0o~C4xP3SEq0j@B``N zNN|@ail5Tl5Nn3$!0N9( z;06C$3r?_a-RGri+&VEmsF(1me0NL+bTP2CV*eWK{IBa9m11D4NB1679Y~#yecxYM z%Y-lF|8*32FMc$VO2*s&7(oIJZ;Qt#`Fml!o5LzCNqA4l=vOnqL+n_GhDT|K2e^b+ zNb*c~gI+-*S?-&OU<>Ps{+3Y!;9q01v?EysxNqWXxV;x0Zw_}SWATd5cn_p*w?1#K z;Y;)xB!}g>JLg-AX%25*LwM<0GCfW!+IPO|5zfSFFq zpafHNyzk6)T1?hE!(^X@=aP7wF#xYJ-!2c~=f+U(xM1mkU-^Jd5In^b(g)tkOe%P5cT@y3l& zsbl^!qvW6bFHC_q3kRz@8SiyJ_lTk4y)!r{O_-Lyt@YQY!4CO@6|96D5{Pej|m0q19nse{_hz>uD{)()0a*kDSfQlb(d;09!G4UoIHNT)xo(`Q( zcUAD3pyKPT)lM5kK8Vpj-a^#rcy+Me>_Yy3`JaYTK6)!~{@+O9K^)bhSIHifZOFa} z&4Yx>rg=MI531yDI=l|{piACXZC0=cNgOO?ymiqFWYinZ)!cB02DWqSJP;xRt~+O} zx3csB-l3%8`?e||sd(+CG*9#)mUC*DwN+*ie+{XVyIfSTvk2XT3O-opx4gsCoCmE! zbYS&&JC)tc$cGbn?@fKX*!Ux+2i=-lyi7|p3;N8sW4M}%{I9pFc->H*I^BDaEH8CB zro7Jt+s7>Ae+de_SEO3)Amgny*ei>MH|UZ7Ny0mD;t?R>eLFMyxh9Oa)>C}}S4}U_ zXSg|!KH8T-Jgz``Y052^qw(<5Kg-O%wq>m^(@u#1Q{N9ufL zohu~6(D5EMe4o1Z;|rR@I|9)$hS6Vy$_91r+Z^DnmuAmL7HquN)qU&UE1U&|kA6fk9Y73>U0!;ztWfe=LYEw6nHOpb^A!h+jrRm88p1F*lToj!FWF$ zv0hHX`{pZ~a9$YiTe$-zp>3XEJ7M?Nw*gC zns;Sr3_{0yz3b`23`Yj=9Z20g(QZX%2s+-9xZ%9G(Gr@&TN2TM)n5uPx1Vzt2MCOL z{e7=S52kx34|}(1=s$$!9()m5H-er2os*;V4Nq%<1dJP!h%bi;VNZhzKI%Ky$jPp*F^eIUKzd9#$gCm2=yl5e!!9l9h{ z=>JWE2!a(ie7-#cZ;&czZm%v>0Svx#2~Y2%<9)@-HIgl{A3uNWPhFDIA-}LBbi98W ztn#Xze@=6FCm}kfF#5YvujlL{#0hT1NbMs&>c+&oH&@M-sP_>1!CRwoJ%Nh+&vx@* z;0AfRKOl`;Mx_q_QCHFf>G0fJi~?`=Mb@v#co!FKmqNpvU0yb{2gdtO5=%ZM-ixI7 z%6mF_f;;E3Dqbvchl=KY;$KP;!SEDQi1ic!yuwSyOTv3^+m_$FzWy{i-kYRncUs%` z;dPO^h*fn@7VkmF`-iKv*|(HuG>5k`qGJN1Kf(^LzL0Aiz-eD1@80cQn0R|OA z&xA@36#c}vQ<48;wJMiMR?|P;SE$obb!zCB419abfBXOFv72W84eUX(6duG|dUz?> zgLJYMDWiE1af;cY74{&)*5ttT@DSU-QcvhBJj7mJD`4KqeGuqGUe6+?ctC5n^BRgQ zCjwRlv(%mZeIT=oBlMn;GT0`5+TKsu1VZ~g91=*2-()p}*Fx%E4&AM?NJ3v?|MFpN z^XrgOn)4uELUY3C|73#m3OXX4_=-v8e-v?8|q z{BF9RL2etNPKWiK$Mt4m3;AD$0&kwn?@p8P-VoEQh=w=Y#HpQaFy7fY$Ms2gHwNaF zF~R{UT~nsVxz8JXt^2{uaKZ!1O&IMeb5vR~K2uW!QK#e_ph9 zEGripIDa;wycs+H<4Tvx#Z~U7d%SUF)aj_{8}7ON=LKnL3cR^pdhV0)25EN`(D3fe z`>NUwAw6R%+UBrw4Q>XVDdX9wHd%&hTEx)d%>} zjkx1IltGNwD`n?R=y(fy_8g7!|B8=7>O6(=)vqg{q00 zEIQud9esmiT(pNbKcXWHqrYuJix?9hbAZa4JvR-!u<^bU5pi4q#yh1h`ogb^ROJ6_ ztQkj4pU^$txT{p^*gG4r?oa-gq`;f=_x&<5-fe-Jo6+!o6riQ}0ml2S7DE~d?}2mo z-H*X|Th9zbf^A+v_=P)8AMXw|3^3*^3c_!1)kjXNEa?O7%dFcpR>{4TR&wvL3GG9t*mtf%o*h2ApUmG=sZZbJSW~; z1Uvt~a;ccN*t?VNhgd~t>U7lY?H#;*c_IJHQ{XKSCHRv(#8$XesH5SXvQ0kXJ&d<% zT)!&`Z_$knL9b!FZwG?NXEzUmq#6%qg19FnXnnrZYJLE?>8G*sO7#Jy@uA90US&{q z>!bcFDRjI=V}3G;e;dJ@lw7I>jAHqT>cef0Lg4qnF?vr2TyAf~-NF(8 zwgl>QFnucNxb$cLe-j1Xt2Om}$#@q%_fbW|dyc34ax;uKhrA+@w7jLY=R{W90wLIj)Ser@(!+XsG&weLyLQwE;-zH-n1 zvb=>mIv`iK|2y6Zshe)@zts8#eR=EMO2R#{IojKtU`BM*V)SR^sOxIGmjfKiDe>K# zhP^p)cRQ=U9VfF3a-`wgTmH-cG?eqvT7mPw zDuoA$7T9kjc@Qc8?_jWILGz%_T>%GbVGrUweqvM{9%Aj3+k%+jH%QNA=xlSm=mWZ< z`qKvHJfVA=ZkTC2vWy( z_Q~t;!{{E=rB}kzCiI5phS*v}#|Mo5*w}{a&+Ov>%J~^F*QXaQa1#x*6>h9$NSXxyM7$$uW1f%X+%c=Mt@gy%nH%m=hz-1%u$l_zv)37`AL z;Q_Gz?6!y@%|37!IxQ7uqXb-tZrK&b_M*Bs>+(SUD;Z;WJEYDb%BjtH5*_cf+f7rU zO04mV|du!l^QO z81MJXo{PK5`T!ZeNBQ=do)GlY`|P#x0l>a-;=O}vAMmVuqW#bN6I^Kh` zauqycWB3-NF8%RW-|-%Fy!8mYRs*H9w>dF{=-7(U-+21#3#*toLHWiw)`##TPGpSH z{ya3iajs!$KBU8ZA*jM1`+~H!J}V2fMvUnG{=bfc)alSxjEmy%TiBdXq`-R(@rW}S zZ{OgH3}|>KdR;iz0OP&6`%*t?^|rk{FboebZzYyTtk<*lp7x^xa^ z&>r6V5FH5^{nZ2;T|9IczP&}?_MK`hHr~!Zbl%0mc*k&@J*U)0MgC7yG!NEqr2qU+ Qr4F`x@7{faZ*Td30Fh2Dvj6}9 literal 0 HcmV?d00001 diff --git a/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory.db3 b/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-right.db3 similarity index 100% rename from planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory.db3 rename to planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-right.db3 diff --git a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py index 07f8f3e30e659..4bb0630d13942 100644 --- a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py +++ b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py @@ -38,7 +38,7 @@ def generate_test_description(): output="screen", parameters=[ {"lanelet2_map_path": lanelet2_map_path}, - {"run_background": False}, + {"mode": "AUTO"}, {"rviz": False}, {"centerline_source": "optimization_trajectory_base"}, {"lanelet2_input_file_path": lanelet2_map_path}, diff --git a/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp b/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp index e951f11e49ab7..923fc53055475 100644 --- a/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp +++ b/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp @@ -50,6 +50,9 @@ struct VehicleInfo autoware::universe_utils::LinearRing2d createFootprint(const double margin = 0.0) const; autoware::universe_utils::LinearRing2d createFootprint( const double lat_margin, const double lon_margin) const; + + double calcMaxCurvature() const; + double calcCurvatureFromSteerAngle(const double steer_angle) const; }; /// Create vehicle info from base parameters diff --git a/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp b/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp index db223663f1145..2dd5b19f2f523 100644 --- a/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp +++ b/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp @@ -85,4 +85,30 @@ VehicleInfo createVehicleInfo( }; } +double VehicleInfo::calcMaxCurvature() const +{ + if (std::abs(wheel_base_m) < 1e-6) { + throw std::invalid_argument("wheel_base_m is 0."); + } + if (std::abs(max_steer_angle_rad) < 1e-6) { + return std::numeric_limits::max(); + } + + const double radius = wheel_base_m / std::tan(max_steer_angle_rad); + const double curvature = 1.0 / radius; + return curvature; +} +double VehicleInfo::calcCurvatureFromSteerAngle(const double steer_angle) const +{ + if (std::abs(wheel_base_m) < 1e-6) { + throw std::invalid_argument("wheel_base_m is 0."); + } + if (std::abs(steer_angle) < 1e-6) { + return std::numeric_limits::max(); + } + + const double radius = wheel_base_m / std::tan(steer_angle); + const double curvature = 1.0 / radius; + return curvature; +} } // namespace autoware::vehicle_info_utils From 470ebbaf0c3a6577be34d1871109ea2f8ee5ee49 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 1 Jul 2024 16:31:17 +0900 Subject: [PATCH 08/13] refactor(static_centerline_optimizer): clean up the code (#7756) Signed-off-by: Takayuki Murooka --- .../rviz/static_centerline_generator.rviz | 2 +- .../scripts/centerline_updater_helper.py | 5 +++- .../src/static_centerline_generator_node.cpp | 23 ++++++------------- .../src/static_centerline_generator_node.hpp | 1 - 4 files changed, 12 insertions(+), 19 deletions(-) diff --git a/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz index fc916f188e758..f1bd110783009 100644 --- a/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz +++ b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz @@ -122,7 +122,7 @@ Visualization Manager: Name: Map - Class: rviz_plugins/PathWithLaneId Color Border Vel Max: 3 - Enabled: true + Enabled: false Name: Raw Centerline Topic: Depth: 5 diff --git a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py index 2cd0c2f66d474..4bed564cee295 100755 --- a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py +++ b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py @@ -65,6 +65,7 @@ def setupUI(self): centerline_group.setLayout(centerline_vertical_box) self.grid_layout.addWidget(centerline_group) + """ # 2. Road Boundary road_boundary_group = QGroupBox("Road Boundary") road_boundary_vertical_box = QVBoxLayout(self) @@ -79,8 +80,8 @@ def setupUI(self): self.road_boundary_lateral_margin_slider.setMaximum( 5 * self.road_boundary_lateral_margin_ratio ) - road_boundary_vertical_box.addWidget(QPushButton("reset")) + """ # 3. General general_group = QGroupBox("General") @@ -123,9 +124,11 @@ def __init__(self): self.widget.validate_button.clicked.connect(self.onValidateButtonPushed) self.widget.traj_start_index_slider.valueChanged.connect(self.onStartIndexChanged) self.widget.traj_end_index_slider.valueChanged.connect(self.onEndIndexChanged) + """ self.widget.road_boundary_lateral_margin_slider.valueChanged.connect( self.onRoadBoundaryLateralMargin ) + """ # ROS self.pub_save_map = self.create_publisher(Empty, "/static_centerline_generator/save_map", 1) diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp index 24ccd7d660edf..de89cf4d12a87 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -251,11 +251,6 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( } save_map(); }); - sub_traj_resample_interval_ = create_subscription( - "/static_centerline_generator/traj_resample_interval", rclcpp::QoS{1}, - [this]([[maybe_unused]] const std_msgs::msg::Float32 & msg) { - // TODO(murooka) - }); sub_validate_ = create_subscription( "/static_centerline_generator/validate", rclcpp::QoS{1}, [this]([[maybe_unused]] const std_msgs::msg::Empty & msg) { validate(); }); @@ -325,14 +320,6 @@ void StaticCenterlineGeneratorNode::generate_centerline() visualize_selected_centerline(); } -void StaticCenterlineGeneratorNode::validate() -{ - const auto selected_centerline = centerline_handler_.get_selected_centerline(); - const auto road_bounds = update_road_boundary(selected_centerline); - - evaluate(); -} - CenterlineWithRoute StaticCenterlineGeneratorNode::generate_whole_centerline_with_route() { if (!route_handler_ptr_) { @@ -572,7 +559,7 @@ void StaticCenterlineGeneratorNode::on_plan_path( CenterlineHandler(CenterlineWithRoute{optimized_traj_points, route_lane_ids}); // publish unsafe_footprints - evaluate(); + validate(); // create output data auto target_traj_point = optimized_traj_points.cbegin(); @@ -714,8 +701,11 @@ RoadBounds StaticCenterlineGeneratorNode::update_road_boundary( return RoadBounds{ego_left_bound, ego_right_bound}; } -void StaticCenterlineGeneratorNode::evaluate() +void StaticCenterlineGeneratorNode::validate() { + // const auto selected_centerline = centerline_handler_.get_selected_centerline(); + // const auto road_bounds = update_road_boundary(selected_centerline); + std::cerr << std::endl << "############################################## Validation Results " "##############################################" @@ -730,6 +720,7 @@ void StaticCenterlineGeneratorNode::evaluate() const double max_steer_angle_margin = getRosParameter("validation.max_steer_angle_margin"); + // calculate color for distance to road border const auto dist_thresh_vec = getRosParameter>("marker_color_dist_thresh"); const auto marker_color_vec = getRosParameter>("marker_color"); const auto get_marker_color = [&](const double dist) -> boost::optional> { @@ -806,7 +797,7 @@ void StaticCenterlineGeneratorNode::evaluate() } } - // publish left boundary + // publish road boundaries const auto left_bound = convertToGeometryPoints(lanelet_left_bound); const auto right_bound = convertToGeometryPoints(lanelet_right_bound); diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp index 42033f7956bfd..fd2314d42e46f 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp @@ -133,7 +133,6 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node void visualize_selected_centerline(); RoadBounds update_road_boundary(const std::vector & centerline); - void evaluate(); // parameter template From 222d3199ff9fd7c7d52b9d6bce47276cbe7497ee Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 1 Jul 2024 19:35:03 +0900 Subject: [PATCH 09/13] fix(static_centerline_generator): save_map only once (#7770) Signed-off-by: Takayuki Murooka --- .../scripts/centerline_updater_helper.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py index 4bed564cee295..f3d908713361d 100755 --- a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py +++ b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py @@ -162,6 +162,13 @@ def onSaveMapButtonPushed(self, event): msg = Empty() self.pub_save_map.publish(msg) + # NOTE: After saving the map, the generated centerline is written + # in original_map_ptr_ in static_centerline_generator_node. + # When saving the map again, another centerline is written without + # removing the previous centerline. + # Therefore, saving the map can be called only once. + self.widget.save_map_button.setEnabled(False) + def onValidateButtonPushed(self, event): msg = Empty() self.pub_validate.publish(msg) From 5bed858794e5d88799d9dd1096c333d884ea3e45 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Mon, 1 Jul 2024 12:45:46 +0900 Subject: [PATCH 10/13] fix(pose_instability_detector): fix a rare error (#7681) * Added an error test case Signed-off-by: Shintaro Sakoda * Fixed to avoid out-of-size access Signed-off-by: Shintaro Sakoda * Fixed the test case Signed-off-by: Shintaro Sakoda * Fixed test Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda --- .../src/pose_instability_detector.cpp | 6 ++ .../pose_instability_detector/test/test.cpp | 58 +++++++++++++++++++ 2 files changed, 64 insertions(+) diff --git a/localization/pose_instability_detector/src/pose_instability_detector.cpp b/localization/pose_instability_detector/src/pose_instability_detector.cpp index 28398588809eb..23362dd13c6bc 100644 --- a/localization/pose_instability_detector/src/pose_instability_detector.cpp +++ b/localization/pose_instability_detector/src/pose_instability_detector.cpp @@ -354,6 +354,9 @@ PoseInstabilityDetector::clip_out_necessary_twist( start_twist.header.stamp = start_time; result_deque.push_front(start_twist); } else { + if (result_deque.size() < 2) { + return result_deque; + } // If the first element is earlier than start_time, interpolate the first element rclcpp::Time time0 = rclcpp::Time(result_deque[0].header.stamp); rclcpp::Time time1 = rclcpp::Time(result_deque[1].header.stamp); @@ -380,6 +383,9 @@ PoseInstabilityDetector::clip_out_necessary_twist( end_twist.header.stamp = end_time; result_deque.push_back(end_twist); } else { + if (result_deque.size() < 2) { + return result_deque; + } // If the last element is later than end_time, interpolate the last element rclcpp::Time time0 = rclcpp::Time(result_deque[result_deque.size() - 2].header.stamp); rclcpp::Time time1 = rclcpp::Time(result_deque[result_deque.size() - 1].header.stamp); diff --git a/localization/pose_instability_detector/test/test.cpp b/localization/pose_instability_detector/test/test.cpp index 9300984967d4b..482e659e7a13c 100644 --- a/localization/pose_instability_detector/test/test.cpp +++ b/localization/pose_instability_detector/test/test.cpp @@ -163,6 +163,64 @@ TEST_F(TestPoseInstabilityDetector, output_warn_when_twist_is_too_small) // NOL EXPECT_TRUE(diagnostic_status.level == diagnostic_msgs::msg::DiagnosticStatus::WARN); } +TEST_F(TestPoseInstabilityDetector, does_not_crash_even_if_abnormal_odometry_data_comes) // NOLINT +{ + // [Condition] There is no twist_msg between the two target odometry_msgs. + // Normally this doesn't seem to happen. + // As far as I can think, this happens when the odometry msg stops (so the next timer callback + // will refer to the same odometry msg, and the timestamp difference will be calculated as 0) + // This test case shows that an error occurs when two odometry msgs come in close succession and + // there is no other odometry msg. + // Referring again, this doesn't normally seem to happen in usual operation. + + builtin_interfaces::msg::Time timestamp{}; + + // send the twist message1 + timestamp.sec = 0; + timestamp.nanosec = 0; + helper_->send_twist_message(timestamp, 0.2, 0.0, 0.0); + + // send the first odometry message after the first twist message + timestamp.sec = 0; + timestamp.nanosec = 5e8 + 1; + helper_->send_odometry_message(timestamp, 10.0, 0.0, 0.0); + + // process the above message (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // send the second odometry message before the second twist message + timestamp.sec = 0; + timestamp.nanosec = 5e8 + 1e7; + helper_->send_odometry_message(timestamp, 12.0, 0.0, 0.0); + + // send the twist message2 + timestamp.sec = 1; + timestamp.nanosec = 0; + helper_->send_twist_message(timestamp, 0.2, 0.0, 0.0); + + // process the above messages (by timer_callback) + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // provoke timer callback again + helper_->received_diagnostic_array_flag = false; + while (!helper_->received_diagnostic_array_flag) { + executor_.spin_some(); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + // This test is OK if pose_instability_detector does not crash. The diagnostics status is not + // checked. + SUCCEED(); +} + int main(int argc, char ** argv) { rclcpp::init(argc, argv); From cb3e7588a8c4ad5ec5e147815c6193467e0ff4dd Mon Sep 17 00:00:00 2001 From: Zhi Wang Date: Wed, 3 Jul 2024 14:28:38 +0900 Subject: [PATCH 11/13] feat(mrm_handler): operate mrm only when autonomous operation mode (#1377) feat(mrm_handler): operate mrm only when autonomous operation mode (#7784) * feat: add isOperationModeAutonomous() function to MRM handler core The code changes add a new function `isOperationModeAutonomous()` to the MRM handler core. This function is used to check if the operation mode is set to autonomous. --------- Signed-off-by: kyoichi-sugahara Co-authored-by: Kyoichi Sugahara --- .../include/mrm_handler/mrm_handler_core.hpp | 3 ++- .../src/mrm_handler/mrm_handler_core.cpp | 15 ++++++++++++--- 2 files changed, 14 insertions(+), 4 deletions(-) diff --git a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp index c908ca1a62ee2..7d7deb8c4a504 100644 --- a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp +++ b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp @@ -148,7 +148,8 @@ class MrmHandler : public rclcpp::Node bool isStopped(); bool isDrivingBackwards(); bool isEmergency() const; - bool isAutonomous(); + bool isControlModeAutonomous(); + bool isOperationModeAutonomous(); bool isPullOverStatusAvailable(); bool isComfortableStopStatusAvailable(); bool isEmergencyStopStatusAvailable(); diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp index 326fbb392fd35..47cbb0ae7d016 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -396,12 +396,13 @@ void MrmHandler::updateMrmState() } // Get mode - const bool is_auto_mode = isAutonomous(); + const bool is_control_mode_autonomous = isControlModeAutonomous(); + const bool is_operation_mode_autonomous = isOperationModeAutonomous(); // State Machine switch (mrm_state_.state) { case MrmState::NORMAL: - if (is_auto_mode) { + if (is_control_mode_autonomous && is_operation_mode_autonomous) { transitionTo(MrmState::MRM_OPERATING); } return; @@ -537,7 +538,7 @@ bool MrmHandler::isEmergency() const is_operation_mode_availability_timeout; } -bool MrmHandler::isAutonomous() +bool MrmHandler::isControlModeAutonomous() { using autoware_vehicle_msgs::msg::ControlModeReport; auto mode = sub_control_mode_.takeData(); @@ -545,6 +546,14 @@ bool MrmHandler::isAutonomous() return mode->mode == ControlModeReport::AUTONOMOUS; } +bool MrmHandler::isOperationModeAutonomous() +{ + using autoware_adapi_v1_msgs::msg::OperationModeState; + auto state = sub_operation_mode_state_.takeData(); + if (state == nullptr) return false; + return state->mode == OperationModeState::AUTONOMOUS; +} + bool MrmHandler::isPullOverStatusAvailable() { auto status = sub_mrm_pull_over_status_.takeData(); From 9f31524e84f984bb393331be71e89f79cee136a0 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Fri, 21 Jun 2024 15:14:55 +0900 Subject: [PATCH 12/13] fix(image_transport_decompressor): missing config setting (#7615) Signed-off-by: badai-nguyen Co-authored-by: Kenzo Lobos Tsunekawa --- sensing/image_transport_decompressor/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/sensing/image_transport_decompressor/CMakeLists.txt b/sensing/image_transport_decompressor/CMakeLists.txt index 2359a327abb8c..2ecd3446290df 100644 --- a/sensing/image_transport_decompressor/CMakeLists.txt +++ b/sensing/image_transport_decompressor/CMakeLists.txt @@ -24,4 +24,5 @@ rclcpp_components_register_node(image_transport_decompressor ament_auto_package(INSTALL_TO_SHARE launch + config ) From a28bbd2c49be8666650e0f90dcc91df40c652849 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 4 Jul 2024 10:34:17 +0900 Subject: [PATCH 13/13] fix(euclidean_cluster, ground_segmentation): cherry-pick bug fix PRs (#1378) * fix(euclidean_cluster): fix euclidean cluster params (#7662) * fix(euclidean_cluster): fix max and min cluster size Signed-off-by: beginningfan * fix(gnss_poser): fix a typo Signed-off-by: beginningfan * fix(euclidean_cluster): fix min cluster size Signed-off-by: beginningfan * style(pre-commit): autofix --------- Signed-off-by: beginningfan Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * fix(euclidean_cluster): fix max_cluster_size bug (#7734) Signed-off-by: badai-nguyen * fix(ground_segmentation): fix bug (#7771) --------- Signed-off-by: beginningfan Signed-off-by: badai-nguyen Co-authored-by: beginningfan <103237402+beginningfan@users.noreply.github.com> 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/tier4_perception_launch/package.xml | 1 + .../lib/voxel_grid_based_euclidean_cluster.cpp | 8 ++++++-- .../src/ransac_ground_filter_nodelet.cpp | 7 ++++--- 3 files changed, 11 insertions(+), 5 deletions(-) diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 6ec706a4aad32..57d4b209efeef 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -19,6 +19,7 @@ detected_object_feature_remover detected_object_validation detection_by_tracker + elevation_map_loader euclidean_cluster ground_segmentation image_projection_based_fusion diff --git a/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp b/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp index 40699fd6e27ab..126f877afddb0 100644 --- a/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp +++ b/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp @@ -106,7 +106,7 @@ bool VoxelGridBasedEuclideanCluster::cluster( temporary_cluster.height = pointcloud_msg->height; temporary_cluster.fields = pointcloud_msg->fields; temporary_cluster.point_step = point_step; - temporary_cluster.data.resize(max_cluster_size_ * point_step); + temporary_cluster.data.resize(cluster.indices.size() * point_step); clusters_data_size.push_back(0); } @@ -117,13 +117,17 @@ bool VoxelGridBasedEuclideanCluster::cluster( voxel_grid_.getCentroidIndexAt(voxel_grid_.getGridCoordinates(point.x, point.y, point.z)); if (map.find(index) != map.end()) { auto & cluster_data_size = clusters_data_size.at(map[index]); - if (cluster_data_size + point_step > std::size_t(max_cluster_size_ * point_step)) { + if (cluster_data_size > std::size_t(max_cluster_size_ * point_step)) { continue; } std::memcpy( &temporary_clusters.at(map[index]).data[cluster_data_size], &pointcloud_msg->data[i * point_step], point_step); cluster_data_size += point_step; + if (cluster_data_size == temporary_clusters.at(map[index]).data.size()) { + temporary_clusters.at(map[index]) + .data.resize(temporary_clusters.at(map[index]).data.size() * 2); + } } } diff --git a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp index d7fa777dc58c9..aa224e7adc5bf 100644 --- a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp @@ -292,12 +292,13 @@ void RANSACGroundFilterComponent::filter( no_ground_cloud_msg_ptr->header = input->header; no_ground_cloud_msg_ptr->fields = input->fields; no_ground_cloud_msg_ptr->point_step = point_step; + no_ground_cloud_msg_ptr->data.resize(input->data.size()); size_t output_size = 0; // use not downsampled pointcloud for extract pointcloud that higher than height threshold for (size_t global_size = 0; global_size < input->data.size(); global_size += point_step) { - float x = *reinterpret_cast(input->data[global_size + x_offset]); - float y = *reinterpret_cast(input->data[global_size + y_offset]); - float z = *reinterpret_cast(input->data[global_size + z_offset]); + float x = *reinterpret_cast(&input->data[global_size + x_offset]); + float y = *reinterpret_cast(&input->data[global_size + y_offset]); + float z = *reinterpret_cast(&input->data[global_size + z_offset]); const Eigen::Vector3d transformed_point = plane_affine.inverse() * Eigen::Vector3d(x, y, z); if (std::abs(transformed_point.z()) > height_threshold_) { std::memcpy(

%c;{O2cJDaS2oD>7Fw57+A7a1F z?b<{9A+g{$NVibwV}skas|Sw%##^5P?-s|3-xs8lPH$xiedNZ%I||<4u7KdZZ(~w{ zBZ7C3y71@@1n*V7BRly`LSed(TgP}BwcvY;Ig-zpi~@+TXqtKQH83l0Zyr4n1QgOt zm68r&&SG$CzfdJM-bxcMlH4n35AS7U9|}16F}=TB{6&obuK9lZ zTK)nbZ*R?3?K}kU@q4f|I)TL75KraOR*uPqrlQ7 zCP1|PHCX1X9V=%N4DQFDA6aq&`+_tcqO~hGod8@-juT*Cy0KChdvc<-^^W7#UfRQ( zi|j)gC%+uAVKdHOJYbnia|8cfe7wu@iz8ofHNi>yHPS>m@%R7flA@-N7fBZWPz+ID_(;J;o`)%I>BIqZ}rWO+SqtsPRGDl1Fm>MD__aHTB@x?WqqzzJy`Il)Txe>6gyRfzEFAJD6*ieZrZWKt$vpw}F z>j3R{GGDjz2Z9l%8(tL^?l9Kx=Eu~fM-L+f;Lqf^MwtrsR88z57HDxL%3IUk6T3gj zK6G*N+gxavo}NnpE3y>&*_0qXtltaz&%5+)p1!rL0S;^Gxc>YseuG4}HS69BkN<)G z--=2fniKEISL~Qj;N1~uaRMD;-BlO`u<(wQKKtw{g10KWZRlRE*!jYVOzuE%H2`Sy`D5elZosee#zp`x zBgeH3>L1tqhCRf(KCaI=vzzwtMt!*8=ByO)aXn;#o z9-O=I7Jq~Em9ndu8mr!dZ;-yKQ0K$$!j&4KKPN~xP~iP~{m=I(-U4MUOR(@hp!0bQ(6^ht~RwSBB9Z-ezPU5jgod4=P+{ z=HdY}Vmq|o5b*JCl{M$Pj^KSg&?`nJ62E#!sd|U^9{nHqKw6zT9~Kqa+XeD|H%P`5 zc(==+os5y3-1w@hYB4C-t(_y6i9fVwi+CnM>a?Uk6kkJ=Lv_m{<4s>3pRrp zT|x+xr$@n6y2?1AJsp5sM3K)xB@nn4*_&?B!p8f{xo-nZ&glXf9^!!Ebk zhY-AL_N6;}eL?o#m^AceQ;guHi|mq<&y0eNT)!T_GwuKv_2+he`Wgu8Jox*8xCiFk zd-6)I(X%K4xQQIMTefz$%Xe(N-{qC8+3ZJq{r?xTkGDAam6%$%-tOlCi|Z9mwfUbW!+e>z(#eJt_qA{|cr_xwNFtf`_09GUZlhq;HoDSdTAiS-;AKm#djJ^!Qjn1!i#^1O+kHys-7N@DlH+({f?Nx7 zvHSmeD=!XK8QL3SCCEM=;pAsiHeX?~lK^C&Es36q#vfwGUQftz&ey|=lYEY{6;vFM z?q};dr13v+|KEEmeaP;cTKQ)OX)^`heeP)&P`tBG&5B^*-D_|%&H%yt!Rx6P&IsO1 zb++Y5BSS3z8@R-pBML52H(c&eU4_ z>>+ks$vY)mMG&qg$5mMUvTb~ejdx6F@qr9E+Qa(`*+(=^e*8oH7I{Jh@KpUMSmKV4 z_p{lzs$WeTV0+e{!s#{mCrIf=fn)OVcME@rB~s@@h4(>h)WzR3NHYq&d$rCDqj(Q( zYgmef_tB^8n{5%iQydMYNO;5M_a^)iy#2RN_C1P@ge|VsAKxu)3m@`X*Z3s>x!%%M z$ZjVif_Ld`=i=c2FdtT8v5$a_H+SZ`?qEhinBm}`xYX6Jr~S&X@n&`_ml0E;J-ksL zOgQpNN{(x~|UzrD1eyT*U}f^U$jsq|s9 zs^@8B%Mi>k4^PiV-dLwwVX;}vEMezP))KTAp;GJl`^zri6 zL$JQ=D$ODb8~9a?uHWU*QQ#7CR@~!b2Y8qeD>W_-N8l1AF%5WK}B^o|$Y zqT+C(h_U0&P1Xw@Z#pV{tSs?O6#esg%O(oEySgPkQM}u^U4^jlex0>ycMO6zzwz{A z(%zfmN42Xa$m;Dtw^X$j{UKPSg?N`y$O>lvMCaoWISTG&Pah0<-T^{tId$Bm0>K`x zo`~+{r?@+XAo~IWBgavFPJqY`jwsEN}Z@Lwk6mK2GA~cQ@@@+#4qXU}5}T zyF(WrZ+6o`?Dmwx8I=l^NA>;F$` zNdIq1QG*6kO6AcSbakDW3|0-2txX&PX6smEuyhvf)u0x#k1aU)wa)uIIP;DG=<1&}yWhjFL7R=agv5gC;WwR% z>A}(XN9-<7TbqPlU-(~;#!%@aYbD!uy@cO0NDB(Q2i)v3P`ocnPDx?mz0-A$z6-%y zYE;dTgg1{UbmI_$cY(}Jz2)qO;eq_cUXxBc;kT=}z8Gv91(%-PH0Lbp1Z}Cq?UMTg zz>ADN!Z9A~Ay)CJ1tIXP5RAsnwcC4$ZNbJH*8N~yR6=`rE0KLv;pDe!D{pf!a{s^S z{tmn3e}MO(Z*m_~8vYIv-EG2>uj0}Reg;{8i#i`h#SGGrRUGL9>1`Bv_pgQ2QM_jo zY9z7n&Rou{@fpFpvWg{TAAS7YNHn_4$7eV_L5hRHr+ zaPkv=wRUwavU*#xOsC|)4gBh@Y$CCJ3sSw~3q(>39#XM`7Tzcz-uekif!wY=x@|BhnxZut9HJ5xn^{I0W($y#1bZ?c0zL1xFvL znPV%php%`Q9)0RC3T9Rlm#y&a1jHbhOT$ng(D9!Q6?=n?w|4f^_|q0b@H%o_tdzd^ zrzmW^bJtk#IQx&LEot4@{r~B$DFYtMX%FxFWFKib`I&6sledv10Oh-HCRQKC z$2*Mq)#SjhdU(0->Qf_Z_;_=9{4%JLUHI2qI=EBk!%8ggn^)Su{r`d}V#o~AmZAoI zIx3Ze)*ustfILQYF9WKu$Z`6>1gyTMgg!aYhDZXw6tJm|I1-}NFJw%-kw`VgOI*~U>5xlok;61YA#xoS}B|ksNV&T18_0btW1n)tv zBhNe#yeCedw^)xnv2&gObh7o#VR-J0NXJe;z!u91HKU_+jE11n+%3uJ-N--lqG)lr@q5 zzq}-Yd3Wkzc)yj(worE`*m!{b9wV@}^${?Fk=D+;`a>O*uT|8$&bzB zRQ8S~1TeqnW+VLze7qmM_PAkfP!Ge?+h26u!k>H7ZHRt0;d5u<<4vWH=0kj}UH`uS zhu6Z<#@{0|NJokq^d;ty4O)XX25~51)u4PwlaG_1O7!Rwi#2?a8l=*+Y*qp3|67}v z{jjW#hI_ggI~{(y!69otUZ-C&3belMev^8$3q;r*mb0Gq2W9D7bI0SbYtZ>}!yByX zOW`}@I2ma>0Xg#k%>F-JMb(>aNCfknrvKJ2`vTcV22Os*pVZz6s^kH?Z{IR{W{Te+ zU2)E|%llRfvnv^MNwDMZ|I?+aMrBsiE&Lipr4M(xWf}6tzh{sR6nKwsbpC6Ib+3D+ zh=q6S&oz%(kRet%OyYnKg7>>_!=(VhTW0gOo|lEu@V3)Q_Re+t;AoZu*Y$-*!FA3e zgX`H{;0yEF(5>_V;91UYk3bh}yl;mPqgA<=!Y{~izMI#c(ig|ZTU-BlkLXw0!@Hd9 zLkB0nTOmA*jWNjke@gwMFV^AX{k~h~)G^&UI442&+=Eu{ig(u(u<-uG=6h5W!P{JG_MSI_cNuSo%4P)bIWFFE zfw*Yc{@b3%h32lXPPBt%ruZm$xq0unbxap{zI+n{cfLP3-+a=#WgB*bq--t8QTsBL#>5r*B!aqsVr-|zdI%?Y*p3R~l8@awG{vJZ8f{DjJG!dXlN@Q|pm zYP&jq_2z8b6<&i>?{6VS!e&`i^#30QBCMa^S@8S+bkzD-EyY7V-eO0AH}RgOB8qpa zqsdAvyl49N9^ZiAZS9hyPr`fdyNG8tf;aKN-QB0xMI9Hg$MVps3ZwEd0dYP46q zEyzB)aPqsmlwIAbh6nKaXqdT)q#Uc5tBaN6n$zMH3uZ_|?yUD_z zdsFG7tupD_2y(sUzu*7=MF8#ofb{=+C~DBmfror(4LTXbpn+9`9OjHtk0JfPvMvN{tx!#N>=gYn2bYIpIvxtvMo4Q2%kbPpTWlnwk~;n)Cx~ zSL&qp{mlo`$+s`vy*RuS<{-y8o~q?65yEbep80FikEhUHgLIPY124b9%}`8I2oHGN zu9%URgkOW~<1)f;CDp)8(%3UdvziC?;k8TQ1LU}eTV7>rOkxkQXI>3= zAIzgYyf>45;N{1rA-v^hIS&{$J6hitg^zdZ3HD!45WHvdrH=Z%pyGgZ-QiUM9#TdBY8ois5j;UESa=US-DLL| z!TX2q?c06`-cMCye3_62>4{;_MgFm9_~nIsW7iMvFul9zDlfKCuqg1nO~9KjuzmfD z=Zq))!O*IwJ<7kZ@ebdzPNDY5Qh1mg*I_dd`9cF5?@LSv^Jg186WTHFJHM=^wh#1xgco{Dqe57fAm5Y$0gYXU%hRp^ikvp2{0e~y}Y%P z0`H0Yj-4ppij1bpSa=_PH$(ph!TW$?!B^7WTh(so5Mc!Gya(;3NgdHJU)TCOH-C^+gJh5wq}IN0ro*a1DNjx~?}&ic@^UR@(bx{PCBgb(B6baYOVGprBH=~>+Hqc%TxQYkUxQvsoIm+?>>)gETf8^1k%}2)@Wx0Rb$G!Kv2-ES`EV0-u&(;@dx&+V z!25^B$-j=b>@u&{!ooZIUMGVVf_LrNwQMB3WjcA}!VtWj&aV9uVjcsZ+_$|13iOA+ zSBTwr7$O4mJXUGC&~9*Y^rhOC=YGJsrhD*GF*e?eJ(&SNF#Pk$%Xb&B@hg*8ciX;=Md3O&-h)hX9$AjGhxawI54`*|1PM#OJtly;^}?FOGJL!{r0;zH zf#5x!EO+lSHLtgDMM$s+Ed1*&=&1G4zeI-odW$m!-ru?+{ZYIlPq=Dg;VrARFLy73 z_mB33gFy)1xuPGJj#{ef&DfiIDDQ}YhrfOx=6~{qlfLy!dXE!V} z;5~b(>aWvV1Ut<&Sa`3KGUPsh;JusqLwO*AH{X??PJ&4Fwv|d;vS(uq{PywPcZ+;| zVVS&y>!+rPVD^-Z-Yv~;U}7F~VgvG-$`RAya|U~`@qT^SO6&xe2%JQYtB5!IzU*(# z-YN}m%Bzc^J-oZfKJfBmV5>5l*W>|@z|S<_41Byprb<^!@YTXPavH20(fD6)(OHSB zuJO=b@OabNQ0L>k;;baozvurcyKLJ18R`E$|5JnH7+l`uqW%9qb!%p<8pK^wXaJ9t z=s5_~RvkoY5K#I#e#=5t?`(@7?`5?Z`0m~h4+ED3!z=Ejx*m8;1i+|AjdipeJn-*j zW3BWByjD+pq=T{VAenvHs*&3+0;6#cv@&X!S7Hyb`I9xyKV6s7-1+|>WFG}M`R!R8 znEM?$LHbo5KBuviRSyps+sCd(HEXM3XzD^}G8I?s(4EU``w>g?fE z^t(awpun46RcJSg_gjhOOjvmHFWMB;ir_sp$TuBEnn9-Kh%QEEkg^<$98!?uEyU(b zX@Q$TuyW8E&#C7`0B^WIl+e`;_E>1=GE^W}<+%5Ie%^?Ucdozqmr!JR3yn)kN{Rd& zi;Z_lPlPtF2kqfqK=y%`AFuKAyYL(j*m$DFw1yoYZ%Nps;YL_B9JcDx&U>u*L+ru0 zrj$)Tloovdzc`*c9}KCZv66odNV`+uy@*@%35vJatse|ncuRW8XM8~LW{($EAmLq? zbiywh!F&8UU6B9U7}$4tYiOcY5X|Kd`VO@c!Rx1N;`bZ6ffPe$MSYDgfW#OGaq8H3 zn<_dV0?6_fGdWI@d0AeyBR1ZwWy0y1ezb@87P1e#{NfT#Z~5sEfTOGBO;rYbylwcE z`X&*)+v&bQr>J?oC3|wm{0WT(k2f8)KJF}%QvCCQ^#1?gEj#~i%n!x;GwV}&EWB;~ zi#~lv@ZM2r>KuyT{Y4b2=Rz7JqZsbQ%yluaVqezw{*pjgVbesZKnD@Izl-2qK2)^-h)E0_*(%0s znh*dVj6b80+Cv0)PB=Ew7j%OU8|zFIp7;Tgbm^B2i?GlC2dz8y=?!vRMU))ZA#77* zp%sXE&YeqH{e-G6?e+g5WFL6>9m`yIU4vsW7(XtnJl=zkx1jd55G`cy&EitTxppeP z|5uY=&zj+RYr)UG)2Q^ZtXyQz@z^xLhBPs68LH{HC%6Z=+qoOLE4fR!&vB=4M{@^q zyK>udZ{pVBR^*o8Ud+wN^_6RwtBdO?R~6R{t^%$!u6V8kT<%;BT;^OVTrynzTr8Y( zoJ7t(&SuUU&Rd)pI5RnuIKw%;Ih{ByI1M>9IAuA7IXO6fag1}k=V;@o=P2j6%#p)! zf~}OTkS(1pku8kPlWiy4RyKV$HMZq!f^2N8KUl|D-?F}Btz*5zdXY7o^%(0RR$taV ztX8bXteULytRk#jtaL0BECVdrO^c1RsZa@W48Way5fZQPm$Q;sxR3I6MA7WviVmDOYVT-Pe$lD zszR7=e21Q)D(I=C0Q3}9f#+UHLQhZ?;ICc;Jw}zk@s2L22~~c=^S)3cs(juJ5ugTC zd0#3jgz8b{6{STFJwlbI*?kqL4pklkLTjN~RP7&IA`R7`%B}V+5qgNKeR+;GP&KMt zx9(DbU{twi*bPEesM`BQEDm~rsy&rAo1pus+MW7761s;fr=4CbP$jB%DMj)@6{vEY zPh)|~QRVPtEhlsrRrcA+E1)~5+TrnF2)d0bJNf%I&@EKiE)nX2%1~v~+nfiLqRRSg z8#8nhRaSmNkE!zq zLOH0?4t}r?I)f@LjX8ZN8&zvLy4ayCRIO>LtAR36rEw{DJCuPc^%(Z|P&%sA*0YyD zr%|Q4#M%H#LzQyx*(~T3s+214`#`CvTAkFq3p$A^MN{EZPztIP#G}7J$*5ZSN!JWI zfhzeYyu;9ORLPwVz6Bjam8|*xPUtAAR!HT`K}o1uHn&;_I)W;hM=!deL{v!^yz++< zP$jjyK?aIPm81sq1}F|y;=h*ZL$Rn5d;HcDib0iV!7e!{8dV~$$xhH=R4uhn*M_1{ zCCrq?14W`r@GX=N9YU2r#pC5r1giM`2cJRVs9Lg-aWQldReVzSjzM9lT09cA4hlsT z;o;?U=m4sC5^|nGA*kZs@?|p=j4CeKja*O=syIdm*Fk}(Vt=$k4+=mPTaw%r$RAa# z_R98#QZUIB7L73tI-v=3FJLr#z@sz_%-AQx1Tw$LGGRFQTZp}nXgeftOPK^5s! zDQGvUNMDvfPN*Us#D{jFiga!n+KDRC4MLD3sz?{EKn|!P-A@78ql)x7KePi?q_3YL zJ5-VGA%<*GMY^^X+KwvHEtilDsz{dtLe{7v-Ju3qp^EgH5oC!f(&I0X1*%AIWkB0d zMS5BQ+KMXDP3+JXvXaY9+{X!hM%6hd4+m%rRcF;W1EEn=o%!Cb0})Y`-P|(|eL_`M z-pxnQ2&yujrDUOxsLEJfr~(b6Dqa6I1bskNTAOteG=!>CxwY@0K~$w4UYQCFpz5TK zVgb~TsuT{n3g|tmP7v>}gWjR)_{GuB&|6d;3)&s7may z{{{7+D&cOPH`I-)_?W$^P#3D=%(@Riov4Zx6Rv?eP!&CK-WYm~s>7At$DwvqMWswO zK(A00xubg()P|}wmt7HlV6q z{`4GVjH7c4{M(Z@BjjD$F**HiGRrROOxIt@C^~g=w z9MVKpoviIzXbq}r8QQxb4OBgBo6?5VQB|EE7YC`K3J&^g0I8y?YF9-tq=KpkoQ9c@ zGOF&i7jK1>$Vx76THPEPNB^$!^3oU3YE)H(Ut@w4QB}VAMiHcds=ItE1))`_y4_!Y z4qAz-TNQrOkUXl&;yIHbIaHOpJnM&KQFT+?Ko(kos_WC2CZOf0x>mb33tEP%t4Z&C zAQ@DZ*k6AFNu%n@O5Yhs3RRcBo|J$jQFXDgSq_pwRdKfFHb@**7jpZ0Au&`H>78(e zL{U{p-#-tDpsJu{T_Lm-RrzPX--Luwl^0Zg5fVaGt^tb`B#5eW(8e8*0IG6&pT|M` zs5(<(eH>bXs_fvq8W10#Ii zmxpAp94;dQje%p$8#nfVBX=FQ<{%rSyG|r@iOpf}AVGz02l`iu!8^%u%(0ynqpYM3SMsphW{Dz4b+ zxYH)YW4PegAnCfO^fB^dCHaaSUkbcQ({vPXbq@h{EWF>GjIZ-X@OCU_BpyQW-a5C; z_aK6Ip_}Wka+w&|XZeq_oNGehvn%Dd9x5k-4NZwT#Tq?8jCoa%hnOGOYhunW^Bj8z z>D)9&V<@*6yoVgOdGg$>$4_j$Yv)vUpY5bQybH)a9^vFSZLqbrV44SrGxHq&ZiJ6_ z*0XOGlEP3k*Qyi@D@S+Vfu zEgu<B?u_Zb+OOJ z$0Zkh^>zT%`8aB7V%q-a^p+O|-lUa56z|kCMH+U{!42X)sqe)ry%Dqq1t}OV#;QT1 z;>Y^Fenh@O60Uq2gVdmNPw&4KM21+awAhMmyfJXZ{d4DBat^?{^6H0;bBI9ND)yq& z#U8-leuK`d+81~PUCpqI$8M0EJ?6f9M2W-hf*)e(GO6@o zBp|8w=LBgG1>U61J{0d}W)T7w-alUFPqHFItj~IuMI^k-I z?fe&Pylr1jzuu-tdw9o^ecjV3-GNvsX@AoQRM2(mQN?-UZe0%9Gc*ZB3~- zK}sl$zHV}J;p5FqoexdMA4(1@<4N!T1ybNm+Py~cu3P(t8w>AKYo9oaA$SMoa>zy_ zcpnZk+3bbjJ@jenSc7m3{1`42E}jX2pLAw_d|E^VhXWIabfbH~m#0atZE?+w~^x>{m{*R+>VX6W~*sAne zFkF7-RU|&%&Cu}iw2o?c4RFf4rjC#IjXg~=T;3H6{(^KiSL%Fl`Lu+8i~HUG2T~>>g{{!RxINIn15w)bmnCu_!-^o zGw$63WThsxnvl<1!Unia=5}FEPG;F8J(q-u!J*_h4o;bMZ?1aH$mnX9DL+ikX=ga}CW zKCb?F^zf4qnA_Rk%Je!BaNC8M%-Z*WgwK+pdC1<|MYi79Q&QM?n|PJK_+lXjqjC4j z-X4eQv6r_DGQL+b-lILd&B#6saq>GKGPqxi$ODqxe>i2k;N#tPWl+fn*?YUZsrqZ* zN_@O|X7*O!KDu_nPfq&2QRjoH_Z4g5sekYP|L@IP{=vT)nL!?;s6nI?mVebC&2@rU zHE87Uv`re)|F0e#nn*xukP%ONirhBjiXG>xAAN;lVE&K|Zu|Q~VW59^kxDFb|6i!$ z&+AYxkk%`C`6J60uQ4cP&lx8JyUri5$Jpi5FDQF0nE|c@9(-cbBH%LcJ9e%YjO2FU9 zae`5f^c7mzc)$J83yOwl4{y}R8=U;!4Ie+kB1-_AS5%ds+{4HF!sVa#h6vtGy*U-H z?D6rY6S@6z_ScyOk2jq#l|HJcb+nw9knj$rz?*ai9>rU9sCx+(-g4}x-rhs--ZCP) zF&@EtULd^pE`s;tSjYRPd17F->P4?ksfWVbExk&v9Y=PM>WY6^zwZI*e7irKm-PcP zqBGle61*_`^#tg{`hrn$7>(o5Qm~e3!p3`z%gu7x!5 z@Agwgd{}rJ?`gd90>PV@6Y3v_;5~LuWBe6@_rSGn5oZy+Pt={i3A2a7<#7}7mr{vf zV!Wd9-18prqVCiRT@gQU_hyn^&tvTBJ(D4qN_;2|my_eFh6XO_L}KF|RJ^*MKu>$i zTeD;z0XX^X`k7d2Kx4e3HwZz<+?ZnGeg+fN%Jd z6GqrOcG-*N3m)$|Dt&Z*eC{2a^KbwE54!OGUTB0(bEYrQc5p!Jx^(`2~I+>NS@bCX$ z98H~%BW`jEf$_hG*hmVzNgp2ng?HVY2o~N9u9AgD2;OiU&*q~D-X-B8K7I(^9V7Af z-;o2-tTO5S(K`;pgY7n7`h1Dt>`njotd_li&uGOmIVT^$^AUOP#Sa_rU0fDp8()gU zi^*|mt1~9{UBkv(&O=Mzp`G^dMt#WRoAf0;iZ@4F^HMCl&xlW|*dchY z-*z)73Bh}PMR;yJg16TjnegrvF>ul}ozM-sgRuCCumcT2M6hT~$L%NR1)H>gmf?6viqAE;1>U5)PEfq*`}YZ9;aywHeJ%>Y`@5}hQzC-*+|<2oQwZJ{kBAg} z6^()KC`SiBkq(2GXNu|iL=piL=azT2!o6T=Ocl^i^#yw-^m*?wVJ~m3+fx;JO;iGQ zCdYjadDKH{yoL?h3#<+(hdXt{`}b`w6{-Fxr!-%PKDo$Ofi zgL|o%oOIIND)3+U`~Okx)cLrrWvSP2?%)0&?Y(IFPo)26qNqWn+n&%Gr0*{$gH?m* z_^jnxhD-DwA7AB}g47`2?MC@wNDZ2#e|X9)AqEzL?`8DUN5CrO@F81EBH%G&5wxl6 z1wWLH_n%|-1xXnnfY9IU|9k70J>kD60UssD@gHCF{k2mFW}lmCIPKKBp7v^x57|c= zPJSa37VIW|1h8>HYb;xoO%IQm9Yuo?9x2uEfuZhKGFtd2Na-ZLzZP!1vEUmds(o@EcFLxUnhW3Dmq zp`V8$@>0X$d(JP|WNnFnFL+`*ducDYNw{*pOu!es=ev0u zAMflOc4!Gfe8D$Jg;e^uC%(6!=?H0gE17`;Z_<5yDBit=_aw3KK5m#jKZD?X>Tz<} z2?Xya9k0Vx5WG!1&%~;(kAYKt`NLG%!eRc0ObG&xL{PHq1fy1NFG$@^aDAZY3)(#d zL-(;_&mbROV+oEtD*<W z^@3tEd3E=LK48%e^|e}z*wwpL$>P4!atWA`99JGXHQ>J&yFoHr9>_8HkoK0hUXp#7 z*{3Ax_l zUd^V%7dS<48(qr=GS&`!CJm`UI(xP~nc1SMH#e)xD8DNfc2ii=(Qq^p9`lITjMXLr=e_T{ zxWxK^C_Gbq;f5E8%(moJzJPrP$+w+*j~L&VfTPH90U|!{E^frGK?Unla~65hUJd$A z_EChB-(jilan>mwP_k&H*SGEXLoEBFR=rhH)$r4nYMszM_&Z2ahh#)g$rUa5AvTgq zA9;?}scOHk*hyxkz?*alI*NDTwsBc3yiE<#8)6W=-z10)oI>yxIC{KA8X01LbYvcQ zt{w}Imoc3b5RZh#1edVnS}yx(yjg|-hNjrS76~i9#Au%j^Lf( z6v#xvn_pPj(FVcWR_WF73g%ciDQLgLv7AHj(~-yW zrC%exdp$nh+3k?-m8Hn?7T?J)%Z90#L9W$nuQ{l=;Fq`PsPxg`mKD9Wim)ASa`d6opq^OmXl5au?R6nXSj}|Jjva6sh-1z$?jd5AWRRwiLl$-WpxM zArVrdz2z+qvX3#G{Avnb%6j?|zySLU=+wZ+TfxsgxoLAXtaK;qM+^%--aB742KH?d zUhvg>{3UfhX13~V^-B7UH!}s^q<2?Pyf+KlF2llGRjaPz0fKkQ`K(PR5xhHJ3PMQ; z-g-xZTyoDNtGB0(ELJ*2z;YTN#N*6~KwFaIenERLaO!!IoV&{hcm?@}R7qmv&Ad*+ z{NYmx*qau{lFPzC49Vne^hD^ z5xighQnTMc&FigaDmLewkXi6}(`8fXZ##dV+n|YaFg*xM7~xHy1@ATKb`EA_tv@p0}av& z>U=CpmWa4e_IrrsqQINV@)bmimdc?sBn z9M{@HZ~1c+`~1Im&bBJ6wX}!#O|lPPoctvDpRqTM^ML1-`JU^d@$s%2ajZHZQ4L%C zFnph3h=0B1buM4m@Iu0ZZ;&oi=_A0KRrX2RZ@f7v@Fu+th~jW*~T%rY+id8NoX@7&0q(6$=}~%rP=fQLt02bcwhE5xif2Xw~xEqulQU(#aeY zc#|HxMDZ@Ve|QxZ-pkeak~blEd!M`=osQsrzsB^}6$J11#OKbV=VRdy4;?i33rE4s zdf(*7l#%cMuQ4BfzP=AQik^<;Y48HFVlCbxOxVj?F+{<6-Om!RJUK2=xK%s6?r$b1 zUd`XQd}t5vII<5rocxSUx$hoiC4lU+>6sRu_;|-(-XZQPjBHN)vMhNyL&fCe#FD2> zGOHJUgG8l|wx-)_{qO&--s}{3lU{E{@y@@mzY+^?7N5;kjtJi0k7wkaM)1C%yvC#% z!TUr0n^#9;V&M@*^LuMQM8ZN@AMYZaD!A4)$^LnDALum5RJ7gZ4NR=;pR<=@t-``Jrc<(0rNX5x7-1eyUiv|LaoSc>#{s((+;!AH! zeWv2|7Wor~K9a{4{@GhKDt*X~swmt=uDAGi|NpP?n|6Od`hPx(8bo@(8m&S1oftK+ zYEZSSXI|-t61~KHwX(BF4VtU6iMfufK|bF9`pa-@9Nhe1qCtE2Vfc_-t@RQPBB*7* z*74?PAJ`&P_tbj7CwSU5eD0Mf_6DiNjM1j6`jRjj7pttl=g|-BA@);_tz%EM5axQq zf9pShCE3RqPJX(UeSrl#3E)N`(dXSg{2|uiz~R@1o2%eAm4dgkM)7Zu8k0I>@seL+ z!OtM$C8_gaZF}j}%B0^1q)ODaCeLGXTY{o05- zf;aKN$=QUmI5;oZ(|M=aVK{zFHuDY-a{pg;;X0=KeISd~@3VEE2bd%(Pp~b=ZjeT6 zWHsv7NWxR(xW%5?Kh8*DHOa_$i)eNy?OYXjnx_(kN01nd?YYsEBW+eV*(5v!8vw zzrJ(6>-p>Ly}GaKx$pP+z4u=CUTd$jW6>~jtAN*iWqv2(b70w;z$s6J=h5#U$Jb!< z9)tT+7Zt<+CGLG(jae%fHt#o+m9fL0=#Td|w2t>U`S~o1tTO84MR?CP+jdppckde? zJv$R%_nvXw{{FE&{_8Em2#I*6s0ij~r@sMdCtAmTocx3q zZZNLT&ln1)ul*)%VYY^xgqKrXDKj+TveMM9BU+aWh(q@#lXU>j+vXaZN6D zu6y%R@m^yhoJip<_;S567H`qgJ;pPT_u7Sa0)KeReIdL!33<-AQHrFOXuD< zN(2EPG9H~?0WT-wGU45OvJ<&{@ukc_j2B`kEC2mS9X4;f++BzA7mI-{Xxw}=U!6jI zY~B$Tnv!J#^v8P-S_cUyzZIc%Zw?&fLx8a5^}G~(-aMzQTUFuS+wvS;{g;;byu-h| z;23wh#PGZoXsm;OVc4`w?0@tB|JBU-zxwCG`F|-@57Od#%lW4VN%gLBamjHeVD+F} z`7N8QVGrU{I&XLh_MqmwEt%qQ1*z`&!t|6Y{jDG=bv(t% zFRAn1xg9aQh;@Fk*2-D@9yH{qTqAJ13hduK=y>%h4F{xu*4EYgt1^5KB23X($GqF> zf6gF5-b<)>YreQ&M|s5B={;PB#XD!KbB`5HXHIz0;7D6koWjUiCs)DkZr zMm*TB*t0%35@(OmA8$$>c=;VN8cUEcf;UK!xmzR#@p%icl-^@DSqS42+_2w%20ho_)mb-k;d}42RFqA8$$>c=-tzy+3an&x-_HiYjI4!sor9 zY46pF%35Hb(wx3U8~=cGgPl}wr>zLXzr77~q^%BafsdaHPtWldqT;O{!P!IM{lVbS zS}fkBwfQWkA@9ZB%cCzLsM=`XZxtL52AK3=z+68n!weup6j^OeX z+gY)C(E90^V?PJr5j#$nfn3;wZVB5yh=lJTPf3ps$+?q&`zb%=ZiO)5XRDvx(oaSn zM^~Opu<1f_U)6t8m+?dnsyh7O0@#mOjwMFbVQyl;3ymA?isy2;i`|1t1DD@Fn6!lM z_W#+?I!bWz8#A@F5D(#d4EFd7{kf$t-F#;)Gj{cvaUW@DT&WJi$F{k z4XXnBG2t#D@A2pVbtP_Xw}mtqe?Tgxtq!$_>u=5m%<*1E#e04B!5m8WjyL$ujKzCD z_iDll$os+3HynR>>oRvSUxmEACTa{nxsbrG%IjmN&BDO!{?Go?!(^m7o@FP~hAyPJ zrEXFg@(#9o=OJRgcI|IkV&E7WS3Q69+(|QR-W#nt1BTDjU-!O+)`6GbHtCz{ zMJas9$@)9pKp3C*?USF^szKiOjf)rSB;fNVXk0$#c4Gs>^Cqa#SjRMrS0=nc3NB7W zsCa81x$R2fU8MYo35&N@oaIg>$Xk)6V0jMYeQ09U^D@Z$e1%KrKFGT^e^7+gDGa#T z?Yf;iN=9}hr~T|!>_XzZ*L~Ai?um5mJinT>1Dkie#+2&y)ncFnjSKtX^nI}?Ht$E` zgQJpH=#O_CS_fW!x}(Np*PintHL+^_BOLg=M}O`L^SM<8rjq5CZjHe|oaoI|;-4p5 z!SK9m2(;BPpH;s`aPG&6;)SVruhaN7cRBH&#ff5T+&nDaZRRRPx{$YkJ%`$5$U7k_ zvvwHrb`pEebitMcgaSL>xgH4vpO}~}Ouv(n#Bs92L-8(T)xZs5VS7)+`ln0o^7Yuf zqc2ND=$#S++t9c}#jKrKU$9?q6&3}Zdu>a9^FO5yy!@_j3S=#Wn-j@Td%g&9;`9E3 z@;*8LWwxCU{_8E`_SsJl)~sUqwf72Z+UhX7tz{UT_22xDH^b4z-@`|&1XT~x8((*w z@`(M?y@d;_2iYD`P)djM|K{!L3Hh)G<=kVEjWB~3q;=bC?R6l5<>Dd&tjuA6**;2~ zyOoU0ypI~>Oz1**^gG9)awSDDU z$M8LfaGka~rcbjeeyW%oki@BYZ?5|sMBzOawuBRlx7+RE%f*m4nVIj>b;!GVLS=I) zSx@Bezb4oU9>rA-kpayK+5jCdt@hv&Aa)O zVsvYb7$`>L%t>tpy+zo(U3Y!n6GMl*DRu0}$?sQulfJVAAJRJCq}$U9pSQS`Xz4AR zO3-J-oh2rK&wJF5FnD-@Jj1Ubw;Z9Zj^2brX21U4ASFh{TQ`IA8-@4&o8#U5K~; zhX~2j9!Q`(?_2Jr*u2lM-sE(-EC&40IEPC>>wFY8Z*NXPh3`cA>)w<)ym0ahv|qDE z$e9mOjGaDmcPl>c(Iwtme|VpFY6#x?h=%k38(v9!g{m+-Zvw4#tPPV?_Y zjsry$-V>%ZY*@Uz?tQ9!1$oPQSJvf0-mxi{n55x=RM7Y4q6VD*hb^aDezV6|z00~1@T3}9Y1`AVL8`g+@XD5Q z#^+6A9kmzzQ&iy(q`|efC>3uV4PH?SZ#CiA1z5aI4|Zw|Lf+wH_pp9W{9KooED%|bnZglJa`y(*9dM-EU2?9;lbYj|K(q^ z%r#65q@Z!5(p|sKEXC&iP9lu|2_3$@rPT2TC%+>b6a+4i`H(~DOgHki@p+r4-^|+R zUI}!ovMUuP@Of`AA}qWobC2QI-nE9b)$y!E>D&3p|IYu@#e9#K1nfbwR6WRe=;VG% z56U#&%#YQBJY|BG>B1f~&cUR6BqkhVHL-%Wf`T|4)Pm7(HoRQfKK!h3!J4<8n95uG9fE66)mw8f$r@?Ohr+azSF zsw3xo^zp+TBtST%lim(_Pbx|oylNyP_07XO3AekDpP_6i{$JdY8ybNeKdxi*j^E5; z>qZa<*U`9~{4UvV#l8_L4W+VOaK8@B>1NGR zDP>^kkKlJA zAX??&0(nQ}_Bs|p-q!<@PIyAzKEl(?t9OyWdes@T-H>;vot{DSV=}Td!7@F$vB2~&^YB!1_z=pV|VZ9rMtp1&FGK!Hna{BPJY{` zBd>J{@gW&ZPdCgD$LBrf^mXC_l26ORvaJZ5;_1X}Cxa$#Qccm9{6 z;%&G~U5mo|#r_KdJ-iuQr4i!S)X_gn)wm{x0tjKdSxItR$9Ba2?mI%r# zdCFftB_nK}G8sRwb|Kf_EzsP{d@s0SK9QqdrMOBHjv@SrSQHqMdZff{V8dxCI<2*KMjZ|fV_>*DF^L@ zZ*Suw2&)h6A%U;Y1Uv_(iQvHj!QTTf$cT-_R{^Q?E~HXM&-=Bu2cq3#@IbyDyL+pL zWY#%<6a#C~xW&xL3MQ%8yj9G2`s?ZN?JcDaC7k@ezlh?#sKkdTnK1wU>4DGtra)Lm z4&?3G;5WAEem&-Ezkf!rMU`S>0xFE(y%*D1M{V=EKW}gUJOBTW0Q&s{oc|T5dXUBY z?-wXNh}%(P304n^+>z%y*k7Piv*-nD1?)jFhkqZ|hmY7MqjR#u@+44kAg!Bwj0h6b zxc!T&;RflH!{qkyF2wlci*BN`J7T|B=T*Nxb`O$^*xY(xtvIkj#o+u_Q?e@?MjBe#D3DVY*dlkc72zwo?8p+Nbk>?9s zR4a|mTS>IBa#mg(NTYEtO=UK%ZouZf`FvdYg#r5Gt$@~{i<94t`??Bmy?Bu|8JEr; zuEFQswJAfPI^hPWYTxD1I)uN1R6F+ll_Bd*hUYC8LR%fHzg$!B`}=|PYAW7lA>Yj? zylY79i?Dca2-{J_30IIO@@7TKAny~uTwgBy!~4a9(3}kBJkrT(mNOAex5xe-npC8<{?=Bf(E=`&}_O=UIx}o?idB`2HYt~i^>&NE3r?f=&!E$k6 zg~l~X?O(e<3wwj~)dS&tPA>YJ|LxE^UgG4p_@mor_aOLzbohjtcMd-99l@57wX&sP zUBK4VGtD%7oX9#jwDPnb!_WVO1+>+1gHNdNn)2M@WEBLuR{igE8 zdqv3G=-_Jg639D8qIJs|$h+ZtLEIU*_vTWRUStX1-VUax+bpXmBR#CUPR=~whngMyhCC7yxnq zyIN^nJo8E5NSo@>BaevSx`2`{Qb#tsoW9I`Hz_-F`Foi~}z+yd|iDX&Ao;1?a5r z9*QmkYFf$@Izu$9AYb(jDHUyG_#Q-fPGcRX+XBV@?jR{s@wQHX1^?UM>n&Cr{#=I1 zds6Ct2IL)jBK1QxYB8P8t4=!R8(OYy0?M0{!tWM(e=KZ;xS9 zbl`GcL@iWz>R>lM@4@WI*Ox_$z-VRl{`f-tM=XJqlzimL6UOI#g0?ye-Y9DI{GI=m zsCZi)S{h2>ZEo;L1dI1mHJ#oYkTS!TX^0r;Uj^O>h6nqZ-_wE z=!VhD5;C&bKz(%_Yd2#3t6F(EZE6;(!H>GrwpN6t)kWx2EJu zRbn>%@g7C%z{_uyllFSfAzp-4w%-5QTYTP?Hr!D!-W39~S1be>8h$~luU%);Hd)3W zkRH)khjF0D>8kj-UvE*Q;%%vI^OVASaqW3wEZ%~J!>j8dZz09Wua%HDd6)7DZ^+vy z`)%2*Fua`j!H79WFA>bEIxNmtPDYk|_Aa~5)Qx1BB3+jp+>x_}?Sd8V*u2jl78GqX z5C^enT+fz|Um7=I^Ilu1S$4IO{&=57>%hy8+je?4QJfc%x@XIj`x2k`%UYJ!&mD!J zEA_3B#48%+|6eR257TuSfBvVj4o8b)`_0nk=KnQRytnguMNxQLHM%dw;w_-}-Mba? z{(SZK)Stb#`!T(P+aT{orSh|d(j>6w3AypaXCi30%`2u}Nk%4$yS#>ecOlFN+QyfJ zxFZR%H@-bSfzA8yOQvciJ;)o4>sYfwtNmYi-(yM5*!GP6cppORz{_t|@AK4&Z@h?o z(8II^4fwn#Kk0=W{#^_-crs563E?kJHkRg0%74;h_{E7v1#NY_U(T+=46nENZ~y;) zHHrV<1jG4Xld1>VJ=Wr;^dR;kF-fc*^m}V|kuvN-H(eGyxC48TM&aqP6cbe)w^I*Q z-Yg>l$tLEGyCp=>cqsLe$|W+AqSoYaNUR&NkbT^LW3@Zt-*IWCU=wx^a(F|KEgTmI zhtW72&fRgT&Df9F9sJF?QmypYgY3{cY;f{Bt8=EkyLch;Ff&##S&B;s4}%e@Zowk9 ze89vXKP??Z!~Xw~^MM=lbs4?~5f0N<$NS1V^@$hf9DAY>yc_8r zZ&YSefCEy3#)Z!+*u0NBS!-|kA`aNmxN^grdmrRu^Cl)VulUwSf4l?HIzn;s>*LW0 zG8N`UB1S#L1BCH;zaz41@8T)|k2@|^sCwY<{|m2Mp!Y)~kKuU}*V0x;`#Fik*9mjH z)v0*z_Pjkn;k{kzp%@l#V@(}R8_4^>3YVr^koU{h)CHxGx4{vvJw2QxFp+b4_pVwZ zFf3ep;y^ALnKd0ol!d#I!VQ)@Z#K9iB2nv7->k>x&7HxzW8|YaSc=A3EidqYnu*Pu zcgp+Cno0WO&4Jc|mtVr^p^{$s_IAFcoS7USKJVDn7{z+XySK@#_Hk1^{t41GQziBK zxeU*nAWvf*mopxq=l|8Hc<++CWkcbuaDcQDi}&8JU02*7?^9i$AK!$$y)S6-{CT~# zWdr;1pm`*a8&+{y91y|9E&67ud1U0WcF93Mp>9N_W|?<$jXR?8-Tb`C3^wlvzB>g( zK8XW$G;ZSO{+$<8j$;069Ic(rB=geW2I)Pt4!rzWvg~6OBzO@;m4>pkDf|IRW@cT+ z@iztF%=Y$6?7wJOoQNFm{d)O!4c?-M?*D!01hKztaaq zv3QT0MIAW?d0RDpeo;%sTY!fpm47x8q1#tFFq{%&N{PA zUSvQtfdem+239b`GSM$WVU-Tz1T z?dng0aQojTwWs)IJ?ufvJ+`ymMyfh(;T9Dg z@Q9tEi$=cvGa~TMu8OrwCL^LAdXriz-H7^vjJKz9-H^OM^{O0J>>d=jLHvVfojACP z#+{9fTl;nn%)%{<^* zY7n=(6#pHhiO`iFW>OCrz6Y&XN?RSNsP(+El#vCiMKXL7MG0D2v5gtMPrq z5ad0$GV*pE_`Bm@=Ksq@W{Ne!^v9c0M;1OKYwwB^wkWQ3UpQo<%oZ)#BR?}8TXqj2?!@sY$ z)=}|x+;f19(!EP>R?1-Ue)uuw)i21qckD8_2YDaz;;%Grt^EgqXm*xg&K zW5XM%74*m30j)z6C%>yT{k_Tkyoi1|-?y9V@Od|-xmu?XI3EreL1BQq-uD)<-@*D>KSCjn1#%(E8C6i7S|Wn|EiN)*&DAPi~uNWS=Y_!c^FFw@@9Qcg^KR znrcngz>c8P{X0_e2PDFtFS5=WY7Ebt;7DT~UT+Vd|NHY6YpHnK&nErTy~ED!l)~aI zDf`k#6!IQq7N`f1_cL(qqbl5cv*#PA{2>AN|F66qeppBZG8&G0%d*G__r0by^Q9o~ zH!lOCb=;9l_wTG7@W)A*kU(x-SXv?O^g!!J(utf8%r6LM2_ z-~PM*k0HkYKlA@4svhK4pFT`^#KyKRQNrp$rUFl{2Ei4iZFWgPE`9dD;Hl=7vmZY|;%c#D2sMtga<{ z@<@PRXq?8qg#jv)*pFC^)gs#0Iq9zl4Wf0ZZ)cHOg45S zTe>qAw5)YQ1Y@E<@&;h@9*uN#SD6t90%)A=VtI?a3T)mj(mX6&T=d6#46Wk@PJUXJ zQA#$4c#+RX6bRDJ_`HAGlGEiNZ;?*XZOmjER*(}S-;^$C3&Z9;)AwVMwgCO{rqnToliz(0t3AKRc#)RKfdlco@Oh_l z)ZX@el?y)DA8<&hrs3m6a-w#}Rb|GX|3A@K$JulH4 zRcAg|-G{vQiAB}khrF2+n##)|@9zCiMdq24z}q9qaVD>bfZ5YI=D>M){{M^b!V~J< zi0%v`>{{oBw5MH`>;IRtw@b(LCGy(EK^q#kp||wpVs-5KUtl=N`h+O`@ut+li<6(= zJHM%kQeNa2m$~l`6MWt^Uy^uptMUMg<8}$+I{dXa!O$t=?C~uOzxE~=(^kiX*yEr5 zaB=eA`F{p@1ppth22?%B``VR%enI+%Ad?1G4_cDyaat1gpeF9$xldpZIy_Ppv~Y{6 z&V{oYcO=Lp@M8GORf88{07Tn=cuyiDCn`RT-#70@2HnOpG+Eq`mnA>-#dl&qVq@G% z66^L$fLCbTQ|YVU-u}XV#Fo^2$?oQ+zaDf7t)mzxzjUYbW!cC0kaY6QK3*bz4>~!t zq<}cpo6HW1>7_jdp|WYb+H~xUz31fU3_0-c^J^~e)Q>FG#LpIx?KHX zEByZdgpQfw4_72%vMaxMEjI6q6?v_l77`!{jcYG8{yg;*n|I^um*2VA>5q2`T1Nv; zenTE{`!C++Lkc$+-#&L7pLc4BP@gU29eFP5_p+5VtRP#2I}4g`Fg$Mpt#yeQ zrborwYwN9l=6}m$S*lpPZwxLfG=#jb7GBJI40#{;LXagw-r~nN8&}*Vfso{9Z?zM{ zK$>1npJ@yk*);EX;EYi>@@|}m+i9m8ve@s3^_mWB-n;JzTK?E10hXX~O&xx#A8*HA zL2`Xh(Rs%~f4uF`Iyi9hODkGl;ugY($T1lim>An&}b z$f1XjHjZDi+Cf;H5 z-g&b_R#Qy^AZVO{MTyWVU2NW=zboC=FQh--yU{v=aPnh6vp{nFLq24mRax5^FMQs2 zmb6T`Z_NeBdarxZd+~XX220fF+)8G6-W(yc)iJqPGh$Qh9B*AJ-tHrdBq)oMk9YNy zv3P&r?*Sf=_k8kf!6V4K*r|BQN;v=TQJ=ip97zIl!}ojTwZp)Uk$9c<(`01V>D95E zdfiC<0z#_!VK-!+a>uu=-?4dj-P-)CNk#%t;!2U^#o~t8yq7G}ys=S;{&;^t>kz`p zZPNZwYNAA=UNk8GmuoPGcPl?;J^m z$6NlJ{~2TcH=*i5{u!-ee|nH~?<$uk3-%DOdQeF#zk73Ufll|gjP#eV2U*rLeUpVf zX#TTJ$CJgPfUDWmlJ14!VCBpHk;G7V|G(;{XePUEB&owH@6+ZP7phYwKp`5ZCE4_a=|1-SU!K@DX2(o_yyMY2 z%5d@viTdqU?aPO}VTti@Ifc)ArTW0@r3RNk%Jh%)qLVbt|4jR=J{lA;JZ}OUjdif< zA4KPWBP!m$2D|_Hg0yJKMJ+7edWHfeUm$P8pTw*NH6Be zTz&?5>rPFF?t{F+0!yJ~Y*9c+?eiEi5e5t!BQXOL_;dx2R{t( zQFs%q)itqrYc|c}5`et>;>2>FLf$Kl1FgFaRdq&psEXd1CV>X|&Y|XyVL+-oDMm9A zUT>+mT_R>X{QiGtSc-Rr8*=aYuf4r7*t~h$m$20ylK^#S+!pOKfkJDsc{9})cGL;d zU-#xm>zId=pFjW0<+bbhkfTLg7s-U<^X7}}urid$0dIuAe|wvQKmQZYT;h3_ti|w) z6XGe_>PVX)HV_H+9ejHS(`QuwfjGk)>Rvy1^c^^yZ7|xMc;Epf(#StZB}FR<_|16v+%wI2t(sm9ZM?rv&QC4 z<`VGpdQX46h0r<%aq?T(^GWSDCm#}4l~Sch!hghujBKw78OQ>ke#c$-xB>qWYxnW? znyL*#48MYG`b=9L*+>;tnAUTMN?sbc=;iSK2Am=4aSuoJ9Q)EzyOoD+pfqZ@t%)PBG|lp z!`D771QH+*jZa`4^!1Fezxye(eM ze$R!x^%iUv(BZ&;drRopUd21KoZ)#BI%%wQn%oqksW7^87Knw1VBqu9LPjbuDf{zZShi_tn>?WLTOYS}=Llq1(gXu`Y~@t;N6(N^tmuGx&wo5nhZIxF+i zW9GW|Rw~|yo5dDWcq^}nnTN%@qwK+>TF5(3${?);^0rZFer^bP8$K5(F_w)2pOF2hNstbYw;Vw0*o%|j7u~FyNoIZoBri(c|G(IK(+g`@c!c{gE^le~FBkWi z=QI4;yU~xfI@;nzF8zx8@BaUP+8aIp0S-vkR6U4z=G#L`4~m;L<-+Pg^NuylUk-cF zQ%j9Y9k2(e5W zNu&Z*&0q9-k*AOHQY+VKyu_)u2)CM$Q`fX{9=!8gmi?@ z)jiM^5gpa4lf8+}J1HsS#EE7Juo8`%|4{ECn;EM_XV^L5>9?BS3TL? z3we>n5-P$<=I#+N^rqy>8t|r#`7n`K&9l&V9hy^*uK4m_qla)aMdlJsKCPlm6n{O8wO{yYCq&x1dj8=U`lQ}rNHgmVI=2MOtK=Ev$mGJ5{)_j?L- zm?qdtKfoTeN^yzDS=fVY+>PEo_lg2T_8r|$(qZ7vr^BQ?A2Oo2HZ+svF#L(#d&U;P z#ued|8ei6Q1G@(`-&#M!F<%laK;vRcpN>ZC$L>MZ`VTK(IZ1y#=qXx98BTt_JR6Rm zjpIX*+|8U~>G(Zp(oSJ4@IoY5yV6RZ`6dkqq^A#!)>vvVeh-?Wv5v`y^OXPYAnl^! z9l7;gAcgl^Wgb2(-iOoIMYKWQ{&wWTZpi!S{MeBXFyN%T z$6xpm8BsZxc*W4a8#!2)Sn(|16*;i!ip%n?*sr%#HraOx{Ez@1Xk5eTdz{l`Y~DTt zp5Ftb>5sP>r4F3@I5(#69X91dMna3EyJ?vJGnf`_Q0$BY!JQKQlNvN!vBQ+LKfRdo zf8K&HlSxw@A(J1TvS!V#Aa_#nKCwc0?t05VUvKp=yZGTYGBtizvTtWNc{1=+Grsr1D+$$W?W0 z-kcwk&CYz50Oe@hSVs`MLNhk++Qq~hkLj>`b5rWT$#0t~@uPw;KcX8OEVm#Tzk4r^ zIGOY#ArV+CzIfWR0-yIp_zwMvjT;z#K(Y&_t&YtvMrA^x<_<{jpyD0=^|Aq_d)KQK z@?i1Kl+J4S33=-)r(NxYy!8mCyvdOFz_m7q_I*)cr`qxbkCno}l@^mbckm&mg{QNPY2Y2^-}_J^IT5tWTW|9%r{Qp-G_j|s_y5857Gkv3F>dcu zWso!1y=|y?htb_S5-_eKHF z{@4{s>S4f2>5|9_p|z;Zp8J;@)f})u1LW}_2A}>*u2@xI7NQ-Nq~GbZpZx! z<>A}dyiK(guUn?kA8$^yjx9L(Ih(XvYhK|)E{<)O&Y^*K=)S7QE6yZ?;Om};RE_X? z2i1N2@Z?@1!>_%G_i3wRyg7f=ApXDe{|qqw&z=8wpz1-V4jcb-1_`NBTY}Yt*6=9a z^oEaE(&G540oa2Uk>Vx|;U{*}wwi32;suOQ`3X{#gLT6Z(+ z-y5X&Q1Om6kq)9fVr^#G7Gv?Q&YgZ43V9cv%B<>#ysZmBLOkR>WByU`vtksm;flTx z|CtD!9^V*z4|zYU<~ZyKdAsMNJSbb@hNML~l5+tE<=PmsdS#q#> zFX(;nE}579KC#=1)-fL^zt(fQ7p^z+BU?B7c6eXJACSU@HLSuX?LdrZjh=P`4I89Z z7eY$(`52xzVLOd=OuyQD;qUPldn(>Bg6a+w-bXTCF2dsdHsMz98OS^3sAP2?1(K?)Q@++RnC5UkIBU<7C^S5Q-^EQ?7 zKt8h{0>Zl=m)lF?&;R14iBVewPBJ|2>sx87!-;>#waeji^S>Px@8}NO84B;o3#o!w zybnwMn#qQ|XH=I~_d?!A8G{qs;M-e^fGVpY?L(XR_Y8Ya{{BKFl&{ju< zCRe9s+T8qaOT{~?D(j#9|F;?k1+aK8Of6I|gS@A>Mk;!!cnAIX*i-{~_lm>?^+Dc4 zen&D*A@4|a`PJ!=_rkBG!F}-b*2*lcryRZ5dvDr0V)4Ky-}i%~i}%9KiFs?^%H?L`^A?rWV9H5|1SV_Lx94%-^FH(G-l7Lh zs~CR%Py0w)9gms4_WQ>DH~;@zr=Xj^gZuycsCrOB*y?}w|4SM-tib9)F9jnkm%ttr ze?Fv=413VsGRq5>;0p4j(&LKuog`2iIIy&HFA-GSRxQ2Ck>~}M;AF=K}PphRx=-q+7Z>Xl@1R zOvU@``Zbp*D@aqp-^;LgubUJoUj=#V-(OSp3GzP562W~0@)o=++B6$Z0vCh_dP|NH zfx>nt5nagp9(i5UGsxTB^s)M*E?30aP9%Jt7dG#G8t)oO-IBl#jT3$|+ME=C&3k9G zt99mb`s3|_)?tH_-_9%P`B!`RkelUkMFBKiZ!y{%xTPj`J<<^R$Z=aP{v(#y8!GdR zw}jz&6Z>eZWA|ET{wIIG|97I|eTHjQ4TX2R-y;z$-o}^TuxLZx``*5){s?&oESqdm zgS-hG=KL4RNkFA?Lhar;BG|3ZRw)8`JJ>93V2AU+y2poQ{C%#7VzbJgk%QR0E4cTo z$ahGBRcIXB`2f9Je%QPn9OEs1iqjwOYP1eJocw;@-R1XGksp~-{-LiDkH3OE*0;oN zcbqFy-k0?``3C+0=_C6j3y$P0Wcc}?!-cjwbaIDciyP(!q`g$U@EndG8B( z&)@17dTrblncc9~Q8X5t_wooP*DdXm;0GGlW-wo7Pb4;PW)+sQ8>{G#_e!)50#1Gl zjw@Ps5&4n)p|4TK3HZDhZYK1}M7SckTV9ok((>yqXV$l@c3H^q-J1|YV;yd~E70Hn zbEM*ZI`8ur3h!~mWhoZ#x*t2v*+br&U3OIuLf!+CoCX}QdnccNywRE|3aHe5Exz7B z1O^MoV;(`?Tw&55q9N}CwEs%f5YaT z^rTesARYex-)ppvvpD(f4w1C~u#q3}?U6eMXxMwp(^0!t&838xR6p8GXvE+DC)n#g zw>8aTc;3WawAG;;;_SJrS}d7ro}r3W>niAiGhpz4N$s&yX< zbR5rv+)>zrmN(D3U4}hKFU>-2L4PC&GkaD1ivVGrskyrA<4_8<-G-6{kP zH>C01$`)f0>>iZmQ{SiySCDmRoYRwMdx$#6G57z!U%42)x1avbAYDT1z{~H@<#reC zMSRGDkw@nWX!r%Gwe#m`7DWdEvu`UpQ*Y96#m>Z*%nHxl4BvwYHw%mtq8F@Fvnj^xOofVt6($3kU)4h_w9E}V4ZTrAa z2AemB;DWaz+5As%0 z?=KpGyk)-jasBy$w0Ne|d`Fl_;O_jkCugLI;8fcRw)t@W|4>`5ZwPre^ZfW+ROE_m z@BcMsDTF;BP3%=Zd~s9~Y(?X$T34s}Zo*zcdhUq^cRA^AK$=AB@W9DWC3;oQAx%C+ zG+g+=;r|8iC939322wPvAgB5se6zj9@Vp6EdT6TSM|!@e^xxnAbD`p$^vXJh!u#u% zgq2v``#L*c={V$lE-$C-GvqB4`KZ1X^43?94?ekw1e8p(mJO^Ug28L)N2LC|-rD!N zj0^G>avyZObKey?{rtqoLM?3GUYkAi4$n%0C^T+e+HXYJ9-Fr$ue;wTN&4e`0IdTr zzmPKFwN*>`k$K$5{7Z1d27#l-F~M=0{hyk z6=t^*!D^mbVFdCHTG^%E2{$Kzdj73_tZs|Lk9rdU2n8z{50BP~a{6y*Gl1 zQcC_6CC2aGTWPCfZR6|9{!#zU|CGfkUH>PX|GlYtP==$Y9i<2LJ1>{R>Or!8#jiZ! zBX*}W+nI6LgEVeUZ}_u8DnBg#d+%%{$oAf@98nMo8ltB^Zh`|+koM#5_<(LC?CG=T z&PlFFw~6tcQ~&b&f8x@M2fJ@df(|rJ*wXgPtR8j`l9H=?KATB@1Cj(<2VQ>L7Sw%i zy1qDm>xNK+oq$m)72dVy`tcv9i#_vIHhiR)rcj>vvpBguGkab>7v)x*`(WY|;+*V;`~OVrTZ0zAFiqqj5%OmR)C2!se~) zv2OhHb^7DYjn<)plV3xU-2v?$UPS&t(5H^w_`GktJu+3*=LfpBU8rF0py7(0wH&kg zeg6-xw^&DG9kDI9#Q&}!y{LGnPPMJ4@V5I|BZI|z{N|ptILO<%J0$rVH~ zNfIQWalS$ihbJFk^Oke0d~yF4{qZ(L>sXDG-c_Q-;lHxY~CgN1l{(&pg-Op(K?oVy*15hFNMY1$N9QY3FIyJX~CtjKZ}!+WiS7HoLEb85gbL{*c z3NlFU4yPdRyK?iJ1R?L?#+AN$ui*KA&ZfJp`>}Z^p8iEBgS>^&I78_NCyP_Cd2ba_ zNLt-af4tA5b>QWf&zv7>Y{ZAyb5HT?b;0L-;)?Uyb&&TD`46RQEb-Ug1mpPok4`o* zJa59fINIuvVM~(v@BTl!9{c}E4$l96R6Quim{d%8#C}QQRKn^(#2LL*LD+-#5dy=1 z!5(Dof66Bz9uhpY9QXq)ta}g{xvV6 zxiYhDk0pK&@~=*aAr+c{r)$3+ZK`8Ve!>=F-nzYrCY~t89bZKt>_od=} zS*+-v52OPfKCHpwZNnBkDFu1^i;YG6guKUo&Oh=7@(xTr9pCRr0#26wLCiIwz=5ew zE(-Ey&0aGo03Wf^ihH^SWnGb1Qr63^C1dkGdg^4XsjMVuLE~&e`m&Wh*q_*iugSMa z9H2km$Iv>$aPnL2^j7Gc2p=->s=Tkz3ZM6)Ons{|O%E_^Z`GDzj?bHIK%-svBOAjX zkQVHst&SpoUq|6{bG#2x@y`BKoI>f|ca5(pVDVlpcGp@H@}4O4i~Iq3zsnb3A;1+R zL3!FH*#v&QHMCDTq&O7FB#qvRfxN8<7dUw#@5uaprQ^KPq~$^9%L z2|Um^Y3u15J`b^ZYkrN0<)p*z{Ti)911G-|Zs!&TIPoEQ@Wbsb(Fn(p8NND3m+=pS>x(v6yB~&(&VvtOXN6O8$#Xz z%ZgGbA#dNWwdQh=x3JDe6_N@G6e&sbtjh@nkMstnPeR_J;_L4I>E3sXx>_RTU6HIS zCKbmLv3Z}|HmY$|MG~Z=aWeOd`h(wK^A2j2aM?Odf89FZXOez|8tx|PP^=EO>2 z!=?84ysfj|t}}Y+0+zke(37ghzuscav9tG!su=%zi=?Bp)iHYViQhHl^M8Jv_#hSU z%xG6`3UAgk2CK1nZyh-9y&LkL@i9I%0eK%Y58dbid2=WV%r5h5NQc9fET1a>vDdVM*_PmPi!_eCIYoAmc7?u4|;LX*|8bU|J98;w`PT1 zkySs&rOy(vAF-=8+ud2FB?(reaj(;5&is6f{fJeUKNO)68MF>focv6s0_r$p zc@ewOyj7=k@E@^+Bf?WsN#0;|gN~}zM;dyN)-98j8RWe_%1D!#O#+pRul-2ZAcF5- z#llPeJYtbkJL(|sk1U&)NzQjg+$<{dKG|UN9|4 zL4Ul5(K`BY^1HTLMMSBY7kR`*a@=8n&$~xHk$gREKe$;J`TR2%KJO$`)|dHlObkE& zmu#c0j=ioLkMC#9&HqQJcwhbYO_0KSD^KwFq$3N~*gBu!g^4tZZg>rlqYFT6GVaTqTj(vkS(_^2U1@5ejL3~V#^gH@ec z9O2b89FV@;;>2&s__wzbuFzPA@y~0Le~-5ursADjB{h%2d!oZ%1&g=;`vcdim)J0AF`JX_N_CNpQG{bjqLNsl4_#A(G-1@>?_x7jaeI;VU zKfm5mS+qeJi+3Xbj21JT|4oj2giS%-epX9#6CrQMXQ?XR;N?WpCa*mj8$$u%gL7{o zsd@#`u;K>;wGr7NZgLkTTA|pjD@`k5D?|(V!MgY`_ataD+$pF48Qi~|3Ow2a|<5W$$nI;=J@EBswS z22t@Y=7_sVSwU84H>|_ry~}yLDgg3s)Ezv^40)froydkj-nX{BHsp>a0S`0B?CnuR z;C=S!8BNH$U6$k%19^WG@wroz>4NNNCs}Z(WAip@F5))XBnft*apo-Z?gVmS4@eV9 zec`d~^!JE0K8fj=M-lT){; zj9g=Q-ozBz>Uh1nB7r!$Xh{b(epwT=#Xx1e=2;pA7a z|1{HtAU~4D!|yh$h|hbMNatk1ufsszt=!&eGd^#E)!0i*8-9l8O|YS{j#YzP$$yWx z9Hru&?=QN8!uzA0nkE)+ZUd)+e8_wBC^?h>c^iD2Q2WE1=+PFSTTBAFz8&lL*b)J! zkgR<+#d_@T`i49C5Kwf;AY(l~?^S0qKKZ75gRe45ANEM#&;MQ0Ri| z3wzL==jHp@VGkNELiz^uRdwn`kwl3w61eg+@U=GF|GzpZKQkZppxUR>J9^hbK;cx}`P|1X(^rgx_KQ^iq7@7Ufm-xjfid}*%ZFS^?+zv6y{WBn)AyDxyYiYbf;r-PAJ2Mt6S?yb4lZRMe&u#*C#SyhA$nhb?)V?}-aMSD z_U->STgHtdA(=wv5G7e;9x53^L`gQ8q9S8bnTlwjGK5MQk_u(WQi{w|N|F?jid2$l z_+DFkeV+Ztv+lK@<9i(6-`>yf{;S@%^FBJ?9k0&oI#;_YW&&xD0{eYWM4A;6o( zHUr#_`Jx}>xzu$jz}qp}&Ych$i%jVrZxcTpjoh4xpKJkmPpF)?fdSqYZ`}fk!Jcrq zcYm3QTXb&U!~R%LII;6pwWtp^-h52Q-qe7}$#HVrn+)N^&ezy@Cq~*j$kE{C zL~hgvPJT;DWfU1A_~GI9_6j*kDyp}r*w<+5NaWs=8kYPt{JFP!ze)Z2O!}XD*9=hS zBPd3-DG_{o```2bwA}cUa|1I-c8VHQqioTP)}TZkD{ibBR3YMewfa@De&eeZro5mA zsW8u;?F2PwxB$`NNQ*@pM#QX-Y8*l$^Q?E(gZ^J#A&KDzSc6Qz-&KBKHTX1)bI=!q ze>fm*)Su-v@=OLPB**oP96c=i4;Q36Ebr-txYFJoBt5bZy!_S}%eP2cfHz1K7M0I& z;@6@8AnD!Ii}p{zW+}Pq|S$r!pXw73ol5euuh+CuH?(pP8$j_kf*U|yr z!U;o{z5%?=JANN-lOn>JPu||oRL5RoKYePew@JSYvW6TNe#Ini0>R!vGO4oJ&$)~C z@J=H8z{^kmMsBu58b2(&Z`tp5ZhX9JHt4e@S9-vg15Fiq*{GO7CjaPq&c284@n#67 z(nrLKEq}itmBLDacjeO~2EGJ%a|9c1w1@N9O*thj%&I2VQTj?)5ua63@>v&bkiO-QTMO{k_S~C#0^n^Udi64U91-S$ zV4mOau<<@pXW%^hQ3l~7$907edtLTm;~lossquO^?cp6o_JNn*tfiEgo{j*lrQ&te ze-S?3de53REk0roPhOlq@^T9Q<3v7Zi>~g0ndu&Hg;Uh|IH)#}W)?+S-b!Jn!21sI z*?;EVn~xu1$HM!|Yt?ms0N!DT^mcGk;5|Ir5YG+H-X5OVZZin*7C8CYMG@eAS?P?z zWq|jn+>y=GzMk+Vwm;{Tb+G&Y^OAjB10FJnH91bblJi4cHFp0W^+l}z)_dAp-a13} zftTODdcX3>mHhu>ykFlmT_fCsKRNmT8{W0oIRAtn`?vq6gYKV!0n{LFiW>Al=%q0_ z#QJ-$7r?4PU(<>&6G06kwmezB2-KiurMs6qfFX8==1J{V?l?pwwH&V3jzq#7bM}$$ zAnmVbc=8N1NQ!@q1oszv!W%E_Xq2zSu0aMS4u*HY2~sO^+(cDsu)-Sb1_?4O`#e)Z zdo^ec*#};J8Uj+uv6+0ZtmB0Tb3eHB@!0v&p~qfr?2P=VHu_RCgI|LlKr>&J6@%!0 zh#g!?oeyKRI(TZ~id_m91>SXEbO|WlJ`9WbvGBf7(;RRR;Jq4wWd#7NPHlTL5V*1aHL;hof~ zp_TyfW(jsv<_CE5j6^~Z=>He1>z)}Jj74U>ANaF&L?ZdQOZRmGyq)_t8fO8#m&ZA9 zi4JO+_D6 zqL3RKTD+$K-rYG}%|w9r8Qraie7Zg1uBLM(9lx=w_xJr(%jLl3#2#|o`0?Y}(g(5e zUY5610N%uk zaj|az?*bQNkT?0^ohz{dQ*vv5~$w)?*HR;aWwFA(EsyO z)S$-#*EP`^WO7Mc7^?>TN{GC$2-F~zQ;uxHpa#9}E9T|{4U$@K>Cg4Hafr()ljYO= z5y*F!?_1bG4cb}X=QRn|AoFHgTaIQD;l<$@$!rqXZ;Np)^n$aOhK6en zVB@{BF8gh5u?&L71uxZNW3vm#e8$0Y>4C4zQnZJ+6WNCqPJWLsN3JjE;DcRPq={{w z#>bnbCv;+Vr9YzVBcWcVg1>{rFk+$pwQP+3@qSC456J5e>wMY51}T98??*R(t@uy% zKHVvZg*VHh-SBFFcLR$BpAf)XTi(}YDZqPF1hFg8h(k)%kCg^pj6g2uMXe@%Ank#q z>_%6B_o?MxQIF?{@CMy0B`vMkc$XXOE<08(gXojvjQ#ZvT{XtWJGWN1rC13FIuH94h!flHO0`-)3#hbQZ{k3$OEg{E@mB9N*)zMByMZ)5Im>6HNQkz#Le^I|vOfU)sLbX}4I^k@(7P_mCYocuDZC%=k}@xhjx52_`9!^hiqJz@3OMi0bD zeH&{Q7Zufe;}fpD*lD_NkQkh)^Kl_^^!?71h3d^ifp@)m;9(T+_ow_8Vc~s2Q>=9> zX>!7DDzcaY@BQlcE#?-2Z<}j=OK#{LbGRd+r^WvQsU&l=hal`pG`<@{3)1;8p7$ept;palZ3^ zu=i$D#HHgYieJ5D(uD`IQ$p!}a>9O%Iv*QuZOIQi`|tgKbo8d_UqSybL{Wp&*vC-}M~JAHg4DB@7SpSF5c>3bmn&7qh6?AXR5F;2^rv zeGOvpqSA*uA@=Y4e<^|#c(?YJDx!FoPtA&9;l1SGD$!1W_la!2aZ!Nxj+^$9Y(^UT zURHBH-w($j*CzLmGkb+295pN@;sEb6w;DSe0p7&iSVuQmJjC7vGIPnSTXTF zn+$T39Cz7CA5JpE9%2L3TW$<{(;nV^WFLVz`EgeIJ~}7Q2Y+jeFH`)0kM|TI^Jh}I z5M1^?d?@4-6&s{cKQG?nn52KaQ>gRt@#+KOh4TwD$i)m6v^Qm@0Pkew(Dy#!afr&|%J-YY!V!Ie9jhRKxA|{g_X&Xa!`3cq zIW;2eyjCL0p8b68RBn{2CwuZ{<`l$_x=C4CUri1dL_HEV9E=a3+nx_xQ5aGH%F*mx%lPnrq{$shr6b zAU$IsCwU-(_VA7&`@qZZ#BDwK0yRE3x##*`KPswsYfMvBri4DySLe1#hmVR4QqINk zQ1dRj$D4slA9}~?)`w>F8qw;#&Chcw7T%ndifv4w|Nnknjgf@+Zv9Jb zOkjDd^a;~Yp<5iH$Fw^^y+0fwzEew|1bDM-*gn4m;N9q$dY|PE5jN%zUU72^_VSjB zos5gaWf{bX9Cwdl_3-O%?CQO^Kkr7c5bZ5*$&q~s;^ddc>#*9Vo(~>`P4ByW#IN3i z0v#6IsoRmK?pK#gSmEEjeLz^&@%G>rx}TiLucyw3P4d~N_rc`k-~E4@?)?8I2l{_e ziW>BUX`3EegChN9WUy+G*4jtMe83Q!J2P=d64W5|>87u_p#SeX)#y2u6Ne-#)^01` z5{?8Y@K{HI8Kl?kI~KBF25GxA|5Q__C#-(DeA7=}>>>7cO|op}s5GKRjx%jgJ!X9z zyZ=XY?A`n}(B2SxgY2UoCqK<6`*z=#;DZSqyi5I?@N3XaYJkK~?;Y^`-r$wT&r;F< z-|1C%SpAv)m)NVR^fB#_s`>YTv-EAFNDBi2fCZ(|O-nfBFD+1tst1q)of`s?= zf}TQvw_VijUo2U1h|yRdvzB!@BC4YnKm>UI8Qj@s1@LZS%z3s3eBSbiB=hixbJ%z{ zC+3Tcj7uZYTtIITihXz&f{>`DnTyVj1>R=ffz@e2xF5g&E{h3cS1W&i|)D>f3T( z5)1Di$)Cqh0K5beow39^4d;^laSy&I;hYL$G6C zD8O59=w!uHZX(>yk$8816gJ-Mdu|d3CZ&-Ua@_1$d-&Q{?CSl4>(7TuE84@GiR|Mi zPJZ{=9(~Eb!Uw-Nv*uS&KR(_uzg2&Ri)q8+$M&&Z7RB%XAEuUT%oD%UJ>Daysq;~J z`ch&`>_Y!9Oo4Z2(B?3-dgm~mkif!wAm`52EP!|CsTEz~qz0+PenkPmyJK&65X)(> zIkB?lYoS#*!u(?Nt|7pC(si{(0>JyE&wJh-tVG!I)0|4LA2!}!o*W%G{X-ftBgcJ= zvK@9F!Nyx#H6Vq}iT3cGB>Py4li!J+mOI)A0XCYKsA?F%$Gi9(VbtKg7TmGUWJ2~i zeuEVKiYLW$^$gwP9otxG8I?pSBJ@a=8V;ly4Z=jB*<2fmSaF9CSV z9Pxd=4B-9te7jvbz+1;CdT-2$IK*t8>0GQuI5L*^>?!Gai*G`S9v1-Kaw$;$;WQbm3(m8 z_0UMeA$+{89>3c@tiKlFeo)#ZF^zxrcJ|QoS}$Yz@BhW)sPo}@`k+-)%)k9V9d!Q- z_x~j*YEVD(dJA-jEoqccz^XyPb{eWnKn*%zR&iVw)Sx84*7+X>8u}Nt*p5sM$02Da z1s}{D3`ZW0u39_;YLIxF&1DC021zcyZGWmT5r*HfjOk=y*Pv6%0gvVzr4cl4(xPZz z7y-LM`Z(br-!4vjH7JSf;}cGP86V&9+4%6mAI}QBI^Td_gO(M=76|XMM%up)F5Pel z|A<}Y^^@X-ZF}i{h~?^`&WCzkS=I;e4N|bYwVVR)zDEg8DBcnK-^pX)ZRaH`BMkVdMSP`L<4Yi!?Gvj$^-nJE*A_dx(9tvcQc+n)dLXB>Q-SlV5QB{iIK8 z3Glr>+q1vw@$t4}jC#M-&KlAFeMaFHHT{23p4#4%VRVl-Lj!d_PH_Y($CNDe|Kb#Q zKRcNT)ZeeS_Ilou!@|2VqhRS;fOjA=kRb!`)*;5%l# zJidFc0p2fkShq(2y!RB}9De@J6TW&xWZ#Mn*mx)K>oR0@N+Vauajh#l4{WKz##^ki z{u1j-+Qa)8*@py9eglIlqtUzg;IkY`((?#D-cAAU&u;5Cg$-7%ak;ewzyF__4vAh) z_(J!1=dU?Pm5)zL2KkQvy&%1e0`I4u+3dGtUA_;X93=mCi(-mm*Wu4KYii+w&95Nl~Qlg`!?lo`?<-oK9h^)Zc; z-$^Im2DL{7SYlU8{+37hct4QX_ua&I2W-F+f4gb|zyBA};mJ65YMAc#-tIY5=VR^f zH_k}Zzx_YG^#3a;YS61s^7?2Enmo^^hE;nhvipcKe5xn@HMyf zx-^2u39j%OVOxt`gAO0R(Q}7^_G(Zw*+(o+ezsi~DonN$;JPerzsQUDHOOqa5v$;( zb;#3~QQAve>v3<8GT1FL?rKpBQR7fL?>$8lyYHw3SK#CAneCOc zuEYqjUHkIT?r|y(C$8;JKhf1k_jofDQ0YUh{+-<4!-Q7Sc#p3P zl>DVbghLPR-C8n$jrWTs(&uKIq>(Uk+`HXQ<2IJqdv6K~r+K0zXb~ll7-Fjzv+1dU8uY>6}xQ%I;2 z3wR)%9Jl<>`p)J1uxn7oe8>fTXWFYlNn{_DIQg9sN`LlcJ1@-g)=kjtD1Hsff4;Kd zT!tSa{eW#ZUn>3#vU7I5SOyFI*Pug2)cIKEx@PN}+=UtBN(#J3ZqyW@cyIOX(!|2s zbk~!j!vOEb^Z*l8fcL8q!r^-W@0sn!M&BCa5GZMt(F^l%Bw;Mz=4*g=edN$PIe_=e z2fz1+xPs#?!e10ey0P)zcsw)xIk+H=#`UduJE-G;jknN^8xkeEXb*2QvJVlQ{A!2o zKCkHKg+IiWn7>NE$Ghjo^wxk2en@{#p?P~0{t`PwLWskLf;svhVpjxH=VP+kmwl%o z>3EAg1>VCE#o;L4_a0|!VBvjxub9{=fcMi5m(3~w@BXuz=}W=tt=QUELYB|t5ZU7! z)5nd&kuOk5-V!i_6n6Z^akfgVztzHGV zu@^+>6j;+QVCe>|+s5ezQlEhAm|IV3vk$e;Cv7 z@vfVRR@@okgVgfhC@WQ`qI!#6xCGBw(|`3|O{I@LrfDm7FH~XGzqfH$-7IyWT>yd`d_=1%~;g9$$E5dd%PE3Ev10Pj^pM|)QTyk(ypb+NeX z3G188?&7vVW)Y2+O_ zPMDSNB||E94N?!-Htcm}F+yv9mIVdzJ^bELl>a8Hitltf8HMlz*>4 zqP&gI-<`v+L2nZL0}QIi=)MNM`AD4)o5R`T_fIVJ|0)!Czb{zRg$}Wvye&FdcxSv^ zZ>tLM&J6Tkq6zTcvUA^~g8*-p6-8RQ5^;#ZrZqAB+~LT6x$ODP0B@TI{)-g>-W}-) zcMZVjEwgimGGjht53$$B#@K9kNF!+6#}zKziC)-vH?2^X2`HpJyswdcG~?u#%2U%4 z!pRE@85ONfrULJ(4w0lLHd*ASx|MR*B`S81w5+RkMbQ897Q@_T>U_9$3n>2GK~ko` zdpuOu1;zWP=J~Z)c%PSaeGUV>Pc~eW&;WRs>ssi#0lWwLh5NRE&s#_-Z80{J2uJQg zlBV_m?_K-C(!>GYU7ixiCk7(y+Fp|rl!RTq&&JH`UcW~g*+GsAGBPoDpU1}gW!ei3 zuX5VMJC*EX5GOz0Hbvp!a2_~}(Kz|nKK$zKH5bH8Ow&LPnRN8pGf}aF6n9|Hi>dzw z&s(ge&PPMen*qVUtG7xNc)#1c&KAX6I>ToT7T!nlj9je&-u#Sg3hDrFuk}KYR|C9{ z^{qC0=^uy8&4f2HX#>11Ipa41yo<75NXh}ce-ny|*8cQ_RUW8C=tN`V{YG%LdiMco zM3o%(zGKJ!qEFa(YY`X?Rz09Sya&lXv~lwL)>>RS!c2fm7j-eSgy7>nI6HE0`nxC6 z7uC}r=!TE?a)zsn#_FHxetBykC7&uEogL{;$%hs$Cn{3lJ+{ce8^znVX0oHouzq!3aU7B#oFMRFb2zf7ZjK`o;9V#@+usE?Cu&dn zm@kbb!i3>E4-rZ1_y0B~22RNQmPYui_wFIj~{XAlLi@N7@F8^-Gp%HLe9Uh%fur zIvCWT6+7CCHpIpvQvshp?&=Cdx-#_I+(8Yh+Hvlj2pD49gF@SU`H1j^-T+atI_x1f z)~@o%X)|dglN={nJsc}4k6nYdFt5EhnoN5`Yz*0l9Zr6>hfYUH1QXy|_-i_^IerbQ z`B?1vHEj*N_)#&3%0v7b#J~&fso%Mo?uS?gK~}1KT#kOda#6uT|F1!T_teFJg#*$g zyakR(v0~w!_W5}2OMv%;!Oz|`0B?zv-{k4m^zwt{De7NC9qkK!wnyAHH&#jFyt=X<6XP= z2UR`_F)Ar<@oz83q~3hL+{Z-!_peFQ5+X6#wmAYDa)_oPMl!q;0#)q8p4eI_it87g0| z_zm!`%}Jfs0(g7N_bEmKyeq>M3q~7bk&uUm>rah@A*x?Z!;Jvm8iS_OCID|2Nt<_E zuRP(~aT&dKPS|+AS`pk93MMDz7Y`h!qS@#(_Nh8waxGRx7gIim$@s4Aj zeY7Hv_V9i{_7RVhpQ-qziYi$im^UCqZJifB-eqcR^_!Trk!07Oa{{lasNSua{G8(9 z^xyxV&7#VOPdm>cyIcSE|Nm{jO>6%V^#5xqYS8xw@9(2E$luMJ8>p|qGP60IYE206 z`TA#P?N;E|pj3+?i>rzr2%FQ>+IRP$yrpva)tp|8FmGInS05?cof3-aD+Zl`8E%^=Itqnse z?0#hI1$fI{T&&Fw@IK$65%2`u|DUf=5+Cxw#@mW5{JOb`H1dla_wXI-YmrWDydOnH z25KFry&=|^?4uDUzk{ukI~sQI!3MV_w5t^H@osj4yRK`R!C4MlB)X>Y@y=%u;N-d4 zMfZ5K{Nbm{N3SQ(hRnYYq-#^){f)@xkK&yuILU#9_d7EVvn+sjCck>RF2Ebw^s9R_ zz+1_9AaNBj7SU7XC*(c|Lw@XzNh9GcXyRGG2JjA$e>>ap&=d9zE}6F0#m0M?@|7o7tc8vD9;Ju%PtB!~d*nEFr?|kESFrIOYS%TpK!cML53-M8ocv6ejCSuk zOMq=6<*j`*@$nvfEa#;-x&@YdQ+a&JMf}5wF}W>wHc6|~egA)pN*`ip>Xu#(U%-1c z1>Rp7XMdu2Uwx9uj)nKk|bJr2J9hu2#x z!eym%&d^@<)+GC=#K}*>ZI!<=Cm(F<5`M;g9X{U4nc25Ehql0Zl`X%Wq^LNYIJL53 z4RpVpfF|0W;M|LalIpkGx!=g=C|n!G^(s|IDK-@d2_ zYEaGVZ>tPJ4Z0@3Z`r6mXpkg!CT!Xpi>QRph+Xv!Lu$l)Qy=?%fZY#Uw=EAFf`8Sq zh}_#jggxuJWco$0&mcWbHfXd0caVtWxQMlED;!d=_y4cC{?yp|gZ64r2iXT+elJt} z)yu&rcDo)WYF2RJ*C2_?U+I>xH?py==w1jH{t(O1#&7&n`zig`pb0+ed~DzLRr&7$ z>Gc$N|BOF4isIe&f}0-;@0BOi=hgwdMSnci-vIEwBg*Hr2rO?svOZ#*?;VTy_msOQ z9u7l{*i~j;0lYuhCyvg7A+}_-^&*LfM0j19SjcD>Hr|^gM1<&wh5Ut8sTLHYk8ar(^ z0C=4IqQ1nE7p4+ot5>KY1$4_5QRF+Iz3 zo5b+(j&XdkT3FW=(UaWu^*Cz_=0AIMygv2x?AF-gPP)f?-_A2s`Irg5d*f=v!UpL& z3cTkOxN}gvSAMz9i-mX0XQgBpfOp)RxgGid@Ao_Fg%1O~!`;8uMmfeJ#ot~hIot_D zc*Gzp4uH2P;kil~!26lV?58hDvel><9zx{ub4(+Pfmn7 zE>)B)r9He?l6?r{d2fTW4u+?mge~*GCafexDlKvQ^#^;E1lo=8NL^)jRVdlJ8~UispO*|nSTo#ALIB=RmA>t{0`Rt}$}@kc3h?%YyWQHchuCiWeWMT01H8#` zAxEvMx{a}CkOzpvKlxtM9^S2FA9(q(Wrv4+_awkx4$^jk{{y^tN1whP)r#-wg$v#SO@+-XYy!G4%0=yx7uZP)3{OZj+ z^|^3+&`yMfyKroIClz0BxyR-=n|GD&@n(2Tr4NUurR3)=^eOOWSh3R$#XCdc>S8Rs z!!|pNa)Jiwe$uPO#sKeBw*1<&U~?j0WmDc;6=bz{_vh zgs6+NF9BA2eVBdp4?f;XM=NJ!lPnQo1Ac`FF8teD3?kcGM8EBz{|3p|g(@GLo|Q;W z<}Xxl_`mR8`TIlZf0nn_CI&3R!n;N!MMo6it;6tK+6dsiY`8h62H<^Vyt9lA?EnAX z+5NR_TNvWoUbd?o;B9a%vJ?h*Pv?%083z;LUpv;PjT&R)?aCifdA>v%`9qFtPmp#D zzl)9cwy>C!1~iDb1K9^&ewUWqIlw(afLCd#wU$Bn{l72!kl)gE-blV-bepL@{_@sb zMom#^R4d)%-RfOUm5`J)MDkb3fac1?jhNJ34)p|iQ6$d48ct2?q5D^F;f^!bktQPbp!cub;oX<94fk)Fax%`zhIn4^Dpd4N?c)xC!tM^&*FxkMZ%YU*8E2->`?H`U9`Lqvrd6 zH?qaQ`P|4%_-cY0?HSno4z}qmBZA=;9ZGZoqU@O2|OkKYErUf?M zBOb!V@d?rh8YkE!b?D$f%pf!KMyj^A(;nWh$Ud@h^2==7S-_A4W{^(XS9tW|<1Mhn z=38{WI`UcThxZ9({2Anv!)wmUm*1j$yz8%MQ{_W<>|CfV_<|IeoETH!&9><0cNFiu zw--dP@Xk08%~}oc4zm?~WDfA|9B9R^-gT!J8&&kt9^TK%J|5uZ zr!c_xm4gpHcG96d`2{}SMrvaI$XKMU9IRM`MD_*^K28R=Wi>{UJ{)mk?mrb3?UVt|m_h9>`bFwzr zdvA$JzbWw2^c$kBPb zb)W`GyIxqmg;axj0+L78Yv}7gpLX%Fj6+;)zZwQLgd)k4neVkh4Vq}pEoKBYD9pye ze6uYPULh^y^HC4G25EKAIyJgWBP+>q3b*F>Exm?4#0ve6B23cY8zib^AHq2KMaFtv z6jSAcuP^GaJb4Mf2C-~_W6lq#A~pUm-YgTvuR&=Vy=h04>A(N)^QO+nQfJE;iSdHt36QM^~l%}Qb6&5^__YYFgXKDc`~JR?4weH#7A?|F5Jr?Y9IQ?+o5ONjBcnhzvRIkb5>)?GbFe zbNDP}9 z?=EKkU(o+sQ|F^6ZVBOb;X;FCNr5-d>R&M^-Y=4BC9&`xk-I#%4dC7CcEe>ez+1up zhD9U5yVqjM01=5pRENh~xzC3plEQfmrT}k_b7j*L0PjU#9t*BEAi^F8UM*ExgpGHh zqKuzbAlUyW$Bi#PQQ91hjrYscu7`uSXsvDDdXy{+)*6J^cN& z1Qy=z)=e+=0KDHg1_o>bcpLRP%9BoS<#d^vZ<&upGzqSvr@})Kx4Ft5(&j{p&2Elw z0B=c2)p2cWB0Tp>oU>9M8*d-6gwFObX=I)p*Z-4P=9h+zx8Vw_P|tg`hqnjWhY?PG zot^oaF?9r3d~?Hb?lOG5xzgSn*cutbVNdnazMQ9`|34E`YB{ul{`-GbDt)L9A0QuZ zF{i+r^Vzch;H_!CV>uSy_ulus3Ilj=;H-|`2=JbM{H@;>;4Qo|IpD?TSVWQe!4vz)Rgk#tDqrU*&8kULMMb8l7y=EH^*5za4-TQG((;k2~8V9v-MK0pO?*9u! z69-Lb5bqAMk3yXM4mmt27E&O!E+Vi({$sanK;|1siyKixYI7L(FvygfD~%b3BPW5j_4pJ9un(jCizoUWf z!#I68T{*2eH*jil%5n;Ga&r9SnB*AZ=;nCHQNeMI;{wMCjwp`39PS);93~uVI21U< zICwc2pfAt}^b~pwRYAp2Hk1OzK>Hz2$Pu!DbRiW;0uq2&*k{<^vG=pLve&Ygvgfg% zVUJ}$$i9c&g?$sdKD#=*47(6J#5TwFk!_HzlkEXp8CyQvIkrT$2sVGV9c(siMr>Ma z@@yh(+^oM@r&!;xK4EQOy~|q2n#r2X8qFHS>cP5|)r?h#Rf$!cm5-H)WtwG_rH`eV zrG}-1C5Pn{%TbnK7B7}GgGuLrPa|dyIaBt-{pzOi@gG zncSJ|m`s?~FexyJG4cM_@&n_o|N8yEzoY%X0Ul;HrX@{&3P<-nje>5V>WID&1eKsF zh9~b9bRAXE&(F?4#i%+|-f|o&LRHkkxF)C&Rgul1!KXHd0k(OCpKjjEmRDiWYmsM>M0 zhz&|bm0QS)b5IJZTrHq>=p?GPFO3a>l2PS6_O=H~Le;ir7aQmVs+`if1fk=oa@@?T z0VSf!K~5?YNfnDib=4Dk~z#F(?{UmO5X)Lx)gh0R;p>QK&L|rt=AkM3rgY!%I*E zs!W0+S)p)L8N;!aP#CI=c)U%aP*iPrAvFLUM3uoc-Z&@(Rr(PVuc2U6!6qfG&;eBG zDZJVT?MIdFh+Gr24^```vM)hFsM3kIsDuJhwbqW|7qk~uYvfavpa4{9eTG#ae^jk* zV9SO4P^FpV76|#GN@MFFKjecdb>;0D&>mE&O^}NP^FS?QUMWBrR;^Y zL7u2m+Vti#v>R2596FmI4^*vu9UlnoLY4g0iPexhs^s=net~wPN_O|hIA{l|R`3nX zLT;#%?%%`?xuQy{G{*zljw;DWOFhU1RT5`sw?NLQS}sz&5!!~TW#8_dhMZ6(RwBX( zIigDRcyI&cfGUxFPkN!Ps9Gw`Vh`D)YRQkQRgfL3gxb6rAX`)krtRGW*`R9i-XlHG z7E~=#{r(cNMwI}oB0sblReX<)MxjlpBCWSW8&O4Co`kGWMOw{)EKvm}H))Ussz|*8 zWR5D*sXfRHRir~skSVH2XF?zoRFSsOA!AgLb{ruiRFUrfL58RzU6q11po(;}1TsJs z=^#F&PgV=(mLV8bq!)xBJyek%T!Gf3iu67Oq>C!jb$)0asz|q=Astka-XVt8qKfov zE3^hxq*pE>ZB&sS1%$LvMS4RGT8%2w*Nh-dRFOXZ0%@R%^sNj?9aW@H3qY$-MS6)H zQX?ycqWea>p-xm4rnWgj9jGdZKKCAKN7Xg$#)nWFs`7ultAJWjb)}QR25LdoDnoyOuu5usr7*)B8j6|SDR9zgn{u*jPRd#XMDD((bS>eP?=pm{yjrMCo z^{C2_jn;)8pz8eOMjhxrs?Oa!J_FUEDn0ImI)tDq&4!x;szudV<>24YJye~3H=hdC zpz72e;e4nXRjEmqE1@b>rEE8Dgep;WQe7txx{Io$X&)iz4ysNxmM()TP<1?KNjp@I zszl33{6*pxda5XUvI#ZlNl+tEU3GiK=5oKVLwlWVMp?g=iJ+=0?>qroimJ|_&0&x* zsyfzLhCoYD)y{Li4iZ9DYj3F{B#5e(;tQ3~VpKK9%n+bOsA@7&YlH+)^;qD#Cd5xx z3dP^e9z$K|&l)}{J%ad9_2}lW6%YYc4-Z|lgm_U^ZytCU;z88|p_j%GH>&Es=n^0< zR3TLciy=-_)uw&;4RN6Ao>MoN@S>_l*`gU@M^)7?f-=O0s>;V@IuI+W?k3ED7fMle zhxn`+Vn$WPIxs6?LRC5Irw)h_RkwQ{Ux646x$i>d+vM@RPWsJi;~>tgm9 zROR1U!N~p%RacIzf51MCs>>F!H`u?T>XKxM8~c}k_y1|X$72Bd|27nBkfd1+y2QT4 zMoa-~4U(IvLf^Ij$nYygXxr9sjU{#Ke7Wf8;*!1_?Q?`u#vVOoc!FJX9L>K@WEq`IQ~>y;jckXl;&@V>NSO@Gmj8^uHf$=)p#@O?J`_P z_d7_BiPZTxtvT)X^6v@KEfjc@rs*i&+$|sFvG6t+(PjDx@P3eO4B*Y!#kl_^z?>15n=KOf z;N>P&+3}(Hc(?9!xBl(D1(|KUlQ;MP|AKV%pUW4|e|tdpct^8bp~}a%{D-_vf1kJ9 zOo2CPAqB;|>~y>=7T)RJGtWc;-jB^qxk-437)nNL0C>;ohEHh(#36MIE8lK?7mD=0 z(D*}|oNQD2Xw(hxW;$d0Q#q9g-x2f(gzjSFt@A)S>M}UqQbmq?u}(48b1637y5g)G zHE8g7iw4=pdYt@tl!W=(n)u+?3i8}q$MEqsDLGkVvcVaS+2GBuLB-cwZ{@e$kJ@sN z?l(xQ2B`D#T&dLOL(0POmQ56RlU4>%yqDQnufW24&mQG-iU9A2M|&h}0N#oBX6KRs z-UT~sp;NALh^BPT=~I27NGWUX57O}#9{$H|;{fk@RWFXEfkaq8K#}o#C^p_}wgnz9 z*)5G2k>f-bpA=Spg*`c`Oo`RJcZK$<_bRfFYMlH+iwU22%@>Vjfd=X9#G*ahKn=1%od3TW|B<7Yn+VtHbXpA$V>d{$e%m?34}nkYkmEXid zTt}$#k!+Z|>u1cu5WAHEZ_;KTiudG~Q57t_`HtNtUI%!qE*6M(0(dtMUmkA=_X6N*tvj=!951v;ZU?#$@XDr<={KNZys|&WjY6Z_* zpmB96KbCyb!p2+RPq+K}YT6rORmeW@^4od#klCx-d~m7xtgR1(Kg3qu<&GF|@I@?y zRq~Xnd1CkY?{pp3{{{VjH>KZ8Hxl|wIz}+NMB!jfPE3b+ug`i-Nu~=OWrkF z{w@rA2ANUuh&wV;8j&E!`DYIYuIICEwn&HMN^2&ny5HIx@u_2Yx{b-uigwBsq@kQHF2NE!-eW?M}ar#I0lM$ z$>DG%EW9T^jeEBOyr<{6iyZ*oFE?}58v(qRoGE08Y>z_%Go5y)3WE=%y|{Zv58&O# zVw3w0G)UvgBD>6eiSUoE0~d*L*m!HkpI^N+S{gy)46Iff5XZ3bo>qx{XI)2o)mxeD zV+JQbyDIpi;wpZ4^tJJ_oVECP{|PzG`lx3!(h!>Q>i`vBZ(UqZUQPDlkCUI!w`bCG&V2B0!#j@K4XD6-Y^V^vuo;QJbNr9o zCH($B`ny@%O73pD$2fM7HgA48Fv4Fqie5#!;};fO^&m*)KQ3Gz^*~2-*uXXWoWMk6_S0J z;N+Luv5I4Ck^oP=_TK;gDt`Z8Jo=|b{jdv?B55NxK+O}oxjYgkt(NpZgS^U1l@GHfVbB04|^x|ctq{J ztmwQzh7@QI?^d!8E1dkUUpXeKrNal0FPjgssKUqlZB5{)znnLsJ8)u~zajn* zE6dtqySuEM?(v>&rp`y|&Zou4@)q#kMu9i!3_OZ=)VVwjEWDq_T|@!^-e*R4NNfjq zkMeuWegMl`>5)BgF{<&%-44V#s{J4$E_ydX04#4Expr9jMFhD2-&i^&kmd>V8Kx1= z`eEa3ZPY?w{3(SH$ZoEe~F)?2SA)>7ORTfxmjopgt)a6m^g8@n-l)rH`JOCSB@4@#g3a zQOCl2tD^B#6u|qNT&%7Oz=<8u?6) zYYsL2Q)YyHyyYCynRBe3_V6Ai`$)&h@0zg$->J>~@Wx+nt_b`O_TE}yf@lVW|Mk|5 zVb7L)m^P&Q>dlx%osS{SMHiEbau#OBF0=wRV}Ava7#2;j}F$nNJ3@V+I!xV!`4 zZS`Gb&De@~#Ev~>e!?IGF|zxiWdQJgPA*=>LFpbpUlf9x$Am-JGzngXBhmH|Zuliud#6^tD)cZ@;>K zKnCF52<4pE3Gn6^Fe8)$yl+p>9=@ayk8~-<2=6`=f*f*v9k~PGeQ>{{3m3q%R>s&dY`m=(Eo&KIqP-cU9NEVvocuKZSOsiz zBET=Lj%^+e!pEDhh25Y1#Y)&=u-SWYG!@mG>C~@HwU6n)dM~HW$MUH^S3Z<3EN{6| z;7xiO0>#^--hB-g-piKoBxnG<{TCS&?*MoU+;Kh;5AYWIso1qvEgqQ}yZ;Gk3_*^K z^XMN2c>h@(S>Fv-ZzTim&))U+g!PVa&wNqG#(V$xxzxUwQV1Hy^*G|A^HFTP-O933 zqxfhK@4aLn+i~(6cS^GN2OmghnZ=IlcyWP~%#=`sbp&ZE#0Pko1>}_rU@21YDD*6EL zwo<#P0j+qXRrV2am-sp!A=zjm7!8(aLAAAjQ3Sjm2-}C>}c8UKV#(@UOlcENZUV9?d zAX5L&|7$B7Rt=JsXbr#jyjWlRcVQtB)F8e6OuJdY3(^hiq<)VL#vyOKj6ZX34Mxf{ zcQcRg`2c@O*lY6&%pkiDY!ZCwmADc7v#;!q)RX^V>t&>7b$Z-`jea@;S*fl6` zrfqBR1no6Q^<*EJIQi9`N)k6==ZD*Q{8BDK_%+Dnb>Sc1JS({8NMvzg4HXxpl?)jR z5?|1N4Pv3z$1BOTe|L~}Q{YW{z6`~?a$bTJ3-8~lS^BL2@7vmYT0H^Y=T4n*;Q)C1 zJDcaP{t$;eh|+wxb8j&6#GGa96~H@|@muppfcL)nT$`*)PuQ|&#%g>X8}FQ6?v;;f zrI3x}INpu(hi%qk?;r^*f3rXMBkkdxN%p~wlb?>F>Bn<*;QqgxpO2{|KHk0&{1sm3 z-C$+AGtR==RO}$BNK3vn+e7~ik`;A6S{uKu`#t6eNkK_Bk zy}#pr|9YRp`9AM?KKJiA*LAMz+ShXZ`vqwmGTw{#@sW5>*o`ru@g97{!22HX_O{?0 zB>>(ExFj44;N8B8OYh3B5crAA!H6pp=-~B6Qr}#D|g)?LekZW zN5Vd!^JaaYb@C(Ny%~wq5uGurUyshab>#3LHY)7i%t#$g82Rni9mLfH<00WhdZN5M zHt*$QW&?*=wBh3S`}X3Bv3cv-)JVUB;Mvd z)%0k*jlW#_H4J#CL1}>_X+t2nMBC`_cv?lXXw0b)qWk81Dg|$NE{(<)oUI$blx#vSp!6WQeXGBM(VhP zk>8Z-y+3M?IU$bFjq`MB*t|byGier!YQqOb(^T?`v9GtlsT+BUZR@6a-Z(4D>Uc4s zZuTjCY5qS!#(VL`R1)unsVj77ym>6rJ7)mz-zj=BHh}k;(qD9o-`>)FZCURi5DG`c ze<;cB_JChiM+Gk~PA1nn*$jfkNlmif>dGP_6s{zlZvO_Iw+x%h$k#>@I0A|Ly`DdT zmmi(C;9Z^@wX@X6TN0^bEk=HU&lwM~GT|Ykm+#_@jIentykGH>NB#)x9Z)AIq=n5} z?yl#YgW^`2=Pi;%SsnE;2RRNz{dfNV|KU_m`TuJ$|2vTNpv60*Nj>O^oaS=09u(=g zYSaz%pnDfY#vMQpYPm7~VV4s4{$Hx|K8cJFI6R20B%#m)c3I!eTnu{9?cC?K%HR=e zYt{SsbQTdB4|ZqUK!<(?>AcjrRcz%V@E8*3C==)S=U;vx-7sX4F!PD}dXO(tM=eHv zC(ay@l5fRBTuuX@w!dUi!}V_2_kFdq%+q zsd~nN)!ol&{t=5?M`0cJxH+%?J>FtR#(VKre-dx`m;qKa-h~Gx-^2jk8MRN9?E!B$ z9-nM&aDp_rT;j@>2jCZ^YSv|^FL=OG`l`D>1Ky9N^jkiG738Be*Pc515h3Q8Nw(Z9 zbl#B-2{OxzL|{_fK<{qexsT{?Z%c&2R_K19KHecn9d|MEbGE$iYovvTer_BUmmkFD z9g`BK_QLldB*e&kbW#L+{(qe7k?)hZpXN768-pmT!+El+>t^86{C|>+_u^+NNW7cR zl(3-j9%y;0o(6c^n{iv)0p1xZ6So<`fV7?NhT2qZ2+aJeJzl}u1K!Ux6S=rK@m3D@ z>jk_A5`;%jc@UwG0v|SPj6vre5s^Ezr9uS$gv5EPd3o$acZZ zfII%ay|pFdz4+Y~5^piB;ALpM4|rGR6ae0)IyGS@0dGRL%F5q>w^SMZMaA|ISRwdg zKR@IFkJ^M7dPW}PZ+88Hp2c%c$g1fbJA}iY{|U?a6%354z7(HMpyf`W~?sNF9Y3`Nd{; zc3QG>K|Qago65bgAF-{^yf}mtT;Pijc2C}##6BSX_Uy6YF>c!5Al1K0SshiyEh*cA zmR69b$#^e*N{z%j$$JGJjdxnqrVUDfcYnT};c39zf&}U*lV*Q79Mtt&c zrTO{apGAS9Iz}FKYO>`oz20&n9%jOoHQarI(+YI)P2!;8@i{N zq&yUXNpY{sflAoXR&W-p11d!0E+7P>YTwS60yYFk&O4^$1X{{JI0GvqVYbU znj&-<@UDg(Z#n|r%Tn`8gaPl>28Po6PKCfT_l%}N=Y`|zk2*O6-eyw0Ed_x0yV%qx zu7`U z{*?@C(0EU6`+DvN;GIw-ec2W87GyhXn+SMEWva%6#0A4obsJ8NdU?XL#fdeAfOl&R zUCSKct$%&jKwkJz(a?aWQkRquz4TpaF##X=m4MNV5k;ciG9UR>{+(R!%~AZ&s%jfWp(H? z$gVniW$E>nD;aO)PvQ+E-g&vLtI&9>*H0u=_KB{giIbZ-rpkF8#n;(13ou8&j8-z(8$dv zfH!k};I@|y!LXI;N9AqDJ>f7PhQQB&ccZ@Y;0?eVI>NwwL7WJ^uY(2q_M!8Z=~ln_ zHctd5#U)hNGgSMc^R7@`w!Wy9`gn^Yb==3uPt!M&?X@!=dUk=Sky8b`dl$Sb-Y@>t z0ai}ZNo)_LVE!Mn<~ykHhUU9B?$HU#>d?>_Ui^VHSbLu#(i-uJ~~ zJ~D#aTYdBU3tHIG7bnwALE*KPBCrn<$K_oDmH*3+6Jd|@n(9>edTSi1qZ}i@`uzMI zr}yHa@#9jvc?j6NSFyQ0U8t~zYgP)s`A~zs_lEmsq>@_sjpq0Nag4?k)!`KI-RVu< zfAc@)Ohyd>pa*%A^`L!F@IO6>l)go8S zd2SX6hL3$*GxFBj6F&Dv`#cPK5PWWQ=o{!kS$6i%zjG0xmvEr@ZzB35b{M}0|I%Cp zZbITbq}{~xFQGqTuQI&!Iqpq;kJw(Mj!PK%xsBUYrRH)%Rcrd2^|F?!VbO4;+hEk^ zEC=U#=q-zM#$G|*5bsqN8rn|50LNSGYJPoDL+1@ui8p*YCIY`k;y%1_uC;PN=l$Tzc#60`_3_?;)Nv0ZKaTYs zcalaqA@}$PE47NSdG~IeN`0j#2cPrxGv%P99c$6b##QZ&*0#<_RAi zsOWwPcpE$s4Qv6txewO3dl?WR<82Z%2KDH?C8R!xC)ta@2a!1DiuLPwM$vgk!!lMK z;nc@l0I4GkBfqET_=?5vazc+?6aCyy3b{D_!Fp)cN9{G21b7Dsz>`*{NjY}C*=h*_G9xlU)SoxL1ze^ zvFgcmP{uyJmH2$L%R_A^&7c1ttfj0Dy?Y6s6&IEkCmv+H)qF?$NZmX1lpP-$?~VIb z_Pz$ZFRu8h;0}0iety63CE#re_XgED1;aWn(y&B?C;T~#&vWtZt<9dKqE^8BHuG|W zilanGYpU@3=YRQeqMh?ctI~_$?kyxv&`nl7a2B2Smi5Z}wKA!X_i>~SDUAFQ+98h& z4Lo!~Uiab8QEc7{F{WpWe;kD7vx*NSv16~jalTtd0)KYW{`{{+VI6N5u8D!g$$#hn zv8FgG_&b>Y&y)3_{fa-PNj)fUjf5y#4{G0#^vo3WpvnQx6kpJTVtWE6et{nJeded4 zmQpa>D$1Qzx)$`HV;L<6z!{`Gh8O8`;0zKz`cL_Tb|SPT#a`>ER`d;07v3(mjnApC2gMhv)tu_b4LXrnlIb}WJM{YX!&44#=fxp3a@Q7_5TCL~O z2+se1c&Ps2DmrhuUo4Zg1tKsD64#^4-!NZ>&O5+sdlx4a?jT7Zb@*cBC%om9z0wdK z;*@Rv^6(5c?~60q!FjC5q2qxkZRmBdc^{r)7u^zGLGuGr!B5KSkUJv%dm?#>w;vgA ztq#TSB;J-&PlVBU9~Z6p;|h2W+?t#92E2XGi57PP-btmypNxcqVejn+-OKiP!V>M# z57+>2`@NL}7r2P9lKufFkthcwTd z;yNS+YUBQ1Z{bVETk}@!Kl}eH`a*@!cv~D#T6+=juFJ5HT;#pG!YQx_@W#=+{Y2aA*KJ(1skMx*l#zt?+%;%mrif_knz@V@na%&Z`~Eg1<`mHh|UQ{1KuH) zAtqD?x4Q0?~BrHiK}IZ(8%$8{hO)iueWyQ zUM_oNDgqB9afPFe8_S-c&;LD}O6-cOrn8Yo*Y7(6DbK12^bFx9-N@@&`R=jHAxg5*&~|wO7mKMtU%OPq~!%uE+!a z4IS4H1uMwtPx>9#!2GXr`5_(;K9Ig~&Rajk5B(7NPAkWa3xKyuCTBzz;Jwh$&=CNR*mZ6SW!P~7owwef zj5@(su>X(5CC^?K%JxO){rm-st8)?cJ!1DFbv(n!&vKS^!$Kq;a>EDOac;oo%|*Z3 zH%7}GQr!((POxF~)_*KkzrFVX&GR0DDXSxel@N0#c8NDV8E^fjKn@b`jI$5K(RdHC zz1S-YcpFWwXIjC5Nv#;F%@6d-oQY!)PAH;3Y zj%!57l69}`Hw$#$n+$hvf|5kw!$_Qx%E_KR-srqTBwE^(%BhdH2vSD?Mt*V=Dt)G} z@ldQIPl|ywHt(YH!RD@A=8%iwh)L^13Jyr;F%jeNWi-zlcbCFC_)b@CSvuYlLr2D2 zFZ*0FiMRJ?gcus{o4ql&l>l!k<|^nM;Qfw8&utdW|6XkC{e1L;VH{_~3A%X?m_Lcf z@(kepk&QjR4)BKG9IOlFw1wDTKdjS`vqk-wFt|fdLONRnW zms~yd@g7C$c#V;t#Ls9i=2ScsJ!PU?se#Q~jbm4+z3p;X&vox!F@5aoEpejS6AC+N z|AI6eJ!N&wY<#in08`N7;si&=Ti2E~h{QYV%7Kk&yem1XtF-~|yPK_?`~Yvol#-uw zi@af@n1Fr3@b%gES7+Hh;ay!-NsGMCRyd_E@;1CJ>eBq32z{y$W2hTN@7`Cg#8fM1 zioo4SoTK01aOyI2-V#wgtS6pQAMY@v4iSv}mUA^{MH9K8&gTuWtIe=^`#$L9WlA{; znLLwiin@o*`{|E#qu{pvG~d0so>5ju&V6&(-tX#v`~TR}_y79{(1TdXdXTBO$Ul$R zJ@lMg(0b5w4@tF`9bo={7MB2s>ezbo+5BC66fl=VNTB-eFeE7qD=E2RNBx5x=h|+X ze+P*(d`DRwb%GAke^-z!WV}s&CbN(pu?+3+Wzl#S3rpVa0=&7k^;-e}Z{tisQBClO zHUFIQlzRxAAk7{a5)bo$CsUp8&;j0E(QDT~2fTN?N6t^ZB0_2sQSH_A=qpJ7UD8#B zej+d_PM;@{M}P(W5sRxn)9@^b`gnUGbztSE`ZD`&l`0oxlf-YL)Q`K#}??tS%vZ6#PiHlAS+ zh1!Ua`?2!Xzh}_9_pVQE6ITO8U>79rNZU}*9XfR0_thfDlx|TU?=46jSotN}OkESa z#042_{~hK&j?G&(wd67LkyB6{$G5961z&IRjnS*xTlbXac`K%CQ&h*wY{E$Sr6u0X zWW0@{haE}0A8`3eqwx+3(rB9oyf--sDP07-uOwWSA%fRiR^u8*cfs%fWxtE``^9*` z=M{FD-37eIUn&z10p2sGh}Lp_L}-Rbc6rG%^zL1;uHl0f*qoR|;sVU+;xoC>d8=x7 zf2ho-KHf!09V!_4+2x+i-qgbd?TFwsbo!0Wn@jcJ6=qapYZE5|rrQt z-UF`utjrI8uZZ#4)W@3-se=_Gzp_gwpEZGx6Fpvke7QF}_WW;ttkbX( zZwT$XT=DSf2JHDi6;t~j<@`G{vT_Kqk_MK`F|x@53=M7 z_9XQn$rP3yXg#Qjv$!`BJYp}7dbx*!9#k9h$m-1wd9_DUN;BmX!SJiv`lrmT9xxk= z>0mt=kQ|R1tNZ!&LMfKjCg-aNP+Wh2tn3B!Gf0jaHk_Nj3d0FV9KYzk>`_njGe{>_ zcx1}rsILbRkUFsPvy!^=Y@h`X4V`XYF7J;0h=sTPq^9h!7I{?7j^$atH79%v)+PCMMP4UMoP zp!2I@g_&Sj>XUM_+Y=A??Ck5;cK~mzTW9y@0p9E7uGdAg5ur2dvTAIY&>yiI_J93k z`b`*iMdI?;TjdN+q4Pe?&t2k9Pkp@CA$4HoCzI^G>O?di>c2RAsP`&1Z`FOr_uIa- zh2}U9`#pL>!4*6DtxDIEi8TL+#R*VW$0?mFQOZkSkd9eS#`{R4g&~PIziFyG8t->c zBbBlN@7AI2kzl~P@55G@4ZOWg$-BHye=Zm{_R)2K?s~wY5d%3vfcJfyc;QjN`+`H< zOxOYeTJ;F-T=f+7+#IUy^AT2t^9z_n@v^D&XAefUmc< z5=Vrb0dIq#eKVZk?d`aDIqQ*G0`yhy&83WXblzHKGkPYo!tf{(C#RZXrQM9qo4)qy zh#Uv?@!pNpftBB@Yj?ZfB;g^mf^C}hh1k3|6z|jU$hUx!?~1=2y+y(NPnQ$k%})Eg zal~wj>UdPv-}~a$((5fYGTw&`R?3rje-u#OipJY7WwiJS;GMei*@+;)`)i!b=}5r) zn&_NG_n%;x?a!pEOMnL~?xk_}5a3;7#KNKsc!%#Ec#(LC2)W8WJd_!OzBu7EklQ)w zAp*N0aWe<|;ggBz^M8iJ!h(A&_3`FJ>d3^%FA$tZR@lM?o&SA%i%1PN?-7?tMP+6u zD0p3wV%{z6-~Ycg>!TOn*hcef@4DU|it2d2BJouVczgTb{7(h*Jyr@}{^us^LDt-H z@L~^=0$1#G2@`N=J*fS8@Gf1@gW?okD@1}GR9K@qL=OfeV@>F-?4@A1`_7SyJ@Ov# zUNPba?NcL=$A_)l#lF2zH-GspRc!)9n27k<*=&P)#4c~Y(=^9pVb~stORH`gzW&4u z^`85dRSUAWUvi=T`(gdZ@PF#>w~#uTG4lH%kg-|kC?1ke4e8S1#O^`UJCBC?`dUL) zF|S+fjj`wd0~c9ft`Aaxx6zz{#wWl#lsRL# zQH=l<9-eoTC`IRec3HXD_gZ1N1c@66JQTh14mxk;O4E$aH`K@58L2}NBflxf+1_2b zcxZ0>u1_b|WAkPo8XFHhYYn;3E#wYwtw#N?{XhS;EkBaZTe^kjdE=tYD67Ld3= zueb1IypLt)gMWp?EnbjzIVElv8t-LJCOrheJITGPJRI;|RsUed5b%yP|5B_`77Pns zJ6ZG0+XG%#_kf!N@a}0Ze#imlf5qP~zP@WDKo4gISAQ);ACP$NLXkULgyBjg?n!@N zf=M#^fb@BTO2&hJ>f^l}sbc^mKe23sr}{2<$gbzyV~gF`yagQPYU1L}A?c*IF4|%g z3`k!mdt_XyXrDLh6h(F9-7}f_nX%NpImvh*_1u_9;;pNCTmg;up#EHn3*bE;Zu_O1!D9&8PU4dZl;k@|Rk+>TB{vHP#^a1JT<-`0r->HvxI8w(CjQn=M#;<*~xS-S>QY8#T zY~IJTGS+*)Fo)PpU$q17*ja@AD?APryfB#>x3}tl)4_D-C_$>bZKZb*hx0Mb{ zGl}=e!nU1gypMN=6rKmXzp}e4F7h_APhL|Ac(dpHdR#Id4BvX3W**q>0l)dgz5D~< z9e#?^Mep90aS{HqRJb{z ziqv6&k>Bp%aN`pXDj_{x6^h@sjl*J0`P&#U8Xc|EKLg#EjO1>i90su!9~XuF*Lb1$vOJ z>di+Upa*epc);ZOE(rFo5HX(CaECK`&zs!6Ho+py9Zfqjp8; z15#MxS=U2>!tfXp*Wb}|$~XaiKw_GXW0#1fzDH~jQU@bOe!I4&*V)c+LTNc=6))15 z)Udz^oxdU$7+?$qgvYG7)`s1KM4Ip)wT>_-V*UG4``^R8xhbmSy@#h;)!$d_Ysh%p zw#BR`@eU0VV?yIC>{rvv3wUn}sNTBByLV#dD*^B}E|d0Y{1pVhBV^Z1JGsLZ-;ap| z0^SpBl36DJZ`a3@y{MSC8lDSTO zyycNP_%QN2c<#r+Kvg`H@};un!EJ2b!aXcUAD%OYtk0Jj@*Ky0y@hL*f97dCyNlZS zV&=C_k+M2mTs|N_kX}v3o0zp~X+T=+-dh?c8PIrVDk#-%1iVAN=v^-Z-cW8c&imJ|i>(`TsE_vmQpXHNew@seje|Hmw7(~2gAqCs zbgMe()Ms|=?tS|g1JUD-6V1>6mz^gFl+fn%)tD%%M|b)=w!H@4tRfZ zmauVSCqTxvN4RGl(RqhgKW^a55{Au@xIZ7y45}YP=RGLZwauQEYsKb$PHSefO1K8(>gxEhO0@?2?d^$d58nGxG|wA%HHES|Rt?+{`TO>k zhm5z4O4uI~?_$QwbZES2N>(h&SZ*e|6(>>ee)tb`h987(K;k+S%&b_NW zV4F2@u3CV%-<4LcGQj(g+}VNcR^ap&v#Pi4JUZ`jLwYHx2g2|=B<|jswx7Kt=)A2C znhHiVP#^DMqz(&={32LFzn1gjA=#(aPw~I8d0R+~a4Yhu!`sG^Kd9AUcW<1$wU33{bIr-b|K@+p#U3>TfcbwtSr2mhx%DTh2X(L2T8`F(%vHInn%>-2 ztJ<(RJ{I&Kq6+8OcJPROFyVb8Pbmm4+2ocb+297}S4&NlIgUV1c}>Rd-o4PO>*~FH zKM0Uc_}m98N%U9jC;Vpj<=hp94i<2 zq}P%0c5H5NCh^YB?J@0o0!iP&7r?y7d;f4yAvF5`GUlWnCdZ!y+-F9 zVO8jD+)91Cg^)VJF!HMs+~6XSkB8FyXJT3pWAl!b)VCTQJ_B*Ni))%lWBD%vR51^L+8zPBegSSfckh>A$8y}^0U43*1Y#CC-gnd5Wm?Ln>Tm$ z$1APWu=$4EyYIk&q_abSsT1(- zE8Tcv+j|0(di2coU+>U)JM{6^Ul|mJGm$vv!$n8V*yeRYA;piLhC`dif-~nfgaQ}wQqd_ z=s`Keg7L@T9i)|&PJU@cAS}=X*J)Y0!K-+`^0zsSKyNg+NauNh4bpE}d=*0kNRQEd z%-;Zg{`U+U|GmdX7&b)W&ZUevxhzLNVt1&0OmxDP`g)KvQpZ7z{PJvmweIHRf_8ns zWYtv5sD|-R4QC_W^vN&J8fsxKWKwy8{fNam-#84j$eA#k; z>f`+#sUrv@zwrtB%6@G;ByKmwN%s+(x0{2n=IaS-sBKCxD02<={Qpzm#8Arh9?kQf zSx#9U!zOg0m%Nwee<3p7E)k>utRN+tx;W5yn^qRx&IY`K~4b)&2jVr$tXP~Jv=}d zK7_=zf4?U1wgR2ET80Syk*n0lTMwy286&^D!;_<8p_~w3HEzTB7&hsKiSJXz zfVc8}bGk*|wIerIvVr-(RcuFA4lW1|zaDCplm_13a@?uY1ia(F^EpKT-Y@5G&#nYN zZwdBXr`7l`ysvcZk}CqoTOyG-hFUM@>?(BLu~MJxPvub`??|MMXpH>Eif6uXz2<~u zY%9bQnXm_>Bd5&vyt8+OrZ<%|l}uxAkd~QWnPS)&PxAxPJKtD}>R`C3Xmj}Qj}ryR zcstABCrG>rq32eh@mBs)?N$YN8?~wHTwPpyCs;)b0^TcaH~i*X7XlJe-c7sP$ z_xa!eZ@IN$Q44@~#_DZW>+=bac=#HvKX=f(w^{OsZmwIxunZD6wnH~}Z6G@DpQ3LD z*-EI7w=q)3I7WWzgMD8iK0IVNo?O+o3Y+)cS$^}kfVY=u_zJ~D3g-XIX}=E)-K2Tm zI5!IG=)QSN_P_ZbYlNeYzk~T-oU8|V_nY~XdeG&k+j-G?(D>Kr$A+K>ZG5#WCJFSQ z7IQj_MzDg^6v%U`iwlHDH_CsqD|3ab#qw&eo*sdM>!t2FdiFw$30#DdeME@AtTN!? zcJwQDS7o{nozxJ9*CKKIV_ZBqThZr#nWXWGq(ju#gO($8NMhtyMYrz7fmSX^T0HJ@ zt`YVMvfcPy<)wZb$mKM5!?Wwy7o;=${Mu%iMf(GiN(5zf*zLYrWC_k70p4O{yw8@n zf`9e*=PfLs8P=fjuG@63!V2(aWxU;Y4e+ktEU>#8@GhKIc>W|I5Vm-!lOz4X6`pg5 z^|A%LhkpOu{{ZlQTh@K+$2KCgY<1V<9(HuzKE@?)j|1MUNF3kP^%kK!=)A)o-SOe1 zLf)=O9YGlR^{t%?eZj*GWg70EY9wOwu4kwBSl?{}jpli=%&y1gjT;(iN|-LC{Q>DK zg>^Uu=_Jt=Y z5Wc1J@lYA78{Bh2XNt#%AFG+$;Y@ul$h!8)@8`kTyyg6o9yIJb05yMc zDSq<^`}LMYV|(@S0a+#LSTg+2vuLWPtd14_?h8%Qi>3^H#mG z*U|Sh_3ez*mpRemxv8pCK#OyqEJGKa$x4huCpVnaSEn)gF{Y^`3-oXjPw4Zt6 zG`~0r|3XfW`?|=T7{J;5s2?iu-vL58$88=1hK?ye`1<-nsWcXbC8qk9d z^Bx_)0eaA(v!!AMpa;zj4dxbv1;YLO-0zaVxxf-v?f-~6k3e&~jOQ+R^g@B`xati_ z;1{HIPaNMkqW2(K7exuV1|fI>iK~2g|IqJm=j|`V&xRZ&wNPZ|w8`-_HNo&2!*2&G(@BQp)ORGqUyM z2wqx2ZX)A-{{HiS9$(_e2+*=0||oAPKKCvgo`IpURMFZ4!c)BXJ889Neq_ z<$!dQqu5AE2leqbK| zkk!1ayK9{fLcOK+e~NBnZ;*PGCUqW^+e7p7zhNb1bquu4Npbu=|1U|#+wZ`eF%oYF zhFkn-yk$JYM3n$<-iLIbuLIr-7ABSrfVbw(x1v2!fv}roNB)SOD@=T$ZCeL;s~H*L z1;N|fUY2cw;%)>emrY0OAu~Gf(x>}$H+2ZXc}U#jO@70<*U)*lH+E&E^-&-1+ejTP z82MG@vkuOMa6#ASwbnZFVe@8@Znn1~9)zSXoY{O*nt~0|eY2dZS9a+3R z$nXCp$awqmiwu)^?=C0uq4DOKSocZ;@P4(m7h2@aGd$|n1bFYV_U0A58VKVI)f>y= zU19MOkHmDq`|`TS4^05?>!u4$Ek}var_G;NymLn1oKRlb)^J@@7$(IXu4DH6%!vMZ z%XJC#JT`}^Z~m7<>fpu5&*HGj$HZtZNJFUOA{@BBa36h{Sr2lM|{vK|!N+Ez;HLE<-rMA3SXOG$K1 z*K4qXl(61=6ZD{Kf;#*6ZXu;h=S)fcMikPUdZv;PsYq zUKVee3tVaS@&F$2uFDRwn*+S}ZoY2mrAL6=uWe=@Wk=_|Y{61y{IU@2fy8laeN}q* zB0BH>Tl9rb5~+{({QTcKdNA@^VOAhzI**4=T$Ri|cmbPt&g!1#{AN3-{Nx7tbDt?# zL9Wc+Zu^ix^Sp746xLxnR8(0%70h%Opo(7kG74C{r_dy%o!~Cep#Z7h36m?&?4R0a|yF1MPz<{)K_hGF?-mBE21UG>JiC!hhJKQr67T2$|+TG{^7jCO}b_Kj2uT0gZ z1FyGMH-#kg-y=Ym>qMF+3eb7G?3b3$EE0mFk+=#UzXmZ;bly383c^AwsgJikQbz_x zery5P&z`x%1-+>$m=~_V=B=lh%(Hdc3Tij8iH02;G4KCNI@;B?U+5^!&;L>)l+__R zSC$!cacOfxhK%>c6}O5=yeDfc1<`m{6+h}^2fR}ZzTQXyynV**cBKK{AK7j_5(^E4 zOF8d;+}Ys*@BYEZvK#Q$C7f+A0=(6~KlbD=CqS(hPfTAFq4PeL+fY;o_TJi%xLZZL zM=Ye#c{9My#lf$skGC08$HL=(&+kX8ui7E7IFT(k*(}+F&709aaplcfD`;i-!1>As z?7cT!bd<)7s~PQg?~jz#QL9g%zU=;g^FI|#_t+_b`F{sl4~l$N_|FCD&-hnMq4glq zKU0$FULaeb z&=%$$na?D^6+7#sCuWzU_aMmf?2|PLLU0NaCzBc-&To%CAPo+uaEPfB zF*LouWEUPX6-mkp`bMvY^$#xWCcI7KfEnaEZkTj;5_<{FDN~+vLQTzI4F*i@^y;7rS)n#l$Os_qVE}h4j4Oc#EITa5m1?hjTNF0s#ovMY^<$(7g_SH&@ zybX?MJ0AnQXB<5rToen0_q48@xbwyZ4i(ZNHUZvMwXCb_0q=g6^z{zQ2@u1CyGwT! zI`4~C#hX(P3c;kfxmO!>R5qdWe${2jwekq{@%BRMz{+p>=In0neRv4oX{u=K%riTtFHVD@5vO{F#5O<9D>AYtQ3E6b~8HfZTPouEbOU|_Xtu4R(@VL zlUFmx;vsi?cE6Qdv3ave(0zHMYY2H=+Ug%yPr?2FM;5#z9yHQCZ`=V2>oDIHCGq#| ztsEKeP`b2>B;Ft40~^tJ7ZZY3wF2I^TR(hV+hE6c(>rJw*1inueSmPk2B`F zz)TZ;KQ92@NtK!!>R@vshEDmRuonR;Q+RI@dy|4L*%=t>!H7O4kSTw~vY)`NcOu5xhz zJ;)>eT}?LVL3}}kuyJ{LHPeVv@m2i+umZ1F_&pm}*gvgq`ZSpT;|VP9OTg-v1>Et%b+iuRCoU07^#C7BfkX0 z%Q==!oKUdc`t%fUdNnK?wxe^79qM|}`)Oa5_8-_Q$mSY_$I*XifByH{Oj#W}l*cr5 z|9(MAk&JiDrTvm5-gPH>Wzl%EK2mD_$ zHZ^pGS!bQCT>ossl@2CiCE-L)_nHRzza+E-d@1Eoh?$X|}z&xBMyv^S{^( z>jMQ-+FwCVO;c7!?9tGze^-#Z$aqIv?t4b!-8Xhe290<2Y>(Xqz+0_}$2SY`)=%E- zwHffPRX%ch%l7~{+F~eUNZA!Wy^`(uDZm@w!PWT~@a}cKRg$9wz93b(X<*J6eFeET za&_iTMj@CRiK|jC-N%`R&Rar+!@Zl0`c{xUNF5t7@)K$iH@o(p6FN5RbK2=XHt+an z>{eg&Z6V(f)|eli6zm{<6nM&*(NFuldnv19wu9+$a{ki%uRz8-N>1?>i8rsak2D%@ ztw_h1NWeQT_U7wMz&jJ?rey+n=j?g6^}=)jT+m@El(E4T{yD5sa}4mlJylZm3h-vL zmR}eJyty5}E__8;iy!G~SB)Pu3>@-jiSU$S(3eV|nh$MZi0AMxoA~E)cGE;jb}g za)mk8T^rN@ycZOH7X1OdV{Q!(+}%Tf%EQ@8=ylL}i{LzsG-QR~2S{98xk8e0DthgF|FLVBcA)hjqi^bGwu2s& zB}4d-2YOIfSfoHZ=s~AX?BH8D9{|URj5Gtnz;c5SL`rqbsK&VZ=-qM zitQgLs^gnmfl2!1CEluJyyFd*vyyoCf4M1-#@o?J;Fk{IE!iu4D;MzAwR$`04|v-r z4jami1;AeEQZK#)xWe~;J`BDDc*hT$b_4_7%xn)%2I2`&@n~`2slDjD?GFr>r5+Q6 z?;>#}>dts~Z*<=3x6_V?mQWvWE2NIy82NSGK6%<{85fivuy=xeCpPb)Z_tAu(W;Qn zaUa#wRTQis54~k{Jk?3_ym9&z)=^~>n)vs6OBFKSaWWqBB;H4FosmQ1Eo-J%YXW%d z&~IW~4 zx3{VA-CHo=eRz;T)q|4&)mnRsg^HthZ`DI9tlk$0!c|DzuQ#eQFHfTL{+dF+{8tzC z@!pEmF^rMlyimeO?<`_2b>&p`_>o4qwx~;BE?V(`)_xHJy!~Ny|gZZDE zvO28PbC2B4{%`)r(Zc_L`F|f-4@$Z1J-FC|Hhq*N+RItv(0Wi6CEo}hvGL{`2#&i0;Q|Hg7qZ|6sVaTVtyf(~pmcxBuIJ9ZPzztdrNLzc$fhpZ zwIdY02VF1~`KkLt06vDqg-sSZ*d?R)poBKAE2{R?*Mq!}I^r?%ON<#@^;Q-S$)yz+ z`$y5KVbN)vUt5~F`v`P2b28_0Ed@JBPIcEVH`vqu3i2Ffbv)MM`V?EZG$8FI<9)-& zHktH@&3IR@h{oISUim3@z#rGad;@rgn!2+)YzOE61^itVR9xY#-MPu3 zfcM$WX^(mUZ*@ln3!8Bp=ts%Lf+<6E-Yj8awzk~@@HZsxwf@_ntxo8?@9Dh^t9GG2 z-V33B>nOy?@3(Jpa_}S`dK&YUn>inwx51?k?#UPIq4f&2CBYNeyd!C zft1zp>Gjygw|_54-$TYbd9T|x67L^PS9hWDme{!c%__jV8s2^THsIY}9^%ytc$s^rD*Zu^*YHZ%J=grJaV(cLf zfzf`?TiElze`KdktJW8q=Zy=Ytd51%KWpJzOWj+YjQ4dhe`OMH%gY1>G~PFc1k{88 z?*Qp)?nU0B32QD50p0~_H{PsU69`KYBZ`;1xWYZ<5h_Z6x03g(s~F9jU_;BR{y}-46~J4{cZdcp~s8HgBA{)wOkPZqRed6KA{xDL9bGHsd`d(h(izYuK6jMjr#PJMXrq8)sL zgwe325cD9~KF9s1!8=Ii+vR1eoC4v4(u&M$)m&ijFG2TDgGa1XZLSL|=t27R0aq3} zY@n~oSGsIY|4R>wxFnyjO#uFa#Hm!2H9q^70cpSX7pao9)YpSNkveoR^0PJ)F$p|? zhpukWirlgsy9dSI6O%12wub5DFQp2wVLxJVceXQI+m6$I4;rVij*uYt4Sx?vYm@O# zcNNzq@m}pD#DvD1L7B0n1Mm(dY*$(2&9s~2Z64rVGH~~qhixDnY=9fHv2%e>rsXC^ z0^Xtq59vF>{6FzzwqVaT0wmO4xkaA?{fga{uR{u79T0#8kT_zY)JZR7G zNl_o~Wk?-cG4e~9wEfo4jfcK@)8%BUVDpwromd~oOMqV}EktS2W8WZ!v#>psHS16N z15y@cb$sC)mNJf6T0v@&@xG<>(3QmdUgj7B8gCV~>Zv}!+c@D@=3T(MEpzJU;;**^ z<{nBF9}R@{Z?-8vy5<7!Oc`{Ld)*3iA51TTUw!sgL({q>dzv{FaUBRV49hgl^Zt6yh@v{e4etMTzqGVLs!7KCCih-`5^rPmT6#3z zH?oWkzXINqI)_#)^4@tUd%X@AkTi1EcOZ9ic~kytR-zK4IjioWm45 zAc}{kzm9KyX^qX>K1)&e>uqDmRi@?4coz2gf83Pl5Bg)1G|wA%b0bA{@K<#j#Q%N0 zr9s9!wd+nFiT5VK7&QKVSPkK%BBh@)PwENTW{ain6-g!UV>2Av(f!J@nwJN0Gddu5o`leag zM`@n71&aYib;yOgxo`zv{qOugm5liRng*Ev4aj;>Ud#(KQV+T;puHTe2jR0nze@%^ zNN3%%^kUG1CN8wu^@A0p)!sPUW#9`^*-D?@rZS&_uX&#R&IWo=LsEHg37G#+sI>|8 zrQ1OBuP;G*2hn?woV=8lPV9Pk4vCvSHFVZT1-%EA(!VX~i{hZV-~Vqy>L|v@&vVz@ zD&lEQD8K7z*waK$cb zSvRYT@)Ck7iP$y~94y3St671@B!doavr`{Ba%@H-?9ic+&X zyc(UiWwWaEngZ(M-GkI|1S3C5j!7}WVoqq<`pHOQ4mR&K3PsulPfg)Nsn1?+aKe7Q zrEuccwWGQ9G|zjR31xM>+9uGm_wV%f@EUl>pX zc$aAAmlpuuC*E$B_qrGe=cxV^X7@P*_s!pYwGr^{?;u)|zgX6Ivr0GCNs@ z&Aa8O#Pg0uQ}`m0J^EKO1s9|pzcJ#qyM^X?qcjjCW=W&XCl-k0k{xL*vc+^yG~i!2502QNki`!B{IrWxzX{d+2eSYancH zpgE|!&IN`$G#(fM-iE^oW(t6JZ0=z6o}V_*_jAngS^x5Ri(_-%DwYBQ@F)`Z$@Obr z-@kl&i=oi8&V-Zt=6^G!4myndmc80jInIuUc4fiG3MR36ONMuU|6XJb_Zb^+(on-* zd)J?v z4?4TBmYd0j0Nwiilz!?d`Ua_DO(*Ns`t@)M5?8vFc#}U4eSm3TDX)4SGHcmUpo4yQZrFAhk|;~VF|EB4Y$UO_jy z1L66)>a)kxonaqkmvb_JH($xKKu^GXf7PE81%}{)w1Hy0;-2?}E*5|9N}sdjA~<8t?UV2AuwY zca*f3{vz+6{mtJm0p6}W+3j`}fw02q6()+o&amzlZ900u`+kL5#}mN2?&g{dbz=h5 z^*%aE_!2sAL?2N*=!NA#QPu_@7vQ_ z^`!1Ste(9RjkoEebDm*<_mGi)Z3*B#oOk2RcQ7DDaGlz(5d-G`yYyC1JDlP33Bt*X zyq`|{y{!hk&z&&Zc+i>v?d6P?-I0XO+gem0(}ovpkRov-UsxJsywG_wh_s3SFZSL% zoT@ea|KAz+GS5>gWQsy4rL-t1L)WGu-%rBWzUQKnEdn3^O?l!V6|nrM(BZ9^0h zCDG*f?Aq&m{P9_5?LU6s>$`ogbN)HKb6@AW-jK9}g zn9sobTD86_hIih9{oHtXr@ED>CqulOSAA2TiTC5~&)?TWyz^I!4BUr!7f7sM$qe!S z=&|%EwR#&qXGjjz&m)QPE@%}vQ--VrdXdt%A9fPIoH%ftcV4NJ<*cvX zQ{nXa$e1s*X)}B|@xS~37-GWz_atBkxot)bx*htJ8>>NH+L~f`HAqvd!b2CfS2^P`fg4w$GPNw14pd&8p7F*}=Fx>t><|B+CztauIujaw~ z|Mv3989FSRCLDOwU-T{R3ET`mHdTag(jb1szMrgNQaxuo>ub=cTPK3CKAq(Fc3I z0GHD;%58}EOXkl_VG!?QOSI1RCcB`|gfC0iU&qJ$c&E-*-%3f)LW^4;uwt9FH$L9K z4v82h++sYuV`x5p5ac)dkk#k=U3k5vwtZLJ7Gk^?flEKOIcx?-T0PamlXSddS2beQ zpz1p7@g{ZA=|k(IvE1L+Tei-?yI5?<0mHjBs8tvbZzHA0h87U-vj(;A??Ak#_bZl7 zF4xfgbY6k7B`*@Vc)r~&%;F6W9%(l$fOwZUY7ZtsyvHhy-aVakK}D`K+6+GjEA=?%?B4je$35_eXaKKqi?reiybH=#(VC( z!%M$(Zbf}>s+~1^LA-iPa#fWXd^tAz@lK%6hkd_7R@mR;En8;beT&pL2g7^!!D~Wz zc-ysBtltjt_LSVUi;8#T)!rYz5N|)ZO<7#Nk>KF23v2c$d4oNtw_9dGy#0lnCi5ZQ zd#hMFoTgmRyUNL|3g-BDuh{A-tT-eI?$F}W!Y}SL=EcWbYqJL5lWxYtdpXU=GJ^be zKDIGfq$hyh+_vYA*GFQ!eVz)j`VPCJF|s?BUa4#*Y-ZqWX&t=Dan`^8f3t`_A2K@c z9@QQDvpHcs1Miz<4!bbCTlRYk;^BSLZIyxx#5Ln#XGz5V=L|749w zB)Fu}`_-+$8;~_t%j|=Ai#2&ROhLR$)`-b(gWvyqb%yn!;dgwzZz=9<;=D5tyr9L! z^4=BTug1swtsCXGa~b2!|2Jtq-Vo&X6n$ZuRnCvD_Fwf%kBfNz|6x|$Q84O`GFe^9 z`?{Qt>TT6B<~}$)`KwEeFL#!15rS;^^R=OS1+(K!XVQb-a&Hc(sij! zcn9h2rxC|@dbyy>5?NSG%J2syuGqDQa^_0{bz0mGGp~EUobU&vhDE)Od$}0z5z9&Q zL6o1yBPG4-@D)4mbdA)#X1@s^nJXLTDp*(?1%k>2X3lgRkPdhWR6^C(&H4^^7JNTn z69u+d2Xl|S_X3njE59cY@3W>}2R^|icH7~}ZWl)v^c;(dgZ?Reye+FH*DhEo3DRkC zo=Gp4ty_nWx24l6lBpu&;cY?lVL_0emXNqk;~sw0;0mYOD{o@Fdy5VoIbe1a1f6&O z6#cZ8@UH`@rm`bH!*tf;O^Tw^hxH|n#ee62yBT|Ct)t1yP5N{p||0YV23+nxv zVwN%=zk|Hy+gA9Dt;9R$2*LADhq@%}&Q?f3763ugcQ|6v{U`RGunKK3;E&;I}R8F=3% zsdiy_haWpFfroeX@boqni1);^uJOAN@3zXSoLoQDSJxaQf4wtuzT$Uf0(?yK8eyvf*9K+q<$DT%BWFztBMDecn9|22O%=-CX z$eBJLhR@bIU(Wc0x9tqP@7!wA$MC+lb(c6E-p1#qeY7CnB0^WZsCaWPjuY#Ec-tNq zP&8f?1;n-^&9((z;JKO6GwSlz)MM@Y=OEtG58fC(zwd%>BR$AFsfdqv_KO9j6`7L2 znieV&%0@2ypAPHH_tx@Q0UA2UUt54ngyRoI;TxBt&5L;kK>`{EYEx3*zNK$1yyftV(tO)XZJXzED_7y+cAOCv&{d{7)pZeNN@okL& z`<8lL>sr@L_}8Iy@mJAHomI0QZyRO$e6;+VP}`JsKojOZztZ z%L~Nc5^afqc%Qd2|IP>T9uCSpaZ1(|brd;rxAYr6-p=A|w~n5c1UqPPJ>DY&E0XZ> zKJmj`YT_j0;q6585l@icoc6%yy6}QD*+>IL6IS8@$tZYkv!H7P;Mo{b-LY-W9plr!l;9pKf1(hxfG=I=LJWZ}Z&+EHm+T zl6bx@72>UZ|3RfS$s6Q_EYkf9@lMP;y4Tj9g0?9H-kBHWf<6Zu^aRK8Hzzhf722Y} z1`j9F;#PcH`+M)de4N;k@8oFwXKvhH9BgJ;-~0dnr}_T><-ZRf zv2HVJP@_wLBUXbJc+FG7t3f9g>$q3I4)O$Ba9|aD#0EYtcK3p>*pX36FTxoOo->Ix zFeE_#Unh%FUMf4XUPU4lRz$Y&gq)89v^QC!RI5`Y|5fTr?jp1o=sNO{lm|^P#$( zk%u)Ki1AMElS->{b^;RXL-yP05Iz{9(~O{4x1#QTdDPdF9tjp@ra?1At9p9*l^dqpN1EJq8uE6Cp91^Sz6(fcsJdwLEq@c90U)d5yScKi;I1 zbovNZtf3umah-v8UCZx(4ksobijv2}d#|Wu-3y3!Vd{B=inr@$7uAJu^|pUaaYX;p zXkaChYa*%W4X)pix`V*g+j*;%kw}QQd6~oc9fq!`r!%uc*fIRg3GI`i)5TqLfjceE zjhQ3+H~Ap$LwoVm(>KQ(84vFjG#{!2`AOf@k{#paN5k8NH}NbbUf$XsSNem+BN()= zcURx=vkCXl<(~%jFI(`dcj5=z>C^8R4{uAFk5dHsEvUQ7 z!~-`cmV6wHyX{Df_wTV4i<~PDgLHS6BR=1VHz(3}E_Tl&>CXD*M0*E)J|g{fbYmj^ zd;kBR^2W%&fb+lSj2iUVdet+m2DPr?Qp2l3H*1;VPr(}W=IqudHLwOHIrv77FV)a3 zFJlSUuZ#lcqwYP3HirWee^mkSf}hxFvOab@n1UKDOY}-U?Se{;dUOch!|xz#MeZhR zR7(IETHNx`UlKej_%)~^gYw2Bg^S_VAS-A-stEEM`CJ%X&n$p`P(GMOPq2sye0L!RPgY= z!uPJ>EX4c4QM;{FydAif>Md5+(0%L^+STwl3iM5tZI}1-0>&{NuSsw~dSYK;yAk3o zF5f+m@0bf3Aj=}3e-a<>WvX0UDqRvFh!%J2!QF+P?D%*uWLie4D`q^rRcSsH2=Ysg z3Qek7!H*vBnfp47lXyU?_1_@dcgh?13gx&=cMxxoO7A|_b6_fG*5h58MV}8gcAer4 z;eU3J_Rhfj!Ia$IfABt(w*(LGxl^%x7a`u67d^VFA>JY1GS~P(ynkCaJuvQx0;eCG za2`J41y1g_3zUI)Z@ag~p9kVCpWpq2749Hew(Yl--j9#BSBkI080%bs#kEH>$JkHc zpCE1I<{e0R%XoP2q4{_~kY7o+ft9--AIhnd>^i!D7;krq0I%8+Z?M|>$m5();^nQd ztBsYH)vnHZyh-`=`OqDDVKb2aXFzhFfp>GQbqI#{o=qW(@$io76|%k#@h;ilK-1uT2qjnDb>OD~GI*-K7cmq-b&Bq6V{6g51Vz}<{q59S>ia&IS z@lG|d+yu4+fv3bYV=a**v25DRneLlWw?uR?hfAHQj1MjA^#vBaq zwMFL2cz9M5`>!*5rJc`OXtAjE%m!XPt|*Yb6Pg0&Jgb_ zdqg%|fOzlwp!ZJZs0$i)OuneZ3Lo!~*WG<4#&ba^Elz^jy)NNj&i{vKlW%WOVm!Qq zX+91US?fgI z2UGBC(2G~i4GWAVKrSsVW7t}E&M*89GQe(=pP3Njb&!u}KK2phm*CO~w@~@fwqIe7 zrO3qd|FdU1-)AZu1BzTfNh){gxF9X<3G2#Rb$4e0k^i2e8l67&BpGY`eL>oH2Hwx4 z8~*t~n&IOXO+364wyqEhfOv22i@Q_@@$PI2u6+*izLYhwc~fi@n3I$cH>bc8+&O>x znxf|rnqpp;<9LvQ7JP8}e)66RO454%>g`JWCH9NCT9JcJ5`dW&H-z-2Up|B1K?>gS zH`}MeczBaytjRt9N1!c9LRJsdvdAMv4fPG$lp?B zT=wtm%z~eKB+%tU*SL@^3m&n9)!SzV-mM?jF2<@iNj6gh5AU-lCZt0k-d9gtP^aQu z9k9+7K)l-)9DL}T3J0Xc=@&@7o}gviV*EP9d!v%<;UfnqXnN?rIVUPy&>f%hT7E6T z$6GtZaQ&$e3E)7BGqDM}xF!)FZ>D%)8gImScx%vnuoC3g>RZVhX()hhIP_6$-63MU z4>#P`KE@UWHZ~X=#atuC+iw zitSg&!+WZF!|Di#w?+Qjidu+w%e_GHvk-5a$+T;4a-u*^4KlzX?FCxbb;$9-&50q8 z*FJCd!_Qk>O{vVUcR?>Gj-kxDM$^pPkA0cz5bdyXbf_9^Ps+ zA8!fr^Xn;YZi?hb>qX?m@17>cTR7Hr5&Q2*P=DD>xx9e*a3bm4GE0Ovebx_1VFl`R z`7lsD_I-K4pX%*31MertcK-8ui!=4;QarpLC#)jy-@fIAN{Bri13tIX@C^%;rzxU4kpg!bRAOY^t z;*Q6y{+4QskN0*!W*ZG-JiO1)eApA@_bWMSVSFt=%6{b6)4Nr~cz^Nycxx)+An@-~ zi5}lfjJJ{WCEsXAu35i&tLvLfmya+(AAA0y|IYu$+UN0>6V~MMma+d@T;1)8agoMRt1}$FD)VE(KCz z(>NJ!|Nl4nuaDgX`F$}D8LmnZKwW+bCB6*#PPnFc!b2c}r}PNOWfhgua3`)oVmTZ5 z?Bt7QeFteQQKD9i=@{3E|mQw$$( z@3rc-4uj(08!hf##EbB;fBF7jMahz9T2~nl@7**XRRsCHS*QQ#Qo8`!MLO`|P6{#J zg<>WL7L*+UW*6tDA8jJuASJbvzB?J-o%MK=dg%1gLXtT5_jpU-47^{y=Z(ei{=DPD zN<6&l<_~VSf_R_X+~-Hddq=!khAhPU{LgRG3-&~TC+oI-ly~(6oH;iqHtvNtNSCh~ zIC7YRilt?nHy?CCzt;BkFPX;gASHR7hr*d9z!WX+#?NTEOdI^_%`b3JQ?8!z@D`%^ z5F*HLMEoiXKc4`)1bJdI2N2_J!=I6=eSMO75BoF!2h6~`?bh?B7~b1Id#=F4J20njp&i8A->{8D#hZQ8E3ZK~Ajwvn z1eg0ofh-F9!$2)hAiRa`LLJ0AUG!{A@gWLYeLXF+JlX|4JaM}BHw%9Cu826sTB;}k zj?&`D!RKC|b->5_1z_ds8fHAai)lXE3GzGFC}I7@gda_P{v_*l3o+h)KOeW=hjb5&v8}7YX$ekPg1oz$+`WFr- z?{z`1c<*`nxEjBDKN`M@>aUOh`LsB9IjQ0lrZJP1$uBZ9XB*>4oZKOXY zh9AAqzOB}BkQncL6$e*lxc5d`TIPL-gSa{2$u`rzQCl(V@m6_ApO5P`TR94o{+s{* z$ysHHbR@b02YG!>d7wJv?9L!x|L0mMf+S)*z0@$nrh#4ASb5 zVu=O=ctJWxDof4*FL0Ffe1Ewcod0uLYrzo;`ZY)5%~vxQw8l(}uUHiS5qooD+Wh!F zaZpc-bKIdkb;c3D27OQIuH#l|l5t$*)IBejF%VICZW^Z$-Jhq*r*M*$8` zGZF52Uf_y~h2BYs_m8mVeCKcq+Bcla)Tir$>Ro+&>DRy9|L4^jT;r1~4%XA+9xk%x zZCZklw|~n?%lvJOhqoKehc7{Xwe1oy0p z1Ja*fT#epvyn5E-ZSO&!583VmGAe&BNZ&sL@6Joc$r#>k`L#@Vcsn#c+PnAI`=`mr$e)1H4f7SiHgM%?UJq>qnxYu%n}>cNbM_ez?N7J~f7)E|ZfWC)-Qg%7Hw z6p8UBsedg3D-Q#cfz{3>5_B9+l+wPRw)5VsACO3zbowZ5%HaEZI5Btz-W@@8|Lnb8 zEQ_Cmi}wc2vDFaok2X)6se5k*d%a@LsUiVbd7QK0_&okQvOJ%MV(`le-Yb0Yts z{Dw^sZrtBoZs>1 z#NmK6exf6MN;L{ZqD<@L^5Hi~&DjrIyAGi@%TP9#78=|s^52O8e_GsIsgu*&Bk<4vU&^+M0Y^C)ZvX!j%||9deovLvr+4-7qhqad+jaDb z2c&g#rmD`{CW6&WmB(JH(NTkTIPSZB*?HD?kR%WKe3U0#jCDIj-TzM_&A|H|>*YBZ z-ix@zIq~qmptk(r9QcS8NHJVT#e2*CyS=&)Z>E!^mNmjRg6vR84AqaaRDH*gLu@*q#{g$c83sX0CY9Dmm1$iH<9FZ?F#ts+?+{^?1J) zr_aZmwA~-<;T1b@c`I}V-n~uf5*XgM1^N*@yp^MV{~|-YWrDV}HbcBMqs->}K)fkC zG8Ix*MFFktWclmx>n*#!XWgVgyw_J7e19HEK@pK%cdLInqa3Q=cz)*L(=w_m@R zA0NcKzuUrriucjSe3WYt@ACKLW$NpqKwa*&IE@M~P&07n{I%Uf==Omj_lO7z>M>+0 zdg_1+YWitR@IVy)fKLW?zS55Z|JEP%eu+3z{0mKg6K6@&AhMbSWrd53Lnb|c|l z9qIFXzWX2hW}HrB!2yYFMh*I?RMCOeAc;@90(dp3 ze|L803poF;+-%eN2-cw3s%vA7@C?$HVSl;%98sWogKW{O3qIgdf8j|D$00Pg?uGKI zcnTV3`T6475N9;Vpq2H!9DWD6d`>`1;Z`vaLW>i0m>ZYtjo(2c`tot%J@B?)2Kz^Y z=7W_WzxJzYf-#5qQMWs_>lE)#64sQdg!jb*dP(5X&xc!HmeNs!D%2Z(yV=bC4zh|q zA3swjEbR;b%>S%2@E-iscoD;!?J5sH9^QKHXFhd8yoEQj`cUzH=aeMf5d%%M zxaTUGQ?X|Fc)yFhc7T1F@$mMd`JfQwr|>@AW_+Uns=21yHJw6?_vFZY#ocX*VC>lZ zd)z(5cyqPw57@f#$*jj)vx7b#RvxB@xBt2SFNtLa-XE$m!ZEz}J$=oKhj+`uryP9{ z@2Hzb%v8M7!meH11@Sg*ju%}k83lyi4cRPO?*o)MhIHE?-X4@U$D`sXsG|&y3Btb98n4mQtvyh%3n`G{Rm6f^c`|38U& z2Hx+J4)I`k2lQU&!NYrHs)5W9#QVejuGEJR?~4aQ-@k%*|86dGD^iF8N33pL>qUHk zhsC^)xz0oA1Ty5N7E3`rKaVz};m&A9*X7>1zwz-_stndGEEEGZw76yW)%%=G@bQ-N z`yq15fbsB_qxqOikl#atJC`3k+*?6(gqPrjJ-c$3oT^ughFY0-c8|1sDkijxkU z|2b#Wpw9|CFR(}Kr{OhXcs1zu94@IMSc9D3%>DfY)*$84Ja& zr!0e?e890U#xaL>453kH?Moa}D5y;jOWL~4&S>5{TOL6n#Aztp5_o(iUiu@xjtJzLc9kg6j#{~p$q0Hu2(okK`UERwEEUNqY7Ns zSC0Qn2kD>iuv30m6sXeTG79$=uo&Xwz2%soUe#{K!`qMM!;&Ds%iogo>)rU#>FIWd zTVBL?hoL0idges%=xc`ZNhM;uZy8+wELJ-E4@ieu(dR?#@LLm;tUq`oGw}XY5%TB$ zKWYbAe)g3x9^U(|BqvotysZy@lBVLVXehsQC&c^K?<>2Ddm}-%SYJ=ufDg!-w^!#U z#Jep|s;obWfb4f*?X}s#>)F4|{{@0fi_18~KmaZ7&~NdDmMie_7MoXGa_bo5 z;hj(OAxw~8LwB&kx?+BGmxEKi)CXY_B=QWrN8;+#vFd$g@S+eN-cJSl+U`TV*Opt|dQ8RJYsL5uh__hAWm7JA zFWqLQ4NUAkKH$fbduDfb4xveBta1tyDJZbrIbvt*jHX^!wF@4=ACL_F%KH|nh=H@T zxDhFP(?AV;yk#_N8eiUIJiHBPJ{Az<_r&eI`1TNfH2v*OPQG|zyf3%2z7?#B2c8R5 z18=`0p8u`tP6annDrfzG)L2ZP5B3$C>MCOYRB!efcn{mR>0x-wKMWGY!~2d!eXW(YA z--h!)-;5eGInR4LR)h3iwCCg1p!nYj3GuK7Ii0WPdkSmNz`~zpI@BE`HNL}Q`jNmc zvEvZ4pN>@ADtbxO?=1xJYsog;63qH=Fb&7)B$N~;+G^I z-VJxZZc2rCFV(z%r4`~Wom?)-3h`Fz9Mt=07YUa4#{XC(>}S4xt%4FOc@6 zQ_znKgKJ)9I-~6See+v>;xBJ4RzEVWks=DXX>q6K2%Fzpjeo>0mF-5(Xw-U`q z5mumGL@A0h*5>g8c4{Ui7Q>5<=fLmbhfA65}22YagpOkpMQ? zcNUUO9^n4DVAY=V5DC8{U^46P|D)H(m1P1#lodWyyt!xKJwCM96vO-eZZa<3cSh%t zvLN1}Cn}h!cyHbOeAh;Z_miO`YBA>`!GMRV6*}$%7F)!30f@J3(9H$wPE$~`V$W=| zEEn|G%O64<6?<@-3GL|nlbzk7fTjI!TztUeRZ>Ivcpur-XESWUczCa%`8Z6FUnR*$ zvL!+cRU9(@#bQE?_xRD&$D=g~V1ZXj=0g8gLcGI#dt3VTw$J+NT@XT_4`HDkiEZOK zRJ^%n;QeL85@QVS(w(m2c-6c1z5jR~#C!RP$h|EPZ^fr<{F@=(4s*jb)vrZ@fWqb0 zWuJWjPuMxFD!U+mp%B+iO|jE@0Q*X1MO_-< zT^6$*?+gw4d^~$_D<&l5)PLvy|9N~f@GoEu5}r|mev96;#A;CTp=GjoHHh;uU#$nM zLDeN`3!lRpv`fIGv<41HiX3wyUe!f_N*TNGb56cMV?8gArS%Z1eTsbPT{Z~lvMGXPuJfWT{RZA@9h`-M=V$CoF~^KM1dYH?%uK| z$a5`xy!V;zTPF63@$lxP`S2si&-c3)BBdyV8hXkmrezc3O|Dh{ItSvt{kBdO0NGp&DsCyxR^f5I6|&Uh`nWh>Ca3 zxxCN05bu7@XtwdG2(aHrS8k($FNn9R%@^1@gudgLR$|JephGnwCy&2$MiWNJbBlBF ztM_WjZJmC{ML`-ZPG^(1RTc#w@A3DSvqpOu4{vRnk52^oF%NxI^?5Idnn$LHyu440 zciorihaaYrfln$YBwQ99#UuHkv()9V@I52K_H~Y`(t-uVtzlW4tV0iO$ zo|eMH`^$kBoJSzu7unBuQ#U6YzS|ck%1o z{7dI4Xo-$(>85w^^%gDHMPUW_cwZenX#FWs6xh<@*4a{wE8pYet=#)jvS@_y@V-p* zp+Jyd(X)mZrX@mX?;1xQ<{o0a)s`(gS#~EG$iL7#Grfd(K&p{E7-3nxb=KqEDMX)- z(9tHA4}U&yk;Fd(?K?yWF>`g~0Lf2du5{=fVG7jnAz)My5AT!3m2=EI2~Kl4K}ixdk5Q8UNHubQUBcpo{JH~gde6c|X0 z$uHeV$NaDVL2pC3<*dh>M6Zvns(y`*fA;^yX5c+1BR&PI-ooEX6!7rwH#>UJ2I6hQ zSF(kQckR$b*gDuj_PsYBYf6d$2GM(-m8SUufkz`zB^EE z-ae1e2~YeEGKN3n!c8Yp;6saJHo3m1x(FX{gNSd>YcDb$-qAE4x&--+sFWgNsedpkVIMl?e{1sblj_fBKi-z~`B-y(MTgvmBh=Mf(HVG? z&bt3|IWd=Xi98zuw)Hzy+Z)*O5Y@#Ya)=<@Dd1SsA9^%zsXW~C5fyytT)dQ)6<3UsABDxJHVc>ebSU!|>= zj?el7(r@zV^Wh)PBwTcudV6b<$p7H2G_6_j7OUQ?c9_fI;cfFpb^R`gcl+8mkyN~m z$G-(OLA*7;t>gP#7y(v$3Q8t=`hsWUFJDGm4WUv$U-xU~Qqbd9cBM(gIHUfr;u^1O zA zyaV}C^xi?dQ_4nvm|r5E|HG0Jn4T4qW_|Sz3!%?PdQe|ZhUk(1_W%E9%4XbO!5XyS ze`=62GPe0ER)bcA@v7m~pfhe(5sP3AQdjGhZih8!^{t+3!Eiu&ts^zB(mDbZnb|vy zc=&;Rx?=tFOomWytL_DJir^WfiPmC2iW6EZai!Vp82*5?zUY|o_G}SQO^aI=v-o^V zH~tx<6R)#_vMbqfkL>;5`X8{C<|Bq6zpES%6Ly>xK+pJPB(G|iAUra6fAs9}{|A?Ja6Ma4&3V%Gf^U9z3fBp=-$&FwBdByIO$vYK1yzgy# zA)yBG7BTB8e+ltUbiQuq1o5tL+;TD8J_7W|{J6nt$k8bT)*eL7)zgM!BF z{rYWfw-ef7Jz2Bw06yMEou#$`_e8)eT3mMcjb(1F_;~M;99gCIhVk&;K=a{Dkl*Nu z?h&Rh0_bCzC&6iNi1FTHld|{{#Jf1BCMlw>mhi6w>E|BtF;S;k|A-}hr_)EkMDgOk z`~UN1;LU!LtcX=_Nv6XbV(JXXlNQ2^cisGwh!hq!~h@8jlCUY`ae$>rOohw11b z)7F1raV)1+M#&w($6NcBw(>1`#=|?A=0lSpzsGBmc7BophG^QY+ZA#30E;84V$=49>+yjc}9e`0uF zSY)7#hqnv=uz)_qyET9%j*7Rg-CYwyh_`HSe3$yc2(YEx?`gpsU*O(U)F=S=-j+-E zzm2*E=l^1_gcYlu(J#4LpPi=go0GHJi?l9si-NDTxKvx;hEW52yd~~NE)&*eJiOCs zK70$O(OybX)5sieH2HPc;P$pA`mJ+*TpgoRlp50jZ9C?F;QxHin!3xoAEBL4NL2 zcg9YX@uO-5ewW3phzF!5^IwJS;^#oBlK#ug4mx&_oE)um>_TRL2T7+78QtXNqXmB+ zu?uJ5%~N64h~d3;bBiV(-u5@A!+9azevNDIyn=WeJ@ND14Dnu_S09qTIRdE1rdaGY z^#^gMc@0i)7(y%WOn%#Wmx3A=D3;oKIiWw7#)jAl;NxxDbn(Nh8^QpKGrm%KBkNzj z|EHi@a?rMr@$fdJ`B+Gh-~D&?6UHY5&^4EeuI=_B#(S51uS3?IbRcoF{J6a;}Cj+pC`=!4h20VqPHU3*$F+O{N3Qk zzuf;fkl3Dkw@DaaahHS^GG8>tuin0MNe3@JVm!QiX+As%^3#;p4%^VmkEVeakC?)V z@fPtvySl6-9kiIO{E^pAJRp&5I0ECVf6RKkN!IlFu-N~*;Mlc4)mwT7-duLdff(L; zC;Zj%@K(4uxLXq9eaVh8MBSWtx9QXcG8~Z3yQdYeFpdD@^4k6@Klp)17fSgj42RI+ z3cj$&68QeVn!m-EyA!(Vo&5WxLHrBSs<%J&rSu8|ZCadY|LN_o4Dj*ZaokVEX_)cw zuAup_A;|CL3r-y?IRTU$F7Fd`mKbm8mTwnXdrpHj`d`A{j}mWA_ywE$T+*|d_19a> z52DY9Q%o*%Ma&<(rDovGDgSF6!+XEw+NF4Sldd;T%0RrOcREH<@orn5BpL(p9#v)% z*#xWiLdT7tl8*ZUZGVIBLdNj?zsB|DMYkxZsnfD8bt6vbdb@Myx0m2ICk0Dv8aE#o z0s6GK--fzP7kKdJ|CO$SE+$#*4A*<-(R^qS@N)IIy>|7<#a98PFh^56W=Xp{c`o)4V=7tN?a!kt{^)Ecw| zUXYdpc98ID(DX({-oe&<-QRuw%$=|Xy;WFoeKB>3ovmhahh7B8zw!N@s$~FRGuT^q z2pvLg)|l~~XrQ2qF~|0#taL&>W9Kee&x>D!?jL_|@m5I~c+leRUT`#w3deuMPTkz2 z>`rF9M{G6C$0R|1Qd-X(s@C(Poe3>E$g8h}8=h>jT@TYAW`f8#QPkoU9rOPw_T4s_ zp|ih(OsCIB+qsk@A(#I=VijlLEmX*#gFRx8Uc0Z2hj&+i@3K*d_kQwtb_c}!xg+<| zDL5c?tTfeMzaAd36Gl3cRRh4;=N3_4bm0fmGrFZz>L_UM&FWwJN=|4g_Yb>J3VsLK z`n+im(;8uLn-;f1s%vz;IX>Rqe9V+@QjCXpGtI|ag8cN)1qwY86hMcc_a(m?BgVVF z&hli!;!N;u<(!dfapL)Zd5`mheBa4gk9XNS`h0ZkF4P|XJO3-pz*}(th!ckQe*RM{ z@$f#ne`xmv#Jhe^mmU>wd+7syB@plL>#UNPj3U7FiYy*K)&Nl06{Tgpb_lhvy6N$$ znu2Ee-QM_Wz7txVrR6Vn7awn?KB?nxtc5`(EpBX27Vj2$e7w`S`KR62Fdp7NdjI-J zCCD%R-GW0D3x1R*DC~4EiMWF_b^o9=|Sg}OPRa(3I)Hi-A_Px8xwSp+c8 z<^R6vnLoI$>(Oz0-4Lqj`ZVAMprC4oE);t?C$x8J(MV}AKHihPd8-$A3xjT2+{XBq z9Pj7jd>Zexo-2TGoHU${L& zJpX@ul>4DXYx}I9|E=isv8~bzE&F>pvD^&2`4_g|#PGg~pjvo%*Yh;BF;SPdgc3uk zcrW?V@aUDQhVD0Un-6VUBETsn!3VLa{vf9GfbDmE_?j7zjyKmKl&g) z>*NwYV!Z7PpIB6nWq~af`yUU^C!YV0$2bnwNqnF6c(IStN9Cz_pYOQ6WDUfdOV0STo^k|8oyXjI;cfuXisN3< zsy&1rek433{g{Hza}Emo-Q|c@%)M{(AORomC8HvBrTs#nk``AyTCo2;FFxL5CY~{^ zMU02HJk7^vg8XhiPruJL#D~^@^DrF>BgT6pC+JIrc%OCKTDXXw`9IG&s4t2%>j$K; zEA;tbb_M-ze^+mnXW%WSBgll|ec~8k!o%A%Xzc47i1+oxm^$j_#O3CNg46@j7HPcC zfkp&qG!cGQWjwrh(R>i)S0B_6TfU4REwJ@GpO;FExBQ~>tW0%TAjWa* zU^*T1fBQse=OK#StjD|Z3w=JU?;lJ|`uqJqr5SjO@+dH4cz@lOI0p~!g3N5B58{2$ zP~3@%_nZ9(GOQrpnKhZ_bJs)wl9=f7YrX-%tZLeqWz7((HQ2pltdW8`pEB6V`OOg> znyj9)=`23pDm^=oJrxrMgS5CZ^X3!l1o821i|`VX7-KxV6=^<*^1G{EE&cu|Kf1(b zYtGy}V!Y$R$!o%EVfA)wZfQ-TWB!k$Z1vkPGW+NMlXUt}PZXiPoX7!Z-EpQXB;L=w zeY|bFjl5;N`Ml?O6L^pC2Jr6Uwc$15UCpb)E5$3o%fd6k^PcB5&qJO{o*O*bJg0b~ zc!GJ{dF*&hdDMAic|>@~+~2uBa(8jJaMy4bb6?^<&3&9ZgxibTf!l&xpL;pCBDVxL z7uRpDQLY}Y=Ufe3rCfPjXSq&t6mjHoq;kY?9N_Tau;(!6Sj(ZwA^Io6*-x=Yu?Mrev)i$ovg@*|v&*uJu#?%ovwdXi zVryZmVJl|4#CDqPI9mvt7n=i{1)DzGayCUa2{ta)->jpoJ*>}J8(2$O^H|Tao@5PU z^<#Bm-NL$&RhxA&>wH!|RwkBlmVTCYmS&c6mI9VcmL!%4mLL{47F!k*mNhJDEHW%Y zENsk^%!ACG%#WF?xWc&nxLmllaBbw$=32}(pNo%+iF2H@pR=8_nX{a;fHRXbi8F#T zh|`VJmeYiD4W}BX45tt$8^>y7Kq`7?Tx~0n-W|Qzj)QNgiD$9&EvbM|VyU_G`xaH#ajI zlW3Etax0(50MdY|Cy#&MKYJ#WKrZereaJ3A0o#v z6)oMo9f`qI-5igN_nDWg$_7(}kl+V6RCP*Nryw_IABLSH5 zlG;0h_+!eWr~WPChpD}Hk~bp0m~ua|Yb)Y|sXc~yuMlrcxk;;3BVL%=HJW0Kcw)-6 zy4n))z?4f=SR1kzQ_i--I}mqFIcZv^A$u_8@a2^{;)bc6_ht4WyD?=SzbOLQg{d8T zzTZb&F=eMwIf}So%J%2cJ%}@=wmm(27jeRr&FOu$h$E)927bGSIACgvUi>7o6I0eA z>n9Lqd59$|7686S2e8=6$v(vK>?A`nmOpEvC%oJ&r-PVQSN0SS4bEDU%y# z`H-!cGLCqjhHSxdeblL>*HLd`>S#mSSqY=G!Pl4O8>xh^Zs0n4+$?BPy7pE>9v$FhyO> zK^9|*I{YHan4-=Kh!Uo#r}mIVn4%tXLKHDYJrjZ`V2Zkhj>uz*y5oq*VT$_hA0mq> z>Z?-7LQGNLEJ0*2MLmd*NMnk6ZW)on6!iunWC5nA7p@@lF-5(f0-1*?>g)W7B&Miu zKO=K7MZJd@k-!x7+EzpyQ`B275iv|rF9k$IY3k1%YKRD?s9!TegfT_^_zNP0DeAW} z5J5~)KP`X=V2XMZJHk&>%6ERMzeR3h>UN7h4{`%jC0P|BNFk<*y%i>q0!-an$F&Z* zj;SK9`NK#)rf$5<=SQw#sxVKw3CY7$fnTf`aurk8H-8*Nu3##kYhE*Q8B=)!MF6>k zsjIgg9g&Nex)LfsqDy*bmRi2 zvMjX3k@J|!lz(v&Iftq9KlbJ$XEAlI&UQYMfvK};hW1E0rZOD)N{};{N?#Ip9661t zGfZXQku*%DJ)~G7shCQ=plX4nU@FDWH3d0^sZ*>AvLB+`@; z^$XVsAEu}u1V(rP+zQ%A^{8n$oKL)bC(QK_N>VZ+qmr^bs2E2chFWrQOvn0lXdhzDWD)WFViR)h&t z{c5U($Q(?)W4$~FAz`YwDP4j*jj5gsPi)D*G1cvwbb|Z~Qxv0768R^l-g5MNl7C?8 zO}lds`8%dMFBvD3r!dtKRM$g9XhSn^j)wcUFDlst~9 z7YDtH$X_t^JW92X{F$bd?`lpsBSqNHo=G>Tdg!KVj<0v7L?N z5llU{UiFMTjHyRUoN~z@G4)_dZZCNVQ_Z#3A>=_!HKjG?kUwCm(Ivo<{2o*Hm+SeF z2QbyZa@c{~kEyzr-)G40FjbooG)?ZqRE_^l3b_|k)hn-zl6x>!#Tt-A?#5K*z}Ocu z1ydEd)~CsDF;(vGeumtIse6_cU&(JURmLA}L+-@XU6N`SxdT&oZZ+wXUt{Wa=vQv? zD@>JGwl-7It1MSg*)8%Ym!$j>oVxMS}+^0WWm|7WZ@ z_kYa>?*D7dSc9Z?HP{;D@TZMjcx#Z=y;++J;2LCNuTSk;xCXf*=!?M$cn9g{;{hUr z14qG^%L}XJoC85_PkF*>)gd(6C9#XtYQb6kJAc3cRY zp~V$HxxG(D7XKZjb#otvW@a$n8ss*b52F0M19v9Jz2ip>CnwJHbdM9B|9`mWuy>?X zF1XUt{vwTz@Bfif^-eF@a%k3Xkdl(<^KrY^Y*oO?KPO1lXW&h3(=oi)3(x1o!@E^n zb7?WeJEeWdm5TSGrG+XJaEV=J~j`nz9`CH)6c^T(4fT%{mvX*16y4eVOt3WII5xD2uK>ykh5caU7T z9w;xo&vk!b%e!Z@IhU_=R=~`lek>9beI<6SMQ=5tU}y9jEA>9&BrZ*{0uMIs>W#vpl{op?j|S`<9#DW z|JEoe2h?3O-p5~kpRk!Bt!_?*JhA|FL)H;Z$|)}A$aD@8MH*yQ zAt_m!Q7ZEk86s0M&t%M0rYIswkwk`MDwc`{N}7qvkZ?#8B^iGEXrK2wf4uwM=fB@M z->dhZp38Gz?{(k$JojGrUVE>-(`L!AB69xUV)0zIx1Heprcd1RORa#m;klg_3fSE{ z;pWfO&PraWi^d%s?uiVp#qQpXrYGa--RX~a6k5kqocwsL@4hKgAb>-h=~JozpEprB zyd(~J_EznDsWhh*KJQJ5@Ojy&9m99;)D+t4IQlN7#xDKe_y7LuyiIREL@u$Lsd^B3 zZ-ml=_Ab~>!0JJb>)S*Vksh>5$m(1da*1t`9qa5xF0m$Jq|JYF!(f*C6OF^mz2Jk| zUmj9ogJ5>&@CC%1~3s8r1B&abUBV1LpJkmoF3_dVQQ1QsN#~^5^HS3B@sV`TzI->(_n}ts@R6zcq`O-B@!@1aO}T^<0~WKOpUqQR5BUp95nvjO&8T zUSj@UD0Tb4B^`GRJHrTx{Cf2_IR1%)ds@zVu+LX8Pm31FgdgCqGV>>wIdi z{9w1rv%`8c@ZOE`uHlXdS^MBQ=I@2VTlVh$pHt~)7@qg{JG9jyCR4kINAVJw_a-Xd zclV(!hHc%G>FRN!TujMqJ)Ic;iIAI-X>B-kdbn zku$mC!;#Rr*IN{+c#|K;pzs#cF5$%DUG-sSRyM*rQkob@=B@ibZmAor$)PK+)??AMU%{cji{<6x)={$fX+Fa{>CH~@s<@)TQFZ*)f{cH9d z>*{DYoG9w~1GV%149}a1#yW0R*Cv(c%+3D_RJ_U07g2a8Zu95B;=L-1(=89-UA0C+ zl+0VfX6U>F!rOe3d-1xCFvxO4V9zRlPiXJ`$0kx{5JgI{`AnT(-`aMVwsvNf(e~HZh$uPtH8#Jyp{P?$O zGwdEzvUj^WX)FEppiHz5y!>2Qj=Jf8=K}-TzFB)Gf8eeNWoIIXv}f~SB-0zA&%O_E ztz7`_KFh0s_>sWH3a-yI|sD&FKrhAF(4SFkL_;+^v*;)@@``^*Kq>28Gg z^tBQBR|xNpv6LOXAqekE=Yw8OUNCOK9^3UR2EpFa`7KYTJAu*m^P%UstN`ID>0rtv zHt!xTsr%OLypR`-YtO9ikbQ^E+r2T;o>z_jcz2_9;N@pY(t}ICzN{i?_#_n|!Ab-sxisnq=OGyqa^H5Z?J5;w&q(!=UH=Y^9r0 zUNBGPWKEjrAZW9y&A$7y6R1Rlrfl0_1z6AKtP9GiJam|8nxZV0mi&B@pL;+|sj&QvW~mt?>T zpQCZ7gaq7=r(kbRu-qM9E%coJZf~Wdbu7Ti@1T!jVonnu7=3f+&VVmI?^i70E$VuC zu<_Gus9BR%M{#3EuZ(u1zYHQpPMmsfKN@!HprCE0SZ{~#@Xq@<9cApG8_9Zsvx&ABP zqx9EP80n0B_vRn$R@-`9HjffBxv*Lb#Gdtp1^b{|u6Ff8=^KVK#>E zLF>QLRtHDOx1!mExfSGgD&FK5k14!sbbc?#;@$Ci)c6R(+tF~g>NCRooZpmkI>P(L zq;d{PI1F}-n{po@&0pog^>foyWaNPLNf1(ExUy;ARDADT*uuO?G1y*hx40vjd{VJSHA>{ z@FTakDgz>yEban1=^r}v)RE1J3zGBg>#=!53E>l4j_|^xXq;bX!Oy5t?Cz~|Zso9h zF8%SQ)S-=&-wI~df!05~AbiSn{g+mJ-aEwaIsQ6Y2+I~_4fpHQ(7o4uz4}u*iQ#z% zOVUuGa~6ICkS)^ZeB5R0^w~K^QVx!_a>APqeZ@Z%h9sO z`-Wo}3@`2KVoLRb>z6fe&lVU2GImRqI2LpP^>WR=PfeDf;AibZiB#;nw~BR-q}Y)C z{}MDV?1J1*mQd`q_u;XiZ@cJl?@b=9124aF{meYpLO!r@WS>)1KR$2EJvTjrkiEC- zL)RxIH{jpBHIHl2+>J~r(TE57fp}!U6N3@R9IQb3T>yd75`37-&E@J%i|C#)0t7B8^RKCvN2c&mV@g^TI zN#Pyg7PAtIw_@Rn?FSLw3eH#R$(s|bUoU1UD9Ed=`}Ltmi6snH`d2I|zUmEKPH|q? zx)^!?KWw9-|B5bfL`7WSMzbZ@XtE;jqbN4-Gx<_>W`(>^0gb!iY1m_{fz7+D(l<=H zk^Xp7>L|v^Z;jcl>_=JrK%Hd2yV4tTn8NPcT zWfrBWjJr1}Zg1_R;!Qp=mBRadr@06gZ_)jPNIiu2TSe$d&3on{mx~>97;Kht z=MT+Ccx#>;X=5J*`^zFO7%uAqr8x)Hdvz>9{5F5Z-*VWC6Pe1z_7(EH5P1h-F3xF8 zOmXub?8Ql+yVX>w0sZl&)X{^JU!0Z8h2%s&5LsNHq!fYAd!@L_8K+A(;kO(8W{EfP z_uiP^y)%5!lgaSBnc8WqWB z0`a-nI;00#9;iRjk6dCOuM7==mJ#vTSIekk5vZ{!R2l2Ub;zmq_`b^hqU z_AYQGaR@GaZ2^KKo%LM)VBcbYWjZPQ?i3M*qj81%h7RuV#_mCGp;p#sbmv2Q`;EUr z>u|xzPwR0CkLdzlaBlCY%lg^xxX<%PSwB=>7E}U-uZW2~WT&AA^*$9-Gr7e0J&49S zyyXk4B+t#w|NE$TlMg|s@P6=(B#y;e#$zx^El@uJp&-3aw)rC%^mlm3NFBc)`B;4TqT)<6mO$3UlP@YnMP*v4=ti zd+~2?iI;ON`_i_E;dhXh&{#*>`LKw|zdJ~pRJ_Tj`crss)V;M1i}z2-H@DX#yq9-a zH})aCLt;%>3lQE<-fdym`x6RPADd;=3;MztBcDxT6C}WS@RNnk<}SecALlPnG@CPD%lceIha=&%$v?~5$sTo)4Pk9R3rM>2pf?LXdnLWJtyt5n&p6v84hILcvlE>xnyLZy)rxNq<0EXwSPGcQ8w$~p1 z@}66qs8jJKe|Lq#J9xMLS}fkRZ{O_Qg79vPh!P|7HrN+f4v@_Wp?>RifkUD2seQPk z-dP`*^isHT=?n?zS_x0hm+Jz7&z9#NH9@}KDsE(UISzaNSNoQ=$J3S+;oCY<~PUkjB>#PflXsBrBIqWHX<^-PYv_bP^J_IbOS|In~G z(f`dkN8=CUfB$co#yST0)#Z`y{crxKw`ugh1vo8r!fu1qJwJ!srmH7Bc)F!n9>HouO66h->G#9l<}XvN7d zJmvd7wkRSvoOkV@!U+ESA8QLdSay}cYhI5v?ib-dLCW+;t8}y7DaN1wr)jHW;pR8o z_x_&$e~5}V`BQ2X-s1~C%VP0XbI=GQBD`PL71R$PywgIhqwXQRODo;w_Ad*AyE+HQ zty6sAN3VO=>OPY|XI%H!D1$DLQ2AwBL%Rj=nm=^0avwHt(=Y3rD~pKG4~_FXNXy*VVdE2pZZ2y9R-_Hrw8Kac90HI@g{#8kiwgH$4wb5-m2r5jtd~Xe=hSmLFOIc z@e@3y|c(c@@7{0Itbmi>G_A zc^C4lok@I5ghVuszv|K1X%hAd(l0H#Xv&-Zc;7_p@WIJ%!M7^Sf(Jx!HQdP^2aVIytmf4 zOJni2eEd#-1;X2gcwdmr`(5Wda1`NfrBI@q%o_&x@v;i@*!e=qOZsC8gCuZ9YK(tu zUl&MAlABUvwgem#JAd0A!{$9v@xm>*hX}dRxO9nn3C|g9-d0VKxfd_eAMf929Y=8T zJHg$?>LSexVxEKsKOMv8JxdBZo${m(OSpt+k!Dk zfpfgIsCbjV-b&%EZKx@Q#ru6kt;H&YHydcY|95lZFK=P@Z9E$ZVNmP~_`LaqFXVY* z`lET61cnUycJ%E*p1ox|#(Vy}1z5nb=7&}y_TAgOUEf3eJcy7LjSC#&EYah^=55OQ z%cfb0{&-(U>oCH}uRyi`ZJPuy5I>PKu>U7M@1{j(9`-*jg?T4u`Kw<%z}>53l5K~? zkDQF(y=kq(-hP^V_x9iX|6k^9dixPF{~J*CAoBOCDLtrZ_rgtBJ!sj{14n+gAOq6A zM@@ssC01C(H149Dyjtugj*6 zK$8#>6EuR|gK}-Z7!?2_)Ij6ZTOIX-XR&+GsL^?gomZIYZvX!pTE{R>ejbMA3y$g% zK}h02@m&`DdyuikzwW80 z{vbPrxA>zL1uWi{lY15aAiT}ua@@(h?ehD@8W7$iuP%_B#zLXT=CP{=_P$U+P(eZO zB?(lCg^SO+bpd`w0iN6UEdYoA^YVvT*el5Sg&A7Whlp?q8h6oZuP9py_WZw@Y1uP1 zNPoOp&^k8Ze7B(P81i9UV>S+`Bm)NcMl8uOyWpL!y#r&38{3l46IDbx(EYlgE z_Y&IbC~HvmP5b+Liyjqk4Uyyjd3r1O*j0Hf-d3;LS(uO&-r z*%rpLhQSQ`B^e*$e4*inA49xvNnr4u&C5;4yMPO8_{GMT79ii0ug51BoA>9|%$~K@ zL`aE~n1H+?SFw5DC)E{ce4szxy=WcxaPs5Hhir|DctOk8*&{D$nEz$=$#x!_D1*0h z`7?hrHQ}xxz4-Lye#$Lo_zlto0&R8p*C%gP`TPFAE*0;+-=3VNbnl$!ZX2<97geji zU_p3GoKI~aZ%#av5MQp0+`Sz?1Gq&*!=Sj$5xA+^7xG>NK5yDc;QBY)WXEG&z&AHV z)1%JIECcigi($Kvvb40_K=P`cwwxX?$#;~5#k*Ra@zYZ1e zJvCp)DZIt6ZrgyxTW3(YVll#7&N<}-nfJZEQ~KrzZ|QMsPe^Wd$hGVOg)Hs&m_J$ow-MzN$4_DNPR=S2&x#^KFElP!B6VQU9Gf>+bD=?z z0R7GXDQF#>IQg-3Hs*wG<^{nHSDk&n;V(|&1s=P2AbW3l>vt8Atnk0yl0ENBThU&| z|MqqgGi`Nri8_Yph5S4JpWa6O|C$dn|C>_vAZ>3GK<+`ZJrcHNG3HEIJ&3SGq3i=P zAoVNGKl2soLGhtOk8jD!tNHJI7j0u03M;%$sMQ?sfqnZNY}4@AceHUnFA&(HBTrs92YMROE|x9x%p%2>R^hx!Wp5Z({Q8s7~e zyoc|9vs;SH|99o=n!_?ep}4&D<;Vu)2~xQxsY?$?Ag$FwGd{WtY-}{)EakBP`YK75 zmQmQei_U$v&)_3MT{P~l)ssSvd)T~ZiI3}a4Cs${30lV=ocwO}&%Y4&o&c^mjfK6E z#^)`*#I^Gm!kaX;x%FK01KjS-6dEgY^fZa#dDC3S8PeU=fA8KJQSsIy1=mt|TOW7W zjK!NzPp*6j;q5l_CxFcRMR6WSh^Vbb>45S&*a15(|kp$#?hAu!IWFR5bC3$|_9Z>4*K1g6)p zaYWwi0v@CGL*o@kz_%q2zP5bAUP0bDKD=3@g8;vxak($Tqx37VdytN{OWgMR^B}$b zdaKbo4&me%tSxkV{~IEhS^Kst}mY6C2^S$r~!X3ub+J6S>6ph&ZTR?*bZ96_=)~kAU%$%Qv*c6&uzYep7H?;^ z^1)_=_c=}9bTaQ|lUpSR5Z(fj_<|ieP2SjJhEmU!|(r>%Ftu zGb-M?9|XE6ye-eyGh^|NFa7-B6~a4QZ1qkuZz+9~GFODRprY|AzqO&TTd8W@`ybx$ zVfUt^rMF4IzTVr{@A>4 z-?~yQ_=o;@Uqb6B#mTS6S<0=cj0k@2c>6+L51+S>hqCokgm;$F;oKXS9^%gbOnQxb z+TQ>`AO8RvKgw0qFbl$|~4S&Ac zy6hVP2BUE)UX>Zk#j$xubgJ7Gu+!iCe-EuA6equV(OahTzY~C;h_~;io%p=ZSnv60 ziR`^~eqH#Oo2J;=;{ z@)4y6IhbiI!RkR4MnMIINDm?kSuY+%dXVD$FNv`-@@f;Gudc7E4Tdq9M^0R_@Pzwo z$CZ6kk#~?r!#W2VyTJEDheOI=ngh-|p}8xauzOJ3@9-z)tpvCPjSE?L^t@3vb`Scz zX=&MvC;eSwThThYaq`oY`5k`jI1v#1zr>%*!S6w~(MJwu#omUWGe7Q8UxPpYr{6AK zKI4$Z@I7c#8Eth0g&CTtoSK{ek5chIEMGf9;eDn+kR6LRU;T>Rr3i27%jzW~2=Bw6 zg;(YwyhS{XcH4akh9fI-%pwXsVeZ3@I_(S+_&O^kxVE7SY*Bn|FVtoZl!fgceb&R~ zt=Yluv$2f;mC(4lLs17+Phj(&G>D9Fi=aQ=8fYC8IQfnIex5 z{Ekld0+Z%IG`{D{t!&7Oi<8-HSasS`b zTdb&f8^6q`qVT?)eU}xBcf3H2!ySb81jm~BWZv!a2Vy4?-rpQzeAgZbffmt+;!<6_ z;QqV?rZZPapiT97(fO(_AmH7z^sL+wki>SmCfpC3cgwlm^(h|-FcFPA)~HqR+5wxl zQwqzK4|(**yBV#+0Vlsc!D|)Yb`Zgu*ZEV^iTJz^KAER;J>oW$&ghglRYt=BX;+wA zcFLb+{P{nJ#yXCD`N;A2@fJ%e-bSh34=B8k-40!Z#rxR>pM!Pe?#;0`kG%KBmV33H z4VnKFc;0RGa|(fr);33*=6k_)e+oQGuaUs~_?wQ*WnEy>_pl>t`4J%IlgSPK$JyJ* zz0EsAkiECHXxwTSkMQClY~I%g%4*`u=#RG(T1OsEevK*c}Lqa#SAwxBt%&f8EIZ??BaqtWCa} zQF>6W?RElI4-!c^%5@IuL5BqPy!?*zAeZe?ldF+StmLaVtD-o9;rZ#A{BK{~q3L(` z*1&M&h#k?Zon`&V`TsuhI&r_uz=@v`(}7Ibm)Q8(CuX092=F)>*Z5Aj_+&bE56bB9 zzP&`5{(4X%T1OgAe#{!)8()MFfoQ@?Ao&`<2gxQr%zAUQ91aC^FHFsDz`eyTqdQyW zxif;{d(gBFZFR^EN3l$vnj4Vpsd!r{=*}H)L4LeNR)dEJi?_e-)z=pg-e#B0JjuMn zvn~-75Z>mlBnx4gV7T#kNr8yG2iy%t_JlRYai5>I z!F(J=b}%C+cz^)4(YT#CFKx$yuz7#$lUt>}hyHlWp>+)5y$J7FL7}2tonUCm)@|z&<^iWi7xtbyO#*H{6}fp$oMP>5n(1jyE{@ zwLCq^;g~@L{5Ae{@9OZo_j*EMk;m?GXcE|RhOYsC|DS2?!UFCe91K7I(^|)d&GA{^ z|32PwjEeV>N2|Okyq(t-b7JxC`*`2^D#F|4(&Ibi&53zw(J4m|-WM(#2X>wehF6Dc zE(vvez%lQG*TWM?z$0lutNCpg__@}@+VG1x_+&DcYE_HPyX~9XflOp^LWvWspDcL2 z0h{+(GeP5R4)n*n6|Ex?C%+gH|KrF}B3PpJJkP!wpSO|y0%E61Ib6;W`5+)xI29yr11)&v_l;U9PHUMdr=a z=kmcF;ax;5G#SeXhRk7_OOLMbgi`PJzdo5v0uOBXoI6^&0LS5n?|!{E2hA%=zW1KR z=KY*UW$$C;_SRE04)V&#m-S;WPCjXjz8`R+Kin`&XnTw zzH>CsJR9MCMfj_I>LdKSw@lgl1k1&ob`N^U)O6_j z7!&5e_5bT{;s9F5eVqKFXCLn9<0XQqc{R^dSjI3{%9J|xn>k)Pc&;2?TvQ4A`x|iM znOc6iy4+7;{2ug_wmRYr*&dl+ox8+3Q}MPFmAyydy)I($QY_xAKR(V6LwFyWvfNAN zz3^9cKbbePo&F_$wUe+#nN)Ap>jv*GxYwKLfxO3D&Dpu zDf=kA2ee=EVeyWPx&J5<;VsMjW8eqE`|ZuPEu0AN5c804gPteh`4b`*Rg&(I?^{k_ ztPcqoI9EkkOm>0G%JJdSPs~8Ww+$Uv#ISiksP%5j|4D!k(72J~JzO#Z*u2FSW(2(F zra#_~&^lJ(7XvJz_}r zmO$eyDiUw8i(>O$y>!~))++kry#=j91Sh{Y^W7%I{t%J>?0Z(0bl~&O-(KhZT&5hl z#H!y>{)x|4I{5p&(!k&5@xQ^9X3yj_o3eUPq| zi0~fbwvi+A)(TVL<41VAG#p#0(t8rxJ!%w4FL8&4!x0~YgGpeOcx~;);Vw|S44O24 zGXvfB0wTVA*u4FJ_@B2LCBRNJF4adwAm$nN+WXfo$BQyD^v630t>XtyeigE_!;d!+ zL32RT*R5^%ydMozN3zP6!>}ze-JIDp%>P6D&KtHaXL#OBgS6FgYQ>8OFEjq_|5Ii) zy8aWH|2?RB(1{&&Vw4{AQBO)3s|Vfu9cg8Y^q_5WP5wWT9`u#7q<<@N28qy`291xO z1L38#y5xb6Rr@b$@g5ZMkh?ZyFuCR5D$?11TNI=Fl{6Ly;H@J8`HgQze z6zooMBprN<%{!7yFpqGW0QaJCGZS@FzXp6UZ{xU}JNn8^gZ_9&qjfmp#M{W?^A@_oF}=8~0)9TWWNI?70rU4lX|1obR_!`I$@niwr(L40j!vPmgd3OU z1|&Bs-cH>OpD4WlWHt$5@n*TQy5j`GJ3OSTb{ygTsl7MG4dLxV+;+}wM-U7O*l$oY z&kYV%yF>{cC4oh(Y`zu(-QYk%b$GdkDX@p1Lf^Jx^RASh+&X-Q03FddUBggz{+HOi z`H!retT&}U-gnSCh&cIuyxViTqJscFJX|d-D2C6wu%bqL`g!ev?Obaq^GxZCi z9ms&BKL2w5hoB&+%0J)a-WoSJu))Po=7TSE$Ov2FIt zuy~7nNU`@tcsKk}TtMdS2k)Dc@7@O8_+rsG6a-% zS!orrg7izh8|~^62uE|?SLx@v!iVWS+eLRHUy#<;Ub1s{H&_wuvh!}RDQG^kpuP7c z_9fOnP(JC?2m!XBar=Y)&-FaT?m-elvFfa9^w)zN(K^=QV;-+YsW%)7h4vVRcaeOUV@uV`c->{uV|eE*s&bY8x@vs8lw zO6RlxxvAO>%sX#gvW+qYcS;T4ysyUQz0GUs!VljG@Gcs6*{-yF>I^pThXG8lKkCpQ zZ-CZOkCUIew)24jZ339F+NXcY5TEz?OrpYNgtxTuF{z^W_&Z2U0eyA6_5TM3B!AlK zIKAnkX71kyq`j$lyL}9QN8x>Z@SZ3Z?>w*9Ta6Ijf+5SYej&VL|%@V`5xf@7woQQ7BF$Gf3dYv}bV)L$)PHhrE_Wz~P zIL-h+2kZZF{-3q3bk>Gr^vAmzt-}H*zdk0OcwY%3D9jj5*rb8a`$%>}%3AkI*krWo zMBWPgH%Ph09mh8w_hk41>EIY`b*Q+n?~Mtc>)u{eyj`=R|8sk5Mmc&V7H^jQ+d0e- z-XDLrZYA^9Ju<``ityGspg&++9|(E#e=}`Iy7z9?$uEy|NFZB_(i*`Z zrof}2!LPdsn|Gd0wNlnJ0eYcvw~|lIZm`Dg-bp9-2RodkKi>Ih9q~B%eHdAu!QxH; z4k>TD=WWO5eJw9Y^@dv|6np2X65D}4ATd3?<-~2hkl_a;rf0O(!EyU_6U?5Q|2?UA zyLfBur*!YT29_dNybG;@i!Bk}Z&z=APu`rM@E(-m9>3VD(evy=@< zK>bis!Ahxapip095sK`+J^xv5_=X*ucS;hIo?ILOzC_~=bCsIDvckT-)semGN1Y`7 z@jj2%(T0=X*a6Q-F&6^Z_vzH@5=DI8<2tXFyCQpU9(%oQa)0A*P6!^bxt&+w$MC#| zXskmkrGrx==->W7UC;fLP>F?50gOP)_Pw`c2ss^qc%n zVp@rP4{|o0D>+zz2#3(PYTv&2m2a^hu{(an`EEB0{q-P99S%78y;~tzxf6MU^qMwX znagSX9yIh^vOGGu0$OcoOqKPc;TF3}q{WD44#W2#rcJcfan7Ka$D(BJ5*tXx+jllW zn!-EyR-ZT)Z+-TNwJHd2FLS-I-w5xA@AF=(A-r3A=Gm=V5eRogr9Iex-xbEx2%mYm zkp$vyRyq40=>{i8_tk$#Hb|?8!mYH~+2$ynTWQcme}&^M~T|z9aPYh+au0EFb0kG1G^?f~*f;5H?`Q&hP`0 zZ2)a`*nNm1ehr`F9YDp~r~P6Lg|~v-gLPQEJ^Dm$s3E+C8-&i1c?a>yN$MlKH}94- z?%x;)Nvn%awcK)r2GhnH&6JR@w>C`2%^G!s)iZ;pCdZK5TP{s6X85srx4b>3L_|Js zS&PQCYBmW*oxSs75znuPfzeMXW#K~`mi<)Xe4H1y?b*#SntPIbaX^6%;NG@j-|L*_$Q}OmLEt~s5I(c(qSxJ-_7Vp<*=c(={ z4@g2sHjsI*wfM5?1j0K(#aXIBD-a3;(Fldht}y7axaYU6B;Z`quIZ`M4eV`|QtWKl4@mPK4*Fn(Y>+ymak5h3#4Wjjm`^D=2{p~iNz)&1ezXodocvyvz1?XM zO9V0TY>L&6_`I91eSC9gsuDivwr1aX{VC?}g|Y@^vaKFFV(|{`l^NGSc$+9SKP7KYyls_dNkn)Tr1Y1?n*~DSgb54b ztFF*y@DFpG8VU4%>u7(ouNxR&tva2ddKiH0?F(0Z!|vWHhvwOiBk$gBN8=VGWNPYL zWAh&Cl&c?5qCeiMXdR2)eO=oA6y&O0)jeFvX6yI<8KOP>mOn;qV@Rm0~U zY?{sN%T&wwytQeoyB4!BEnEK?$4p!XD?)9^Iq)v+|IR;{&+7z>zId=-$hfFv_pnO@OiR%>i8{u z-q)4xZ>U3fJ104A%P6kLT|qLjb15lQFJ|}^Boil%b%b1OlAoLZ&oWW*4osNGO6lGg z>V2fKcvt_rmn4hu7Vaw&BJ);x9c0gk@K%?|FI+Yf0PmhzAW;3m74p|x>XfcU9&a&O zd2Fp)Hz+CH{hg)J1e9s23FJP;=KX0yQQ@i$L|Bc+JzcNNp__@#+n2YEHE)3acz;Ce zaL36noJ%ZDZUqs<8DCvfa221oS%|Ms?CT2XqHLh7dm4X(^mXouyB`(V8NPd0UZSlI z@m{?(5ohM^-kzl59bk3LnZlb%Z=VzvZ{=OS1bKva--JRHdGD?LFkinY!h4sZ_AB$L z04Q<8_VK&7u2AF0k9v1JF##e=r*>@2!{*Jbd?+Ax6%npM z<3wcMemJ9x&AajUk}-v!^v8Q1T1P!jehOdBzsp)7PjAV|cm2AE&->g@mJoY{x91n> ztl1eF-rn+ie|8@0QikWvTf0DPQxpy%)*H~7m*(&NlL5@@P; zUo&yF8_0_?9jj43y;{hvbM5>fJ@O#kEOVtps=t^i@)!e$SpN1VIZbyDMyFteP z#LiLL>R>YxTBbVpfwZ%WsCY*V^r}*LKWlDLz~U{@*vY|#@Rk$0(>0Coma`ojGDLXq zwQQPyJ2n7nRV8N^?R0~iE`0wjxsU|zEjTS5nb{52Z5mm-a=-|vZy}t0}yDeQwHQ@g6o7 zupuJ6$9ug3$-E1X9yBN4y=CXutpRZX&_dd_t4-bw-YPnIp@j{(z4bWt%feLT4N~XR zHm?^L13sRe^Q8}C^S&auT~Y5n0aD`RgdTJECSvpcc3UKS#Gd|mQ|cJR$!~#g_WI`p z0?pZEP{|7Jmix6=DR?o>yq!7GCXgl@EF?a_yS}l{?7jksCb9P zhW@8}*D<+o#NsVka^}HOg!fR2%rY|XYkCQv?GfJlxB5R@ofH7SrzigWB;p3Q80YS_ z=OTe5zwbv=61#yT%R_COBx6wiI`dD=3^s4`3d3b9Ith>xcXEGF$pRhh0V!lOSbaAeGvrzF4)jM5H>E55qRX1Sq_UbGF%MspLOrB-ry|?J2_9{*Y?+GcT zgpS+*m{K>i@!6Csd@n1*xrmnpLgfV|mc@1hiLGUl$4pE>yxG+7#9i$9U+RF7a_@d3 zOhDrf4F>Z45XRpB@0*R2R|ufL`JYlp7fybo{m1x!FCqe`ZEX2m_wacSbT=$dLH6Ea zi+3_tl;HC&dsVv3I^_Vv^LC)I4&K2MpoV;V```SJHQmzD&yo3`gQ^Fe;YklB_aHgs z5xcO&!%SE`D5`(!sqyCpYBEyk+nDBkS39`0|78Yp28l+!%!<*304UwWY~GgZ21$Wo z!7E7vfGfg<*|z~XK`N?DX;HipurR$QAMA>KiDlRS{q@0aBBaEzwy)0My@-8@Eo%+? zy^N3kF0l*II!bWz(}|npxU0hh%!5L;UXA1TpoceSKfQ0RgdGP$f1GQ>ACQ=iiOPTb zs>tv?h{=YwI>Zkz`K3Phg7n!XRJ>!6qbVtu*s{-$w_x$kTF_el8{w@sz}hy8Tw*_` zXfJw<@Q!2EPceuOfVnrnpD0LhgU9?<1hotgfVhPVxMpj+K}aloqnmF8cy8Hj*zJkU zd&c5k?rr4p7A`bSdzIL81%GVblgvh&UMkZc?@6?dUpV;{7xw9lUEl%tHl8@aGK$aJ zyS2E*oTmyJOx70(jN|VhY4WT*+GUZ!@Vsj|X{&?ipB5{WHMfFfr{Wz`vd)ddJJT*z z8H;!8ft!QV2=AKcN)IycX%TIeS%i0>2}|uBWd2_zIM3YD(+z$xF=#mRV*os`N;WuA z*$tkpS6p}Mr4h*8r|~i*2Aj8K%D$#O2=6OsT($4#!?mv1ye0PAs@}1nKi=kO9cys% z14`E)JAdH;x0al3aTvzu?GU*C^-hHMvm)cyn#nZG|D2T~UZgaJ=gqW)#yUzm*NXj} z|JkT`M|-aU6yDkKM>b>e{%P}Z9Wyc@@hezzlX>ss)hB2m1Coc1*vk0`?_l$5Y|A3DKzVj;r&Ku%pgdGC$F zTR?Tz$T>Oy2EUq>^fYmUNm@E^cxnJhO`prKyU`66m`|;~+GYgOd~eirgkpDZLC5*E zmyykhR5Z@Sv8H!)BX;+;)XTZ=F)>Yddv5}09fxu9YmiXRcabN6(RW>{r#|8HUfQ;~ zWGAxs);8=D#k3B8{&$v{UGTxFli_)H7}8cpeb4aPZBhT`e>$4-u~R|je*#qxI=jf- zf!u@0^S_Ol&O)pnBw-nC(uu4fr{41IU`FQu;gvgB4UrY(gvt|f?Z^PQUCm44_KX|s zKXC8rla~WPKx;+Nsorj28I>nmC1nVv10Db5s9Ry~|A$Vx$hGzm;3OJ%`hG2|{eA2m zB=7kTG(MC~(OnM;K??I$$-Kqi31pfgykk6NUzQ;&NcC422Zx8;;I)FChnIB>fE^;5 znGajL!GraJBO!W*Kyjt=TJVls;GzNTcI zP2PK3tr+px7vWucHJFR#Yyi9-=Czho=?2y9j&3^9I{;#@owFTnLf*Y)xo_eeVFXqm zPu6^W3VZ&y*z-ImZ!ZywqH*uv*QojRVDt8qmX|L5PJg^j(K@_v@{2UnH9NhG0LF!+ z4+;Fn=e@cp<4X#%_qHc4^VbF;{Q3X%RHyMHW*LU>-sO|D)$y`O_=pK|_V&O1f9$cF zZvG82|1YKLL21m@lawAL#HO(Xs|V@w=X*XydQeUMRcRKa2bmhIm#aZ~kWTUbc6PA< z=n!=$x_unkAgy6B-hXERgt3Zs_$=rFt82Fn=^Zlwqrd%LUv0F+od4~1s~J}g6W|CM zH?VAJacUFx3R2ZVrD$Ry{jDIa&^lCb^5Zkw5hvl!4N8^{M8Dz3UqN>ChI`l?uYy+$ z)jv(su>T)C$jx4{dJDt%Af|rW>hKiR=g=>myTtNS@jm~wbM6b$qLQLb^AXiT&afD5Nqw))m$^WJ!U{Vrz`0j8mG@zS2@HxjUU%M_;SepyR@yrt1Pq;T>Ze@lEy zxWx_Z7RS|n<-_M~WoqN=v#|==J>UIm@EiX8|2ApN|4%#P&;M=-wAE4mC&TE&+!v(I z@=@_VcS&yU1SvA_#4r7ev3M6&Djj%@@ct6wJ@m&r7Of)_C%@!*06ZM$2E=>2*9i*X^Db+0I0+EmBd$>m2DHropZT3~ z`SKaRdw0`VNBZdFRe$GyUMk)xZZ;{D#mN@#YE~@XyaWf8R)qKW8WA=!@4Jiat_2{x z?>d<)C>{%dDrr(OW%JzOk<};0eV+_~1xZ%~wtVjfA}J;Hdu9y)S{!SG4|U%W?YS&4t!Mz{zi!qwBj($mYbx)BGp2XyC1zAihks zp%QL4S237+L&N+Zv-v>xe3}0P^FM8Mw1j&-9Qu2D3z3R8Z<07J z*@5sTEe*&g@4Y3p{$$ldcsq0@-PS?&-hx9bZn(0zLw(l3ZlUG@5OuXNZeXw*M4$Ff zTq|t|E_d1ftaHHTJ!b#YC%vBlFQIW;=bc<&w;X%^U(jFoVDLQs@g7F&V8+QW-d}se z)o>o5xj&};8x4z-&GN=-0%?_SP4a`!+{^Lj|D(#s*k&hW8NPcz-AY>>UlL)busf++z5L?)Lv9(K`0vRyU2Sb_|fBvVnj_8v+{1`yuwR#n-YJm3$%#%=jv_|px>f4d&^{n`Mid==vxFVX|v z960lerCJ~SxSnWyWDhp)JA*o_ea4a7TWFk;Ma%5dY;4{dMX%?Vc+ns4O0*tK;C<UDyVk|Je#6n{@3z%dsS?BmEkY3PyA@BBWID2#l62P zNI@#z8Rs?3DZKMWKXGC4{*WzSS%>iE>uEJ1^M02X7toFH9@$)|RTkk77p;9_+=p~; zSNAp1&kF{?$zuU)7cT1o?e0}xB`@>=&#DpAH|p5DJ^90YZ;uinCmQ#9QT?ZF0oc5Q zj9v@>IZuDQUC}!Haq?3>BD#2KB{yh)9I)#v4ZKIw*&?D4-WTV4W(m?V|L;GdbgJn8 z!2C~Z9aE`hqJQWAWmLS=ExB(~co$Y&=fvX8xASmTJ;M9S+mmDD%?UI9#geTE@4X|> z&CWmahfWCxUhEx19!~U;FS$`N09a)r_W2QdK;0cv!z>j8kbH&^5b_+GcXeM=g(ULz z*0X5beU3xR>%_4Kq$LxIXH_8m@xG1L!G@Ec$B;v`D$>3AJ-eT33gItKINK9f$R4VK zr?xXU9HeFbuN(I3x%huz{;#F2j+xv?A4`+w7AFE!yf4U{j-l{w*yhWD#XElQhSQG` z-tuw5ab(_~e$Ky7emU`ocmY9cX#jLFI~pN0>IQY^e+vvN9{_wI!>2~rdqBopn~H}iL}-6Ai;IRqS$})|Nk1h z>E_=d^S>xn54!q&@g+(Rx@WE`fYpNtGS@?LkRGIX{j4f0(u3}3m~lNqdXS)VFaLsC zU-?|8GU>h{MT`?RA47XF3lER?jt*6UXmC8R{K*=7Voo`BPQ1o z-me$Td$kDRz2n)2@n(egdZ_v~=eIBX9CwGuqsk2m&N#(9j~@VP;+v(PgB~E-IguZ) zs}F8uZM{FNi+zc8SaG_$ijN5M&^Vin*!#Sx*t|D~KdYJdf&O^gp>-(YR|roR|D z-h$ZPIO<0O?=5Y|ofXO}Vdr|WRMQ8K@NaKT@bw&6Q^)wcX{>|WnB&UszpuB5Q1Q-= z2)IDueX6B}4~uuX#!Zz%gm(^?&M`9Ybyr@lCl5%kpQf+45By+rGwDosqZ_>QDO2up z@&I_WCF!({at}CsShFO`P9HG!Df(FckGr=ep4W?~*obiY%ilPj&cLJ7$FO;8wKjfj z`$>Pii_khWaPm9A(Weoczyo;u;?~Ma;&*RozV{BKG=C5V= z4bo~F>u~$fD#`ly_LeXe@5?$$%P739Sh9GrcsI>%lqo@YXBB^(ByUcva>%mmL3nq5 z6m4C7)(>)-cg5I$M2@$xQ0R0?8vyBPXIm#X_JE|$rN5q?(gz~iZPDfC*xma?wUO^P zCL&yp#vQk)+Lxn+&0F?U)od$){str`v<^v}{B+tj6a~EC0czeFR}$9Z^UgeS=i4@f zH-GGw>Q@kdbAl;rZ>g5sYKG^{luctDi+){6b>Jg^oM;6V?<}!5aTMNCZZ1SD-pgJX zti6r!j#PDuBlGqQio7_A@b>V&7+UXlQ=6M4A40v!iuz;pBJD^3OsQ zb{-&njQIN@4R>!}CWW|iA$xC5zQ5!nSK#meKmPOo*t_$1s=D@Z{71$zoMQ?hgp?^6 zN+k=)oFNp7D09ddN`|5$LrN+`At^;k88R(J1EnYxDk+B$MWtx++eiC6pY!{?zWdqd z{_mX6>wf;}x!uXC3T+q(2uY|2zLP%#8ov53#X^3(_bzNQFa}FU0CWC1-A*IEM6~8D2|=c}NecbE`Oe66rxNmzMj8AB}*k z@AO4)M!ti@QpYU>1`mVD3bhg~&wkLdXx*}Mc6*>4C6T{55W5F;C-92()(XOIHH1VvFGJ) zBFp3VAnC-NhdmcuX8IoFn?PS3(*ql)H|@`$JYwZ(co$c?xltdn>kt2uz~cQvTFfyM z;ca$*`omm=_qy~f>jH!~*G@yj{O1vHPJsRJcAjA9!sX6U96k&p&dbkl+|~~sM*6H? zC29`}_2(}*;)~6Dd!&MjLAf9-K;v$_PM0b@jLmy*?(UkV3C82?iq;Wv8AR}tQ)HCuSR6(iw|)aCUe=E2ae z{!nmQ)G(0DJonVhu^(*jno~ZcZ4dmvy{RAAi_QCrM7ZqnVnOJG#*tfFT}MN(dEa~Z z>iq_O##=#_pmj9kB9XyaervNXIe7%lRl@)qhnx&VuJ^0&ReauMF$YF7j(ynnI%SlEd0 z&J2G#$1^Pww%ri29>@rWx$+T$E^)))ZqQ5CiH-fBb=QjD-0sNjt;XBeopZ5ybGmL( z4$l{apU}AJr}VZqIQePzP05B1^Mi+@i{`hh;q(5oZcI`I z;a$OY(=WJ|j>8F?6Tm1ekLh2KMzE%{j=qyd3V*M+ETZ9EB+|8)%6q|54>2s>MRT>w z@)6!spT#aw&fciJkA7%a{x~TTerZvt(8xv>Cju@mB;?b$8jx4)J|~Ok zDt+G#gKmbibe06dh38b<3!H|**~LX)Y7+W^ldqSGxv?G4_PzIf_bcoklq}j}d#hIv zYN2s_S6+Ho)nY$llZX4?ELLH>9+ZgIk%W_9k^;NDN*F(|HwMHx()c}Sx83@wVU}um z?X-^$RKQFMqeE>Ik)@a+1UX}k%srxOEN7~-Y-oi7h&;!pAst? zkMOR4#lb=09kk=uw_t>Kvi;j5`%J^3JF8aPo%ew-u-8}Hd)qMBpCY6mAJY$(?seuJ zceMj+R^GU8OUC9cS#~|{P`4n|M&nYuS%)1nv3b|*J2q@+!+5+GpmkK^^yFdlC%v<@kp{LcIR-kuwc+}^qz$~CkWpSRwNPN%DDtKnhkW80)I;P2iNsw-Ho zmI*NZ{7-KkifnmV@yfH^dkGEiQk&5cD(@`i3~4Oh4^_t%jv%~QT$N z|NiZqH+-cdV1$QO{?>g#Ffr}AL$~)Z*s-l3Nj0P&)AQ91WXAUe6SJ{-_s+0- z2qWD)1C1L#$ad{kAU5ykZ?#TH7Be32S7;rbIQg-5f4JdmEdbo}l^<5?;PZ}lUwqFN zdA-Hj!ldUr&a`6w+EdrS-o0k-?ZwPLAceoAuMWsIMjo!8J)BUW;a$Qb*-GVIamPst zi+ARmgT1K;?{{-#n<-~+gkQQTsR-}s6RPptb`ek@QY2UALJ+k0@!`r7|6x$XHd=kz zuOB?-mpt6`%?{*{pAYox!R9^V{Y3eEiy+KG)^x5 z@Ak%~PO)%)aNwat$Tm8)^ ze-?zx(YW;oXC9tEh~0y_$KLIl37TfO`~N{`9WQY5+p?B_?8S0^khERUDCGwJJ4nA> zBH57ntKiRirCs@=_%}!i%eQ=V;$r?UNTauodr?PyKHQpJK`x`=U6EfupUPWbcz6jG z@5n!d;1Gm&`>#O`3hzbt>(-JG-Zil+R>d`h!6lLQiRW{6!RmRPk2y?+K__3$s^_`= z;QC}|F+157vy`b#_oJ-~~{eYxJXB{g(ZnhFU zIm=s>hWCwK3g4)_O;Rfruz26RSeUyT;eF}o`$ArXx1`MEmIVm!6cvf|Y0_>u-F1jd zkt-0I`+XWXV}bDYJo$d`WIy0`k132|w*x84Dw|YaVDonPDz=MnOb{MHptFm+Z_cMLNDgYWRcpJ~8_$_*L?JT(1cJ2@=60 z?$*W&1g7UrcO6RUN6_#8Q=#E~eI3s_D(@1lLyNI^*B2PwjzoC-iF+7QcrQqibX7oj z&$CWBBNw_G_K67`i?RrW_P;MFuCf^hIU2#f6Y2fH_=b9bd4wJKIJJFwQylhyRBas+ zNJe;%qH#fHZhJIrVle02Kek8Dog8C4-Z#)Xe&gi#R(B>UE{Y%UJkYux#D_oskKSA- zxjmx_7H%ol&sd5-{}VKaH#APqXa3#W<@D8YSLdR|*^9H?TbYJ;InTl|DsPgtojexr zNbel^eF*Om4)vFm!wH^C)5VU5*4ID0FquggER?g8enJ$3H0ofA5_fRMrTyqgI0)v@=w_0dQF zzWhu{N5C==ev9u5Ng%Kdu#f^;Eb>? zN4_nnYCrhI<_cJS3?I ze&Ffynp+Rx^UhdpMp7)QgmosJuPVOb4@iN37UW#z9ASFi?sV4iq))~m=TznB~V`{d5- z?9v(r4TWvI8WqULTPle$dmkaYw;#_-ijQOS=5cVyIpZq?m!ok9&vC3B_%Gf2;XT`D zAvui4dmdUxD^7k-!c_aBZu0}p;4;?$M||Gao;qCq2yavQGO^KYI=XkPbb0uzDCWN) z9ZzQ+3J0#p{q5fBG`w$We%nFiUDFw*jKw>-+mYmp@D@|xSE1#7;ugR2mU&@Nf#u^R zv&;ZE$3xo4Y4tFOZOSb5zuFHJ?2i{1T(bp^E%MiSpJDSp^Of|v`IjKvjK-~DW64pH z!S3G4n?JU(sWKk#9JG!koc!F@Mvnem!w&|!>uwFE;q!iEy<RslTD}W{WdY!s6ZW{ELD=!uwsG`vc11 zL`ppWBmvppdbGdD`|#Q@cts|A?d5j?ut{BM|CsJDART`6F{QX4z|O_rIqGeJ(`Uuc ztL|d+KIu9o_*QbYSn^PSu^QbK1aoyfe@`zTxEOx+kE>eg?U{b-`Hp zPZ2(Et)a4WXOOcu&CIZ$*Vg0T-ilj%guQD2F{bBzp3XX~p6~iunDp=G{~3GmN3%ob z|J5`-=yq*=4Ydb(&gEQz)q~!O?8x7U^q@4BBl8829;CBFM_wE0L6c?E>GSS|K%Nhe zH*awEg+;fczj%ub1GC-IH$J`W2X+I`XYw32f>h0|!8^aWK&-!`GUL!i+|LAIG8#A5 z3Ixn`uzQe^d~f60ith|}{!gs~FTZo^T!<6O{D5U&{2_glFSzqO_wvwRY)dNO&*a+& zCvxdnL7o-cv3jvA)At}kKAm;^{!**+cLlkMhWD-1?K)K68oceASiH~0KS{7hc%O)N zyUCC6&Tu}yPaNSrCpY!W>klDNFZfRGaJMfcp6lw#6(0slg1<_0o+B&Bz+RWwpp8KD znYGp)_HCHFqaQ9Ib-omYYG~ZUql0zq^Ramw^1_RSWX9u7tz#Wde$IoJTI}AFzy^I$ zTkj}*-lQAu?SfA#pk5tU6o)VV{6Doo>6B;dY3AoGL0=u)GAl|&kI$|kwP|=addEvq zdBg+z|}xt_x3y)(%2u`$BCM8&{8qO}RP+Y_E>%jI4=$^5+O zt>gH@M8&_|dnFBTxJV$A%3F*zKpl&>D_^+d7KHZ=%^4O7?+%MQmiG|e!cQ;8E$|J6 z$GXz92mSouE_b;F(sIK<+jQ=mM-TdeK-Y7zBuiWH{8{g=MFrRc5}W(RcRmh6uoI0F z+OBbar~-TbujQPsD|pFxyjjsY@bWXW&Av)NE+<|%RMdO32cNg&Rzkhsib^P75OX5$ z5B}{f!W;9v@i{!q&zsIVBz`2578cER?-ew>>%aJ)qVhJ-&{>YfJ4Z8Wg$u&Fr{>9d z%Gq1w_5B&`2yYgd)|u6bq3~n9%~Z<^KiK`U-)!HKVK9=^bXor{^64$V+g(?7*n-ub zuk#k4!{*&?^>$O2lMvKK;}jzM1H@vnd6y;o3vh5U-u(X~DTzcZ2!CI;oHK zAAjNV_Me4OlOONHI_vf?Brqo{GSSWIGwzCz-25VGT8#_zp;YC+D@a`$-uHGp)Ked^rTuqSWAT1Xc=6R3 z;r)T@Lj;94`}4A?0|@WY?XT~c3WdP&O%8TfLcC$*!WceI&S3yp^Yk;v`vK=&-|&u) zHejXD`U`W?u(!8PC%h|?t`LMP(6}d4E3h#dT%6Pmp(K_bho$G(9l0NhU2dmo9TE30IykbW8U>!E^-T7`=Hc$|nqH#P&`aEq)v3bjHf~Sc~ z7;k$k6suoam5@tUjtwY26j-bqc-v7t9a)&k+Z@#Mf9~KC2w#oyKD2Ee2!UqGl zA-lIG-MtEV$susw;x$S8kNH5j*QiX1I1F0OS!!+?><7fB$Ooe}HUge#-JgCxv3Wmq zt8-h}CJ5)DacY$wZRuCBdDq>NGpTfCJl+q`I_h!qn|X24L#d1e`t-{)vS#pkgZTdY z#t3hn+0c)zP7?FIxQf+gsMq@NW7bWJm4ZC6AV`#NzE2 zA#>jf;VoeHC78lHF(y*c65(y*A)S5hLI|`}ex_+Q;R7e{ZwW9F90oles_~28_Jg#< zo4cnCHUfFo7q|9(z~&wMPQ2@JyC9TB<4i|(R_*o0=B-s}lKCx>@p#9eb>QVkJ}13L zXN&~&_4_$g6!7PN7S;g&5`_wQ=0nfI@p1gaiLI5!u^$hLGX3Jju$sO)a&LE^SsM25 z{LfHxK2|cw{BKCpgB~^BIZmDbcdrcL!0JJU>mqNhLVD2JXY;lRBR#0_((jTe#gOaOZzB zgRehy<*&o98CL#JPvd{Y?!ere7cQ zw1^#xHz|LWunxl8-N%xT!aH-IWu6McyW5@1;H`TQ)ZW?|x>>;k>WzrX)P5NP$-FM< zja+2FrIT3UGH4A>ZWB&zvBTy~oGZ}Q$d9~13XLoOa5>WQEH-Z&@_5?UaK_`!gVwPL zC%=s?#Xs}7N#Jv&P@sAuK5yR*NjaVf@1h+873^&I0}>(di$bI9O{V8f2&S)&`x)9N zdV*$8kPK*eKeWmbr1BQl{>6&L+ehT2moCCPz`?pf2;sf?PW!%12=A27`z{k|gP^AT zn{TR39x(Nu|F>P=hd_B-xP&wt8K^j~AVvPR1`p;po2~Z1<}Lj&Sa`1#@_Gw2E-p5< zqUgW8Af0viWa!*WjK^CNt%D0EKbbpTb7Ya-+pSL~`!et0^ZxNxPvm3Bb=aED?K?LN zpZA42|G29L%b9-u2MzSq@k}K8!}m2ODBs?qPs96xT@5>xclHfdOy0vE$F}Mry!~G_ z?WOR3bo+s2GQxZAQ?7(R(!o$OIr30ngeSbd{~+&)A48yK(H!D(0vYuE+P9Zg*#;11 zzV`V&!sadR@m@1jR}lXB^EWPDV_C4?b?ok~HoE&<+!*8W7DemO#L4fuy4l*VS|m^} zaW>`HI6m*!CGDlBL$5=U)D+Kn8y&m16*2EL2UVG#H{m9Ibu^L>pKgy$rtsFI;ob5o zPmRjk#VeHst9yriez$lX!rNhv=t2r_Dbc7-R%G|qwN!%bdP6X*F1qvSMZOnQAKP(o z?#vKKI%&|A{R8=WOM4Fc(qlHjPxSfg)~ncOZx8Y#)MfZ*h&T0;!S&?wg8rrm5g>Zynzs8h;%*dpqy(nqV=3KmQ*a`P^K) zM}+AYC(@(z)v=PN{ku-azwr?m{Nx53{v^g4^$r1VgEN($vScu`=cA0D zmo-SA*K2j|#1_o?Kj-H*RXssLn1aTcFYDd9ZwUJlySF_h(7NF(!_EI$XdN*)`57!f zl{jw?3G|u=1&p2jgggJQyr%WlwyO+AT%FlFRY%7S(vGYzvZ2yU--8JB)^Yblq3YlB ze-j$sPrbB1QF%Mx5aY(;{rK~w^>T!_OSMZXg?Db!i-(~I@1DvqH&Ojvuv|c??taR4 zNYI^9x%hSn++Ox(YK0UTY`yf>Xn(#nm>D=(`gT3`3eqjQaE`TtApC*GeR=fqd2%H7 zBX)56^ku`ZjK|vrtz!fyzg53P_9iYTfm`KLyygbuxV$CA2gb!WT!VcP1SyGbI!=)0 zBxEGF6*E6?R{H7?8Ay9`5BZ86q~;Kq#^2#P(grJK$;dLLPyEA&_UjU-RbzGT6|xCQPcq8uamYjK125 z&HM1EEIDh9Abg3&JxFd7srSL=ePo>YvQe4w2BZYEjx?P7SY(Gz~{E&INTP!~B z74z8Vg=>_<+mh}}7Ej@?AnU(^W1UItOg|tEP10A#3$;svArc2Dyp3phcaZ$vQ+aRW zY2w1-&Hd-2lNQ4JnAO=|v%9yiUa?Ogyki1AdnR55!jWsna*cBCuyj*_%;BLS(Azt* z>dJgFP)(@Fi5Rd3?Q46t>epfO-r}G#;bbcaAEI$*`!4Tn`7bXgelPR9(%qNwcsrnV zjNs&F)WzR$s+$0Tkml;ZRL?jg130>azneN)DmB0g_I)5UD-wv)_%{@+Yz9k0gh zzx`dDtf%4q_|cy-D(~8p2RN~KCni5VuoB_j>!4do%R6r*%ANgXAT&Jure&FuJJjIb zXW=}GEKU@U-yG#9gO=W;nLiJ#fkOV4{CoScd0%c>p7w280Lr0pkm>2Fw_5u>Ohq%wVRb6kBHaf3-CKh2hO=G@JOj=hZ1Kqd{r7*2_BVh$Vl8QUP*1Y)U1|@C zWdj0OJ*YUyS8_4ZgNkj&R78;#q~zgBXI^BBU9CZ}yg$bqHfNdXymj6Ry$TYaWjz`K z9~OrGu3bR}!4FTRSdLl&SI>wfeIxAoe{S5!C})WP+=|9^1uA8e&SLkVrKufahp&BM zxcQ$8twRYXKf9EB_Pe){z}<+!wZf~$a0etGcl$O0+bgibQE3miJpO%#;4MFVreg>Q>3wwJ&>(}!wyVD{@K}Sq1H4~5?Xh{+m?+&l zb4vi`pm9a#3ZhASv3XCHKY7OYp7D5BqjgN-i8D-S)dw`}0%yfyiM;Pe0V*5P4%7k#~j1r6^mb;Tko@7M`45sUYU$L$$Q5#B8i zRW4I_KbX;TjzxG&cRE$xTC@|IbcMEmt=a}NG<$cJbPj<)?Y?Y-Wn{2&bR|Nh3)j;4@jHS z@P08zu$IbuYfCX77VleC9DYg&Z)FcNPYUl?uEN~{2=5>2>jXlY{b1P+CAIU&>nl?X z-|%O>7y>UZ{;4TcB7?;ZzIUz#TLaEV!zygMv3Y-0?c(44Q2@?C8m3)+3`fm-r38EW;DE?weIVq@-~)<=EdTjA^jv=1>t@B4|xHFx1!Yf zy~+r0%ajbSOMCp`Nc^Z_n3o$oRMOlz(K7@*RjUf)7094I`aSz2TWc`)Tn~r#G3>>O z*qToZPY?tl8yXj__d3Z?4100Hx@Y6$ha|@1ErQm;fs^0+Q0~gLfCMVuzE5lT2fVBH zzS+EZ3;y<29f$(qR?Po;OJO?e=sUw&b7t?q^FO1F`v1>-kon)1rU&(9gwCP%pj%vq zqF6mBea)FRNu&qWc4h{MAw6g?k|n_lxr4OpYwu0lSKFbP_Q;Hhnmr6XY;Sz1aR>}q zPQ?8&CIj25+@nnoErHAN@mnoUPVoPk6Y@hA39SQ`%aHjWjf=Uy`km}i>>ji~I?+-o z_cO!I|I|7T;p7)!TNoc|LIUn033*XxMsQbe)g z{Hu)k%q%)yZ?Pn1-3jAWJzUg=un|FHSd)j$fZax?SMrT;EjaHMvH2G#8N2?WRdf2|Z-vWF7Pde&eJ(Vc{ zAsXlOQqhOpgU$QVF712Eq8X2OB3ef~PJRhX4{c3TAb|%yLP|3AqqyC>C0M=Hnp^^> zy=!X1rt#0-2wpCpU875xzIzkA>8nHNbrjzXgF~Vb)2NbL{Tgt^F1k;mrBg7@ekjxbXzL zMLNBq%>NxE1Y7#*Aelc*TmSbfb~n@T9@wJxo65WK+Oz}~Z?9ZsUQvYi&TUyX6yEus zTq>s!-iDWFUJ2da2G!f9&ON(j0|iK%e%MzI0oGS**!=9sprLr=CSQvs;7yq-s$Y%G z`~5pbo-r8#$cM(+Ujc7y-->f?4CHdiO*a4 zb%4F$vSJutM=XEujL&=f4L%m#=i|)(h`ml<9XAE0yl0Ni4oI75c$0~SGF0BDGn>S* zc=sLiHxNU3t1et9OX2;i_y@R!@b+DuH7X_L21|CI^HwF}os7pj0Zqg}wDTgfM+@1)IYF#L zcC|y`idW+y+Z~0Vi_gT(V zfa$w8@j88VZ1Pzlyn6TS`M(_v@3-ZxzEs|Bzud*Jc;~-9s3(E&jv-}Urtn^&KBjUS z>E5e#ST6^Sxj_YD&i7QJ9qd?o?*7MmWO34Hrm1L72A-WQ>EV|wf$(75g6rF`c^6iT zBsK{PKtVLFg8jv1(tYgtf5K9oThyEJcvI_`#K~{b^EF}5NhBa0Yb4LP5dUz(_Taso z%L^~TgoLdN#OV2O;*+a=GZD;xy@l|UzBDJZW`!0LdOd7 zo&}lz=ozMe#1ih)SBJAq{I~8)vjfsr8r~l)a<@}?6ZwBH!s0D{#nDj!;eDp&v3Fe;F2dXI=eeo=t9G#9){Evy7ZbSbo9)u2my!4Xy_$RYj~f{XE%(}x=d%Gk4DoO& zk;Hz)a;;wBxI~E`wxV(TY~i{nA{5;MRCv1zLyN=-FT|M|KNJ3%{vDsFX`7cN((O1WO>(Ww=zr455@E+kl^q&J# zY1;-FEZ#9qEC&S<-Z$Qs{GrVMAV~IUC$fU9^C^4YT)GL0N6$RA(ldi|`}nFIONT&O zp^n_{V+yo^O{g zwFKH1hYqOzm&=KIK*v32fFG_z<0d?oeA6$*=G~klw?pVA$r!LpEK(xG0$3l zu*;yuel_=d-0t18Vz&*bFM>AidIzke=(wEd&gqw?z{&h;@9lKfap{ea3Ua;W-}8U! zw8p@HB0Xq3O%M9)_r-(yh#i-cQpD;(kHq~ec#s}s_KrtV0_j1MV+w*!Y8rZrwx!+; zykZ1ZhDa)ATn6y2f1hT{*&$FiZ$hhn7a5$$TIb;W-5mUR^gPV`fCI$(n;9BEY`$s( z3I0Umx?)W){@};%K_49V3x7%f$Z+%j7+S|9PJTr?!>mCr{J?9kjmWk8Z*hCjkEE(P zXQg~7YUVQk^#?k7&{Un8VXPeU_aJ)fI6PfV=|Ko@HyYj(t5fe%c^`f|ump?u&)fFC zya?~`Yx{pu=6}btQPJxV-WTTjN{ob=Lb-?|LTp6_kR>22_h|kQnBf}aJ>^dZqT7xP zn7CPhAQ8imnzh*5TLUgPAMf8yf&pk;`?mI$L*3ZCO+4k1x2Sw#INl>@9UF1-i_VKF zjFsdETT;D8MsB~u<$W}ue!GNB0hCm&Y29+2j``nmYxeEm%>VTk1Ul!#;#~&W*@FBc4Rxf)&;qA~9E3+8k{Y(2^p?r-6G`5b|kh*Oh zoJ&p!ay&N#N*sA=19y^v;F^<3VQCg%Fy`xYg9A42=Nnc}^W>4>J2bA=xlN9>4V$-c zG)GI$A;#m~gVrI1lV5(W~R zKE_N5jTgY)@q}%+`sjH7e`TT7r5()wf^1uz7>*sL1RQ5-ddHY;z~R`|ZQ#t?n!yP_l~gcpIQ~XyN21 zB2ZSy+0PG_DRH(f^}s)Si;cNe!1AgP9-gy1*J3gL;>7G!%4b#445nXux6@h2yY{y) za**!*@BEK7-7?V6kpanzrUy-J?mkNGLC&Q-YFIt!=pxyF!uaU zR`!qAALoOg(KyYT1rnT(v3t;@jSb6Z-BE@ckUpVx{KUymR)RZs2T6(eE68VpR~GHc&SUx>BrHr{9l~{_Z0*F^6{IH(@9)~vI#k|U z)n2M%@jk-(^CpG&g23Jj6yBG40VR8;%(g_?lTYJ-B@gVh{Br~bE#GY;VrCR?C}1X4)lvZ zbZgTOJ(!&S)uSV82%O`JDya@514+|uw^P#00YPT;vu6x8?~=!QY!`Bg@DK8pL6o?s z_A74X9l_>3c0n^3DvvQ-_pU_i_==O?ZUrl^==1!bRgAwq?i@bvqKmhsD*5xEpOYka zo(BF3vhu8z$Ivw)rl0?V^XaQY>B^zrvj=9ow>u5*uWdhusk{$H#VKR)?mSg2&5iK> z{ocld!u#&QyNP>{?X8HXSqcf725{#Rd-!0UKHTU(*Et|(2sGQWU%wYZ2G{-KKfY}= z2fsD?bp#8sdE4%pUv2S&2!Ek*t=T7vUZi02R?}h?F}lKdyq(cHR^sI6u*WOd>#`W2sd+4`4J-2!>=mDEZH9ya_>ZxP-;)%EMV!u03=gm?7SacHCW%59CaySF=N zcz-z~MyB%KEM%pG#anQL`5=Y2toSE=3U3p6;`C00xAW<5J8Df0p+nryuKZYiC>Tjx z!gpo}#2>oG`!t9Q!mF*lWV_5kK~v`@pCoMF_6zqEmCKRfSv0P2(e5AhhSKb}NCI|YK6^H|_w?CGb1n9&4EL$5L(uV+XL1M5-92u-%yZk5n zVl$u~;$H48z8PXAc18GngOd&~)Ij4L$AdI~Hei1SsV0OovV?Pl;Z~5fXdMtIKih*g z_ZEzjz`=|kp%$CFaR(&Bp71ZjGnw$Iw)^d}Rytm>6S=!tQS<-67JCGpbr2WNDE~eG z-$}#!xAd1RD({6G+cmLxE9~EKg~Gcwuy8qrcd_wlk8FfDna$)%7CSqbI#fb7Gth^` z%u|o{9z#};PcL7ri6Mh{ww=$H?=b^x%SKLKEXL-|+O#)&X(lhE#?{D*T!34!AF*b& zD^tIOGahduT8A}Gehpl1mlTUgK!Uwv--Ay*xV*bpK0NSf`)T-U_bJ)9-}sMMf^YRr zLU;kwKVoBj=&PeW-kG%J@9QmmX?XwqaOpqWTOA2!G_ZJU#?%>bBD~YzEnYz3{c>f% z-u(#g!!e2%j$5!ot|OOn9r*O&g^zElOOFqM1z)D$nnxom$V=pBq;qD#WzEr3uOK#W zi(eJ%2gZ3JHBRD++2^K>*u3=;FI0aSWjx*vXdOm4`Q=I<-|F!m+1?uPA_vTQh0DAC zO9{@+Sx9aj5SUo%OX9guuzc>k!s!ba`hdWS>Q zv3RGc9vGnT&YfOIpztnP(UaqD4LqJbMzpf?< zc{!2%TA}G@W*|&F!fVw>Y~G%q?}@Z*;Dfu-xPAO&<76*v-kV8X-JxC|7;bSAjMm|d zliwe0cEboIeoz}G`snI)eBN_(_4@81ynj#ZoA+~+j?0NlQoz%Qc1w~`iUDVu{V&kSe~hduwNpD7fqKf?#9aZ*1wG@oR{ z{&3>d(5?#A4#wl1i`MZ6CqFKUobw6&Bw+5>(_*y07q@$xeEq7-eK`jnF;y}jsKnpB zB?LroPwDwTaQ8NlzB-az`}Tgy{&)Vznr#{C=g9mY^glgFnQi^9*+=a1{-vIx5zYjx z9`p!Yj%7u9kX=-2J>?PmAz9jNk%oreyW6Y!wI)`9h=)a9UN;S3=G(+Y5y?ZKysEZ! z>>wG4gpO|XI&2Dn%EG2x0qjTYDzA{+@58vEE*kge);`N$|7AdeKh{0A8=9{lKd5Y-=q$_mR zVUeyEuK4!`X&?=6R*A;*)JN>v(1)urc|YC3%7*YZa9Vht!uxIY*9$xd@4O9;&AU=o z0GT-Bj^BX>uzXxvcyr1S_;#gPy+45roT|obKj)i*bl)HH{p{GhkNnw@9^SzXsc{99 z+f;QFu~(46gu;0y8-^H;cNSVlBu;+txTRivBnf!xzqYqie2&Ze_N&r)PiNBM8IH*O zO?13sC-!{(L?9>gUvG&mqOXoMpN0#+MOB$uQkj#Md3Z@oZw91eQ)Y_ay`QPfPYJS zmWn(G3V!sK?}R>lVdw z|EF^H99TW*+rrn6SdbnR7Ns|LA<~1^E_rfe7cwASvk95cQfLBt$26Y3yt*D9QG}wa z5{E$kW_#sFNo0_1Vm)}(-2`+A`m8SPw1-$}ZQqp?z_(&9e1^u2pHVvtHemOl6I%MK z3S9>n?h)&c){%{q-}|kLY%d1#gBZfYxUkZ8+#aO5?M*AU(?Mu$xlh)Fj#un#Kej{5 z`fU=^_n_$G^wp81dsC$(adrh6M#FpV0?P_2@6e&e>{z^Q<4-J^gYecC-~EH~h-qgRi5Ra-wn_xV(j1 zLio9z4?-(3=p!UU#|ctwptp|KPK#FjT|tJ@@aF8yw7SNvE$MHIWRKHmiP8 zZZ!dI$HV8x*loh>-d&#t6FT0_g%8j;$2*?JD_XI6yH>w5&|5UfaNTd#lcE0SuE$$%;a`xB{XR0KCn&@8=l=vc>(J>qYO&