From 5d7305bc5e398ffb222ec946d8c5b251b0184967 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Wed, 21 Aug 2024 14:36:49 +0900 Subject: [PATCH 01/12] fix(static_obstacle_avoidance): target object sorting (#8545) * fix compensateLostTargetObjects function Signed-off-by: Go Sakayori * remove empty case Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori --- .../src/utils.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index f7bda56150b49..79ba00cdf4d94 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -1674,8 +1674,8 @@ void compensateLostTargetObjects( const std::shared_ptr & parameters) { const auto include = [](const auto & objects, const auto & search_id) { - return std::all_of(objects.begin(), objects.end(), [&search_id](const auto & o) { - return o.object.object_id != search_id; + return std::any_of(objects.begin(), objects.end(), [&search_id](const auto & o) { + return o.object.object_id == search_id; }); }; From 071034352c372d250f9ae0b4a136c460d757473d Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Wed, 21 Aug 2024 18:01:15 +0900 Subject: [PATCH 02/12] feat(static_obstacle_avoidance): update envelope polygon creation method (#8551) * update envelope polygon by considering pose covariance Signed-off-by: Go Sakayori * change parameter Signed-off-by: Go Sakayori * modify schema json Signed-off-by: Go Sakayori * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- .../static_obstacle_avoidance.param.yaml | 8 +++ .../data_structs.hpp | 5 ++ .../parameter_helper.hpp | 2 + .../type_alias.hpp | 1 + .../utils.hpp | 2 + .../static_obstacle_avoidance.schema.json | 64 ++++++++++++++++--- .../src/manager.cpp | 2 + .../src/utils.cpp | 31 +++++++++ 8 files changed, 107 insertions(+), 8 deletions(-) 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 0e60e3216361d..8c9dff8ece448 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 @@ -28,6 +28,7 @@ hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 # [-] FOR DEVELOPER envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER + th_error_eclipse_long_radius : 0.6 # [m] truck: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -38,6 +39,7 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 bus: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -48,6 +50,7 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 trailer: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -58,6 +61,7 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 unknown: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -68,6 +72,7 @@ hard_margin_for_parked_vehicle: -0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 + th_error_eclipse_long_radius : 0.6 bicycle: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -78,6 +83,7 @@ hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 motorcycle: th_moving_speed: 1.0 th_moving_time: 1.0 @@ -88,6 +94,7 @@ hard_margin_for_parked_vehicle: 0.3 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 pedestrian: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -98,6 +105,7 @@ hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 lower_distance_for_polygon_expansion: 30.0 # [m] FOR DEVELOPER upper_distance_for_polygon_expansion: 100.0 # [m] FOR DEVELOPER 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 4e14dc4886768..b530da909c59d 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 @@ -90,6 +90,8 @@ struct ObjectParameter double lateral_hard_margin_for_parked_vehicle{1.0}; double longitudinal_margin{0.0}; + + double th_error_eclipse_long_radius{0.0}; }; struct AvoidanceParameters @@ -420,6 +422,9 @@ struct ObjectData // avoidance target // to stop line distance double to_stop_line{std::numeric_limits::infinity()}; + // long radius of the covariance error ellipse + double error_eclipse_max{std::numeric_limits::infinity()}; + // if lateral margin is NOT enough, the ego must avoid the object. bool avoid_required{false}; 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 56ac3d7f4f1bb..b56c48d15df24 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 @@ -69,6 +69,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) param.lateral_hard_margin_for_parked_vehicle = getOrDeclareParameter(*node, ns + "lateral_margin.hard_margin_for_parked_vehicle"); param.longitudinal_margin = getOrDeclareParameter(*node, ns + "longitudinal_margin"); + param.th_error_eclipse_long_radius = + getOrDeclareParameter(*node, ns + "th_error_eclipse_long_radius"); return param; }; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp index cfbd3f89308ac..d9055bc8a1c34 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp @@ -41,6 +41,7 @@ using tier4_planning_msgs::msg::PathWithLaneId; // ROS 2 general msgs using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; +using geometry_msgs::msg::PoseWithCovariance; using geometry_msgs::msg::TransformStamped; using geometry_msgs::msg::Vector3; using std_msgs::msg::ColorRGBA; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp index 909d28ed4bab6..66e8ee550fb2a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp @@ -174,6 +174,8 @@ double calcDistanceToAvoidStartLine( const std::shared_ptr & planner_data, const std::shared_ptr & parameters); +double calcErrorEclipseLongRadius(const PoseWithCovariance & pose); + } // namespace autoware::behavior_path_planner::utils::static_obstacle_avoidance #endif // AUTOWARE__BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__UTILS_HPP_ 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 38a91ac39525b..eb80c705cfdc2 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 @@ -96,6 +96,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -104,7 +109,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -158,6 +164,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -166,7 +177,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -220,6 +232,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -228,7 +245,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -282,6 +300,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -290,7 +313,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -344,6 +368,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -352,7 +381,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -406,6 +436,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -414,7 +449,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -468,6 +504,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -476,7 +517,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -530,6 +572,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -538,7 +585,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp index 5655696ff086d..ddc425fd1520b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp @@ -60,6 +60,8 @@ void StaticObstacleAvoidanceModuleManager::updateModuleParams( parameters, ns + "lateral_margin.hard_margin_for_parked_vehicle", config.lateral_hard_margin_for_parked_vehicle); updateParam(parameters, ns + "longitudinal_margin", config.longitudinal_margin); + updateParam( + parameters, ns + "th_error_eclipse_long_radius", config.th_error_eclipse_long_radius); }; { diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 79ba00cdf4d94..3729188ff9294 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -21,6 +21,7 @@ #include "autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp" #include "autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp" +#include #include #include @@ -1500,11 +1501,27 @@ void fillObjectEnvelopePolygon( if (same_id_obj == registered_objects.end()) { object_data.envelope_poly = createEnvelopePolygon(object_data, closest_pose, envelope_buffer_margin); + object_data.error_eclipse_max = + calcErrorEclipseLongRadius(object_data.object.kinematics.initial_pose_with_covariance); return; } const auto one_shot_envelope_poly = createEnvelopePolygon(object_data, closest_pose, envelope_buffer_margin); + const double error_eclipse_long_radius = + calcErrorEclipseLongRadius(object_data.object.kinematics.initial_pose_with_covariance); + + if (error_eclipse_long_radius > object_parameter.th_error_eclipse_long_radius) { + if (error_eclipse_long_radius < object_data.error_eclipse_max) { + object_data.error_eclipse_max = error_eclipse_long_radius; + object_data.envelope_poly = one_shot_envelope_poly; + return; + } + object_data.envelope_poly = same_id_obj->envelope_poly; + return; + } + + object_data.error_eclipse_max = error_eclipse_long_radius; // If the one_shot_envelope_poly is within the registered envelope, use the registered one if (boost::geometry::within(one_shot_envelope_poly, same_id_obj->envelope_poly)) { @@ -2512,4 +2529,18 @@ double calcDistanceToReturnDeadLine( return distance_to_return_dead_line; } + +double calcErrorEclipseLongRadius(const PoseWithCovariance & pose) +{ + Eigen::Matrix2d xy_covariance; + const auto cov = pose.covariance; + xy_covariance(0, 0) = cov[0 * 6 + 0]; + xy_covariance(0, 1) = cov[0 * 6 + 1]; + xy_covariance(1, 0) = cov[1 * 6 + 0]; + xy_covariance(1, 1) = cov[1 * 6 + 1]; + + Eigen::SelfAdjointEigenSolver eigensolver(xy_covariance); + + return std::sqrt(eigensolver.eigenvalues()(1)); +} } // namespace autoware::behavior_path_planner::utils::static_obstacle_avoidance From 6d9633e2292cec4415db8a3c6617f36c588218d6 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 3 Sep 2024 15:24:47 +0900 Subject: [PATCH 03/12] fix(static_obstacle_avoidance): use wrong parameter (#8720) (#1502) Signed-off-by: satoshi-ota --- .../behavior_path_static_obstacle_avoidance_module/helper.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp index bfeb942c82be3..0f3536eeb4e7c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp @@ -305,7 +305,7 @@ class AvoidanceHelper { const auto & p = parameters_; return prepare_distance > - std::max(getEgoSpeed() * p->min_prepare_distance, p->min_prepare_distance); + std::max(getEgoSpeed() * p->min_prepare_time, p->min_prepare_distance); } bool isComfortable(const AvoidLineArray & shift_lines) const From 847cb0edb08a53a0cd913490981b921b1ea37de9 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 22 Aug 2024 13:23:52 +0900 Subject: [PATCH 04/12] fix(lane_change): modify lane change requested condition (#8510) * modify lane change requested condition Signed-off-by: Muhammad Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> * style(pre-commit): autofix * fix docstring Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Signed-off-by: kotaro-hihara --- .../utils/calculation.hpp | 38 ++++++++++++++++++ .../src/scene.cpp | 12 +++++- .../src/utils/calculation.cpp | 40 +++++++++++++++++++ 3 files changed, 89 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp index 3dc5e7ee62a57..ae0a094e038a4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp @@ -58,6 +58,44 @@ double calc_dist_from_pose_to_terminal_end( * @return The required backward buffer distance in meters. */ double calc_stopping_distance(const LCParamPtr & lc_param_ptr); + +/** + * @brief Calculates the maximum preparation longitudinal distance for lane change. + * + * This function computes the maximum distance that the ego vehicle can travel during + * the preparation phase of a lane change. The distance is calculated as the product + * of the maximum lane change preparation duration and the maximum velocity of the ego vehicle. + * + * @param common_data_ptr Shared pointer to a CommonData structure, which should include: + * - `lc_param_ptr->lane_change_prepare_duration`: The duration allowed for lane change + * preparation. + * - `bpp_param_ptr->max_vel`: The maximum velocity of the ego vehicle. + * + * @return The maximum preparation longitudinal distance in meters. + */ +double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr); + +/** + * @brief Calculates the distance from the ego vehicle to the start of the target lanes. + * + * This function computes the shortest distance from the current position of the ego vehicle + * to the start of the target lanes by measuring the arc length to the front points of + * the left and right boundaries of the target lane. If the target lanes are empty or other + * required data is unavailable, the function returns numeric_limits::max() preventing lane + * change being executed. + * + * @param common_data_ptr Shared pointer to a CommonData structure, which should include: + * - `route_handler_ptr`: Pointer to the route handler that manages the route. + * - Other necessary parameters for ego vehicle positioning. + * @param current_lanes The set of lanelets representing the current lanes of the ego vehicle. + * @param target_lanes The set of lanelets representing the target lanes for lane changing. + * + * @return The distance from the ego vehicle to the start of the target lanes in meters, + * or numeric_limits::max() if the target lanes are empty or data is unavailable. + */ +double calc_ego_dist_to_lanes_start( + const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes); } // namespace autoware::behavior_path_planner::utils::lane_change::calculation #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_ 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 42b22f9b1631c..28efae2549d1e 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 @@ -153,6 +153,8 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) bool NormalLaneChange::isLaneChangeRequired() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto current_lanes = utils::getCurrentLanesFromPath(prev_module_output_.path, planner_data_); @@ -162,7 +164,15 @@ bool NormalLaneChange::isLaneChangeRequired() const auto target_lanes = getLaneChangeLanes(current_lanes, direction_); - return !target_lanes.empty(); + if (target_lanes.empty()) { + return false; + } + + const auto ego_dist_to_target_start = + calculation::calc_ego_dist_to_lanes_start(common_data_ptr_, current_lanes, target_lanes); + const auto maximum_prepare_length = calculation::calc_maximum_prepare_length(common_data_ptr_); + + return ego_dist_to_target_start <= maximum_prepare_length; } bool NormalLaneChange::isStoppedAtRedTrafficLight() const diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp index ac205ceedb34b..2dc65a8b78045 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp @@ -54,4 +54,44 @@ double calc_stopping_distance(const LCParamPtr & lc_param_ptr) const auto param_back_dist = lc_param_ptr->backward_length_buffer_for_end_of_lane; return std::max(min_back_dist, param_back_dist); } + +double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr) +{ + const auto max_prepare_duration = common_data_ptr->lc_param_ptr->lane_change_prepare_duration; + const auto ego_max_speed = common_data_ptr->bpp_param_ptr->max_vel; + + return max_prepare_duration * ego_max_speed; +} + +double calc_ego_dist_to_lanes_start( + const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes) +{ + const auto & route_handler_ptr = common_data_ptr->route_handler_ptr; + + if (!route_handler_ptr || target_lanes.empty() || current_lanes.empty()) { + return std::numeric_limits::max(); + } + + const auto & target_bound = + common_data_ptr->direction == autoware::route_handler::Direction::RIGHT + ? target_lanes.front().leftBound() + : target_lanes.front().rightBound(); + + if (target_bound.empty()) { + return std::numeric_limits::max(); + } + + const auto path = + route_handler_ptr->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + + if (path.points.empty()) { + return std::numeric_limits::max(); + } + + const auto target_front_pt = lanelet::utils::conversion::toGeomMsgPt(target_bound.front()); + const auto ego_position = common_data_ptr->get_ego_pose().position; + + return motion_utils::calcSignedArcLength(path.points, ego_position, target_front_pt); +} } // namespace autoware::behavior_path_planner::utils::lane_change::calculation From d2142b93a883493dcf8f35e311fb049619406983 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 3 Sep 2024 18:14:04 +0900 Subject: [PATCH 05/12] fix(bpp): use common steering factor interface for same scene modules (#8675) (#1505) Signed-off-by: satoshi-ota --- .../src/interface.cpp | 4 +++- .../src/interface.hpp | 3 ++- .../src/manager.cpp | 2 +- .../manager.hpp | 2 +- .../scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- .../src/manager.cpp | 4 ++-- .../goal_planner_module.hpp | 3 ++- .../behavior_path_goal_planner_module/manager.hpp | 2 +- .../src/goal_planner_module.cpp | 5 +++-- .../behavior_path_lane_change_module/interface.hpp | 1 + .../src/interface.cpp | 4 ++-- .../src/manager.cpp | 2 +- .../interface/scene_module_interface.hpp | 8 ++++---- .../interface/scene_module_manager_interface.hpp | 8 ++++++++ .../behavior_path_sampling_planner_module/manager.hpp | 2 +- .../sampling_planner_module.hpp | 3 ++- .../src/sampling_planner_module.cpp | 5 +++-- .../autoware/behavior_path_side_shift_module/manager.hpp | 2 +- .../autoware/behavior_path_side_shift_module/scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- .../behavior_path_start_planner_module/manager.hpp | 2 +- .../start_planner_module.hpp | 3 ++- .../src/start_planner_module.cpp | 5 +++-- .../manager.hpp | 2 +- .../scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- 27 files changed, 60 insertions(+), 36 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp index 4c9f139365a06..fffb86767b0a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -31,13 +31,15 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) : LaneChangeInterface{ name, node, parameters, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, + steering_factor_interface_ptr, std::make_unique(parameters, avoidance_by_lane_change_parameters)} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp index c7fbba34b1adb..4d200411904b0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp @@ -40,7 +40,8 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); bool isExecutionRequested() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 8096d2944ee2b..ddcfda50d18c4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -192,7 +192,7 @@ AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp index 9c85a463067de..a7f470002b01b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp @@ -42,7 +42,7 @@ class DynamicObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp index 8f19613b50e6d..48c6084a4f424 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp @@ -343,7 +343,8 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); void updateModuleParams(const std::any & parameters) override { diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp index f195b91a54f21..debd13acd31dd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp @@ -331,8 +331,9 @@ DynamicObstacleAvoidanceModule::DynamicObstacleAvoidanceModule( std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{std::move(parameters)}, target_objects_manager_{TargetObjectsManager( parameters_->successive_num_to_entry_dynamic_avoidance_condition, diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp index c04914ed1c72b..3c730e6d36376 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp @@ -26,7 +26,7 @@ ExternalRequestLaneChangeRightModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, std::make_unique(parameters_, direction_)); } @@ -35,7 +35,7 @@ ExternalRequestLaneChangeLeftModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, std::make_unique(parameters_, direction_)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 749ed57f95cc9..4c23292f63e61 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -307,7 +307,8 @@ class GoalPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); ~GoalPlannerModule() { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp index 32d816d9a37e8..1ab7b6cb265a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp @@ -38,7 +38,7 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; 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 7792b427c5fa1..54a1c0830fb06 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 @@ -57,8 +57,9 @@ GoalPlannerModule::GoalPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, thread_safe_data_{mutex_, clock_}, diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index bd309dd35a260..fd9375c7e9f75 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -52,6 +52,7 @@ class LaneChangeInterface : public SceneModuleInterface const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr, std::unique_ptr && module_type); LaneChangeInterface(const LaneChangeInterface &) = delete; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 9354b117cb160..1bbc2d25fc0bc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -38,14 +38,14 @@ LaneChangeInterface::LaneChangeInterface( const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr, std::unique_ptr && module_type) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{std::move(parameters)}, module_type_{std::move(module_type)}, prev_approved_path_{std::make_unique()} { module_type_->setTimeKeeper(getTimeKeeper()); - steering_factor_interface_ptr_ = std::make_unique(&node, name); logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); } 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 42166c4dff0e0..c197d0d63aa37 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 @@ -299,7 +299,7 @@ std::unique_ptr LaneChangeModuleManager::createNewSceneMod { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index c4a05d171654d..d9ad89283d304 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -90,15 +90,15 @@ class SceneModuleInterface const std::string & name, rclcpp::Node & node, std::unordered_map> rtc_interface_ptr_map, std::unordered_map> - objects_of_interest_marker_interface_ptr_map) + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) : name_{name}, logger_{node.get_logger().get_child(name)}, clock_{node.get_clock()}, rtc_interface_ptr_map_(std::move(rtc_interface_ptr_map)), objects_of_interest_marker_interface_ptr_map_( std::move(objects_of_interest_marker_interface_ptr_map)), - steering_factor_interface_ptr_( - std::make_unique(&node, utils::convertToSnakeCase(name))), + steering_factor_interface_ptr_{steering_factor_interface_ptr}, time_keeper_(std::make_shared()) { for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { @@ -640,7 +640,7 @@ class SceneModuleInterface std::unordered_map> objects_of_interest_marker_interface_ptr_map_; - std::unique_ptr steering_factor_interface_ptr_; + std::shared_ptr steering_factor_interface_ptr_; mutable std::optional stop_pose_{std::nullopt}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 82a364a9c37c7..ceecb7b02408a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -315,6 +315,12 @@ class SceneModuleManagerInterface "~/processing_time/" + name_, 20); } + // init steering factor + { + steering_factor_interface_ptr_ = + std::make_shared(node, utils::convertToSnakeCase(name_)); + } + // misc { node_ = node; @@ -339,6 +345,8 @@ class SceneModuleManagerInterface std::shared_ptr planner_data_; + std::shared_ptr steering_factor_interface_ptr_; + std::vector observers_; std::unique_ptr idle_module_ptr_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp index 28c310ae20ec2..778afd1698ff2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp @@ -38,7 +38,7 @@ class SamplingPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams( diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp index 2b6f52998cb23..8dc04947923e1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp @@ -86,7 +86,8 @@ class SamplingPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index 526a761e6957a..b820e8d03322f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -33,8 +33,9 @@ SamplingPlannerModule::SamplingPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()} { internal_params_ = std::make_shared(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp index b495e6619a1c7..d1c9c8e2535ec 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp @@ -39,7 +39,7 @@ class SideShiftModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp index 543b17aca9352..74953b7927b5d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp @@ -45,7 +45,8 @@ class SideShiftModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp index bcb972bf5dc8b..cd4298c56929a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp @@ -40,8 +40,9 @@ SideShiftModule::SideShiftModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp index 5d3d224673124..a26c48ad065c9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp @@ -38,7 +38,7 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; 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 bb70ae2638056..e0bb5d95f565a 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 @@ -88,7 +88,8 @@ class StartPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); ~StartPlannerModule() override { 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 e318fbedf3200..dd9129216fbba 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 @@ -59,8 +59,9 @@ StartPlannerModule::StartPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_freespace_planner_cb_running_{false} diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp index 895390f91cc16..fa54ec52203f9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp @@ -41,7 +41,7 @@ class StaticObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index 34d06a46d9ac8..dc6e41fbc5f7e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -46,7 +46,8 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; 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 39a8d1b853e47..3c76e288fdd55 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 @@ -76,8 +76,9 @@ StaticObstacleAvoidanceModule::StaticObstacleAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT helper_{std::make_shared(parameters)}, parameters_{parameters}, generator_{parameters} From da8b050515427fb2bf92d3e292856b7e0a94a046 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Thu, 5 Sep 2024 08:40:01 +0900 Subject: [PATCH 06/12] fix(pid_longitudinal_controller): fix the same point error (#8758) (#1512) * fix same point Signed-off-by: Yuki Takagi --- .../src/pid_longitudinal_controller.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 20f8dfe642cc6..4acb73b1d1b60 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -488,6 +488,8 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData // calculate the target motion for delay compensation constexpr double min_running_dist = 0.01; if (control_data.state_after_delay.running_distance > min_running_dist) { + control_data.interpolated_traj.points = + autoware::motion_utils::removeOverlapPoints(control_data.interpolated_traj.points); const auto target_pose = longitudinal_utils::findTrajectoryPoseAfterDistance( control_data.nearest_idx, control_data.state_after_delay.running_distance, control_data.interpolated_traj); From c0644c325374b25d3f7d3385f6cb549f52c34702 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 5 Sep 2024 09:40:07 +0900 Subject: [PATCH 07/12] feat(out_of_lane): redesign (#1509) Signed-off-by: Maxime CLEMENT Co-authored-by: Tiankui Xian <1041084556@qq.com> Co-authored-by: Shohei Sakai --- .../motion_utils/trajectory/trajectory.hpp | 9 + .../src/trajectory/trajectory.cpp | 23 ++ .../README.md | 191 ++++----- .../config/out_of_lane.param.yaml | 24 +- .../docs/ego_lane.png | Bin 0 -> 17530 bytes .../docs/footprints.png | Bin 0 -> 28711 bytes .../docs/object_paths.png | Bin 0 -> 26240 bytes ...footprints_other_lanes_overlaps_ranges.png | Bin 127593 -> 0 bytes .../docs/out_of_lane_areas.png | Bin 0 -> 19244 bytes .../docs/out_of_lane_slow.png | Bin 110077 -> 0 bytes .../docs/out_of_lane_stop.png | Bin 183400 -> 0 bytes .../docs/path_green_light.png | Bin 0 -> 23635 bytes .../docs/path_red_light.png | Bin 0 -> 22819 bytes .../docs/ttcs.png | Bin 0 -> 28315 bytes .../docs/ttcs_avoid.png | Bin 0 -> 31503 bytes .../src/calculate_slowdown_points.cpp | 131 ++++-- .../src/calculate_slowdown_points.hpp | 45 +- .../src/debug.cpp | 305 +++++++------- .../src/debug.hpp | 8 +- .../src/decisions.cpp | 389 ------------------ .../src/decisions.hpp | 116 ------ .../src/filter_predicted_objects.cpp | 46 +-- .../src/filter_predicted_objects.hpp | 4 +- .../src/footprint.cpp | 23 +- .../src/footprint.hpp | 12 +- .../src/lanelets_selection.cpp | 118 ++++-- .../src/lanelets_selection.hpp | 39 +- .../src/out_of_lane_collisions.cpp | 164 ++++++++ .../src/out_of_lane_collisions.hpp | 57 +++ .../src/out_of_lane_module.cpp | 322 ++++++++------- .../src/out_of_lane_module.hpp | 25 +- .../src/overlapping_range.cpp | 127 ------ .../src/overlapping_range.hpp | 63 --- .../src/types.hpp | 215 +++------- .../CMakeLists.txt | 17 +- .../collision_checker.hpp | 69 ++++ .../planner_data.hpp | 29 +- .../src/collision_checker.cpp | 70 ++++ .../test/test_collision_checker.cpp | 176 ++++++++ .../src/node.cpp | 47 ++- .../src/node.hpp | 3 + .../src/planner_manager.cpp | 51 ++- .../src/planner_manager.hpp | 11 + 43 files changed, 1412 insertions(+), 1517 deletions(-) create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/object_paths.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_areas.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_red_light.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs_avoid.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp index 126e66772920a..0ce42fbe1080f 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp @@ -2504,6 +2504,15 @@ extern template bool isTargetPointFront & trajectory, + const geometry_msgs::msg::Point & current_ego_point, const float min_velocity = 1.0f); + } // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__TRAJECTORY_HPP_ diff --git a/common/autoware_motion_utils/src/trajectory/trajectory.cpp b/common/autoware_motion_utils/src/trajectory/trajectory.cpp index ce26952c3d634..080d8ca8c7437 100644 --- a/common/autoware_motion_utils/src/trajectory/trajectory.cpp +++ b/common/autoware_motion_utils/src/trajectory/trajectory.cpp @@ -599,4 +599,27 @@ template bool isTargetPointFront & trajectory, + const geometry_msgs::msg::Point & current_ego_point, const float min_velocity) +{ + const auto nearest_segment_idx = findNearestSegmentIndex(trajectory, current_ego_point); + if (nearest_segment_idx + 1 == trajectory.size()) { + return; + } + for (auto & p : trajectory) { + p.time_from_start = rclcpp::Duration::from_seconds(0); + } + // TODO(Maxime): some points can have very low velocities which introduce huge time errors + // Temporary solution: use a minimum velocity + for (auto idx = nearest_segment_idx + 1; idx < trajectory.size(); ++idx) { + const auto & from = trajectory[idx - 1]; + const auto velocity = std::max(min_velocity, from.longitudinal_velocity_mps); + if (velocity != 0.0) { + auto & to = trajectory[idx]; + const auto t = universe_utils::calcDistance2d(from, to) / velocity; + to.time_from_start = rclcpp::Duration::from_seconds(t) + from.time_from_start; + } + } +} } // namespace autoware::motion_utils diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md index 99396eb0edf22..0b6aa697fcbef 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md @@ -1,161 +1,138 @@ -## Out of Lane +# Out of Lane -### Role +## Role -`out_of_lane` is the module that decelerates and stops to prevent the ego vehicle from entering another lane with incoming dynamic objects. +There are cases where the ego vehicle footprint goes out of the driving lane, +for example when taking a narrow turn with a large vehicle. +The `out_of_lane` module adds deceleration and stop points to the ego trajectory in order to prevent collisions from occurring in these out of lane cases. -### Activation Timing +## Activation -This module is activated if `launch_out_of_lane` is set to true. +This module is activated if the launch parameter `launch_out_of_lane_module` is set to true. -### Inner-workings / Algorithms +## Inner-workings / Algorithms -The algorithm is made of the following steps. +This module calculates if out of lane collisions occur and insert stop point before the collisions if necessary. -1. Calculate the ego path footprints (red). -2. Calculate the other lanes (magenta). -3. Calculate the overlapping ranges between the ego path footprints and the other lanes (green). -4. For each overlapping range, decide if a stop or slow down action must be taken. -5. For each action, insert the corresponding stop or slow down point in the path. +The algorithm assumes the input ego trajectory contains accurate `time_from_start` +values in order to calculate accurate time to collisions with the predicted objects. -![overview](./docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png) +Next we explain the inner-workings of the module in more details. -#### 1. Ego Path Footprints +### 1. Ego trajectory footprints -In this first step, the ego footprint is projected at each path point and are eventually inflated based on the `extra_..._offset` parameters. +In this first step, the ego footprint is projected at each trajectory point and its size is modified based on the `ego.extra_..._offset` parameters. -#### 2. Other lanes +The length of the trajectory used for generating the footprints is limited by the `max_arc_length` parameter. -In the second step, the set of lanes to consider for overlaps is generated. -This set is built by selecting all lanelets within some distance from the ego vehicle, and then removing non-relevant lanelets. -The selection distance is chosen as the maximum between the `slowdown.distance_threshold` and the `stop.distance_threshold`. +![ego_footprints](./docs/footprints.png) -A lanelet is deemed non-relevant if it meets one of the following conditions. +### 2. Ego lanelets -- It is part of the lanelets followed by the ego path. -- It contains the rear point of the ego footprint. -- It follows one of the ego path lanelets. +In the second step, we calculate the lanelets followed by the ego trajectory. +We select all lanelets crossed by the trajectory linestring (sequence of trajectory points), as well as their preceding lanelets. -#### 3. Overlapping ranges +![ego_lane](./docs/ego_lane.png) -In the third step, overlaps between the ego path footprints and the other lanes are calculated. -For each pair of other lane $l$ and ego path footprint $f$, we calculate the overlapping polygons using `boost::geometry::intersection`. -For each overlapping polygon found, if the distance inside the other lane $l$ is above the `overlap.minimum_distance` threshold, then the overlap is ignored. -Otherwise, the arc length range (relative to the ego path) and corresponding points of the overlapping polygons are stored. -Ultimately, for each other lane $l$, overlapping ranges of successive overlaps are built with the following information: +In the debug visualization the combination of all ego lanelets is shown as a blue polygon. -- overlapped other lane $l$. -- start and end ego path indexes. -- start and end ego path arc lengths. -- start and end overlap points. +### 3. Out of lane areas -#### 4. Decisions +Next, for each trajectory point, we create the corresponding out of lane areas by subtracting the ego lanelets (from step 2) from the trajectory point footprint (from step 1). +Each area is associated with the lanelets overlapped by the area and with the corresponding ego trajectory point. -In the fourth step, a decision to either slow down or stop before each overlapping range is taken based on the dynamic objects. -The conditions for the decision depend on the value of the `mode` parameter. +![out_of_lane_areas](./docs/out_of_lane_areas.png) -Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the start of the overlapping range (in arc length along the ego path). -If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used. -If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used. +In the debug visualization, the out of lane area polygon is connected to the corresponding trajectory point by a line. + +### 4. Predicted objects filtering + +We filter objects and their predicted paths with the following conditions: - - - - - -
- - - -
+- ignore objects with a speed bellow the `minimum_velocity` parameter; +- ignore objects coming from behind the ego vehicle if parameter `ignore_behind_ego` is set to true; +- ignore predicted paths whose confidence value is bellow the `predicted_path_min_confidence` parameter; +- cut the points of predicted paths going beyond the stop line of a red traffic light if parameter `cut_predicted_paths_beyond_red_lights` is set to `true`. -##### Threshold +| `cut_predicted_paths_beyond_red_lights = false` | `cut_predicted_paths_beyond_red_lights = true` | +| :---------------------------------------------: | :--------------------------------------------: | +| ![](./docs/path_green_light.png) | ![](./docs/path_red_light.png) | -With the `mode` set to `"threshold"`, -a decision to stop or slow down before a range is made if -an incoming dynamic object is estimated to reach the overlap within `threshold.time_threshold`. +In the debug visualization, the filtered predicted paths are shown in green and the stop lines of red traffic lights are shown in red. -##### TTC (time to collision) +### 5. Time to collisions -With the `mode` set to `"ttc"`, -estimates for the times when ego and the dynamic objects reach the start and end of the overlapping range are calculated. -This is then used to calculate the time to collision over the period where ego crosses the overlap. -If the time to collision is predicted to go bellow the `ttc.threshold`, the decision to stop or slow down is made. +For each out of lane area, we calculate the times when a dynamic object will overlap the area based on its filtered predicted paths. -##### Intervals +In the case where parameter `mode` is set to `threshold` and the calculated time is less than `threshold.time_threshold` parameter, then we decide to avoid the out of lane area. -With the `mode` set to `"intervals"`, -the estimated times when ego and the dynamic objects reach the start and end points of -the overlapping range are used to create time intervals. -These intervals can be made shorter or longer using the -`intervals.ego_time_buffer` and `intervals.objects_time_buffer` parameters. -If the time interval of ego overlaps with the time interval of an object, the decision to stop or slow down is made. +In the case where parameter `mode` is set to `ttc`, +we calculate the time to collision by comparing the predicted time of the object with the `time_from_start` field contained in the trajectory point. +If the time to collision is bellow the `ttc.threshold` parameter value, we decide to avoid the out of lane area. -##### Time estimates +![ttcs](./docs/ttcs.png) -###### Ego +In the debug visualization, the ttc (in seconds) is displayed on top of its corresponding trajectory point. +The color of the text is red if the collision should be avoided and green otherwise. -To estimate the times when ego will reach an overlap, it is assumed that ego travels along its path -at its current velocity or at half the velocity of the path points, whichever is higher. +### 6. Calculate the stop or slowdown point -###### Dynamic objects +First, the minimum stopping distance of the ego vehicle is calculated based on the jerk and deceleration constraints set by the velocity smoother parameters. -Two methods are used to estimate the time when a dynamic objects with reach some point. -If `objects.use_predicted_paths` is set to `true`, the predicted paths of the dynamic object are used if their confidence value is higher than the value set by the `objects.predicted_path_min_confidence` parameter. -Otherwise, the lanelet map is used to estimate the distance between the object and the point and the time is calculated assuming the object keeps its current velocity. +We then search for the furthest pose along the trajectory where the ego footprint stays inside of the ego lane (calculate in step 2) and constraint the search to be between the minimum stopping distance and the 1st trajectory point with a collision to avoid (as determined in the previous step). +The search is done by moving backward along the trajectory with a distance step set by the `action.precision` parameter. -#### 5. Path update +We first do this search for a footprint expanded with the `ego.extra_..._offset`, `action.longitudinal_distance_buffer` and `action.lateral_distance_buffer` parameters. +If no valid pose is found, we search again while only considering the extra offsets but without considering the distance buffers. +If still no valid pose is found, we use the base ego footprint without any offset. +In case no pose is found, we fallback to using the pose before the detected collision without caring if it is out of lane or not. -Finally, for each decision to stop or slow down before an overlapping range, -a point is inserted in the path. -For a decision taken for an overlapping range with a lane $l$ starting at ego path point index $i$, -a point is inserted in the path between index $i$ and $i-1$ such that the ego footprint projected at the inserted point does not overlap $l$. -Such point with no overlap must exist since, by definition of the overlapping range, -we know that there is no overlap at $i-1$. +Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the trajectory point to avoid. +If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used. +If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used. -If the point would cause a higher deceleration than allowed by the `max_accel` parameter (node parameter), -it is skipped. +![avoid_collision](./docs/ttcs_avoid.png) -Moreover, parameter `action.distance_buffer` adds an extra distance between the ego footprint and the overlap when possible. +### About stability of the stop/slowdown pose -### Module Parameters +As the input trajectory can change significantly between iterations, +it is expected that the decisions of this module will also change. +To make the decision more stable, a stop or slowdown pose is used for a minimum duration set by the `action.min_duration` parameter. +If during that time a new pose closer to the ego vehicle is generated, then it replaces the previous one. +Otherwise, the stop or slowdown pose will only be discarded after no out of lane collision is detection for the set duration. + +## Module Parameters | Parameter | Type | Description | | ----------------------------- | ------ | --------------------------------------------------------------------------------- | | `mode` | string | [-] mode used to consider a dynamic object. Candidates: threshold, intervals, ttc | | `skip_if_already_overlapping` | bool | [-] if true, do not run this module when ego already overlaps another lane | +| `max_arc_length` | double | [m] maximum trajectory arc length that is checked for out_of_lane collisions | | Parameter /threshold | Type | Description | | -------------------- | ------ | ---------------------------------------------------------------- | | `time_threshold` | double | [s] consider objects that will reach an overlap within this time | -| Parameter /intervals | Type | Description | -| --------------------- | ------ | ------------------------------------------------------- | -| `ego_time_buffer` | double | [s] extend the ego time interval by this buffer | -| `objects_time_buffer` | double | [s] extend the time intervals of objects by this buffer | - | Parameter /ttc | Type | Description | | -------------- | ------ | ------------------------------------------------------------------------------------------------------ | | `threshold` | double | [s] consider objects with an estimated time to collision bellow this value while ego is on the overlap | -| Parameter /objects | Type | Description | -| ------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | -| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | -| `use_predicted_paths` | bool | [-] if true, use the predicted paths to estimate future positions; if false, assume the object moves at constant velocity along _all_ lanelets it currently is located in | - -| Parameter /overlap | Type | Description | -| ------------------ | ------ | ---------------------------------------------------------------------------------------------------- | -| `minimum_distance` | double | [m] minimum distance inside a lanelet for an overlap to be considered | -| `extra_length` | double | [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) | - -| Parameter /action | Type | Description | -| ----------------------------- | ------ | ---------------------------------------------------------------------------------------------- | -| `skip_if_over_max_decel` | bool | [-] if true, do not take an action that would cause more deceleration than the maximum allowed | -| `distance_buffer` | double | [m] buffer distance to try to keep between the ego footprint and lane | -| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | -| `slowdown.velocity` | double | [m] slow down velocity | -| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | +| Parameter /objects | Type | Description | +| --------------------------------------- | ------ | ------------------------------------------------------------------------------- | +| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | +| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | +| `cut_predicted_paths_beyond_red_lights` | bool | [-] if true, predicted paths are cut beyond the stop line of red traffic lights | +| `ignore_behind_ego` | bool | [-] if true, objects behind the ego vehicle are ignored | + +| Parameter /action | Type | Description | +| ------------------------------ | ------ | --------------------------------------------------------------------- | +| `precision` | double | [m] precision when inserting a stop pose in the trajectory | +| `longitudinal_distance_buffer` | double | [m] safety distance buffer to keep in front of the ego vehicle | +| `lateral_distance_buffer` | double | [m] safety distance buffer to keep on the side of the ego vehicle | +| `min_duration` | double | [s] minimum duration needed before a decision can be canceled | +| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | +| `slowdown.velocity` | double | [m] slow down velocity | +| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | | Parameter /ego | Type | Description | | -------------------- | ------ | ---------------------------------------------------- | diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml index a0cf69ee71027..5d36aa8d3f018 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -1,32 +1,22 @@ /**: ros__parameters: out_of_lane: # module to stop or slowdown before overlapping another lane with other objects - mode: ttc # mode used to consider a conflict with an object. "threshold", "intervals", or "ttc" + mode: ttc # mode used to consider a conflict with an object. "threshold", or "ttc" skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane + max_arc_length: 100.0 # [m] maximum trajectory arc length that is checked for out_of_lane collisions threshold: time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time - intervals: # consider objects if their estimated time interval spent on the overlap intersect the estimated time interval of ego - ego_time_buffer: 0.5 # [s] extend the ego time interval by this buffer - objects_time_buffer: 0.5 # [s] extend the time intervals of objects by this buffer ttc: threshold: 3.0 # [s] consider objects with an estimated time to collision bellow this value while on the overlap objects: minimum_velocity: 0.5 # [m/s] objects lower than this velocity will be ignored - use_predicted_paths: true # if true, use the predicted paths to estimate future positions. - # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in. predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. - distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights ignore_behind_ego: true # if true, objects behind the ego vehicle are ignored - overlap: - minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered - extra_length: 0.0 # [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) - action: # action to insert in the trajectory if an object causes a conflict at an overlap - skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed precision: 0.1 # [m] precision when inserting a stop pose in the trajectory longitudinal_distance_buffer: 1.5 # [m] safety distance buffer to keep in front of the ego vehicle lateral_distance_buffer: 1.0 # [m] safety distance buffer to keep on the side of the ego vehicle @@ -38,8 +28,8 @@ distance_threshold: 15.0 # [m] insert a stop when closer than this distance from an overlap ego: - min_assumed_velocity: 2.0 # [m/s] minimum velocity used to calculate the enter and exit times of ego - extra_front_offset: 0.0 # [m] extra front distance - extra_rear_offset: 0.0 # [m] extra rear distance - extra_right_offset: 0.0 # [m] extra right distance - extra_left_offset: 0.0 # [m] extra left distance + # extra footprint offsets to calculate out of lane collisions + extra_front_offset: 0.0 # [m] extra footprint front distance + extra_rear_offset: 0.0 # [m] extra footprint rear distance + extra_right_offset: 0.0 # [m] extra footprint right distance + extra_left_offset: 0.0 # [m] extra footprint left distance diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png new file mode 100644 index 0000000000000000000000000000000000000000..65cb73226465ae3de6c27b35562d35c57c5906b5 GIT binary patch literal 17530 zcmbt+cRZEh|MyWTp^y_2*($>jiv)`ZhCH&b_`CIsu_%ImkmZE};1`KvZ4+g`T z#Jd9ilKS1n1pK)9Nzk3I#)}d(@2BU>3%1CK>7_U#O+ELl0v+OTNZ=T{? z@hU3ivlg=zml|mQ&9?ol)S@{e_>6CC^fS-PuLN*16d~EGZ#OngtKQ=Hj0MF;hWrj8 z@|}`Jic3-~1--eKS8uei;pR9?!%YX z$G9VQ-WEiBBxj+aa`R|#`3!&m*K6-N_!0!p!J0K3hZ$S-T&?DstxX&*<*qh-rnA3BZ+!QBzXo5 zX41=ssYH@bhT82SoStpWw6F`R-b7b-7P6_A>vR>eVbJ7KK1)|9m}Kn&^exg0$M~5F z4;=l{ja%{dx0BZTxP&D9-U>fTB_}8EVh+HLj~`Y1*v^=3ru#hAu%q{4m1OPg_TI~v zFU>R~3Kq?CwH}76j+pGvlbSG(+PWV~6>L95*461O)F94Q3l2R#9)p)$K_9h>WiN>R z5^1fRYiiFIsp-tIH9dTQ_^9>E<7YI-qSqVRYXLYb@yC&okv+G^zQqKf5JKlyNcru>rIr`-=c$$^MVTDmKVX4}Jqgzx ze}1OP{<3n|?Y1a9D;R|gFV6zIZjxMHUXG38NK!J&C28=G%04hH*v28zF2!`Z+!Wt( zZeVeeskNS50Xt4B>($p49Ua}$((;Y0vgWO>c~b8U>JCRyYhp1~` zCZ9hk9PHuJHp2J(l%`hABW-y8a_q17Hl~{}Rhx+^;e2Uf%@>*-i@mCRCsdD8F~umi~FXrH`VYp^03KCge}b#6~&vZkAd0|_AQc!t(U?y zGyHkL`+l8s;~?(7|5lpo1%A_GwIHCL6v_KnoH(4uoM^e1v`y{+v*92cJV`pbS^6`85Qu#~Y zj^xzz8K$XebL(wsDMDZG&|Lp~w5RmFE;QUtjndJ&y1MNnpDI1ZT(c^Vy}zT}gfD9; z+va+c{13K%Biu4Y=pQC!Pk+H?S6r|j;s4-rjlKd?`DmfGibA0V{r#5zjv{{7_sJqx zU~G`-t6Y~vhFbqdq1rsR7l#vAWK!XLFTh;HX@w2VKI@TOehk?#`Vs!{@6{aG&R60d zTPD`aO&7lrr$nc}Pd3|{z4k6V54UDBoAEiXnFqsY8=aSWlh`qB`?VRN?}qprj4LB` z^T$q4PYaY&$jHg>%D!XlaWle3ys0juIbFUu#X+1WAdZ&m+s@ijl(bEMzH&}2^xXNQ zDyxnk(hfhXmm>(ly-6KP;zz)RTA9mRJ1;(oUDhqxY#FxG^g)WRN8 zCyJbtp5hM$!!@I${%uVs2&^K%5p!ZpO2t~CjTLX23Nv4`yVV@zaU&^FGLx=bBl>t zw>L+SOD^@<1X_@v!6g09-@heeUc=YU>%UptgRQ6uKL2h-(Eo?TU+-ZO^H!dHGhqie zVbHQ=o8!R#e(e0C5r^sH`l3g13Qt*={GUpb{c#qlD!%3aocV9tEufSGPr{x6u`7|6 z1zTxsf=y_tQ7*7Xqh}GG#{6meV@-!y_fGupN0ET7{5vY3I@0;;sg|~`wnPfwJ@eMh zhY|6a(!5pX(&R&ua$^jpUsWiSK9|w>?2XdwER2rkaB!R|ZvV46Otu4x>MCw=xVx%} z%_R|?&0sjKzxPx4<>uv<>NiZ76QkmtR)hxz24Xf(7LEfETFWP8YPPioZ{NP{sl)^J z93gbO#cgfYs^&se(yh>-e1Byq&qHu^(y`5ca{o)=py6qMj|Fd36)m3J(OrC_JQ(fp z=N+HqBfq(mJL=!+)(tC~TYUf8lWKf-qN1Oeoh5IjV%*GgeP=WhKb`NsIb&pKNTn*Y z`rOeMrZMatgadN`P3oJzV8^4;7 zFv-r@`*GJW)&WGf&7F7l7*G9xQ?Z&atCrC+ZNVJCts~B{v0ahZd!5q7am`Cgic92V z#_isO9lAc8b(a_nuUuU^yT=6F*{%%hxyM@yGp=8{%f`I8O=a(d--7V+Z+*Q5i@INE zlU{iA?FNmw&*3NZwC~&KZaVdE2Ulm^*^{nL*4@8Vn&NI_0i^Is+F9+Mm%uir1oH@E zzrNW<+c~4SyfSs)7~gsA^1?=(sNcRVVP$t9!HeC!z(_}LA{ezfsoRr<*STXav(o4SbvR6kVwPJtg(#PVDbDPy<>6K=aN z)T+-44+qxUP_fWh=h0O)R76W+Z*PCIl<w0NY;VlJ6~1_n?A z1G;-&`{elcQbLI4( z@F=DxMO_`8fs~MnH5H?qtZ|*!VXzko=roDKxq$)yi=CV{dD5J~sh}G~f`WpF*!zyn zPTLl0s8*`;`DY|oV43B{mFw&FY!S(Zh#AhO-zMvk6exf8>}&-mqmOIHvM7Qga_C)k zrx!jA9nPrvZ6isCPBu4<+s-RRE7&qsoKIF-f*1<@6?7Gq6#zY}GTupNKv zK^~3o_gKf-a|Hjo{z-bf;{NXH$WJRe6bP8dbuBHeEiKu7BHc#}ep_do7u+c)A|&_Z z>Qb7h)M7l8H`XwfmF4AG;v(qFm1<6D9xtU_tj(UUThbrT9GrXkonJ(7rB>v|h0WWK zZ6BRJ-Z#m>{|LtBl!-qdwazIg9y(|}z@%_poGca>v*Tkhm?K7w5&q5DHm>Y!b?BP| zgVlapJuH>UgrUC?jydvtZnCEMEbr){TWqZj8qF4QgL#TpzisOCQ!Sjx3N7Xd!FJ4v z$JbM+%;@C$hIjqE8{+CL)phhbGmZXI!#s|6{eRyOa%gtnCLHP!&P3(L-6425&~h^I z`77}F0j>JKhz`H~{j2sgTg24c`)nu=2^5%sfPKEfX6q1Z?#DgJMEVfu#`$NWTd#F1 zF@y}dm1;;??b6Z1TN#{2jr<)!A<){7=R9dpPl8(VY3o~BI0aS1_x5!CckUTm#zKPV zNMP~rB}z_d^WX04ix5*7boY+vc?;dqj(rlu$K23+KGWhozq;D3qkDm@vM(cC&@~%* zVKYJ0#SG?td)>P4?BqaogfTZ(@>oG!Xo*6dvF@85NG>}I$K%lwBpD`kQDOFtnk)Wt+t>YI(=VI$(a z&R=SkYFF9NSJlsWDcjv=9rSh!s_0o3o+Zm*exB!~Y?p2~`d6UprioYc#W|W?SI}|h z)CGG@rQyR3y02PmXBkr}F`PTA+d&5Q&Gq#xg0)BUkq3^`UM=d&!^5Qu8f>IO*~JF6 z;V<0lv5SgN#4&9LGtcJ{XIonr8%w$?L+@usO<9wa%rvFj+=o zWT64$RUk+E^2Nh|fBTuw*4!J9dDjDwKKq@ClGxkX?e2Bn6a1>r2l8wQlrfdF_{_Y? zeT6#=pcD|q-gTsYQgtA+xJ0Y*jMyI`EU!+H;=6vq$@9Q_)OL@)zz2%7+$SEa+k+eV z8{riGQ+b-7joQ%oO>louko4u@XnUMV6JL28;i@8YF2&JFCo0>t))JH`Z_<70eR_!1 zi&qN(OXUBX8rIX-L6yemwn@95>hFZb_?=NeHOA&y?7gl%A7Py`7R-B*h0S@g3P&o*E% zIkpB1Gq6D~U#<=1$shT&>T%pruhQ#V-T|Iweq?wVD6M15UUJ3S=?6>w#)`E@$%0KN zWuHqrnDLIK@j1nIJ1zYBr6ZY>!l;PZGpjn>pLA4P?LK>4R$lIV&@|iPx_ZYS)GSzR zHx0t~c=zvU>FJs0?#fV)wF(XhgfNn!7ViU(rEc`M#bQvQ6{+PgD|eLYR)(7Dm5#=z z^f#XzYy!uGmHts(hP*h&lIaE)dCVT?)i*ua8b%o4 zqYJT5E_{G8fMsqnF#t7s+p~#NYw(B@-+nT?q7n}{4_Kr7=7Y@*<<}9fJH3@g_-w~! z$d7As&dSUOm?GQ3LL!P-pwKfnx?j2qZkW|g z)jQanjcs~DBk40%Kn(9R|EQ@22d)rkhVvGxA$O-dcxsvgtVd^z!+}% zjogG1XO_X;^>0BpPR~^fZTz;r-B{0fwU6dU7wVHef6L}6U&4u27=R<*&Bps}f1tk> zunUzKB85Gf%pw*Z@3cb;^;?~n$jr+$Jn6FUrwii_W>QZ?u0F)CS`~!lYdKr1W2Zc^ zW~?(MVh*eCY?8^zbO;%gWsrVHFR{BnI_otW73flT=e}J%Uuy%ImhUZ|7+m0a6^g$l z2UV4qKbovN8s45M8r*vL%I`cr_oIwf`Npp`hKKprvjeB#cS9%`t_37gdWcXwMK~q2@EP@y|yy6qNa&pH}L`U56 zMD+uHRCE~?70A*?G~i}Y;P%H#=eVM-_Vz0zzDG+b^Q)R$RaH&yn<#%&o@GzfW2xFk zv2^FHAR@`R8&?&-9o}wfzWt}rGM^Y^xy7Uh+OLUVBmAC+_d>rtr|K4Q>e8R6`Qh|Y z%is>DvMs;yjh?NkHvb$NLvGxV`WG%PnqN%J%@>aMK%G=kUao3K1_|7)F(v46*>$;ld{ghQ)E7K55V>p8DdnFh#Rr&D+2I_iwp{GA{ua zvbB!}MO7s7&zZZyy)TVz%zN3Ii@BLq26#e))WV~3M_+b7;g4!ZF&w2D<>~FssaaWB zc7ho_7QIW(c|*dYq7iE2uO*y*&oOCkbtBHJJkrBBe;j!h-n^Wc`$T1=Z^^kpLve(E zh8}Lw@s(Yij-c&yTiGuq_a&yH>%=q0r03co9laNDu|0e;GC~eh??3qSeNq`&)EBe) z^!@?NDrc>6&&$`*F}BilY-Xm;{(1Aq8|6Bsl_y$1*92sTc+(84hnzAS8bJLH$3GqY zh4D{lHksR)Z5!My+Xapy23Nn<06Y+p%Z-9Bo#Mt@>Q}5ql*=TJ8Jk=o$3RKALZnA4 zYg-2A#V*3LXU^WSlAy*UCMM=#5#2cN>+9=WZKuu(n|;T}qR5ws zH)0i#>v!{bVCM*3M5`_c8*lGvr}UoWtSoBd_+<2w>Arlnbvo;<^{n45)jqvZ9u8$c z1n^-t-yG%Is;cOwZs!_T?!;(f+=6IVh9$-vF)zvtrXRuoBzQ;E8I(h>TT;J|l6KB2N9|bGnt%cB%$a*HJfLiUVt5WYG&Q z(N;dggNV30npVsuteq4g6gxt$YeDKt`uFc~Rz$W#;YCGcq?B?PIt32KiQ>DnC6 zU`=jl?mnS1B-inm3D@SZDSH?z`joQ$`^phOFKHh!e>fEGe{a?A%5eigL=PEQ_q>GY zrhig_Kww2hLo43xGeqKjxJ74F#wuP;wYYzP3{%Y_^geNP$bFp#u$`|_86VS*jSPK+ z1~v$8u#~fAQh}h9YMFp|oa*{clFjvVFNJJZ22NVPo$$S8rKZOzxvkcY{LAv zm^id``kF$IDb^$y2i%(qK9KoSW3lZ$AbkrM=P$S#Y#1B4w&46}_S5E=nAf*7-s##w zhG;S8?$*F7AaK;!DBZv__kC2cSxS|!S=g8P%hJnf8vU)R@;%6BzS^Y^)dl&Ylfgq9qgT^jSVM`&c z=$;w!JCQY~mdC$Q+Suf6AfiB8lL!SZ?p0B;5b{;>rT8F#HL#5cx4f-U#vktNGY1Ld zSHkqaY#3n|fSH4q|Sb7piP#6%t&=}B7EceBvx!@NXk!Fy2|ZyqU~P#*ssEr zmxbRpBX4Q`QR@n2(|RaDno-z`*9zZ1jJ}18YP^49y#|x;J3R#1U(fTs+s!l7c4V)S zyh9EFZQqYRX{@@D@04A80BioWkP^Fb&;O*Zs`*sQPL(yqyLZ#iNPG}=PA5iu>Ki71 z4J6IyAR%<2KVBpi@*Hn)yTELAVI1ybvFhd8;|@$uU%Q;tIjzP&mASwo9z-n1>>aLe zO^rQwY+<;G}Gs0Fn523(c|JQ#Y{7&!f>21H$&*cQ2ZTl z?L?N6<@(_HKe73n!j<8-r33g^ums3WWQo`52Cva9(TxAalA6C4o8RH!`S=C1B0@0} z@j>h1O(rcalo&Fv$-?q}1FZ z-jBUq#}#)0D!vf1jbG(c8IGL9L*&SR2+v_+wR+FZmI4hnhPv!rgW3clcXwo)jx0r@4fB&pzJ<4AdlCV^3hUFyb+3pyr2=78VtsKs#s1ZKpWU#pyqQ+i)9n2^kDb1kuqlru;dL&O;ilQcReno-tX_t9{_3cOtm)&R1y8JKD|<7Y;V2Jo^xxEWt*V zIi7rlG4sfEl^(dy;g)Ia8w>%*#~T5wc{T`+6a;;)?cRjVSv_Av*ee^h18nyu$xw|o zf_O0cIZ~NN zjrG7!v9bQ*V{k?w6_rZ9$aekFg^3@l&J$%ubhuq3K~SA&b5|{)SWA-Dj74pru)JKG zzR}xVQ=BJn9zHcTMxlWZwO9%#0F1Gst$sKgzHCK6v%MIJi#X{cQ5(#)z?bycdMqv> z47nvU?4RfB3?Y10v_k2rD%3>+Ox`kY(=S(AOs1BWRuSzyVC{RxjG)+`$w;6zX8Y!- zDy{`R>EP2#Si2s?=gp+moY$M-c)q)srth*jBjNW6l$2W{x$BVgnQko0OXW%GE%imq z#oaRJum122s*rPw(Bg2hkJ19?p0f;o<-h0K#tP{X>a#)R>%!1tzGOdj$QSmd{>FXH zeYrJkK6wJEaty}uG>{XF3ft_~DxDVbyk6Mxh4~o5uL>0*5G643GSY^z#9Z0Mg?w?) zV9L=++XYuADfc%e(5v7#faVs^t+0zwg%v?#{hMp5I33UNl^4f(B?_%MM$G*|q$jwVtzVtY0h&<%`FaOG8c6CYG+W}qtUsGzbm#W=M0*h#=a3B~z_jgg>zFZql^#F!R1Ih+q(GaPsmew;*oHS%STq`XcKK%&Ri{r{ zF@*4>IWG^GSJ}MyWNRh}^>7Qtfyc=R%`+EKkZH(d6Z~cYy_?-J@JwBW@4j1XgVz!S zueDMzobW%n0FP&rQ!qccMERh>gZP`n^YW1NX?LK#YIWnf!QfxL1nu zPp3M?buj(cxm)J*FD?~A>KTL)3wQ1Bd*zvSxtJd6(f)0-xkLtoEVVgG>FXY(1USk4 zaklD4n_Ph;dp)50LAxWRDX2{WBj7F_?D52&K&|zDi7^-%_T#UunkMK@8bKfW(x)F*Q*;hGDK+g|X41KO<(o7P-%G^gIh%*Xln9+cFpmzGTX3ee2?fCLL10`A| zH@Lcf3HqU@jgjQfi)er#Vc+e?%``I_wMjFqu0Wq(Tyzm2wmN?$*w#u^*)T)86Hum9 zu&QVFQhG$fR&Sa!)fns}jF!H-jL$0AAW8qZ)OTq7fR(bDp?>SOyBSuv&_Ko_!n>{l_ zw+Zp-(i_xYdDncDDQ&Nzq)?ZsSH=;z68epe@H3+&v*I{ z<)!carQ^ZLgnY~^ze0V%{^~J&O~`5Ttt6-!0-xY4;$mtlYZp=saR-FkG;9>@0&O7n zfiTMqn=OU@Zp>4NJo8m#$+-|XD=4tMdYYz^O=FV!>XJA!(8FEbj-vu`Hokgta8)wV zn5Dk*f^^_ItR-)R0D9m-d;3i=5EuB)IVGwKk0FWgyqi2b=lK?*HXT3QMSLJ$b7tE-!moa{3TE?u~#w|555pT>%1 zPk`HKJru}L)lVh}30(G6hx4GekD3>R(+j6teNUdx9_!SMbHMQ@Cnvd#n_mcK%&P_7 z1lbqNLsdP|eb!fqu%n@&p{uJ4fHoQ!w+C*`bKo8088L3;WMtxlBW~0D{T{caC_+n0 z2KxI2D5F^;9w7Y6Se2^u7ArrswOyPZ?Ia+GQA9xATM-p&{#!Tv=NdPrrly96HCl`> zCNQmqYsXVlhQ!xE4PHHi`-f z9c0X&GW&6=T!FNheY5qXqNJqDj7Q_=nU`;|9wYti!NLB%-6S(TilVK0)V8Zzrt`+_ z=jCMnV|Iet+Izk^VZ8TR{)nE`wRo(j`@Y%&fV5c5&SFo(VFUMT$OqEr0!#F_w3O{x zq-=GhroLBQ#)fa+=R_rHiKER+kU(KBMXV4Hmwi`JVq3E+Ht=DsA^!7gn(3_xg1lGDpUAv65Qi2!3*)$>nO;IZ4T7Vd;DD%%IgtFr%vUs71S;MZ0lMd2#QV12}HbF|XtybrFNP3dYU(K$k3~uJp#q$w@>Bf8f?Hp&73eG#BD*R}dL= zJ;}Sx6I1q28LEoOQ8FKxWemLAvzTu;C>6B3FZu2N8(%`Fgn$3O^ta+=i(Pu5ezDe5 z@mq3`S7l>DJ4@!wPEKZUEtVujFe)Zn_Eh&hj4vqx4rD`O>nUklU@mL+G7pNd;|G6q zSgy|6u=IEd+miD=DPbseQ78@x!5#e$k1X`n<0A|Tv(V=pObKtH>?6&2g(F40MWg;O z$)G%$1Fa4pEv+rIKWGvsxqe$}tTaaK)|Icj&Q!~vyyE&T44V|y69<=Xb$nlPk%3=( z$aM2~LH%G`uKPgE@Y(`Y=q2`A@V2gnKAJrcr^gQrnDvUIiPS}^2xcr* zmaTb}>!2-ou_fWeHFDihAZ5E7YRa5oBS@JRB_$KZqdjtH7HZnJxG1FnxGlfj{;`_< z`u$<~q+IGP=PtptFDy<2=<-G{D?JJ{&v;d97OLOAc||23&!`yhs;UW>)lQoCDdtBS z=;;x2g$zjp-C;}Wu>k8Vv5_ieQgnvP`bZLxjMrriE+>%Za8V~DS&HLy^Y?djq?g!+ zR;;BDa9@~Afe03-QD{RM`oXqjnKzd;qVuD9w~)!532$l0)>^ly$)A_BWzSKe+bvOwReR7Xg7rV)42oeXvuVz%Nrk7WTU&EQ*Dllqh z6GX&W>Z`-)osEPVdg<{3r9TiOK>Gp9ua0rc=(qBT2s?b_A5JeP^Ca~HzAvb-9+$|P z%D`)VkZkak!@BK~60*oHVam0=#zGrx^lPWPEd!3 zKmn(74ES=25V$%;D8M1Q38lu^|8ZR9HgD&)t2HpCkTZn`n|^rq#d%4|M`?tAaEAk( zJCabz;Kx&W^mk8GO$Xx!!W2X}3Xw9QK$)&T8+l&Mh$|I`UZRW+J(T8tc)1fZZuevX zz}n8;_n7gRwYA5{~t&HlSwi6jjat$#d!MM_oKG5Bnf&So;@ax zAp!Y{#zVX-lXaH*uc=uGpHz<0=Yn{OuFho@eS~X2`BZY(7eV+$62mNV!I#j(SV4~( zYi|#<)R&i+cPT6`u_gX|nmiarO-+3lKLj*#7WcTJtXY9=aHpO28C*7=i7heky`}!I z-@oZd8Y*5+*11H5-6kSB`g_P4F>krubJer~7tuw5wyJ5YP>%m;C%C-4?9z}~Xw$kp z8MAOwPK%enAR@rcd1;7VEi>D`+S-8qx9l0SaK4?=Mi@AEc?HZ$3dJ6O}~Q_6NSq8Ql-ub4XFMnQmq z#zVjk#G^2e;5aEyw$yLktT!lUjX2B^AC6B;A#AYFsC$b%8E1{~nDfjQLULl(+_bd= zbs~BGe4wX-GWNdrh8y8yKMRd3Q_z;$+BFTCv$jd(WOeSZJ&=|Zq3h$QAa4EJsP&$p zeU>}#7!}1WR}c5q(hHZIJqLG0us6A-FLxXCMZKi7wFOj5F>6sgvg*048rs^d*AlR( zg=cup!ng_RfIVb0(c6pP_ITv8kEA~!tA>Px7;?J5diANLg&Kh?2W2E|UG9DjK1bVt zA-b`#0Z5`A99X&*;jwu{@!Hfq93u20PFpvrxt*V1tJcF1(~oOj%n84RDr37zOm~Tc zed8E!Ug+akU7r=;$Gg&M`66#$U!6XM{R+dW+0V) z_i6XR<%)~Rte;oQCq^c4v_3K2w%Zo=OO1N+I{?X`sKI;0uc|pZ;NBAO4zgmet^@UW z#-5$##jI2hQ*tJq-knd2(Wilj^NSsexLB#?<7^(XP`WnKkX_qh)on`?Ldb_1%Q2HW z68Ex$&d{pxsD}gAJlg_G8UnW?M}9>zI`F8Da7THyJjh96Wb;Hmp^yL~&DVmx~*pO4c`@?i=! z1CVtEWZzMD|EXd`I}=|cARy?W&6jEJdgSzue8F1G7tv1c9?FoOt)gr(6&em11=($Rasd%W}y=&xjEZfkKBoD`z@Az3$Z}k zXI0a0wX-vbh|Oiq8AMl?y#(5!#GJqe#|PBJ@RVQ@Dd75xcL29m42?z$InI;`*_&xl zgw`6^`$N|(H{pyXCFvb?57w|9UU4}Ybu*=sinVf`NG@YnBi-bsygV;k# zvd!GdSt7F3cM#0TUdELoZZqkxJ|7vpNSFQQ-nx^uSng|T0Tl1+056Qs#KB<$B%5C6 zry?Z2XXWl5v{>4ynVEBxQ0s3`;{uKFT-E^*$nWkF_W`H)X>y-OL zMGbhXQZEwt6qbrmbx2_v|7~obx}_+vNpD;;je)-#w-Y@7HOX@-`iDxb_OSX;U}1rq z@F;O;Q8fiF`x~QKe_NM=6YzQ;d+|hQ?YT*q=<5LUSYw@+YF(kAj@@^vL@rSv?jvas zOsxStWY=)~&kot5!kq{hE>ooVyJ=OVG(lh@(A-Y8MCoO!Me(fWA6{AYIH+CJpSgp` z>dt0V9Jfopz?&KHHe^Dvk|c9`tx)0yxSA*aOV)yS)!C2m9~>OyE$sP=??-gelR(9d zI3n!M^aoQ4rFgjRn|>=kyg;v(jT1kLP;oZCG?nHeLK3W7a0LBZ)8P15QI|R|#UA!_ zCd$v<{h(iH_NSY#jSX80df8c@etyzIEQXZk2lfnC%$dsC$?09pOQ~+BT-N!J_nRk9 zZLBmLKlzPx7C()yalQ=2vRB>Yybj#T>Zt9JOn!-NW{CL5!|6pMjB25g4p#Y!)YS@{A%TUJW7UaEGY)NL0}s+l5kY4PB)`i6$$d|O^c zYoa-{z1V=C{L!pt>N2Sud^(UDtW=S+j{j+UlwOGCK}fD^swY~kCU>65dc%=@6bn)- zjT>tt-A6^=4_P0uG@pR(O&8#KeXItC_NqBQD=fXA8ElxVQSAMM-x%FA3S?hBcfo=| z+>T*N7$fsN(T#qwr-v3d0(N_ss@wmDutoq1Ky|!%lqK&yzgG@Ubg71_gDfMgC5^7D z8o4BLP;$1Kgr?lJE!(KoDeWQ}n+x3_>>$3*5FW-g{o|Ie3F7(y1ZJ#ut;k%*mTAD5 z2HJ5%^$G4!SIW3jJ%90*1i%H4y|BeRiLB>`1|G8N!MxbO!!U+C-2|23(wsv-4Nr_i>cWihV&###T z5#sd1p6bkgE0+c;8evzX6h~3~1qim>^}^1}0`HRh(U6migM&Y#pPR5|+%A`X(QWc8 ze&^AVr+)I$l$NZz$8mO@70D%)d-d)$oXXR7?!}OFMn#|QTGPH1y8XY`gUfZ4lP&3o z`5#5(E~d-=$2;l*n@BM8AV#gL!>KpJ$f(Iff=Fc5L9B3RGSt(Xi&mjrj12%sI8Fkx zEMZoJTsQJqx5XVn0Ut|Zn=XhzsL9ls^O=P@?A{4kCp8w`klNW^LW8nJ@{UdVpHdPf z*}IiNBmkIr>;<@79o%-44*Zm-8v#)~=;}Yq%R#gzouZ-o@)E}PWJzcOqTbSJYj;un z_J9(Cb)d+kdh=nuW3TH*|ME-@&^?u+pGSx~-I2TH3o>V8Q;G;x85xT)!O0o2=VCn* zEgJ+iho=pulUO|EYEJR>N}N21Y%r{xO4<8%qn+C@C4UdB_11$+S&vm(!|%+wcoEbw!jm) z#Q~j_wgm{ZzV9w`n6clvcp_sLcjM+2FIU%mYAP+S$)wMVC#Ia3>?R5ZDlx6#vv28M z0s41B>1Jo5QbL<~B68P9wf!A7Itz+E_665h!Wf%hZAbkU%C0^|1QcRW9MvVh7PG*O@*rkzVr_Dd$i5oevhYYH{LVpH zw?!KEQo>yfuY1&EStD{;<1IZuJ)t|Dc`J_eoZnv1DGiYv#!@aK_yBAfuKZOv!UKPM z!NPwPceQcAdWkinokDpaTCsv7xC(&yk4uhP2Pqb^K-R7ppNL*+oDIV$f~|~EQ;E*~ z_>4O*Vfqs|L04HB^sZz3CNQ?ygB*mvBm#j1?C@Fx;%hrQJ55bZ_ZSlTEfd^XRYbe3 zrm~kCDozfu3qU@uuAi}|B9Qi$RDOKH!`_JGrq{_x($;KQ@joSdAD3_jHn{(dN$PSUi0c@LuL?l6D39tSTfkd`$C z9aRNvbM~Mnt?x3Ua7+wc zjU10!-|=Xvf}k+2!c5qqQQWy!x0v2WFyB&EQu1fVQ+0$woik%ZAUX_G#&2k;O5dFE zU4^MotBwS|UuwuMVTH?vn!aefjf^udZ(9*hQyUqLd_z03Vx zP5=DYJJBzadcrp#x< zoGAyrr}wNq4xo>;Ev`n^QL7Vcy_MYxk;Nsw2T#{X{LkzJ(G&@(`NiqEtkuJwOOjF7 zFGUc~D60+XBL3)Z5SycT!mDQf^v10@;q!T<^F{5Vpm2 z&H4^}^^=VTBV#th7LS06wM?b{I5=aCFg%FL__@>4yx=^tCvJqf$CDdIbU*tGGRoH)3eW3uj%qQ*#_wyf{bwk2oEg6?%GS~PELkA*!;m~|X; z3f;D9BXxIp4nQDFN~DPS*9$j~t{OHFEeE*MK!RwNmK>zuDf}352TO_l!U?j__Go60 zYuU+xiC=hRyY~*&;g&VywzYq~ANUt@;{|eqK-dhIgCM_EU>k7R?B$fhUz6oz2}?eb zvpgtazY=A#VK%n!4Hcy}6IfjJk-84r-4=(+Yc^O#I)qT?6s_b<* z>H=va=*>6?JEo_nb?ZxLh%s)yv+h*#+M`w@w*$W(_$VfaDVPz8p`*xWe1U_8(yZ3? zMsSjeM6o)t{|_*QLK}cUN)ZEWOmze99|RRCK=BUFRG2%iRzG7Uu1enY&PG{ zt_t5)6EL;1F%*D2wF76$OTi2&;K_B2#fooc$;NwdvttsEQV(boN)x+Nt_ zGNu$(HTv`qt!nO1P7dZEVv)B{(v4nwf1&eDbz<*=eR7d7ttBxF^w-Z5Z0g&NK+?_777UOQwcC1F&3Me?i zH4o0dzyVgQ^-xjWg7RML`I`gJZ5Tion+FnN91GApQFjDr%%j3Q=)Q|Z$74GAq>l_U z0Jve>u2ZUAd;3i1rGo>fzFGT_`AToMNLrEjpo@)H(> z0l8TCBX!^4-TTSfl^E3#Lj!}}e5rz4s3Q@=%rJ7RA z9-@Q}ojbnP>FOlcL#K$vAGTL%hJm)GWEvFccfcVC;3`suufl9xTwQ;@;3wGfH-Yccckbv%moQT zZEY=U1UNx^KNI&23;*KB-DLS>_qj}@uQqfwA_;seo3m2 z@)knrpszAwRntRp0vu6io6>P=A>fbvDqZ@$Lc2~)!vY$P8kLw1?q=VU{fh&P|DMHW z!LnzC+vnyli^8`ncfgUVpSHEY3Xw0qeERfNOdJS}jGX)kwB9Zm*}%*Jx-vb%n-*14 z67`}=YdB26;Jnq16}=7IIzSh@+HOR3td&qv=fmQx0Gt8jaXvkJHmwF0w))FTGDnED z_k}?NcfI52p?Hd&;PXn%kXOlZ0JOKA&ENZ7)(zuxz8sB{)lb2Ew8JuCl3WD z06}LE94=wY`AlT)p6g9{IlljnkpB+oYeL<@h+NPe1e9)#Vl4@A5Zo%(T0OARBcG)| z%z4gCO=WVRduV_11IPjUATKEBs-%;gwl@8QPs0;{)$gOC?}H>W$9I3c#(Hp`rF|?5 zuN^d908R(ax@_Op_$LK8-Yy;0`Lk9fCj2`$p`TN^4rqS3N8C{_&`^gn;RSNF9tO7IsqpgP zu?xR;Os5zk zZYkivOzPZjOVhVsAqOqyAkCmSM^EnkEJtSI*U31rRHh=o!tRdXR4#Bbp6}mJ+NifT zfgU^sJ|@-m5?h#q7hR{LCL-Oox4?nHtTgIr7r9mNz?aLO6N6(liJ-|(4F0ZN4^{?C z^_&iT1x%NS)J$Ijrh*GGFRutI|JOb1YjiZsfKkK<7=B>p7QaICRzg6Y$-kgcjS-E> T)*PUKflE>LsZ52mN#OqghXEdX literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png new file mode 100644 index 0000000000000000000000000000000000000000..a04727eb5b718ffb3e7f6c0ae3807a0726a26596 GIT binary patch literal 28711 zcmb?@WkXbL7cK^hAYIZ(H%NDflytW=NOvpUT|;+@G)N0bch>+S4BbfAxq04m{=wNF zbY|GI?^=1SYfYHqCn;n^d_*`nIArOM;>vJv&o$xTo-H9f2cM+&I~jui-q?TCa)N`y z2CuO(p4Hp7tir*O!byvZsJiR#FWY?4S@2-K2}u-Jj+cNWn_eeH^M|t;^Kj)y@6kdB zM#5ORqNhHfp!{&bH$=-Z`e2!mh?jGN@vmDN5liC5?*R6fX>S~VVafY@!673;J<&`Z zF&p{|RDM^-q(uu@=#5zXo;MzJvoKj}-jugSsxpZ=Zoz4>S9qZKqVHntam|9f~ivK;{q z4qx|nB46s<6kGk?oFPS}_|r}VzBpadBrZp2PmhF;Qh?K$7@ANMTv@4}0o(}9ySKaG z@9T$6L|j5Im+v;{uGV{Db_gwohetljOdlN`X%H9=dA(B2((o1T zAA7zPU`LnqcXoX!g?Vq!(EQcw*SEK~*8%nqSb@t&a1W6ix5mC6P`?vGQiNwYkP{I| zC>XI@1h46*7*lu53p)pgiT6uos3Hh(jK58pM!_{UHrM^3Im>~=_3p}H$gM_@Z4AR7 z4NhC5Q#T_slQJ=E2^j^2SjacyJ6(q=oy&SJa@qQDZ6G)UcX7uFLRgngF{2I@FP5L~ z_3}@Le1}!Mm+#@e!lOvAp_e8NiZeY7ALj=%J}|sTcm{{a?Q>ISxXFYqY^7IfH^OVpi zj1aRo^Zv{JPq&%cgL7mG5H;#s~=&=6ZTJqX^?>C$Gv= zm>d7^tx8a@vbbUOf3MYZf3S!Cngm-7XO-XTP!fd%9T2O>e;S(6(m_+yJh`*86G+fN zcIdCqPgA#2h!9ILDyk1^ZpF2Ddc?VCRJVVjkrF{b0B1WP8yws;v_hwGc6OE(GJLq) za_{@t8SvWeV9{l7meHmbJgqp}*VEAO>mxXt`|B~k_PV+{A9{NvY%t`qL&?STrw^s7 zyY+MW>r0BPPxHuBUblC3b@lbt=k3X1tc(0_&>_OlBHLIhw%k$(aLtA+SKm;*?Tyxc zv_B8^@61^}GB7Zh(@^aN6LCFQgq?fd`wB5j7b*)qUXL}}!Sg*S;c~862nrGJ%{Nqj z90cbZZyS1g`Wqa^FJoB(FJ8R3zrQ~?IMA5MhllAy!5Df$MkY$0v)Q{>~(2Nw%F$7)|M1Z7$CY)p2!MV-w0z`lW6ln^W zmzgp@RaR68cwez3$?WXuj`K!nUqm?6%AdmrbascJ?#VWmcUQ`{w8O#uQqs^+(9js$ z-DQ2mLk!wI9#_}-CQOQkV6TsJyV=hovh@rj!#gAB?$NWq>+sOlC+^#7a`S(?m4l^C zh@nJ-wP-{+od_kloN20Ej!di^V{lejfu#A_*hizmIZH*qz3~?GDNTw-@skSaXyMyF zac6~`UtGA>BS|l3VJ^NoBg~aue8YC2`gdol7$%OLjioxbxJJ8xLd^eBr}*uv@2!nb zJ{{e`$V59QjCX9880e4lYgA$fyg(qd&b&TbqnUD4D&-_s*lLT_`t?ms*MB-+oKtr# z)S8?A9jDj$q1)lBr;ZII^xv$GowVKL+S*!ueZ96z_QG}g)WX8fiF?h$7Y;wsTuUrC zXF&tnz8X2I^a1xUPayxzEw{F-4T4QGX_Gtb=*ul`3bzh9`cebe1vzZ>kbl#qDnQ6) zEU5$>{_Z$?y4ctRg%S%g+`Gjr->MKj8BaZ`1j@XbnSZ^#MGS9)F3^?Cw|;nCuE-YR zn0O$`6i;0qE|ZfDt+%B4^BrAlm8%4Q6V@Odmk`e#Z$CT~mI|Rx(4rr;2jwc37{;U%$rNkwz)MJl zROWX}iRzjo%V#vbH$*I25$BfhWUP*x}VZ>w>7w7Ol(MokZV^Tu~XVIXvm6$7K{=liBuDrLG zetFm?720+nV*xGKMXZ55U3ebJR#~jPB^51Aowa)62c))@21EOp_GwAp zw&vE>pH=p^qnU1d@Be4@v9u8}l)St`OqFOb`=%-2wSuUO&u&|wFOAxgzW(>%iD4`g zGbI|01bd+Xi=fnm>VsBxXB5%Vj&!a^Cx;VTqRnh!wC8YGeN6BJG>9`;-_45UU&Cyu z>XAfgpY8GdZx{p=+WrEX@7-7?P`PI7Ii`-)j&25B1B1OIzekzYDCOr?PuABKTTWz= z4pHbd4)x5V(^FQY0Vv4DlAV*~Pp`|vOx;@lfU0U4;in_csWPlO8qdx3r|pj>5%T>b zEHq<{hzP|0PiH`(>DrBF^O}rsl!gI_=z9e#cWt8hv>nZ=|n-q)x5`wXjs zzIRs_Nk68&x$j1E$zH<-*4kl1CvQ7rprA@uSP5 z4R51$QLyBnFv1XE3SXlT{#oL(mD7o){jShxyUgpj(LZ`S%1-m-WE|AhlNXnKcK(TR zpm=$DcCE3jexgbsARyRG?ee?;Yis<1Lk8SmctcIiZwDH!t4>tkSUZY@0T|4bwHIr) zqjA;O%iTRS)b(gZPrDEDDrl4yPVq(DM{$GcuePgM9(xrAOiU{RuKVwpwKO&VV3~Mb z5+^PpuMH;Ad*|0hvmqk_2dFx;v9WP>V4JnZ>o{{G zqn*)AzTL85dc>6EIJzZjX;KUb%=chwIJ4A^t?^YY4w=jZ41d6e)v z-2B_A*fF-Hz<8|mP_9}F7sXRVfBQ-yTd<(i)BKjYuxO@AU(et{EI@V3MvE}9J(D|=H%$M~s; zP){$fu?(KG-k zJ5{U@BAR>tbh(_@U~HmA^zI4{PCvtzUv+o|;=G`q&(+k~-tnOrVIagE{_}?v9RzfO z4_E8(V`ma%aZl4H%nK7I!;iw4n4VUx)_NBv{&33tcsf9x&F{4Nw$Hw^_(usC{_5Vh zWAzdB@fh`{`M_a5RN_7D3p$xBp9-a?VDqacL$CQccP|w+_2Z`9!)6$D);q$d>uxfo zeIr&n?xTsfcZQuTVohl&tuLBmTu`;<{`FRNN_?W#@^?=V!e!+-xw_8g!W92jH8xg) zttK0UIeIg$%2BN!vl0*ig+RROfyZm1$1Q^gn1KxK!qSp8-Y;wp zZf^I#zu%C_6e=H9a<7Kc_9rJN2L}hI-I~1jN6Vr7{kdAf?`CQh%sI>bZ`jjorfxB7 ztQieVd3pK!;}D@l&3F|zCY4w%vs^6%K_Ip9aR~_tTVvT9=-@voCJ%#Z5e{ zs%WKO?EKJcNpm#G4e?uq6LxCxy>GrTXN6>BWx0-0D50U#MC--~(#72i68{EwAc9_x7AR2CiWrII*-zDI8{Ms*v*~timhX$(VW@cvp zB;YD!M&6OdH{}j|DA~}*W!7hR>W{|{Q5`0NxVkw)1s3(Ie6NQLMz_v@4JV81pP!%q z{re?4cD-!bCQ5++XqLc`%Io8$dAY@FCq{M4%d(>XQm9?E|5B*>rxXeu>j>M10uhxc`JMMPND|z|5WSQI8+1Y=q%-juR-wl*kwwKw7{5y&9^ZxQB zvNoH(9|Tb=HS^g+j!^4PEQ&k=F56>=^ZkX|%C?KN_U1T`E0R}m?6GHCV<5V72O)Oo z5B)Y?Ha4e&MGl{Q#-~FWZt*U+SjLzXcOuDWnHn1)Ac`Sy1Q5~zi4CSt5&q}6peV;3K6H^XCfk0kT& zb}LqRL_@M&Dsl#RDT74c`zS3Z_;n*QCdouaMtWb=X3uDR=}G0u_yhE1%ll?Z=w8JJ zyTyL(Ij*1FNL8iJfprZOlIEY`y^FyXpl0=XWMri6;bt!&Ai&#zE7z2&4ewj4OoKCI zWSp!F7bKlHyI~)c(*)p|w^Xd*TYSQS>W)O#P(b8-Pa+H`aD~}9}eXmU|tM2#B zh3H$jxVSDu{H{X0bwVe1sga5K1p3u+c-}3&0DmoX@6TFFo`3|pfJb2IAtw>1f4QRNSrDFp{ zb3yttQ|UXie$vlbrv`r-gtfV~bscH=M&N62Z|{}lnF|JO)W5VQN0?0YmR9Bo^-zi^ z!~5s;hUx@nnSPzXa9NG*GY+_ue!~fmPf5Nu!Eqh7^@@s2`A8#1dZn;f#;Ue@GutS5 z5~dJ)Px{)-EVuc$(Op1#xH^(5ndf>Gm+xspHcdKzSMF8YkxvX^w(87Z0SQK6VI3JkkCSA=jpk~+G|0NwXETe5@yjzZMJLi zrXotPu6%x9bJM4DP%d1R4XGYMjw)d{89J4;CvmRtSXA{#WlEhV6l=QwC;%f|l=hae zE5;aP_DV9>;lO39hU;NDWE|U!Qq=aZ&wi@mh3{vGkU$n_z>Y5(=*}a(alels=3Zi($AcD(h%Kdz*TJ0AHNGCVp4maYKKo z*u5-uE&RRbJ-$R{lN~7xp>DVXXzVn_H9JCA@~_u!39fK|$%$+fs78P}7$1+lqfLq$ zJar%OAZ4(|N^qT~ha^kZuvwY*a@Ez!w-z=*2yI5{Pk&gsWTnj}+r`P$L?v>n)zeO{ zA*%*NeaBZi;GK*0@hz$2ujTV8iTBQ{*j9G?^<9L~a?BbxZ<84=VLyhG-`LglVq+lT zj_A)f!a5G5XQ>$k9~sXS!iAh}@kPlEaDmj(1;N)S!gxlgb4;S@`@oM_Cu%s+5v2U$R z>Co1UAVF2#N!33p($D$sDw&eDFW?_Owp9TnCH_z||t<7q1B(5MA zmy|e2+ficR>e^^1%9&VPh`$Z5v&b{TsgjVS)NjsCB1%PnXyH56u7#gD)g?uzY`h#$ z)quE7q?wPjlngUOz9T1_CgivsecF+xYbjA}5Zsa6Z%eryLf@O7Hl!H%YK`K5mG&Gd z!6$nZ?|%9I@yu*9M*UpD>|w}lUhW~N1=`F1p@_&jqfrT!W|6btpO$?`6l@A2bT$&= zSSwp2|Jm9Q(mh3)hz{KpD|ORwQ=qiV-^W<>^+UR~nU2W`8%W!7cnxFEx(ucy;C-bSlkAny^bjxnTY{K*UmLd z@p79}1GcEBsAtA$3dQXSr$HaGKe<|3S;;ia5zDylK%1O4bDkF+#(U~4OS*=ol%w`Y ziBTPGOiw3zM_mguPiG?)+_A(jjf8Yy)Frtt*1ruhB}>!lk1>0Q7%w^LjhB3h$fZ@n z=?i>+>UFVi=;^&uh}?0b67O`*ZOLHdFaKq!J#{{Gc{#b`xt`OZ!7Wj>%}YlUlfVwS zsi`UNZfH?fQlXvfl*(Ctb$?d6fcl0ZeoWuBb%q>Oy&pUXQN({QF!ZS(z*TI15X!`_ zK807Y{>(J7%O=yk#&VR3|BaB^Y74);Q^SFb?7Z(KtZ=MwtmyndrYe&U=d?084yX=3s4GIazb8vwD-< z-90%=K6NqnsVn|cvE{EJKk-)I&sTg7b&$=X8u?n=rM*lIar+4V9 z5LcgP!aP4C6EfHT{pDoh8x=b5cYqcY{So^xw7Z~d!L+u{if$QH3Q6()y6J>gS8u#2 zy;`&WJi^Y2Cha{DN(ePIbuqY#iZ;|fPB5I9Woc>nk(DetHBspx)-p{KCnPqK5u)fk zc*jvyANgLk@Qcx=1VkPQvalR4T31TrIse<9P^6g_&J-DxIKa(!35grJ;QXwlnMInh z=&NU0BBmx=;*$d2`~L>`H5u32T<+ zmaM6PBxrqoeYaGcW5vXn@j0H|nE4K&Ot(8fQ$_uv@ud0*V+R2UnMYLSl(DjSoHnV2 zuEW$1q~#>Z;@tUtuTM>*yA4^~cc)7q9v*`Ewo@c+km~o*K~&Y9^cR5a1V3scH4GH3 zM}-b@U%G~rNj9EUhU2j?HF;a5q+1S;4ZUYpgCa<)3wi!MapxzFk<6d4P$hl@`q2%} zXw>86Z;v=x+(!zTC7ah^su?D_)jQ>3U29b^R9rG%5bN&0pYyJv1BuV)>VX020}TLy zwYs1DZE^zG6<^=llTb?pbsL?dzvO~oOkAIB)f*&iAWh!dAB^bY}lvBe7qg1}9oPqN9Yj+=K=@1W&SKCKJ#oZ1?GB0shf zF~5NfB*hTBpM$U+NkRYet>=s<`AyJB!ZYR1!o>26$s+}F6c}J7R+>}^(w}5{k(LRF zh>~8<5sSy4-d8k==POx0BPJrs%*cooCj(jsj$-k}De_Q25|%$$?j~xEJO3#8_H`K+ zzOTu-5wk%%bZW}!;qIE*dkqN)DG>pI^(^t&qUv>+k}t$(kso zV}e3kav>BdDyqB*8eAP+#j+1tiN`oDxxaIhLr>hj-Q6{xTY7uzj&wxeGNYiPme;Re zUH!a1rIa7ZIxbeo-n5jEzOEoG(BF9O?C5xUbG`>wr66!V4Rjs1{Wu83-(04a?jRc! zJdlbG%8?0HU{_ZPC4Jerk6%gm`;c9;kVh!fiHgU(LK5ZYC`ZYcO*B0^CpO=^j}&C` zp_`m!7-7fO&X2~F_)%rd8G9csEntYs3$0ZX6G}hsuIioc-R^H(4n_c|mf?3ACy}od z!VuZF-pcufJr?Nkzr}iMU97%o zQ3T~Q3<~CWUvIW_dy_tF!mjo*?7Mh8i3YV?auYp|Dpx*5ZzeDGr(>?}dSRf16k1Dn zl2A_Oi>K;HhC_@p8e}97kI3T({~+p@tN#$kijpimhUqC^Qs76)9HsZqnl@3iJq4Ff z;Xh?ws@joCoa&|lh_1kf0cTxXTMG>c#`nv~{088(F-iM$zWPv`4;&^9?(@2{4>XkTVy+|Hw{;ecah z%_vl*HkHi(?h}irEg@Z#^X+Bm2 zA!?NWYBnqnWsvS{`{-EF`)$1(chu0P%8;YtsXIv9xIW@1Y|hiZM>0k2UaRu({bXUM z%8n0nih?HY9v4+lJY7nMRQXIB#OyV{jUMY?O#%StDILOP(&cvAjJ&A_k@JAb>EE6R z$LH}W)&q17+^no*ZPEdqe?a0o%0~KbAL$i9^^*#sI- zDB296y$048HWdxJR zM9KZY<-uYku*(eUUOPE)IIm!-ja9gk|MY3lyh6>F(D#(}dOyGQY*Vm&==#G<9Cq=i zOuFktBbIr${rQlVmVnY}|MnlBDd3SVP+an>!$m9Ga|D0#&^<#4$*^C@8W{dZ_buIX z&ekHwHMXANoV_N>sebE@G@5Ws(hBLT=oHvE;|cYq`QXdlv_JOBAwHdd4!g zC^J9Rym^|_>IALf4>uUq5!hrTXSLjRoP75Pj z83Chqh@*FkUd=F%5=$~+KY5Ecn&nrbdi>_mpF@RCKUg?uXT+U-_v$zm;-L5r=uyCn zl)TMrWO&#Y)z-1~|nmJA;Y!~8*)31dNzA33roVe%Cqlm$UgolicahH%enbJC&d@@U$7`pS?DuU)i zR=Ya8P)H)7adPEi^mOT@n$gDBPVMIF#&B1EsbtecX18YCrw z9&XGsSfj`nt=VgOZbwE(gAisF24ikL_J3J0`)6QC=nOJO$mhC$3~Vhb3Chdot?Emf zzT^E}{Wxq$sD$tM9sXJlA()_&6#bLHCJi8ROZD$GJf5#MKE>H7Cn$KDV^qIs7mrD6 zdN-PCbocGiX*X;nV~K8=J-b<&d7(EqGXL}dLnwOLNKcK0wx{W!)&b`&8`bMe07!DI z)U~8DLkXL09hne=n$!iOcXlj^w}f@%i(Fr@Ok;+ak7n@rJ@Av{!wQNbZ~g@E&4q$; zqUT}L7O}v~2>>?@at-VK4PwRIxw^WVpMPh*rY@xXczk>mD0*AxRSKk9-KhWfsE+tG zBd^2Xmyd$6*$73!G>8P;2)QCnZ+SK|c+Y!z9s?nGUEd)YTEr(1*zI?YglM|%NxjLM z@%58!oiAZa!w04J&#UNfr%^blTBclv-=p-X0Pop_#C)7EC_OUfy~*Zi|G1;zH;A08 zjW);xtd7k7Nj!+I+Yi?4Q#I~4xz3P~2*le#t=+gUdf-(N9ea3|pigrh)<&`d$KyZ7 zFVlWXn&N2M4=tZjKv)L9K-9XMab`Poxw^J=SYu^k+fe=eV%SymwHY++{n}lZyj91z zozI@ml7=njGX6j@XRK9Sp5oFl6ID?6Qh%kYK^ZW_!(dO&_vT>uNKboq(t~UI;>RPX zAO9P%^F2#nz1#f#`!_(-uF`)&%!#pq#U_jU6XxhXkkY|VjCjxj!nLlh=jc2pM%Xv~ z{Usikv?UzA&0|7Jj}k`cA_&6juho-0bXl5s_L~=aDOU8NW~D6&BR+Is{#l9LaOc^k~HN6L*1)*VEGj6?7jTA5;=S zU48vzHEV17!C+W%QI0N$Vz+z|C_611?L(O6E-7gh(M4_cDcAIiHzHez}C ze#0_BWsRRWrFopEu;APDw+wl9FAQn<(%H;YDsG|rtGg|s#~xruD%Zga%2?aIfSO24~xlD>6^p;tPVf0E9MS~r@u1Syx$Cisq8ySb(XD!XFeK;(5K zxyoGUuXciUTlEc;UWX%e`5Tzh{VQ}nL#XH;$*rR0@sp-2(1omRsyNlki=aGeLiyXp zbPB_TkZhsrl=;0$gsHHH5-l3pX`!IS#-7vK*lDf~;^d0_U9-&jm|6!y}ds395$Jy218b1lblqlqC#@qFy?kIr|icJCG|g`d)V zTw%60qo6s@(X)-yl9D%9fz1+hmxl=U%dPT$eI7V00NHYE2*gUu>5gRqgcO zrBSKxa}7(G!Ste&mf2yjTJV{MQqp1yT{evkh>`($%$Y?p^YG9T(9+xyWVPZ_8p6VA zv|IJv%5+=t+^gt$x+HwgM?ulYUP&`V&kQY4T>P{aeXwgp1d2RFSMbm@Ol%IH5P#Ct zrpchrg1$WdO5>-u9LI(UO_uaZa+UllVMxmN`e-YKTuF{%fchjzUq67T7}W8>^@I?v zK3p_1>osFV^!z>fdE+T>g{n-8D0E&bb&!#a+;^fdGbUx;5}0hePs@H-zl0HyD?|jXA>1)Z9;W=G%DGgRc~!n2+nXsQpwc6F_#3`< zeCQGvZ5r=Sf0Bd<;>+w5F`RIv^a(82qsUn-TFRWnDjkCM4%qMCf%~=M-^HIl4wN(L zw_02V3!M$KF}Gj+jbLu4kyry6o=4IGFMeY-At^=}ILLHu96*4=M4t%eyw&y?C=~&w zC0@MM<7{)3;8P)SMPnYC$aeC=@FW_(bK`O?UtrQN)?W-Ub4e=GTa>wlRAhZdN&>PY z&TdRea@uF5rZ~;uSSgYhh^;v#;%l}5&SQam9Sk@~4H(-XCAMupaI7@X@&JYH7qtc>6(Bx0!oMowB8cMZbp^nGBurIYVu% zv~Oyq#$nzjvPwD`<=Vy!C@NU^a9Hjsl0R~a<)W>Qk0uP*mSpSAzf+~!LZR#$nN{ME z@ApHzE?RE6%xb>F?YPo{`RCS2Dsj0^+SBQo(Iws&(h>%uJjTM&mFWsGLjx1iZJ_qG zW3G=y(_h)ey7013Shuj326mpXg7uBAC9iP{3dd>XNmitU!Fj&gZ>sl}c}bC0Dg|lw zcbyRI0*K_Kk+=@i#^;c`;u{2Q$y3|(ihR*>{A+V@3XCTEwGP3v;r`k&K{1`P{{GnZ zn%4oh)n}Ab_@B;a)C-2>^rG@<2m{qNH@PRbhyC*Slzx!A2b68%nuXYL_#L94l2Jnd zEWqx#Xd1J;ZcjL<{R2f-(5D1`rX+%x-3q7dO|DszGdl;lc&bEhE6=WI5z}-#1{6vc z6=+6hf6j3GWr2YZC1fTtaXDGd>h{FqZs>~C75W#u=S~yT)uL1J(WVXYcR+j??@ABCTL4V`=h6T_g!4Wij@{k z01kuDb6Z>v)G4zO8P2D2XsN3=EF+;l-YMQ&j#JTR-}rIswb0eG>$6kXkRzj))=x~U z{1TXZm|<1SBcHwD@vm>4fS57-n8|&@Za^l}A*S`e8TLc(UcBI9c%)T_==F^IhYu3J zwk7UkQYDKE?GD0!Ny3X67Px>EjQKJAEm!o;V??bO=P$_jun$EeW&j5#xWx6+&#cxQ>{QWG*@qJ01InoTXj zB?(KK_0)%&!7JSHkM#73AE4tXS{RUy_dK2?Yah+Zlr%bEE%~EqXPkW~yxCp53?$fe zfKt4M=H}+6t~1O4$Lz>goMz&AM7_wQtQlJ(^SdL*h*J$uZLijQjBM*^b)MMSj}KFK_)dIlPbIqBg)zs`u!#zN3Ei<1RFt7WOzr7`Y)}d% zBqmPA<@oRc%@T9^zFC_fn#$p zCKPz2<;cD$?oQbNw2ivjyzw7|CX0WN`I54(5@*!*EEfD@g}z*WR!d07A+}IYmXeh3 zgriRZ8U84n8F7l`?X}SPDpCm9YI0w-_e()EP(hP*^W#yLB^%`2B~nu|7Gw+IuDf#^ z`F2yAeJ_`+xsuXgo~tD&6FGp#{m@Eb$l!PEfUqNL1HiAQCZ0vlDT*z38)dv03+c(l zf_B1%LJfV7pvOcts-b$mBZ06Gq z$Xj^p$_ixy^|fzFLU{&$-j6WwZJ<-=&LF=ON=yzN=26sQg|I7-3{GL+C0)aq{j@|s zPxt%@ubPl&{~@PV78jY=Qo<}QKwC0n;s^%_7%0XVh!47Gu1oe;mKFK_m&r%;EgRlf zi_)1JEaKu=42b2)iOI`a)`gz}&<2MNFTWu35T*qU*`&6Mu2KCO^k0GwyXll)On-?G zCxbrp8ucy#xVu(!gHM08`KBCC$%<@HltYmbGY)lXkqEYv;TO-!K|vvvbk57hoWCT? zblpm^wy{j_UKB;x!MU4Gb&JLkZYJ)#c#kxrI^kBP$00E=}%)XHf=QqpI#WMl%0R zQ+m@V#k4MRI=-81n6OQiqDMj1w{2n*cLvCuQvgWD&ik!x^Y5FpQ&SbixPZY}4hasf z6MqxZ-5RJ89tunj|NcMqMrn_i($CRRLOlE^229idE|fCdNp%TxCmQ71lWtF zj#-2V`K(~J<4R@Xv7Dl(6UfQQS**UcX}bQZ8+Af3ntphb|Ch4o_u2kf-ZnH8ZC}69X7B^<6+L);8Ymlk0P9VL{W@+}uzj zD&DBK??IOY2y?9GddTk)%FRJRN8smME%_CThd(Y44)Wq_2R>6U!!qK{s~lRt#cF;G z%PXT1;}RL2z1C`)pIV*Bsmo^Ymr&@hw=Zl6YyzsQKe*`P(_UjKF`=>x2pphA)v0Mn z_XG0Cf7njj?;}7$jN1I74j8EZFIIKJfDL^6+@rT61!E zB!e6ZB!j_GPiUvHj#F`|TO#bPYH=kxDvBrN79chJ{>K2A0m$Mmov&~Ui6q@h{Ho45 zhgCKyAadQVT()xw2r!b!gM=hT|0a(2Q4A2wSm#{(Vo2Ob0&NFH0C&p^MQoEq5UON8 zDy*TAQyvj2dV7IB@prjJ{2w61GGdj8TMu;$_yD!2`?5dlo1|k)Zt&S`VY`xugQ4*Q zDq6D80@SWsXyhumJ?MlRE{QY=4IR*OcHW9ctK~~qG*6oi+Yr#Ydoi{Rvs1!oDwzr@ zywxB&GOvb2>%aVk5&G63KWZK8d+Yd$QDD6BIJk4AOoGVz{mUl-IHl@CTP-MT+xgut ziT@i=@I4)du+_Bj&-Fy$X6CClBnDf%rEJQt}t680nY1}6JzdOa}60cAs>Xj3h8-^3D7I6T>!ZagJH{~Oa z5gj*4w~Xc$8CH$e(8v{Qta@z8`;;Qt`U8~bXhj080cYqr7Q1T*1}PT?duBj| z+T2{V=VqWrpJ5BVqqc#MS>97q7+_{%8k~7qzrudnYO#zRVW049MRit4MEo97eM~S$&BzqYCgP1FgBFxV4KiysIyRc^&si}4loX$=_XTw3EPoXZSy+dThj&eGCOSMV z^fefYN|lAVzJNhiZm?62PRJ!U)Rx4J89qC9Lxteu404wa=Fi_rvlB-?M_x70I(}SV zU&kAuA7!QeMPVrJ!6P70*=m`XWvy6`95CIps6NQ+^04>OvJj(U2TcQ=hEj0k__8jYU0-k3wDe!`}Z8Yyk(!FesgOSD8CKqjt|oI%Gcf+I6GYd^W{IERxz25 zfS1;o^oNnMsl-NJhNs)q2i+CxJ(?t$D*a4wRZ5m&L=*75$Q-6UV@dj3Y9fb1`%z|V zei5*OzK-&6PN%YaCG)Q1C@t=04PGWmeWW2`xPF`zrduj8P1fe{J#@-mM-HVSL`m1M z8y_X*r70s!oMs6)xnEUe8is6LtyM(JY3e>fHCnOjd{qT8iwaZWUJVv2y6@NnfV zjy%Ui34u-QXEl;m^e%g}(5#oAtLGI*raLMsw>ID!gG~~auxEE#(7#}k&ibxkU9km(FIpRJBx_z;*_-I>hJtL&Xrk+xf zq6jr=p`mxLU-4&PW>Qk+(Ok+6JTM>2nn}UK!Non7KrUfeO~qd{dVwH}Y&nB16}rG~ zC1rC#NJIp?P(GK-eQWsV+p+j>T)n^L%uROLiN5sEO!M18sk(%GLQ6A0lBm|eD#v?K zt-NRsXR+Pl8bTZ^FV`yKV2p;Ag%?~)(;c4M>2;X=d^Y*(s|``*kwST>z>w5RG zE2-$FiOT=VSw{;& zB#_Q!cdB(NA#$jImO`&2wjx(j|!->`)LA zF6aOP%+4fGK0o8YfzC9~&PdqUh>H^t)cI()+=Ms;{$SVbR_#8pkD$LuQGX-k9Deg& zdCA~S3X@*5^Ufqdpu+m)kfwh9`l_k{f~^>Vi_~FeUOv8b_TbA>u*UY&q)N1jC(bMC z>3OA}-s;CE{`Z-g9dNk7>*iIioB|rkNBuO=r$b}YKo>&R-jMy#0iO~6jR=AwYWV${ z^8N)3hPFgW!OrG%0~pZn(c8{vb-+OLfIVJUPsI~(RUPBA|Ku4+0Oud|?b{4~59L+c z7C<1+%8oR*kfp#tnd2wROVRfXvui!>LRy;J-cbHk1j;gxLmhV!?TP(sr7-*kOiWB$ zrZH6?Z%Qg2zU^bmiGP=uLyBm%YttrN-CrpW8iPC$zh*~tR6q6OM2o%U`%V`{xM#ZE z{DStOxuwN4mp3<3&t=;Yt&K;&>)T>VeI%gJ^SnaLnyq-VL#{H-^)0~O*SGyo+oxpQ%OlW4T{KjRxy) ze8~p=C)H0%VpMXY2fOk9pbHN?v=Bav=;y2B2v&Yn6qYYSz=0@P!K1A{uzLJ{O~kO ze1X=(=QF!Oo|03JLIb`{1n>#@=n$f!)MWpgUB@T8D8^cOk)xb0NyLfi3Nw6D{Ho); z!cH1dztw%BCY1g4RRE=Q=fc7QVj*en91R@%50D(3%pjg)BT9>ej1Ufr)UQp;dlm5- z>#{0DNXRfEP%y-Ce1afbOA$pcSv=)CiA)B4XM%iu zIv0X@PrX#^4WQR)y)UK%FrHn{beH65$bnreW&}B1^A0)rvJCkCwW1soiW-hue=vU8 zVyVctA|*JBS93q~YSZEQ2vM9yQsk%@BZQ)O^}FN|2Q|G~uqe{e{~1c-OOz-0gI3qC zRQBt=QK0)3kilEb#WiP(n>jiv0~)vgaIQAIGPv*Z)sxd=(*!n8d1tav zmPrbytU#&G5V844Cg0(Qx(=a%ji!M%Hc&u|S7&Euora2%i%-n(r8(T3=#=?(v-HdY zLkbL9ZvQSLnFcysX%3}wdO0IPFiGt8@5}Ypa~Jyyr4A)I%L%C@(GWK$i*ot zf=d0~RY_C=0Zv|WlQQ=+6=!XPT)jW2X2XZP56{hg-&E-;<$_&eHOVCNG-do!Rhjf; zUgDS*ejalkMA3tlzo)IF3DS%GyV16uBf|e1LTi8=M@F_2@PG2(hHV3?$0pGbM@{>+ zss~})lQJY!wc6|P6E|94I4f!+0)8PNW&D5#<>=$%D!t95D%px(r{Z?lPdzLH*g9Cr zvHoW7Ef!|!!j~z5W>4aFjz0ZKdVU5|0z1eGQJeEiTAk=I7{@h;bej62Ctx<;;9N&PLZC3yMSrV0lHrkm#DzZ)mZ`#b^=tHaodQlImgcRkUv?TdYjSDzn zP|ez#t1LHvDf>}`EG;c<5?3TDhwSCoWW_3%#Hg59**q1x;$>bcEVc37B0&r~i)& zFi-$PyZT7M%E?LPhr=IWL5&kpdhhTvg%*9`096$e^yX-XI;|>2rRlp$YsH$rbWCfw z!cN(JJ&OKZ7^%7?IzBl%nH)BQ3=Qr147xis@)L{o6Vhtx{$dQGfZnaTSOELf3#tH! z!g0|u$gr9mMji(!N1=MyCA4Lt9F=VFrvGiw2hfoLSPMR-U2E({|Al6|YEBVEv}4p* z^;sOQ=m_U8fK*oWci)@!dffB77h*a>`M*y%WY4{YV^CkosRO^(GlR7HL@wnKS?K@ zZL@k>@f(1;fJU?C-$2rLoyL52L1i;(#I_9SK+;-R4~zqcw(vV$*7dSp=a2y->?gB= z(bm%rJ2Frc$uG*0Sp`G16qDz`Qv22iKvPXP70e!cU>D38jz3SHBwwCghLcDJ&>uh( z>&ZbnSFuWI(7~P!WD7r+>VMB^DFI=cWdb|-AnS7oXtq9B_Np>OOG8De4+0`pRFmM! z`Qs5PMT$&S-Aya6GD6(Ap<6cqTxNmT%5jQFy7T1eW` zKrQ=IFr(wMaMJIL;ND;48PSKu!PN|}13KGPtvcl&N{2>Nga6x0dRA)f^@u|p4rdYi z*J0bBfGS-q^|0i3TdDnk9yeqkv?~U7Tm_PyE#&#Hq26i~VY&Hy zrM&XtXCR(bZo|`Vipt}*2!TAI?IyZJR=7V&^GsN;K`V)Z z4nk4@XwxMn`yVI-Do)AQeE@zm;aD$G>_(N(ae1=8#~*=Zi}>~VBr@Myr)!Mq`scG* z+X{pr(HkNMJo@q4H49{M^%s0DE?v>tsn*#H=GTm{P!E0X`EXOBRxit?nt ziJVQ5%Q^7!boGWFJIkQ+lr0<2Yqzxc)oUR`uA=e7T}(wCAop-&xQq$Opz{le?Cs!K zG)xnv1m!>RV5;mi;Tc!#4@IKG@>QgMI*;bM9Z4xkNzhzb<4a)6SN~Qh`6ETB1wclV zOS-rAc(4LG1%2WKhLYEUpMKTD{WqbyCRTgPa)5={=HAF!_m59;pz#wpLpb5uokQfC z=g&Y(`)HP)vyQ?1HW&cz)3ny?z8Rv6CBQ%o3aaQS%m1udmCxCn=W6_a+WPKzs{8QoQ+KzJlqeJuLS>V^Z<3J6 zxXIpIvUk~Anc0z@5e_=Wk*p9ZapHusj(tM*dakeg_dKuH^LieCoL+Rk>-v1I>v~`7 z{dKfdG#=gl?{4MJKm)wh_K-p{$Jl*tF0Sz$JT6edxXRGV^}u7wc%}#8yp1rUMtE)BlDq zy)VCD217>a9EP`q&Fnu^xVyRg>luGjKtvb+*t~G;!)&yanw_bszk6)M#!T6b)A#v~ z*Afu*G`*Y{J2dp?EF^ZlnEf2~7AA>=GTAd@$obdBm?xF*1TT0>|tL;%^VvI>yJW{kbFQJ^g(CZuP;mPmY>oZVV#a_rfLL>Y^!yk@FD{It_<# z+#a`tdsNyilV~gQOv%^9x)>i6oGvlM(KXHtwfieQ$~8^|EdE29SZj!l8kCy4Bqk}laUJU+uczTg;h>O3sIZ0KEkx&JN(=`w%| ziz+I4hSEVrOa;p|4vG8@R8yq(f5XDOeaOR`ncw#S0+MesE^%*ljs-UJLv^9)k{#vo z$|b3?7o2@a^Qhq3`eiCOcly1+z!vPstoiwQ7}ww}mz>WQ6c!F+C_g4%;Z{yfgQU?Z zQ#BLh{#jnDaG((zfkF%YpHEqTeu+wX#oQVS6dDbudE&0|rO=vsRMh8YfEI}s4P4}D zgbk>5#zN>4^&5i`y`baa(ItxG|0&j4_v`uNaGL^mDI9c?lf!*nW5dC?^%p%WD{C$J z)c^do_U%Jw*6D>y$T1%`F0!4{7sw#_@6?b#ZggzqyzS=MA;J|3GXdurghW>;Srx>hz^64mEQ&{Bak64-cAlAqMSh;|NlHX^ z3JP!&Q25%_yh5k&UG?}+FLw$;k>&O1nJE(z*eIT9dQJDh_!g|s)2t^Wnm049{azr4 zlrQRAYDr0npL8W}Xp|g4HP9MK$ui#RNh~X;Ag{W!wT(@LN+(D+zAKok?3lfPiu^vk zel-kn%0)!I?fEPO+)vzRVcGt_pMXVC5fMMsh4fFRvaTG12$aId(o2Z_&iXyViW)iw?=oo`Oq1AhBU|G?=?h4x)k1 zqd$sqUOz)he=?I>JB9r#dmTAGB7)B?*AfXpUSZ!cbdb&j0SGoJavJlAcebd>z~dai zs+RL=Qk*>t5Ir4P)TM8^|5W(&FcTIKFq?i4LH?NMs_Y!>>|VQ{gGNV3m&NOBE?!Hh zymowrC^12#Uwiq^=c2(k&=XdOMW4@}@^x^aXw{=e7IpG_0kc@ellSzJ!or1>PfKMh zA?CF0xMVsSBEYW7Klm8g6*D0>tS%$o_Z4aGXK8;bAyLqer;nhiI+FAJocyAVxg2aV z6iWu?4h#l;lfmQtpUKuYv}=k>Rbw!@yrDjT@ldZGi#m+hlTbgeJ1K;0pcfVbCI18T z9|WwdtFkk97`(1UczZZywqDEzs1!d3`ki~0raY;GwA!-n*?*(bAA#*^6bczb=UtxG zn<_OqFPvz=Q(yH=+61L$@8ctWId(ziR>$Tn_Yd-ciBaOfiw3mbMx{}Kr@(b%WiVl)Cf>z@T4v-EUfML zjX2bmm-kJrQczOPuJ5>s_XS?iP*PIjNnPJNaCCH>cT0D!tgPHSI1E00PG9=Wx4#gl zx)=JYYs%Ky+1LPK)`F&?F5-Bz@6z|Gii!$Y54iK*88|n4;_A4p68^2#HF0;C|Ud6<%z>($dv;>4*@T+ zQeL)%Z_bDS?yCL${n63OR4&wnZtk7WMycfpGN0p5rG=oErx9~gSC6)V0t+wEc-2avWM)S8QHJvyPtK7~ zO_f%;JyWX|HF}k}i~+&{BO~LRH)(FWt-GBKI0@0mzaQo-1j6NvA^CjZ^nevHO5)yY z7L77*(b|HVU0|~($1qRZdgjP)_ z^8?R-E&BK_S4aepkk}!iL%EZc6+12I4Zua?4(kg zTlQgtsu?*eJ=%MA*zB1g_zmC2u>%qd&&eRw+CeBdV2yCY!{QPLi@hqRH#d39xSSmv zK5_prRxbcPf=Fhhf>qDgaar~u@El$7UO2lVE$#MWaYNdmDUdKWzp}EDjQm`5SE=~@ z<0n>dad9yr>zS;HlarHrVBjO?$G=+FmK>^kabM8W-P|jS~4T!&6_t;jX?_DYoA}R zD*ch5sSZ2}@c)wHC*6WZx2HACuNDrAF!2MS{@cKvk&b*pZ zEk6eBGwVCCs&&0N69$HcdV1X!0+_y~(S_3bzAJBA(i8SlG;L`N|NR$+jy@9Bp}piy zr>y5z&#sT1(``Bm9xg72#w%L1h>*2F6P=x%ANfA=^xa!nSb$dJo5^XqIt*a{e;U#PqGQ$N8Gmp@>8a|y0kLYz%Hk+58p}Jx$7Drqi4uMS4x81 z?akEQ<%RKD%!~Vk>a462@m+(z)?u@2ier+fPG6&PcXux@!mW9$FSG{7s#?|j$UV~` z?|K!5E(UTKM|)NlY}x+otQ8;KAFq2k4?6YW&V8DVDsja1+WLA=H#Bh^*ssWz#~O9V z93c2S01$(O^~K;#jFpt6bGE!bE;>$81vJ@#^@hAKUL-KT_@&k@mHDR#U!CN?3v<8! z-VbOQAj%yD>m#`gYJCHPZ?yD4n1@?*bhh8}X>Qr_Z2{7{`v;rO>!m=nX4`F%G8iuY z&Xo|iOMuKpPtQGd^>b8G272=g3rhX*Kw zzxi11=psTQDJD>l2yJ13C2vN{4zzS2`vH4R+Sre!@mhN~H!VC}Db#*Y+&zmMJ`t6i z>O}0Gldo@v>XSMQhMx2k13RUAcg#O5Yd+1=#!AxaOxfLM?GSj#U3%=p9IR>_mzR$= zosWh`MlgSvJKg|=#`U&$S4)1_*xTDXJ9FegWyn2AQ8;5JMZK<};b!a`Fd09zdM}zb z;`UmK4!2gu$Fjx@9mngyw#YDEjX!Q=f8zOHiV5w8F7KX;g#A6RCox_{jM{@GnX_a$+hke48;1WGNJs0CoY9q=1OB*&9(hT|=F>oIZ zb)EMu1k#{b0-pR*a-he%I8g9|fusEaWVms?1h?2nZ3*-!>)!FW*L5ZGpnoS`DO%Qy z0NB36|C(v8Io6&mzM-u2_Uz93{|{@H9+zu4vI|i)}XZD z2fV#8B6Lf0b04il1T*N*d8eeNQiU9+^Dfm^Rec#6O763g@MAQB8y{0G&^*T^$qZ|> z0qlBzF0uIh{&^xkZh){Zpla0I`VX%KillPQOA@9)z;`TefbU-!sVRbuMp(BL7OsH~8tdM8%)266jHljh!1$xhMV*QjQmh+$jL9h%tAe-V`j)V48OJu);j zpR{)p;^j|uMaO9d_l2#O!nVw{|oo2tjBYAop zbT1o=g~y7E+gzG01SALZSRgyIu$VRG~ESP9U(rIa9PcX>qxB?ZODj+c|Gq7zS#Q>@Vmj{!uTIdcXUGEH^%@L;dWU`_o{T>%Dr;#VBh zg=cC0cuCq-U!d}2fQ>$2RkPz4;O?${#r}kL7&BK8ZZSDf4E1>qA{ieapZ$O%5DOHP ztD*Ixpx`>0{OI_{8>{SSuf&hvZhkoDKle}5Gs%9e|K7W@CYX+aqd)=S$ZU1bikB1Pt2XQBbC$l;XC;Xj67hljy< zEUfQnmV6sOJp2}X8oFUxfI2A0Z%z4>X}QUvD$2$%(wg`c(Yt=- zqkLl@+XL8d#x9Znh~x}_yM>=FCSTPtrcw&T+AhqUmi~Eed;f$?4jSxguT>4~3GLwL zNnVN9HK)mp>@oDb(|AALoB`a}*z&5E*Wu-y2_pRaRihY*$I*Gv^-a*`2-_L_ducO^R#KY8Q&z@~=)~WkVQt$X3 zetf~&+}sT5a|pOJyT9nXwB7MspH&-?eR6-eXR}F7I;X{DisT&2w7pC>iAu@0#TKur zt)sm_u+?&Z*{U&?^t#Jg@>RjAhm$K<$3~v5DCep{O0my5#re4 z!qN8CzxH-_zP#E+OoIN(c=N6L8jNJow+|oWc~bF!eE4FpgZS^$;2%lluzuIgAKC~=*G?7 z4t~z6c1RO1bNKG^lj^kJUXnnpN)amGvO81>nij_(_H}4zX4Pxu(^&J-QN1T`i=&|@ z)B8XIcITa6VuIz1NHdA581Z-#J-6F~d2?*hdhXh8IR9rS4;}_N9h`F$`$)t2HJ?$H zLoJxa!>%iZd!&j@B}E~Mrn`3!YkjG!0h`CB0^Cer4gxN94E@3+eLi`(*%VMT=)r4b zQ>zbFx?9&o03`9;$b3qWAId-3@5c9~B`IEoEKIR46L`Le;nOAe& ziu&qQpPHKbnzI3#3BXq@ZtM;ZZ{{4W$s8Sg3G8U0WJi?Xh6nSh$Osz6D#ykLoM^lw zl?h85oq2&~WCWf0j-Qd_r0CHdb@lZVUQ=fcaaUsRfIFS3R$#mTLn4k^=KKp&x^CJ;hA!~X=oZ;I zQA&crx7!y5EAlc3-U|7)4P_tIjin>M+x*3gvAcTRKvUd!Y;KJ4e7f>tGt*WjH=Iy=E2As;w@>B4dsch3d<4qm0j zhVoJ1C6)un_pMtdI9NKrL+=x;62wxg@kh-=cCjs}M94`!{nKM1;MWqD{+;U|1sKiO zFK4RPo9&4BkiT)K`HM|)X%C%wOfn$CW}}?+mn>b_VOE%@Gyy8;3^x59C zhF(SxdEYHT_y<>qFKTN`4Ls7tNO+6r-IxoZ|6(mUd3V*a|~Y5g?{y&45y!%C?Ul%)YJy=QLaNBt7`U= zHjCxdFIQPh`lo`nj*flnO?`c8Rl!<==z9h73U%g!W?@d5?BwTCjU=i``XF3~-kA>R zA^BY9fY+tPQwJspsrqxHRV(`5>h|TQF;xLA#w9_)-LFunbG67j0<=ExS+vJd)Uak% za{!^4Y-jKD(o(b7#|>~CicR=!J5_SkvcvgI0lblHW)S-54fWLz`KA@;V97FFWj?)i ztiyKZoY}PG}xBMildMjx-UH*-!sWW(sx! ziKG6Tq06yhHlR7+e>7;CcV;upbX6Rdy2``P>9webe#i)w#~9oXKsPsM?ej+=%#cFs zJ0r`>d=!f2H6s*3vN(6Ow%e+M$F;wE-!8+7NfWjlC^f9C!dwHqoN6FG4n%X^${C=I z?wG!<3eky&hfb!k>Yq^MV})1LXs2t0nNn!49>(DmUze7G8>_HQN2a2IJ~82->rO~U zM#kR*4|`{@gjhpueqlVl;tMwAWe+@GOxtO06GXJnJpeTTAORRoD+BZUl+rsE#AMyD zuqrg#?Je=$!irOo=C!;^?5^E@%_&2iV6dDL1P-ZFjqLq7GBQxs=IlXO<>IAx=YC${ z6Z?L9*Y9y5)6XT-n2|ch_)Sql#`=0dmDgL`7X|X{h~*^<5s^sFibCN{iiaVA!zY-B z6x1}d{q^xPzk?>~2{hzwZ*&v6&2sKn|6Pb+fEyby9DV-9lxPe;RY-SevzIfWm&MGv zCFF)iUd36Rv;VW_%XJi`uj@*Q5;9%&QjAwLBT7p%U0+nPxOCKr%JC1=v(H-|4p5+e zAF%Y-JT$}H&wu50zdtoVrJRB#w(rR4fE^NiHVu6$_Y;} zKWca<-7j>?NMsiq^oWV{os4(ycBKs3aVk< z`2|J{Hs1+u@IHvauS??GAq>MWdqAT@TkY*mj3Yj{l{sf1kRuhai$lZE&m0&1Vj+K2Ig4nsmzQ*TfG$9bTAa;LGrl|I1ysXsWk`VfSsAv zRFezGI+p2*a}NXpgnv^2PZciiLOMb^$GKl5y1=YNOMHz}aqas*e&W&|KZ0_Idth3u zt*wPF*Ww*}tKAHFX~@%5Now!>C)S~Pw>v2XoKcGn7z1I7*WiQc!@j(<1=4^)A@vwA zs&^vA3%XnkbrbTP>KkGH4SFZD;^=~{1nF_^kIIL)&+y5SejuRujtYg1H^4O? z{X85W&t7c65_NA4HQ6pStn6W@MEk4+DcT?&Ud3hGmi?%ERcc2UmR=ZnQLc?oe7UZ$ zlqFa&?bGq;z+6=VpHtxa&(;a-;iL1Xutc0)Z3H|s*hYe%t82{!F}}t1d7*7-sea1s z!&W&K1BtA-DbZ#lb!{4)JC}XZ0O7WpFHFyN8b2lbuu2B@&&6U~NX^V5-Fv`YY9P^4 zFJ=1Su#6xDYerx8T6?Z&9Vd2VE0{A1nC00s=(F5Pc>RiwMIDxVTJC*h9^VrNk(fM= znxq&y^P(HuliuU=o+(kJehDE8Q7pYtKZxhzB#KTXBE3d`64>-oEEQjz{U_B@ImNQe z1^kdQ$NebsOxM+(?bAx$;w(vQtFJikNvEn@Vh-&_RK1j+#n4xLO~Nw2LreQ&?cjZ7 zzd+#(%NS+VuUcvvH2>T1chDuW!70@S6&NmuwbCWh`Oex#6dB->Eq8?GZ}jU%F#CPY zqN2j=c|LfLhV&wHv*dtz!t@@NtG9x%dT`~1fVOx%V&gOUYe$gnJ_l7B+lNH?}Zqv_P^f;wrs)rt8F( z7!{$NZGI$t^;cuq#Zkig6C%f7Pj57Mt+G(@cjoa;XNH@y^;SFL6WC%M9%+ArNZx>l zLpW!kphL2%FzGex{mZZVMKSH26lLVbNGkaL#j>IzKfV3|}YirfSJq;Qt#o*ix2V8Hf zO=X75{ad2bHSvrL$!+-Xcaj8Smm2~a;VlDPmNgh=QXw__db}xJN-t~}8b#BX$PXg` zVADP4eosJ4w$uQ%guHE_QjDb@mKYrc1s{BvsaLkh z2?tYC(R+zpTf>j(6kinDVhs9S81zzFc4n`%@wI1dG*rAPy&3d?;k~Ef zRySt5J*k9Lk_Avr6id}Mp@D~BfOhTQJHQgW6WD-s#DJ%Zt`?u=C#_qeHA#H-pDMuP z--=4>yO*HFlL{52h`Sm|Ff6EhGa0N;RY7Qk1KuholHZu&SxgllMPi4%7-5nP>-96! zH(P{((ziLAxCfb`Q}Cb)T)+JX)`6aS5@))GD6?Jc9dkaqq}~~*l9$>EXIz~6U{?zj zN^q_h6>rdx$5h$X_Rvw+yk6yR9UB{CCcRgXP_dY&L2=a)?_pR!L5#L$`RWe&Vf%EQ za-Cr2j}`)Tjw069l@kr2`mYC(wmGebG}oi@)@y36Y4D_)$CQ+cGf>`Ei?$X81I4D? z*w`3T1uwrS*SV-jwQ7~lPNkP}QSk+W%*5kZSLS2e1P&D^TipRUx?+CV2$8ozBfC+^ zE!F5XV8b_V3Gi>Ck9*c5fU<_{-4`K8cmIPST_Y$Oj5+Ckvc3Q(%F~Q_Np+n?Il%!x zJ~kF>tgEeUFiztcO;DUN6m(H{33NsWK7O0jC;j7x!J|jf9Qvj=^Q~&cWMpKSY6}^=%C$U5_CV$}KJX;!`N^0nK(Q`Hd;*jE!7tZoPNZ~Ow2P{b zw%pU5roZ0lXC}!(5@hz3bA+RU_2%a2<9^024ei^cK~8}K=YqDsORGl9D}>6Qpw34< zzn{5|aDP`U_9tXE{mm;(u_FV{Nh zqVw+hDNE<1vXx8_TgH86rdkepJ$h8Lz7n_2gv!^9IMn0mXiv(HqV>xWCKtd;wW@J5 z0;#mLS7JN+GDJE$@9U*h8eru2+OS>*oa1UFrVL&Re~@u;w8EZ3NJ^sy#daCs@Ev{r1&iN@!{xnL%EyDH11-u2D@`YSZ<*(-gx7*}%`4}kwnh1Q?oIF6#aPeJ8f|RX( z`LKg9zZ^NLFMdoYt+PfNcWOFG@`<| z#faaRJ;8Hy6Ro!lF7&Vl8eJ!@-g;a3A9m^1S@PD|?Q=!|<47(Y;I zqV5)eofQ;ZC-6!i4Q$Eqg{8=Sx^7pG2kV--4){bbMVsqV<5kmrLbqpCUCGB%NDi5aqk zn%niGFi7D{$Mf;4tCX1r(V)IAL2(+^AE9-38f&OsvysXfxY90|u5&wjIY2!jALfi4 zgki+M5O-08zoX{00uAlAVWHRvXitC=5nWi@uLtC;IZ9(j&eql(QF)pr7U{Flx3GI~ zIB0xs(Dl_YC;QzK%ze^(OEr}+;LyA^K9vbk1`xah)E&b^60u^@$-%)U-73A1;0=*) z%8bQ%yL8A|w#R%~S*hUa&7(L=Rqiasp64LE2NN#KOG`hn{=N>sJ%K$Hp2YNY(0K{C z1Wb2q!b>5{S)i^3KYl>kxWC`D*Z|lXE&@pgd*2R6wQ!eyNBpq66h)g;{iB=7ANb02 z-aw%R3J`M}KHcI4zj-HR&tHIBh8CQ;&1Hn*hdpmV=4cPTw{NOY+$pZbrFd~^a4Sx*6nA%Tkz&P)dx7Ha4lV9d+zS+U3lij>^t*T7 zn|W{EUoVphOmedKI%_Zet+f*NK}i}Ng%||{0-?*wfK@@Dr`jOUlSSmGz&pwP&L4q4 zuN-6`&L9vz@IOAzlRCSWRS<|0BnuW-_b@nE_H`iL_NBjuj_G2)6~iQc_KDO1*@8Bd zSA3p;73J)=6V7i(h9jN2I`1um!(dp`hqUH*jJ;YtWs6HQ8k^--%niB?3lUxV^esv2 z8uMoq5P_DuDqlRBkU@d!Hlywj^|CTQ#3Vj}KGTAD$30RquizU`$VGOJEH7HGhJ8dg zzafoX41WYUwBLKL=nzv-(1Spqls38e0J>dpo>Kv@-2b0mYkzik2Q`(ACMG5hE3z7y zne{F`2Z31G-U^u|GUC z-#rh=B6#P2z1KYI6vjVsXXDxLO|))yoBg&&$<7@9T>-M$XtL1X?7USHtXFVh zc+lQ--yY4FxgVfJegd+o{7_3r?W&s6A1-QrtujR5Uyl_80(mDVCs!T{nwlEv(&gAb zuNOZxmzTRU4G8Vz>)i4V4P|iQFtK|I+EKT0HnUE7Cn&f`?x@Z5xR8Hc^G0Q2Nu9{m z?)Xhx>~3gN(Y##76OSjO5bq$suj#QyX;A%(bvdxGM;aWTDvMm zW<^C{8kS<3bc4+F9u{7^D%G_!>&_5XZ{F>Nl`L+fyK?$FWv-UH514utp!@NIK+z7a zM08bGG~lgFtl;=z6Dh%tedEyuLnB|x+!#-4&Ghwrf(5eP$?bxh!+sYqzq#K_#CoP) zmpwxf>-3F7v&8@z@98Q0cOS|$cFxKj!u7);{?H3X2e4(T z(w5U%!Q;3ywyQ>EVKbo&jyx*o0%FACV%#@xdgoT#WXRi`#u&z}f;2nAf%=|i+OKP?O z;5i%MOepctWj@s0ehV>ey3FIvng5$NPWAVLo);5)SrL~2;<4~&AP?QIi6DUTc_D|g z@AKI}xZP`5?jOUV7;4zB@F%itarV9SH!%se2E1As>kcfOyo%BEs#w$x?8p+I zX3R3u#&IMF-y4bHr~rq*Mj`T8NPI_ha9)j4x>9z~YVPKi$Sz!JNLnrVIrwv@^#!rL z5B>dUpfzSt?$6T8fbr(H&p^aQ)zJ^(r?MS9jMUb_WAw_TWhP2zb=I@x`YpU194cM! zgk1OV(lBb|O19uXRrX&1w}`AZI!_R*ekns+!(T5;xHQ^_t)(%Nm9E9E)kxaUi=m;x z>dq<8nSxi)Wl>bU>K9U?h}8^jc?PQ6bb24AW9g%Okh$TRCq?b~VwaA%fqo15+);tc z@tQcHukO$Eb8KL#St;&jy_;}kHBzQ;@sY%Wg zC;Ba$kgTH3#C()A5zWfFPT+0je1s+^Z1`6 zE^IZ2g9HvY8l14gVmWYXzO9|zUb9k*pt^A!$Em7g{iH*EmYX?Nta4SARPH;Tcon?O zsUo$^Lqgx??Og?-_uz<#h%I<43g9`+s+W4~E|8GiRwt3`2PQo7@oJ^2i;IP@Wv`bo z_0b|HUXMxeqW8I&s>SuG*|tevc-r|V`wF7LbhzKwBP?Tq}6xz|?L;JG&uDtRd$ zx<>H{!_i~yNWQ#!6uMuuv?qY$<)z3fpnCuySmS&bjtJKwg1XIf6a z<6wkv+a+y`Vf$JN68p=D-X-i*bekFZ^1(}S<=VbHnxJ*bSr@++tBdQ*q?xA+KH#o811zsQ zceHUT1xFdzohR0V@hTiIm>Wxjrehy(WDfSL_@F+MJ|V%4?z~V&iqxtKVn~E-2-D;5 zjn+xW1ut>r59RqjnKLBt))KXC!?z4+X`!JqZN^7ohet=IkIM@>t4n%Zm!Eh}bIUj* zk{U|lbn+-`9!cPs^q3K@hC<|g8WQUVAGS>c@-e121~!bLWV*8Dm5CH+58s2UV=TS; zEYSmEveG+6D%6IZSGm)pi5nVMz&vhA0aQOH0!=Z;n!7utobM zo*Pp$GqbI$dhmYU&aE2}Wo>D?rXs1MWR3m)gh!jR=b<=^h{1!*Y(vYz zlC@Ev>WEqlVc*qx%hswD4Y7XyMu%&9!FOl(LJ}haUe$^Y``IL_I_BS!U>mEd8XZ@1 z^&*(Kc7Zr5u1nX9USLZ$G02}bK_x!9X@ELy#NL(&+SBmPBL_9CV5CaT%6!(FAHVvD8^+?}sxTC=OLbz17d zCz>Ty?29#{OC!2)ZScfZzvjg_6X(s+!U7$tXxE(8?i^Q<$cv%9C3vTD`^oL;Y}gJ7 z^tM-ih~!UOrbo(Y!B3;#k#}XvnWV z!LY*OhXcKD;h()f^M(o+FH4jT3S31!_MG~jwQFU0CxjZnM`n9@hqUXV<>s5_()3c+ zs*ajJr#!JRuD*1&6$^m5dq?v^3kTQ!?oA_1^@s^@5BZg?t(+O&$~Mpu*5C^-UxS7j zv&j6>HV+|)CKk@bANQBg+q9&)i_zWl$*|n%#2*-QKMiSW#uq&8@G;y&x|Y>@9GuE1 zk+W@istMaNSlC9n@6p;;E>OLC{K)~!m9JrU>hWy^)9Jb?#lX(H?GB%KacLzp%~n=t zmPK8oZY!zA{7r@hO&n)pc)pZwt9x4*cK`J-I_Qt#Tu6o2y6KzZtG{ts9~lda-`i~w zaR|i#p7`#m@;UwXyeo?Je#V7hO-&8>2g6_rmpKqB3` z~oMJ^+k|;l4-^+!qp+mga`4kM^eA4q7ZrGEs{i zX%Ew62K>1<{IFsEaAIOYtw8Cpy`#NV^J(f7B{E4^mNu39lkY6~Lvjc0H8wMNCNE!p zQDiMp%3%6Rs1QjvBcMSt!E{8&I_)pQ#pS&FJ5S0juKF%5)oXvH4eIgsv5^2(qOeKl zk`?5U!uXnA|o{5m`<>O7#Xnq|p3jCP;SbYHl5Si*Xgl?Zi({fVL# zQ4qee^h;17#ePqMoGbZ}Y)$^!aSB^)#i8!V?|G$5$Zr zQgYnJ;>T`4CQ?$p`kE0Pb}Lyzr|xi1w(M7}Fs?*#L*Ly{q)pt$s zc7czpt-Lvw+e1Eto9PP4!&&JCx?8=sDa|~lc1&f1qa~{5^3%rKy7{8K8-<2?g}!wv z;dPJ2w|-5k*A%ZFBSX#8?_90VcA@t8{sDq&qm0IJizLaX5kl&ZjwT}#94}^PXD!Wd zckWcuG8)Og4JX1`O1H}N0nr#v;R16D2sGE$a&sAIGlMpnG@r9scp5FeF$F`|%-prSk$+xl$ zuy*s2?!S)@+WRth@rS(1P(s-YMvHiMt>b(9`bKOC@*l+1wEV86w1rk{-N+O7ZW}T| z3lAt|r1jF(A_c5T?A`BL_0Ug`m+p_JH`6XttNpG)pvx^LxS-tsc$2&viz{^g-TCCS_ULpZi%nVJ# z37_W>0B*C8*$?9vSDHKT)ZdL{q@RzsBEDYq$XV@5VD7WA9V==_C6(*u=2IHiM{w~p zjyH8Gkdm{dZ#&EJ`MchqJznU~Xy03hbt^Xan42B$8I*7?Rr*>VB7(y5yEQGsEH*!pN1a~j4ApIX*^fMq{SAAW5xxbZz{kb2m+ z@96C)-3qpuH=`Q5)@dVHWxhOYShYJ2;{s@&TYRA}$}g%6*1~;7ZPYNIv>oJ|XB#oJ z`sOgpR=KeBvp6uTJ*R*39jq!@1A}Rz0$BFIHQ)Gb)6jlo-E4}NzC=CKR%epzpVb4 zQWAi0WHA`~>B=g{s}sMBGWM^ZyWBbMY1fQX84+d1`pYl6nn0c~!ZObA9OHt8@D<(% z&fxuxw9BlQTQ8Zt+a#^-5Jvd!AF3HSLfals=;`Luiv^x1ABNH-_IDyloJC|Pk{2U499T)(dXgK9?3-K{HPC;T?2MrQLnu*R;l`O zPTj-Pvgi(nC-LpddkdZSYR+nqwlIZcL_KCbW*3^|5>J~J%FP|jmf0HX1B3JA)_5uJ zSB~#9o6w2nXGgrb8~ALu6)0K{_y`E1IvxbDM~e1by3H0lszwwE%+{Z@#x|vTv@*oB zU}I45pb>m5UBErwypeNbA2E(*eM3vV;(Oc2-ge>J0ToK-cZAo^^~iz!FGkq!ww1B5 z+pJr49j7fK622K>L(VVJFy^dJJ&P64YbqlJWw3)lA2&8z+_StdHJnRA^hLd4-pazJ zc5iMMqWx-*Bl)@s_G3%NO3P^*Dw1krv^|Vh%Qs5gVYl-I?dIog8sDcp&j%+G?0s)^ z!50bk{+nG;_y-?U=nYKEh|evWGLNoY8CV z=Ma*C@6oC3&oCtV;;>#IUQKx5G9X?hFPB?Uq`40|Eltk+JcQavYf7Fjj^1u{tHPBh_L?v27EiP~{*Lgx;(iPE(voFBGYgVIoar^| zk))^4Wq2P~T5zHE*!!@V?q9sAa~&Bx8{Ofz{wr)^mCTg&ar5z-eVxw}U}A80=dX@; zGT`LC2L+gMm|i|CyoQ} zPvN51PYyGU_7wDp$Estlvclvs=kHXvE&hh2u<2;Mudi|H_WY5w9EX-9xY~ASM1_0b+(IP&y-Q(&ge(Z{U)o;;7 zi_wU{Z;c+ReI5B?AtNCF4ayOr{ge=~{K#O{h{V3TK_c;Jsw`a`n{jjqX#^j+4Ueo5 zK>n1JDMZ@}lKm`co}Yt5T%wKPu$It$5X`r~Hk!_Vo?CGr8rkrsoX*1hvW>^dhKGf? zOguSdxHKKYcp0ui5bOgnd?8824kzu5?#axzEcIXXaW6w4!)Dh{#jlE_@{;fqjr2!5 z3c|u(g@yXM5eB<$ga1-o`M1x{PX>d5Y)glUZ~FDjVv~7nUlR+8qMf25paE`!+bu2LID&9W-kxkr_JrHRMO9z! zvz3J^tzHG}*DZL)6Bf-Zcp8M;>PkqA5n_vXEza9YYTw4518#^%Q=A}iQCvq{MW$sV z&NaQdaHIRat2BwEbl)#C$0>IL_F8Sbz?NX9E^vzX(c{!yxIGLot{;roU)mf67B5|w zerNd0PGyJMCpyAE1GQ?YGwZ4z@AlTf$+4FWBl zz#}a#u5+cq@eBkVlZ)0Oolz`9rousF6g*$;n;)G&XqY&>f=BMSiQ&Ww6wp1;PTa$nJKs~BubxOp?&NMnd&pnfXBQL{R8%M@ZmKio z74M<4x5g;YnL@UZcA6g|pm*zlb2ZS{$0y%rMZ^TcnZYVu9{fqpxHf!u4_(#iQdtQ5S?1!`lMjBA?+N}rREyMk(@Ys@p3i<>gfanU{-G@+QJcLdMu+hZec6feidjUz*7YSrYQRp?|sCu5Bk&%&^ z3G;Ym0f4ZdyqbU$!uM1+Lt;E8bB#+y8yc-EFIQC_4LtdsCttc69eR6v8%4@b-J8vb zy4h9j<9Y0^C43+7@TtJ>C#xo1SibN7uR=~n<}Rdt=7Ov0;gtV>2dPsmqd1Db2E@lmpZ+3P|mBaoN9RoK*`6brjv$t z%gsGUOn4|=U0vX*a7iizAoqFJ)2=$EFD*?qnlRWqF&fR=tYg(4Wz;;=Q!3GPvQs>E zPK{~k?BwJvd_0ML$Oj@(R$aM*-9K-ZeW|aYpg=0>2e4z(C3$*U!vHT|wP=QzZfT=f z9R#X#5+Kh~)1VgM7ZptzNIqVPWRDZAsjh~TbG6_4jcwyqC0s6bcR$yCX2A5K2>?E- z@UIZ*z@S^{jk8nSa`wa=7RH!1it6 zZ;@KTb>=gGcUt9oRrqJG**@Fr#%ORws46u4;6+XCu{uR zLO_VJJ&N4@ycU|iw7f=XDy5u%aU{(>a#N|Qts%`eC_VusS_*lFJ4T_<-`PveZ@E$+ zt*s14tGuwmWZN=L%t3z13~wKe+kTfIUw(h5hod3)fhsJ#)5sZ}5(cm&GAOc_@8e<( z+u!Ll=Q^#Kc%uDZrU`-6yxH+1-%oFRY%o)u_B+3zBMHQrrX08D(_fA)-!55LTm)uf z`ib0~e_*&+q3CFUpM2|9oYl!=00ZG=?y^H0QBh;*cvE1!a*Csp=GH;4l#4k;IE$sZ zzFyM~>)YEvv(ct^=kc)(D-2vNtj|u&|_>(KbeJv zg_PeZDAdc#>u9CTx_vPYu-W6!g-~<7ZGX}!@wp=NTW4&GDU6hl`9}4d`5#uF{EjIr zz5dfeagY+sGf$IW-<=Z^iXe8Wj&yNWH$|n?K07{<8HGa%88qU^f!CZWgEbMFuWz8o zy~_IW{ioVlG*uB*i}u{w>RoB|u+75govW29T4ex4ehJD8-achp**!S_`lzjDTPB#YW z>o{6V(@mO5{mZWUqzK}PhTc_bY6H}2Z(OaR#i9JVa0zvQGYZ>y!PCL?+uQ6rTh(EL z1q?PX89V+~u)2M9Uh5w&+PkbV?|7V2t95>}lKQrc)8}+6qLpn*sPDQ-DE;}r>< zGE|tjk53uHi&&%2EHvcr2OPr>RmS>NZ739aalcbtJ-jFCH$o@EC8@j@xJvpXgQ>E^ zA4-WuORebLST*roVh^Z2*l<0mFNyMj7~I-wYKvm*s?ua&=oJ2wuJfh=2@$ehs_iA^ zlrZ_QrX`>F!KTEv+8>t160~ZWg`U!@NT5!^}Oiw*00f=d9aZNAl0Z!^4Vx zE#(S~{lpL~9F=t|qa9In{;^xeyx{z3ASe8ZyJRDEo3UcB&Ak6@Kj-bW`vV5au=mZ_ z!!WF_xbG_aXn&vi4nkEY+T(8T>2jy?s0_z6%knzumX@0Gu)25HS=l(wHr)Jfi*j}< zPkjcz_kFCjA0w*FtCdp;rF;&m_(M|3Um8E>yvma#xdzzkH#zJpZQds{tRY>mB~?ry zA`X8(6&D|ECzY3%pNaflTQjsK@Vgy6-8EJN<9!YJVz9X4AU#RWYvytS;26~`ac^GC z?@%t9j)W4c&=5Dj#;F;H2`C;&(+)WaWNby2sp27S>pg7gYy5Wld+oEF%Bf3+Icl%4 z9SUgUABW@|29~>9I2>Q{)$^xKdZWHr-}DLGD0aM0x?y_bz@{ODnfjVX?95lvbsU;_ z<)tk7lZ>abduzZ6jWWI#B{R=W?g7W5Tb;4^(CXEUU(oz^)kl-Cip{|ST+~V@eNX(L zgr8VZs{NQNo{e%{fti`eWldJ>=3Cerd2}D-`o+^Hep*f9GT@Su5(!%!|4F-dm zL5CtB{gpWm5A3UiB>RQ{u&57R;eR1J=Mt%CtAUs2T?`M47UkgMlm^$}*5oc&?5vbW zyoUtF=wu_r@zeGR%h$xYPqt&evmVEVmn+YZFe)kUFh%dylDgIwDIPuip{w3qT^Kig z3HU)al3=0CgS~JY8=LFF{>?lA2@ki2V-aIXMl~GYJ)svpks3Y!fQPXF!~3o<_$vZ$ z%uJ7;Tw_$Iwt+E1(0}~QO-DF}z$qO(rtq`7^RX)!3`d12ffLQRP@8nvr1|`&BMhv7 z*{~^sJh`h*iM6-4a9K-2LekdO_UmJ1OUvThujA33`7A8Jo?b>MXC*IFRUQ7cJezq~ z%WUw}A&t11$({J0to^8xt3fENU07X%9 zWm=rBAbD}>X6J2;me`cx6Fi~&V`cxl3Xx11TAVQOoGNL@^;QJ<0;s_OC|4Zc(POXQ zir+q_-6>4fMW3FUSGLa@aOs~4`0WL{1ZBvYfzFUqf9Ap7-rnE8e^(jzg<3c|awN!M zPlS*0Rn9wLtAj&m##kEnx-4mi7 z#-8Yb!09!%xZ+ZF&lg+j>B{N8J}!@Qvtl93d@~_qIP@$jxSn6Hu4W)u$g?}AxZ z*iA%qEPTiVY^Yo*U*Bn8uZ3LgL_4obIu0%W>`8g2crjC^Ya%P|_o6T|5?yf;Q6X2( zFDbF!=4bd8p+J#lpqZ#xW2^vq{SdvTD&E-KJP1oa|9H#*#Bw^Hx?b9h!pp}AbXL+SHr`_7xZ;+#of&*avaiXbX z6eFV7(wLee4Nh>1Ri*o7JZx6xp`pREiz-W4M^kJQ@LV^Kfcv%DcU1Y?nT+0e0~yxk zRy+|L$_x60lo8d(jvHyQ0KkpJBrT0x=bJ_hE>arO+=qYf?tYB3tz0r^-3(uahFVx! z!hfS^Hka4%lY#M~`@&>2ruC)O*MQoK(9K`^&b7m##qx>@cDB*pjeD@m&NvmX3!x}k z!B96FiZXa1R4OT~!hwAjh;LhdvBx%gc*Y7h2^4&>58{d=aue?!sXBzby~|VNuC^3y zb+}%BcHHj$XPJH{?0$9bk-7~~1bZtQoxc)4)VueZ%NfFR7zRwfwVASu0pUwokb6)n z??-2C&Hkg?fiPUmF2jXg!cDodceQSqs`&U+abw%~d0GCR_qWg*L$0cZaUH_yA>M?R ze51ch{h!S-U%&5N6@fR*M(KH92uAac+MT3x<@5si6FHgx4|-SOA`+W;jYbev?r4#| zwLb8CHj5NbB$=Wzm%p}`e*5>7o<=`5TI3uXTiEx0cf1WNOKszA??Az@NAbTfmUSzk zio-3#tBS4lH42#`t5n5OKAa2Z5Bk{ZGx}z>5^~%vVEavD4G^tKMV8uF~h8u)-|ZmF{sFe`4^Rjyx(V z>YWZuO--#d*8FRzxuF^7`Nb#|#77+hVVc0<>I9E4>--RId%+-Mzh=e7q{~!L92; z9rN33F!-a=_b@w+zq=Ry{HZuh6o&Jq%5)h^x*K)I2&no=P3`FHbB^G-j!ION<^CkF z28|bAzqFxA1@b7|EB&-#6ASY*lURnT%C|X|r4vEIKOjI`!!?EppiDeW+jzWQ=0Lxn zLB~f78KrbaCIdaj+dKmi!)XXpouOTIsD3zhEN@Ois;M0KbkY%auiIfLLhJ>odQ}?) zaX_6md^7;WUPWTAsd*g>j`!Opv!>x93&Wa_!RL}F>E`PssQJ7ZiN8t{uN<>>otYzg zcZPXm2&|E$plK?99LHSlIo$?cV9?xzx2*sLMnkO5)Rs zkbc+$!Kw`|0xaBw)SS5Zcw^rJW=}*7+DhI7qj5jsxt2yRfF!y02+CwcNVqDoCPbBz zw!+Vr5&Z*oU)#<+CM5MEB-#_Zx~Wjxo&m>wC`L+b0=XWXdyNeMgqqYj8R(`SD%aPs zf^%JcydxQrktStv-L0~EisMS6wANEn+~lmKqJ9PK!l17K{M1pm-9T8S)#LMMg!Hi`3jkvik;7 zSnA_d>~E>gb&n_zVZ;4G3)%nHf~Z_Lx}$)sebRk1H~|%a(kv*1P{)*&mCZPljH*(A zYVJ(%9J9vFDI>2UDcz3@UvWiAD*0Hz46KnDW(qIe4ct6?9DAaMqT}vrI9PlG>xP=1 zcgRO}oOH%zU4w;EzUqFtzrLH+k8D=rSstk~LTte-G&aX;1K6_A9e-^d&Jo7C49<-g zcSf>CD*fkXo5SHwO4v0qm$B`BcdmSlGTxU_c6JMdgWg{5*BK*(vt7%}d*d+z+}sbH zs2l99KP6Q3de*A>>V6>vOOx%3gpEr~=qS06HZ65dcjr^6rnc1}+A&X^Ql918{Zt7Y z0ZG7-sQrVaDRXc!l`6YPRbybOoHgdFMfen*cYpE@BkrB{#y{L2ta$guVaz3o@;2G9sAsp74Ek zN!W7=N^V;*wPFUF+iEXB@xDakg&+Ee5>D#85K){G5bV_~s;*c{;nYl`?-;UQy(Q#R zU~Fvk&S&U&YciRHgCJ5kLk&+v>|K46<%0W&8(A=6;xt!1)vqMg%A5~+y;pnA6%Qvv zqJN=BMT6_g-Q}y@%a8QuV3&R9l85^>8II})@10tIOJ{@<2m`>Nh#135@{*^vvnn2j z5Mkq%#>}9c70;Kw2)wYtJM6l%lywO zXU_Fm$L`F)kK;bvoo0(Ky5iMGDjMqRDNCsIYtgh;9Y+?lU#S-zmdRITaHZ^06;)!M~tWGi7 z+cPVQvNAGU8>ikg=I4y3MoeR=#T*QZ_tNOv(*R%2sN%of#@kHK86R!82D^AVPPh$z zl}?;i+g(vPqQJ_#X!dcZHpl(4?7Ht9UZzS_Ze-Utjs3=YjQwNe_C59!`(dl zedLXZGNMhM9!F57t;VGDbCDS_8QEdWe4m{z`vIlFQ-|BT+V=$2j9mD`@e}Mj`FJKJ zbgwn>aAKWh_hR#c{z!;ohbRkp-CD5 zO0122%1Xqhp5%hi@r@i2&1dH$|?D1cEh_ie3hjQrxzj1OU3JC{4{m z$!Ktf+iG~U)Z`3&vpzK7{>|J>OTDMsIZJK+pCfo!&>P&ak}$xIE`$=KeVr#C;J!De z8vk_sa}!GI5}^5LT)1`xok@YbC=fTjpIqVklQ!+Fv5D#9;xct32&KFY%vfAy#S68F z-vP>OzB$stPq8!3JT2}l92{b%1Md2qY#!$JX)008c46({F9g6Wh<(Sf+LXXzz@;vKq1eiO}DeY$8gamApr_A&E5 zdZMd?wd3QA9gZv*+)eHf5gM8Umh=PHq$p+LNzT(B$fjOred4kxNwu@cn)1o7>q5zV?eRyg8DO2DQg# zSzR~K7v|n|IB)qrWhCw=TQ%7?b|rY{Yy1jRg3wbRb>%`_^xX@MG&D@@KkHAAz0uH! zCPX=aDf@_=!Zrd^e@xla^5W)hhgt}3ugqQb(r4Y!W+^gx?RhI_*%Ljs|O}O?4-W%Il@Ei7JmSag0DdN@nU;@xj^pLr7 z%4{M&e%3Ef(hNBS1-%a!c-CTUadB}=&l+8JzukyPClM0Pcc)CAzH3ng`;;8f$t*Q>U*_62f4*4Gli;Vjr^++ z;JgsVJvxT_G?+8RBunogS4~4h#2;)TnA9C9U-dc*NE~n{Oz64@)w%V7D>yzfg+}H| z9jGb@R#+l3t?pVP#)5P;9Kw3~%5hVtxL~##wG6eJ>9_qCNe-WCDngnbH1}3My zsxf8ACM5GVQMSjTlv_|nmLFj<9pBR=QakE|PbIQKSN!0I#1AWJt5@it59KK-DXLm# ze@I_qlW8}QUv^e|MPd4<-UdNfPBW%U_xB|S`Gd>c0FRCsP0>#oK!a!biElIZN2NFO z@c8<9-QHc?4R|Kz9{8_!$p=$+xWsqedTsjwj4C^}{-A>>E%?^W)r(PTbY}^^gKQlj|wX#hmdU z9E>suUt#GpY6!T-D0JK?Tf1)?l$y_2SXudPh9o3p`zkMk^AhjFu7y2FQJK)?{KcPUgs-#Spoj;sC%byad0eRCPH@R|5`t$r{`EB0;aPQ|>btybRjd7PHav4b zT3XvM&*M$C^qvus&E#7MH5*AwjZly-?Eb64yz<1FxCc*AvIq8$;GwjX6vNGr!m2U$ z&0E2S61qN-K^jG^rvX5lL8uJL1PXmag@>fz=Ep7pNg@OlfulrpE_0f_nqA=%BL35x zsHZB!nEr?FXF7*|r7E~MVFCj2C+L{bd1{V_q{mwBQnoq|`|m(bOr#OQ^iP{>$}%9? znm?Py1mc>7&-s>{iE>B!inInqB!XHY1Mhf#z1$`}$-`r_uKThkxi%(xlccB`}5L?f512T>*pQs`Zp&tUA-S$4cd)*9=EprdhP?D8lcozgYWpFdzckk$2FX>^L49U*Dpe zl6nGm_I6lWMb+Y&f1>;9JSBnz+>uo09Wrl>(P?i$1JAW2Z(sQC&EUz80EvUoeG7E; zamMdl9Q`v;7qRd>LfR%)!xI=%Fawr4TmCs_APPr#4Pd5&xHT#hL2sJH&*1$9G5y)u z+giXF^tQp*O{DdJ2{ju$>YxiF+QELW@5Dc8wZnLq2kNQuGqB34CYnhSM7+n>uCb+vZAzl!o1f z)1dxbV5%_^LFmrAO9N;Jf4yZYc3fj>rPOz6L`3bYUcWDAUOaj0l~}P5N(T#$q9D5J zclgc6&^vOMRai1yjjvS1Gi8J5zUIkvIa?j5 zmIez*lp)s0U~^;4&zKDb?7U!w^EmrXE6o)DQ@~Y)9vq($yF@+()xO;Jbsk*Sllp7s z>ubhIGaAZRC$_S%?u&4OzCdN|-!v==+ewbY=CIt|dU=9>e*1X$bdWYrBFgAUm11yu zxco7IG=OT;RM)_4noHKe3`Kn{@|N=GBx_anCLmNGtM@8K%?1P1L8-|4XcL~))Ky+3 z3JI9zfa7k-i=>$MhAB?|yN;4v+0FHmn*+Hiwfl8nFNP#Wl8@0w{4~8|;J?qsG(ymf zhn5z!_tKf7{>Huy>@A)uO$0npZCrl-nphIGG_zj+1j|27X)b4$o6lO-2=9wSG}fmb zTj01Vl~MkDT`%osQ~kF&6c)IN3j$56PE$FnscArCG~xmA8`RBTCIHwgZ4@?kpf#PX9{ahW<9Aj&0X*sZ@PEo%} zi7iQuUv5(ID*8gUentWVAyKTZu9wMaso71FJi?s*({B*(&99%*-byaMMC_E9D(F~S zcS|dbK+!(%ZaYr^LA_C`hwo|N&t+r~zaaP}@K zaOxl|HxuwdmUd_4h^2{^;sXtm-!0(yek1>PTi+Cp$keCjYDjI^Y}nME0M~rdwHp+- zf_1C(()fOxhEg{^K}cJjR&-cy@m`p|@q+TtB@hVo2AJ8fvD@=uLnA@GkhtF#-%B4H z`~{5fZjjX@cIVu=4KJ@q)^(Q?%Z!Z;HS*T(vY^pPU*FQK3`8*O34!+rx@aLOLGm z5bJ*W-GtZC_OQg%k}ceJ=J1!s4Q{{g--9`aOHp7V)ZTx>aTfTNj;m!P5g!KRP0!01h?c=>^P&p4KtpghSKo+{d z9JW*W*XIlF7oQHP!^nc(|g#VQG@R6?R~p8g(GhDr*ZzuMA=32;ZH-sf45$Pa!ae& zmU}CQ&L%s?%X3MG5NF*Yzr^r4L7kFd+|5y_EiLdKD7k87LTQKapC);id{hsgC*%r#%zF6%d!N zsp+J4$;bCZN2hsvLrr&*YX9Jv5%p6l3^2E-eqh9HIFok&#Or^u)qP9LOrE|UWXXw; z1CRjmKWRAq#SbXFW@St+2SRekkrRMjK?qW(lKTGPJD>&JRhOxn|L7#h!kK(GuGHhf zstqA=3vrH9Co)+-`evs9FbDL#-GjbNdaEK8paZm!ZVvyCWf-q-9jD)o#g;=t5K^yk zKfPxiVE^-QHZ1i_J@g5;Jx&{U=Dd^1bg6IfT}H!7nUU3P9^ZX(cmvgP7^{X=6EI`NB9dELWBVPMw{)B;)3*u_PcqeOhWB6VDR^LxiX#$WW-thKYyh{Z1L>+f0mL)D7D!C{_0C4 zjqV(m^l!m`Ugkf(=Kp+MNbD=H_Im!mWXCBSM-3Q0#MeOq-dl(%-`~o=4F$)4{%q*X zd{F<-tRsFxLu^yswSVb(8N%IspqgPM#&FMdugyb<4-;M(!xo)|_!H-6AW-Av^mLaU zFvqrkJ9s3h8+e}JEnn8|Kz8!ZpT}?h;PDt9^SbxkbIyI9bDrl6g@#;_ z{n3Mu>)DV&p0P%7GG*DFGri}cuN#*ALuo!dHFtQ|PWON?2a?$2ITcD%pL2tnA{*@m zUd%0ug-8yGz6rupZf-Z1o&dvU4_^zW|1b70HFScEtP`D*m;;XKht|t4i4IL&+hR`&EKck)K3YTQACzOyS?PR z2?XNg{~A6M-4nsb1}S@e)jFxNd~%!je;(rh{KWr$rXucx&NVyAo+$b;*8J5F*mI~l zklv$~nN7e{fkm^>h8+b2igN*i$N^S~i=HE8oerfW66yJ!2Tz_D;@-K- zr+3%`cEJ7nVqg860Sl>SATip5b<<8ZFcr?lt6K!qn5601v zP=xK>`KPx6(jr0Yt7x(v>JbKWE~Lp-MqACwYU|;MnO-i{T@52pOTYE>tN4q>Md!a} zPVy92!~7kzb%aMmoUw}Uay3Dr82=n+-MNE<62;$tJ$+4rP8|oG+xE%qF@MI`aY>kZM z*}UrE+@YQhIkQi8fQ^u-4hX|=I%QdA7!I7woNdW#t=yWL*`33O*avQCJH>i7}-mGM#(*#F?&=YO*e?%zbBh|dtV(i z^}10auV;z}vk9||^K@Ybu(ujXpVdesIcr6a_^z{ro}C@utLixCiOn*21r_080M>}Y z&#gJ3)EF>qTTfA$YV#@5(o%pXT>atsi=0;ArJofD1O0ycOg+c&N&>#7_Rpbj?Yn7w z1D-VZqah$$5HTvz8uD?v%61txbOC`gIvnYpG{}10!*veihLPRCJ+=K%U9fHc^+Pj3 zO}Gm)9$I7wS+E3-Wh7rq%}U8x8+9eSu<*tfVm84^c<-9F3ZU{mG-eY@*VD$8RqPln zuIXK*Iyi=3$%>*7smbP6R$cRSV*)$6!`WVc?QNw5WHc=vSOBGCl!TDIvm1Kwc4AfT}^Ki|>W`9q^@HsA(hm8=Gj z0~*Vw>8L{BMepAXl}^9BaQ1YHjt1@>7~()17Ww`)Y4uX%V!?AWcsReSC`G5aYtO-)T}YifSm{|FZ6I)#~0c zY6$POv@XJ0r)@kG(K+`tI(tae@BMkAI94gMhn(?Ut>#;D6=hJhYtV}1ReHDYBFdx9;xLwFJvO{l2grVno>z$5I> zZ!@M|0G5x@?B8oR9iI&YGT@?h=wlhZ)9M~n_UzQvd$oQ?CDZqS6tPNTB&7~=@_R0N zh4DeQ)YFcFklrl8cujsLn!__nnJ+bM+0&qk4Jzn?!0w@ES~xb`oV)xD=5ryZka*-i zT#6Z7s`6}?N)oV22pqVXCf3OZrltW1+A!4?+jvbuTun`F*WEjISs?!@pE$9;e}MfP z)My5u-}b4PieXQ?+xZx9g^6BFvBhy~Y%(b&( zhK7RK^4|=?2oyk{!%nB3Z7Z5~VP~(e8$B1&^Z2%MC-_}gW0z4{s(1~)xW$|TJbSP-Bk z3f%Jh>l2(WBQz*U<%mvu$uO)E6V2}K^_YHKa<=**tV@^XMsz+Qm}WD;~QY5;gb-fl?0CEZI&`Yad#nkuj; zE_xtF2g!>>O;lrmVrGxB@6N*aoVzQ&p$bc%%mmtT`t+*(r|D%now!=JfXhSyYXIwv zarb(R!Gr}1;0cR58dw@Bu78TQ%y|Qs*kLa#BeOoysNDGZ6=^OKmev)`+)lc^hq7kd z8e-k)?0OuZtwZ^>*n#k;$bGPbo zD6O_EGJ_LN2%4-n_33X(h!jpa)>ndezL4xCk4uJHTQ$VF+R0CGP_zNF3_E2pKfrr% z4&dF!;x%QGV=mCc#~XVNuhE4COOKi{MbGg+=6r0%r>O?4C>OqJ`Bwz!nxJBe4qieT z!cF1G@Lo&OD%l0cBhE&Padp+ivC*83Zm|{Tl41|Gtt*j}I(J!Lr6heYEX%;j+xs;y z6Kxo1&|tW%ASW))6s2}q(YLIss-5q2ETxl(p~W*`xDi0ez!PEwNVM{r!TE<}fyU!Xs>Wfv-3oRl&h zEy5o?dIZW$ZI^4C4pm#^UyjZ3L?2n-;{hHZ3KZgWt|mzIg+mc}VNt!_Lo)ObdD9ZJ zodYaT$$v1<4DO($3ZwSXAUOT<=v|w&tJH1#+(r=Ym;(|FBU-iCelOd(%uPw@^Ts-+ z4PEKnfXd0}GNk0Jgd6y_9i4Cq_`m&`oRG9`MTln3gNLx{WH20_ukFEwlsYyln@POJdGfv z@fIsG+LB;Y0Im7vnW2OY4t2xksg2fFs>VU`cGRG>t8!M1wU`g!fA?mA(|C8gufLxt zO2BL7Mz;tqpJRV%b29ha>IgD!wj_S}eT%IGOH{Ak0>JbJFt(VM4BsV@O>ZahZ`|jC z7^DxsvOW)*5I1s7>|Wm|Zy!8=eoD9hE79yDdstMCt&!x4wdcD<@$q&hLl|4Mnjp}7 zknGpQ3n93H(mf}_X*6VFchWh(w_W#UL6sQU`0900bIXGx|YdJAdBzF_3RrU&CI|kDCs(Jo9TzmzkZm3R9Tm92FN1>bqkUJuN=6X^}21ns{G>0+8E4= z5uD@9^DhGfCQ{s1NMzO+=x{&L$!b3#J&l`aG5=k^qTM*rSYDpgVQk=4%KfH$;U7)nSq?}LlY-LGkdZr5+{cq4j7mov{|Wl~9w9k2;WV6_ zoXUSUUxGgWq$GBeR%S!6>~qz~ztYNOQ%71`i>~SH+LwSx@U9v#_??~4m(;Uv zml?o-Nm-vGe8>WxdDyiA7|OeqrKM@VP9{Te>2bt74{9`kWkX#lLAiSoRuuKiU*a%= zkuPAyjxPc2>gDM{u|eTa3C1jYBDNT&$Cd z?mvNHz75W&kGzl;=H`;JDjp!+&|Ceq8V;a?N=6v`{m{?Z{>8G_o<|><8JOEQ&J6Vv zsMkg-fz!W{*0n{1BCc^n^-7Ppa$N!WgJ#bz&nT-C6;~0C7=Uz{Xy_Rj)-HOlbr8N? zjg*A*|ChyNXn2j|d;&U^GAkp!pgo5rnlEkdBF)*aeY#%{)vczfwQ*mA z#nbha8~lV%P6uGwWLX0a(UUpTklxF|0htr)J?n61VG4p4#6b~w^f)XWg+vP~zsA^T z-7e=(K;%cY3m-HS2E~kjjBj)>K+><#hbN=8$@4J64*i#j zj)cn2&TmFmXHU~f2cM^YVJEntF6Mjty5Cgp$(NO5m%4RS-xR5NZDFI?^+)g6f5bA{ z^I1msKRohLZi`_Q%2iE19eTENAIbC~0V#4$ZDH>AAU6v8nZWc0rQ4I>tV61KvORBk z#Zm?wnz8BFv&Am6F$=6b3vcnb5^lMME+k&cD-!#*>wN3G&qN?_-!ji&F<()E5{q%bO)QNJ4?9u zzgn&UGs!Fp@rgKcUTR*)qTfiWdKJ&V=V!yJw(e;?$#USLTCds@nJ2ySeg?70ARB23 z5-=7nij5A;qI{I?6qpojzT;wOCRn-nmt9F!x<)G&KHw{#zV#tAT`%HN*pv8))8m}M z8;TDcF9x}UlT->lQuBZVRnTx6^(^=)m<@|Ndw%dqa#XXIaNV0K>MoE8DKIVehDy>C zWv?XWmH+0kq}YqGX$HAyS;J5&UGKpCj=)zZsfXp}>V`Bd!r{YFc&w32*O^yy;_uK% zt}Auslr6{?O6xxmx$==i-8w@o1;h7NM@4Y@v7#5N=%vF$$lIDkqZnN^wONh$p)o60 z#VF1jwPN3v_9`x^&(V;uR^B5oPbE{TFUEt-KMXF{+|yE&eX;kwNoSi8UbXngD+(um zbc^JT`FrsyQX}uyiRzQtmG#q^++aM`d(m9B2$avE0`n#|<(GK(7`pJgt42XVsYcGQ ztLV62Ta52O}zL7)IeTAT6JbgXKF6_rUguZ#TlMBmPA4z2Ao;zyIpQqUi*17*D=G`!~w zm>c*$eW0$=OEjvhznC2U>wWpS6{?3j*6wA-^xL22uJTbs6Z@WCiwg=@!_$8%vHmV+ z016*E*|LJ)^?aPHU-DXjf!LAxS85{rrCv?YbqaD?x)v=MXD4u$dI}6m8cxsV3$j~x zqPv$}eREj?IscFnt=Dui*B%%$7M2f~Yx$J?CxG1(AYT_2MUj2tl==$7IwXP4qtBaZ zFz555Ebty{k_SS!;)tbBb^6&jjX7z zAA49HP6UA+JUaX5!}@^Zn)!jc8reYAsk%90ablh`4%&FMMS394^|CE+bezNduA$WB zm;MvVUQL2nBg&&i+n(^WMP)n5r0HHwQ0UR^FT?mrrmw87j)64Z>HHEWaDcD%@>Q71 z%x@%-ZMed1su~*pjy`S#fz*wF$(-X&zQ0vN?kataZyMdVCQ%Gjm&hwOH&Q4?3yw|r`>_7UQ0k`c zJrNH%9$%C>ll4u`6I90X>b)ajW=K)=jGPa?T6&OxX|&#dD4lCuIy_s03Fw-*I~@Xt zleYXPDljU>`%7^cR>KUkXz+%X)sXT{$QRDGiq-7)erUN)LYb%4pywMX0t{7riU`4s z;?cT2xBY{2ojcXD(5dDHi|+F^MQCL67mk~z=XWnajFXpZ;%3gO+zAf;qMrZ-E6bId z#r?^wE?V{(KVrZ*PVW9Wnun8;j55eS>r!Xx_N9!g?)>v+Qo0w2y=or~p1fhxs!ypD z)TAl-7B1$TDym$Xcx6MEg(W2~F^?yCLUUE1_;Hl}Qu0coPCVW?#>OrEy|g zK_FCsew3iwpE%!feShjHCA_YoCyL+D)^Z+|Y0Fx!QKk7Wa&ErU00%YdME4~)PPj2O z_*gPA3pxAl#XZ{i@XtW{q$EPy2|8LS?>;DvfZq8&DP8=n*Wx6}LJ!=V(tg_YIV*e` zB2_-_iYAluWf_G%DN9Pi$2d9Bh!yQ48ft^Q>fDupmP-a&z1gPxYCs-=+w}g1q7^6` zK;oSR3lUu517u-Qto-YbI{}~HUY?YX?}JCHGC3EYyd9eyI(A0Zp2I zN!>2#X+x_8pYdiDR-Whix%^$cI!~s3v4!PipO7Yg?Rx=9*P>NF$Thsa$2dg@yIoaY=o}IUt-$apzI8NwN1K%ESYIee6>@zv z>k{Q6W^XI$GZ&Fg>!Q66D-1KLw|;DAH?yM7?5H;8OizSG2Q&ICZOjNEK*E)$4Ug_}Ff?RCre5sh z7yOTA1^%pjqmmKwQ#wTl96b)Yyc^m6DxCatTcHwDJGjiQ{@qmuGb*Edk7i0v506%} zAN5QXElQr$$Y9pGd($?r-x-hg$#6stEbm$l>h`(%%Czzf@{eKtwbrJ!Jc;`%& z;mD;?I{a&RSU|8}3RUm>^I`d;iH7t%5n&{ox&k^;7`t^Tlu6z2TXA5o`L-6eq1Qa$ zSw2MvWEJt~a`V_Tk~F6U;~kNy4hbFB2T!W76ickx^#0{4<3CXeCv7Vf(T%R|xyk@k zlII+51EcsMRhl*48^R<|$WiDqH8J67o6->F%YkX(?4`IjrI~NVfdu=*Q2=AQx9dy_ z)D7JoF{_&c`1L>98BR2rrvV_jb|YFa_s2wGA-meHuN93Aa=>1)1XH^*r64CKPML+zN1ZoIyf?ArLAC%6A0J$juvDyhfUv#3BGfH7Xu-ECmG? z5IcgT*|vVO&`mx?-<{u^Gc68s=REPJsvH0&XFA*HRqNGw_|c@`0@azd9;jdj8F9Bw zm^t2t%aCpN&+*m_9=$oGJ7e&laocO{ z6X=eVIRi2NFM~X@DMwEvZptB8l=!3U;3UbJ$V6cIB0^+jRAhAaq)We)Za@4n(1VK6 zimu|h#9alko^2^H^Xu0WI?gWB6yp(UARV>tSsUX8fn57S_~cOP?8I9mZGG~^KZEB1 zIHzTWnFW|t_s!ITgHR^5uVMUN++E7|x@qRBWz1cybzhSY9=N}r^U3-CT1;YU>!KQ4 z_*Bl_mmKS$mU#z{E*)NRliv*kF7h`Y^<~~%-Wl6C*0?TIDZwIXUWpV7WDED7kfpZ+ z@#Ar;DFA*j>f$#N+_8}~yzd|e$cA<0z`u2TEg=DbPY%|G#4}~T8E=*_xyJhFuMp3h zPj#fgt-J3MjkJj3^67C**>gV`_x5MxL>WH?71%2H?Y$^o1JU&n2jq^>Ms zePNfZ858Y6s#1$UjPLQZ?XQh3GyW-T?R1w))wycJHD2|ExPM$;UM>!tH{g;hE&UEA ze@`4lcL|5O@qo)7G!ERg9Q5CqJS8Rz&tBMDwGcx!?D+GsPbJ-qS^$F*Vl}SN6T$iJ z_$unWITiHr;>$J=p|KWK8C~`1R!jjFenjr>jx*AtX-a>C#3w~*-jx<4^X=#1@7rYn zgaE3Mj8q}Rt{m#|1M(RQ$law(Q- z{T^$Z#N+oGYW<5pDlnHB+@;j}hXY+PT@E(|zQ%BhaReqVohQ1LEIzGAUXEkvo7|KZrSLkWkuIsRG&i}TZP28H93m>V#u*R?dDMmHU zCwRxIqRlUa6OWJmbANPpYB8M!)~w*nSM;l7&Ds6c={rfs8$?Fssn6*}h%p zx4*W!zOL-EHM>6%D5gwfx@N`%+?8JbGjccY8h^`Wp!CvUQ=qwBky#Pcf2W8MKus)B zD1F>4n0W;3H_lF}B3a+XH+eulTCnX&bT$_~)%EMw)eXx=SHTD1d;ShZ9cy+ z^LO@v-}Y}_Ifp0BEI>Yx$c2ssVf_pRfo#6Oqs^ueY9K=J9U599gC386RY|1iM7Dca z1$fKx)D)4@v(?<)+#aMl7_up!9Nlc3m8?D?7xnw@_dE{tW0awKwlDVcurctIMLC>G zpv&Wxr#z)9`K3Q!KU2xSX6Ue*&{(=C_Tz~7)Aadn;{Y+Re)?h-Ne*O;7>wA$AP|(` zpWA;1yec^?rr3mw&o1ox#^^#IkiqXADrP3nhl1DueV{TSj+oBtc`PUwHLstfP^S8Lr8ZI-Q6*W5aNybW8Z4KY?B6WJ>&QSBKRRA;QQwdqorB>&SSAW%d2x!ce8qrdh_N~ zhq_Ed;=vvZgL>4#OGN@_XJ?c5lhrw=5S*EpF~7WpFU6WKynARFkWTJapDrDE-DFY2 z@3G=P&&YG5U{I*>;28Lc@ z?gvY4bycz@$|Ey#K0(`=_>`0-K~C~;#-pJ1Gj)QYAyq@Y28V-@XI@xp$Zjg`1G(zH zzND>A=h715Hln%S96#5 zIQNqz-0X51BMk{7P?z)EA&5c56PC)7p*4OmMHIx66ag(4K1*G^F-fRBGIRIfYtnbn zY}sMJO&cG-2Nps{;J21DF-Rt1|DBHn+a-OlJ%m_5ux7VFN|~F3F%{Kc;@*=jj%eM* zb8&P$_+~6z+eW6VaQSwe7>15G^bZJd?GnDY{#kC4CphGxA#{;QgL3;bO?7Gwg7WcM z7O9{cI1zBA1Z<*YvVP0QOioMnGJ3Vtf2W%=red#)W{vi1#`5K34zUijnb-VczJuCc ziiKY&ruMT_OZLG4*#WkZ}EQzK?5aaCy6IXM_gy8$SO6 z#rr!YU1<+Tbm03>9Ni=~-`;fVj+;AB{p45Puh-~oHbKDM`I@l!=Z=Pb=oXg03kpzP zN*dj9mi@QbKksPSDH2%k&@13y$lJVmk$k;T;N4q7dggKkh_m7GmS`^RrqIj}TVse^ zd_(b6YHx4vB`J2Cw7SFQ@T+1(?)*Iz;lH6UdzjSNbN8O$+LMk`vVsQ+LQxNPg@(?* zPXfB$!5eB%bw3KHjzW=;m{?3!5ovJJZgID_lv#UgIHNh;3q1%S;KKMf+V}PV z7|}yOhe^RKcR5h`g!xEyIq)+Q#RhTXc%p&>K! zI}bw}2e=Q3iHQ#;K~9)Qga54~OP7RwT(J4hR@|?AUw=3=ZQ@7k)2h;*#gWF#-R`E2 zGhKdG;+QM{#@%fK?q38N({>^q9^VGal%OByP-#sz|90b}yX^-P2(gtA=B(sadJx$z z&{TtfdWoE#{}#0|m485>pb}YQvetS`fJYDB-BX_nO>46F@6!$7({?CZT!0^-OP|-U zF4r4(N4oEs+zmGB7211LqhfFjk$YlWwVBoQaFLMyicEZMtg=eCMg_eHu_606h+15o z65{*Qlp{|Rtc<}0N@ zbDguvbLNnEW+JHyTQ>rauX`(+H%W%?SPTjBzs!ICGVn!!`Y|$#JzU;k@S2ze8$ctC z61l(A&K2W=p9$8KW=DsIpPX%RAw(Z!ot#Rod}t+LctI{qK8Oi1qvQMK*chPu2vCh^ z&;;8K)A)AD7mK_HOaQo0`1oj*6t2Yn9jrwpyt;ariu>E`{}5sr8K&|7XQ@Bh<2t`` z_>HseJfiE?LpTi#%DzC`V*MvRJJLwB9C|U!FG%9MnS(9__GSO=9VQr7JcbwBScq*l zV1FAM>sti{fSGtZ@0O&{dM3>N`xXSEciP#sO|fz-@LNBX@(_5Vo}Pj(GIxKtl@U+Z zJxM4H)h}^%RvyhWSG;ncE;+OQ?>iD&Q9qd93t`8RY;iUxzn2=pf8_2=y;vC-{I&2Z zV2$U0CIe~}U!=lpVOGAC#&M67Ds_mhMiT$eqenY+!p@_IUjL2f<3pgAYZA>GB5Q0U z)}5GQNgwKoP4-#=nFaU|B;>!H{=(C^eW@&diXxI#*-xNZTcYwGoPw0xFv;1qA+YG* z`|WYBS#Hh-ZhE-YW0Lp#Q0q4Zs{JYRf~#~oxBeD*aD&pm!UPa15DM0C=Y`4LU7i{( zHBrZ$D(fKUOfJ+ELkgETpp2a_^SWfl4 z7`HVZAqCauw$42N`?+snPrAwx6AW4@T#;yas|!E5)gz${WvVj>i+`8~qI2q^WIy7# za?RP+P(<>FQS;1uzBJqT z5E9Y@Y)SKe#;3oN+9^{@LV!5|wV_w$jh11eee*K#|7M$O#EoEmr`;OsAyc?Fv3mDwNs-|30(ajWqH$dJ#j+-kQy`2Qz_ zm;1p0j*z{Y9Vj2w`R@4%_zV|?Eyc#Kv%ayhQ1c&7iCY3`OS%eb(6&b-caRKH zpc?{33+hzzAD)t+dc|icJO0lYKTQ!wpGRL~4dI*)!xW?7orfBa18L@CTZ|FVd9-V) z$-v-GW3tO-KP}xy9D0(vkHnYOG|$ieX}BGtJAF{xtc71U9VT`XZ&^j)?-&aXin*4* ztk8Vy{mfSJ5g4ErC$zI3e`fV~u2lciXAny(cT|fLQt25_)1UiU{>A1*G-L<%^Z z37(xsYx|~ngQ6$J4GoF2_x`=EbTow*E&nCj>g}_nhVmR~zXuPOuOu%B`X=YU5z-0^ zJ5pNP|9cbU&Q*z0w?;xKf7EHOsL23?Z8?^cU!eUA0&qyeO#*Ejra;nO&MAYt2q=RD z9>cmvH9-7Q;G2{4FC1uS>WC`a{yTgN7-4iFY1UKALdMbWB^s1NgA}RKY`}mv*7|KF z4}On~?8z;K6G|d8I|j3wn?>DYQgT+dG9V1^LS16G&dvhpq#Cl~DU(OW*@63yKFj6q!76K0m*5LPa{^ z`TeKuO1*)pc_s<@Bm;5$W-pX;jVASo)$WwmZ<*pzwRZqK6N67k$o~8gZL&YOxX6Th z@|G0wbLQvF4l}BI*=>cUJ~MTt_kVhmYayke`qZ9i3c1 z3a+a|MX#<1w%eokLG~skqn#I<6`XYqB2cGGn?2{_tJ$pH^dQhI1tmL0GOPOCp+qs} zkZ3_=`~-YfrE-T7ySx%x{hRt6>C|dO4E&9rd(+98d8*=-K0fhZNM`jNERla4XJ%N? zz-Q=`S8|j+{(?gf6U3Tp@yi!hWx$Xq ztK+2rL!u)>9Nh5YBz+-Z)8b+FhzMn~78?$b5Ah@QTSsM@3Rz67;4?qVvZ_CGQ#Cclw5Y)x2m=9pvAuaB*oz0E#95V|`7%R1RX4 zM;pA3&-<^lw`^xVo`wL1=EVmLs}`Uj>weJkJF#Zx!^6(4z{Q&>Dt2`hVtQ>+@~lFp=&=4!}|r z+*UFW(zk&_GE@#=oMS(4?OGlYvE*+Yf52#TRzmnRSO3+N7H@64tPkXx91=f6yUYAqF0nQ`clv8fN zqe$=#)QVyMUidE-MxA`M>{n5X650g{^Y>^ncYYyLX=^iz8b=bnBy8Lv#wT`|pj}^C zK%o$v+h6Bqu@)9$M+?V0OX{)jz>3G%b~3TcS|JO@J$E_mt2Ph@+hdH?XLF{a29 z9UY0v0!3zqpEwjga#8XZ(}j9h{)bZ~+eGSGygza+5yYi)> zUyJ}MjV-?6LnYTWF65G9JtYtrtIjz55ox z-5x)fMnL&+46AyJ-FBuNjUB5Jdrn>sNcLPE}KgAw{kg~ zH}zsm^~y4QZ$fmcOAJ!0$ZJsD4D!`Ub&+C7j&Rzh8p`a|)PYOMLBFQdrmd~9IJ^2E z<%tMtc^o~A2&(HB)gFnhxO$6z7gdDeBgT*|3tK~|)M^o~&_>~$K|+Dd)Psi$y}eH+ zt3{p(2}wYupfAzL7jsH!YScu5IBzx*SwRp5fI$^CBPfZO#q9b_V#dcJo_ZlxKV7*2 z{2Z>(p>QAv4R}vf(hmEx@a{lhKP8bLVv?`6a8!EYxYi0{;J70862BM&w`Owy z#CQc&3`TQ=LPKfQ;CgaV@Kt%PnuYi=0EInxk}lc~&&}Ui_+o(`i_+-PG&x>6>$)*NZYD*Swot-Kmx%FT@6#n}uJTsJMOlVQ(D{f6X1Tjw;f@jRvJL{3A8^PgKjx zIY_nHaqX3v7@ny9S_NpP-r*W?9^4OeqG|97WbrO6T5A;3h3auoLq zQY3QK-175(=IH^cnK_NujLU9AIDhQCO~T|0Xlu z@4~Ut?{Rg9mg$pg|4~`@?zd-b0zWzXpvhEz=y7FY0dWq+15d0beUxF2C ztwEU=EFeA24FollgH#JnA&_Tq$!9>Isz>> zh0KXSGf}ZijNLiobf)-{Y-9T!e~+U_V4|HHd?j=xgn~lP3$4zY+WIHN8cqlYdVcC{ z4O>k5&aG{)xKF>mO|O+)Squ#5jj0%-<|G(`)bmP)kuI;nrLu&^W~_7c;Kp92Zm2cBg%a5$HMArta2YSR~ zdG=uS9vjSqYxIn9?T*!_vzDS`L-`VK=4vU219`{q0Z_&g7>qw{b9rKR%KDSB@6@$f zBx{|QSX8Sl!9(qnpYhj@Hw01q0DqmVu^lZ*yCRGmIo7Dl&P*rW(BNkE^|*}eK;(Mq zH+hAR?{Yu15G|XB>LNKxI6F%Zk-*!=@!Q|clD3uD-5x$YzHXP z)(O5Vw3_x>5kM_Q2)fVA#bOr1T<`$I6KitYz>%Z85RlM*xZG>;Dpsqqa`Si7$t+(K z1Q}VJ5?vVVpfBWwHWrroz_QnM{^6ny7pzae^flHsyL@IpKVEI{HC*wJdC5m7DvFeBNh+%UIE6Ury{=_=y{Q6%gb(ie|p^|*mz# z%RyEfCuIq`Gvq0#TmVXbhn2rh^!h6GX3hBKAqsykOOe=fVo!hZIcN@nt3J+}MFN3A zqvQ>&J_PGN`)(h+5OYXl*WQVz_s89>sG+U0*n4Dgm_^R`QnIwMjT^vF9zU<*(n}BB zzx?4>VB`5|!66q)C$BY{^(iCcPNGYh_Mi4ARn^4|NFa~`a+gXAo_G^Dbd)I|@- zWo&57a!|Pavykbg`iPRnW~ApED2HOvV&8>7xokf_Z9;q;J#wI0x%%VDK?C&AV8df` zvLAK&X?qX~<#)H-ekZ_X$nO@10s7ikER(4k0bl*ZB%?Tl0DOBK;PH7f^)2zUfK^FWcUQVhwQ#cJ+QM=v$NefL+8 za3>MlKqH>_&$rKiMu%6WeRuzEP_aaNttE{9?-A>EKKJycSomSxmp(O`scLZHi+ zez|GnBoNmh_E`xJ#Qw!a?PgHksDZ=Oq(`YRsecLHnNeEU(9lp+6ar63OkCJ|jv6O) z;{*0L#UN{MZ_~*}cKJzZh%r#u#7ml>4oI6~rbl@11FO_HgA0@;!bLCko2tPc6`H)4 z5eml(+Fh{-3w(U(TCL2YBJ1h;JB(7VrKQObU%l?+!vOtwe?<}-M4U%#xlzX5Rw)BV z*dQ24yX0;d_#Dmr;i4M}9?_@bIz0NTqk|-19D)X&b1xNVDzBak1PD?OkfnUF``WPH3(#f^ij%7lmFTih*=AM@3sMz*QN-) z&lld*apJ&nn{d4{>#!Xgbvpnjs(=}XLZ9i?*e`qmDoHfD^=LHWzgoq#{{LW?PA&hg zj>GThjX)7nV@L0dPzI**9|pGCJka_N7UzaJVs+lzRo|)rFYYBl^q-)8G_uL-nI!w; zU|K?{-TKPpvo?9IPgM_o|6VsKr;n~rR+w$}h=tqCG`js+9}Y8ndSN2e*rov@(P}lk zY%`2&K8^9J^mbY1bVb&jzvyF|Et{jz`TAUOzp!yY z1|;k2>&Khp#^=7e^BAb7BYRKOc(1M6YdGfefV#-v#FIY2b^l0JepO=oeTW{=T;+gP zuK#3r8QEo*{Z{+&mfCJ@43!PlKXIyEF1^-ey(0+$;Wj9pG;6at#ksoKeoTKFsgagx z*hmvsxIQ`_#Vs9(`$oerA?)_q^-dW z=I7rw21q5de1`fwuHGCaLe=un;PP}k34nDOQMH4o`>0>xbEFU*aKSy>O?1+nglWa9 z?09mU=*;DBIk9W6A8b*g*yNt;C*0^@R8(Fj6tP!~_iX{7QeR=82TKlXyb7GBhn=Cn z^IXc?>>$$cfP9SG^;hVyr~R)Npem44l@}k#%u1HUSyC&H_Q-p@=(Qf!nSp_m;_%+s zf#!-m(n-NbM@RN7EAIk@_XU@Q4FZ5#(BE3T4gx`XHi(_G(seth>F<(5vVrX$8~nvw z#-Fd=-T|!QtBz^#s!MTND?}{7Z6yn}ET^NJn2-RM$uGEQEa=W(Dk5L%jSKc>=Kqc% zJ^%#Ti&n*pj=5^;2+{@JvWS_sAjaFG+yMPo*!9~pmrqeaF^odag0_OXe*iqhV7fZb_2%b0605cVdZ8NcGG=->%{KSH)v3CImNIo9egG%wDZmwD~u!sJiHq6N>FFeng zP&&9@VObn{zNy1V!)E413D}}xf8B+;jgNI+JscFX(Qa0wOT$BC) zT*Q(zAW}}DeLjKm042Oax?52WJ}$_}f*arCEv%*3vn#}p>RWW6y~_I383(s;a*Fa) z{xwszH?zBHgX04;rD9jMtcw^;Cnbf1jJ~mhd{Y^uQyUyg{ni_F3CDayPyIhh2Isp# zYaC6fm#x*)7H?9~0dZ&}w#YS4UnX);Qa2g9G9IwvL;I(I&Dv$-lR?@Wn4i~>Lh|R8 z&;g`O{#i28i;U!(xMqqf9YpM2mLS5w9mz_!;>k8GrlEOY6(i6R8Ga(L%L z+m>PNQ!9uWmJjb7R)WRi^CqB(m+yTYpDMpQ-kB}A8M&q>R}qz#NoR$25&So3`WNuD z6wmSljX+jC-Y4z!p}I4$MaQ1XqtqK}z&MnWa8YlW!)4-@VL(W~v9WO=M82wd9?nV) z#M3&unsvH`i|$CZaiD-R9X|~Z3;f%E!0u1^t@IQt>3Kr0iok|RoZ#d+l1WHj#8)rP zy6b+Q|%RVYZ*qD{f7jB9?E zx}EP7uDj~)Y(oH0C)&)~$YfPUA3L4rWy$q(8#V*G-I}bKlsConvC7=lDSGL0}A?~ zE1|V7+NBOizYwoVLKt-1&h|s3f|xhfEsPo-37-(XV+N&3zJjm|X|gK-;n-&hCfK*& zP(v>JcPERB(A)eGcJ``*;9<#sM=&d`(KNpzH5(*10?1r*&`cj6uMeU9^#hjhjH2L*k41Y7aY5|* z-_uFYQaGGlU2pWxgiwJ{v?Q-vUfELvC$gmeA9aa|iDy}9?5qls^rYll7*h1e5)%h# znf-g=j-}W>MZwPQRyLNrG?-=VvcJ zIAn=<9M`I!e{@+cv_w|2)dNCrVn~<+>I3u&n65&>VStkg=0Q%H1Lc-fPBC)CeV{y5 zpOK%+-sP-b^?|kse&|X#t57&+DIQmH3Q*(=c#fxMG|{c`l_Kyw9X-QKp4YKC z_DYzp4#_&q=Y++s63S}x)akBeaUMG=^9S=lT+CeKPIDdj`H zXp28QwotiafAXxWuIRo!`>S`0muCYdUeWhx95qIYbORzFK2}O9xzOr5l}p9>!xuH1 zYN)}RqXpY1^hmv9>0Q#Cu9l6^Krnzs=mH#I8Css#$0 z3Ed%6M!?@?jub$lMj}jX{z3ugq->ex=^`gHK46jT~n*4vz2ii@Zcp(I!5d zjStFSSK%%(kYIq4hG*tOO=p!Kr?Ur z$c};np){)tlKs{~ChAbm_wu%uXmW;wm%~)c{VzJq)SY1`habqX!(~wKq9B8_HQ)-5 z=!Rf$!-U{H)ao~*HfL(}riNXONj?MgeCg?acD}+3IgtdZvLEwBnYAA1p&G>eSfi#p z*m$Y8v{LasT!wk#8EQD=UO|HW9oVCyl3u5{n!H-p_5m_;BN^ohN1<&ZAWF*)HK4pd zE-lBZjhQR6{S{~_d3pOZn)lNtu6H!v*8Wl!L@ur901MAAC@8q?=)`LG`ad)-q`iW9 zYZiAKB>^=y|EsTGvRPi&DUz2g@Tv1{ww1M4;3Ae)Gqok?CVyNc(aGdL(Edn0G-~4_ za)h(4U`&?_%MN8&VenPTDPS|MON`M@?0P`k-oDYI-wxwIDK(WtU8(#F=%?y zrBtB6`$Vnj^67OyONLv-vAim&egmN-kc`~ka<=5E89v_c@$&kU!iH=hAf8aI=Wv`n z7A-@g_Wi$59q5Z2C$OEiFw?`>y5jZvKDLeV?C6Jg4*DhQy}rL}-8F_yMJ1I8#y@_- z`Bxn6({&M#L_du!JO7*+kFTKV5I!9SJ?;q&4J`rMQ4O7kZ;SnEX_-eqx2;5{6Au&w z@pl=22^EXW+J@5=4!@}_)Y;5Z+Ak+TputPnpFJfu1^c|emvW@BkVvVMc9wpZgi3u_ zjM}s3CPkQS%-wmZBtlvik{>j7z%iftyrZ~?!qaYz#aPXpkr`JfVDsL<-JstYJjItJ z9cG2Lh3bNbH0n*6tmlQ{2w*ClQ zj8|+$23fI>7)`dxEaJuzi?%tj{ozxg4}4EU`u6! z+xeS*BpgOPv|;kLF@oZU)6Q_Mg&uv7)HfNmA0?kvDK1+G@~G9H%=?U)p?-;8(FcvH zv@dsPfUbI~)-VnKU@=%-bv#REm4+%KgITK&y4@O|-}t?eineDTQIYs)(QG(#-&ntM z3E;XSNQ-EDi=>mEV1Kubdu;foyu!;XZ+V4H+&TpqplDL@quoXQlqUEGo0*;>ZjZO) zDLBW#foh>Fp2Z~kCbK?WbD9_;stpeZd*!j}k?Fk65iY3E)eDMUCz_Ki-N$#{-KsLFLDL^*QiL_J?Sdu( zaJtt3b@jTic4-C`lubdMSY238rH@ivTB2tzvSrs3=Kk|=vAGuML6Lew_C1eZGuTVi z=H(0a5@Ct>bkWOKMkwde(i&Xn>!GqQk zwGfguuPR$D@(6*;^@si*(QuP!8@$7t;VBMPlvNCdr^T@?)~Z8uPn(oTz7BWb3dK_H zpICuF2I>@H$OKC_baA_%GlMEad7(RKCTM_FFvH}w45pk|)@sn8V8VOM4V5rEXRx$= zV_CwY%K&D05!oBT#itLE?L~fMi>(kU9KLUubTIGRSFTlQr_e|i@{PNnx3~Y%l!u&@ zvY7JZbwzwuwQCh+>$+uCyM`t2xJ$8mL{UU$bdl7ZKQOM9m&#omzDPZ#s4CI_M>BUd6{2D z`MMzmInXBMRaL_oM9*v7XZbl5V9eZ4^or$;f+Jz0#`lf$O1f){^FQ!|9;)SaJXjhD zoTr@LOXN@sd7D`* z4P8m2w8raKK;!xYsc^V~VVvnE!#dN8@Lo!LPak}|Pe*cAai;kMmAp>3Xh4` z|4_jM98)h`o&8v>q$r|NhGa0`J%|u3^5g4`8XQZoL4}_2EKzD*= z|5EMP`yeKvPkHt#<(X9#AaVF^M~vuL(!^yaPUu$~&Ke3u;kl`3d4qWkcAyjSZBw~u zru`tPM3~e-EkWnjR9p4HMpJ?#l^uKru~o%d#YIQGWc&0ku+%x~m?-9vCSx%}G0d zUw4H|8p`nEF@j{kygr1hL!4GCK^6B%8Wa|~CQS6POOzu|AX|2XQVI=6{#gASi!Qa% zw$Uyi;+v)(x_{DjSeU|%(u^WNu9n*6d3sT*JR|2yMlX$-IEDORe*R`A;x@kebT}Xl zKr=3Z;j1j5*{VJ_$Pj`I3tkdfvc!4x{7>Uh2>kBScc3|Dg}53>lOZ{_o^Jn&O1@&T z>?5csDOjhFvZQJ&iZD_CwOu@UAT&xUVWFvptfND;iErL0E7SS4GwnJ45KaA2%&%eX z^oCShM0q!oQT1^k!$f%(mye=1h?Q}u%WxNN5941e4}NLyf2Cm#6!4}Drz*Q`5p;T; zOPkX6k9Px5;1o@CkeDC8ffdcJl5VeJ zpJn&i)73RgTz1D7SqhGp!~TBwIHCIH{z=kUfb*m3f&rkz0NHt*HJ0}Yv09(My!@i` zUX2u((Uw#}(6;Zw0fzX&fLGSo& zHn6fD`NBcl`(iPk;Ah%XJa4?C#;|k#8aAtAF8|)x&w|iq7}P#6z*Qh|!#H|yjUT1P zrjn=j(#Cs)Ksu>ImdmC7PGBS^WQdXQ;vP_&ISB~wv{oPP>rlh5-uMA)3KsU2kF2Qd z>>^Yy?8HTPVFjuX3Xe)l#gOG`>0{I9kCh=bm9*scl72DtZO=<7!Dhy`d8_?BPJT`6UJ z7Ya>|h*BAjvfzVk;Jnke_m;Rc0@|klh zj_tS~xN^2F5wB8rpTHz{j5CAW(R=U1$QYUVZ#LOtX}Q;4GoRY|7dYzeIBn4?hK7c# z-$*d>rNqjuh)L}7mqiVV!f8q{i9D8FJV7|J6F7swr~Ts?;} z8y`g`8ygesZzIph=-Y-LA?BChA0@x3=?0px@8HeRmR?7GCS#M@oByu27feH~^!npH z4?J6f`fYT|FLJWn@@h38a~>E>1$febYFT zU=ZhVyU*^t)MM^ImS}UZt>7MeTQB(Fk8fPOXoI828^0KvuS>mZ$Fo%I5-&V_X2W^F;L3<)2*5_mdsFDD{L2w4NU&|5%9+Fx#USixIFVT zel(C|JIh*kaasPLJ)b$Z3YJP_3(h)jh!;xeJ(e5Pkv-RyeSlsn^m0bn6s!X*k~LO1 z934EopW}q#^J{Ol3X@K$_P|B`H9rYgJ0>-|G+9!(Mr|hHLA8pkpIke}y0A$+EH_yi za8j#dO*0g|?8-nh{UL%BxU~h;!;U!abw>k{NWt9N#1c?Vm`$!v6jXi}TJUDzjgcbI zEhi0_vGB6)OmN?dLrK(bbb7tP$I@5l+I2!#tb0gnfN_j$RPgJ?lW=yj)h%l)> z8=zW#h2}C6U^~p`K(ipOM~LjlcmW`VHh|@+x6;VM#TB?0cJh<@eTSZ<%q{oVs&z8~ zq$7-nDX*P1u=nxP&Gi+KWV-a9vo|GCsfre+X0ZYfbQ7bJYQ)hu>r6wu3_G>DX+QD9 zE7>z?${SzB2t(Mo0yR*+aDemCsOvM~zAxhbQOcfqP?w|uKZG$Kz?dER6KN#rBRs|| zcUrtf#jXknw+(Q?!K*~yGR6z{qS!dQ=P0{3ECenFdxC$oW>IAf0Qn*b!Ot5VoK(hJ zS~*O0`};P|VV$=g4Hy4oZ~17+;o~^bmJ%*<52n{U`#}j%hJoqnCeI5OFRX#%t;xxW z3E$LLIYVm`6FOd1B&w>amnzTVA9i|9aVb2A!T~P2oekrcLrE%C8>xlZlm@97w67io zh^j|jK=Sm-f#^VN_R(aBu`tQ8W;RsLk@k8wtjh!QIjg=R-mBLbUER?c&w12;rHh`n zJclIsKGj2ay8Tg+32;js`BvwwAsWSrft@70^G)Mb6#lc9FXf@xbt2O!M2KgkwaSrjmEq~Q^j)*j&M8ZXZT&j01Wr?_ zBVpGz#V{U>^TdhF`}6k!TNfN+C=sj@dQbo<-bk}HTd;H_e zX3vXb(vk|-2($^?tMI>g!Ojy#{hY@WxFH3c(^XQk8s&wFTL7n^mQ!1W$f$2Sz0iuu zBhvSdd|srurhj&^?TDW@+!wD)lOt%oV+#9h`a%y~^jS0o=*YApi#@d_XagvA?N8f- zZ0y44uV#|)zI|bn14%GaUj3|~?(S6qc~yxElu$_-nm-N>4Ly*1YvgEkFf+UTj1WRC z5F$)R7FB2khy7*@viYi5 z&1RG-oaBDA;x4grS6harjE|3ayh;mo4m1)++uya3c6p1%xE)BKjJnd1A%2E>Um7RA zY6B1*=hyl22A}3en}%gk`B*`r~_+-KVDh6U#n2l%eRo zVT&5x*C0R{8MINc9>L#v^PhJ-d-i^XF|*_~L-!q{I=Vs6Jp=J!_hfySga6_QWm+wXveu`nL1(GOu#k6?E^xf_4b z3K=0YSFcrb`H-XBA4DTl{zM|}ttLGPxL>G=1WwTV=DKFqYZ6_{P(TkeNo1u62r=R7 z(|m{dJmN{be06m-r9Dxt%K37uDIi$J$1mTJv8eB2LyrCHr6L4igLgNGe-*QLNuM3F z$lEW3;RlB7zpLQ+^769W{Szeef@l4@54f-!C%L1$dn?09EYDAlm0?CRx{$SeAHcK=b(r(k!6E*#H~EP5Mf+{ct-kkIgHO zROH|fAJ9U7s!lWNh#t%$Z@Z?M4y2?Hw?Q70O4KTnQ)ve)CMXXlLN#xh?*n>jLbfhS zDZK05?yhzK>t}$pdUC{XuE51TGJH@gW|OUvQ4;B!6jN$ZJJB8wKi2KAC2_(7THc3g z&5AK0Qu4)}9+mei*|B}_e~ijch;0;-LQ3T1HeXo?Gzr^2T29>C+k5tYWVhgKs@^%s zFrU*g=cBOAATRpk6)QVfcrt;IWyMsNBTyg&&yW>1aa>bMjvyr3eId!)<}xaIUT4@= zOCLyN?hI5`)@regk0pq(!z{xj49uuS;|LJt{0u-;oPsvK z?d;~?#39=U+Lyt$=_ZI6#Jf;dho%oi<5a9ya$K(Z>Z*a|U!h}_|LX;iCof@z!PLED zdt+Q#TKuaUG|sQJXXd#XBxS!1Jd@QcWF=X;fkbfrtr1~Id8Irbc?^VU>{%#&l5MR!k#9|6wC+Vqn` z6n_BmV}YhVc@kJm;D%4ZOWT*1{=L{)hz@22ucbxDfYb#+Y@cS5wWr!(z`0%U25g&)!jo`&U{BTX(MqT|z;w0JZZw)b0S>BaK^Umzfe zJkj>=uWZdKGP{U(*ZHHO%|07aWnBD;C!Pu@1YDBSPnu639DW*gqPqR71SO)^>jXQ^ zEhXoWa2Y38SKHak)k)-BO5RuJ2Q0(G492IAMe-C#;&CE371|*}k!^&x@bk z6qi7d#_1%evPPJT0i{sbcZk#d0UAmmR=75y78OqDb%905JI&a62m!XnCcCw?ia0>w zeFFk@C%}JrVS&hPw#n`f>8-5|(NAhvu6) z@COxu_4kI%x(6AWYkeM+-U~e?^kU?Yx!Lesm*D(B@NV-8e7m zpw(^*xjY`e6gir79Uz+?;;Bz147;-=Vbe2aBIVvIS_IsulU#G6Mb* zUMB8;*~NS58ndN!w~D2Yf8n6WuIG?07SXX_S|}-Q#H|+LVcMj()era?Yq#!29%uOn z7sT`4_bI;&`db~qBuuvwoo6rvpFL~i_R|0^Sq^ieqq4*iSu$-QuN)-Bls&i#NZU5d zQq5m*Dp^qx2qz11Tku)rOlJ67G)MM7zngH~Mo zE!1@thTAu4DJ~~sWHR(CMR|w6&kx5o9X#j z$=rs93znNhvWw4CKqXc)v7{ZncxPIwjek+B(4MzCrWBicd#vSuwCyC-S zhc{dE$-udQET!jZQJ}$ zoaYz0^e?KFJ#d2H+?E9*at?{MIUJH>j;ovNBk%qvythiaTrYT`K~A#tP1aa|?MuUc z3}+p!iU=}^-0Q`lHMMJu=l6Elsrm#PLDeWzft!;RsfN_*4Tk6 zh5bL8zB($(?hAK7noqjB28IUdmWH9bySt@RrMo2s8M;FnR2l@NLAtxU@9Xd0d)E6G zYi126-W|_=_H&w&dz-5L0|(z4a}W$BcI(OfBNZsT^@f*aHoUlUb0+)RC7J$QISU+W z?(+&0J7!*K8D-miNnGqh>)P=<(62+|Qp?~2?<$9~R8RT`+tig!LZj5%w8F1gZJx@4 z|Ju>+VX9yJ=gIhj=l=wRPKr-7p&AC=)MHO179OQo-NaPhh#iTc)JGKxZ`d?)9S66pjur!vCuilq==m{5qQd^*+UN^? zS4lS+!gCATrinW3ygm0nb$aRNqp-K7DlA@XZc=(%Ha!=)=U~$Acl=j+U{}=~8KX$( z167PGeOt)#)##+oxxfr_P{CcSe9@a}-0$IIkn>c|^%u#H`Ac^@@!X zj7n~iWWNFr7F(qkc=7D9Q*y;%_@JV+?0-4yiTX=A=kM<#`-Qq$ZZ{%g2CeVJP&R+;WYGDW^&iS;#D2Y5BFH;XR*BAr72i)H?L z|A^zq`1Pjm#Z1!i>*L&uWWjAMW~U>gv>OriHcX3y_|}l`RYdQCyHsVs z7=-!*uhoDg(f(V_Dnh=zCf z;Gf8ZG~a~TCGq^W2)c#w%~X5TVE+E{4Y}*SXO;=t#|}j3|1SM$VD`~m>ETtarYR)t*mtE z^D&_^c9rF>L>F`Ke|(eBjV%$l96Jv~D+hzl2Ziht7vqkW@6}zr+SwzP?0Ju=-HC4) zrR)3zenmus@Ds=#56z^!5jm8j=vR>+5TFI06&?}Rv&!4*gB|pR`m=C|*f?k~PZHtcs&KVZ(eM(uHGTFdN&Rpo34=&s&d}(DUTM+Q#)bAE3K>i zXdiN{7C`*EVsFo6d1-Y)0C_7SI?aA%fd4O0_Gg;m5rj&;Eo+TVGx&aLiO5)*QN{23 zxE!YX)l$=ZNS#GnQc6iF#@>F5y{pCScUrguA|M~RwqWV!$sw#b+o183KZK4YLtijy7&%ljZLHE zl9g80qCbw~P_tagI;(!7=-L0mQP^(&FVz$J!_WaeikdR^%^@U)X{H(JPW>x#ZjZI? zN$pR?5B}WGBcnKm*DOJNT)JU6Fjx8hKY{_g>P1S15=7>uOTE{;PM3usPR7CB9?-Rk zDy^yll7x#4bQ}gm=xfHG{D4!D8vli-*u<-JlwW~`J{ovRViKs1p~+<(Z#wkSx9H?1 zJth$%LZQ_a0^?H^WknG(kgo1$F3F5kvejjtfu# ze8?}HVD3vN1fY55=wBk6Ee&k$hNuaS^Z6%3X~|&cqHw|p1(1~+yQaH)A={1RVuMWr zXRj4lOjNO(O@9TU?Meqt!?9AGg#h@^X$rHlT4~}J+dOoUzW9bFUkP9*rFJw~Z|Po4 zE=-C2ec$*~Rr9Dfd3N@2bMvWOVKdS2JOr}BE-&Rdb<~rxMhGGPlFovk0p8zs3R3{u zTA5WFnFQbrH8$17qn!5~D=K1W6v{bDU)|B^Us?uzsL0!zeQIrh3`5F*uB@XyOWZ=E z1&g%>eaAq^AuOhB6w+(4y)D13(g-^U&-Sc-x4uBIys>){6TRBpDO+7 z0v|$54pi!ydarFBye5utZ7;rBmI3lpfOHfLCOwiYVJRMpqX5`nTAE~0GeROg-~CgD zAmt|vUCyUdD~~WGReP=@^LN#R5W5K77cvLHb$7dM?!XibGT2SDq3K07QwV$l0tK%G zQ16~v14H60k_?=Qdf2hl^!z+g%nXaYp{61G;%`NWN;sCxT?;-_h?^9j-zw8MR@NFB z7poz(%)b3aLW1fS^PiG& z1LHHe5ci9s&*~f9S$Qd7!O8`BxICJR`?sbtX$%t`x(qeieR!Rw5RlpG#o!EExOv!S z!sux19m{JRN;7EG*(yr6A-z9>@?QV=B5Yd)Ovw(bCNVXkjtNz|?r-ZJiK-dWM~@(e zMmm=r#C<*;i$O3;qN@D`X4QXpQ|adIuEI9(Ruywl@4ga)XkmC~G&@FA6QNW%i3SJU zfAB?ydMIu1gP%7xScg|{ax|MSgVmtepOC21V zC$j+l12<_)#=t}=RxGp;cWLkq1So|kFR1CM*iypQfi72D{V$XHYKAN*-kSJUQ2a{s zthJ|rVH2I1!`3BztvGr0Z&a?QHQt(Ok9Y0uS`{h|^iqUz|*=}s1>M_zhZ7rNxfW%YI~Eod7XXQq0|;IJVf z>CRdnD8_`wZaN&(879%&VSgB-v+1HP$T215z910;)z%F4)RvP}o`rj=p@RUYqZ6x==!R|` zAX^K4FwiCEa9-`|{G$pm7Cx{T);-W6Q5izf(jcpQCwt%2{9+6+2(l5f980`~gjMH$ zkBuD+FcDkOpF*C|u$@lT^*(tzntk$&Wf6;fbRKwJyspsdT+JLwTQL-PYLD7PXP3a6 zc9W9^@cHT&?bGPOC(-P;BUKG$*$wO3L&>uUw=OQqFOnKuW?z#tx{`+iiFgvkKlTvO zVPlUZN6N)ZCxNxNf{O>?=KaAb3;0ous1lC>L+asseYUAWUV@tcStN?vhIxbo9hL5@ zo|$|l8p*nio_!BpJhSnL2QFq>a@c1L`ETxu0X|+G@iIA@HY)cwc0DF;g-KU(*A+ks z%b53jkmJc~I(BjygCFLU6N%tech3F3{D=7O(Eu7z`LLXsT3+lfP%&->4+E@OU0q#u zb#-J!DScWSuSjlupS?m*%?J3FACo&y4OCG(F~Ahk!SeBUiD0F1 zMWDe9L;zIK{)s|F|N6T+UwCPcj*_eM?hE0!fDF&~NDl~DbEIP*vXua+_aL=MS^jS! zWKMJDPV-$AIl89g29R>{78+L2 zR`%X$Y)_*I;4>V4Pc4_l+kb?v0Kl&ZC(-jM`*W@xyMa}0Frg)-+FwH|l$tB`tU+CrQqTpIBZ#-NdM1yw0gCOPwokRqxs?w~QlP=~HI0dd{VL5}A zv04Xk#Cy1Gj+xER$~@S8(wxpolOzrU@G}UqQc+UB=5s$rErYhqOQqJw({!2hN0m$m zj-_{@hR8Vv-{mGpkasXv&{(D1HxL+4HTQ%Z^5DVJX1mAg{Vn^q$Z872l#_q)NatoInfWr%+f)@izBq#7mGZ}%&5NS@0{j;UzOtYafT zeF@%SSHm!rPF9~Po2@L3+JdOJLwH#g^a_2Xu7+jYZV8&8 zh_Q==5FQTp2}VL1T6B!3r86FF*E2uXi``!9q*ZO1lS{pMFqCiqz0@4zzb$Rlzcz%- zWg=Q(q%wIjqtac_E~mQGKBY}=%3L=R5k}0xIP$t2p{+feL;UWKBow_4uAt ztWk{aLxpS9W2Z8O7qG+(gdf9zPz!-|WN;)OGq47N<}G_oq?}SNt&n<(t2dR(yQTyL zpcAr`Zc47_K1)Mb#>`f$KS8davkP!W6CjfkOF&z(LjmIB^XGJw2NxfomaeY6ZCM%M zy?FcfE#Ri}a&oqsx4!`bDe8FO*;2 z>OrG~VpbTPb=4WsNY<*r(BCEGO^{HSQMhPA@t>nm3HPsS%d4~)ZdCNMcFG^2@-^!N` zICM5>GW`!@{Kar_a&_|7`BD=`wPxJGYy+IeKPc^;yg&3Q?96SQ-0trrv|L}j>z+zK zjz>Ce$xWNy*Kx1IfZaG=Z7MxTqscIQULXfVvi=BcrX23Zv~9%*y}GDb+SJw;kmC^6 zHJd(l)&;aqE{RQu{0C1O^6p`pWpFO#H<~5HM^B~&ZyHy&Ep?WA6FmqQfMO4GDAzas zYfw!R7Qg^%akW|k<3Mfc@!?=VeElJ zCfY^S=G z=AWoM4>O93wMKC~R6A?E_jkrP zNpQ`6zOF@(mRFiX=r0PSsR|6+SH!cLaWhE@{&_FPU&_QBj*k8>qpV_|-bMZDn%x)15Or88$mR8&=Gsq@prD zHa6BG_~i2NKizy)0r!#W+tUEFNVjHG7tGbRaMp%aI^WqfMnwp7L{Ujf!EEg5>=&6%c|gEl338- zXs67{*0yc$er50ODZLn2#aeY<+~=rPUKTZ7A!T{~pGSf%ITNt4)kUq<8}By#EMwhc z+EV{sKa~RuUE}!IGNO6=VFl*5#D$?{2!i(k)<+_w-s893VJH)sM>8tM_LC}{ z@Dfac4rfYdblk1q9UL^n?&Rb|%J=em)al?#rjx$vdtnVmbHSrPIH!VyA>x>$<1p6A zQt%F%c{j*9x#(VzY_8i{`1J@Gdsu|8N8L{*_C)7?#U`KPRQKTrO%aQyu4YvAxWmN6vV`?!(PeqipR7L^(Pex~Wsx^ptJ?mdR~>U0;j2o<<+s+bi8;GL?5V#1e-h1d|R| zIi$lwg(<{>UxX>IannV58;kn;Wp>|OM@69)GizySoiBnwUtzGm*6OW-QUoDmI`RvF zD2k|LIP-EEVzmg(YsK^;f%}IOVsc~E)TwB5LC(CdSLNm5X7uHSZEdYhO%|^&{oi?a z=WNbmy&5zth2XMM2JKvpeZ&+daUvr6A0c7vAgme2Pe zrwqz8y(A?o>*UKI3JzsWamUB0jk)#8SW{swBXpx{NU)tM!_sgwlrV&ZICYCY6xdiq zuTgz~xSApi?7~Q2R$cxP6CaPQj@zi~Rpy!)2zwH}jLQI_Xn4@|3jWGPLR}px zI(otpJ{UCr_b)=ogvqlOiiUPaT4Ar;+$T9r_fl68$|Iho>!*o$S`((48WW9~*0k+7 zOLy8Ysf|^~c#b8eP71??Y}*m3#_N)7)CtJ-58m#F%*dF&!lq)v^x65B)WNk(Qd+T= z*TJ6&Dk6+PNAy+N>Xet%Zd~D~7i4qp}oISbk8~)zxi$Hfyv{p& z`KRwWrs+UMPkErAQBya3y5MkA+&jY`RiFyuBK2(?wXiF=Hh_=0-O=YiD2PKyNQjsB zJFjS0{rB(n1o7%@%B3N_4;_JUr&U#6pwiOHCp!mbyr>jI4H9ywfZ3YHewikDW+Qjd z;m+0FZj6Tq@PKO5m-H2!N5K@%&SNzt!*K64Gw4Qz&Q&6M1h$ZLgJ4n%FM)gZgPXn)> zC&ACNvr0kPJbmDhzwPufpT)|8v>MB!j4~!IjYswzb-fxqerUq1zS zz=Je3wd0$b-@K1aJR850A4<4WU8iFHSlpIe#3n_s+9{1v+q8lfp=O%ZdcCXQp^!jP z4J<26$;sJh#V~(mUeVEop}9Hb@Q}GYOA);xNr0*>q38 z8ZyvmQ^e)XtnU4g{Jc3$!<)y4A-Z4_M%jPb`Pkgc>3V-kEh+^(odxGG;+465268ggqYp3UEVKGzVr}`l6G)#0Ad0w zE2|d)H{i4b2Q^?_~jf8*k8UD7QSgsHZoJz2AOZR*K}VT6Ydw$jBuWcGE?z`4$S zBqs-*%^c31dV8L+x&=kTrzceucrsY^B~DKZK9iv3KA;wa)In&=1_3u#rWbhs} z0DHLe8n;esX69=ayL8~uos}@02>d;X^3PMPIJ%k#2;URn! zei{CO4mLK--&JMJs6tSFo++Z|ohD2XnH4AZk>MeRmc=F_4J&=FI%VJumMG&FVT#fK zVbi6VO5|46e?~}I#9ABui(?SQSf|!WF5+ORHZJeFq-?8qy7togZyuE!-mGuIH$$mu z$CLXPe;LXiY6kdLW8QRpB{PmZdL37-5e{0^RD&;Of+tdda#c!|!vA8^ocjIF$}Us* zw{r?6st(V5hO&oEqEZyT1>dBkHDntjMrB|N%G7s43$jft+I{zGD@2W|WH8Nbx(}=W zEmfMc8+&Qy>DgFPGBESwgYi^s{>`7W&s3jjY}KONfHzG|=U{)ouI*OX^25K8-U&1j zB8Bw#_s6QVd_tAcZo|1_XH9~G4^Zj(6hp}VvdQ(d`E*EY(v39N@^zON%;w(x&7!0A zOXmuo$TKq+S8oimIy<$j)k3+EvZ`O%SEg_VpP=iV_amWi@SBElmljJ= zw-&sUMg>vLTy<;ye%)^he9W@8HvgnM(^g*?XW#sL+=)$YD1q*JB+ESLijK#yivvlI zn2w;KL*WxbHz)@;op2|Ea0hPfXD2E>2i$u}4=#|V?8uC#ev%ak!W_c{jhE!7%c-qn zTj!GdC0BQ3&+kR7k?L=g<{!Y3lZpP-*pv*%9@E*kgvYV z$o%NObA9*|FY^ha`MJdN6G@4+D;^tS?SM%VLj z^Ng3VeNs*Kc-3~uzG7}QB#w_SfsfC{#W^qNs#K)gCS;$|oDS0YMR}K2KTg#zD*-<* zY(B$WNohOlyHz{CQTh5zpHqlaspdP;Vn%=4;|f-CQofR6W!yf{FVF%9dx{_QO~qs`sW!ZZS7QL}m&#ZfD*>7jca#~}nT-R1kah}Oq`{f~ zD4dCwH0fq?qW~J{Vkf0pZ<#>4i0Of0#y9ff?zqwP#e8q2EqnjUZauHs>qeapUMLNsi?d`@u={NlT6~)nT$}Wj6DOvx@;5Y;xC@Jp1C5?3E(uCH^mm&rZsjSQdAxe=^QqIq~`dd&?KK3F;E-qVFo6!*&MbgCM^ z_C29jY&N@elSS<{DEdF+B{(MPh(UP*xM=HxA}SF|9Q^y<(2#Ff6v*IZGF4On7II`O z5+^D(L%LHvqi}mWV34!a^A2s8Qck{rG@~~tDd|@mt8lMoc?>oVg-V>3dI6__$EV2; z4RkFYNpfoWxdB+adW)!`@0AZnJ+nkIPSyPq6F*4A%Da;3Y3Yv>lab*yxGLuf+c7aw z51xE8EyU4X3fdjd=VL9RBx-}BYd*j4?UkZQitIDjo=jd{a3xbz+ki553S3){o=yj3 z2P_g@k#U|o3Fqb^4W5<2y|=bG%*md84ZD7Dz9&tM#(q6g0KV}JUjK?%l~i{)x)dn?R(WFZ-#fXSA#d=4T_} zVfL|~K2hm#yieSaK0OXusLaL=loOV;E4#LY?~zwu#|LK2rgzeJSubhYP(_;>R$d>q z)t>s!E=nP66Gaz>-{4Ax@WucE6)9+*l4Il8W)uIv%$$MU2Yn;JD*3PiR*9zjhVISS zptPTwW-4gSXYRaVSPyj8B-K1`)|L#-U6Vk%8k;4Zu$`S<4QgXQOgQ!HXksVEhh5aa zd%WWFFWM>r{RuqM-Pje2$W@QoVNOI=P#ckNMiF@XC$$(ea$89aZx4RzF8)Vjvt0sx zQutpYkkq$$eNz=VReP{5ElSu{Ps&Ra*QR;~OEdD`cL+}o9ex)5Px7?w#7OAR$8NN{ z0J4Is()F4Ky&)v|heJ)K!z#QGw;^uy0Z&td_dq;(CuK&0m^(2sAw^?B><-%7-(RQs zYy}u%N5`WS6;ZdQmdD=S-oe4ao(RnQw@CW>`tjsKA2vS4O>V^3SmpiMd@~>|y+7K# z5>N}PYw*qfU}>S z{yc0piT2ESg{K=4(tfNczu0~xAoDN7kl zHxfe^sw`t;Y7O?o3h%s6kdTr4LaS^|Bodb+O!)9O+X9|r{lXKh&F!_(TFje0mgolr z7#r~t1}XnzySMNF`99!c?Pr->k$!TU;^aE^+_VOosjoL4PeV!y z@Emy^hQ2u;8++*A34hQ{Tmd7Xie*OV#?}TYu)~f&&0o1vL7EY1+`$O)u9Y{f%0Bk_ z$fx=^ofakdi1V@aAFn2fs5!+vHhM!@L6L7n#?J6{38=&FK6Mu+<0^KBo%zx#;)P4mOqD zZ=Xz!rwqN{idgklhO`B-yTS^wu*aaoe|mO~-JV1t zj2V%qS0}no%KIhYX)gHr1oL(E^~vV-MCJ81nDb@Cgl%lRWX3RygxU4;I|Om~elumV zT58UnUc^DIf(l|qoSae!T!?;f_$3=+f9%(9h_96$$xt_W*NxUcE?^7QPusn|{>=E- zfNOW}X?SE%k*YDxOj)ZOJa`!dk`oXMDF$dM==SyeIQp>$9Gu_PL*r2>-wOvG zuezPi(NL8vDwHrE$)C#vktjOgtaWdkoU+2+`2(L$GLZI*k1=x}4ZJx{&VH*au;bwd zb~1NhfkZFU5#p{t$Z>c=X4q+!9bx^=(x0l?;NAn0bQxqBTKeWDOHIW$vRj>VGsR*# zqCq>}aqG9?tB*(R`EL`c>T43vj=g3X;YrybXwAKnLe$5feycvXF?n(2j&)C9V*VVz z)SU=C%GB0Q*ELY6tV+vB10HE$c82zfZ9r=k!@sQ@ud0>-gF+gos`RCpV>4~Z@ErTZ2L9vfln$>k*N#j#V-?~)ZsXerEL z5YB0lnxDgzmlKmeL{Z~=(x8jr5n0CExyArza78F9{ZHz4{E=OavrIGy;81rZ`@*%{ zmwJ0YHUE3>x&*HI@_nBZVt?|LtbFQ5TzxrP?Ek9L>at6NeIlOiv0MBn5UUp7H|Zcb-z?rr{ch^?NUk;f$h zwd46a#jueGu!OyW+xN+2lb4GRW6{ZO8-y{Gv?%JjK#*BU@_sf-P$X%f$B?3TP^m$~ z_2+hPwoal_SAabza`{w31e{Cv(~Vz|Jq|lLSUD#U$B?KV1-n-=tSbQ1MCfBsmX?-&ep#=jaJ!R}-ODdE17fEfGAlWLm;an9R0b^e z>b@#waGE?6+|r5)^8J1-4ZTqC<~7#0c}+HH`}P6jJb&7BGu?VpH#?W0o78V zHP7U3QS6A{BM2aKu$}>&I98D-%A`|hWF!)?Yq3=eOcmDB@GI~cet3a4H5zfcPoGSi zKO^0}Jq_q!>pLg^=M+)Yk9?M%wq+a+LkUfUXXabH&DPb*?ArXUVL(ct?ZD{qr~!x- z45ctAVfG~oddi5r0X@F%um1UX+IgK9Rk)R)G{h~vptV8D1&QkZ^fTROGpOK&ZZFxY zxvImUcSZ8d(W}E*Gu2agA`K0&Veh>>Jd7-++OfZYe?IdbKn2vY(0@>y_1J5J#IamZ ze>+icwEC%g{+q!!EB;Ty6sqar_obmV)h4@=umKd9bIKY&S$Siv2XkxNi&91V)zwwx z<%#W@bad7)ldk3E0YRa5W+o;$Q^zA2Mu)bKA3rMUZ}1UeHLQC|N1g9XuOfu7uRLrV zfodS3F1%p1|Azmvk=F4+jI^|tzta6;QBX=w?Lm;hHe)BLC)LhB@fe+STh=jtH6Y+_%Lc$-m;7l7C(c)#` zV{6Ey1g{XLagv+XT-;&`fIq_`DMOp4YrWzXdh1l!fCm|FuSLu?FkJY!A z0CkeO^0YU{pF*<9(YX*cQ%O>Wwr+Sql`O2%->jN52=$)Cq|<^Mzf_i7Wi!qtI9Y0? z>rWfGyAh-lL;KR-ieu4j3GYAg8wiqv*yPmn6iPDQ@lEYdh2@zyl?RGS1q1xBqLPY) z5r;XCJm^wYtm@x9WskWhL}_d#MU1+(H1~ErHj}QU)zxuCAyN|hR;(~Q)&LD6P=5d) z`EqeD$Bd`ImomKC@$g6g;EUTktRDjxHo@{irddtvvM1U6quWxyT$bkfMLFxn%@^9; zB*mSZYaLs{NIPP}*6?AYadE)oZ((uU-+!{&Apmgl`FNU|+On4BIf9PtHQ@k9gXW;z z4%2?~Lw^}X{he!GB*z_MV&d0!Rw=$XY?hr|%wny=XE{Ld^1>(N8Q4bFmO?r|WszH( z?T|h4%PqrNgQ#a~1`9IgUb>dQwv7$#2Ej3J`PHWp0`FzIG>doJi8=qK5&?z#9U71; zfU=1;F4hf)KX$&}_!}aC!iTE5>BK+{9fo4=tBSin>!Ei84D@;39wjnZZ+{k2H5**T z;O_pxJ^3{UP6QQWZ6#vYb0(j{J}~dx|)(lyltj#b(x)m{W}?~BA@dk z-Vx-n;v!o6wtw}3boiXctApMO|JP_8gzDhKhbF#iVjdUTp!rlO>7lMUz%jT8`ND>*RZ&sd*VNu1A|n%a+vpA9 zb$uEbXjMw+y4lOU69TDD&CH;>x;XxBnPJGrAtY|DwwzWNRMY$Z?!%6%_z)^>Dm-j= z{wbSf@yJ;1>yi*UN71Z}=0tLHabY*Vd8}ohhqRrC#TyWXvdWtfgY&^?gHMf&Nf{dZ z1W+Bi1f< zsEUouFAbNg|A9=gv>53K8RJ+XN>@AGAJ+Hw0D1zm4lD4(g#|FH^L0tk9vH!euSjm) zD|Agy*N1MWYd=%_=md}x^{P}z48B->k+1nXA`AC&UGwbl>}8;#VW2T}`sR19`O$k{ zXASqXJL{*jjh=|ag-p>u+$NN5euRLS_PE}u<-dtC*BB}4h$Z29luqwO74~Wt#m&s5 zN&RBRm)}~Bd|FjdPb+THV5R;h74`}7=#m;meOh=Q1rPK&2OjD49sG9m+s_^SKMagKvEV!|MY5;?Sqf2Z;H>SPscG6fiJW~K!!!v_ zNNE41ITbgs32ws48A}xGWxoaVB7@J7gA2NitIN#pt&U~mQ+2d&Zf{KK>l$TB%QR z_8tln$rLz~5_agYsdWg5Fi0C*2Awj`3K#fzPv!TB?SeXkf*=n4Lgv0P|16{d&4n-k zZhug6#5Jtveh^1$`p#WB?D7v_W_c8A>G(6ha3WzBMV@tW9-N5IE-W~eL!xxk_IB3L zvc=`KkAjo}<1pd=WA3R5xEt>6MQHvSl5|S>DoQxSb*psb;YuE3EWrkezT@nFj*rhL z6QigtECROU!TB93s03e{1-;3@tq>B0_&v9BdWTO#NQ20&DphnM%)n3}n~D{hUb9*6R-!CW`~X+p#2Eq90#Sd?Ud%fWGxC{==Szq}iN@h3Z86A4|dO&DMV zT6$aE$|TcQsSsj(NwMF)OY|1ccQrpEib$_0_tPKBlohLj&<+)GszZ9qfAZktN8|j#V8NOqcm!f|H}G#+<|Ynx@H=)LJn% z{uxN|1c8ti^PQ6hPn493N&;sXRbSY*?BQ@Ac;9APRT@ZBic$;1Z&w21R(>3jUlIRt zC>#JDnJ?HYYO&W5N^|Zb3{2wciiL$mmpG%BKJ!b0;<19Da`Fh;2ny_dS%qVZx!F;; z&@!)_;Zw9JcXdiKt!@y z`AK|o5$62X-aD~q^YCaX4=x`ZXoDaW$bLT}S2!bfe~D!$k8M>MEE^g1%drpuiogvd zG1PLl>sIi)z@F?K9qoLJcXQA%k3=nPzgub0KRK?tXueaW=SuxBbg?Tozp+uM6h%uA z(`U{(mD6I(^?LaqjF4qXzE(q=(II7dets|lEfko6u|$0kI~`@$7wGHocl+|#Mz!Pg zd;ADtaT8GdY6x)dsah|J98#grp@qT>SEzBd6q{_>r5=5NYxf_dp#M3ltUOC0H0!!G zm?u@}v6{k?IOZH=*dI-?=U7=yvI_qLx+5qyW>uE7p+`Hzjmmb|dbU{H+YHw?;Ko5OFx>7rpGqVqg9sHN59QrRbM`lp4Msh)8!OYcYT}{+ln(Vo`2vIT9rKt|PkyfN-#=Wb4Z~Ez=ahiq5=cr1 zeeLeH`bstCg@+rhlkl5Zo? z;y51__?KbHP5eAIO_qU4~u5D{Ng| z&-_;(R{#h`_r-8a2hPvmU#PtucrbCyw|%VxCfqY*OLZ+f=2vQ_Eq~iyj zG#`(P>|qcQI!iPKMgbWUcFduCS8WPuECf_k+V~jXX52|}IeC0Qd|WdM$sjw}Id-|F z?hG=3mly!36whURbC(a{*gwvvs-N0mLV5g=Bh;X)B-JGFYo-zv1I1E!5MW7w zaoYXb71ub;!#7~udw38(auM|gS^fC9P{|H}Bs6mvU3h_59l#{m^n#?-FgE5V`SRqa zOcu0TQ=9eQf=rE)MN@|G#M64o50fqRlhB6X9=9;)_|8gc2H7Mt(t8VpWaq{N-C$qY zmbryU2!$upJar!D<4A#==N(@-3R_&YY9vYi4Ad1ab#LeHYBS*;3sj8|frq`|?`2G! z>Ujb97O4gt(AD+zd4YM4rdn2ViShjzKAY`F!CwE*{Mk4I04c!PaD&%tbo4ko4=Lo~ z`nvP-a-xbAMD=*H-w&SWgdi?lAfX=8DQWywj;v<>qMa$>{#88LIMwRAebk`MyZctf zKi(gyP?FOo6|-c1^`~hL7r2!vq_u zf!>OIzBAAu=3wu)(=Dz(1(^^boEf9ONjPam0eMgE=a)=*C3`aAh>s-ebU;SN zhuoVM-rGhcu9t?ntB+MeaX?3sH8>k$nbeU~k&%*ij53kH$~7Mo01+f`!$BUFEfZPU zTww(DTNIZ?`*XLO)rOe#h?s}B%5jwuIO4Xf6TFnus7 zB2>bMH4m@4U&k%|O_jQ;cYS^O{bd#g-cdGZnVV(P(yE)QsGGNRIFzum0!s7-Ox2|Y z{%p=(!baXIRbp?*YkHoW2{K-NICDki)<)-5Vg1^=FadR5VC zKZ>Tfm-{Wqp5u0uueOLgj4D#{s!s*<1|C@NYb<)0t&MsF?b#Y$O=o`c*y%xX|e+UOEfP`wG@#u}5R84tQ!|28ga zpl4vPz(~^EbXnT6I^iZlVZtF?z46cE0-VQyB#L0963G72>LrQ4TgIeA*)%uIsQ&1< zQa{R)?Fz?TT&=QPGpJhX1()r7CwZ4KFmG~Ixx719(?l7DS+c**ZH1WD_Q9xISZ+rx zQxXf|96lX)piSlJyP~f0(g_z^oGKHE<&#{P#cyThAot^}V0(i7gwUihQ7nbO2%G%=scS}Hz^haZ8WTjcHZsLpca8WuCY5c_YA?pV(Ot(OS{kHC0% zh(2Kfg_IQ{fb3d@$sd)Tk1e2jaHq?2r{`%NNrQIMoUDJ^SyC$0wwL8XGuBbW6eS+4 znMO5>03=5^S5t*y#t+&G-38n<3J%jr(UfzH?_(0JHkJ(Jnif_0DOXSw_RDU9a8ir? zObrD3V{csC)G?1&zQjjf7a}M`_<1;Rs+EuTdyLLEi4UAAr0>Sj-I03$T+QbcU#BTx zN*yY|1eG{hT&1jbwF))sdC35-yCS&WBQy!PWe{tH=cwx(b;1E^VgRv@g>4guIo}eo zO1M%>IBn?49Io=WWnN&I5vB%{KttUa3$>UUjjbw9U2-Bu86yLex{=@ra$;p9D|Of> zT#Zf&aS0SIHUL{>n4GkeUf}8LU@t2#g}ZMne+Eoop3doP;dm|K=Jxd$gRfQ|)JE4~ z1c6KfzKq2Xizql0S^P|BSa*{>Ov)at-Zso0ctqFe(PW z#en}2h0CCCU;x}0bjukJ>|RWtZXfI{!vLy7xhuKwCk8P`JN3r1Erg5IY{!t!9L!K< z_m?o0-e@qdJ!hBE>6^Yr7W{kd(a4Wl8XG=&>Y9gG2;zygoDz&c^s1(viy#x5NCc{A z(L5q&t!u$i=(xD{k6Ug5iY!3=feOhFLy1ntL> zN-*@ZxHfj2Q_>{etGpsfRcV1A7UiduWvIA!SNYoqOQk zE`qP;QDark-;3=|D-QB4i^C2FzSq>SR{(d)voI+C)>@3^Iy5tR=WI zm10TjPFblUcZp(r7b_I}WYN*GzNY?zcAEgKo@%*09{#AdRY+bvdF8TCO_TXNayO06s4gXC=w>BYHog6!4-Eu}|a!A@Jw zwe?6l{VF67R^Ig*#TMP{(G&=j1&LEb%iAdi)1iXWt?HGVwB+@Z@({!lj&_P9nBU5A z>t_{%V)Plpj^Ih?%Jh@V!FEbhmHMU?{F~gAgYOkrChBUOT)tW22Rwy;3S}T?K<)>B zZ}KTQ2V4gTI4Rh-NMDGkd7J450A-z{Ez6g5uzo+ginX+@$Es&63FRTc=$|gpy00WE zNOka9M1_O))v+4HF>L`R)^Y)mKmu_9-q6~jE_%6O##4j^hG5MLbNNs9dalypz5IddlNxrbktd4`xTq`$yEcTrG|@hE@j`kWZ4EI4ntX6j#Z zh5y=xh?<^8_Fd>SwbLJq#Qg2@Au_KFD8f5wYH)l$RJH_(Zt`PinkUaWcqtvu^r9?E zWu`UK25%A}%nuoa18Tt5EhxMlJ(6|xUG+1-`T&X%TnNgPOU)Ukmj2>gri5n3b)a>00qOBor=!*MhjaACfj7M{j^K zS}>e@=&S{vYH2`%1|&h#CkyKYn^H;C%3g|r;cqQo>*K!Jyu^qIp0|M2|w;&KY zm+6ug4iy?u6-8Yp&};1*b~26tQWl=Eqy?^dPC@f-_=`6>MAWh?zH!_Nx73-@ zIJv}Ydyrxc*oL!bCHzp%^iHiDKK(Y%n9G%X&>98nc?dV$n)aU0NnQpj2U7+-*|dxJ z9xy`D?B9JHfZjk4`;(rbC;nf9svsSSw%SCCIMj_(<}=f6o&;A##^)#Y2Vw{fLGUK6 zkFP1_;ub=GW8X9OphVt{nVP=x1E~Q{jSL9DV!lIoK>DaV30iG*6d+Geqj_j1ndN9R z7+U|fkn;*uQ)&4-3!}$C9cM!3hf`oi>?TA35o9ARmIyK!^a?H8ICUxevHhaLA`Q2A z%0S~pe832+23Zz-s~D@$@2{806exbI@a510$q&E@!8WgQ2g5jtOq`7Zk>cI^R3;4G zx|HN{BvTM-d!T@Ts_=OtbN@x-O;9#4w5k)s<0yR;qJH0)>LjWEKub*|``&W?C*IO5 zKD{X=fYbMCF* zn7NHb*dQGl(k-K=Cf*<=l$rMs<-#@np@+DJhzcWheJ$ZyL1xtSOdG&i63T#a6K84k zON>QyX=Fjz?8F09Jk+KhR)sE6AhpCR1m_7Ioo*8a5M6wJURs0gZ&|%5OHu@1CQBQbqM^d#DCQ-7pgZ zQBcqjwgh51BmK>EU}amJWouhnZwbZ4CUid5kSWl%(XG z3p0Vt%fjW*mi#Q66idwUneIZkc3*o zIRXSy73jTzD(*S8it&<#G3TL9X8l(h2e=l$eR~!tYwS3bs8*6Z;VP!c2yI>O5c@OG zos)ogj^DZRM%9!hZEl+hQK69>;hl-J7?_)U`+aSuY2zm%YF9q4+Oa18Vtox6{xBM! zJTmo3@Ac^PQ_dSV?t9UEnej3BQbFWK;2%HPxds9cqdb94Dzh(#c2eQ5OXn1Vy^nwL zofu4UrSmgqs>VHai)0r}8sjhNd?tM1#R4-;L)tFMQJT4T6BAB?sD{&BN6oFw7D-=3 zKaY>)69>Fjhv|AYG)y!RC9*kVV_u-B>+I@E+^{t?tA)T&2jE<>il#6Y2Fooy^5(gb*3U6>k= ztvZuLbbi%1!#ocTsJdD<`u@zZAHPSd9h9ZIENXHlyUP(^=F~V{sf$<5tX<6IRg@Pt zAhysOedF#bxdXj}yvwYb#vMixur0!NEt7(2K@P}^W2xgQp{ZrWgBH?|FcZrrn%9J2 z&*5wn(0e}i7iW{TvvyZ5+c-*1a=ZFaEbueI{cc?ctt6}=j`)zKT^3+Ft!obz&%e9` z#N}cTJx{xWRh@_D`bpaTr2X>0a8sal2?G(hs}3&pSGIP53(uGYULv6~dp;E)FH`r; z**ZejUZ&`WJKfl*;xj+Z78Oxz=u73F&;9&gwD?eW%*_IsfT5bZjK12RDd7-d*7A#J zkPJ2WN*M0{NuDZU-i?$b_x1Cg8kSZ46KPEiPqe?mxl^e6t~}(~@C!u&4A_)ywKFCv zZlbyc5j(MVgpg;RwP7!fg9zLL^uAPR99HsDh`-%hHH!_;B3R~Qd&qM`*`2~?U0!hT zgGPZcDmZUUayby5{VLYZylb&TWrrr?K+FN@U762}(H2oSdAs zl^}%yfAL}UsfokVVj$dM>C#n9fQjSf+ui6i4ncl?LH^W2(_;42#kz+zionFepMo2? zZcI`?nq_+HzQ3Ucs@3=}+E$_VGVZJ9o@VB>=H|2?yiV05C0T~#iReQW!f?Kom;v2R zV|Wl^Pc(jpA3sM8M{oxPq2KTmyUP{7NUhQ z(R7rIi?JiA-7x58jF+IsnaUxP5>dxw2o z?dg0I(ylY8j?Of2tN=mD<^RogSjzVHxSB1F?yCj6 zY|RRLLt?Sq^W>x>6&+gHjFW4i0U?NQm&xO>PqmPN!O4N(mGTiWutG#Kd4KU(61LZg zU5yhg6f4}h$Kh6h<>yCzRt2h* zam}7}SUaI{=bn{d-*_oxSB?5CJoiKt>{}iEuX@~6ReXM-6T&laulKaM~WtVCe%}&|dH77fa^%$&q4_-i->7OSh14j87uY%WkWpmv(C?|)dFRfz6CmWj}>`(G7y4&OwxzyVk0W(Aj zvsLseT@{RvFQITSOc`zBL#5dp`7MSuHf}=pknzIsmvnd(Kte?3N7ZDlHP3Dl!@-4n zrt?BduRSEO2B)?wHLEYgwTi<$hygA7H#MFu1<~fjO89eCpyC2i_oi~nT0W-cqm4|% za}Nu$NOa0K`EB|cQE%e=)rGfHBAxK3T{))@LD!pniF!H~fB3Kk#ZI z(E_Z;23&6TzT%?ZCwqGZN&04{YLtTB;-h(h50q95wai_H|>-lM!kNgfsiJwrVMailZgBWucc|&+0 z!NqP&FSm2a0THXeWfmdLLEShqqsK@^EU5b1)SMCrGMUTY~ZYZ z82_hwY0K^Es1GJlJYHGi@$s<|H5gP?RdoVz-C0kbopFGeguMuY1MF5jT1rZ&60X2t zc^2X%aj~a8%lF&qhomp#{7aI=rkGjAqKShuFwM1%n(g|YCCkR*v7?PHII&YEFgm~_ z395hx)%piuG+yY_*8!Vq(PumMTp!3Ns-CF{hr>?0ul`~+aPazbWSA2Ar)F~LYf!d` z!klX(E1j77LY0lrES34MYCkM514S7loGYWtKMve)j!}N9)80#)nVXBUse42#bP%`7 zfS>v#Y;%WkwJ?f36pXPh!#E`A&mStEv=wOE@hg3*`wK&hxBJ>816~GFokBx)q1a)s z{*dhExio+Uct>Zvqw6-?A-Q|-i0~6pC9RabP z|1x?@E|7V*W3)S`Fc0l{5W%&E4r)v1IZT4bmxb?K2{rms9Dk;?Y;6J6C8zGqG@>j2 zd!F@U6BgQgir*o7CTa}CDUUL+y{9DL4A734QfLB%q>lNN08u}?aIBpQyY z*$=^r@BoT#W;agmxLKubT_co|MCrjBz z5ul)fIFOKgmFHqX-_rL%B+|sgBe%s< zRoRjwkyT1Tvd@yKK~J?-O&VrNe1c z@ULYk*cgPHa4y9?ke*OJfM+kba3hwAI)1mV>EfUq!mmN$GLWV8W_MGT1WSR}N1tDoIeH^cQ$Jt^to5NRbh}$kMR>dIgyO!W2S)7cWuD&oAAWgc4QGsa#E%ShW z(z#VM30BFj@x{Tcw)<@o-23MV&+py{5?V58yJCW<4mcTlFuue~z-lA``auvU-*O?q~k{*nj4^SJQc2 zB|hiDeuv*-wZDm4BMf;3{pLXU?Ev5~Tt?&ZP$-kk5^Wda^x8o+)rkJ9^bEh^r|u35 z2ZKn$-uxCfo84|@4*-8wD>DBhHTV^X<;pB{9;`lZ4t)FOzhgM(9g0F$BQ%^6IHefs z?PdZXQ}2CMiF9tw}1Lx|1y~?$Dtp#r+jtILneyO z!A<`v|KD}3_P@L!+3Niww+DBT|u+kJOb0?;e#k|Mkv)LaxNqAG_*Dm9d?+ zOTNm_hj;ID4ir=}$e*Xwhdil;3=IIq>iVcRSRxHTV_L-C|D@e;w^E$|@cU={um76k z7->WD{r<2p1QAY#FI8&|f7P~-A)U`&9($gdpfYIr{;c=y0Ke%BmyPzMvkUzgm;MK! zIKNjpu#V7^l>1emuNe($PG<`LbfPH60n53_Vfs$J`vQ82YqMBFypo}}Oj$M?kGWm4 zxg`$WmJQba{O@H;$=&V+vYW8@48C!4#1tg+2(l;NrGNW(^N*F2O?#OL^1rGe<>D%?Xd^*%?s(~z~5g; z@181m=BNmMma;8L(6FKIEpdMpP|B~m)XYgwwWQY=EnjhHCqHNpc&g5Re3joza-5J< zZI{bct6R-0yGbR3V0QQ~q~f!;)icsPjFQV0g;#}Xg4il8`oAWSsTT70Je>IaRxqyHWDS211|ZI=aS>qt2`a;g`&(v`hE zuoso^x|Wv7((5<>Yeg?GD&@C=LOujZ$T>CNZTOP-9yZxC0w7!nHLXY*Iq&hA%}xg{ zPh{aFX9AJc?dEaO1-`0e*w>ltxL+*63|OOZk_k~UK1uq3#DB)Hva){GkONyzOiC3Kwsb$e9u3d z;5h=7_#j)5f|+YvFB0UhL9!-}+#q03$y8L-8@;Tojl3Z47K?qlTW_5d)8D;W!|#Qu z|Nd2JX0;}R9FpRweSz)l3l%AD^kIqAB?V!c|G(Ia8@*q&+3m*3n=i*2DiwJDWm%MnM(_F%NovhO6zbrUk`*m6)~4hIaJt-TkN!r5`i&#pHp| zco7)R%;6X+e2E>V;1gX=TNC$LdoKpY!7CtyN~WvWf?;t6VomfoR98^Q8d4<^eVw$! z2D!|k&7!V`Mn9#szF0qCwjR>h1qH3V_N7_TpWKx;NnRFiv@I%37Fw3KKzk=$k4W!E zFwm_ak4tpNIL>@FklcB<&&gRIY!Z}=@JV+e@;9f(4yByXyX`+s4wJ{c+#|D43T?@x ztf$`_VRR5(4SALdNO||9zUL!92@654F*c|vgAc@)B|It#`j^R_3%=J>=eCN-4p7+D zqoxFc{YushK8H10LWth8KAPkaJd_ciSb8X?(_F?!J1?hPHGK4R{wNcHfsk)s=+HJ} z#?z^8oS}M-gW>JP=~mV444M{dHP6HohW)?bZuui@iU9BJjQ%kse~D?kE0mp9k?GLu z$@_VJq`_TR_jY9_$;o_bbO8LS{+Up5IZA-~ReQ}uY#+@=PBqg_`np`$Qb+rHD`BmBzi;Z0zaFL0{{(K*csV(|Ihx$#A zEmUb4^sfA;-Frp}Y|?ZOZcKDG3^ok=S20(#yNURp(EZ7bu| zb^>`ypS_IMTCTq%h>A()SF%=Cd(O<1n0|fUk&P2}uW{g&Cq6LyT92EhTC1$HGrL`w zvx^b>)SWV4slOjWO9t|*Xy&ir9@mcQqtVr!9vm#pZZKVadA#xVGEep6()AJ0#+6LZ zwRpT!WMMnwyC#Q=%N=Z6Co|5TbrGhOv9KR7!6SX zjza}mAI(l4xj9Gj^0qcjSpz6qJ~lz!+GaF=U>apZIOK4Z|p8w7B)A>4< zqp`!U4I#K4kRz_a)U`%^c<@I0$<2!bvcac%AtkB5wEXw4xrs+jlIZkIQQQ}8OTBH@0 z?Xgna$}V)Pb41uysIqj`B3oS*aJnKm~x*qTCG>eU--YV>ql)c{ZpO+*W{uGQ615`03C0?HeTk4;KTo@VUbv$>M+sTBkNgl^@s`grM z1}0CRIk|gG6T1Zg2`&K6_}rX<&HPV^u6~fw{$AdcN?K0Q2C8a0ST*5};A;CL&~IN_ zof6-<&{S;*NqB{M9~aC1yX({9Eb2S4wMdyOz{`7^Mo_&c@U8+1@qfko_d+?xUgO!n zFbiE@=b51tr?P&#o0XjJP<}yYYnA=}oVn0$f*C~ZFLqE3J$wHMY&Gp@g^c%=PQ4K% zHE?94(2kJ-92Tfs98}8=%;*MqafqoD-xWW1cpeU&^Ke;H2ZZ~>b1=37@6F&QSsM)$ zRMq5U4cQ>&myscfA|_tz{zWV0_y+kGVw>|V59q`y00Gn$5F9KR6;;)av9JJe*V*5e z4Pt2g0DZsuYHI8qfTc~&qC;ELcHk`f{d-I~;{_t9Ywd3BW>0{O8C;`*e43FV7quZP zoCtM9Ucd#~WUwbQ_=M0#{|vMwCW^ZqAEjq?tc?G5L&i_WLKuZt=({FDLNE60@RPI) z&PY{6LZ)IstIZN?-FJ6ts*}A)BC=zsUDHM_sDD^V%I?eQ!X3&BkqVNRDvzCkw!igr zcKitbMH{4nRDDW@W@{LU;fn6P;kxhJiwKnZhzNKdW2s?h{P=Ca%BH6M?ahy071`$LBxI(dJ%xgMR!M> z=i`O2B7q)ppxO6b196FjJ>4RovQ1aDeY|?T=pACKLo0X+-TOHiKI)pi-np{&ob>6R zI20^Uj*WvuV(fhllj#)(HIz&u&%~z#$M0aS7CXYb;?x5a`{6NLXx9@>dmur%;$ed} z%T0TFw6lCB`*$8_aH7ib_bpio^wiPiHG6Iw;Whf>9eHC-gw9(oX z&`DvBu?t}7s>J>OKsWBMSGJ8)H$2b`@?SU0tc~HWsCImRE{>||0g$1PX+Dz0J)V%! zG}D3H*$*@yX$@jK8e9|zH>Pd-0eCv|(BecI&&a12g}y7zoI3`OqwxTrtQM0QQ;6E> zxb&E?XRo()+~?yrG!!FN^DhhjX5cUa_){a@?3i3<7Vs|2RJcX_!BIVyjhX&W^%wDJ z**!X zwGXv)8yj!9Za7`1hxUlz$xN$!@!BW1R`m4b}``p5lH?5 zY{V>x6@`Vgs{j)#H)Tad)yxbcko48FZ*;u9I*g}PItz!ry>_@Hdw~2Em9h^h#k7vn zRvtTHh;f|JQ+@_g4ydw|5*qJx%1g!u@i7dA2tVH0Z>@J~z}gaHyQrvOLbg~P80~>T znzeK?u2Y5ZWtntVdQx3=hl6kbRKgXKn$4378sHPKw~t+U z4~=|}o&Yr0cc^MyZORA8|6?ZOB1mX4`HP`#)~->>75%U2aUKm}p<};UCVwDS(L8vh3g{uV8=4cNRwmSR5Vzx%S`(vuC}CMwVSO z>Gq|O<;niVjvkbkm$xPs^{uFn^X_&;ATWjOOF1*y7{?mA^sXIHr_j*>@ZVYaeWRm_ zL_B7OelOcFE6>M`J~}%)zaw_PF~|z2$@agS6Wf1wQb7ce<_x?TiV^621e?yPC<`Rd zDSin^4IzZ`)8{8+i%g-@P}Jj2P|NBKSq*m%rLID#F;7=%>FP!PXv`8Pyj5oKhHNA8 z^3=Nn$8n2wxIz77FGZmkG+>}(bQCihx$Ng@{6H+gjq%ApkYDjUKFq3x0;xZ;XIH9m}Lz@z@i{n#Nv2!olC-!UT$*zHO=)6$dm4?I@thF`?NKMFL5Poj&!b4HOOyq>TwAVFTi3 zsZO`(?akP;?u*r0ZzoBO02nQ_fNaAUI`R7J&%z)YjR6Y__Z_l>6hg z=!2fz20yz$VO{qUhfAc%jg+2B_ zmx>zD=%}Hsy!)RAa$gC(l05&qLL^Y}?MkzN1C)X!fL5nU#SNQ6+sI0d?dGGF#6+kQ zM+ZHSjns}u(Lcr}AaqfX+rVCeuDM%KUC-jhQ(TSDNzZ%Lkkek9@F^nRpmh<_ts`4x zThW&WEM^zK>y8fJ2%nonLBTRxq$w}A;k6||L|ucl6(vlksp%3A<$cm0XUoUTR36(w zhV)-JDa}w>Sy`qjQU@QeT)WO555lRT{BH(zNj&+fXB{XKE6We(T3>^%re`Y3%0OLb zi+cTIO@@+_;Dlfeu{CVmm9EY1MqWCPQZ-MpQT4`4B;G05KM!VrtkJ^Z)cx+M3sb{+ z*PO^EWQt-}Hu>_+`=2=o`H&xMxM5XfyUCP1CDK49QDRnj3RKMA=8=24O9G?pTpNBpLml^+-ToOPdcEZg$@feH&w$$RnP@oDI~DRjvGmFE zbJngeo42RPRclsg}li9E{OCUiS`-L*bMj_7Q;+;T00NvZSS%jD;c2!%joPOx;Wa|Ig#| zZ&I1hWZ6!!&sTj%ne%@0ynQ?S>pG!XB@yHPWL2v}h-FUEGspT@n!)WweUF`Y$KSC& zglh>2%^Bv+L|dErgyojY17bS@CG}BNd0B;~rZ9Rm!cFRDlkpNqW^;SQ#8JO=b#!_k zTaH;qsN*G^+w%fKY0}b`)6qV#aZl5Y;61~R())|yMQ{2jgivV*&)Rt-w0>>Dn=0B!;KoO9L9Ahe{~nM3fOTL zSZB0qVlLKwk=aF3usF34x{?#xKWoQ`pIXOtwK%2l9@oQx@;vClW*B5A?LiOWZqCk) zb<|5rE!^DPLj`!WpE+*r9|1X29){_{Qzqm&JlgY&bBpO^rxq4;6F-}A)2qrhm`1_F zR(^gB+EA%Jf_WqzGHth)Y8*0O#uxkmmUGSCFy{FtB=vTM_Pr%5ef&VeU1M4fi`+9{ zO{md@)lDWGsq#Etw+kyBo|ghRnF5!_f0;Fs&OH^;f7Ic8R*cC0>6E{nHMyo1N`r^{ z$$ppU)IvX-`kvH#T*2)794Aq$n8(VBY-f>B$7YPAmd3IUBsBU@5_8OtdOsV1+OWM% zBZ-qdujAi$yCaUDb~LM%q%=RIF4wJ}iDMD=0TgOC?&k-NS0k=CF@BF} z1y0HE`E@5wBu!UK3zH2hi)WbRe2|WSx9_vwriv_e+Uv03;@s!2Z;O1bXop9`PRi}P z_c26*R~N@RiWM-FYBeRe2AlsVaI`E-N=RUF^6Z}SvdeSxfX5}g@7?uDarDb;y(;rV z-dNIlp6!3gCLp8D)j4KKbUU@tRSqseNeI7$WqeIW0+yh>Zp6eQRd*NDn3Z(|d>tLM z6$b4clmT*xR=>fS`deE3R{6L=myh&SC{?le9Y67%l#10XrfU1_oblZj*s zpq&CztYRp)mQ{f}UTDC47ru`Gj^y`X_0F{NHq%3+#Kn}8AlW1%|ACU zn~NKylChnVkRLdq`QR1Cox(WrT`ZIG0%wLn^c~czwrYBOJX7&Qa(I0aFimJ<^Rr`O zXlRGq`sa`p0r`k@6fok}4bXuNloLi0O*lMGR=c6m^Z;)v#}yeNOLDpsf0q6YZUNAe zRUi9|!c)b?rLIZqxcWPeaCP6}Fa?zcM~;c!VUpbPZ8l#LAy zFBRbZ)KNj?FyVDK-QsR?mN4Ff=G7COTUe+lbH7sMXv<@T&arRDNX}Jhpoy(t2pK(J zm-e`_Z_s+TJNe7U!Q%R0OOq$Y*X6E@6)Pp1h=fGVZWNeKs&j>%F_Z$cIVjLl?P+gq zQOw95+a54}QCvLNDGu7-O9P17+uU~FzpZc$4cGTth)KYHXiMLLC>NV9fG=Rco_>_P zx$P7ojMTM0>Z%mpGt+zOk)3KKN zRrx$yvBbjCwJd5DN8_5N@tCn0&8zufrM#*hicPAxLaI@6Fi=K>34YpR*6X|TFOO$& z?tEv+yvy$E1<3}m@I9rRK_16o$>P?Hvo%4K1QM8nC>>Q= zptmd_<%u6QX|8$pJu;r7EGDq0z-Q^rq=@n36|sN(%U!R~rlHg(#V8kWYq=9;8pAYt zv7XIH2jSF#7BPFZpll{(9k*oLMz?)WPk;=AC?C}8L)G*IOulf_NC6w6!0Xg+VoTFA z?33@KkNzZ}3n<{E6xi>x`9o zWknlA@*aGc56l%vCWZXl($#L0I)J?3iumx*3V3<|cx+G4_C{kU8#lSQ#Mmbn@td~h zwXS=4y~6&`qWHZdOTE26P1b2m$`Q48$Sz-QICV(Ja{<$qDptcSlo{vhVq6YJ>fT-G zMnB&exZCx)t^Y}xBk?yRbf;eFgP@RoT4=aSLeY=@BfutmwllkN-kJ$27VvOuq=fb+ zShIGd;B#HDH?UIpPQ9dPe2k=0gt{hhq`t&49L4~)_6^D3xAY<`)HSZjP~_y$qQb&f z;Hx|io7ZW{M>YxlVR$l_)WdO1sBhPBM8Tcp5z`VX;h~<#4(V?APMgHoEKAWG2pl?Q zt6gaU7x&*rCE8bablJWh4|RGpl=Hq+r^~w4$satl-;(eNoeXYiUWB+ zZe|(*UBD>b=~9rFwXvKXHJGjg`Zj^a=hKtA=+*aVpieM`J7^bmQpfBI*@P zgPS$80u>Pby?$2zS`l*cKQ$dnv?lB>s1K5w=Gx6X)5XED`L(tX=4x?Q!Ge-Js4>Y7 z5j{K&iwW9QxN9_;VJL4RUYo~1FfX^Kay54Hsnx>>I&WKe_;T}sB=lZnE`IHI*Y215 z`&+sGgg}6>I66AoNZh`EIH8B#lEoOR5~SfNZ(-#1*89FiuN-+h!j9O8Bar01W34FK zej@@P+v14;zNWZbvNa+HOETk}z}Ib=50-M<#OWI<)ci~v(MzF_W$4`+fnci8T=rq1m~>d^&GmJ1 zBt2S#xV@2awvTo*fW*|btz66eU;E)y&ue4GKKnqb6v+tK`QI=V8 zR5^;o?J3J7I&Tu2n=W1%uSK})GP&-CoI%^}5ig01x6A_5643Y`!5yK_386)DyM$p8 z$0Y9s;zxq#6e+()Pb4yG0*?yWfI6_B0B#_%x`~ceAF!gPSly`@yLW_9A143e8%azR zSI?~7$9?0l!>6K*@wL@_{yVd%`tVfNki~&5W7h+VhK43z3he3+HHWY8bomK2b!W0=w5oki2{ZJ-59 z!7WIQ(+Q|@BP*2lL1Hqgr5H(7JxoU{BS0KFCA1M zr%W7Ci}6E^1Bn&~BhE@7`BBJbJ3{9GGP7!t>ZVY+qtQO_`hyY17PPP*?$WL$G8*rE zAZ%wa{mPM&=F>Q# z7gcL<4|kfzL1^R2_R^;sVQA0ekV*$qRxsp@@MCiU|KBpg-n_x3R8 zayMZmPsWqE2U0ia&eG<-CN(LJ4=; zv5>yCi6Ao?#^ur^HQ7NB(XLBPrIGkWA|x98?B5oDr8j1ZrmS_A#rW}u1F4W>G>ocM za>{INF1hYWc@LJf3;{cpL5hn|U^dZ_-zPkEE-@u(T~xNI`Yl|q^i`BlPgU=3X^RHm zaBH0YyRgvcv%LE`A7g%AJR|5#qoW)Kqs_qq7jGi<-e)TxtXl#(4%g}VH-L)5EXK!l z6gW8)`rU%&54o6^TWOO^df)zOkeYmBChvSvW+$mu;0Kmke$s?ocw2Q7;25gyjRWs0 z19I||Uu2B9J*neG%-rQI6!N_y8QgIc40d>L2Xqt}~N28NQ8snh2G;R)j<3kHD) zA|N&${f=|Muj;0mnIzz2i0+$X(e#umC7#&i4AN^UJ?ByFks+$Yt%x&CZM>@sOJALU z8Zo`krf5&)qMR@88{KQJCo0Xa&96}3+u4a6PCzX~GUZ83OH12S*%?HoL!+&wZG0SC zAUpb?Gpdl-mk=mVW4s}q#!1K#lo+WIozpS4b$t%_E*1W+J0CJO-%@76Iha`{zWM8w zf!Y6<`vQN2b3G(#LN^32px8-g^Az`M=lQYBxMvez~VpaCPN+F7Ah(IHy)p0YfOb$-H!&&KFsDoc~?0xhR)afEb3D z6fV7ol)+zSLPw~oqABs=>VYcJD3gYRROEG{qN)ing1L?vpYs{ipX-lC`Tw7}Wi)@2 z#B!_L*ZQPLzsRo#o6x-8MqS3wTr?PysmUHnFyT$pRNnHRbG!jNr#Q?jV4nB}{ar%Y zuqv3w##1N;{?LN6Q5BmWN@QSFmFdQrF`UK4x=oWiiCFl!hxHiF(8|s`t#Q4gNXDRV* zZr}8>UJ&4>dTm_b?dMdF7naKy0CD2OX6|`A1Q9By80V1)#u=}@$dfQ-hEOsDCeF(X z7N!#u52U#|qPG((N?lNpj88cOGKyxgMO82YKCIxduEZ$Io)Tg8!O z=B6|WM8e|aaBP3ihmitH&PS(-$-HLnCo)Z|z9yP4n3la8rB z94H#8KXWj;Bq(BKRM?-4kbi@!IE(~in2X%2wH>{^g}WvU5_p|QI2BspZJ+k{H#9dl zH1kt}A6uh}VnP!XadGCj($D?^kJt^t0$xNhX@T-6t;^E){1gBdYzK^)fAgQQ;vO8) zTD-W}9us*S0q)c8?wI%|hBzg0dvO6@Gk!zyC(9JNu@DXeR8_~SbZAmgwH5iIkJXaB zx>R=-%3ewK!n}COxISG?oWl z3&w?}Y>4A!sXieg;oovn!QsTH%uExmL=t1@j5%G8hx$ArxZ~)P&!z3@P3!e&wcz*A zow$*7R{Vz6OD2{IR{83BR;D6A&AHPh3N0E63cM|$Z3g;)v6k)kOc>dbxG2@DV0h7t zMr8+_1qcf{&^J(eeW>53MoHk!UDAAz*jCAH11@Lr_$UzXQ7SjPja; za-V5iU*gt|TG7tHa-<214o&27bgW?TwD$XbI6WG`7UMfHZb zbiE#Pj7d?sF@&ArfyIkcK24zRs%t#ldw5!t=J_0$0^(+wlrHgfDq5vTKEQ@|!{xead-xxe*$x!eaW&(fmoQ<2iAOk<>_cL$~8_{21rE3@zzRyF%IF z)-XI}iHoYsY`kmd`*!Oq*3xn1Z$F;G`mTWCP%3XAFVr9`UObgY!Ic=gqtNjOY{jNI zNZ@}iv1iCn$C|Gi(fjH*^=_lfaxpulCBz1H0Tspv7Se5qi@WYPl9_~m+q&Y{J3649 zbzq3)_5e(q<4iXjPCUl&8e2($+3#Q36vO0cvj040#fD4C7wg2vX?rG*TW*L}m(6ZKLYG93< zO_piX`S9ppb6)f|WbM>DED(5`42QiI7wERhHqNK_=nj`!e>LPK44C``iZ~#UyM2bx zZHF3;xV;KH`7xb#%AwAks2rMPFZUW}K5m=?K}HN&gxVf^Gtzr}*V8roId4d^?NKXz za+~q@6c2;Q(6jXOJ$Y^RmA`-84Cd~_o6jnDKcti0Ap3vSEm5K3}$ZSy!&iZ)?%q5Uum-n`|UzF3gNnqcE?O* zeW^O_X`wz?cC)YVR)^l@Sjm>Uqpb4Es;iAxrf0&}Oo`0L6$4;3tKFvoWOp`rA*)lHP@CT9 zsutd65+nbdFbY1ZV(Po-q?C(}5=&13s>8jC@p@>6ZVW-7rLLtVFqfef7%S$oud1Bj z&KT!A2ZIb`4JTP+T>?+Ei%Tlw_pvv=aRywPUR?YPi=_=f%GCY+m}pHa^jn)uhp6C%xuK-SVM}P|6Z_V_Jg!_@ZPmAeB9EBf z-&N2|Bpbu{%hZ_Qbu;sJG`U0S0zJ#6a5&-FAJy>c^fyxE)9bT?`}K1Thk-2p!lT=? z3J66foJM^DP`=H>?%y@3n`a|l+wkp8yPk-j=fDL38i<9Hp+fWX^F}PeuHePk(N?;~ zC4tMUNDbcnAx=8%z^7dHp&~4J6)w9{+y{4A`oWm^t68q#O=({~SYqU?G0geKQ%=x?7H>XCiJL&{{7LXRrO=i6krnT$7l-Yob(c#ZOufSs4pZ5*YJ$7F|a z3*$Pf_K2>{BP_d9tW;_H_=koXalYPw<%OM|UR>@wPQR#ZZxHV9b#Ux!E7jYJWfc~H zVtd=BY1=LXyr!T*PL4Ax`Z5W1Qh%ykn7IAg1_z2tE7D>LwRd>aMfGe^wd_()e&5Ln zISh)8G_-AsD%a{A=PtKAI}#(nO?u-qPpckXZLHGwdP{hGcyZC$$*DR8mX?F&do`%N zHmd6w78(jxMYP^((qpcGsY5qCDB|d5ln3p7`j6}z|49Q#0eV02e@tCvR8?)T21O|; zK@boSq!EyoMw&x6lG4%*(uk5$0*CHCq;wxd0SN)=IFxiF-Ed#f@7~M${(Q@|&fa_W zyfe={^UUl&f9i`g%VgU@PPXTE#UF4tHLiU*qR+^;@vYQ$M-nR96470>Uq;Uhj+HN8jOTP0|U(QqM2zZ@q*Sv47dtrir6XSUt-g$1u!~G z5Vb$BdxXVa7(rA7FD8nj$5V|%7&cs@ClQEVoZQy0VH*j90Gf=P zd2rpK)$Ln}G_PE@)(hN!abvxk`yEknV)9W;Ju3$vGb1s;2;P#h*H^4I*jNg0eV>H4 zF+5JP_lH4{jg3;B+_y=y5b2%i{-di_)SZSMCg_Tlc?)g40OW~uo9*);ZxH?_VkFKX zW}s;I-5aKJ9Kjj%SOcLiq$w9)PF#^oz_f9d?q^=0XNVOli7lK~AJ`L%$6$X_Iq5Mg z-HApq(;^^)i5{XKe#4;3IB;b#_uTCddaNoc1(ak+NCE(ORO?cCT%Fo==e|i%y2CDB z)x%bt0~b_NK!MK;EWrmQSp^%N&uY}xR##&gk@P2gF(Sgx ztgq|0dO|Wmna&EQ=&ZN1L|LBoRo~VZJdDX7&Xeq{)J*%r|D#P7xT5P1#Lo~W1r>Y&ex+uFfL{7<99q&G; zmlhi7)Q)T>2BB2EgqbmucYt25Pp+7m_iWJ1 zyk|9MxeJ-k4G$+|VL6@33!!mcZel@>hhu?$qwgw>;s#8bO;T@scuX zwmdY&)%vw>nRcT29SwR0CdKM^W*=QHf_szlwEz-<9Lkpr#Z?Q_WIS-U@4D!{2FLv} z(AlegGE%#lsc{RL$8ll5hYP@>0!^0s?E7%ZPt+k(sIkGFu78-T!XE$iFC}zfazM2P z>S6?vL}kv4*}Hwpu?}^ZNZG@*^K>vAqF5p2h8$WWhMJh8LgMyb%HioN3lSO&Z1yv# zfF8j~-xcY5``!6J&msk8X5jihSs6FUDWKHH{BrYh2}^0>`^1@XkFmq$#MS%ho`D?j zT8ol2h;c4W^;vC5RV^FcB7>7iNyn_mUw~-yd8&Ww)1C&yqwI+ML$(?wLZ(p#aD;Vv z=jFAp#L<32cWPW}YCNs+>E&v#lvWb|ls2UB?AiN;b!XxkqL z=N{9*r?n@t*<8}Buq;Y)@CF{VH*%g%%q@=jK$nH$ioQ*jRh+)Exr%peCaF=8)1@$E z{>9fJ!B z>cfAuzhCso%0DSD=XZGe%IIh-zsHX7U=wUk%It`RU$yYqHPu(aERD_c-!cXa4WlI* z6vc+RXTIYL3GPc6lnE5utvi$bR)4Zee^a0Nu_~mV?e6#cR#sQH>&oSlW97rd#a9le zIJ8siEA&3?P?mCsO}(WlQ8gCllrLYNzsq?wNb1AnJ8O~UKjKyq@bI|vHwdX_Jzch& zw!gU?=5+*>o7b>H4^OB8Demp9n8;LJr-4qDd!T8D7SyUPP2$hN?Yi^M4Ha)|XO?yS z^87r!7Cjbxig1-)nX;H*a#OvNag$!=b5Mp7*CV1Do?qH@(WC)4oI9tll= zL9ZM~0?0@k>p@0!gwpe&=YgsmlZbFHIsS@?GH_1CQ}v)Sm*?dT^^Hx9P2dyIpE4%9 z({PPGAhz6nFj`{gdj_koVApNb@@Q$~K%^;mx!3Nu<2V$J`q=*Um#+qRH?)?;A4}<# zek~qFXFO7N8?=Y7k|pJ>zEC@8kRWoU*T2D(8+k|vPszgt#o_{|-394H4Sh4((|^tH z=lCiN8#My9=Y`oo_9P;PaKmisRlcIT%T>d+6y+JG`Npm zsm5|?DPnt^`(>GA#bq^RTkOAR@l@O%t#4@#`sMw&0<)xeNfIpy6=|^i`upqisayuV zu~?SKVRXjP`_Zzk$)krJz5BRRot;vHD7rT2S7z8v4kKz*S+}`gMQ?KYUvDhhsod#u z;;U5uI9uF!YUdHF&D*Op9=NSfjj!*uh>_nEOFL^i-}zDheGW^c@2$&aK*o-7YHBMPAfc6huU{7=Aa=UtbWhmz4CG9y|V6PZc-^ ze7d~;aTH~$o3d@=;VO?s{UCvZQ<6nVN5LP~GxWv?xquuwr7R~^4>fX(*Xt;~m;OAy z@^;r{61&!3C8svQ1-nNr@r-!R(+9_wa$`Ie+Mn`>HS5A8G(nvV8a)$J+|bT;Lwoi3 zmr-*>b&vf$P4}4^6?cScFQ42KJ~zwjh^@JPbr)~C!Q0b3bHM&IGborI3Mt9SQ&}RT zskjgKc)Ve>xj+^EmZv$h@ButC`=;HC^geVMH)X7~=w2!zXKL{FhOTqKR9ImB8nk$5 zf4F|PZ`I`#-SEQq=ZK3rA}y}F{8Yy!eG?k0uI3o}%UW_0KH5zb0ThG^ z8`MLs5JgI`S^t5)j07t1=e&*dwX@(fUobk|MWndOyJjlAGWhADkznAmlW5e%rDw$d zq*pk!ca~iw96W_`shGT3H)~=z`@5k{M?*P)opZ9>e z4xLB+4jIjj!O`Sh6ah$di+vvEaF!6u8_h2N3ZIx}1+Fqp=SeEONyvK0b1lZn4;j>& zo&45iYw5HVniexNeo9>jIG@FbBK4s@X^&zQ3|d@mPCu6AM_N~N6=(3sl-Zmjaw6adLJH15vvw+u8>*J|TGzGCd`>OSujmcyLCHoQn^9bGS`jfUwrs;Ifv@Y6fa8Q zA9DsV`U9B`Sd2*CI7xjjnys-Yi*(te@Tm( zxmg=ixV*gj4%60vmOHCM>S&ai4_lh$)830gITE~7rNFr-aZK`xIzB&VCzFapsv-K@ zn3U8<>4vtt|E~td!vZO)<#_G*Ed3MSfYx*u{K@`s!k@y$O@y8vT^8u!sWC#U0=>a5 z<-1ra_j2~sAzPJ|(`(L7w9nv6W#v~Zi)p34u|4iK_b0I7_iED{Yio)Ax?e%u@83>< zNhv8|UN%agYsFe?`s9cxNyS{tEV)0Z%}JG2LLmHYQGMu<;*Ep0EHiOrW3#HR&iI}9*1rNB^lDfkZd z^d9yH#O^kB{bKr+b<4Y@r8Hj_{rU{7Z50x%E5`_iL{0G`!(0-*F+D>m3xs*PpzCkZ zN(*cji?hC$-KVIh7s4KP_hG`TXtu(~tshX2x2KCD_Wn6*ChQD1g(QkHi`63ToE5RD zB4}}#!}YKlZ~r(~eJI+=siWsi_v*I`>7uaEULMqVdNj(b@>w~Vzf=7x28dJw+y;m= zX#fwVyEeO)P)~#2I$W0-rQ<3`vms#g22*DP{%W6%Aj^4yB#^>(mudWkB^==+wi>YL zI$R=-ZF=Z1a{sg_1^@Gy{Y2(FU9xPZQJao*Sjt?4eg!Ra5h^raXBw za4t!va?4Lwb5ik@R$VRUmDyWcTZ`A`yqvK0yx=0%_=A+)Jy=@H8}HNHG;b+`3!(UY zlb^%n2FcU7PevKv8!YxSmkq9MsL*H=x+za<246-6*R&gXr+99u);Tm7*fPqn(F}2j zizmuSu8ZfWFjP+vyoNr2hwN6xb;(#(9ZY{z?vvn$2^eC-$pqdhojrZ{4<}>gD_owO zuCy>8?9Zp=HtRY`S7aCI&%1H&8JWOM(t*g`0 zG$%%}vbCkm>fiA)WAVtkUlF`o%KkcUn}LqX1*s%Qki@DcPegL-{)8G!&|F?VM@dPK z8|U&E@>Ee3jDV|SGx@jTTDx~FZrM&~yO$lKsbY72bfPh&rc(3SvuB>i+gzIBS}@u( zNV+-u67$Nov9;#&Jlc?t4_0_We#Wye>^?J17FT738w{&M{^f=0u&|4UvK@5T$;JL` z64Qnmst@1k4*5JI@SynweC`Y-XK|M-@P75ReLQSsCS8W>ysXW;WN4fMZJ0zmzQ_L z8M}$9?dXfIt5=20QFdGPAgOmL8)M&#Fh%59x^_a zahH-Zug7Pg{H=SHEILwBkf&09Is2pXb++N}b6njT0|my*zD!BHJ?FQU1%@gSSbAVvay*t-7sD-2m@%10YbvfD+nfH6wJ~g|$OZ^i3AM1S$MM5fW zZ26l`cXf=4(?&xo$a11o%Ej57F>*dtPAm1IZh2+?*EK-`CwXSwFHUZ_8YJZxfUKz( zKLG9#EBl^!upW&#QIQ2vFmbIaEEQX6`xQ<8_?dy$*a)+xRZ!2f@sWG$gEIC*Lvfxe zfFWZa_jMo3%DyO2BbI*fxU40$hnU~PO8{LVoZ)g*SdV1F1teeaNl+CUC`1N2=|WFF z8!t_O$T+ZYI|k;XOG;|{4zNyc(^5er=W7b%8X$U`kN<#*Q^-d1*Abp#07p>2q^{#R z&EjmL4V*iA8wR$gz_NAV^u*$Y?eJ(k{v>sl>=MdUgNh^QWH6aw&$G~V!8L$h3Nr3~ z6oJQ-={4@tz?IW@xJW>NfQlQVAQA=zy)FKfn5al@i3ht(tCTMX`$bQ#;<2ZscbT!4 z=`#yw+Vf@=xMol3UR1!yXdb|CYBdq(6u!d+(B8>4VmvHRLyskiS{v4KTRl#5s-(Fi zIIzP6!)$K`ijW*~1D(uPDe<)fn|)RB;ei1Lb)=Ml-2m?}vKU!p=`EfT+Onw54B^3F*{^s&e&xR>)TDCVeyxN1l zs6Jm9(=lYUwJ2Dt#iCL-lslVZF>P{zBXDlGat8Ebn)WV;*FFX2TWf|u%W7-gF8iNb zjoY@_CQx7qVYg0n#I`YQo0mySO6G(*Q|n?m;43+qW&%-E#v&t4)n~S)yMY6M}za|AGCTG>-daDqsS5eI7&jLc5m)m@+h*BCbVD-CtCpC-CymF4 zhxglAdq$+!_ugUpejEWpBsDa8*r!1$Nug*)q_lVEVPVC+?mhIyTbs$PPc#_q&`QTQ z5e4xH(HVhI%eQ*Rm?0mO-b+DN$iO zOi)9%e>00+zzpDCE~I>d=hfu69w5WY69(0Zun3?Y5yl5&F2`&~mfqgwt}221pvO^X zL5FU0ye;!+#S~HF{dJBHvOY&@D10Lr5wV#U$cd07034P=imq$XFG35JgJ>hlBPfI% z$(*nk9&J*xkdyqImzhP>u>B6iY*3p9Nm18Zax?`LosM1IP36e~*sZ*6vAU)4aRpl; z^g+nTl1Rihb&DnKvr(TxH8&NJ6ihH2J1!rqfiJ#eFBh#RklyuRTsrwhe`iTDIaR6D>y|c+S6O#BZpibs0Cg{UWad4cV zUNb_o#R8%gX+FG>pobccPDm-#{@ygl;vzC(P2TDKK*aa}kQvY~JJ`b@65Bjwd#Y|N zL)xf^-TLSg1C-~)Oli!8E@ptQo9$P?RLSVhA@=(+`pp%MACGR15)#!0s_=W_hb7@)vAi<&rT?tg2n*-ws7V_$MEsCU{x$)QQS=vB%J|Km{w(?XafJV~7xON{` z*QfSL&H1PIBg@VzG!|rsUT1}68`yl{z%=rI&WvQMu6;E1pLZe^KLsiFJUlICRN)8a zr#SzGo9l_6LE76wG(Kx6#xl9l)xOdz`lvTO7wz3L_ugn`Ts}g~-ck;>fV1HZW)Up= zv$QuFzCWO^o^GU5x6Vf!iImOwU{_Na^f&GeH$3&FCwBRb(<;N9Q%%BO#wnB}jlc)V zn0h+W>lKT{2Q>Qj5W?W?m~B~+uICk2(5IGJ=OY_|eCMuD9YhLao#UK%#O!OB8hXiS zf({2+a)&HnD$p;3{~HS2MY`O_s?U-sLVt`L|EM`$#6(<9S@wX9Ux57#ywSljz9$(x z4RiTmnX*b;(x)4eG>osQweo zD}0yg%~40}Um4DjNWoVe@7m?6=ayiYE4F)bL+hPOcG_P}2i&V(z`w)A;li7avn{CH z=sDhhqrpI8`r6r9w)AiSaFePm_beh}s~!&E5vmzjTr6YNFDe_Ws=9y)sQ)r+;n&KD*l}n4c-;N#^=R8mOgoTdn}3?v!)j|BKBMyH+tie z-Feo&2((o7{Y;=Je9wxQ(*mXkI2RiF*QLH@u|pK=j|E z(H)X3-m8(eFGOgv=b-_;B_EfhxLe4qW~pJoutju1iMq-*0p&x{vj(#3^*Y_c1lCHs zz{-?l1Tk=a@c6#jPh9I2>z(0p#uI_i?qol3PknYC?m&T1X;3eG4m}55d-~Bg80M62 zY`vo`WdtXD1d&B0ESoF0u!+7OrYfuvGys8X8r&5L>RAI-r6u<03TA9+^UQfJU5H_2I&#A_wBfD@a?-G zz_Sr}o9Mm&nM8xp_>O{e>`y4@z@N&q%6ilAAm`4pzp^dZAw6=s(Q_fGQB_gaDQ{%i zQcY%;yHint8@kS$&FvEIiHtou+$b8Uy)yq|O7* zBR}~c;=Q?K=D$JaO#p~5r3vTVj=9`M{r7%pCOI{&{h?lj50ZzI8M^egnMt=~tdudx z^Z9~qLToEM6W1GY>Izfo+DryHD%E7uD&!-HD&)x*3&vAv8$-9LVo;_vA0p=hKHwIa@SkN}5Qf?c+isO>pm)!GH`hPW_nmivIfm#( zGnxWY{`kdc`*_QGd^RUl9yOOKXcj%H&>PzlDsCfPdK~{}WXfDB|0>JoD1HxLoWNED zmh

>GnC3_8UZ@GL}>^C;JKLVg)_fub)v5#as+fj@wMk_fG8X$iVA8sEPzB1^ZOP=P= zeOj>55F=ANOTUK|_m~LJo9lQYed_!?-~39WkhIUFQXRaYzMsLGpe-hn_ch)|is4tF zrj%5W+AF!+j-f^kF6dRqa*3>WnZ_?pLxgZzPhF5wasZKbG6Rf6L**f5;1xrJMPH5L z`ix=;$Oll_4^SUrtUIwObqU7`S4M)4aIWYv8G=bR|65`L5Ax|Z?&3wqJ1lIbyl6Y8 zr~8Wi7dGtYA@2%IcM{TjZvtDuAB2o(<>3zf9Rqb@FR{OOLN20C>>oqDc?N;wwBBp| zapRuNZ6x9%Yv*1wPn3X+HQ>G#^lReO6Z9Wv=_T>9`kPnpX`i+<^oxQ^l7%K6^&dMS~>u z%A4iBl>Ej?ostZ$VD_rOXBbN=^ZPj;u4<>xsQDZwNl?%^A zZK*74&-++xMDpiQXFFMLy#owdpgE&$mwt*3PY~lR`v|=t^T+HvlixeTJI+a+qKp0X zv_SPEvho-sm{A!dt!*@bR&&9exTMRlwm?3Qu z{IiCY>0c%kt2PM|`5*(YJEvV0vHeR%I1jb>W~DG`KtcEOws!jZ;kzqZU;LNBfN$#>IZiHU3X5)xJUZh`Bp*BS@@|rvI#F2a6jg@WG#k%{Dh>3niI-zevG6RX2>4xnc2s^B33Q7LF}QK8G+XDR}FOi>za zRZ=1Y+OVj5f?fw)0wYh=y`~0jii0(bA&BdY_rcL&pb4Ej6QspThJtXJZvO_M%E)1% zewc-?#F!_wMz8$mynZA>g*N8z0eEu{^F%7HdVLs1kxWrjQ*&@A_*+)13*RL>s-*|& z|AL3#^K#y<)aT;;g*cuk=Q39Y=qY?Dk-jRrL7HhNM~Os9@bsfZinF?0ph99IRDB3) zS*zG);a24vthx8wP5eNV$`B=1Z2(}IB=&-2t`hb7!dE*hw2cXaVD3Wg7J9zJEg)@V z%6FA}+;zPf-;~|so!cGHG)>&h5`Xb@Qs&vt_0;7KC~ZO#;p_m+8`exvRcJ7rG>Xwn zNf;#lR;6nJX3%@S@a%QA1&)p<&wG~3axA9AGBFC{ve7XjD>@0@jA83D&yq%8-${}a z3`5~s5>+ayf6=nA)3tuEH1s>E~eCK&&a!Q#CvBOm(Nu%G#N1l4hnEl6y@$vBm7etopm1~u|KEz86 z(dX;ZKwO^h$#}Nnz(4EB$xMfVeT3i-nm{$P%+_lUMnne^PBlX)>mXTzK8eYxWG(LB zy;)`6DSWaUn-_PM>6iFz_gluQsJHlm-`ti}cwY;22jtVfzoxt+h>hWTN;tUR8E=q+khk~=ksNt>E- zQ)PkDWH3)l%7tudIMZQM2d_2_E=L8<-7!t`vr12$_Fn3?b8|^dGoW3bjxb*u)f%n> zfL7l^OP3_EkDz0gJ>}WIK=5?m8#EY^?N7O87mLW3ipYCwy#;5F4yVq1WtM7Uf>(K& zw_WIJOQKtTSrPs$3I;R}8paVv|BLI=rZes7h($?UordtsDU;ePezqvwvXmv=kI*ph zK_GF1ytvnsB2nj>^-#RA{v}WC`d;&OW*B&-r{qfPQ&cQlclAxZwK9Jjx@+9e zNQeS-g3`GX+b0l}mX5e|>;yD=o2L5M)5-A(3m@)o%zB%U>{(Fa z7w*-H{7nKGj89a!0SN-##8^UrKIqN$)_a45>l)UME}qrP`x^Tc0=m{Sgi8%vJ?6~n zRg9~PlwnCUJ3q>2r9MsLYLxO^guux%t}1(qa!0qvR4TD%ro5OK69d3S;CY+ioR~!2 zKHE1`R^>maf`sx)u>Pm_Xs0XMHgSnUVcnuVQi{8G^ne1%d6TkQg^l8V4N*9cJ+0(S zaObg~O2W-}3kIONOSCN+PvN)Mn-R3q<*?e4J1vbY*WB2sZ8zd@iX%{WGG0i+BDG}6 zpw1au>&?zyP8bX;Ri!_#x1qc>_n)~rfv;FUl znER_?m3H59N+XlbUK%wYu6UEk)JCMYNISDWPT)iy@;2jSPN7~g8VkZ>JpdZ4cEI82Elu7e|y z!cVh6?=?D|JEV6uTK1lbh|E^T2n$F%JcXlbd)>3l(<*m6dqZto6B6*n?3YKQS;g%C zDrk8#Ot>egcJxR2=Cp*fdbQ`H%Ait-*Ah!Wra6qHHxB)UZ(I_c z@F6*^Pt8Hojoz492^+^|dfoC};d>uTSS)}5mQ!_+3^GDX0v0wA!IX9EHS$H?EF8uk zxG0Dx8prm?O0u)RU%WUQZdrDg?Flbsf#l~l?1;-*fY=O}o{vpnGScYpOE65L>A_hR zBp!4pTB^|*lDQRoIKUnwT%##{_9MreiB8v9LxMJEf@;p|(}(8gz28aUWT&cyd6_?Y zTrQ8!5B*BW-yPXqEj^iM$07XOQ?_<%6Dm9CjL0dyhOAKlQ#;`+u{WrF_)y*aezxwU zNWLAWUIZlK@&R9ojX$hMy|{Th#qUm=bl+#l(8bHtnxw_aX$qmNgvmFPx137NOKj06 zx;gr$_XkZWvtPF_kt+K!?*19kkpOD#4d0p>T?RW@Hwt5wbK3oU_v1=CJxJ}Umr%O0 z@zbBEk_EMYS9uV{ZwNNZm)z}ATua~&gA~E zO~$_OCvxt3L=&-@49|4{sa)CJj|_0$me-{ck*qomHphhZK+o%R(>;>i$^?OiVnwA> zdiAE+rBR$Jo`(ggk&LZ|aQ#*iu)TnWOQ`L;xXeRgBSjzdu}wX{2?xuluhlb1rPst@iEC_A>8ie!UXRTKI9b1$K}i{pu!MM{5nDCP1ToHT z@=`dxzo@1AH6t|CXI}DBN3pi*FqkLpnVsaWcuRaDUBk6I*tgVH)3%fmXb8)ggMn}QJ9gG(z zZl$X1u5~Wje@oog+!34eZa~lbv~eV{SU{2vtCg2^kv5BCqPXFe%%jVz&ya?bk|arS z(B}L+ElQJee#>7dF*|76KI^KrEY{qDxNMw#T|K3eq^v=9@0A|d<$v>MwsxSUs939e*hS#*Y&qs> zC_ZyEt?k!tTSob4ADxvB@q|A#%tx7n)_af#Nx&+t68tiJ;R;dMP59PCagDRTz$k04 z;gTqlZYaL8`Y0op@Pyn>kAzN{@NNU=`7)HVMp8U}|MYrjfildyn=nV&st_EJ7De~u z%aD(g*6gu7I~qDxP*5LKm6|(y=kI>0pSZBb{i1YRux30UBO?tAS~6N{`=!zJ;-#@~ zlP{FAQF`-&fAiX8kMl%nK7rk4Nt`FXOS?Zel6G`(J*rb zWH)KRzA;ZPKN<+Ey|QLQum*idF`pfdS)exO-RWNG6^teCXn0JzbWx~>=ya#7rTeT` zl%qiQP`QJX`(_XtsF=fSaHKJidsizO zV`udfl+z(CyRK^8v!p}8-cI>m>%TZPEk7aLff?>5B^!(5-DjKoraN| zuufF>aE5v}_@CK=qLkU8L(hgQFs-_M6Qrh}FS^Ecnf%1bu74rjd}15) zdN*##tv_$rw*y|{(RFJIXt;{@%OvIjeyLta**3C6-w4a5jb*Jq*ey1!W!V}guZZ+p z%aT#uv?N+~FmAhN(sW-8wT3AR40Ke`K_j9+B}7*xFsSA*0akVamTp=}k-!Hb?&~+H zgoicB%gISYXJ+(aDta|U*A>%>0bm+rF}mzOk68c7U$`Qj->ty_>)Y7#9(84g|7iG* z7V%4KU(+Xx|!i%$kS5IZo0V%8TqNl zeJlG}zRm*4T$A*0l-LJr&f0}wX_qu~y`uTVZpCqZ(D~K{{4j1cJr5_B9&3Q4`K;Ks zk&p;E7h_0;5`V{PEo}l~7_aCjt#w5$kRoVZh^nC1Vq*mcN7YUjVTw7S%!rAi3S&rG z%F@&-MRRHoF!?10J@Ih$)cRxwBctms;CSW!e6Y}|wS_Wj{XLwxWIoJ^N1P~hcOc?w zI>4wU%XZ%yB4+ zgw0CT;*(O6eBII@F7JmUqS-vv_2s&lDBR3ytEv(x^qbxdTqs3Da)#B;~r$ zyyPRo2S!W8IjcRYcjI1t6}_b*{DO=28(VHx77b`6Gl&jIg2{0a@%RH>=KHZvzI+?B z^(*{hpiPK(q|-1PZ%Mcw`qucUF#6H-ptNSkSvFV}6Tz%glfd*UO2O&LlP7YyD$D8+ zb%UZDeJ{p}bi|8+Ve0r>|CxJb=kYm&wKrA zMOpq>UAWJCUaD}8F(&fbt<{iuahR1chA_xH)9ct_$QiQO|L*5?b-DtEgW9VhHADv5 z5v8R%7zF>llOSiu*BM1@Ih1utGhJKHhjpH3MMNmnqu|ttv_vs2xyaVqsAlgaM3Xu> zfySVnNsiNNUU9Q_^!(U9&&>q6VW< z)M@BRXm%X^F%AYPlmxCssmdjXMiW%Hv%Ae&%FEec^Q;y}B?)TXgMpagTkV=<(IyS` zuUSqpFrl}gl#F7w!eL=VJY;sr0L=Z}v@MD< zH<)zkD|=3xoJI6UB7J&H*d1@P36f}Sw5I?PPQpp}I2P{?#mtBEH=U4oZEJsdU6DiQ+draFC zXNJz((ad=8+7Zhk`f8IYG(H{JhWWar_*k$!ce1rqgJ(64OzL&pD~QWh>Mf&}!C-W5 z+nnTwCY9n{7Wq$Ecpm?!g9mc7<)Gh6+aD-J=hthp{YDwxX_`sf zf%QMwElSCS$Vov?l1M$Bi`Z-8y) zGx5^6146sbndK7VZb5-HTjQ?+h7~hxNYuMN+0oLphz17ytv1woB$}9$oY<<($QSHz zu^gxhN405CS!$h$bntAN^xfsUV#>?Q!BOrUp$hXEa$M+|bjcE3u-KjC%BIrhko?Xh zGkn%X*X!m|G4h`lAUvEjy!NTKra{Y;3uD#Sw%68{qcH1j)LE1TZ$h(TRnIH#rt-f) z=4r*Sx5#u`;EQid5o{7~aTn|ql^%@Yej}pGlHH6RR=Y)Y@FaPfc%25f2`;Ws8q@B| zyr{A+twxUDbxG24a&o%QuXsEvR&r`=tU1mDlr2(E1>ip3j$XO~oP0c4$ke8(&r!$S zH~D~y;lau_>y@)prS5If?T3oaE(EeL&y zCt+U_-SAvjPpE{}G-smd!q%OjD0-r{OY}z@Zx07Q|Aw9F+I;(`n-Q}L9R)MQrq268 z`ovxZ2c|=6e&fzkt+6%OyNjEhT+Y8MrWUEdZ6H zJ#EO|j6mR|_mtv4B2nZwW*bmuXB2maIw5T4so+%{gow6r^&tvM?oX(h+1X-+FLfnv z51?O?8UCgA>z7hd%nflumotzi(~_azn})E5Bli~Gm9BDo(3Fhs@)#q# zvaLCL*xD+T25xsrT~28MRJ2Pq>H0bgXU~0i&z9vF{O9}pc}kZVKuGcX?h65c_qO@e z4yfm3AfPY)K@f;>n!$H_b+O$cQzXl;dd+P%u*kf8wj*SP#U@39*r}Vs2}p?shoJ^+ zxg($wk$myP&_)S2v=_eX5(h^Fjir0=Ri~(7#BQ}4^aZ~b#wZ(Q-Rh0@aC-mkU!r`= z=;}zUMql+s#j0qDz|JqXzZnE-5K8y)LBcaJn;9$t)s2fVkNOkU!e8U#3Az~5#{5E` zWqs_Oc5OmtQXKsCyS{2p{6lh2=Lr|@yyJjeIMHlJRU!PaaXIr9`CT3`Kj{PYCqOp2 zjz+47Nuux$Eh%ON5vMqX{3VswPq>l6C_NaI>-e4?UdAIx94pizpyw5YKkJX_W%xG$ ziNwm|rROgp-v6N`L3)bRQ+pXdPNUkKWL@J-R3Jm#v-t=QZ#R3YY@*hrUQCCwSRJCv z54x$Q+uj2Q)HE?AmS*{)jj<6A>pw9NH}fu_G`~0;S5y2% z{N{!D6I}(z^!w|LlzBVI1rOq`I^Gc3uSC<_3J!)buOwBc+Q%a>$rb%}G zIX4Glg2~qyVrFWc5FyGhMuy7tVG@j>mg;*!ca>v2oT&ahYI{TSHzN3v>idXd7`~0h zoC{agMtLetBXm4mJwe%6zmvBW`j$sN9D~?Aj=0J84x{HC1)KYgZ0zh*>cb8%$^dCC zKvVNzD8N8{hLshNgZBn%ZzC(x?8v>Cir1~|<0DuDZ!AW2!7K(&kA5_g&d&_ADf7TL#yh ziSg~PmaT>}U&J%c_A@_z&+6b$?w(HN3?B2p<3uxw80(}Fo~q>*7bUUz^VZ>qr;|Yg zi$0-SQ#|5;XHQ2&t7$e+^c{o~T3EbYr3S{-5FG&*dIQYda-`;QA*Lcm%~hI|ieF(? z&~7t?vLl5myTUKk2_F=uoTI*f;oxfwXeu}^y|1oYX!iOpxnKx4G_KiNlRkv{6!g@Z z^|n4Im&v#5p+Um$NxcRhd+|bPaGSbykfeaW<-+4td7dOL8_n9!id&l`do$5OAzd^? zUQfI@{$B{wW@94Cl31rF{!8;OS(+4MGwp%pg$(g?$h1FXZgrWqH$sF5iklpWglILq zi*N>I!|zqBK%K&r%zD=V4#exGD<nS+K6hbnJNlZmGrCG_# z{&o*t_M(z#&x-R}Ya2SWyqmUFsNjq&I40;E28o{;Q-wFI^*6F|)pCfA9;wpyDf z?@+6ytDinPa+*EiQBA%E-tKaGP=vW{`BZC-q%ANV(?N+(PDpQFB9Ex*1lX=#*)J;r1H$=aFg zkEI)FRh$~k79N~X%AbDswM@f*b&+LfluQ1@fI5=~YHqg?!+ez-X`;_~TLTFmHdcB_ zIsweKYu|vPiGZ)=R#x=wIz$iaRqXAEc(78rXm__*{YB(a*IE zrc^&;_}zA_C+lQN@0%T6Sq~M`?w(zIYa$$)a&CjC_1GzP+AT-nfk92z!D0)_#?bxy zrDF~X;-A8*OD)0Ahab+1hRu?tCsul$aNCsYW^HCQ`8FqL32;00@9F3@U0heXt*|*R zucVHr9~WeAly38#(I455f8QPm3*=yzk>%if?r1WkZ^|8k$J(@8x{3CgvXfmyi zOcWOGUACvx3e+W7R^_jmj*Re3?jbJ}bJPS@nb??EnQ=Z*ar#q0DWTz3*-+THeJ;57 z1EF_0y5qg!GrL~6y@Se}F_T}I+-p=RdAPJM(4w25dTm<$v!i4+Q`up-LJS}ntW}*0%^jlKAk(V<&*R3B6sI!<+ zd46-}no7`6*_ju_KI*`LVzhr_Sf^mLv8ikUUFB>rIrd$HKh>t3!n}xzqKD^5N_Ez}R!&uV7q;t8$`h&v%W2ikjAbw4bo4`)pG7?yj|Y-AR5G+UfDR9StT zT81x%M-F{o9V2iOqoOif%sx@@Xs`1l*T!!MklH;+lr!`8)-%{W_u#S@%%<<)&gI8; zSmdV3rjjy|fS8(Glsv+?m-jbUz90}fRu}p~n2*sh`-bGf0qynPR*!X;rFQ;LQPFwy% zm{c-F7rS&{d}=wb+<~9*9@%n)bW$O)0mwhjq)R)p(E zF0FnTGIvVaC51m$6xc;kmC5H1}~7dR3-smTKuVE##WPBE6O9y5V781E|_h1mC3GeXLS=dYgUV8NS@d%Jm9%;D$jE94i)mn#}u`UAZw zugyk0*3cEdvOQ!%uNgKKK28Wx!HMJaTKf;5`OylDlX@XxCSLsX9-5f3G-*5vUA5Eg z!yQ-`cB+hgVQi2bE$M6a`g5gYvvV!_%O3ODFwcOn#-L47ub~$cDP&LdRjTtgl6;Q^_SaSkSapG&z`_&rfdn#wt0w z#&A+dkaq6*kIi-3@7lS+)_cj-U*ut_z3ML`imgs8zyB*Sh}GFHFb^Q{Jo&%mzdu*~ zMnEZ-aEhb5P!hp4zH8-hnXB%zuqA6KF>rr2c(tqFJ!G}-RO=jBu7->FXQHWlM5R|V z=l8t;NYacIv{bsn!82AJd|bc*8i4h;|Aj=S8=@9-tcMiCwR(Qh&xOhtYeVm|WOoez zHTWH;K)ajv+ALGF{Flug+dBtVP&w4u=hmu&=1w%8 zHO{0&jML5hYacLgoZ*dR7j2J(Vb;NW>EIJIZR-w>Ac<*vf}htjGl!Gc%TuR>c+E#e z=T^{aZW_(Auq#SQ;CO5?bX~S1#6i2`>=ho(RStLhZtkBP5wJPaPo_a&%x&)eJ>KDO zVT1IO3RTB1(_%+Ea+ZK{Zh5vgxqRNd-ab3D{N*gwiks@SX!#BIS>*jLFs4COsP#0mY+gBUB3Zjc@Q{mhcoj2|XWasPY; z$q${AX={6%9lDa{nFjkBVwy%vy+fB6y78Jwl{j_3vCL;h;~WA$ojC1H?{f9$qN1yc zK|au-Bw8LALiVsD@gM>&s zP5B?P-ZCu8E@}hCRzd|SX@~BV4yB|7ff;J(6c`!?BvqtKVhAaT85mN!K|s25=nhGx z8_pxV-}jw!ow@kKkD2G$d#}Cjd);fTz3u8wlcA@;ZE?fLo$Hzt6^wQ%TaBgOb$s|l z!Do2VwmWXQ2nnBvZZ>_rmIJBb5yka8f7UW4iUDWvv3&Awa{rOTjZf{1U{|M-!t`6y!*;dPYPM150~m$ zo{UTAe8H#xxklXR|SFM zCiAC%SOOK4xBZnmCj1Kxxkw}07I&H-4pxd`U%Ld9Ml9iC!)l?kj}Nx&+vcROmH4;# zojlM_=)r@mt+z*sN-Z@jW-L;Vn0;~$ko(h`5=RE!YteW7$)0Hqh#C1A8{ICkvsv9e zIkbth_PK5QlhH?ssJBy4-ehX92NrP+AHVVbfQ?2iLzF|uDSpzq;2}bLJ66XAe-_B? zCi?7NaoZ?F{0gr$+S;G+mH4f-l$kIVylp|~CseYTVra6dh6ayC;qfGNM?aw|pNt8V zgXWqJ&5`5Fm`2CFOeCwn9)=;D`ws=EEw^Q5Y^>a;>AtxprlC|5Q^sA`U)}+U=M7hJ9*D_Z18T2aK=~cHtibyQ@JFYqE(iu2$^lKzm}-?xwpvc z(+8NKJSLu6=x&CH>zUxX*th$681d{g_ngp|4)WjA-jfq+FUyBj)~xBx|Jv9us~{4_ zEBbxEdX?DiwH4gi3#NOfS~to~38y6-G|=I2-b}d>!+!WWIOE9Lho;I#^WHY<+{Z?! ztsbdl*wuKR@u;tD1=EoWfLu(@7uEyD+?t{{wNNJcALk#yQ5Z#o$R&89TE_UWE%2&= z?TZJbXI^YOq3L&pulj>2v?u=(;ocv=mYcCCa7ebOr-cszM-x4~k+tP-?~8WB)G8qb zP7GY8WxQ6;lMgB|2Ske`S9M(tZQxC7b)I6A=6$-g2eV{h4ERKz`Zbd=;nHdS2W`0j z#{ZqXxq%tD#LM2@PXR&av2r1FLZQCaD0qDM;EA`Y&-i4P{yCv~k)2G1zhx2gBVGy? zOJ6&iF!$s@+rGXE)*!?{-|j|Z<)&z#1Ml?Tn{)s_cdNT#70mvF%hid=tZ&*p4nsC3 zVq)YVSBZY7^}GBp_0)Xw2eaN=vpy)VGr-yY-d=;iN^0IR&piJ{Xu*&DK~^>XV(LKW zz?-dj3%(Y@zcX2@-tou82bU)SKMsCFM!JOoyvX0c__Tw8i)iApleFp_qn9q|pk(oX z3zH3?A{UdIBE(1MX9gbG4HUuCHVU#HydszIf|1B@%gf&RVFUMCxJ}kB++U$8p=agV z7=AJwJ&AhC@HFUq%Y8%C{t5XtL#9==1UFrT0uT$=cP_XaLTuX6Ykk$SE0$ z^Jn^GFyQmU^%?#Ek^EzFZ%$VVkopTyBHU#IBFMq2bRM3@v(6+#mGu z#-Ds!A1dKD{n|fKwXPlMH)t(v!6+B5vDRJ8`tbcCzXaB?2C1C(;6;taY)bSv4Z};b zFa@=xz2c)gr%#4-gMb5<(?uTd5UI-96kD8(JA_VD!v^VYRsd_%-T8-7kQb{*C{t%l z9s2`c@iet{(L`z8daneu^U(R`CHLXt9^KZrk@fl4OvJd-DS~^O&n!~#?t?a`pJi5a z$VK+$K8C|a;#s-Rs$Lcb-iCreCCk!_I4-^Q2tnJBie1RhF+B)NT>On+3`MkBN`?KKc zVQ*Dk7J-EdeQ)(NRmIsu5WCp8Ph&ij<$l#5kvzYR`k<{T&vSFN?(i}N@9`P->Fa64 zdR1KqcFs#g70rfsFuwuDd!dVS?@r`0 z@@1c7)5fDpJ*tYX<~>RNZul=H_Lk>EwxrMK*Jn_f-29hX+bCo%dXsegnqz;=Fjo4< zQ12VU<2UU_YpT5ux?Jn?3X`Jy);J$5T~S`$xA9!`Ico*B3ApCiBhJU}#JX#XBeTML zIsZ`4J+^|`vII8Jj*VYd^L3?!vTacFOSlEp+K#MrPj4d+_Rrs9JmexaI+`0~eV9 zfS*O4!9U)$Kk$7~j@>T+R+v$_cH}z7R=(~#>YO>51OvIVUJ%8&at@n|!z(JH`lp+t z?@Sj%xt z(ty3#)JHC!TdU00yh)eJ<+FY%Jk~eu9gqH{0E%9d8)^j{mz#(bGQb#vDV9uo8qqe+ za=l?7 zegJDfxA1|~?BaxM`nH-(gb(*vl`MW00lEJ!s}!^Hv^_G?&uHj*nJiJWh|Nw>K+yNc zJhAK>w`!*;58Rc7dpEYXK62dA0Y{4a`VHc_OzZ}+cM20?j08!9E?+u(f4VpgPzb9K zz8!a5CMcHA8M-}wwKE=;A2x_l@NuvVnW;Ie8oufjrP-(98{V9J_c}^HPt`*4kZIFA zql;C^SIxk4i_&bHx!iqjL4RGT+~i$>b}l#IAV(A+4XKlh2htg;xsC~|riU-B14?#( z|LboBK3r;nV=13aUh|Ld-X3ZZb?;Y9R>{9S$f+-eyY~nZ3-H)XtF2ih?ewdgr9`O|B#fl{0*8DoqTs`i3j8PtVVr(y%Z2Ew z;N(T@ocOd|{cic=c{I|;EpuTeu*j&e=Rfwo&CHu{`j`ir2(!fU+~dGZ4Qc{eCyckJ zL)_aVmXj&GfDh@?=GOVoSReft1!M8rn0*vD!&=<9a?+63h!1w{=>q4ac`vo7Tm-FG z7sx1HP0xy2x~C@$Ods_`gpq4+87>}x=M!E1c8?~hJ-6COcJG=0%^!iyI0OpR*zpuw z4ca^<3g6gC4y7Rr<3XrZ{Q_T4sNw0zK&UD6K3k*e^JTFs0K=eU@(Xw+R0%63ocbrJ zV9Y_E=gw+hc_!y5nXj~>M^#a50AnXGIvHnCdn%6J!qLuZkv7O!&uA{pWcdAx^(MxW zKXLm0>_mJdH%`_(fq(Liw4si(p%dQkqKDh`OL0DO26-F*!0gD(`X<)N1qB9XEGtG|{gy~yrslJGY1If%MtRo_tW&bv*f2(T?hSm=YbTNP50k{O zW;kz?ihPt^+`vVYOS2lZ1TvB07Smr3E#BccYb_Gu5;XNCwe=tUXKxG|zOwPz_2%(n z&M&M?5!+lSQbBl}Z#Z#m5tjT&PqLA(b3!V?WAtRCODAA%^zsJiz>A}}2$Rw>1zdB0 z+|Cqeo|QA>t6K54fb+1eYm-B&Lx8Q4z*7)-lSI{a9T?zhfbFAndJJ z`t|4RVN-d(n6NL-yjrs)_JU)X$cO)@% z1PxZ2_#FO~TNRYvU;H$>!au+^!eNGF{eo?{m@#C4(GpHfN8KFnCj;8;rZ)r z{o04#M2tIzTODS!(aK)A@a_7;0o|)l&g;-kT2v6v91X!oq#Gz$#spTSPOojmvbyA? z)Z$o?THg~J82Fn=^*E&~Qbg;vO=#?)qsZ2z@52${;-KK){RYa25!vQ3)V?>}t~-<9 z@n$0WS7#;TY4Wyin#O!(;vwhyHG+IJF~lZelh67m6sCJI*F4Mr%ZL)yEbcozB!=Fm z0kMOz1Dat~LjYTYt;tOTb&?x!jZ(4rNqb-tkHw z=C`R*dt3447issnuuNrXX?N_L^g>YfA06bO`q4Q&CiAn3QIR$-gh4VFLYvE)eRGzF*XE(!9FT9xNXA#qS zvwzE*Qr|T-bZKM_#wg*3Z!$e54M^L%`g)+3JM5NA>**k7{rXJy52tZb6|b4@+(nDd zBCW^Ttwe+|Ui3_A2Pr&13cwW)vBH4Q(tJ&uiDfq8eWaJwad$(ckVXO=H2PCctT z`2Zq=AHG#*`e9(7RHo1sy#7b@g5Az1D{80W+P1MuB(L~GF9fWTbj?>lZPwHc-9fWdP#%Hg)TTf+oy$fyQhEImq4GPy;!YS3A@hBB52lZ(l(0|7lD^>YjEti73oOnl{?I>+Y>~bC_)MxAAD^-9h4SY|lTQ$*+w1(cg1fDo zcnDdPop#P}=Zw&7f-byXf7;0-bU-b8bRZCnPkB;RRE$V7E$3GebBN7{^H6$P15dU& z%ujsJC#-X(BE9XloHNFC#&5oIGb`#{q+jx$UVW4QKyW;zNm=iN%4)!m+?dCVM|~0( zBID-=ff$6=)0zqdE4uzu#CtVv?I$Z(XJOoxe(LEpoGyzPjB1XS=TD(c^P6Llj=gL4 z!qOJm8Y8>3CIx)Up*9MC-hj6Fk@ym_=T18E12jfHXBWvJHF|`ag_A zaf3V7J8=3P+0U`g5%J=Mflb7HdU*(yv(>WB1YHdYyow3f(@0ILG6^K8c<%(h;A4kT6XIc;N)Arj z)E;^kyfz!P+U>Z3k1zA>$w_|UQ`LCak|$!{TV#h5D8|Xi5#fhIxBCMW=IymK|MVT? zg|w2_1sjA64Z(`?-!#3fOceEr&NOhX;wKA(7g4gWQMtYEn|`^F@B?rUlNGtk4tF>e zM_I&7d=l08$N+@?_puLE^0sunI*?6lDDyF)me@_2Fm*$fAK-)+Horpy4yY9xP=$-% z0>otE)7HkeOdEF4As&-;PMxv}jXr%QqTZ#)yx(}M@)n%esAQzU#AC|zH3wR`rb;n# z7?kv4PrVColMawr!E;_&lnJ-hIpq{@oD0QczlOh`?=}O027OuceY`hA#N-DnrOVoP zetS+b#0wS7RH;lJ7vaA(XdY-sZQHOXVM(12 z1AMRc73c38$57+{Zc)xaAwme+)@~{Q1Y-5uPk=ujc10@ma-9M7mt9 zNT8NWFSm5!J?Ui3{#jK=@VJ2b|Ls2tN_HVK7XEaT3Q}@IVV5ro0Cf-({-5w{%bK%T zBQ5@5<@4S=DJ2D#D??oJQ2y^jIre~|;BJBk zk-quk$p7LZM*TP0!yfsA0I(U<@0ocmCwVIS2rZYFN2ds-PHw#b<(sX!ZV$)h23&|Y znoGqjmyC4YX)d6La$6%fmT=OrMJ7zeOuQ$ziu7muMek`KmQ<7BVW0n2q z>GhPOh~NBr<{<6etnmGC&0NPDELaJ9BPZ)65+DAoZy;Ge5YTcrkD(D|3a#!7VRzYq zUJevqqh*C=VpwSx`%Y7|U!Ig|V0O!nbm_b9iwxuK3wvqn_uoVp=b$qiMiVh?|HuSt z5bM7RQ!G+w4v!qnIh5N*!Zi6*I+RO<00G&Ay%~`hKj@vEsT5)C_4?S+=s?8PfKi7GQ9;|iE|)QW$Q%p-ZDw= z_B~!0aFsLHQ3r|IyNC)A{|n=EkZEkJn<3r<{vRfD$9Gac$cy0~pwJnEk zyZGSI!GDt-nuk1AHu_+ zU^>=k^T0ems%_&rKn(POGRy0=Z)NaPX`cjh|Goe_DoH+ z-3|8r3$qxLef<^Gn@Y9O48nm-%Q)u{=QT;RJp(54j}nazu(wSPovZ;ZoE4!+3q)~2 z?F#KbkRBlw0-7ucMc7S+uepMUb1vn{dELaI+KXSWXhq(hTbp-~eSE6~pUne85XA>K zs>p%RvI90z@Oa&na<&FN=uaaHGWa)5dYx~{{LGU#f!XvgpGbuLhACEq#*10=ek6*O zwUnC!a}R8AAR{zHhz(0YXsx}cAlGg2=SRNh>x{h~>|Eu$C*u6_AKpT~GU3^Fab4c$ zGCBtisE-GL#DvA>pO{Q!2RoFc2Te>U^L)Zzbn*FnrK49P(kD&?%qEF7URMVF5a)ZP z7#PoPCON(z5xt=sWz7fERh=6rnRnX0Bi0TxmV`C()YQ}{Emy6kSg?#Xt=aK5F7@~b zQkW}F=i9j2SbsC`V^Tn>(WO^4E7QXh3GnMyQfd~t&`@%Ay~w2!cC;GHdI-wb&a`s1=)9SvXhu>3Yo3)XyXd39p< zi!Bcs!unOmC0upA#R|4Ei3;u9vTtWEG%NU#3IhdP^koUgEWY~>*jYE1ppmqTCD;3a zE1ApS4sZU)3w8TpH&ExYBdn@s_#}M)g*UscJRRY`ux-ZswES|=5nuZSNF^hO$@kJ? ziJ|YRs%s$M%(C>oJh`VyFbdH6{HDWs*I*+yq&@A0A{Xout;dsdt=hN$6Be;z=Yrld zHa~{gU9|PBAF`Kv`^9oxBe7fq4NW)Q z*n~1fKL-wC*}IrD{p)rUQ(<8-_%nhQb&ymnB1EX&sB;4K1aBjm7wI1rirLC^dOBZc z^L^KpPJ~+hug0s7v|+9GAT`Y=!2j?B02qol(%QHF+lKvZR7G8U zhTm-L?270=9mXmz^xI@_na!J_7Q#Lxbiypl*B#@4hJ574mNxWrW{Gx+WrA?P#CMHM9c+?@O|Sy%?+$ebL^U&9Z(p~Ua)9mkK?{cSn# zI&m4P@7y5?X^rpvr^UBC-ZJUhrO-qZ9!JLkY3gpSU7~H>&Y;~l2T*(359R4y z8=xU}2gB7I&YSz6+J9_EpCs~p3=--Vx1Fwc*=drQ)*}pQ4W(3)29Fz&P}R{j><8=z zC=IlazLobCp=S;OKoB274~mma=kG}zcdynz>OCn9SY8$FTfhB1uRjvOmFOE!Cxa6d zYGQi}K}=+(nl^cRc6-B!0NFjdf@bV3=Vasu3O}wZOOo>+ql~2zZ_+$T6tBN1n3!l* zceBYfK52$=*<}xWX*MdCmX_wk;q*xnFD!I3(Ra`0#O?EY)~=%QdAb|;HC03MKxw^Z5yqT za|(2|L}T`w{H6B&Th4V*pBrh^xy#jWEC>r<2!^v#U~o16M&i`L%go5=HBbsMWRx9K zn`$bIaL3sWQtD6VpNC{iBrC_^LJ^$2p*Yn2@Cl-g;!1aT5y|~4>J*}<6 z3~t-}QB?ExquXt)7SJ=BGQ991@96{I@gmW-3tg$T_Dr?JC1;T*_kRz%ZsU&7nN_{# zn^-igJS=u%7v$B0+-R8nnuW+>rA{Qm_pq=`Eu zWx?DRmP3OHlHBBgY=+0!$Q{qLisDurcv4oi21K59%B~c~N)T#mdFg%i05`q41UqIB z>lvl-g5%58heAxi-0LpJYEWg$=Y&1V%r;;EE~DdqX5VPoPs+lbFhTdc;rWf}V#U|$ zFWUJ!iEX5F^Irk$bYXU?=AKkI8aJvtL?vZS8hgvEI8mo0%5MT1dnmvp^y_e#oLnwQ z@`tv;hlM!s>aPA*l`09iTi*=ps+EM50offM^AB(>)ley`I$rdtEk}9Tbba@Sm2Y7y z6OBPGTd&rIv>&0ZQWk3;BrC{-x3e{qMbEBU+(bHn+I&w~k{;NjVF!3asI<)Z&>^EN z0+%&QvVOX()#_wzRMtyYh_%^a_)aYd`!snZ-N=HvR62=~ju|7OCz+xd$^ zYnj3{U0f7rKh9PcAhUbvxE^i3C&;3Nwkm}I6QR#p19Im9WBkO{*5rU&3dV_9Mv7=; z#5v8c;?Ym!s7($YW{MLAah;XeMHj~_S8&D=y=0RQxfl}KfUrW!Z_w|)OxpI<1P;Ff z{@I@?EH0<9xIW{e?1s(q+#28zUKT+9FlQMGdj7!rM^#U~BsUaI(Zg(#V-2ZMEr|DY z$}xHEqGy;Jt6+l~BN%v_V&?7}bB``GA-4Rl$-8kWH<9B#?%+}x8&)SXt|E90# zeK#q~{|W=OMXHiWAUoJmOVUX^p_X=NYYDQVm=V&erdN3OwZk<2&RlgFPFY;?YM$-8 zbrhJR2vCwq5lmD8Rd*sUu6VGxTyPoNlt{YkDG`|Awabo=-VDTCjeHwd*kq6YP}>*A z)ut*L2G9`XhLGB5nu^mwAkY>T%G^)>#&ByG1qT!-LDKS2o) zow{{wWu-OFa}@l|R;zZZ1Huv$|9Qt7*Z8r#+SZKg=TZV&#ZyYx<3$%75o05li;FE z@!0+V(2&p%0O8t4mR>sAB;uuzwo)-2McbkzrT^t|JFr`MyCzz7?>n=(Y&_yIce>f- zv_GLZAGIy0P*c@jA!r!D3yDl5OBsNytkQFj?=T_&+VNnw*U>uYbqwzlA_dA20i|RMrrfaU$)m7L0KE=0J}x$esSm{xjTXd+ z1}wtR-aFOcicigg-}PB88ZdF}@}*l?KL>KC^M>Pf6pmf3SGTRHdk(1Ovg%vJ7qZKQ zIc@M($}1|yqQw6CsG7@R2!8@{7;zXkqEp!qT}#*S3vB**y6dBPj03>wBZvp<_GuGu z4BkXu_#nR(%~{TA=9*4)DeZLepgI66$yrZ|KEqzH8>~;PZ_Y9kABR?Yw3uKvn&&IL z9X~y$c;N5RYucwe<1aYn?DOn;Rg?w?2SL!{x9{VRvf%#`4MdlBq4ZJHL1>_yYilZJ zsqq_0d|rW%WmrH>0>C&86gD_9<>UBO^`Ut0TJx+tClbu0moSu2S!p8j!LN&%ZDh0; z#ZI73%As+Atf7t@0{HX(ZK$9EDkus?boqtgQmU)mTF|xf{(gBRx=Y~pLV^kBYp@s4T**w8`s~!=SSMK&78E;Fnv*IDw}uGg#TM4^YH>z zj^B|je9+Z9@3uj7cheLe5A4eO>hi&`lBk`pl{4b!znftl-lx1>-vusokoILOj>5F& z);CSNhNCui62^+phBv0yV&=O9#s;0^(^h{xkZB}8Oc>aB(mwxA z^dO|VE@#xh$qnP6ci)uAOG5R>l*3GFY|mR5CnTbr`DT~o{{5$qV{r{Jsu%$?;_9La z7goCua+miGLMxRFX5Nk*H=8nD+Ho&6TRnx{V9nf^z1X=hRCuo4>&g_Rj48bO3S|E< zj9?yP)MO}Q*#{GS6c6Ewppc@dQ$H%x0ZqAqe4};WIlc7EH+H?Q+|h1FF8=!Qh7apz z3@Kg$RmpF*&tQmlpho)mFE8vMQ%6h7P|?0=ze61$y)9rM=3x_PADey`OO(e!9^wsz zS3$L0pUhVOSK|B0J@_5%oy8!29!h)Um6l@VQ%U9RH9cL9(@yLUkU}NEnlzd7 zZJtzQdvy1r@CD^U6bWUl%J#2**kA7_;Qb6q&7`uOBNq+SMee^1 zA1#%UlVxvqddMa3B?)ALmRfK~fQlv^`qpp5tYCMpD?=AMME(RD=uZQSpZ&ywoLV9p zNKbgl*b8QlSlLs&wc;ciV*f8iQIL}(7&qxSMBM#}{_dxI-1ns_ODC_Jqs7w*@QFfX z802(B>QJfg6oWeiT_{dlMZZ75loS|=B(`P&#E98Z>pow$y-S07P@vnHFI@zt`M<#D zmBof2oTbAA_aH1bE%Z>^myy%G4c4CJlO5Bw?C#1)|NrGXgbz1}U24EY7O{A&(H(h( zg%7#{7%zk%IUB`QQ`~3PHy-@WywHLHt@C*3^8Thoz~g{*dy0y`%a!X_S*6kAMl9V0 z+nv2eqg?gF3c>8-xLqIbr=^M~T9*Z8zZ_TJ`+vE!mN19PBEPZE2y8!5Xz{H+TGemQ zFRs3a`ofeJ2fLcOP8Dy=jv~#%*+$_OLU+i^c6oTWb}#&La9}(lzKqE*7^nxoQJJu+ znMg+&U&Q;$lQH2i5r-(5Z8;ap$VpNDUI})kP??p3CY`Xc)}bi&4*%R2E}&4(f@i#M zRu6Q(`MP1}J>T*}nMPbvCh$5dkg;w^I^W((dv6hI`2+X;t9llXW1SFcOT^9Qe?@W; zcPS|WF#4$b!Qg9)1gelj_Z+MT3H=oC6SnSu8Q}Z&cFP}-NaY-arSS_jZ*~_JXrvJ(O24QwQ1IlM7p6OdPW_fw#*t!ta_ z&4cf2eAmaZzh!ueN63;ecm#sLS*ksNIy*c$pM7%t69}Y%sP;4abaOW5F@~kgxh8v; z;s!?keVw7#^y@EWK-+>nQZ9d8f(7UxT70AR7sY>zx2ZtsaZ7RWogZaw-N~K`BV_w~ zR{-ea`^;6PH=Us5f0OX~$<~#jZh0tnG_?o(M%3#YoQQR<<>rKv;STNdq0EqdAu-Ec zAH&5|a%r*K3T&_6oAm8#GZhH7V@89FSi<_ll{q=QQ-M*pU*shk%-4&g%%Mh3`hi?u zB$1UkSbFJQ%xL3hr`Lo|{N42@UfwsX8~CLm(?G$G<0EgY0Xe&Ujd__FyRmlB<5mrdSshlP*YuuJJ*yv&{I4_Ydm)Sat)O~9hQx7u((G21Mk3j zM3l@-yfVBdD-EGOqEj(|4)Q)8RxnbPI=PWDWbnA)9n%lw9V*UC>ubEXUl2rnS6_=x zJ#U%4y0}`NoW1NS^x87G+Vi=bEp}B&z~FkI|7u_}SO&i95L_IUs<_OknW=%Hhh{l1 z#h_%6v+iPBg{FZ9!=5Cos;LyO>leZjRQ6sJ@ZN~?UL)yCZJ66}>r2tQ8fz0j>`=J` zoqb<3x8|y-t80m!GbQJsG#q8Qcl#4uWDs(hbII{9-LJIV4(Uhpi83T6#tAF?(5C+# z1OX)TW5Rc)<312@vRZ(f==KqHiv049o6qH{&udo+EN4;<@Oq;lg{yW|H<%&M%RGT0 zGe^HHLruD^2P-~Hb#1dCPl&=VerwGLt!w;WJXk*eSeO9YPru7AtN#nenUkHpgkDhI zUlH;@+ifszu-Ze`6gP|Qmov*&nuDdAErQHHi=8a27|E@5HiE_Zk&pL(Y61RPlc9!^ z;8Si03lVR^{>+Rm8ti^`QL|Qh?~l{1@Z5PxBvmMRT#8zXG0U@2@shl-HSp&FunUkB z9VnkfHryBosdNHr8xQER-zUSjv9S?%FFn|JdNdW=iL@;o}@)tvnl zUs=@PwA4R?aoh#U^LKwMl0Ay<`2dFS1KrJe6g#OeuT8u=NfavR?z1Ow^+&UQ7wJ0l zA!{Tms$&WGhyDZ7ywRpMeu;-p04Ork&IZa=0U9Sl&B3iX+PR25CFSk7Y!yiy>OX}p(W znu{fPxACqn^BgTG0yE@rpmwWUAwzVCxC`cQeAW^U3QVJm9 zll^H?s)7`wwqQ6*@{w~-Vz~5cL!T0X0rYSLccKaSu4>Jvt%>VVVnt&%b>F_6H?%b} z`o!KS&*PjkXp;ZW%O@Z8n=J#C$6dzY;O8bOl%nGJ&!GjYi2#gud@-2E+%FJKe2N_B5#BUc$GNd>X# z|FUjP0)ZgLP0w|800(X5oBvjlA=>E1#OyZ($C?KIo_v-j43aJxSE>@-!qMNz38r`y z-pQ1vCeU#vzfR!_ofI#YnFd-}WDy;QcMp+3&FP+|u)@rfhX_dh@mBbPso=9Fn*|XQVz?f zSFcoK-0S!SR_8y|gIPL?oAz`w2L8HSoK4e!`giT{)jns9PJbfBH|=yl!vJXf>{fxp z{KGRuJj_4(jtp^Xi4?}pjcJ(MbPg=*XSy=DYl)xae4B)~iL1ck-iM8Y(>jkMo&1%VnVH^R;ys%?-KDC) z_65{O4K~WEdW+Z|;*m0Ua2f&a&w{OO!=W*qGPVCn_fv#%DHA+?Gm1$KZCh+KY+v0Y z36Y8G5|faij^N~Ala7sxtJAm3*O;B`5=wsjdT!%@tZm1`qoz3T*t5Q_PE6hk!eRzu zA;d-~2vMZi@smf zh(lf`hPAXH5eRkLBi$<9iRo#tzjK!WG(3`z!toQ6kJ_HSTC4eUnW@3L;X^`9HZMe> zkoNV-eJL1`at^)}J#9WMx>$XH1Q6HvExqR3VLM5Mv$4pG^lFYDNabrmCU9mv=@3-2 zH5%?qTWp&j1u?j3u?uI-8cLQ+y8QV-oaSNER8rPB%+^jqM`xigWje5B!S)E)DdMSi zPP~wOjc+|DreLHRT9>1z=R;t&My}%nYxuNn1w2D1-`38~##UTQD=;vf>7jASc=pJ8 zm~4g)dtqMEU@;>o%B*U{3SYHkyw>$kIB)=5m2Qvu;^oEBg|`n!9EJ=<@wn~$ylH*i zB%!-k#oMt&!&**lBZ#p#MXV;JZ`FG@x>lGc!QdNl^AKGs<$h`p- z#y8fPl&^4bLM(doT8u+J(>z75?E`W2`S~98^q8BY1!J;;m{Jz?iKlqh5U_A`=w*1{ zqt7(K;clY64z)vT@A(rc+MWTU+IJJ32zy2I8(tGASTVWfEXd!{I)ZmLtBSSdw#MR^_7)?TfCf? zI9~?9`>5U(NK;`p4iuw+*W#=_vt>%2={2tq@%G@or>Dp`75E<%WO5=GF^^qcJWTY3 zKTn(HCHguL`L=Yr=JPD*3!F24L(~lb(u7QLDG_hetv%UR0&xTRy0rT1t}=ng3{X^DB2tz z2Sl&ldp#E<2Oa3yqrhipV3vwi*Qxujw5&g+OaDd*t8Z127e_NS^I zb`^B;%2_2NR_=8(vKcSrqtclu+JOBN?o@X;@dTPbx(M8E~3y-BKsh{a0T41Ep~ z=LWrx&$*1VrTz7$hsA%hqY4MqJJl&M&l;1oV|h!N@dtYOTv&p}C1OFT0xJrV%X;<4 zHYh>vR#^B8F?VU|(&Ih>fUMnMyCCWi+|u<3HUc<41L)-OcXqr`KNJl&w$w>#RYP&p5lFbqJ7p~RYD*uesYSoJ<%*C1(ExM!yCb) zzcSes31r^5tyw6zsN~B^FA>T^AmNLF(oyoU)aqTBWMjoBy4PbW8KsDsi8yvbAcQzN zlS=!MlY>wI3UcJ5mX00-2IJu1G#c95*>NT-ukM|cSO^5lB_>+)Z&ce^(Xf|eaS3Gv zC{*e8mWnVlGb}m_UdE0oZ3eu(BgaAC;eUs?ZqkM$TsgfSYyt@L_y)Z$~t%MLxYP zxBEk;M#$pHnBe*uAW!)$7g`Rz|weNItyP86xrU5G^X7H&o-`qv}h5|5F{7H8p$ z32UFDv?qF%o+s))CvjJOy}b;3T?eDz!)K#BzWF=OjggBH{vP!NkE4Hc9w^pCbQ1Sn zB6IAMiXOV7#*?m#(t+M?6iU#OGes+|WI&&MSxuL3lHAV`{K4ijtD zckgrkZ_pq3D%=&P#-oe1EA5?}YK-KIhO#nk4idm|&*<|gb4iz%LHBpyH`li_}+3gM;W^&Y3q=yx?8jl4H-iH{tw`0V#SA3qYZ} zUeWx3yKns=xzY#DThJQQr5qIpRMTw%8JTi_od|5l*YlzDx6HkMY)SQcRzhxhqn zD(-!$#Kgp|t`PCmxIpQONik~Gq-{0i`Fr4~GbVRkj!%owdr>3NIf_I9!>%R!C^frBgw{mg4={Xz?ugW(l(E0=>JR?W-TeAQ!@R$dT1`SCCR zsSUUrL$S%-%BN~=s)2EcuG21B{PoQm=AtT|{Wu~wyVcwgsy2L8pi-CQfHl@#ispt3 zi%DmMTrH)Zo3oYwhWD|vwH_?*1`)Hz}sTW5qF2PMiSkA=+J-epU8(M#dp(cmd4JLydp;4V*E# z_F&uAwvQ;xJ(eJ9&b}(ig33p9?x1b4tKo8^!QnUrufx(Qi{RsoR@&gdnx$)bI6)MZ z*1G>&;0L0NvGRq-wOAndNiyxXg~S;YfGpyOHZlDQ>t5R9=H7RiFFF#TXrM__hb1nk z@_S!H+_Xbgl1?CSG1O@}Er@63t?%511a}WYkhw4JDmI@=OP; z&oA}`KtTP9ZJym-K;V$6NhXYT5T5Ew9;2{!+KVq1OoP!W@moy%9kCg&`j>yYL%!;C zEq~6D2DZf3|Mm0Xmyno+$wy$f*hZ) zu6{Q*GovKt`K|yA20fFQ9cFj-+S#WNRduU9EJ$-Q{W(fc(?LmMCNR#=ly)7P+R&!O*Y;LI{fSUL$tA+ zOR^a?a5Or*qLLmpuLA`&wx3l??J$hJl~_jEK9EB#Fi_o8CKgdQwSD2yq2z7HL8z9T z($-gSwdix6@ZMSe>g6reFRev8RMR|gC)J3L!WGycRK}!LPZ6%AF?J6o@L`5Da*5p& zAru~}Vq%Bx89qG~hEhJNPP#@9<#5?mY?~AkIvIRDTY@h~)Ts3y|Gb>3#uOXnIhia) zOMVr4f?_%nSKda$zce!Ir^JPnJA7n#pasDk47m0O%Iw0sw{Mx84Vo?Q zK3M}wj@~ntG{>?n{0R+yD{%Mq6R4(Z`2)AsQbeW)KMwebla$j+tJ;8x^C}(5h7g;qJR{KY9)8bP`t>&r%Q~58f?5)# ziEY^hox-za(JL9RzWCj2X+WH)ns%Bf>sls|iCi43Q1hxzcAN_E|~T+r-d!M&Kvi3hns(u7mUi zP~@4Zp{BGWw=Yuy+Fl{Bu;;!nR8F^kz?dUtJhf-8ar+WFJf9;-bY5`eE`Bf?Q$ z^-f9T&&c|Pf@gEb=(;4EN)v{fV6kXaBKS%3E8vLAs-o80ZdI?YawXZus^K22*X@mr&X#6fQX8pyGv*Eij7%MH4D5URP42v-kU{V=em20?(oIaLvxIDA?yiBLl*$iyOr`Ys34 zdxvEWUVyAPf%CyUPUm&TZ!ykIXh-F&+wtybh-eC*Yn)%cO8Xj@X7W5Om_e5WN6r>HcQ zVG^J?zH)NK&BTb;ZJu~_$}{3`uMMTgyFbHi4lik^HVZv}7>1^Q>yFD=_-Ip-T{~bU zNTc;s%R;L`qW!)qLR%Z5btSy;>i4hb_aBOFcgA;Jz4Gy}-AhHP%zmkUzu^c-?Tg(~ zqc?jG$$a<5PVY&d$azr|=37v<`31}$pT9eUHPoDT?)7bKP*kdVo}YE9BJ;b*3zI78 zEoY-P9pxW^ZANUwj`>DVcPkiV2f9TbuX{1|8PI#sSVpwu9S%V590i$jlz)7egI|ja zxd{DC7i95qoW)pbc11C1%pbc+C$8G#6PO?!>3}h>RmFImwNrWVb!)Nw^Lq2OD)yov zGBDWo@3rCM%;M2bp<9cauH?{n2?ltW*d%v<_Olrhc}JY%6e>DC3 zE1=zDKaiJr#A?uIr9Q7D3*2;e`Sq>@>MsQh`(4j>G)fyd4Uc9Z>Qc*Zj`vYk?jzHU zs;2Y)(+}&XC=r(<1{WO**;u*?$2ParU z06$XGhjGn5fPcW;vSD;%tzK03_fL#acoaV^bTOx9fcSWAuxgW?4 z>(JZ)4jOQ@jJ7mf%<@Bsn5`J$^WZ>nu+Bc$CS_^X#P#bJbRt zIB45O==*G_IEsi#y?zG0)f@X-#2696j*@F0G1`zs9nC9ro3VjIkXh3N*SLmEWw6Kl z8}WnhhzC-URT_*O6%Ai>D@LC|l9B{or*~`LJcJJ$7L^0E9q^aj^fB{=Oe=Fb1$k8Q zp5*j?-D?q|kmoV?=nDlSrKXP^m5?Trrc+rhdAmUDme3)uH2F zDWrd~-oJ7ptf8@{iXc!KSrnu1f@Nc4b;;bZI9@np(qZGTMT2YOw6s$J4oBN77Za?Y zwGN}oKG4~ftyjuLeL?b;A%WhW53qaX0l~NKHo&8^f~Dd&#{(KVR!#v)@|gR`gY;YCJa#oy|+6lC`t07xllB z*U0~xCzhgOZJv9My=0|n!!b_;$d}%R>5jkDkCe|a1q6i8cwfW~zqBSRW0!i4ZuT9I z6rkJ9>(NIbruSp#42yJ>iVW8!Q5jCIenARK&*Bhyhj-eYjg~(v5hzv^!?BZ-lj5H1 zXn7tqM83waM)3Lv(J_OvzqX~~kMfHu?WV^>4|4-9;^ZWGdM&KF-xx$@6196aV^}se zA^m{P-C>7KPu)%ezpbOQdd#Dg+Um;b*7tEM`I#-;af2}1w{p*iXK%M`$(A;0S&ST{ z8<~2rN_*Nj>)fcy9Ou2l%jR>eUvHd7ueLlN>mR4Nd_|79wmkuHP8unYXR6v%kb>XSR%m z$fpy6(JIK_eND43*lDCf-!~mBDzk@X#LgR8FcfE>%{AWDBFB0OzLr!xZoFo$*~zlerSJ$paR> zQ3H9R`uZ?W?}gfiGLcQXBHH1E`|J%LL>~#XJCl)Io2K==E^Sjp=A1DZp`Xu_wif+y zqG34TM7F)ATKsqTT_Xu5WoWzkdAw$xmY7bCUQHhrHHX%kUwPGO=NFy*|DCHp8x*kZ zF$-&0#rd*D`zEe572;U2vZNH9vNmAC!{=$Ci)X7@GOsS8WQs$Zf>>Sd-P@mcs+0G) z=IQI3iN+>`4NYn5=u8$=??RFjs8fEo3S`E6OgJb*d{h^ zsLObd6$Ba%n(Fmz0D2EC%`7zeC`nJ?aigoXmAeLmaBO4d-^T1463KUGNd7JOc)2b* zZQ=;#^;;{sG)AyTr)%beP9nLdlha?ZVUWH7K>A+x1%O??g?>Ln>6yUldS$oyR_7lL z=S1$4g40DJDv%q)XzbPzi>Q6uSF}&Et_n#I@^|q7dw5+=Jby|I57+JYsy2ldSidM_ zj-ewRBO@rvUUecnr0LTrFyd~%TfSW$MmPCocVs4K)yvR1En2^5EAEP6JNP*^uf2-V zap;TsvY&Tjv2*p-t*J+L-Yi%i9mBsBQrvcldE=$0>yx!*9I<&8%Cf`qL>Ji3SFO1M z$Bu#fN?c&2R%pQw5v|TUN5|PTtj)S)L!%Ja435! zR*6NdQgjtKOnl*^3HNPOBZ^J1e(mOFwlsoEstSDg@|88ix^$ZKe9yC->q{06z4E+$P(1@2#j8}>cO242~VND^eZ z=;-tY@`6f8cXf0kXm+1BlJ4I=W&RzRc(#YbAO0-VAr3UQv~1^D7Zu_h!Yuy?kjowu zex7Y&_#V|!inh=_#OlSh_ni9kG-eC&m`gD>`c~Jw&xd8JDzsLv$(1DJo6^-?;Ti)X zsEGZ!nXPrO`yJGo@A&CgY-zPysJ&r#ad?gZ7T-9Tf%;ppp@3`hN**He%hTR zB`y2L`v&42zB?A+tc&EJJ$4ZZ_TDS5M?b9^M3=m+ID3$VG@n0J=7~PZrcz|hPM*sX_msjnT_E@yKofKDF+#K)kd&j3) z8>>)!<(i1Yp&P;dSp$LiHPuQ_|A1_Xn%k=7Q|6ENu6g&DPL&n7FYa@%BKBe=z%~Mo zkloMfu0-|^`Pew~IemQZD#neHFrqXPz zvaF^?{m)Y<)I`KzfldHL5tHF%-RH%z0AB=ei*r0V^gP|&t#GI!msP9sVHTT&NH;k< zK8=&4Bk`_JUH!3@@i+(&E=^gc%|>j9={ea3oV3L5{oK<-bDIoCV$<{*r@O0x;|a zri<`?;h<}`5YHEya~nzQ&KmkiZQflfml36&r_jzbNb)^~WUY1JGFdZZF3EZYKTxu=CJzcT`<)*p z-i};U<*EJizQqJ^NH*SZOhvUPmW1~-sx`N zT{;dRP=KPfewi=ELbpP%`pMwpqBiesyKYt$M_yUzJG3d7%w&2$Ay+#ofg~Y$W2b6z zGTZ2E>!6UaundUJa3x&UQPL~SKj?SN)Wqw3TxLYQR45DOR)I{yXDz7Vjnz8isZpc1av zE%lgOFr17qV{<;-`xqfW9^^dj@+#;`<*D&^NeE*4D=@9+M9`TUZL z90E$~_XiA3j(_qq?7Ex&-p*TWRdNdr%$lGD31Nsu%4{l;m6zS0UTE%jzw)$)rFkMg zG&|YXE0dpA7a>pVsiqTeKcVRjx__%@S?4_l)5dJuQy@#O)(a4TQwPPc3fFr8X5rws zr|U&p7=(QX$NGz1Rv+ublEVd=%ey!o|NT0Iwz_&a=C{^jZ)`HZomg6?^+=tr)@REV$mApDfuRsOs=J%+J-?0_V%RMf^kvxx zWS~ms5Lw_XyW6W0QP^$p?925yGLBwP)34Yj|L+SX7Z zDy9=?BsP-IP3xP-M^-Ig4a_`D$?hL(He)q=Yof7CBR0mg-I67m_uq}^5;6aBv1 z9r*wvo7S_YztZu;TnC2~$+~;W<_O}wuBFdpac3zP&VB7Lj7JtE5CD15Fi{Nwx0SN? zNnbI@0b(yWrn&@V^!I)Tb*|l?Uzkh(Gb+r6NFP;9v;vt76%abqQ_pL}j&oGt?aQ?; z5(R?ikZ$)$xVB8sN%^Ep{dms(UaxgL)_W(xtg}l7{0uvZqN{?6HBOdTe zf3Glej4-gQ9t^JIe3KhT$pL)et4|&a!oA7N3#Qyp5d4T><+}rTI7m%ClcK)#F{ zBQ{g(@R;b<_)p>m6+*VTtop>*A?Cyzo zVd3qRnlY~@`o7rzz2#29d}Yi1DT-1j-w(eD`}?_`E_4TN1e_Pi&E_n6vB}DASEYVZ zfAUtae!vZDj(+ zqE~C;EEaAhuk4W+69Pe@JYJT#C>v5I4EGN9=C{7D9=^h#_0um^s@wMD_do^74&U38 z4+O|VgHxY{@!K~1Tuq3bOxR?DqM4y?`jDZ+9GvE^wWsX%wT$#R#eQkFi*53in%6l! z1`5%)1=IK)<7atJWYk?9Cw@9qjIWK1OP?>D`|ycDx>$Sbn{i#sjh`P=uQ%JwP!;=uHQEZgY-WNHL3w}$LV^Xsvp|9#Q-Y< z{1x)xOHd+}T;v=qcsw*yM?ZCGbTu5%m!INE_6%x&tr`8h7CX^_Ts1*;HUK_38$?|nwf%G$q*isMFlACD{^(kZQ82@fn<4Yw!@0ofgJ3 z>9v?&b>Ev3Mn7kz=tPh4Ceo8>-mG5-g}5vhf8cXxIB6a)pCo3%uMhra7U zYbGOr0Mvhg=6YL_|Dc6Z9QYS4VxNymh0lIO9vKR$Kx1n%N7>SY9=<;M)rofu$X)m8 z2}PEV99m=!D?wq=6JMMKq>DXQsAdSlDq3IU{?uOnmyWni4Na?vuC1m+^&52MjGNay-cdy+oB5{qPyFasYYHF`aT z>J8GC6!W&dL#BrLpDXd)`kNT{fJ5ywZm=ahgz@{Wg$fI8Tu!N%_>_ZZ7F(3_+houF`b>e+~2uCuGsCX%nCaosQl2EZ6i{GyZr z<5f1oxL4oN{$fV;1`>L^w9J0zy8i6ry@t6IjZh49$Mbypcw@@T(cXU2U@7hVu<@n- zbf(6BOkN}We5-8PLmWr7{>QlU^WgHGv@Gd&-P?KFm5<||_-ZnEn^Edl(q>!dyUkrz z^-gVH0#4eg2KF1b%4+qKLfYkB&mO+|;P^p8i2vCKdps+1sXe~5fEkADkWeiAl1zKI zn~e)ly;X8+yowdb)_Y}-SvX1lCjm-kc4m;i6VkHsq<^!1!*73Kef?IFel4dmZs>Kv zYYp*iwW`{a7ldD5I^>}DhrBMb3WF(wzcKpKkbCv1Db$4PVZt1GHBMN>lBGbl#c{Io z#XfeLbb3(Qp&V^kv=4^WjqgmfGK-6gSB;L0Bmoo7@mb^S{U6|O)f%itND{P2uft0q zJTxRnHhMl|hjJOk0KJ1--4z23+Zf`sIU8~;0FfGop>ffhCLH1K)iPT=y|MOZVoxGK zJ3-5J(lf#*sj_Tr`Q#KaE(2X{J_bgwQ>gvkIFqA&|@2S ze$@qL?%!70jOvV>6NyOAoOBrFXwu-DSl;!HnE$gO?fD82Pmb6uwCkra0qqv`dY_oQ zc%Wj?xOAAM(&ao+=h9`M>aP`N@r33Mz7oGS6;8V>xn(7|vhP!Ae=nq^l|tCs@A)b- z46WX)Cc^JJO(bmYTIjoY^Np;&!@uI^n&{H3Bl)Rr`CjkVO|b1j$I7Xe*A7_8-s3D! z^?SZQ?I*EIsZ{xIW*BQKy*a-14B} z5HCp>WYFn>COI~k_HK~rLe%QW%5IIicG(!$pI8pV0GzhK^2>|?H@XnP!`-8^4EceT zP>V6ur0_c+rpISd=jhW|f;gLM;Br{ac9jyEe#giQEYkKo1nbRWdyunNWyBp}@I~Tq zBQ;kYmE}j<~kzsA% z2;6HZ`2sSzp%fq>XQ})=u6OL5d{`+hEc-M~t7)mPWjb}@Qm-?^LB<4@)Fm~xR?cFp zxSjIDNe?QQp;m?OTn$=OBC35_k%(WWBU8(E1&lo)HJr9@$DUimhP;}c43;?}U4#|P zIs%5#4YTUMzh;2^_tnxVA+-0TKM6`!KUFn!UKuIPJ(boxUT9LBn{3naS>VRIT3rfw zoqAb@*838W&~)}ZAw>?F@b{4nr*48oE4#v6`h3fS#-wzN`=g_yi$5Oo*VAZTs zYiPwtmI90o1)0D4<)z~JV+jkVzeT@|VnYo3^VFfgcpg)|ouE$rbm5W6j%^z~TLcx1 ztqx-`Z|cKAPe+FinbFhp&VlL%B;Q)QwQy(2Y72GMiG%h~^Vgp$t)=1lOoLqI!4nnz zgF6>dby|>Bn^>ifoO?;6`h*;WbEj*MSYw8f$*MJUw!#42IieKbmcnK)Cn_SkVILG6|SP? zjWE}r%^XWvxX!KY0sBH3svECjNGLw^L5WaV0r&`*!Ts|B4tFmHHam zqI3KW4#NgHta=4*u&+&3oi(NIXh?r@j?rb{lXa$}t9$LW z9k(&e)vey89+y|`K-V5*Oxot`>As-A)*k9Nss)x|X3mtg?N#ET_uR$d)6PRSFakn9 z;Z_p#s^q=4Cd9=eOCXMgOB|Fv@^Mp0tRVC2a4-E)gR|@PYI{$7T}Et*RI)Wz`s;zb z+Tdchyjguj(qdY*jP4NUG31ES;yycjhSSCeY^JO5)7)JJ%a~`y$g2H96?oP}*ptVa zCeOhu#&amHQI;|@b>+t+6LK^Z72mpTGotc9Skc(fT8V?OYokoy$7#Hh_|%vz2@T5{ z*`~inb+6C1adL*6tz2{=;c|e)lU`BR^q^)G0nVRG#kDZUB2*tpmKz{-T`DpI#?a>Ld>3-8sGI40`b!F>p z$;}^M8mrd0l;D;f;Z-0|$(P2Df&sdJ+|yCd*HoHkrxDNR?+l|0NVUVO?%3-?0YeJ> z9s*&y2$*x$80y_u*PyG+s1{zjo#Sx1GHq9sf-Plx$p~04BBJJSEUym!<3=&b5(NkK zz43ceS&`it(DL8QDpj1Z@V`e0bm&!rue3_G&F2W z%)akqy`LIpxys>Bib9zgMx^Bl-F?S#7DkS?WfzYhaPC$LRe z+fxCFKba)m-4-W7x?mHL(D~oLb7B5^uBAR(a=R^{t6R#u-AA9;Qd3KpO zHuQ3B26r#c%nW11K`#C+*^YC%?++g2DFvZ4X3Y@D!Vfj-y@z{zF1Ry z!i7ug1WGy4fbNTkeO(ZIu*0n=+0TEU?^*cAk0KE*a6+}@)~pUB1{!+hjzE$Rl~5AV zpcM)O{rRT}(WOUoow7UQ-5@fwN9HZHVp+EOd$i$@NG6!(7EB4P+6xR@!EDdKp~#nz zHYN0)Eq}a;N=K?u(Xatisl7g1jds4QT7fCHVo*;UoVsLGx$Nj985tFmwzg}#yL)|o%Af(g@)0%G z2*6Ro6^6kOJ$Xh=&Kz}UaNF}sv0j@lfnZkpsh!3wBYd8bQj#YHS8UT4SCpN<7})z7 zx45{`QHSeLvJC^bmn3llg00z_!qT7alX4mBhfn&8s-LvuMB%wjpVCs2-^VPdK!2!^ zS6LkXDT~?oGb1K4n%&szoLDfsGp-w}%zcbm*YfZEnomTv^W=}4*ne<#{ZxqsM3M%p z1&6kRWyDBAS_YgR@NNSppt~Xe3QHMgM0z5jMJXJ+_5FX7gfxO>OgT1_<{+fE9H0!9g_lFn?kl35zECgx#I}bnfP3=?7xF>t&?0h<%F+2JqQDaVwsk(79_0uKlP8`MT zOnRM1HjK1{Q2QlvJcFI2W!9;qAn+kFoi`$e85SBdg6wdfnBxFZHm5irX!Inw1S3Pr zaxJmT?vUYQow+Ge%OG}fYLNV`y;vv?o3ip7BL#ml`Gr_;HK&5quYo)17Gty)?oSzX1>Ea&`U zkr)MZyLU%WV@D-Fs6yU^MxRneLe@E-6z8}Y1YM3TRSzB3vsG^XS+X|2SEHwKr+-v0 zQUQf5{nO%L`F%A!U8F;XAiA{GaFS75Oo_*4YQ$ZLtcgPA;&gb)PEB&; zZBZf8+G->zVu12D*OxA_*C%$brN>oR@!dml_E6F?YCY(XW7Ez`P>Rm_1s9a^jlAij z(VuX4AxOz9Ry|vrI}<#VQ7h;&BL-#FG_3@9$*P8(yHUsy`XW{t98OslsPP2rvG4Dk zceaF>q~DBYHG=LO3vRmXdO6Y?n>>D~DaMGi83PZHD@}@3)bR{APc{ae1AOj(b;24f zW1x8Ttd$fN9y>2mIG;%$rGz3SCnhH3i+a(X)bWC-DgbMax@U8DAbE=^hPg8p=AqKM zb5ErqyYp>N7^YuF*U4PU!Y6BxJ2<~H9)r=g|2j+P zeGyBYpG{5O+P3L#R$gdRKtM1TWe);@V(d{JkyS!chlfQ!YzjxlD^s#n)7)w&MT8_{ zTa^O4*Y{WvRSSyqpCM)z!GzXr!#{peCm^l#RnaMKXsZn@v_3m3HY1OqPN(7bAJa^UjNmZz3)sO zwDUzV_Yju#sgrdVG1Ak^s?oh?0$FqGDw9&S#LvmFsF7`(INXwDm15mXsB)&90V16YbnEdYge3LT@nY;?E@x$j*b`?2#i4iDt6V3v)ut^;{_=O;^Ds;Jkg zs?7TONxD&eKcrtL@v@%g@$hBwF%kBwLPE=y8XpKYT!{_F2hV#@#$m!jZ$jhu?kmmx6_BQ!?6SJnKYrInWCL zy6!XKfj*74C0yOxbvPV%yE}KcgHRH9u4bs_&9!84i?gBX-=U^x~dAiW#0p(G}*0-2He&sq0S4C0)&{y}~o9FZwy`;Xn z8|%U$ls{IjdrWyjYW3?$PT%(Z08e02NJxr|y4lqPJ9}^X7Y)z(^uUOi>uOX4l>2n~ z5j_vV^BuM$1yv`MvQ{d|txBAnoQJQYnNw7R9XopAnC+jHI1YCLAQjMtD!D!F@77l_ zIgV+QXkA+i*cKY@3bGveraC(JOZ7W(>2#nfmF8MSZLQBzU&zdxGeoV@OQ^W#gtg+-w; zH#}vzeW$3nu6JE(B8-W$Vw>JzOw9AG$ca8C&~FCC>U z3K8BeY`Bi;PLQy7#=qt}mYBi}Dw@MNV+Rjxd2i2&(A<^RrIUkZzQp8fc2R^VJ?Jn! zJGu84Zny2{8RGxBd{(ee;?!P^MWraS>=Rki>Wpt;Qf|M(6VhtOB)9m4G-)Uhj39v!9HG&kr zRBN$nor!kry_V}1GPVU>-pMimCY&UDx%ZV8+ljl@uiv}*47W%YwOZ2xAnNa1-sET% z=#fP+!?uP2-za3L8Gu?oi3+oW2cb)G?4W_5y`Zh{E(u2+b=0KEhEwrf63>dP-l~50 z`8$)`aM=fK#$|BvEZt@3n^HxhJQQr|?Os$+kYE6b)K+oLXX8KP&DS~{(J?K|JWv~# z@*M71>IH%LG|I*Vo9=^HU}V?djsfo9+n9*SMfF(q#V99&`-*MQe0}|eS>X|T%}aR) zK^@cJN>YJl`-w*6zbyD#Ow#qHuYasrkr=;F7HK;oR079XILdA?a*nA;!AkC7Y`z_L z;nHYaJt0TdD}*Xy@gJj`xV4P;hkzkih2_fbU$#cIIt+pND!A17R^ivrDcQCj ze+Q&Qd}DY1J@*+gGsGy4ugug!oeZM64gk7zY^>&+66B>H^4*b{(O?ke7CreG5{Yu` zdD(#HOpNE$`qsS))yT(utL2NlmOaahoPW8R`GUU*YOY&pFTU#?boeVmWf;ar(EX_p znB-u0b7!uVQT$-7G- z$oj4~;(4VmP&ULZ9G@*N-s#`YTCgTqS_97qS+Gl07HA*dxe|Zpe_|Q~)rRSbF)v%o zC2dlY_fXadKG!BX7;W{QH&8{rPQ5rLi9TzHet~?rZlULEj|c zA%n*WIz#*BA6VJrp3vPL)HRx4moe+1YbR8j%CEJ4uN>ZQ zfJJ8euGhV=ia7ZQFGMTn(dK_sMZaQGl~Y+1xPO%&3`PL<;6ocaw)Xb+`CbTjx@3RR zuuYuB4u$n(vBk_LYh?r2ZXw78I&qmu4xPHU7&DM@Ukm@6ieh#1m6%f6C~s05oNPJr&)Qm>^PgjXQWC#u z;9lSeiyJgRtkWx{?kM?^qB^}**d`tK&SZk)dD(b;UpVJ0h$W42pa9)R!y8qWYi2nD<2(0;kV?r&!qfTMHn zU*nk2{H6JnUnyJP13yuJr~brq2~TrAho1MpqVd_f>w@lEp7e&WCh|&kBkB0_KP-gW+D&Z0%e~Pj(%{$py9BaA; zkB#Ivn-hXDy&b;}UXLlQZ~Lj*nk+VbiVwKK%{V(-l5_X(Yhu80p z=mUfyef!Sxp-Maa7#{Dl^=mWi{xQI;u!6hwx9h&Kf9SeJ3R?c8J;Oq8!G`Emk(j>K<1{n8t` zPzAd}97lgF8eZ$>lPXPjv%S53&Ja4WiWSux*FZsFZs`jfXX|gN&#TjpR~*ZQ(CQjS zRxqjKKW8C~{uvTPqdl?zT!}wPZmSUb&`SwUP0()k z=QpJM3{XU??$i6H|5BW6!3YR{ZaCqa9%z~K1I>DtcE(>hv~yq>l#f)ppUckGk8^xVp{Iy~=$-7|E?);JvVV zc)c<8GR32m^x2d3Vt>N<7ea=wOlRMd$Q@mU)|HlezkZ!?>oLFoOrmHCDGFw|rID7v zNGX$CXM<9SzZJd@3DzxxF@=H=hOb_ksGQd@wr>uo3FAdJACt7fp+7$G=s(EPP_|hJ z%-t@&5VGX2!-L^0@xD`Wm+Fb)_mN128)@WG+kdON#a~@**}7N}!B=qcmLCsENZZHY z1Ov&t8qnW=i_7Zkm0SO9khrTX!q;?%9g%;6PUft*s{2N5Np>?6_vQuiH;`_ zanupjzxy9c=p;`6p}Tx;Y83j=%!EfzsQb|{QWAi! zT^@c_G+H}(w~Wx4IbRbjAcIx~B?a_FZ(gtI9M~}e^INi}cV#SWQEsD!F-q|tR@xL& zIWc87n!Z-r<78J`KZGUFg~qB!*XLOghP<`M_l&e20`izxIO({f!oz4b_`+s|;|gvA zEq{467lJixH69;ezCxMP?eU$_^qYQ0?|`BZSAnzwaf5;Bw*lMl*o`{dT^Bw#OQ8c2 zVkmgnHAK{Vq!zz!zBCzoU}R8}dgpbj`^mVp*f#QcoV=)@5`{+blk zocy-kS9HmK8MmRNjQ%i-4{-8wVc90_`t-MUMPo>?W+DDyM{xNV=G<^ zAPmDVKwUu0Zdm7a_R5~sT%A0;IBLC_ z(r1egEKfD3zKI(xc3GS}og3^ZqKeRqcBs+-ylIH#Y4fGU=dIt!|LU0{|}CG@u&Qi~H~cfA5*BJNY}QAb)Zk_Rn{5ijv&!;Jx|=7D+x z{kUo+uIo$=6UM?Lxot`5?~h)-TQlk)zT9r-$wy$O+`bhsnEd+(xfT(JFNK^kyWaB) z-Osz`KFc_1eDK-&(FqknOiT!=oZ}CnP&DYX-T7u`Z``2E$RiY{SG~rQiGha4SzEwD z8_2AH4o4J}W!b)>0VYx9RADegJ@K1uH+LDVaPau~bKBK@vW=9j_aDa3TeiO6u;z~> z%EyL~UOtApyG-!8cbK20y)iS00X@3*UY%8Uz=y$=PXGq1&lf5pG9Pe$ zd1NR3e1(TFQZI0!ru4Hq-<@hZn}Flt0iF{lo5Ejyo6>P1eV`-tix7RS27$GepnsI= z1-MzC4sPuGO}o;yGeaxw$)k`$kccs9#V90_OA*q>$;k~i&63M_25m6PF1XquVZXL} zz5g6JJ! zLQ)U&7n{tM9^e3|2aacQpy41hN*`AV+2eZ~0dw-5w#<5XyR_-^#xd0ND#TT0TJ=#j zd{6MSkI!e>#+jTPc2=YL<-MCgd<$#YbJFWQbk~EH`qQSrI6s29MYleCQFDzpfMrWu zPy3I^W7ngK#Cf_z1mnLtfB%Um@cO0i+7$ajFg45-MhuPYfQ0Juol|5UceVqEa(IG! zoplM4KCuCEwyx)CK>Cjm|L*jFB;@VVVcU1MFc%R;^j4E8m4<(88Kf_hvo}v5|1cO+ z?UK5bv{_N{1fKK=px@fyIgl|uIb;HBn(-~CXI;`Yj)fizqoj3N-+tNLZ!Ej`&cd3> zNy~-LEM&4^=FEaEDsb0I5VB{d%J6}l7cd=tOQLboP(T^2I~|IC1@qOav%o5MVLVD{?P^xfGE}(A1(mqVG|H`fM@>q z47$PNmGs=12A6Z_BT zara$9r}KnH&o44u4DW|%W>A!b5nmBDG6|JxGnLeO~PGn=n^dj##PW4MrL>Bz3*D2-Vh=h+V-M^z(6aD6e~y~2_4%-Q6a)0h=Y0kX!$n!3*F*}8UXo!GsMlT}jcu|thOO(A+PW11sT#UUTV1!-#!dgAT$?K2TuHVR&4*YDXpiuF`EgDQ`ajGrVFOYdBi4IPaYNvoe;| zR0jHoN~WBHsWVzYy8ziCV|~Nms*Zr>3bLFiSV%JJeom<Znu2oc-wcCFUH~QQDOnmdljBtpf+)a+se8D*?VMy zfYZVV3CW#jXPpIbuUb#fE_r!twtzZ)ToUV6LG(FK>v!a((-v^)M@yF6FFj znsA^rL4E^8i~HLd7%phKjUTr*3znk<*^Df}xv5YQw0F{{&Q91i1@`l(=CgN|FRsS7m z4cl4VMK(w9X8XzQn}w?@)&cbnlsC64;jn0mbTC7Bvz^zKzVkvgTl=Y6>mMn>P#I`X zY+&w=5fdxkSs&+7@86u+xJAB85NB*iRVI;^-{1Y*>2Rm-e3auN;0Clx=6H{?YW_U* zuh+Vj>VPPVJ>1ybhQb};>fk4Gk}gqhyle}A;-XS;=54p6oXMvRBqWkLEo5`)sNHJiE2kDA?}m+m$0J+S=9XeJTrzp86Kc&J+OReEknuyy_afm&XSW?GqZ;v}OCr}geqG;*$uQJ6SK=lc`!04R zl){xoDfr@fzG)lO>xWcfYFN@9WpPy8pbdJfo8WESsmC*U2*u5tfdOT_`}}Axl06bx zFdrZ}m1~S0;=ZQ^kF>)(2qrp{O|R@KK%s%g2kV=gR)So?aMrIj%s=#cA1A=dUut_k zV55!sJc!KHP9Pth*^0kyJXEy%Adj;$GD*-sb6klnuCmDRu0-vnnb?U=j9V(DISD7Hj(v z74vn)Lp-vx;X^BMztfRkyEjlpPmA4ipS_)#1!(@35ruouH=|C1*ek`pI!u~kYPX~n ziwXsF|JTaB_$7Gpt;5#DK3pG}qosiEF{TLaQU_;IK_-7%3t5zsS&i5$d0Jp41ba=& z3>gw_pqvev3v3@SJ`UZI#f-c1sN4 zzueZPla4_-EL{7{6ls)e^!Ve|mvy!vjwV!|U+%cVrF6v@^S%Yp=pHq2g4*5^6EHc7PmRR~ zI7w*ZRqI%=niR5apf_Ra5o82eD=Npkmkk~M(zF5=Q7&*OH)o}$oou*Ksc_nQ8X zr|W=fYHPY!QBffj!3GjRdJ_G)=|ZH}P<=`XU3v!rLk~R^X(CO!5D7}} zRf_b^e~|b6EL@A_f}3;ioik@<&z?O__B2x1uC~;oZWH;xAU+96?28DdP-9Zb7x$l^~B(rlVH zn&W6njc!4^M+NyyR}b*WkZU(0I28c-)ucr1=@;M1YiVlLl$bMr{Drwy@xA0YTKUNX zxCvX3Rb6dgjh!)nXrx!Y&>i1S;BDFgZu58~ztMIYoic}RH2i?q`}|um%0#M|_g=gt z6}joTcxm{S+lZ51&j#4$kc|Qdc|`4~onXx8>qwk4Cs*1{vOC*PI^X@1?BAZT;55{=^Ge#e8W0x6q8U~Y|dnQ{X>oFxl^9f z?{d}p@3T2dPo9`rUofrs}3!S1}~o7cC2i zjdr$1`N;@#@Q-i&KIL|)%9(B3FnRT5*>ZK!GNE92MZF*%vGk1gy}tt%YdvKrsofQFH!S_T@9UMNbP>tCp6}WYn+!+( zWx^(l!M|5lo+zxbgSB6t`uFU@F{x_0EDtRxDoLe`f{SGyQk_QgJb}>gIV?+$>z*1y zk#KV`{MIx&X0F*4)>fjCO+NyZ9a6`4!NlGcEMHQcF_7DMeL-mPx_B6Eyn@s3cW0Vx zZ)1&0is{9@q~OHC63&u|ae|73=_6b%@AXOHN0Y39C7k_8sc;}gx{nHC7; zot+)?(kA3HI3gw%dv~y_({Xul%Wc2%!;&si`&^~TD0&VEf{dcH45e|%Y{wrI7H0|D zmvy^hSqG^PAFc#2LpZ(?Z%M0mn(>^)h|Jz z$;T9jx#Fo8_3(kf-JowKK?3HMR-ds${ zVunJU=ECuvot@=3)r0xAob+ivYxHoxZGO<1`~ia}25PXdP8vOgOt_^=w`d2MiWFV! zX3^LWKkju2TouSO_!cVbJz-&xs8a!@g%2*{Iyd=^0(Z!~|H+Tu&|zp`}^5zbe(fAvLSZ zK?&h%GW8d~hAq=!b}3nDJ`x_E6i$7yz`UPP@@a3{L+I}O4J_t$@>8a3VVkV|h&Cf? zX*jq2{)lgT@t??!l-K=JSsO}GqnJEM)1z?4Zy-qM)k+ScNUM<=DkEZA=)&DZ(4N-ZuX6b_FUaR)G&}s6?`;$sbuC5szHIR&kG@s)an1#Y z{e19z`d@r~k+bD8c}R|qeR*7JV&c8K5>>wgw8XqD9odz*H_6}pec;+^+8uF{=aT%RuSF}b$xf3J`|S2Ymu!%o ziSrKSi@KY;3-h{XVcuH;iz(vrzo|@J3K7=&FQQ9-%v!;upr5wpDou3wHpnVx{V&^Y zYe{I_ffaUS2HJ;`Io5fM{;=(xVga&{d@`9CAQVfwZ^k{>sAy@Osn!t}SvVc{>xSO7 z#s_klU0oeq*Wa5hT$weVb>R6xdppmOyFjnnYficJN}grE6f^CGT2AwLAwiGP-G!f3 zQ=3MA)Tf48qOAYks_+GF)obt8UVwHIvDKERuUnt~h%;W63+QNWwf-0(dL(QeaAiZX z8R`BT`SdM+xn){k{L|K&oQC^*;8JB268DGp;c)W&kyoRld>0r}D$nXW<7BT=%$b6k zTQ;UDX-yH&`@b!cwK*a0?~#N~pj&mTrr2-9H1K%~Oei2zYAkw-aVqdlP234c%mg5N zg)J1lp|Zvdf7kbx@L|q><^A)XH}yGvED$^LMb4I;)cUA57GgFbI@0hv3pxpzK`P1K z)Eg?lY_!fP6BhmDS$4*gikUkTpXf8uof)v}9#aqh4r{#7RONAUWR+*|)7h_!=k1cU zG^7>mg;hj187u8(oeHR>i}701d;HN}LH!5zpHusiMOQ&1>q*V2DS->qHeW?kK|FPG z2px&^+SM(=f@e?BcCI_D?r7OYFfR*Zk+v*5|GlIDee_+zr(SlkYzo}tvoAX^l zV{f$n2BNRF>{84N&Y2G{3si9Fh9U2ggwgy%6IUt_I-Z-BWWO_Av zw8TbG!JzwPR678^gvuVJ-!P-CObTh?{mnl$y0aSeRm|zn3(rYUtg`m+^5)+$Tit~1J1GaC-?Pbi#?Zk-fJ%edMZD7;q_dfQxon65V+lWCiVeFCkvGr;u%PMkfdUwRL>bMQ7;s3OFJ1qA#^CAGFTS^HD$v+yKJrbSk*5B8+TOe0-L=|TXoeZp**OzFc0~T+6qE+Sbu5SPR z?&+B&#VVT=Z_P_{i|L!BlCfQR*LWY%deL(0COW0|Rg`n$j|0cUdoe%Cthy)H|y?V`YR@a%2 z_`+VI6CF~_-48emG&mXt&ECMtlI35{#BJTGTP+;z4iH|B_qleUK%%)qI4ocZlkLSZN_Agm2cj?gXOGCdCo!LREP7 zMTPV|TFUNNd2!2_zxPj~6|N@V^rQsx)b7C>ii=%+(&ZF4#8?>ZZ|HXRUqB_M4y|kJ zxQ7p=H3t5Z?MQUoN1TmKCs|vxFtZh zz38v?O(CP>oyjWMo1R-oW(&*<3>JR6PmZ_iZDM8}_v2Fzvk_tr9TNZ5pR~>c8X)y0 zh>}>XaKXW=u&Dy&m~y$fOI+N)5_=RVcU-L}#BG|uC#9^v7BDgE*&vq(bDEFC*)$U8 z9NWkXLxbw}Hz!qx#&$&O5&7O(ssjt=6Fpv7Ro%N+#Tr%v2ZcF@CRSwC9@rG9#)Sr?-QEu*5*trf6%y3EqMN6#dh8xp7nA1{P%4#6_^T-xJ3EWpqoNGg8Nk@-5r7c@)o5< zoD__I|LzM1ch5%p>uy;?Fuw%U z&Su+{m$zrV64fm-HDq=-HV! z7$ijVA`H(kpZsfVf$92WTG64^&JK93ykyhc;gz0ucxt{iA*+S`tF5(iIp9sYdiDGc zDRWTmiW!x{M&T7$}oInf)gO9QMWJT>Da`o%3ShvKhOl#sA`Z^Om@E#0{CFhw-WuK2XgsaCoMpsKA9-b>;@0 zuD&^!-?nzf?Y_)!p``!bF-0ho1s&((r~Wi;48Psj*a5MM*;W19vJ~S8QK#Y+N+(V?|G=^ zME|s4{@@&Bqy}ATt(lNo{vGxbDUisFPGPV{ofl@%FD0?1^Q%8IA`8~QufClA_vpDa zRA#q9s&rVwdHy8sNvc~9!C183969C~);#w3IL1Byk+)M3VQw~^nGuQ;>)Eh3p0kpd zf-lOZPhXUD{k>S`M&A!Hr56q5^Wt1ZaX$c&|CP-(!Z3f!2rQZ0=>Tb zLi3Zn)J?&KwU(C5rLLzUuja3FK9UboTuL(@Cwdt%)Z zme#H*K>BTYb(Kci0*BsRGepGL4e!m27|<0z=L~0MR4S{(3&wXx8IA1#59+&qo$m(-a# zNH+Mp`rvD`UEaXb44P<(*IACy8r(Qys+unq5eCdw4xFGW^BHgzZHV>AN?uoJGWyF>IWc|XdD7Aicp3s=BpE%3W@fIU}q{^qmsl z*6QuJ+h%7Q%T_PrluK@#{pW>joS?edD+W;l@WCWDUe`2N$bS`x?R$nd?@as!>1& z3=ZUkG%LKQP*#XRCb{;K&XTWD&zIg8T^+B<*U0|SI)bVbxPC@ads}K49N$Ix$m?)E zd~UA=SqwD__@zyV@09Nu(q8p9{9t;!)EYm@sW6O^Zo)xC?!j2w`f8|?hCTDZErGAFGC4pPKJB&uiU9hmX<9LvTs^~dD#!j2FQQ=-m-}BDKgbt}mQH;F zz4E3OmN?B$zj!#@C%#$>wu~RTZ!EvVas2`cH)nw>n?rMlKJCza#r@I^L1vOK2<~+w zUvQ9MN3HUR%2?hEFj8BzE_|C3zJ+@KAXvwa&QFp8Zm7{>O84A9jMVm~KGDE`rmx{n zfqIbxz24afzM|ZBUj~p=a;j1C94?6!?+cNwcAQW|j3o}pOT-~~9!&nqN8WIeM2|Ks zP)pa9m(QX_l+>H=`G)7o82&~h*|g-@np^0wQN%kg-tSF|64EF=4FCU_d4{?Vni2K@ z&^PFy8lf|uS*8a11*vx>BbZX=uok)aEPPgU7GBHz=f};y+v-k?Y%}j3#&V%M^YJW1 z_GKrL`zlMkS4ugVjj*uhK*StkU`a?{eRS6h9A4Pg2eT z)0ghlaCOQ9OpUYfIhk~CabB&K2fNVIV&lCUSuDK^^k||s9lnb>v@Qa1sMlM8)bz9XpSHiU*r`FTpwcb zK$2o#I-Ke%zl%F+*_k77l1VOKTm23$>}oVg_fK|z`Kx9mXD1P79ys?NP=_mL5mtAO zgl8LGG*N`BeS-BwnZ}rVjYI76Xy(u@iW>`3EYj>j1MdtzB3J?^wepq^8XQI1Hhz=A z6?k0vkhmQO)Ul6{P=&LLOZ+doXH2-tOF{}o=~`Lp3oQYXf;Cq<{|oXa zY|F}tC@mGqWJUypBStniNg8gU1RnQeT0m(oNMY2{d<;6OTsaF3%(kC|RpInYL=X?AkMk;iG{s zO^RE;KQYOH!Hp<&BcmL(IKraFwZ`vsr_h~_yYp4$S`u3?BSpA;-h;KE^v)7T8=D^F zvwr{0L&9pxpv=Yb{5RQA$!3wzGh6qNlU8-Dn*&@;wBjd(#d3dxJWJPNFt$ICAixY{ znam8G>wylztfaxsCtz|0T3(@ZQIuE}sTmmU-ZZ@IoJ(K=t(6$OR?4==7+Hq!_4E?X z_<*>+%{Oi&`rm*`z^UakUyH6YuOHxS`1SQaP)L|xl{)-NP?6EtM!?N2`YQ2rw0Lb% zn{LBLW@?@JKZ5WRn0qHnKz;^8Qw*J4dA`FbLw->6o?(z^*}V0%I+8zAzEih1E&>xE z2l#DTNDd$~ltKhkKJHx^PkI19ySKL+s-&!F)ua!Qew>(p|G5x>uL(RobjCQrme)sp zHa5&~fkdT5Q&5VDcpopn!8joW`XMe!{=;Ml8d2yj{;Sq=Ttm{`4oECIJVhVRxW*(g z&+*+sdvR|+m408NlI{)PW{6kON@sOz6BDgl4Z>T$aB&#wm=!5nBz_VOrQvA)L=DjF zMJKz?z-arPfVlqR#uVpJ55>8eWS3E^m{&A7@PQ>YWe$x5ML)y&AR0&_L(NEsXHY)tdhhF>Ki$5PrKatL1OVVSd7S^)^yH(+7|z-(*QgS^ewJ3;xMFl>2;=t@ zv-l@1;SnOk%te)DT%kIM816UuR|u}Kr)e{D3Xe12#3)NTrIYf7H}#~5rkLN}@F?oz zpJaVoT2_+Q$0uPw?$E9;?CM>$f8_PQEV%WK&J0u$uAA95sReeXkut#tBdr^(hJ9hV z_t~kA!g=@t^wA_|&n!bwHHR*qTs>N>N}1V2zUX>4m&U%V=MT>R@&k^>KuviB3P+Rv z-uDel3$v7yPS}f-xz;CqT&1jmrJOo(CnK;SUdJ83sph*qd?1Mn@hUKN1^~U;Rjpp% zJ*unbXDvzd60Ca-c;j4#)=~gMFPk;xdOl5h^1tNum$R} zF*7MLNuj+q^Urk;27*HW9p#zs__Gg(Pm6>u8cKF<{Knp1(?C-~AOW&;GOE;ka-v{^ z1WuWU;=NL4?|Q1Xnmq5J@l(wMx-0iC8YW}{XQ%Ik9u3rKJURzKphEaS1C*+23|fC$ zx&W`1f9o0dTZgie8{%zqDq&}@XS{RQ>wzY1C@;s;8WL;@0{}_MtlvGzewH2Gpa^s? zj}JXey(C0$Hhy2uz*BM%kq{0e99}+0Krh`;&1Izqc)h%H$?`86D5d_cUD&t|1TiX7 z`IVNsYJt+jiplE_MTp|RTB$B8Xa?}XXg5WCpfNL3c^S9&{N5f&mBhne;{w0J zRXL&7D-lb7_9%0UX1^60-yd0?K1yvgHFA3OBXH;dw747;%pNd?@1_{6K9L|;%2#v@ z&XS6*wW>W)Aj!IlIGch)l0?>B+KDulj;pe+%gN#lz!Q-!4i&t?1OdL5X|&*xrVkKl z+DZt@g!td)YoV@N<+&BK{z59sJpKSPtPp9Evx=^$s`|y*!2Wf;!r>JEd*YSnl^YQT zKq9@Lf2*w|MeTh8WEtOZ)*Kz{1mWWwsDNz!akJ%y#}y@<03zG>8fUN7cX=HDL#DbC z&MIf-$oo83#1zueiR6GLC}vLm5$mObf}Kc8hG_zc^2IM?0RUiatU z0BbHSMMnjdx~%g0dTp3NtAKh+D3H4cnkD&XE=~S!m><+A{{yBtCaziOx_zV%JPN;M z)%}$h05hzC!q)t#begK8cr_%-8#k7!%u*no$Jx;r)p7?~LZr*UMW=rY#@T(?OD77WhRmFBSr+cx3(fHo4#X30q-XzxV5FO;`t^zX0tePSxzq#95(4EN%JLjNfr8 zw)v^NO!5bzv#pgBem?6BErO+=JZ-G91nPeXvTB6l z_V&&O%%K9!5&0tu>zWep!j8Lf86gVjbv^1Xk;1sG(NX;@LSomWp&^y_5}=}i(^6oI zo&#wI{>c>>iYvTk{HRx1j?Pb7b-zv`UJ+2QB0jmhUx09&X6P#`l{P8ypGQ_~D-B{U zl>(fdErbgny1^;b5|vr@Bu??svU3MrbLZD`*7ZHyWQuXnUcMi^A@52Wr3Ux+|D2Zg z4I~Pc4^G+$BWN*^GCVQ=lXd`xFO&5e#6Cp6K(3W8BZ@M7!SQio7ZSwp{YK^Tb}6)= zPz(JOWdxYI>oD_2(3|JSocJ$EelRtt!Lh=1}T0f-*Xg=bnob>bwcK{^H8&jT*Px#fn?=K698BNVA6AJ zCm=3f_p?TfU%Vc(oW0qjbWV-{SViNc5Vc>!q zR`W3A{?`zXlg-}Lb%`~DeHc8h8{6wLIuZqN%JH$mK2X0r^Is(S>98L2(%XD@)hUYa z%5%X3H>$h?v{PrJPHSB8|YqbO15J$Q(Yuc)V6Yv78S$hVL`&)vcn%`8lw< zEz<|1MqUEm9;_Nhv%feQb4g98dX1*1&-0|SZ;QOnwcje?)cp`OR~7U@H?05gHEAri zvmGgV?LMG{${$pLf43 zES-0o{YJi3OiTc%F~PkDzeUGzsSfHS(48FyT2c9hg{vzoukSxDePqXJ z6GW`M9yOzjNiHQb!UOq`617y*=BYmYm}kf2iNf&Bg7m1l#Un33XK@Bh1B(PF5nP)| zE`Hs!XU7wTQxmyasMWhY~0vAyuY*19I)vHNjsjPCk&TpP8oHX|dWUHz79AarbKh^Ckb;5k!^ z_L4GU;J58<=NK$7x19@6dmLc6DsId^uxsmpwHj8m#dR*r!9$AWol?qd#hQXt$WNxK zF&b5UMshy09b>n)lRHWTdV>7PSII9Q*wk)4;ioFb7-gojKF>(QUl8&K7Is@b3JVEm z#guTC5-Ez++#cU%NMyb5WTvM8aJRUO&1)hRFBW9>WyaV-5$CrTUkr`C9O{DpJ*B>I zJPS;ZQ*6oTl|^aBw16y`NQdHt#Fr$2vFm?;?q+~&UVnSZFx`|Cr~?KhUiHmK5X;Ri&L**-Ud3ASfe`8L;y*8N;sM4Q)t9W?DlN6~3PdChDn9YIbUrM0%HBjK zg<6&!R(js_bOK{@Lij)g*Wuz^?kOP~al2n!}u)UL6sYS|5h0(?5pQH;KU)L=>aJ9G5 zaN+IW3&&iPj59@K5xO=wuY7GYsVOZ*;p~!S;8CV>wME^v>{kwXufO}^@+U@3-e*$y z2a>t%jj{2=P-BQi#gN^-F#n7{jx}|4#nlHtHUP*y4fsdm+li#Y#$dDG-@4GGcy=ot z<^l=%g*Koxk(_KrslOoyL@|?^ z&}JEOxwaN?A_)SfS_OsX$Nl*8;DhD+6LX;uJ|PFJ@BME`9qOt)7<&ENj3mrp;K>-_ zzW-}_I=)Ds`j%g^pXBj(49N8lgM$O&OF2QGwv2N@N{d}yf8dDK0<4E8@G<|R9tV`~ zuUpc4RfAE)`QUeRb7+uJkj$#7kr1rJFz{7GwplwCYw(GoXYNHBM-S zb?xyl^Lp66-npb$n(NV*=~B;dJzGgo`ZNl5x*AN=5!j40qJ#)FB*g0`_8BET?$M$y zg*^RfE1+smeycR@Ik!5Cymchm`%p8X@`JG<;?PR*?%l~ks&LSRR&P5t4Rz^k*3G%r zFkO07jBZyIPm+!p-W5Fz^6XN|M8N+yh6 z@C;VBRd#mSNx%}CI;Z}yDn)k07HSvkHj6YhVT(`k!TV6>0JZzQ7}?~3PW7zCSkXtN zq7m-4A2|A>sqR&)RQ-{NCk{<#`cpw(hCDAnavD1FG~2n=HN3cHmpc#UkU`gLUZt>B zIY3Z2RK0y+AJQBV6NS}g>sa4j9!M4UJREPReVB{@+-s79n<(CH{S!`NoG|QZhs`X zQ8;a%TJ=nnHW{UfzZQ0DJJ?HaNvzweWX&^NG*cl6b8`!dKm}l`++LaiD1be%Z=(za zXAg`(fM6`d_?aTSCGHd#;p(tNk4IEHFYhOdc0u#$4(nyl9E-3J(jDmz2NO&**sSvZ zXj@=0ZOU1l!>c`ItJzMa_O`bw!JW%aX5x8Pf%n#CmK{dKf)|n~Tfb@lj9Iq;i&6V#pjR ztYvpCzTB?%dX`0i6gJj$t}^xF8hSZpLh+0a;2M1i$nbhqR6mE;ZC^9?(8J}nZNRQS z!#Sx&IW>l(B<(HaVob^6Rg*aa4xA{?YjX51Dn+}UH1fcD)2`&+DQ?<3@)fh(a?$j> zt066`Nioyy`z<+q9TtWm4h#ffFr}O{5gNbE-7lb;kwXicy3=JoE5qnQ#JiVYuKE4P z!m<4~xYgKL9{b~&x^hIkS|BD^P=MSWrgGr*G0MofK6eGEe2z4N7RZ#nAHTmEw=S>R zr!`;6fw0_%zf3v_4yqNgrOe4--|;vOToiqp{n;kp%Rq*$;&TWss~I+`gh-(pV+z-Z z$)tLI*YI95$XT^@hUh{rE8Jyo$h(?GNnv=E@vj*rv8c*#xrwPqNynfKzrhn|sBVBJ zx52?d%L-#B?b?L=n@)>K^Rfj@1;Q%Mx*{5;a3>?D_kZzO`S;h&S_;hY8fq$!q<(~d+c4)OpDM)N%dq1A1|nQm(Ra*P$v514PS`8 zZn}mTHM*2@E^oM!$FW&nlqZfR+|&%KF;D7=9dhx$?JU~3oSe=I?b%=u?~d9xpZYbR zy%iV{*r(#4*3X-1>_pzZpL9ltv;P~jQ1P9~Abn|WPy}5fOLt2o;*_)gT_p>^J3j&A zlDMIg6xMGxS4R?G4jP^HyX)C*rFVtgD3xFh z9A>y)-I#{iLKGKWJN*48l0)CNtxvd%rANo+hv(=`5}saQbL9C)nl_humN;+lV$Ujb z-QQmW)sgRH&x{pgOmUUXE%_l?^#}89Nc}sghY}RUC-yeH@ygP<5P3w*au(X$rCvn- z{tYe@c`{E?e-5X-KA18x*eBHaKtpGvUR<}}YSk-?LMJCwwnmwT}>bUFyLDi;w zj2!0k5#FEx$HyPu`G^p%jcU)kt0QvVd%bZ-;#IZthS~T*LdLhsg+s(^(HAR@T9 zkA&@{9D{)+qods{jU)RnNIFQ;DDSO$#8T*2JL3?4kNvmNTGY(~SIV?RrRgo4X8LIO z%nr7@{=D*b$gt^njMNzl(SZ{0JZ!%U^Gr}~sVYvkW|1R6JK6<~ng{~qAt|`Q!nqHENp(|y%*LBokr_d3|Zlg%+%zAuJ8k~>eQ3Nx#GEM^e^2ceXlf9 zp2ncIw!1#lBM?axvhnr>I3$u0igguQg2e^b^6CcZP`7e-EU2(Rqvp^tSeb)>Pj?2E z7j?bGVmKYeA-zTeeNy3=+}<%b+~3Q6rk}u9qY4OOXX#ei1jue@n1uuy{Z(_z;kW5oYTHFcZ=QA!1IKBfjqH4c7l|6 z>{WVJOCeFPg3*6#nXz`UdQ5*8a_gE7AD@l$X9h73(7)YlT@e>w6&O=qUjF3ClZpx# zkn@9KbcX7M6||rlHAn{ozaU z#xJLtslmd7pGMf9bW|55@A;=>1$;v;)v;qipt3Sn?``a$?!#kHonrD!tGcwdej|D8 zV1U8<&@O^$g_WdZYFLU{+e{QXkaGX$e_e}y9*;w9@sm=GU5m$WZQZD@*dT5V z&`Wr_9dH;xKy-qkGycj8fS}Oy`6UDIgGd!|wm>zMjd%}u9iW3Fz&J(bA2rhFpcW3P z4i04P3GyZT$j)P5&sTad>AZHd_FWlXaH$PwK1!-5LqUOyqgh&2x60ns)6?^`Mp{~3 z{j6za=)q%95|B&C91s!`aziQJ^P5Pnuiuyo6R)(NStn)iipvCz3@`2TSP?H!)GBy$g=RlBqCPSG4C*3o#lM zTL@-NnS1{+KbcdJIBWxe5E8d5a*N&Y zZkj@DIp$jk_h-)o4pr*asYs(Lt&p`MIKd;D&zi7R`PCamMT?0dtI*8yg;k zP94u;dyiN874ByAg1Le90tQ0uFL9NoCF{73!W`$d2_Eq(P%@lq4J*{I9Rz)4q#~TB zO3QI_P5N~nXuHTcP2&j5fdV}XjXUo?&e6Zd$p9#i@1-2kfmv=H%*WKJu%1Cf+#32v zGgsETSB^WUhcaqeROrory+NTA*yow%e;^ zLEK&Gzc1k}KW}1aDr^GuWQtxtKW0`}=sCu4bEjl!z(cwhY0jfS#DD%=F4#p`PqR$E z9o;u#-HLO3n2yKe(^)~jJ8>a3M>w>jj{6Oc#%NhpPf5Y|urF^&F}td|EQ#JeGmWIo1=r2C zR*93@!n%#FfdbFn35l{H@$lj5oet;f(&A#kV|&9pG@tJjXH)0Aq`qy22E?2CvF?&i zx+%0IUHRt`LFnU5MZ%ArBLOA-qWF0-jIq#S;^6X42pcw@COisjffrGwKCP|*Lgxw` zhr=ItrYP9@#}=$3CSdc6>1%M7;#^IYibFZ9|%)vcZ^j~&-Dc&tS(a-ECm2Q5nFH^+!} zq$2|V+ocD88dHz=Qgen1$148}R@80vNE~g_y1R>lGRtj#8fkjzf7OocoO+o>M0PKlKqziT|QYh}i+Km{Tn zr7Xh!iVf%*XT1hoC4vK)m(Dt@004)L;hkF6YjDiBCFkm?Ke9gHILnIiTA#KEH(zEA z1T!=am)pcO33baRkC~tl%5bebrKW+xdgrZ0JSZa8A1~GK+ng-7ZiG#ocb`jkSv}2e zd}-__o-qsGkSN+tHOf4rI8#7+@u-)lyxE?XZ51HB=Dl0ET6e%xpkM2}F^d~JUUmT> zkhs_3>&Lgd%m}r$Bj6h~P(THgb&1GJ#SBe#Y*vU{k!?Sa?yIAo;3Nh{`fJH4J~}8w zB-t61)ZgIlt!O@gUTYlxnFaks-D+ooW0F$?#Kz_2Wpe*#5K-`s`dm{6mbTVm3J>V6Xh3FB#vghcgejE|FlXt99-b62eh73 zvh&#uk<_e@y06+`=C=mMK07UK7ak3Y8tk<%1GvHjvE4u_0rXJ`0MsD5J6DUjuvB(+ z;W!hK9LvrcF)bU85sHx}S~1uqetU41A6i#DYXZbCP=4&p4UGp?UQnW$TYX@P2yHcn zQkHUg%+EG|K7sSDys3kCklzD8&Yp z`I9qHhR-dW66@I@fC(rZ`u-pPG!?+ujf;;DE+#DexCC#BI;9zsMQVb`5Yzza{Gd>% zDmA5?YGojEdin>>L`d(OCnKX?if}+A_4G`R2eWkXYB7)GGQlwU#r~yQ{rVAW0NP6& zPPmgZhyywIiSF*H{blX~@W|@^v?O-1=a-Q&ux~~GulMAY^zv`muV3i(jZ|;2hqr)- z1dkf@4OEOBx46PgGJ*IAeOSws>b;67VQvNfJ0ZimVA>CW(mN=jmiR&NeEVsN6+W!P zoSX*UY2;nVY%@{RxPeSi&H{1h#3>}1?FA`ahec!!1`a#>qA$VyaAr=0O4adi) z3U+Io3sV!eyVGrwVf`KJbw9lW%FhXN(28qV?&cCtLicXq3cJ0pnSeeMn>h*2TVh4! z2p~ho0LwV5?vN-R<$-LQOw4<JikZ((y%xXx}0ubfp{ zPE;Xm9v>Zm*J*RIZBxSeG~@x`5Z|N1>vDSQQ48G^;;^c^^*sH%Co?p?kY31n|0fi3 zWL;|eYAv{C!Kb=guX277F?W_|6(#9{-iDKz`osGW&!eUKZI1f&8!iXsi9+@ETZ{dt zt=fRgXEzK~lq?du&C~&_?3c-7>#|1>@Cxpz{z!MOrfTIHAX2yD^ld_9JtSVp<8Zj; z-@knfcY(uBJ)9PUx}6+>nC$q?$b&8M33hVjX5byYUUA*ODp|l+c;MClRhF9n#7UK+ zw|BQq%=M3;W6xme80Wp+n%@4>$H`Ro9Q*d*C*^B@J?S{7*n)rvLb&p&Pbr>qo-Da4ZRN_RllP4le#0|4p{}|eS3JC z9pQ&nUu7k>uF|D~R4!>_Aaprs)#K#kM4u&0jNcG9dkn+-o-EL9fJXgAWeSN_W+WPn3qteoPi^Bt{;u&#vt7e(4{gLt#gkgMT>`P*o ziYS!<{ie&Wk2=_8Y#z_>0lvOK>t#!~i0j&`B$C%*orl#7B!lzaEQTkOv^FiI#9g3R zZar4#DJE8p!Y@uV`gGVfl=9W zF{)*3!WgS2zwrJ>j}ORwS#x_dmyWjFi3z?ZQVu~l{=(HAwdJ_Vk4|-+{5C%Rok|6U-k7bX zpJB(9^m{IAOe2pC+w6AK&7xv8V;l#pAaHJNwD#!efZp4q2vE*DW?C5-JeF{%KXR}y zot;0LnqnvA)0`f&Lmb&9YF~o(hFg|`PXP<@TU2tD!>_z*`HJ?LD779`;n7U$iS*R7 z!rE=*6ytYUjdtw)Zz>!;AYW#!sZwLZ3hd;ShIucl`;(K4?az-!^+j`(^3-ld?rMzF ztLBW;LnXkkI^tsW_uCYBj;6t|3N85sbBTkUUEVHRgVnE8(Ul!|8?a)RZ*oO6%F5uk z-%eKcAFHIj6NR6mlPlF;N6W(D=Kk`dy9921oj1`-Q{caUemPj>X$p{93e4V=tfgmp zY-ZR{4@Mt+9IDmbF(_eF`3z-0M?GCgMnVEHmxD{55^laD^&rvWj(<<$e-xag|5hWM ze;yxQuuIo2p@~i@6k`Cr$0Q^rEIO*EluWIA>}bNZUo&&3xYp}`fu=`GfE3j!7*6s! z;cv?H4*||x^7_>mu~USDz9qzsOF5ZeM1-E@8vO6oKU$=p9+T9>b2f(-iOO~51yO}S z=9%Ozw=;+7d>_{<a zb0q)7-hoLt?gWAF=LSj!Rxl54u>sdOwa@$C`db<~s;5{|eK@1n)icHEj~CYe%_6{+(peXlg*Ow82?1U%I&L$Wr-qACu-$;G`-2|`GEL%VKq9i7{_WP zSJnLOxA!R`yWAufhh}7M=GSHXAh%SoaQbjfklkwedJZ1JE~t~~PIWi)1O+8e7M^3XRNmo1=mU&nLxn}1ooV_`ekX8$aia53Uv9A3oY8~(4XYmbLA>*LS1 zZ+SQAHZBz=X=}!9yhWN2ifE_IGz?opawm!?p)$3L#x==W8kuNN7*-9@QWV1yVi~vE zFzzaacE!t{b7pwk&->@hd7g8Azu))w`~JS?d7gR3NqXOCr?#QNh0A_zE+Cdd*s^*eH%#FK@jPM}*oY{*zo~3uoI5e(- zU^L4=Q;6s{yK)Ux=J6@&R1Is{h$|!Y^)6)uR>>gsMK!B$)D_KSH#Pvuz8Q}y1+zr_ zaMW#nY8tSX#rcWyg%&QCOt&}qvkF+RqM)8w9~=2hAx;lp+{PERXw}LfuJMenoczH* z!vv8Y$HCk}&~HY+Mscm09^-X_t9-TPorw?pGai|3YcF}ih=PptbT3-6lb;wwa+#IS zR_HhLpXr63N@xeOthZ(8+ZxD=tp=o`PnA7TjLs^wEU^MsuRtFZN76c!2^W|Ff~E*= zSe~(_Y(&oUpDrFL5PZYT$Z4baFT+-fj?{&QbyZ0NMrGz*D1BE3Eoa4S+O!E7)2XMU zBS(nJ)yQa>CB1@l=y{KKjS`l(Ck!&6zLTi$Ae$Hkz5<_2ET+$;OSU8_!ZY^Wk$I*O8 zh`UGMU1_AQh1|?Mzp>&!N`$EW3{_lKR#qPfh>3>M#Ow4=6IITaLJx7_au5H=7q#T? zA4waI#U0p!{#rpxC&-&bmA$z{>|idA+fO8|YSz{DaN>^V!^20}OkQ$+PT<23T`Kr0 za0jsZF+z^GWHn1`rqD4SB9yly^sJs{W@i7%I~&Zl?HmQyQ$Q#&Cuttnj?Ixl-e9TQ z#mhe+mv11fq`;hFUY&IYul2NR%3TR&@yygoPLIQdH}|5p56y3;KOih_ z>Khsu;Co~AjJ2*MLsdgwULHmbbG4xrQ_@ITjNZC`wv4>{ghq=r)!s~M<#ESTsR4`eF$#doDM8>WR4_}i|hD| z$F@(Dg}VaTnz@H<`^?sf9l2)ruiy{Yht?K1P4b8Oq4A>jiSS-B{og6kFyk=S^c*vD znN_P$_f;B&xQDBtz~}2C+!MaUT>?rWDWX{CWQ`Gcl=r6k^k<6?;6V`17$`K$f|_;1XMy%v@!LSb^i<&eMsT*t_j`io z#si*QGi z{{=#$7WyEj-1)*;4iO z{8!74V7UutKur|i{TYa5yzDJ2iq{X3#g+}g6;6)3dlrDwjierHBd}6nB#aC4Xvy_z z+~p;g;jM!9#L^tI{-FmHaY6ODpERip$k{-oU@{Lc=6MhYS6RZIa!?a!oWoT1H z=@81N+at7=0@mFB$v!Z~DGwop^qbA26f}u`k(L^b3*V}qASWz%?4|||5JjM* zdf0(l02y)ZtzpQuoH6l9p)$8O$KYlNC=3dc zrsA?w0rA|g$JvfCXh8>4Q&Tinw2$GejC0cl7`>^eoScu=?mjp8vDII7=pnl0BHg|W!dWWJO_fxGbGxX`F@XDPSXJwiFeW3ndO4F+5_oStf!PLP;i&m!1L`0{2&P_1 zf?u~l{xqN8s$kJ))`u{SSs*4A0}&tk>j(0FcnzPw^oeVsFJI zd}uJE<>ly0^2_|yctdD1#}xFu?NpPXdV5rcDzj)p&NO0mXW%S`U2~_+pI|$Mu4r0Q z!(t_nc+;WnMlVG$$F!5j?H_U{wI|aV&^^qSdOUuD73b!0=&%n6`Cnx5d z*tI%z)~Zqo=`jzZX1ln#O!8`}syzMd0&Qc`;Q!JI5<#lwd7j@cV?>2CS>ZUe-nK^gsfK6CVxLy7S z_`Y)H+p&vFvXQfPkk+&t|0!+wl;O8RkV4RuT4iV~^TjlEJPz0V3Wx;J=jkz+ASzAj ziAiL-EQ))fDPp0Xe}o2ZKEV`Dkw~G6$2xl6%-kVY$~QnRk_a0~-7L19$C?lTFqYtD zYD($`ND||qf>A9g+K?321}YL-u35Jj3#vmbPWKGxUq^u`eYT&93O&zd#A+KA`=^9? zTLdKx5MIE1?0jQNJx##6C^6X%Bu4ZAkf?;iH|sSP6v1no>FSp<7*RBEa9IaZR-|^E zRIzVHkNtgvqJg2!-bEi*`OFwdrIV81&+#r>=U04RAczEM!{iC&=p(20euyu1IR`Vb zth2P=BYk!tAokG0(XbG%ze<6#uNo8lwBG}~zh;jTFxC;6?Qa*4BzY>P_c4CPrM}J;zPF$LMB$eu?(y>W9{v5E zHQe}NMcIJntQBo;$l$w*Wt?rh@;uIc*RYIZeZTDy5SP!9q>4HnLrE*5H&A@Xk9D(- zfzvbq9l2+D=<}NIise(?R{Fia^yMCaG3K&>pP8B|UrcJTU<1Kp;5sa#HFL$bB6Mq&Bk=Ph!h3aZnwKCDI*7cK#A`33-33JlgNq!l(JFgw#TfiFV(!>r-|8daKY}&Y_gOZp>El-Y4yleHuQGcIHH(FRC@Z#Pn?^g_fAMN znWd@iOp_{^g2Z4OB!*~gS$UQ@O41p9- zgy2IU>NpY@5XhHsIuuCIYsvrHnG!u6e6A30?bgq!wcSxM!OMG6dmW1vMjNWe15{^RxF`x8UNiZZX6$K9V+h6}p% zKTi-*v~LIl!Z#j$S5#CyU{;axHy5J+nLfo4ZHfjPf4Lv=iLjY+kR*-^L)&fi%|0eKnY13WekA%H)k+ zG7r1sQH}D)Hj*4yBESs9^64>ISy>_?A`|;G&xduMdF;;BRfrF6es8G&!u?>xytcfy z#`H-^v_h-Yu-PNFNi!ha^k=hYe39T$(@P-RmJZiy*A%R65oO1Wnc{Qvl%-bRGpjS^ zP$2z{kT5fAdiBg9DXnYwaN1#q1H>b+q+cl8+uMd$D!LhhX;CxJ?yrA5-^K(-_JMdl zyRla3=g*(n@q#-kfvy_Y?qOgUG983e_5!EIG#*u{kM8ZT{kb&q_*E*k=|>c(JW_*L zvq|0|p9?uTIT;ZwVCBSjT4(T{vG-0BibO6$J5#Um5Dqj;o7U>hUuyVSUl zZKEoilG<>Aa|lw~gyJ(3Mi`>s*DykrLB1vvGd!3rM@4@>=>>S@eRujw74Lo7%Uvs^ zmYMkV{m_lZpdv>8{8NT61&zQ<7&*=$*&C|9Y1G`+!f`aPDQ@{{LD61|RK4=kX?>>y zE`s1tq}Y^6qNq*p+7PB?~|3 zM5nFlcShchAl65*-NVDfIXTo~tZ4q9B$3ieH_B0jVkDV`@%(AJ+8ZK92^}VVWO%LKT|g62sgdn(ryKkrBheU zss$z6`N8TUMFIn!}UOs@mKqSUN|7Q#I>GT&<{ zUIphF_DYhf*u_a@pdkzKr7BAfRC&V9aMY@H*1^L~JmV8M-WNZ|$9b?`%BX!+w|$&7 zZ1~N&+F-h0;m!Cy zc{^uPgAM6vy;!47gHL&FCwN@_+IP;2q=-c$aCCC&-%Gb=XJ<#=WuI(I-6C5W8XAgl zg7(xG4mCCi@2B#A$;Ay3i0SF&@_yytm9bP#5Xc658vEMYUXQCFf88&yi}uSMYj`r0 zn37Drg*NaaxQKSzUxYBy!e5>)*$#C1iP1W3bp${)PVB)&3Yv)QeN3Rqmcpy`(v|h% zD!^@Thk<>ym=`N)MLZ+wZqDRA@<5ErzLZcn?aHX}Nsk?R8{(rN>MV8RR32x{J^fU> zLG?t5h2MmPQo+F3c>RHKBY8-MguYJ0J39_8O5kyyYaX zZ`hj7jnQaBrI&hgys3e3XFj6}!vtvw?!(0P#_l&iXG1Fb(s8vXvBjbGaHWxl6-fwwV`x?!L`e zzqEvPQ>CSvo13fg(8pYpFYz!>Nq3q2x62!VHuX&?``lbA!|k%HVj^+zRPP##5u?_k zz(hIwRBRKeH9HE$^;5E^Skez!VKq0aV&{*{YYfzsEi4$)Z(ZKfD0kM5UT05!Fl9=D zTfCKe{RO&yL@rHWfMBBMulv@1E1p*k{7T2urbXA^DCcy_XR>BwB1KMAkpE6D;d=G2ceR*rFAr8VwR6XWZBjb=3XKXABn??}@G-H$WbNUGd9-{6#2A@a2pPyE{1+B)JZD`)!*iB{~L*FK?b&_ioGU});8gyECv3_6FJ zY>x~P{X!N4ZXUUw%m3c%Be91-tZQo2OJAo_#;!AK@sANxoorAOiEIXJEG6G8T%?t- zX)Nu>EVphGy?=qWjkLmhhpPh7y*vb#wchjf4)gDqTr93x<)rlW^{X|*yPwy>bjmDh zxf(Q&ZaU6F2TuM%OK*-h*CvXM>-C1k#H*2Vhh&eh!kwhnl}hZ2#=K}6Z^xz7Kg8td zKJ9@LOUoljm&>2)XkGpKs8;DD?ti(;_lFkvE{I^P4klp&l-)4qWt+=)@CNyql|yE# zBH_CUt^0j+U~OpA86is6Y6GfCa&4g-k#2ALJWj`}0`Y6EeXq}tWL7SS*Zz$}rc_B> z5C`MV3|YzkI@|BuEboi@nCo7#(48Pa6&;Yv0=n*)E>7M^27b z(I`(Xg$^?C&TR{~#rZAMRIj2r0j8F>oRcF#OL>Me9*D`@xJZm%!w>J+4kY;O+J z#AA$e64{Oi$k+bJhIg_F(X;7J8}II5C!30*23FUfw)RSw zzV@+pijTAlH%(EXl~=!h`22c+TMOm)c3a*x>yw(cHlr`E9p>vDMSRMn)(K-W*fBTH zL!uk=1d--G>1KfYcIUvH{<3#&F1!M7vf<)E{{`M?-VyQjrwXDm*~FgO{hZcT2HgRp zb^Fo0_S%NCkwv3Kr|0T>Ek|)hwwXmYf0)Iij74Z7YITU!EhKuscp7ItLRythJgRkH z;{bWtr>AX2H~oc$h-c+iWY4-cj45tATyEEH{ig|rG(M2CUhi;RBP$VA#vwlA-N7`Z3ZASD98R3ihTtHDx2?`#r=Ku;96ju(6l> zriF*?mE|`&n%;h?&{BIy{OfY9=71Yv0`l;L>z)f;C5fV02cuRW_cnAaf_IP~8g4e+ zsTL07L-Cp?w9&mIz$#$Y(8rUy8rE`aVbrkli#}OGeBJY*!TMF<{%7N7i?_xEAN`gv zpJ197y6vY|>F|^=AkB@q>t%h1u z;&Y(fN&f96kaOU8LSUQ8e~UXlP|_J78S2W^G!(!oA{W+v4R3$nz*tpVOXQTvLrF<_ zzyu+a%6rSLx4-Z$AgAG|m^(++;#@ttz1ioazhr3MT(x+mvZF$*>~))~TbE>>xaoIr zt_walt#&Dquq79|P+Xjm4E=^Tn@uWGd#z_i*K_ZQZcm-=_!rSuEUC(e6{2MF37kSU zkCxszwjR~y5sY;!tOm5f6C}0q@GiEz0v3=58rFM;`HSXl>Z=AuH_3Hc;o>0 zdpxmox&ZG~a6>=F>;bgVA9#0mFwJ^8zZZB%TWJv0KzQTXemT`>e9JR8zCDt`Jv%yF zMqkhq_+Iy7l0AMm9|Srv0)>OwvAw_tdreHP+|lORK3obKkwcsWw!F36)nAI19+>nw zEq6K@s_!S|%#QIBnqZaFII_>)k5AaIk0P28HGu@F>>SzO#k<@eGxnzOy>1^k9A4?? zlA@MrdLH#z8{PJHYbq^1Ep0Y*M?SALK%4WZAH+veUu$b?tE<&Yr`k?tt*?D=%p7+E z1CEpftO*enhUQKi;2Ftmnz6fLVci??O4B15v>#E50pyNN)0*oHyYJ9RO>nW)jsM*pkRk1J(2)p$lbEInd(MXfy{ zLUT{&?})I$T?qd*sXJix0XJFI^Y3CI&8%+e6u?JKGWjo#N%3fYKI*+Y*w~q6P#4qq zTKae-^UIXoL-Y6usu%$p2T6G|V6?IOH)}pr_Q>6qy_;=pYg0+^Q4_Soiy!J?=J4Z;EVs-rFpppAm{_{`Y6=74p<8 zSi}UyqH(^p_Rut+&4;QX=r~A|mjx!n$s6#Y7aMc3J#a`eHY3O@SfA_1&+{yLsP! z-+9a*(e$Rz@L%9`AscusTUuJ`;HgE=gT1mjQGB+ybO*wT8{o4>td&vNKu}(@f#xu{ z-6f$os6iZdtuNIOwvs~If2pX3%hcKTDqq?Zap~j}-CpsE;C{ykY1N;~ZBI@=X4xFU z_Qjb3h*p;9^<>{TIxe*O3h2?L!Yxlb$o_mRbc-elOHo)|8_ufJi$w%VS&;QH=lQ+8 zI^AVuy+sDo9s37RsP44qb1wNR9G{_Iz>R5(h`5PPU0yZq)zV$3g@w&%)c^Y^ftV+) zkPes=kAvl2yE@^(bq;L!^z<}{vz{sI8yd#C2L~JuGHXoT%|?)c@PjOzwv=t&?MglW z;P%wx`mKQYBs?x6_5qrrRN)s3~MWqRPV} z=YIZd0g8!E>-XcLJ6jLwpI@J|hCYlDrKk!$Cf2Z;k;=Vss7J&Ye{&AjdYjKvIJ|jtyJIcxyZ`GRB`Y)y?zy-4 z{PsP05Ev5A6t9-ZGd>j#`l+dV5c9*F zl$1Y7FE4m5jCe(b#7K{O5bw>{w;RFI>d{)XG2em|&|`fURVmx_S9(CV7n*v{sAhit z+O$%h=ay62ri&E-RE(IXa|=Tjhau0zZ;7MzYY^(DP^Bsq=@*5chh| zg|1DP>-*Vl0I+vO9P;$Wb2(Q9_)@ZlctR%`3PY`#_RwV2jLp2V?`Qhu<6|{GV!CdD zfp^4D`>cOti+H{fBcZ54C3NUXc8|!_!H{tT_w1WXXe4G>7r@)gX~l#yb8aJFF#50D?W0!GI(s z`0=XqqsTE2)2%)UJHTq?pe_ICgnd|6aqggQh*f-rH$W+dhMT@ zkR2)Rq9uc=2FyVZ!_W78a}smyEJ|K9sO=NJE3v*zRfAs2hLHo5TWY3(!hNT7KS71P7~&}{Rb_WseZY9k2G&^D$v6B+;l z$|xESmr8b6s(Tl+ z9e7q8I7H)jw=OOoU}0yNIo;E6q^ioLjUJjSmnK2BB>DD9zR- zB98`XPxSV2W-iN;1zo^E(!WLaTAtwF^oF97?)}_!rOe-MDzYWzH2D0QZE!t}KTCO0 zwyCL!V)yZm9x4xrC3bi3P4DK+HSe{-)8w5-lPQNLW%3(QG11+y*Z(@g>j@5h|4YP*L zrhtpXRbaI$%gZg1i5{X>;m@(LvH2YGb(8{aYG0uJZzApZaw%ob+9&aIT4nhz;%%6w ziRpnLnyz&;0Yuh3{boNYt-X9kp={9|YnZp_?&)BNFn9WUATsi6EI-F*;jwz{?9M7Y zZ6)nV-w)Oyyle_SRMnd&nYRfq-D2-|OkQjh;LND}^ei70j>aP8ta1;yn;#9lU9#ZG zYdxKN*?7IV#kPI@esR|JV}%+&{==J3~E#eu5?UpPi zfau(Xmrfld%0nZiljSUv?l-#)OPnMzQWlv-mb!4$Z+`@ZmhMI`{B|}C8S!4u^IPf; zTgA6Jluogc#6-jXycL4iWDm^z>69=pST*58z4#LR^m6QvPHy0Vh{`xSMsW*E4;i>` zm9$&Jl(;)h-?*EOxjmxj*Du@jE4Q24YHDig>x*cH^Sv*RSqYwN8NGHui0*B8OV+lw zjy2Nn$8fco;BkVun6kghB4n>f3_ak0(!>`k2>BWyQ6YmfTTbNdS4;{wyI%rHD!F$=u&o(#3(Um&qI z6AJQ1p3e=C)15EJa8bmDTk0OzOLjf*!Yuy&(ViGmWS9r;%wF^9*ufFYIeAN-|LN>{ zULYsD#!^?nLTLSpUMyKf+LFv@{lLX;7B5J7L@kWfAXY?UX-Bljzm|Y!3Y~RQT z?$w}0?d&-<^XAku1*u`Hq+KC_u-1I!wM09f4JyBDvo}PjRh8KIB0pEac2`brZ!cgD zna(aQR+V{tT?Ig@$d*v8PEYwmd$DJdC+;Ab@+7dSTgRf-mo6{0qlr_?3&b7m&J%bl3)2}%%ow}46h%KXsrtmp1+ z-kneu*JYp^CEK=v&r*uxygyn8VU6QNJ%^$3FWJ3AL+#7FB@uiv@l%j1CwDtmLzITn z1e(tC(<;0--o{6{ClY7w_9Q>_CGtQboW6rBNn{1x&Xj~+#p}ooncCTH(P)?G=`g9| z-x0Jm^ih@G;`uhkHVDnoCL_x`ecdnRWs{u70iid0mnT_>$|VDRUp41=3@*$FBa}R3 zdBjTnD_63$X(g`uG=X+0LPQpy^{s;jqBI|0#6BuM`yge{y7R%aIo6^3@v_uc#)UNo zU!c}JLZ{*$)((aJEK2jjn7|)?XKUM3;yZ=0O)-7u=GC4IbEMO9|+q~9xQB-6L!a0zLZe{8%!?>U2KjCfbpfq7% zX!sniEA1Dj@lhwidU`P6fSpj&`AWi znTZuWLv7M8Wp%Z#RJ(Gi#rq;wK+CQ!#Uk+SG@e1mhMytQgt>;T&jLKCD&;w3Nq<@C z>0#!o;9H)bE|_ca;8B?TkVH}7-o|g!vzJ1jlsL6@jVhpA#_irmm%~|5VpT(E91hTl zHOwWq@W{5n12Z`(qfy(Ee$r&@>}=(ybCp$g+cfXZmiDm+vibOlA+cpj*pb&9nO^S2^;1W%AZ-y)U*|4 z4WyJ^BX{fi&@s#@e;l)6GPjlG&d$vI0+7z0+DjZnr$L@;I@HXOI z*xm-n8k>mSyh2<+euJZ!`DgU}k_W5MiD<=?Xb6i%-q;rO8f(X{kN)pTj=pG>9^C7) z`BlwUwJjWNtD`l_U|=u`?|j#P@2#P)?5LndQM-}$qQ6T zSdPcT@i3Gft8<}8(=!l%B_#K}==<>&&-3Qn)n7f@ul}v3x{;;#^i&7?_CvQOv$;rY&c$1$_*y8zh;zje|ai_1W>{AUU?_!&~M9)c( z9OsTWe}7$(RW3E^upB$lNY1)P9cwH&e!`VbwN3pTu9P8mnHKu*4%rg#(&gkb68ZPo z71f@_@Hh;8XR#V$U_~#sU`3*nHGE?cf_7(yIf)@XuZM!qo1HY`8}t2z15|(SXjr{} zBmOyfsB@5$F&UJKA31GvZ{(s**s`=gC35S-#SbFhx?4PvGz@H4Z=AF-u;T;SFJN~- zd`w$ehEH(CbNlYgSo@0St0Zb_KJ0we{ynb&`CAnEzZn5#%%&c#C)4@|MdXv~M3+h% zcYVSig2gg$R&O{p3ES*jwaeRlCzUTj{<~0S1$}A@WFP~?M(-zTX)TYEH~XIbMZWDo zfO@4YSiML+>0DcNml&lYc^#7-w~q+CK^)YZDxOn5gh=xJ$bv`R6aSK1THEf+a3|D4 zgtF5q9z%bZ_&ite)b-bs5WoCgqPyRHMfevzzrN~?bV~eLR?Nw}1NovE5l{}{xabej>GwMBCb}}( z5ztyIhd|_yGa4t>$6rm_Jv$xgT@+?d!ORmUbl+-Z*wZZa8^ZQgk`i~OYWrxm45o_- z7DGKiIS}H>xnuFK3IxUS9HP8But<#$H&-=zl6(@XehDldyh!KP*Vl*UyFNENYnswo zXOBShS=rv}FS-0XCXCs(96;gV;7}FqY-?*vF-_^lqhC&hXTBAEH>J{pLd@dx8Gq#L`7z-WbLBZ$Y@B@Kf0?HV6r8{)=M>}ZoQ)4WYKQRtlt_NgAW(xS?zX!AvLo$GhqGXaZPaMP}Y z@SE4V#>UooKrtf3WWOTor&jZkMcih-=i91+*Q!b^cx(?2JtW9;%3`iC87Ix2Lt_nQ&$MZD3Z6 z6K~cx5ry>eqBFCzWA6S^PWd2(7FGN!J*FTkee$6OQm*XRI?a3x{nzB{7HYU)9Y?mr zymG~zaw5SK50PIXCrf^0f$c0vF^uf{%bTnz6&NQY4WGc8S1|Q^B%1_M)Rm4Hb43nE zWG?s(SH@2LK`Zzcq^thr^|G=vvN)VhlvKiOGL0N2z@+UvG}9{<O#`W}+$hjf{D4{vz{CN90YMjJ{LRNN&yTcE zz%7FWO;1=r<3NV11=_%63O?>Z^zYWn*-OoZa)`y379L-vP2Gw8bMAI0^!*@skiLWe=>L4`Dtt~d=^Vtj6gaNXT$X{kJvtMAZthvX%ikV>;^?zdcOryS&MhD7piok-dTw*6;b?mYhS112%y_`RigfniqU zvfL8FZF&A}{eR9m{J&5XO)8)q9KBhPOC&?=f536%R-}lPX?Zw;1nB=0zN1pEDcM1h z3sUso(U81FZlp8#?^fb}GS>eq)e^bwU&n5(CBT%heOAWuoDw*|E3q!k!JtQ6WT;E z*4I(SbUoxK_uLEx3Bne~GLQsFGN$9W5h~%WcsN78a^ zrtK`@53RAl$aD#RsB?9sp6UZ~DNrzTvXf@d?SttjgXV-q$RNrD13TYZrYkwg()+b8 z849>uD1AqU5QvFUEH}owJU&X?N{>FU5~rp$O7yTuT4G3tU)Pn$|A`wbU-Fvmpy=Sg zlr5>NM-39x_)Z##UcS7n4DkCT5bm0qjPmNl(uoX9XOE;Gc2`Z=fvVQo@9v0$;{O<2 zH|=sQQW6rsrNH$Z&&7bNT?hW=sw({O#{{SnRSgZrwwc>ax$7zLRc`EO%2**C?hB!z zp~b3sx7+Qv+qKrCN)vwjzdAcRC9bDT?T}Y>8C03|DcyNv#9#BIcgq*Jd97q$?(jghat|J3lRS8NT{T%R|2$Nm4XGEX>Y6RZfaTkudS}$?c~lBA^sJ z7LE6xebewr+Ql#}vPQSuR=>HZ(QPxavB7ht4+mcJcd30e4~q!NmZGD-oNj2VYieS% zK8mQYr=qf8kWaCcz=y(NG+3Wux@3$PA$wOamT=S0tkL6dnp5kXMCw_lN6G`P<`s=|oFDK3?OkN__cig(?&sCY0S>J3=^%YxEBSoRHr&|>tg`c2E_3)tIl&mJp*a#=2 zEOo(&FO=J>X$hO^igM{%LjwQyfc7q7=>ZWEyM4X#y!+eU;&;>6pSNhwf5wV^;`g{% zj$GPmkW^Vh0^eaiPP{!7#^RP77eZ%~DRcUFYy8l|+{x2ZTkDUc__xcs6G~%0m-UgH z^CZ(9u&xhwOV?`xm42)2%~w|usnW2|a)(3X%M%flui0uO#1QVf=ZsMuEXosn%2?e$ z_=X*{YVk7JV-!!OgI5Gcw|whO{XmgU8eioBim5t`1x*6q2{nj(-RJM!*_CRY87sCt z+=BCUscL&m-srkMNIy+xFNh%=?@G}tyHx@6xsah4J5{v+G!+o$Z|YZ4Pj zEehVjk#b&Y<72iOA69BrrPYX0I{8l1*b5D09$7T1f3eB*xb`3u0IFV)ws%$dR+?@o z`sMr#Gt8q|8TJD9LblqoiTKZBio)$C$N3Ptojp;6tI$M^T;fa+y%K(t%ssl+%;BPK zbRo_8**SW8g!_Y0fq6$YLf(Xz93-|m4-r^+jerB@u^Mo`|NG)-J&Gl1w83HCYkJzf z)u@uzm*PDsFnj6>i3Kk|0fJ2JtM39^?rOw1-5(g_KZ9I<)i;=gStU_m1r#2)f)Vmz z(BicwBkae~2!~c|kwLi@!Mh|R2_ad}z~D8{>|0%dv#boI@JI&v63*B1UQg3W1G~u2 z+eX`@3)K%qRTB%ivGrrE=K0VKb1@_%=#)yfRYD=$%~1H9)6Qy*?!1Er83|?>;O%n# zi5fV&IbX2utIrx-KkB<}t8O2q;6Ob0AW}l&D0Q~1;ih_OuZnF!sXtd@B0e9U$1VBu zHyXsX))d(eTk&QMA8Hcavx-$gdN*}8j1UL@c`?!NR=iRS7$L9{ho{{vR&Q(Q7+?mR z*7{atm|%vLro}2rQnawYVh}l2pw6C_WQlYbx$B!vi|(`CuXIuwqhT!3nI%ItWh`&K zKdI|}hH`TDIfWe{^SrDn!&XNZEwGZd^(Yu|_~We6mw+M&HnY;u&izVBhFwwYo-E?z z=B5btnOu3|wQ|RGs62pJ9aMIF6bD7PO%>KWt7VG07;bjk}x5CI%}`Y4hm4d$JmnciC(v{$qX1JCE=!W4EPUc4LAeP-;*MBsgOaQ zP+BdqkQ>{7$(pjwZ8^)V7Cn(+utrI$-ceRt_q@#*N^+65>yf2OROi^d@a9NSsweK6 z5fhc3q7z$_3g)njn z{A2}2dQedU{N+?&D;?%ZP(Qt9Lp6Qz7*ztFFvPhF|DC+4HF=N_5lZm7w*>w>i4Am# zYMmD6-}l=KN=jA)!%bi9{n?IQ_-=>n07;yx-!-fLTmnA9d)7P|H*0Mr-ia)iZNQx1 z;o+@tp{yXojAS#zG*dF4Hd+*kzc#z?wwpjY8qftEtQvEb#R12b7kGOCiq@Lb{%p}^ za({etNy9@}h-0Ktexm@WLs#gxB%rL3$S_|MLgy?RABl^Li`|XUU8RkgSwwy_?!G{W zF=LRmaXsq5PuUoQBB5hoz=yr^>(|GE?P%C}+qzH1i!R`ft9AS?k8O_w$e58=KY2wk zcn@9!Re+I2w(XIJSGR*)aJ^$zkuCLO*v*Z9y|5UzWSf%MC0+f`5JN(g$7yieOr~hF z<^>}ioq_eEl9Hx4d%e_cpSHaiSywv~b)>mgFV}**8cHX`^uksIQ!VdK8`@9&1D%kc z_#D}R{0bs=6x~DVQ0{t2Xe^IjYF%@)K4+S=8lZ1n7*s60DUBXdpZ3V!&@lP_Z@4mJ zK88-0pIY1dpcob3P%k?A1lXH=f&sY5sj(69;Y`e$F%%<;1>^o{Q0sX>?Uxb-aDOmE zSkT&N^$qTsBS}uln4n|HUjpAk{_XQoZfu16^HHqs4>xJjdVEK)$E2Vjxxd{)5&jrU zwBLoKWJ;^Fkfml1L@a`zF_@7}EUZ&@btO|JFqTHY#gmq;<>k|f;<8E}jF1rra|tpI zbZ_5diFKkVIb!M58aKD=q>_>gzfKnerdt$Hbj6Km0jAyrjXufDtvq5Hwdku_Y?y?r4_ z58ii%z*v^k9+|wUGL!@tO+OqoIMn#W_0#xvT)xbAr)i!PC%%}{p~4LLFuG3N??TmI z0~TwBMPzziM7k-LnAM0;)gcgRp}c<^H7j=Wz?&xp1SNBT)%_ zo(u=F@an=d?f?Lu<(}m_j?t)vGn0#d;`VuVnI1?U+dcEZBc3IC?2m?~rdm^;&pmS_ zL-u%ioh1skA*gc9z@#-3mXLA?h*M9RgO{joczhlNc4#jFEDfq$Q7`?TZZci+aNk1? zU#Y|o7r?N5^r>RoE!hs*Fk_x-aUE4nywl@k!que@x=1W|0L#$$k@QoaipT#EBO7+N zAEz-3@yuiUBHM7&0UwF{v#Ptd*M#lC0;f%}=yqh`7k;^MF9onAH8o48wo=%&VQ1ax z|1P4D_lc%%Dim%}&49F!F)=Y?bOmxP2P8&+Tz2db^Eyv_zvmW~*oozlq6F_6=i6n{ zVStCOqqwbf#O^_C-A=YN4H31C*-&{YH!m+1_~GFpDC~-Mz|Ly1w?nNTUnRERzv9B{ zGT=nKX%N3Tp5VsD3JYP7&n&5^r~n-?X4T)Ss|md2$%v5fK^TzJ*M^3Mz!LQwlTe;w zgjm%!0%+aboHb~nqsmIE*fW#%RFo_9i4?I+QGs3Nnm3Jpi_LsJgFHGq$LN{U&u=c9 z>iy@rH{ehBolprRWvsT8)Ew8aKA3?wbYxg})e8Y7`8ZuTo<*+StzM z9vvu_g&A8KDu@Xu>Enc%+73%s;`e0+Bve<$ekmFqnYP`nvkG!xupg+i|O z>%*~pS*hccZDaG`o)BjM=Ianfu2jWFl@X=`u5rU#JDIL(qVqFEB1@d$>{j2#%7n&U zsz|G0hmy))%mZTT%mOzj^5E0J6*%e-z^_ROc1t!wM@I)eVU6tUS*Uzqh2M>tZgzwCqLcv5S3Ltcn!1oe+7(z$W?}Q)kVH{&* z$#K02J(W`XzWR1Yzsh5Jg$?t*bQfVC9%zpF@aDdBGoz(0zp@76WMN@p-{yukruA*3 zl2iyCF(&FM-FvqPGzq$B`pWzByY+ilz=R?#x{kV4t!`T}HbJ%fyBa8}L}a3K2+}4R zwXH|=a*ltAY!2%+d&MMoLwrPaJhYCf7356;(9D~kl!N#$W! zoa5|R&JvC0h%~gf?=^9@E91Z8W_XF%C@=-xNo$z%&qN-3+)93B#Fkt-v(z=x(-VHW zpE$u6tBh}{^P;3gff&npTgm?7tD%Y?70lr$LJlhy`XN#lE@;T82GgyCvt9=pWtE0M_US~_u)$~Ea}@b z98DEu>*!Wy_z9vy(#M?n_ZWWXP(#Mq^G18MxZas=cpH69BtikrVm0W+eOR3vc0T+W zGFr*2uIu!%+;9FZ$&XW#t8dHbP&EEIez<^J+MtD5Xo6Hv>Khw!N1G)y6=Z>SlkrD2 zwwW#?oM*J_v9J*qA$7UbS19i^?myphY^Gt(qJCXnw_gM8AL`*XdlGlQHNAih<9?p& zM_auHGlD*3igVL4lZo0fcDP=~d^cZ_DL3%i_hAV452e>+!qCs?LC5OEVTHg$#I02I z1E~1YT6OK!=Mpw~b zO^E(5Q?cjr@&b>+jH1-rOKMMW)&2{}1AYh)y- z)*6B&9%G;f>Ffs(K++WQoaO@l`32WhZ-o+#N3yL{QKD zFOy@Xwwi9u-l=OXpLLQUjVVw&xCPI@PP>|kd#DoJ*yg6DooD{R?N*xh)=i z@FP=KBYsbyLW0}}C$=PiaG31tX+GE7H12to;9@$0YA5POjFs>`U1 zoBE0@&MA*5HF13(&zB{i`11rh)>MU{ebDy+bW|2-JJ_*MHerRBND`OIqVq~SMG9%N zv?y3?Us_kdr`OKL-Wn#ZZeU@`UIvnqJ^L4@N#IxQuN03G5oB?#L@h@(m!+^ha<%

p!Y?rv%3V5%*&l# zPrITdr3J~#zM!WwgH7xX>(~xZbaVeS(sxxXG;cV4Wvmk^;QnN1=TCjZ=7uN}nn4Cmj7di_ViO3G45k^*^pY^sf=lu zRC|66V^#a}-A5@k1BygGq_ovBaX#-%$-+M|$ahm?np)G=_*q85X?$}d#Ks3H*2H-s z9S*-4>Eh{ALv~!gwjaOeQ#P-C3p!0v9t#UFHPzrV-3Qm_%UV+f9Y&ce54NNl@zI6f zU8q-iGE)Ggw$y!^j@e%eMBas{QMW zBL}7|_&SW4SSH7e_f5Zx!+e|P9-zYu3JT8n9m`=zPVfQo0n%v{7Kv#As0+RD0c|(7 znYNj`9?esB)KpYt;RGlW+f^q!v$aGGI+Su`;k{;Rnp40h1IWde;s#FkX1q{w=Ug(K z_@CC4lmM!@1is%=rB-PO9TW=vR*?m_iV)EVAGE5?Py*yxMSFXY%)*w0^Wk(y{&mCr z*Ta3BXzA_gDS#cKRmzC*vQE#^RfJKuD6W=uWMhB-RjQ?KDs?|AF=o+hs-+M{$c+_m z1YP#$-+_NJobt~<0KzM1!CY_3aF9`(dMTC%w+f{LW!$niF%=ggPp07|EDE1qz0%aA z8ycn#c7{MO`;dPZVEr(&gfL;_!>$= zHSa+so5&!aO!zl2b<4tn31;c)^~F%e4M7tGTlrXz@o)HH3Tq(Lj!8mJ{t zCPP#rLv^_A9UWDWE>1CsV3Ooj|M4*k{ZG97Ca$zks%)( zDzInkIpoz7k1cAQbnx508Pd_$P#53Dz2QdoXv=Z+S4&Gc8)}2V&7~`!D1i#$LM1ZT z`L1F++|*{CnM!^1^l)vpXjc$q5E<~p9A@?bx-t6qrhMW{dc+Zm#B1V=t`Eworj3&h z{P9Zx3Z`Up_5RMz9c}-jYJ|HajGIA%xO@LkPuN)J>%vYGiRT@n2@JEqin0K&jK?6) zqpU&PTW`x&a|pE7Pi*w>vA=O514+`@9B23_T`Z@hMV6a>YHwZz3rIAy?KKS7Z-0|C zXv8ZH$`b=%X+^O2r3AhlzJ+wEq}CIfsjx-^PLCfbF&##%atWcVO%?qhm6`^BMuCHH znNdV-+d~hw%s9{o00Bw;Ak5t-MUfy2k6Y22nV!#OmQ(-qYJx(QVPrYMl ziI1D)4F7Nko1-P21Ad{KvY>Q=EN!7;+9g-?29bMf zBy8gf9C+d-H#)OPd)8M|j#U)#R z|5of>0pOO9FJP>|&{136_w#EIyrJ3x2~N=z$)D$NU8 z#Jza;=c|<`k{NX6xUql{=*=>b`)54kR`|}&9O0NDFEpq8#GG_f8RS7q))F+2FQjJ{ zu|{`=yaHNC>^L7#%_+vCK5#!iGK3Bzq~oZC4#Qy{xBEj~gsBY~+Wf*-qssLoZ;6i! z3qGGdoBga&x26w6m#taac4zXnI z4;o1zd%5$sX}h>B*binyxv{DHZR_-gt-zluaNvjEuhD@LKFr+~j+?i8zM>j&08&UV z=72qX&6e`=(?=Es&NOp((>guJhWU6}abTVh?h^PQVg@GLGg&otc7Fayw9Cnr_>cMkj@aSH&?ffke`3K&RkjQd)~da1qY z9Q?J(+OhSH^YuBS>;IrNVDf_gj;O_l=1hUR_QqG|EAcDCKOT6b-b?2NMqURh=68KQ zrELVPGl)D+tO*IS*5zgUnF$hDqKj<*?(QBGvqyK~IxROG1gMGGhcA6$!30H-5AfB< z&)IOtH%{U{$C2$6O7FZt3r}5Lofj|Ug|Jtyr?d0N?aSNFV8{8LAO;fiitT7w5I+L@ z!jNiBMR3tJN&^xxa2}9hVsp~gOlgHGf&|&Rckaps*6Q2RsV?EJ!NjNy5at2-#u?v( z$la4xV@ru93-@7yPm5QHsgjt?I;2i{FOR7;K}T8Cj~<4+kSfEs$dMWIJ%9g-AHjqz zS)cjis3p95&j<9WMyIB82hbCMexSNae~tiD2py^c0vz8}L z#kM~0cLD2zv4G6WCI_@nFxPpE)UenJnj1uhbdw9K~X?_g1!HNfo zMZm-_R40&jad+38_}bkqIqKg19%#a>4|Y1;!NE$u!w8|U+&#J+D7*= zdk?Za+n0xjZ$G^f47_cr*hZ#8Gi)ZS(H&@T0>9gfN#OH=q5?tFvmVFoDxq*9~NICt*c|Mj1L^WATMC(}C2 zkYE$-?(WuVwJ;1vfietpAfemL#cEDzSZPEX!gWsu9uQ z;i0OkY&cL0$vkZT^3I)hyDbR9mtTGv|D&XjuIurp@p`d5937;|v2g+bm?y1PD+q$u zUw{4o{^wuc-+AUZj%^&QEG=7>#p=9s=gxVaS1cCULc_(yMb_cDxVX5qw8XwFl}bcZ zEEYY_D-;TBx3+9Ht0;;^|(+dWGKw4YPDF}HJWUmOD>mdwOZ_ydA8_~Kb>!=t*R;!6$*vt z&!4lCctt;O!=TY@?(FOYK~OH2i^bxdJ9pTmeVDjo-P7nG1%NdBmw)+}yLa!t{r1~o z7?w(Tsy3TV)?>7{x5p;VD2hTv zkDomyqFgR_`SRtRot@wR{`U_bKIBh?i8~gAj~_o?TwJ_(@gnOW#U7*pkT(1K`#=Br z&xz>u*I$4A_1Cwyw$|3xY}@|)^Urg+oMl<;*j{#8Q>QQtP1Dpg&G-FAqfsuGec!KE zt52Rh+1S`o|NGzn{`bEpqTl@HH?O_++NDdE>h*dM1er`` zd3m|jY7tQ;lVLYEo6Srn!#YKYs9vwjvh4f*XPUIeCDJP0Y$LAtoOh#&+2`1I3H zKmGL6cq`0{E)yX63{vd71^@tauS*aT(eCbUya@mRU>3ogpVITX2XP7 zRu2F(p;oKKn*dJIF9-nu0OsBaLCA&)F<&MM3+e#?=1J1`bj+6l0D!sl{{sP|VlLoH Re-i)z002ovPDHLkV1n<22gd*a literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png deleted file mode 100644 index 2f358975b94914b94eae386a9355efc5673ee30d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 110077 zcmYIv1ymK^7w&*aDd3M1>9~}1BQ4S?UDA1h3kcGUC<0QKZjo;3F6r*Pgmi;+!yEj+ zw;t=VV8P7nGw1C1_TJwPey=2rg-MJF005S(jD#uxJQ)VRr_hnXzo@VacY{AL9AtEy z0D!;<{Qia{(mJaQ0F;2N#9MVYgS`b$FA~dCw)?|@E!O@xmhQ6XxjKg6=q|;SK$yxN zt_KE7Oq_`o1Hy6k>7lr*uY-1v&L7+D^4WG)k~n=ITb;`cE{65_rS*GB|4oA0DgKvu#tXqL zMamaOLC2iz?5)`5grS`?8J&5VnVGq{LG$M~cl-PMPVqE>FT~MV94(X)>inb@L6|R| zqe8vxt*w(9M$kvCV#vml4W$2jy0f*lwYLYUX)-umZ1P0R&25wffcH^VS|tj@ZoEWX zdWys|BF{t4W@d;4E8U)ceyh8T3bZUm_>)k90^|c{$E&AzY56MoLPqR+O9~4^=l^;% zdBplxX%$s1r8YwCe{=ZN|HdM!eSDWnvjkz7TANWM+3W8IqA$3$iq7^!bQl8K{@mZ) zB=Xudg*!b84;<*7fF?_oQEON_+b;~|Cw8#sU|#H;&@~y@+t@G>*8O|dw?qNhxWPB- zbxCKg-g(;2$%TbMYyxQrZmiiH=V&_q1Cwh+h83u!W5|oWX*!t_aY9_~$$z_<6{r=Mq z$h^V*rrgOf_;`pq3H8x|YrkY5KjpD`70!36y0{pf%{H3i=QINF9OFYKEhdkL^*1yh zDg^iTaQ>|!#C^P)BdU<-1h8ny%i@T&XgUZ*0u^h*DHc%DdOY9^$&N;7a&;8`Hoojn zBIhM$_xijG$wBpKn9W=`?;L`#!kDnNpEtogwn(gnXl_Nzn^|? zdxC~-WQy@9ju0<82S)tsIl~~KDS4~HAmr=dU5!IFjJd5f>`~OyzAPx>@FJQ7HQwTE zhd>FTU}DzR5I7FqMIKI*03R^2V$@Yx91cpMLGm+Vw^HB=HghuDk|FIkV;#=H`flC3?tkzKDAW$Nba0D-Qj+92n#aItp@KS5Zkx38)&S z)AC8Oj(6vkU0q#U^OXD->ERP)f@c`-$R!dOJ;(pTW~6EV-5gUl<{~>M^Ua7|h8{9n z*hq%?1(cSmWVv$-k(8vl7vCEj!f=O2<|9jJ_lN`UQGq_1Q!c-`n4OjGpZZmvo`*0gpN; zqZqIDdmy%&ixy&v^0}?PUZ5Pyr^PVd2k!6h&to$cV|F0QFf^M^*FC?!XKw#qquDs; zBygUN(aX#W1ps#v$;iseY9sldI>^TF$&Bi}!puF?xZ-Tujt>bQbHPB!HP@A%;A_aQci(=CHSpejlaxi51zQGlJD zo!`ss?&cH6AsdbjTfWA0-|!&eTrvW=Rtj2b(k{rK1;yoGSV#vFGF4>3UgHMG6#P<* z9H;H=e`{l7vkXP_{H~s(PQF)mO(fSz`i*2{=GCFLfuzwmL~s%Y^$iy&$0M2_6$jUn zA*rzBm=^v~a;YPhk$$ZWAF8K6GxafdGc2wKNo;AH7VF2MXD@En{ceGwTB$BF7`vYM zg@j-pXXg$?^9sMjK)t~Iz4vWo#bW5vYHshFqj^YW@c|XbyGoX>ZFtxCMd>FDN6+~I z^x$OZJ9>;2YwnoBD7iY_xseaH9#1c}%qq)&j#*TVMu{()vh!1C(U7g0Qu$6l_g+dM zT+!pwO_EEm9&~Utd%d6>&;1^!w6|5+>6s!0jMP0eTDWO-9^NeSh#4M@EX4Fx? z_~jnZ0tlI$x}*of(W$Zoht@eOBjbpXpmPU%d+Kas0Z`uo!CFhX$Q|aqqvFwlqmSgQ zFFRH#W%n*sV`U($L2MP7R;;Dn^419A2Qlt3rhlSeh-Y_spI4-tcdIi0K?&wAN3>Zy z0c0SQeke{($gpXb$)bE;~eX=q^K0}`GN z>V_Wdu!xZ6HV%2~0VUz66)=cxvZjFXe{1b48aC;VRYCi@FN>&t+S~#o(=T`SHE@#f z6vs{lqCTlWO+U>!JWq%KO*4bG>vxBAd%!9ffP1mXEblTazI}3bHouyzQ>9mDAMapH z%o2w5{4A?WeD$&ZgAFlBf79Z@w1FvMY~XbW*AAZW(b3Vjp+_4jK7xl&66z-lQxi9{k5~+w_pf&&S}v&@egNDW zy9D`AxKh|?B$ezx%<(D{1uA&>L0dO9HTBaq3@@$*>Nt1?lFhK9}j0%9@!MLQUbM_DS%Q{$%c>s4Jr^L>Hn-MDT#PEHQDg-t^6 zw7$OnFPYC(tYthby*1%veRAhJaUXbA0Mb3}UhM+nMnirw!E=Ux5GFAw1FE;6m!f8j z*wi!7su957G4Bd<1!1B`y_ue#p3=on8OQ5dN}}flmRu<{VI7+%lZMU&Ky82D26K;B zZ?9x}@v5t^saKxlENu{5BynAMtRuL1nU`JJ`_%`v_&Ei|#W-I)65HTg+uIzQ zwtjP>td!+7QIRQwUv2v=p1k$5`ZQ{3BX!($$b67DD9!roosR4~`z|#B*)iN31M{Hr zzA6#@yDC|iN4?@iS{-vC7lv3X#Ht7t1E)`dV?_lA_|I# z@8QT|{G>ykCGamYixaHZ_GZ#tJv`Nz%M~DG^4bC+6M?VC`Ol2{Uik=_+AZJf-mEE?>t6hDw37TBgxk;-VPtfX*ycJc0OjzgGJEHkIqTEJbI zYgy*w(!?3vTz;TW&`aki+RjZ*O;xG%Ync4AByEqc5*SCBb}Ig> z{hBdrl8R+a`FA)mE79{YN5`@YW4fLDlsfqh8uUmR+Yb#>u!^_TNN|b!Q4^QpI;XuF zE3taHf0_uohXLeHp-HwDjOtBu_?7HLt~}faPQBlyaJ)5~h`j|dD3qX%Dk)(-JD)B# zP_$!@chO4M>;2^OuAb@7BZfm~G4D)`mgpwOtx`CN4s18xkN+_GR9GK3#C-&=sYF4H zf{f&$PhK?B6O{qlSi*&T^>#2{%bjwb$$Z zStRhRz_M>V6%>!;2magf^J(;eeqKxExb1k#AgSPJ${>D)vsXv_x1RKgh122& zZ+ZUbm=h!spPty6#1oeBo{h_@5rkccOj%J`l|z26L6^CWJ!VU>f3m1d|5lzCX>kQ3 z2}8ca5DFiu-nC!LPK?{;7F$}rw)p21sXia=h-tdn_}2%E-#|v5Itu8^7o-Q054$xj zPNX#XKKKmG{@ZT4w$IjSA;?VS{$f95@N9>foI_gS=mo6o+ZQ*X|J8EcDF|WUKCZJT z(CvL{&lbxb=Gx9LJF^Kog)!x^(NUGg)?$&gj9>OBRDcY2Q!n=8wREjd#Mp_L8ygp< zrljqT$FPAEu4O3X1~B3H25P~+NyX{G5I;6;-B6s*mm9#M4Qd(3B7=^n@pA99h^YxszGae}YN_#J*U zHKh(=%*5SDE{qTDN*noBBkf_Ukv3AT>eMXSTnboDLT0)u*}}aJsP<>=!)PUiqu;ktS8p zWBa6p1Aa~y&A4_7dn0$BvLJfmBSFDJ0{9C;G*PKffYTr7az}wwJzX6QILT`c|7GAN zDI%_7YbJ$pI~(E@nF*Z*^!K*JBW?aDC0EF*VUi8pxGYg*BYoIa+2--c~~UBnT|yYuhYd?EDYRGwXbkhv72*Njcl z*il9O)grzze5Rlgzmpl2?so2WjnSUzSrF&w7GHCyhv*>}ObZ_yGIX{HaV8j5>2AMt zX=uvGKmtgygMKpH-Q86%<(O(WxacpuK69~9)mUd_azbjIn3yOt?VjnRb=;dNo12>} zD0mIz6%@=hx;xFmo}nNg`dl>d+0OiN7)aZF6)a)kz8-6MyYf=dWsh=ISXek$IX&&J zdcLZ%GLqya>xYC3DucchyWBwwQ`Bg|`=t3_AJ84O#)QH*GG>H=U40F8ot}x#^+#MV z5fsAhZXeZYb@ra5r;b$JDK{{FyEw^L3bB z>6Wj-O@tub&Eqzzf%C2&ylzkLU`2>YjjxKR=$<4~*@t)h5ZwIoKwKKWuP8apo>I+T zoVl9{RN(V^qnGn7AE@@bAj86zXG>P#XP|3jo_Mg=*Q9TkMG6A%UtGl{3 z4i2Vgc;vD&Gd~}&mQEuU7fb9Kht!92ruDUkFH~#6Qo^dT9_DMWNr0WW`8O*&kCIon z=<75O&+gO@UNO&Q?-3nSXw1I1EtFk=*hh_igO>d-EqG51k(B_+pGyOV&vozl^=y{k zl|pozO}0G}l0!z?eh=#Dg^<-RB_L;jR@L!TcR@MA_B#@fIE$-0)NY_r4;d(XchPWg z8Gbo6YGVIbLWh#`h{17q}Q zvZZA*){W>_3GOB&=e8Ls+alG}tAwUCDC!hLkxTN{97AKy-=c;oz=JOphbj)sibGRU zI&Lkc>OYXX@{B;-)wpQ2OGOaw%JRhdR^ipl|OFIp0dl_&7~dK3x=Svx^Oe~ zm!Iv8c$GI&6n0`SC?}Z=Qo3y2SK6ZrP}_IuMk=?5hM4{5!cBHmoVgddSSjlHrO(4f z-JaO>nQYu%-eTn~=1~U?=(1RB2z%;0)4|>F)Rf0|*}TS#=A$J{2ISMe+)$9DML+P5gX2)C90zz2YP3%XMdM|mLUh6u@TkK#&5_?}m%dnxeAX(Ed{c# z@1+V;7lpMmL)54TE3D8?gW8)z!Jx21nsu>_7K6SjVU3@$-K_) zl;@k=2(m#jp(B~uw4kwO9b)C16Cu%|g`3L5M3a6-T!Ncf$^PiQ0Q}$~U&eDhshc#a z-mzb4>C8QG+M!ESIZtPaSRyR^H|_|=M@26d;B>IUh8nfPf(__&c<0a2t;-p02>uQ& z4L8iQX|cY3^3yzIqCtt}#x83K7dvQ^^)2eh+OgrFcXA6FJUs26KO2?L4AM#wETW2c z6&A|vE*A1PmPHJuT{6IKDJgF09TC?-zBJwl$H}jksiIZno-g3z6r@P4^mrH^B>0j; zktX^3a0$DVx%;DSDoOW7kGs_Ad9I4SN{cVA0D%9$0S5&qMxGvh-%} zRju9!+He}a`bI59Ho2osB{r|qk5q(6eh__%AKy1Avl9kqnR*&AcitBK1&s3z=+#9! z!Yz#SM^nb_2ddbIXPGK{X zaSCVh%5F{XbaE)Pv=M^V5PBVmG$?I#MfP8|EaJy&`zL<&jj*qIWTBF1sMi1`{!VIx zSvZdkv2nBW^Jqp(Jf9ZPag@!Si2vluYhH%c*Vn&i=m_8G2rNs+Nk{Tq%MqT^nsCB* zSaJ4bDfPxdDV%Wle0PN7*qh%Vtj9uNgGYcR3cVfS3!*kxJvMFi&MV3{U&y6svEFq* z49U2Z=xo5=d&6;ey6dVXGWoZ}s(+3BT7 zQszDpD)2BoRR_+RUxJP*O31{#g!_Q-iPf!OKx6o~vD|$lc5N*!X=LiK;A~+oRns0# zy^0(TFcC(@isQA6ZvL-62sMG{U3vXz&>N5XM6Q6} z5Up0d*&JDWl>EVD!10=%Qi?!J(GiiGt-+@q;jK4+j3MHc1UXLsel9NRXC%*kyHjy% zp0WAymB>wWei{YL9*-6EYBi#FQY*r?;V@ZaeJZ|%s<=hX_C9NU4aev;b#aU7RzcUa z!R5-|b)8ucQtyW3}?p65s|rs`WA6qe^g+#h$OcO(<}Z7yih8YE#%o87A8 zc}HZDp5;0yA^P3}!RIx6sz1gq{Ror03Y-=}H#ozSz9v1EtKI0ub)n61^X|`llk)40 zc?2cQC;~2Hzt8|-@s(~hPgh0UyQPnW7r>^X4uzx2q{IiAtd zu+|}?rsgFO&}KyW;)myCy5l|xv+eHC<_S{kP^w_q_l0QFOxi@@_giH5(UOCkK=1n zj^)aNlRU$Dz6Oh1;ZUI3em}3NF|n5|3272e6xS$t{M9`#50P1R4i*?#cQ-fU=gU#CG@gd_sVfb)9qkLM3_3hul#z+eV1TZo_ z{_dDMwJbb57v{-O+|^|fksI>rlYoAgawAxAh(4jLfgz;044DZ9-H+GeSoC@Xz{V`Y$xL(89bJQN15xo*T`iabSdvrjOjK==pGZE5x{*6cxJUkPR!>-|##v{g=HS zQS!pvlRU|7MZ|^svpe5cceq~p#MK0zRpf&db(90Y?T|p>a7_vs*p5xNuQT=+^c=G2 zLTcUq6dn;l@y0Q$u5NbUrF~$)Poa@_6Wfs6OC)`GlgTALSipq@Vf-_XO^=It4uX^$C z)S}uufA&F#f4yT&Xpttj80!M906hPxnHibfl+Q8l>usu&)^y)Y zWj-HEFbt+N*Inn3F_H1F`ho0)5>)Y3H?wVSg2j1WTjxDaL)b5d(+BeSr3F|#A zVs{(Q15)I97ERTlL_2Ep!7w@&TT*VrA!-b?$Ryc<#I1*Qf`~+v?po7 zu0_ynZR#mM_Tq_Q-0dMD_}X;WNI8~IW$l`!KVI(*&!YjzVvfg-D^rJWeB4+VFtzoM z7H|S4&2QGF->A;80`7tkj9^XVA}6+#$x7`1#|2onNtnsF(RcL<+VER5;(J3bW8E;8 z)!dV&lCCMah_SK|^wD%ehw9A?EFX&hdN*u|2*l5E3pX+@S;NNQF4E2tT@yuZvbIJmhQuP4ZUa2!rA-=^I2ULNpIa|Z|)aPG9FanN5Sdda%YO2+4nOO^=Aek zsNM8lXCdFvvT;{_O+Ie--Fdf3Du)mCs%d2)mpWU3m!{{CHr5vSlOp1n?_k06WTaJ5 zx~Ge%#c4wCH)#-2%8frcL(UB%0}VRh78S|T3uiug7IQ__otIdR0)V;idP=j&MWx@y z>I)fn;R$N*IgrMXFR2MwSz8m6lk;k9^yf=vRac8VB7>914vV?px1ph-TSs03>>xB$ z)U6@ch6NHnyDUYzwT?b3?t*?D@0~cRn50I6NWh{LVM2gXNLl+doLlP+isR0*&_Lp^ zN&YvotVE2HEi^~;=}$t{&Pz7lu?5>dz*Vco8SQ1}Pwih&tmk~~v=L3Wy=M4J*gxtk zJMYnYy>d5i#m4VlU3lo%IL2#eV7YYc-)ra<=M;BzU>>dPqus>)aRVyfj!0#>c$HW^ zsk-!^e7`!vG%bvyH!gB;WGq3?_9xZg%83bYW?+z|nY>J6PWmuWN(CdX(UphJ0#>%D9j7>Mp2QQv2~G!L!e5=h&Cslbpp^&0tq5`C-k;F88;k9*WP0eH6JP_uY>GE{2ypb z8yC-amHQ@>S8E>7i|iz$uC^lg|1QX_Uthv-oQ}#m4(yqDBit4YfcF9|ZAV_~FO`r0 z!{*=RUKOyD{U5Dc7j|*grteXif8)pJ{JHVNC#DTU2J#uSy5;IdphySwenzhpTLl~j@$yp&oe;ML*r zlUbrJpdosBrHByjv?^Yyb74qjj>3gdLetup%XRlPnE*eAuHxIhNo+~ka$V-=BgXf% zwt)5vs^s$K+tR7{2LhmV2lXRo-CgNr^Cr-GeN(FE`*4=;88PE~0`=K~01i*O#pGrv z9)6gxDL3v4hNm|^1L*pB1DGScR*3$JO6*lKZO4LQHh8j0eX7GmjqwAXOBu}F`UApN>nNW@5|PM^Gi`#SwFMRpmi$cA(Z zbyF$O7-B?>^c)`Poz=MS(s1X~B5=-;IQ%QX zRSE3ud>O#VYbM9SpUO^^YkJro(n31`3x8mne?kY$rs6(*C8{`y$8Mt@L1-4HE~cr9 zp%|OkRvz9a{~Ez{@mPTf{yqw6?^pbga<3Xy8!Ru^shc3@WJ!iNbmsPT+grwYZGvy6 z^S3yR{65HSdiD2lA=ATk9_cp8UE6+2r^?kAwJB%5Z2f$yxr}yJk9?wqdu@ zq5ocU@FsurGQ@+?%jLj+q)&CS^|8LK%P&V%HTg*hKT#2(FyXUb^~RW+6np&G1*F$l z|M{FqhZf(jp{M70d->6&tYqvwGO&Go(|NFe{rJ~AV)g|Zfw)SH`UlX9$V|{}Do#yL zM++-YXWWPqhGIQ`ZuEP~&iXa2nl%k0WnT!tH}qvfh%DZdOyGTs*WHBr1gtP2g_Mj; z9`D^t_C;h;9FQL5FcxF-aWL+}QoF<>d3Va&6vx+3%8Zud)u9I|kkvNcs%O%67(mTr zqE5U`@LDSvn9@LkGG{?@lO3}DzH#>gfVJSaf83OujXpoNZ>+|l$p-pQ$0T6^AYqasj_`g`?3Rnkq9BR}2~{z8On!dHS`QI`-uEWYlw_9-JHCC{@l8Kqr1I2`5vd$yiZdZ`Te(cb;V7z( z3F)xl*k?!Q55Ku}4EF2b#7tsIB*5I!qNazlt~%TNOzCL;f@$Ex+G9&Xmz0^E z&pH>TPB}4dUb|q&$wHQ298iY!-2F7N!(F{g7AQm3AdT*vplP`Ab!U6~ z6)EZI&E08KL1`&S?;7Vjq5(VcNJh3os2{9f#q;nGJoU?9dihdgD6LKL1H7W4Our}Ulc{=vk<4i!#(fZVruVLw~Dn!(mlknDHWuUaD)_k28G3g2@3@;DeLxuciMwi(#BOevEF!UV?z>Kx-hcqz7Jr=ag8V){SR!N zD-@hg*AvdMo{ z;#dW3WtO)w^p(2P!X+&&$9D5-GM?xSK10a+s;QeqqvJ6Q=$0a)o@C3qZz6AZ14AZg2MMP2PcI7hmLZ7u+XoN ztN;B&a&-`dFf>)v_kL?Mvpa$Uq&1ypeg;W9Akndqf)ON1fz72Bi8?t*M@B{z`00-i zVlyPCQ}Hyo8_loSRANrbE3UQ4J@ByJDapmxlPtd)S9296XxTUZ!{1MFuaU2f74Yt( zCX-V7{)i>y0T$wV{^}XfdXk3Y<+>Mz6L$aivzN}`g#4202R{8uO}bKrrepR2?gq8< z!lh)dU0N6X*7|dg$1>~I^ZpQv7q)oHUPGf^e1$cL7D0A z>0=LvkCcbL;ZI90ae1k8kxf2#9`LtdH}VXYm!M^8S~0$DB0XN`nEh~hbX&tx}9^CiXV z$|@Kj6y0`TKvsXqd=R46Di}LopQgk1`F#@Ay|(OhycWA$YX1jCZ~f&kwy$@l_bQ87 z?B8aB^TER!{SzNrV$`SehgZ2Y~3kmFr>dQv*QAz+ejIo0s%jMJsGAn8DlfV-A^3A$rbfdDQ+!Xp(f(MJg+J zn7}uVp_K%Eb8CetyeXby(}y#WvWsu9aadXdMacbz|7dQ@KtmzZMe~qW2^@78UBd^Ys61KKpC z>>vBB8^#&arBvK$XER`SFP^q^h=YRMrCwWc8acADmu&AN*ueZUpBA>D{4L9*Oj~XI z)Lg`fPIwbDbe=dYENt{$Hw;mdet`$qW)@(-jO*Y3aQjA3FdWU`y>jPZa5Uu%K?C2% zepePtA5>qjlnMbrOeM$iB@!U16z~P+u4VFH*#$ZP84?=QNjVY~K?07~2xy5ng!{AG zxXx?56@)HsPy3EkhV>uP;oqM)M7PvY04ayJ2oR13r;z4G`iBBqx1 zybw)mypKoqnh>{&hnM~RBkAI_Ehi_3dR?VTK^XEh4JF@V03!O&U#4Mh%a zOK08vV1{B@oA(#C?wzZ&=f12tt3$a0sS98830m;M(=UhXrkI{X`IG}y{4Pu zuo^Lw@;&b*uy){7w&d-7jX(m7RyKVV?FIEjSG~G7rCL0rFSwu{kEDolRcf47<ANRQu|c{H8cqMfWgKWEnL*707lI%KXf>rl#D1yVau2PB-jY>57!0RT+D3^(hOE4VRFKu-wgcuiJp`5JNPA*WPu!2OXl7H zq115lyRh)#JV`0H)y-a5y5`@yV8?XyaaTj|^}|N3+p>9^9-De8$=$u@Mv2JaU0SI> z#N#0CUg{r70aFevvCYoPUdx8K)@KdZ2$43=FWeC~{9yMN^Rs=UGJ!|^>NL}D<;%@P z1--G|TW`kkySmCA+FVl62K}Q6rhu@}h>y|ny}$PVT8gDW@EGLY*?+&)?;q2MU^dpGTEU!B49G+(yZQ^K$!BZ>F?wJ2nBc^Fb7~Vs0wPo(j_(Ke1aK zrQV;72E=ZBUyRAc)s7l$TIX95pD4voP~!%h6)cQN!OF#tJaV{Hg7nV_zC3?- zQ0k%kF@=F$3nX$~g3PWnI(uu&pmO+bb=kXDGR@9=?={P7{K=9+(ef<1G_2&Y85(O?i3h0Jr`n%vnL3*MeRXtTRDWo3JWPM_Lp0WR= z4M^8iVmXzv>dg7z@^DG)pP$cm0W`xsDO%FfXi(bjf#Uysul-I={V(;0V<6TiQKay~ zAI3^JAvk1~L7c0~!y-ZS^mIW%Up1aRl47`n(x7_Y^=7>{vLJW3l~hGfcs>1Kx|}g^ zc=O35MvPyg9v77tuUgz7WA*R(wGhymWOPaoS7HH=-Wno=>m*N9tB6|#4P@y>wF(4R z9cOuH8U$WO6*x9(+zdla^&wGzsmPrMmQCF!EJ{Y~Zc*0?z^RUZgB{Y|Pf6i*M*{!j zk-NVr(qt0UOt`%KLTF&q2+cp1kx z;c(g!1?(k8xD3IJ?4TXXomNSngkQ7od`LekD znDgz685QpMgcqixM1ucb?A3KH4B+>^t`u;Xo|;M%@lMju=eL^65fBuV9~&G4f#CQK zQ)#0~TA+aa9Gz0Si1+E%=)}On$jC4Ela0wjEt2zuILsUv3p?yFT+b5F!k)BlkLU8) zFDeAsYiPt8`zOmHXur?xki+3%TW>U>I=C_svFtFSdXb};{N3FwEC{OiOaTFI-g}o$ z(8oCJ&2TvX(ZtW5Ia?5;{AJvZdYvu%vwC)}%1I6(F*kq(XlQ6~yRbD6g#G^;CBgc? zQ4NBGI476Z&dQ3x`j1koe-?ybU5s*MeqO;Yxj;X;j|PUv?G*9-dsf#$r`8TQsPHrg z2CkVwFx3(;iyY&`YU^z1%BoNKpt}RrR&b^wX&O=W-VvcUgv&m8m+?M|+y=ZFoPx-z zg_3L-9Cz)WRoB$)roB}&HOwb+p-Ki@xFCI?uRoV>z=G+?3m~hm-$}~E73{}Eu&rN! znS`&6O(6ye^q;1D@2LC0>QaOrGTk>Iu`dG=KQ3u*k$gsWxLOUH7EJB*_;7nqP*pVv zya<-~By?&dm&-GuF;&-;{v%@L9GD!N4mPYJ^RSH46-Cu zNJeKnlaOVwu7*G$pp07a&t?@ABnk?(w$4T(;V$-vua3>j#(77VmeQfv(O*>m?|D_C zSN`=%|M@G^ipmD6V%MTyK3m%?60ZL>ayi5&4w6|>QSp~iZbC(GX=7E0-BN19H9{5Z z`DwAvcu)8S>;FQQp!JVEr-Vohg^5BihicOlVqJLp*HlLLa3r^@OuHASXJug}EMhK} zOm(x6^g$y{zn%1;fo=QjHSo*1@YCA2(Kl!r>h+T#p?HUmj&5cYAGEKKpOJF~?aMPD zpQ>bia!(~$i4LX!(_3ed}C>TRGMIgng>Efz;s3K!!y~fpiR}c3<14ySp@txpon1xLr!lb(!&@g*r4RBdnsB`#0Eeu6jQdMsAA zT2$+bC;I=_3it@-?8m33Hcqarn6L*1CKXw6@v(z?DGiv=sMMdUentVNmUIuHPOr&U z+W9&GzuODt^j}8y7z3XoBFUZtzn}X1M$`A|HR@IRPKsFWvRKztRgEG* zifaLFw)!#a{s;4V32b+h5&VOTo9!}12rkm|74(dNU}c4uHpQ;mIO4bme?;sUwFD#p zx67Oa0jH($4WR^uf)>}{_wkiqo&}t#Fl|r9Dfg>>hVaO+;Iu}S4qXv`uBv3vtC7o+ zPyQzHrvroEi zys4_{jF`=-f>LfS(TveK_cvwui?J__2B^TUy=CDvTC{BKXM|~)7im$}gd%6nnDKw{ z1{>k&;nDDF0ZTkSJD1nK-zn@~#5Q!sd7sl9+dh1aQk9<@78Rwpe1aZgGN$%s6mEhv zIq~Ak{Gh9A+b&3mRepAIlIIYgmM&uMYM(odn>U)d7Vbi~gQ3uabzCNUeyeEwLK+=P z&m#jKm71rdOqN}p+9kiJ9+=u?w;!)JkXq70M=kB9E!dpH@LA2R>A zos{K+we2>CJ<}Fv)`J1Xdg;Jt0jq|j`EQa1jx{d%V}wsd>8}sN53iQKYThNnU95M} z<0_+OwZVZ+D=)Ctq&V*26VOJvKMTgqoem0gl!>UkHIPl#GwUg#r4?^2I}}dg`*Cwf z&*h+zR^D77rYaHA&&R5%64h^@7L%xKwVSmHV$M3rT?U!zE>{p@91o zldO|U5}j{g7d+kmO^M7}5pPIuEA+`F7% z3{H+XfogS{9zwRj?fb)QuS|Oi0~v@^z3BGY{ootFS_ILLF@I8Sp;9FT^es>~_By%h zRxQQf6isEM)3TN*^V)y(mQLZ4{Bf|wV}s5NW&00I4#>s`!q7U!@Qy#teT`|wnnR|I zu15N^HNV;HvSX`Q!X{G_WRT!(&?%3omxh@js&^-|cO5P{fjm=J>$#zrejZg{lOIP! z7XRsqz5U=?5Al?R!%c9@efIn!XTK?bJM@}Nx-cX5WF`c(>Cv+$umFftyTb6r@3G$} zeXG<(@paNCv-F152;Yl2iIdDBriTV?*OqL_*(#eMW!~~E{k=*wsi)1{ooM$tO*y*=~KN}Qd#csNnC{6ps= zq=my_$oI`*{C7jijl7>(Z<)8|Sa z0CMqw9|hJrrmK^m7{#qo)txG}RA=URV|6W*u#)n@kgveh4-%Ng6R|T5{=%-|6pTtGH5KoL*xIA5SZ5#;y8Bldm z`Y^7{mo`_)m_nsxwRxggWZ>Pl`syc*R!OToTU&2*#jfpadHX(V^4*+*LhQ+LwCk*T z1MQ@5&%!6Qt|zzPfG1sgl#6wrMTJf=bci!CCB;l??CY^Yf??9RPAE7YI7SUyD&Mhv zeOB0lR66mcf3?+Zxo=z2Z8_+-=0OdBmLQS204*+dHHpfb_*%LKHl;RU8H#U=~Wf{ zz`Ta{x%WJ;MI(3fBYP)94~>X9&RNZ9jAOQPotdQ?oVc6M$C}@OD#{A0sCtJ$oW#xM zwiO+ea4Ua#&D!x9&4~y&2kXX-Gi-0qHD9sj6iV$H5{n|)Enn$_Z88b7t3U`e-Ay9% zrbv@*_=%WA+(~je#5q8;(E>}ClpSVcqF_BRp$zX`TVt?#7H++>m@v^rB(##7Dha~D zPa^}tuT;gI;yRwc5_ei;2N6$T;GfdY)xCg~A8PS=XccC5Rn>{R+t&79=qrfD>g7LG z{k_$EOQ}-phDO3Y_@wpZXM&oSOWXhB0@x&V+f4nC{C=}%DcT=y9_KM249?7dfAN!n z4!7>?)%bJ_h@sg?GsC~`94TyF&)rn3<$F#&yLwY6CnzfG;y!@-%?Umtq!=o@CVw_A zh#Q@u>UZ;2A`Fs&8d{|3bO~-Px>;3O5;nl<}JDci@N-R*4 zH*FN+sK3^TX%j2xg~^o-4Gpc!c&Gd4M^@c{t(_fJium!Rtuqf07MA;(5x&>g5f&XF z8*qNWr;a)6i-KNx^;Z~%Ibw|A=4{4}_o;(h!xi9SPVU?Ak`>Y68r=CH5zzLQQC* z@5(YybovsL&33^_V6sxhcf>(k&;4}z1`-nf(`A@~hF42+dOy8H=H!b_id8$g2u~wd zh9Cp02KM&)`ZMdtLyh9sclT3MQ_QLKU-+qH8{Ei&DGYJ>DS6wt^CTYhSB$IA{bqT1 zc^_Fd;MdMuIwzaPfv~RGBAyaWnPds;iK(NfGJt#u=Pv8-)q`tC+Mj)zyJkH*fDP>tZg|@!QmG zGR;i)8(CF7X%O#(n6#yY5r(DMAk>wWl_9wKrKKRbz$`G(p179BU_)wwDs`Prs0Fje zMd6uT{!fr*=i1WsVMxD0o0%B%jPvs|;^1jTMa4+d>M3~cf8z2e7{2vpI{G65e0jR{ z&{R*4FY}`nR3K|%NWcD*I6OQ>2t!%;>6}u-sYlbAdEAFH>cbV+b06FdTNxR{u_4hE zN;7eHkqlXL4sceZ-58u;51oJ9m8vSsp%mHuHKkDKwC4Yz=_-Tb=-TDr!4ouiAh^3r zLU6amCAhmgAxLnC;1b;3CAdRycXxNY^L|yA+JDr}&hDJ^NI%_u7$pC={m{}m4U84D zChPFQ0RA~t4Sr`XY_G|W)vKrMn4a3u8aVqRydlT-l^_e2yBnh;{|82(0FWOk8VZwTXMTCdPbaJYT!`#e_ zF^#RM?VMZ~;xbr(1!ne|)fb|=r!yh~d*iM(-*yxAw0`kw!ORwa5WZs3(obb+(|6Qr zZsR|L`!_#Xma#6s)$@6T&XjnApc&Gd=t95!LSbK8(+GwJXwu)3&7^FB;crWcD3t z_wV}3blRvX>KPt_$%I-CDR1-9&%SIMPkcG|#w|p^Ed08b*7op@IRYR z4@>NfcKx&5g-(Apn&khg6OH#V%52wU1)TthAh={HO<$e$R*mb*w;#f)QGotfNpI=J zMPnwPv-ykWel}PjCcxC)%YqrD!`JxGEwiB6tD46>P- zEKGjpa#E`V)6gg7?&;aWdx6`C*NcgClbGbmCfi{>R!H;?HYFuRNyvhnXK7$=7AJ#g zFjavi+Nw=hwU`1Apxs-ourzv@mPtU)7G5^3n~Xd8Evgp3P((g0acuZ|Lp~}%MP0#~ z+9&~j;9F$S{Adq``4?WEPSaab1^G)qaWGvvv1uryOtz5X+pJzPtL|vt+w}bK6}%UI>F6$?(U?ZU?z9|GMl^p6HBXh1|gxV(9 zXJg==tA^ugjQa2u`?ij4RqO9FJ_S*FGyt_)DRs-!OYS%n8gKzxpn>l{uQz^ng8n>+ z#Na@zQEPiU7XX-xhN@ls@MB)g{d007TA*9V&e=Z8#8(eFs$#nbRwVmu!TQl?4WUoU zY%{zWIyBqtDRO_6Ysfy3XvM(&vgzmx>V`AgP?>LJvvo(^NbQ1`nonp{D13GnprSj1NTL zq;R+{vj|{7xWic6(zW0=_=t#@?_`tfQ{{YNgu|rAn4Zm^wGW&x0Omsp z$9|~qZo5fJKkFAbDq>B}Y~yw8Q&w2@cls74mLYwC#)_{ILkH(o`aQh6@t<$qi9Naq z_TbjLZrN`nfb-pHO(+1cq1m%73cZYLW!;TGL7HPW!YdpT+B8za8Fnu*+aHnJ)_0;D zTr5|gRCSRa5J*0W?0^iOTF8fM5n}`Q_AUIJ4RV<-!Q6Ydw^)&`&G%B7>lb#aeCPZF zvHTpycq9p8U7^&m=vmyUvX>9_vkdZL{f02OxxWu1{I+I2ONfRKu^P5dNwo1YYb$Qm zY;_^-GqjOgXBytlMqa{%Q6f$4znFQRbY`SZ8o}W&xe(zlux=5P8QRUkj}8LqoL#Fq(rqWRP0ZcdU(4%vcH0c z#=^gU%sf2q2a^<{iUU?uoT;*k@n-BEJ42uoORNO>bVrv>gPN);$T>|K7Ci-3c%Sd& z46Tu~4F(vj_kwwNV)JVaU~S-eRP*(4Xg=VOJ@rFdfM~}{g)a1uFLIvUm1(kL&02$3 zGlZ`8Cd?dkbN0)eVZCLc!+$~@=#yaq=Wf@yPj1|dbC;YvH+mA(a(q-8e>s&?sx`A@ zlz_h!H09)e(B&VW;@D=O|KOkjIXJ(N2uD!+qopZ>nyTEUlUvs}2PHbJJ$6bkhWc0z z?3`bHw_a%a;ft32*Rkds@avObsgSr-I8Q!3^OkLAE_fC7(8=-NzCwhs^_yU_&;hO17>q-gJR0@$Cmi5p z&~4mPRnOPEw-}-t{24Dw9tB1F9ej)L!|*@L3JOXpDxLEB3NPcU(-pL&Fw6kH)u&b0 zHIJkD1Ue?6muvZsbGS=GF7GcGFEvk`R~(kRtwDq_I|;GV`wk2pyD9Q(E~$HqmTKkN z;Dkp+5gZ{kIUP(MRdo353}IjPt<25!Up>#Y-_~JL$?@N>{{++NPm<^Ln>oD>uLlPJ zbS8N?koSF@R+hiHz8+vhz~D@^23he9D=teBT&s;PCz=gQL{a@9Z#BdB^?@qW>vFnC zd2v|l-2vU3tHFucG-c-dq9=i8AK&sTqdf+U5UeL$5XQfpAZYnik(!*@N zw8^n+#fq-Bh{2kh`si1@$<5TCr$Z`zBysp?J9ugGRl>8`$i4R(HA))Fk2M$?VB`b7 zsDNvZ59)hd5>z7w0OUH!3bToJgpa*=;=5jALUUQ{b-54&L6GzTcFZG#&*P|zZo8(l z?EEb&c!C)Rsi}}_{kx!jNlUzmV?4lMKNP@mZ>1ET zwB|)HaG95c9^#ElIhKjjAAHcj+~q=JmE>igP1~2mgAGtS3KQ887~(wWG)%wjm?qk; z^1JU0?I;&e!owf$?9i><*6&7n8I6|f_};JH$vxlsCQ-$~j0;c&3KQ6Ntkf9v{!3Qm^nWj=-{nE*q@7t4FnP#0qZz$KQ+n<(}mZBna zP!*x~IGN-nxb|Oc>g@b_*{!9i*?!;4WV6=p?c`M3(&G93dscOIbyL#=)7vGJ>&fEH z`cE+HxkZaP2863z|L2ZHYHT%m_O*qt^?$yGVRI{A54e#-btgGHQ)Nkc2mnnt!4p{h zK!tH$;pplJkAP2Xk)l8=p<1u~9{FG!e$dzUVljANT!!l%pj|u6tlU_fwmJNVABdNf z@((WjEBlVHP*qNJXtEnEl7^YUaK3YfeA_2=>|xKi?x-H&)WhCjyDUR!ddYZ_gz1vmD((q_ z0PhbN%Smo0G-kDGrrWvoS?GFn@qMsp-@uWS5`0=5Z*Iwu4ZWZ_Yt$A@onV7(T4HvE zR>A>pod#N34X4VP4z`O<551FjaBOc$zC-)?Q^z@PGU<&3z+?c#W& zdqrMg#_`_nB$44XC1sdOp7?D8{c~H}pqtl{9{CWhG4NXfs7|Pz+H!9%Ewy?v6;y81 z?>t7i3+S*!nE)czJf0^ret^4#2G(CG--V>Z#UVc8V8GpU+7ZUvM!l5`} z#=W7~|GnAuc;5c$q(QIM?V=Y~&xi{-dz0?8B$l@@W&tPy%?JyV@R^~ap*o;1Emk-S zYGpr1OOMSmI^*be4P9-8=43D?jc^kv#t)3FH|7v#*eabc`0PX!-;4L1beCY}vdw#7ZvlPFLrycFwbs6n6~ zswttkEb9O1%kdX3{FR8+;=_`s{{OtD+OoL(K0!LVKRc^IYy(e=_dE|DR_{)@USEHR zzkUDyv|*VP++WdQ>1AgwmNGdSrcZ<6U(8CoIUE*q9&Y~!BmXH}wCNop!#puIw4~PD z&&=BETdG}3oYfcHr3bF5#P`5KMuMb9wR*{ofA{ z|BK=08{L4e*F`T#*RWpVgg~I!IXK$hUY~@X7REu@9n~-^NI+P1+lm00D&QD4BZC-F zExE}KCSGiIK8hgV@_C%fY` zByp*RKYUxJ6z*wcWK^doEDzC-O)*U`r_FP6nGiCd2tedX#qQrRuKHofzc$3|BAN%u)Vf0<;AJkiJJ{y9*;)utgYt-9SL)SOfkkGRaXIlrH>)_y zv$n*%hMqFGBkF8~V~G)|XT~2*uDj!|*yakS;lWV_Z=Kic$nf3kP>01GxB+f1TRGmc zcYaqg%b;x}D^ce#6x9pTR5q>he^y)q8R=VQ|x>GR(@^HzUnnOL*)zzi0=>wLMMlDBN&z*S`;Ir0q=s}kH3$K4g{+OPx7qa35KXL=G03u%zEDzlEu z{T5FlsVl|9*^^<#t5|DkMjyt_kLryhYfN@Auqh0v0Gu*%@>n~~-<8bbxZA@vHtAu< zh{%r28gss2a>f4wFO>orpdu%Um~b$hZT zs(Ah2g)VUYFGIldx?c`&P{$yJI5rGteC8t%I#+mq1{b@gwRA!)o98m-235o>f`_DjgIR{`F znI5OsIwGJnlxwh;2rs#OZkD4R)y440tmNs1f1_P#I(Fggm42oHz-`4s}e3(8)qp$DC9#;%^* zy`SoB*UI-VgYiKg&xF~uMcHPTe~9ECb%r_}!EXkB#rm>Yp2cTd7Ws- zC4JHyRsBc!Uc^tOM`k;bHSO$b?1eh;LHgXQ(99w+<~osKj0ZW=lk5#rzofAEHcm5Z z7;FriPGVKX>U#gQ-#XsBu+jPn3T;6rnl7-`kV=z=Zq{2by>2qS=5%xjeME`WZ6=S5 zq!cFQiQ!I{JM-O+0a^U`BrrW&7bGwH;{4-BOh51L?v5JtKlT|^F{3!%9xn_hF^T`_ zO$EXuBN>^FLgQ0^mtvRX)ZgI64$&>oq|wr-gy#M0fGrDD8vLFGPis!A@sObb3DsOI zVFxi6Lw;Ysy(RV8KIXeco-jX+3L{*oN&p$|y)>6LjisiZlVnu*0ftle>iZ7_sR94k>Bx) zi}R-tI}Ntnko$LZb*7g2xFa{*f|8aHwupd4SY&;Go@uM&*;Gc(sD5oeWCg9<5!o>` z0rxYCUuK7)S4kddLfvua+0kG=m49(@0a`Q)c^~8@5yu%bP~3l2n*(M1mn1RWS??d8 zp3J!eRv{2)clU)2yH+rryq%-JF$)T2c;`JRMJBiXW}?K&*F++t1w;Nf4#nq;{zqHw z&3>(U9Y&LuRC|}`!c3_XGLd6)11dw^hj1b9zD%Dct_ufSgGL69<;3RwSQC1w>|)}p zp<1-T^d4g_Q=ECuqByIt#3l66`S!qp1FSNf$?cQvz*ZQXZf2Yb{Ti;SwCG>rxlSm4 zQtyDoop3qMZg!3*?skbvsX@)%Q*NyjaY_+11X~PIm!>7r)Zxlo3uK|WjrCI1avI8c zHgkRoG_s98xW3deFP7$|g?736xE-L8&>|}H`kpO)o37KQfrQsd0;`wg?Y`f1JVQ25 ziD{r(HO`{41*Bze3z0=-XJ^~`T%|s;HG)w~E!J40-Tf+`Tv9MIYAltVMMI7Kb-vhq z&5m39r!_x2yVGV5;)%_t_y6R**uO_FQpu$iZet_sZ6=#$@Hp*9+r)WjP_^HLexyJ7 z@1l^1NZR1rpy{=|#m8a)bK|dWs#xgAUAWqbYX|R%@9ecw)ho2>&cD;YTfp)bKNYst z(N)J4wM;eDwol!X#c6W0Hc-k~YC}U59VS^T{)p%&;${B03m2sC`E*vba7Fo0O}{qP zF>c|Qr#vjZao|K-OdA?22VKb{0Ixr4FD(BiSW+h;Dxc8l;L>bl`>W#c6Xo#a{moQt z{I#pC?d3g+Wdj(xR_4m72Pxb=plV3zcs%jqlocTA*nQ~+=!IQ-DLtz4F?68->+EO1UxmodZW>HGZw z^+d;JE%fC#xZo*1`>mISLAn6y(AZEoDkwKCPB$&jd|TZtV;QU4eCrm$iN%Qu*M5kw z5e+J22hM(#j@RvL0)@xnsO!QbQQ1Us|Pa^B}k!@D2y92^Ln zRWW(z$-^-{OK0mZY(r~alvnfCF69g~WFbFTvZv)vFXGm`!o%fjj6pm&XJmXlq5bpv z|8oKO(#OCWvSCSpj}LiW=j%MtJO0O|j?oaZ7;;4{wX^|lc6KZj__LjV%T zYiepzpk`-gKEH_aeSW+-T9ll%X%Kq7-}O!pV+C_c3A?-xkNgRW zqq77tL&hyZIRne@L@}FZkW<0Pazs5IxIaI0-&$I-5&Bt$#?i3{9)&;ZG-Uv1xhAHX`$Qy_Qzq+5-j#-R^g1?Cd62 zj+Y$IDtL4lHvVA^UyL%Wq}F?TnOs&+trQE?2ygG~DA3j&+j+Fy5`{R*%|#^d?_=L} zIqe{@Xh^LzKHl!2zwVTKXSQ3eRa~|jI~>EL8oD3ps1|ryitm|f1ZAc^^@8H&i@UW! zeh~vm*WUvZ59>5l;S#Q%hTKM;B&BO-&*$y^*I3EZot+&J@UN?>xdNMj7>VuWCeSi8 zbDYa=PDk7FXu9R>GN-Yq#-Xj;XDSs^qpFVBg0tCu>IEOZmB{?p|4sDvIQ zGxpZp_tHUok~&S0yKuiS?o;2^_HunNHCLfG?u&*Q$B`3bp=FEBCGr;!mTOcUoai6j z7^E9aoMV*mIxB6d&b&_Pp=M2AN!HoD<0wh>Az&w_q zyox(}pmMKFj-NH3vB}!;A?Z`@z4^<^(z|aOu}h5V7*%mYrWGlr@Tc6;rXSbDN-@D& zG)JQIfuN%OnyWhP*44J-PR+-V2S0wNc4pVX(`zDcfo{*&{&hq;tTPqB;=xXDdOc<8 z=rA1bPOV>Ao2j8|W-l4Q_(;j_yLFhy1%4D>VqOhH2w6WFvKmt>@w~^H&XW&E^TC(r zWzS0?Z>Bot6@txgWJTL*e~OKGaQGh%T~!jSmc91>zVr{Q|NL%1XxgyQY|O*UdpQ}U z_dFpVr8i4#(7;OnGZ*6BMz@d=U8jiZcT0UIvBkNfWNt+DX8MmzBe@bmMtvVt8T zNc9OO@!7ZI*3{A>@wwmV?Ck9A75)0YxuwOhYQChR-Q)TGVmQe$bF9aR!Tk5)tf_=* zTCqA0m~TD!IN!h9=kQjn`iK^cno`YwO>u3)lW-F_u8nP+B315v(jhFJs^s3@T4=6= zs4r|#?4hG*#y6-h9C=D5;4?{r&HIf%`iR4^FVnn4m$QS75QB;ZiP-@}@>E+**nk`|Z5TGAw&A-IMqL_1Mt)% zf$Qr1(^)GoADi4-M*rZob9ET<9993y#=ijiJd_=1nl{pQuAV6O9pT=!EfBX+T++m; z&~5_vM^_iLp9tB-td{M|jNZ#kf#6LMI1mWU`7M=argqz~>T%@gzkYbEVx(aPnzvYf z4gfunk#QM8V+e0s2`PG<77%hJi}{_NKBHZeoSY28w%0c|bqx*3{_A$!n-}+kaa6&< z!QjYlrmBiX^YLGg(TV=??IEm`A_`tCud{_BlJ`OvIhW{C^)!4Q^GK7(N@nlb9WH9z z^JP-q4RlFh4%};WI*En_?#!PuDEh)fa?*kNXfIW)3YwuE-J+F}+xrlvQMg36HZmHE z=ufHSG^G&?^LLl^Xx&|l+}s~pR}WJfOiXA7Lo`O0bS3Vf@9RRY3xoMiT2URAJPnb6 zlQLqRXsGAbI{nXwIoyrL1ZvHh3LGe7Vb?=JOrs~s_3@9YSew$0t5{kaeI)_2c1Cu( zPW=l>p0*mArJ99YGIy(=4eNisxD<=MEg*VIDJnjGthSjryIuT;yf!4%UZI6*1zC}8 zLe}g2wCaO!X8MHhmL?;PY={{)5;T3kU2C086{JYfRQ;rzWf) zQSC9dPDzQH%VN42WGaDDI?8YGtr!-SwF$M<_@qN=3&A@%i8qh~7_A-CD(hYeu!ae( z5xvN3`rBG4Bv$c}h{gg_>SF4PA?)3as@j{dQ#+rbEhf!WhPrAP7OeW-h{k-`2e@Xg zRVP!5CRrJjTG2+tU=%;q**6LM2?`D>4Ud3QX8CIGip3TdTk*E%nzS+ae=B1+WxNL8 zyJ&(%HtS4uQy6o(QsRzt681SOPC{Irc`o8je9!`H6wh8U^`1uteQdTA{(^1z5 zO_`;urpvN9`1}Ko)nw4ofSOKBd`RUjVY4954MyhFy(EuhzWQU!Vy+_JB7i{Fjyiw0!V|vRX&kyh}R@Q1hnAZBsez zRxUep0>hts%IccC425WHH7|uaLlOgASLxgqVf*1ZVtz%w zxo%m+-H1baQ|DlUCZ5Dm<%e&BeO}g@rb?BE_UDLHV~6B^PHfpglYX8Pdd6?F{1usH zAWiVs_W5)T%1pLe@heAb;%hoEPm$;OcD;6pegg))E%6ptxVR^+SdlAo;zWVID~@eR z1@J3V6n!^P;<+I%%P%OXV{$U=7=oA9(!L_;|ouXW$7dOEqY$Nc`Cf;2u7ANp&WsT6hJnKQ!7RrDbsOBj~+ zSENc9Sp=>0pFA0xAWSGb|2Ta(p1MNXUYMe-_WYliog2$mgD5KpWCi6n;o097^AVZ!2&gJG+WFJNYFy9uuHY=>awUi z$bwnnPL?n@WttO7ZWFZDE*!MpZ=LO}2F%KpwzMY2FOW?p)en`H;0^hFjZd&}{xLrb zqny}6I|m31DRT=lJ~}dVUteE?RE{#$k{OGtsLrcx+s0kNG!q~L>yqQJlj zFFLTiqp9FpnL}95#0ZHqG<-xo{8~{HBNP%`ZQzt^g3^i6Ho$448BRAk_H(!>@q8hf zY&2GOs1xagaIf0U1xc1bJ$o504qKxZqo%K3a)%nn4O6=(M^)GHQI4$MX{#>tMF?2N zAb4jQSv!n#sjn=SVY6Dqo0j~?p7uj=|Kw~|MWcI2W>wrfq9d$7bYnb9JPhULHb%i> zJHrkgpN92JJ|4dJ)_8C6z9l6n!~3H5M?cA#D=!qg=$|LQr?cjx!=2&4+c-{4^RJMi z7ZJ>DFjQqT)|C}FKxqJ=&%@6ST>E3YZa98Y^CX%9` zCMb8VN?m=UZR-qY6OSyoiW5*elg?-Pt+E!%uIcGxhAT&dBVo54MHG3l=4HHE=)&f#dt|za)OtFsEy-y)QA4Wei-Doc2Ut<$3Tz>7F(O5+Q ztnQGge~U?iAnQ=-vMKfs^Dy*z>`*5FU)3zFQ)f{@_l|0TJ?>ZT7QV6 z{uG$H%8!q~J!Bpvf5@xYw?K5jjC-VUk1P%7!(R&8e}_bWB8=3wN9ClLPz^441YXBD~XXUlbzAG3}!|d$f3&;wFk@`Yo}l7FFR)W9^mF*SnjU+H)IMG#l?C z2U~(YkSM|=<%0^^1OCHPL1Kh7lua7UUtQz8&!Td)U4{_8mKiV$Ol~eb1_tf_!kO?P zw^^n_{mN90NYA<)rS~}CnNYb~dFqJGIGp-)EXKt%BlQh$!Vq`N=-O@>47-P{~ca*zv*?VFn6qS=(qH#Rm$9_xH`R z2WI2s3K$acF*`M#MBGHzSGRyl-!vX=ss6Au=>RoVH46ga&+%RRzcz|(CaM=W{vxIW zQXy6X#ntq5!#lDzeVgm4d^^1~9BneGi{aoGk{vu52nbxT&{pM0>Dq%RzJH-buTRljL?$&m^FEk@hKmKVFP zEX=Rm4msO>A)P<%hXaDXMLMR!;Lcbdl1ZUA&N^%WjnSM-ew4*VP(|YbtK@umloc6@ zC5IX{ivc1Ibvlb239k9)l;%_OPZ9eRvC8LPmzCZ;ASmnzL+)M|d66}Mz-S_WcO-xLN!g&)D z6G36K8D@X+_qX4@Bv1g?7#^YJL8D4RRhzlZm_-f5r;;YG2KmqDAPK!5n`2&8hUq@| z%A5htEQza7c0CnGzg?2s+E!%9p+$ z)ztjHn`6?;`mg6A5%_(ta=6Bn0hegzne!@V4*zOp0$*twiKYyYTHyFenM1uCd>ci3pt}yMg5Dn4o9t;pm90 z!PM{PY{6{<+IB?+?#Zaou6y3bPr{ctE|*N@RgFd|TPu5C^m{gs7Be%bUJHYGQ%JBW zSeMqAKwtii1=jC7*4yryQX|7T%k(*o+%5Pr&XVirvHK`l)C82ILu)|dcKrGbto$(& z+m_Pmk*p}ph(W+a*K)r~!YmcbG-6Tm)!z72*amS_!82AV93-zGf-$jIs;?Bi3{|f+SUV)QFFbcT8t9x%I0fr1dRk zHzb~GdLow-5UVV1E@J*H>+sz?kVpvzap$ksp(EmspS|dcLJ{isuQqtH)~QBOvkHw0 zmF$TAGY2*ei)pF_{TnCmQ(Id{Piw4Xh@UoBc9ZA&eRp$=2{`n0Y9^an9m|R96M*}`> z4}PzJ*C}>y7W4lqyA2(6<9vo*_q373Re0%> zl#qGJH0279T(;Nit5m~r>nJo^3Gf9kN-AiZY+zcgUotNtodp$D43AX7s)yP-g55+|!O7PvK;;4^d&Q02A z!7zT~d*B&%c`~Q?#WC@lAygS|udW#d4J3p<=d!IuWyM4DV=KFjhF^-poPyk=S7)=67O}=wf=bQ#3>Bf*y=gd?nKzO!dnBxv zsBddSgxGBq@#_7#V`u!qV}d@)>szl{&e$-#WuARF(Y>N--0jFtx&e6RaRqPiLqgNxTH1vRXmx@Pnmr# zLN`+>02BhIRw2LVFv+OptFx=qxlUoMwb2(p;7ctR>M0rE5lahr5PYFmtoxU&^N0zO zkq=Ji8>(g+?~2KaQ(vl>V;W4w4DVJ~N+`9aZ?g_#qRk+240Roe8-r27QO`5GiF)>g~&uKOP1&&L~^1tV+5O9V#M6!dH6pTjHMPg**d(p;(=ItP%$!Oq^ zWV$r1;!36*6&17*dGTD6WA?6ZhLETTPj0`q@d*`qDfY6pE|JNCROy-hzAeYKz#a~B z$BH1Khq{exIniT3$c;xndTtEdqI0>kc2y+Cn}okT^wNadp!5wW(oeSb?1XwbY>{2K+IF zm|?RSR(w`Q^G{sgp2EW}S;F^Yqs#B4)0Kt$Wls5)$?f^5njRup{X%w^+cOx>zZp!n zm#xtHS$o6j?R%*bDvKsXY`y0lNdDj`tx#3UWYzuJ8Q87o`MP!O68dc0PcO81kaBZw zWfY?E29Yh=1$9cODNhZZB*zp&yF2IHYVv${!nEUYzkjm_6pPA?_T7dGSmMiZ6Xp*I zzJJFLPT3*7D$6!pewRwA7~q+r|5}9|< zr~Qxy{b{}d3ZQ)v!R}h%yj(>SO+m<_XoAGT{`K_0N%DzfwAX6)=q@>qpm9trzDYI_ zQU;&$w8*=GOlR|&ticpM<^0JeW#??}eE&vv+lI@#{h8-jhB}^d%HwG4?>k`J!OBe9 zyt-KD=v<|oPk~L1!##nnazLr@myki|FD67zjN!@8$vGg5t8}cfr^!9&h+y?)eiK0J#uTgmzmi98u&;QW? z&m$bOe0Rt)PWSk6MAcs3=0{V8!LvQJ{Rra7P5gzlIuFro345SCj~P*iAmphAPa<~> z#^H?c3x6O;N1``sH0oxT3V;P-lfJ5+U`J*-ee1#2HRxqY=r6({+Wr`X5LmsMwe@Fs z-Y2@ziHVCX7_*}XU2iRqp=smcS@zbqDM|?CFOlh-JY-7L(ga$*h*A|-C-$o&%>0SI zYxkuOm7=No^xT-vI0&_YmeO@-<{3s19U;uP;u#mzJ{Nr_BM1X%o-d&%J=Iz0^Xx&f zMvZAZ&4%(G~e^?ea&9n_VvUXd9WippNzCOZni#l)ObN>dja}G`}_y5?M zBEZ|761EA*3^0@SyS-L^^0NAZbi0@CrOLsp^b4y4_AjUDXYfcYlkW_~zbbH6<9Id> zOy!HEF#baOyv$5jrAng#2xanv44$XSs%?X01p&eWvS&(|nl+h4LAs$VoIZqEKZ8-S zsWC3F$JP?2Y~K>;Zkh@w+dnl}VKFuRCc*FV-ceYPwY3~tGSP$mF~si3uc(osPwVid zXdV9h2PXHlHP-U6>JI1c()E`?pGQfPpCUmB%jj@=?$_8awe~g6&E@_7w8(g8$r7&OpNe>N@CthEJgaK99X&C67_g4j0pC^pd`-jcZ<`6!^YKCevt&9T_}nO8udj6-v++8EhSNtskp#*ypaw$FcA_bpb= z0v&bcyA{cnJH7}EbCo^}l9V6V!i(SKlDIe^^jWFMS6Db1iDJvnYScC^5-}M0?|*TJX0IK;KfQs)`E%;Ge$tvjC?Emdp)hhT=ktcTiM!7@zDeB8qH(_- z2B{;*LBo@-WL+LtL}&~*Ox6ZO_VcY~Br|EuHFTlXr!sS!vfmzQ$}na7D3^0_BJTq> zRA2;SlBrlU*ou{xAb3ln3@62#gs5Mic(Qx$>m1m-TUw9v`NUHNLYg_aB5Yh=mPGf# z0uMjj+PYqRdaG%6RkyGntWz5a4@KVtZKOU|vC)%(c5_OmxWcHmG`eBOyXgd2oY}>F zFzndNw60ujEj5-_i*)e_-%Yh^_bi_nr08 z(ECYjofV6BxL09C!KG43sZjIf>`zYtGNy6S9EQ7+GPB{d(=LI1F4+TpwBq7Jf8Kc9 z@uvkXdeaagGl88LNyFGkfn#YC&J$&R881aAkZv!XrQP=6gBtv|`Bm|u%^ivX5vZC4 z1~HDYY5d$=Ta}-LCVi{t~sYIS5X}8 z^lfOL3r#u^3jA>46-Ub3-Gb!j3g-q8{A;>ly(BP$3yyt96@j7yeaD^j*dO2Jb`4`t7jNXB=_L$Rf; zb4TMxZ}|MVLK!0(^#}PBFm@Z_&85@=+%FaIDsPI-RaH(ye;VtiS}{Rbh)ytt0C>~F!fU&nkOY%`zMe3@$6s+k<;F?2uBve%!DNm&DPX>u=m(oA*8C6Q?t1*Y^v zw}s~toP*$*E@~f9&Js;LrRqXt2|mhg^FUNTofpgL5}4z@4GymT8uXUyM9FMZt zny7rvpmpRYKvLwZ%3|O|4AN5NxOzNGMX5K^;jFT??3;AL-8v(NH1otxY*53jUXjAT z3IW@?0;SMJgRL|!9;WU973?npDNmrvDkX^Jikz}UB+o+Yo2^ySpmO#92Ujg4imw2pAVboPjQSD*!x9B|y<}uYzp8smA4$9@spPG?sP* zemRcJ{$icbyouWREbVYB4#d_}HlCJbhZ@50Nu~T&34C2QscoJUaU`I({^kVROMh~y z?IgK~fJlE4bh(srdE2~UUrfL|ZS7s$c|LoG;5||^Zu;PKJJA5o8}Q}b1uBxwc7(0v z>@rBtTV@;Q|7Lr{SJKc{L#wXoF$+M z=EvVDc_AHktE>NUKr8wU(#jS2^BfGdhNJ&=|HE7$3rW}QF|O+>{+x2>SR!-kio?1S zCr{xSee90HbaLu7y``dq#%)c@AVZ+jH>yF2r7!ZPuUZY`gl`tF-_u1CoA+Im&+;fB zenGI0#q6I`cb$G$7onocW4$fI!9L;^S)6mo!O&4Q0+&almcS?x#?`bI41+a{>GOfW z6iz%t2T`b*=mMJ}riEJv-(z*V-3Hjj6Un|o-D6ryLPU;}W0#!etQz-YQ{qYqth6#O zZ|g>gr{o+{cEt{e2Lsc%?G5U{AHyrYNW$6@JX7@>n}qd4Gxh>jN5}Zy()k!)!QI(f znAU~kq|qHH)4IN{^#MQ!X{5Dr5N63f*^7yZS-{ofr+@d8{%J9+NSh{hD7U`-Z~ex< zDa!1YPrOQnH8sFI&kSbz29(ehJoKVfwAx zG@bu0gHfd1(v_*DX=!*>x4KHZo<1ZbMAF&}r~A;{W@uee$%K=)_Z*TNlR zON{qA$W;*s)VS{C#W=P6lD9T!f5~Q*8DIe(QV0MY^^jdoZJ+>oboYcZ!eEE4{&Amq zCh)Ot!|uK(1oOW&;gPtgRe!wNXfMrA?0r(F1|F!cQ|MjD5fmg76chyNXtSes{(VOr z?LVq(B(+eoo)Pl?Va+=`H_y)HdKavAqvSb4hu)AkMDhy?yerMNn-~^?2%f|O(%{{$ ztyi;mrWLGn1-})@D_TUdr^}&qose!hPfh~@5jB$As<3ZIn!7aSg;siuC{Th*5dAI!n<6!R7%}WvtdIzo*gf zK#9VmSG#l)BiJc-_+zpnpupbbZM{ zLq%EMap8iIAW!_+iKmF=>A{L~5J|)bnj@C^9&56)u-Jo&yUcO%HHO}!8#FXD3u*Qu zZ)M2Yp1ZjO?@}hurq&tjt77OS9;qYczZ@%Y-0#xVe5xr?J39J-M=lo*_`vsnG<{`I zoK3Lq65I*F3GVLh!96VQgy8OONgxDwcemiOxJz(%cX#*ue&?LKwY5K}qUzn*o}TIM zN17JsBbGF|L7aP%PNNi%f~L`rVwf1)a#k%3ocpp>bYg9X#Y*L9jEJCKx2a~?Lo3yw zU4K{M)Zz4V=k{fj$KaJY5CK`eEPVxiY~5$YLfHYQzkDSh8h7>znNA`RWUm!Wh$uNV zdRfX8Ww}P#g?bW1C#Y{3$;{?>EFBS3iv?R5H;$%-p4ewzLKgp zJb0u2g7`Rg`+yYK}9d@Ls*O4k*K-@$4OR%0F)@wU7tu3IK2I zAGVfbbIRQ7WjC-_jHmPKoyV1cqWjcv16S>b^?)pgk%}piYFaj&$dZfI(3LWUCm!nE zkstTjt}l~kG)dbD!Yct`Rhclzq_!&7-f%+K;YEE7S&&`vO3%2J0c>EInqE&rq>5zibo#W?#{L*&Srysz~xEmS)=EHBi9^2Fr zZc>EA2ttU3d!?QyNtvo&3-N*7eA=QHigr?mKx_$~ep7Y%s-IY*JM0X+&qzgMfvJzd zzqujm$A=~{!Tf^Y$=uxP5U))Xk2+!}gP`)6volDr1z!mP1(g z>zvZ!ex671j>w~&-AW{A8U`0 za8vo&rG47)wqIv9O*Jg8?)r_|Km^I_6rK;hI<~igOdOc*_>}~YrW4nMy0psru7mZn zn=qIF00+w)#mcS6Dv-#yC1(pv&1`-nnnJIerhd_+0-_I16fFvR0?UnT%_MV>=i9f2 zHQ{NhQ+6YbN^Ul7*y8*OrYS{paW@_9@?{OyKfvCGh>g~gX-Z5N(rRSoV*$m+DvpId z>po6$6D*wW#JYCv$#X1F(> z+bI|^Y9KG+gq9Kyr2<}E2N6d;<_|1a1J_*ki<|gFDa;3tw}00z--7xZ46Irp^d0A0 zt2rx|or?TCDD1_$&VQrYg&e)0fSyKeG6uO*q}|)l73Mp) zKjmkP7RJV4=vk$_5$uQI=Fbdwe=SL$u9g9$uJX6&V^szJA~^w7jj|@fVF%qKATfg6 z(|s3)zjYX6tV~$i;T5Xjs4o9T-Z02wQTvK9(wncd0HAd6lAu7{n^oL77_c$FZwC{Z zT14)ugJHxt8RrR?G(D&Y^j#5T!iM zc+?3FPR{&{pj83)DZ*ccZMI`RTXNaH1eX%aW zI5LM$;a}{ZWdK^(L6^s~8+AZuozz`-&NVY%NO4Q>dm_E zd0aE4^Ff<11*zB9p&ndQ{<_X>*ONv43m>POMFU*CINoL^Uuj($>3RYKqRsg#EW#zk zTR>+xeZaUm+|2qRHF-wrEF18YSC`#F}RNxAqrI-^fMV*kZJLPKK)m$>;4O z#@CF}4z5oGbW6-0k}&56pu@%CVipoGw)b~A)mR(YIseQZ?t<8fn2^CI34tf51JujA z(cTu-YA)zSv=aMp+JSdO+mew(_gnB%L9vLkG3_T$-_V>??>74?JdsPZt_sWB)B5n{#Gch94j^NAtX? zsz5h4Z0?#Xtfd1V)HzOCO=W1HkD0DK6;f*NPg89Ro)kiC!T6)vOcqlZ2c~VdQMBCX z)u#95f_?3`#LR8O4W_yne+vrA_sLKDic`8wi{zaeB3g@r4Zcv8c%)&5cu7t&$6}q% zq-~mE3Mq!cyM3qsa~M=#D?7(smJMkU5KyeQ1)~Fy z)_p+dwJvor2s>Ll5nIx+4SN=@%6$CQ*4B?qS6QdW4p&!K2t+B{?63)D)w1*JDQD{N z1;m@Lo2TeJK+?b<{2H*Dr1aR&iJUN$X`c>hqb7Tq%5{Q;gIvEG){)@-6x_^#7c7vL>0UPDiS0IpE#yR=0Wk&Xm?3dpW48*E z@Vgcd13$jOL1cb6v3a+ZsbtZnAy&EbpvL6t(M1FO9aLA`^T1-WhbGDS(Q&{qz2n~v zJ-a)aG%wz?tlCFeFq5w{{datdi3K(ZaaoRyAa z(;qv9N*4R}B!H|5%!@vwlRTcSkmzq`wJnm>d(32zyE`Z5ppr&JX%EyD4aOY0sIt3r z6Wlt8*zeBQR+mp^GJ9fj0oeu>xY1_*YFgK4{j+bV{Si?A%uViJ=N6JW~p!%NT)y)P_?7s>%Tb2K{D0;_JGLqzBXl~k5T3hXEai*Ji z!nYjq$yLaNIk=1i$5AtE0`=`DZTS}Op5I&=2-NPFk~7?)ee@RapL@FN2hPuzYxn(p z$5Yv5z|9Ik`Vx8eFn7DVB*?Z$5nyKryQCJn2-4J}7RUfKK=Gbg_ogoeg}Z+93| zmk&Mb+0ME^USp;ORoXBsKi2IGeBiRxKYVl*>nI7eiPvwA5Ay2L4~2vKa4U{*`soms zhl%WKPPO7=pLM0=Cq$6qFd7Vv^TZtzk<9;yCe!I^OiY#Qks(22bAPTC;_z3wOF+&x z(^^u@99^XCml1m2GCCWTm2m~TANKV;HDv7ntaI2d5@XLjEEMznV(_u#^Apz|D^t-8 z&83DwEg|OounD6(i7SgqYCcuHp);eqn`dyNUDn|I_Ktv@f>jbHI7C25OMo{V@)znB`JCXVS`Y6Q1 zcYt{QZv>7k@np-8>Z65<0{f;B!o|>`pEJYE*}%1=bvOJo+n%ze0Q=I+^oQ!l4#8>< z;pzuokgoIDxs3gCYDcWr=aBKXY$ik0R=bzE&O+5nvn5o}!l7WW=_*b$xi+fJ-5N%n zPSa9_VHLYGj@ua6PR~pJK&cG0G#%KGG(Ru|)i~04$JCc*JUB9$^BE1~$&swNAuR6{VnS0B-%CGN~AgoUX){P>o zULCK|XM8TSb7}X1m?%5mSn2H@2;P4Pc=!y2@J%XVKsle0^;>BA-vfRl)CtU`B)h7P zWv0jhgAW_kt@A(L19r(3hnXv8PJEgE12BUtwy6WC7z8Sct7jPxRLIn{pce>KzLNeO z#@NT#ELi3a2j6L_pt{R{d896=l2vg36Xq=WM%&g8yE}0L77APB`w16%qT6tu22_Ap&nNvUWU@6YF+K6_J!#gD2+-`K;}zug;nET)76Wz=(q z9&ZkJQR6r*<-n%9_4PdjKxOnrQMu`F2;-IP7W-M6z&zh=YVaJeHYu`|+P2}07{+~E z*ZFnHg}2tUn#mQn^bcn~KkKah`Aj!LS<{O3J8+A(275=Fp6~GzEZwmy$f)-O`ZNmM zR{ffWJN}(#;&TRD+7x5&dOat{!L2^IUef$|LeAozmt^!WEm_Cc3HYK5+V!@P@1C>b z1*^lYibDc#YYwc6fj5kwesoflxCdifx~_i!^?Jeu1c3rf%o*uHyvBX?GGvxGped9% zvrRR%FeJlpn?FV9O8EEm1sBkLM2sLMu03TWNdClqKf7W-wyP*!6}=W~cqkOzxmWWD z-nv#K)*WwH_`wm4+3?A`%i^axk$)|zatff^9`M@)=wQ3M%AR%MuOL<^Ivs>hA+2jg zb1)7Ol^1C%P&-7r43j@~1g6!w0_Zd=T06MeFi}sZp*)@ri^6a^EAYjCQ~H|{Kb89b zJF+1l3Mna#`<7e!)J%!`=_*M{Nq{-&Xh|lILbBX$?Z|TRDxr7l4^~#JF%7^B-#vrE z?p!R}Mf)}?i^IJA#RML4RMt)4$|ixWlF$#*uEN|GuWg3a4O?4l;DWaq{n2Yo6F^`BnUApb zHSx-+pkKn($JCohTj9Vl?a$?;(T0E>a_wN;f-b4~+6po-W}?+Yj+Jtqapp>jD{P|k z1Pgkh>x*MG$G!W=m^-%3I z!4D2UihVYxT$O)nYT6q$EXn+(w=|qX!U%o+F?8V6bEgp^xp>MTX7;U-ULE`Q00G<@ zDkT}#V)ZV?6yd9T;DEvOFq8*OuU#nTlA&ZbK3w33{@k>6c;Jzld_ zV$hT1hlIGW;vbW(U?Ke>pJ?Vr95|ce{;4jfeooKKoMYhuWI5(Z+gx^sp8fm{g8=Tc z1UYiQ1lN?pcHS>e>bVwyZTs5))Uy8N@PN^s*Dz^6WMy%gbQR>q#nw} zlz6BOKR*0KOffam_WEo$A=Cvf=4MK(&57mg+F^NK(Rwju`{g~@v=M5Lgj8L`ObOeg znzNBC4XuzWMOn=4WXIskaIFw($A9#oG!)HADfotT6`!&H|C=85*VgOiT_|)xjAz7nEMCy zDw_%&inKUf=-qygwwjQu_)KDT$~ht?6m@$Dg&UK$#+Qyh{)#;;Is&U6a;&n6T6Bf0^ zYb42mUp{e~nWP2fYMRj}K{gb!hMO34snT}RhW_7qgGAy=6_#wV;0z7Un{{q+s5o_F zuc!W-n+PHAGefq1B9t+&wv@wJt~}*oP7|OfeGq?yFFQ%N+;Nq!-y%Umz4JF0<&#tR zzEEc*b799%l)=!i>b6zQP!}5L`d|Z}=^L56d~O%l#Ohxj3%H%eWACDm!TI-(u7@NYKNX_*uV`QQS6`d`B z)sA@*vx_I*3D6AJV2&04aK0oiH}~d5foXSd7qAN%Qu)g3@*8u(?SgW~YO>*pvI)R^ z$@V8qr`W{MTgvc{Hzn6wnEP5_79&M9`k? zEg8&^Q?k`8NSj|+D@^CRHmfg*U1CL{Icn80`D2~rPd~cw7NP0%{kL^!ZURCE<&Fc- z@>>4VKCG8*bu3B<6rFGZY-9b;fS@=!uFz2XC}>A^SJ(XX>+*pLR;IANT|yzA17*s% zP`$lC6~Y7wY5JV-Dk&u)LS(*`N$?zng8T^Pa6TpVKlWNi!Z-(|QNIfIaOix zFFOhfR9IaFgeMKcQ=QiNUJcSgrkUw?=H!P#h$(VclyQL*i>h_?pEZ~qt(@TF+RSFA zzSzg7kXUYL=qu2%G!n{)57`59bJI(w?BFyFqQ_y16yk=C%TUFz$Q}DXWAOQjvSB=3 zzis|F%Z=j4UddE{ils)XZE*LzjF_s9!wZci~BM~98Hn1kr~GL6EAR3 zc%rcJ0*hu1S{emsnZPhDv(;Hls#iY1BwdQ+Tgyv#@G1M}{27%B4DpDU>Uah729vWn zuSB{ydX<9o8Ux#|HVdjJnWv3b-jzh;j;5OZAS+9ct(l#%-|!c`pOh!a2!`mtKtnE! z<>04#Nb_VG=`d2ioI<={v9h}!-%Tfu& zzzAKCOYY7pwAEuFs(OxVo!Ft<8OZA;|K(PCsg)?8T>@`J5Mah!6tj4&MmI{@D(vIZ z=k&XMFEPK+F|ax&oC8e|EfyU@V zNqJ9mjjXHzp_S#J5fd+M?p}HR{>Mnix76Gh9&O>~EYds{O;LNe%7w8uOz?Ci@><*9 z1D$Aln*dnY*Rcv^w$}_RXjq7ujcOg4#3oJY=vx2M-7`m1`DR%Lusai@PRG(coyRku zw=ZW?^)!~@89Ov1WLtc`>vrhQtyC;u`8|p7;lqg%Ifi0oebI&(@YpM; zC5Vke^jOqmsHZFS%5}MI`bce5n!3P-qxf+DupKq6OF==A#H>GLsQWRO_U`5eRHaj1 zTB@X=fCtesH8bl6rn0ZGfZm|jc2dVnfuE=Cfk^iFzOEw+K0D>pDZKWbf4x>KKfb%7 z%G>!nKFupk01%}!3w~FB$aSiO=shqQLB9v<{-!z7Ri|3HJ0ucMt|ABg8=RSH0k~(a zb~a}!)0oUrY$2&~^l>+hbv|M`?a>ICGBC>j=rAM`7D~6K}6F(7h>si~6 zdpqDHLTXyot2|-T=8JSzTgwa`?IXgV+y>5MG^3{06RzBgmY#CC4M)s=WNe-oEyTBZ z>eU$rf2Tjwk!v1{lHSk5lZ|#yN?`l)7R=aj{a$;2CuWy^pRo^Vne<5O8U|heCNt;V ziO%IDZvV$=Iu&p7lyAc*;O2Q4F~6TTUczwPN=TE`RvNdxEI)UAb=DtpUs~fT%S=~b z#B-s2R)CV6sRqR70049tya-^dx!qpqR7%f@1YJhCFXu3R-Xyh~`0|816k{ zSsisvqoS~~tggRpJ-_&sdP%9TtITRErp=CsNEs$YmA}{iDlJZ_+x!sLWwb)nnpbL1 zD;K^UZk~=XF0$v;$7|>M<9SeUOn(zQB@UZeLOz)=`4oKj_qZsZIU()TO5GNEV#fs1 zJ;44U;AgSA$i7Z0A-+Tsu64xHm)U*ju*^ZfYflCW3%ef_=HO`ou!)^z`JVgAz_mdn zbhbtY3$tOn0@VOfjA*#`&nxreS)9L$)Tpzd)0U1jab4j>w)U>yp0PSaONx^p;|bxD8Nw+rHt&?gx`Ux6Imu7&pj)aCVc zSkM7Im-_=oG^gM!Ib)$=ZdhMM|c=R(da4+CKp^g{?`N-lC@KX-^VG@kCfziNId+#}-%mX~!* z%E&Mab=JiBjx_ae!*-wR?`~5RW7+fQR&0I@=*uZR{b)0>@$zRPQpucSnC3s@d{ya@7VF3WHlO>tts4 zQz59EeDaA`-r?@=J^_UUs5)9w%XVqC-L1kryZ<*-O?>ZOagW6su}!xusgJ(tQ320u6?e zC3+#gM|jIH+f;$o!m>o(%QLO3bqP};)2Q2Tok4QAb8Po*ZL3u;4RjTwfItnke2Yd8 z!3=A|VOOM?jKvQ@r~KkuwiW##Q*G<-``?ya`eAHMIEZ3ZEQ7;~`q~?!|0HCSGEe zHbwkg))J`H_r#=kI~E~4^qRIYyeBHFc(NkwJZ$e)h4>WzZQNQ|%j9%)37V>tnSo#AeFyH zJ4R#-^UKl#+lB!hi%Cb?d>UQaA7`Oj%Jt!P$hWq)8u9$eTIQ?`nDykV&3nQW=Oo*A zk)=PF%iDG#r`y@1lxz)U;|a49GR=si;qu&`gMGXB)oU&%fpcv2g~38O zHqc>xc{#3r*nS%Aw8efM$IuHgL0y{BcD`n&qV!2xL+S%7&Vrps^%>~9?8!E|;BHpS z9R!&IBz%y;x1#%zvAQ?1p`xGWnokAVp-j3RgDDqq>DXGtXf|I--n9Ib$Df7mf{^!Q zqY<+9Dn}IA+gw^q^0W~Q>fQF*3wC&aedfTsr@H05XM%;WUOPBaY8bGX=;$q2TBON7 z0|fg-Ab;I8cs)3ne1i&*pN_O!Hd{g>jgk2ZnQSeGy0K=sh7d5Bj<(9`^agk36kG+}4b|MX|X-2WR~wV_)<9_G#EnPN^);D^@XC{}$_i33=2S zXL|M@wSyt?4}7BBG4>(r{S_!B{m+b3f`gIj^IkW@gZQdVAmRVJsJNkJ$oescLkN8O;s*cz1Zk}xH4uf7gp?lC{c5geHaXYM55J4ED zW+YdSp!}Xqz180Vn+^+alTnUQTN`zKuYe2}n)dj9_|XDGTcTCLUW!pnh$Bwnrkzk=J>`54sZDG-?9_@{RiIvmA}x~6;f>;t+;A2 zpl&Wp78#23eqICg7I`nEHvTd*Km$^tK3XJ$0f)-*mE!&FB4$llml&)(f_hEW;l4zA z!DE)zpLV_?kP@Ns2$Jd?*`&?B;-T~tss_z{)oh^z#3n-hDhUv9UXs>wm@D^A$@t->FdbXYl&v1nP&*`peNqafkeJh6=#W!HaVSVf9I) zzj1HQ+^_3-li;I2z9)~JD^gYlN9&e7<}}CavnoS@);1kk+d!fUJ;N-~fg>;Mm?=(P z-cC;78;^evx|MBG`wfWM!Q*fG$c_cJhr@m`Y0X^Uv8bA$pOfe|7qek{w(Rkiy*z6euxI zb%JC=`lR6DgU2(xds=f~+Ij(vY2#%PoX7Ct+l%)fxWZ}AlYee*Rx)YYMFe>SU!-_n zUarUU=npg$?~?s&Fb%N}t-Y_Rj#SjAW_<*i>~vjY{C9OfY7gnrJSWRE3rYwvr0B-# zidm9Tobqc=&2hzhgqSSJ=|a+;Tv4F%c^ZRA!lIDAXffh)m(-5bNk$S2$!SE+^PlcI zHQldyj|+O!>@fbCG+6SJF{v8^+Rfo*nc*&5pN~LS(&BPSdK--tp%bUmQkWHSi)V)Y zNX3pu_5yXtX`S*Q1396$G$;_BatO!ACMnnUem%6r<)#i6CIck7F1yoCyVEVySA1Bg zbkGlIkXWs7d8SaA<|;sQup1US>AId1q9uqO7w~-#ADb?rL_BS^D2<;dmoR_!Q4(&p z%J?qWaeB{ozqn!;Ap>f^ot6eEz`Nr-KgZaee9e`j!~FgcbEZPvc<>HY^QJKRBKek$ z298ThO`g1)f3_T(*aJbd`&?PCx*=s*ricGGhoi95*z33IZkghWuWRJJQ+cM&rDWWg zOhukL%#AQv$BRa z>2YXay-X&FAxkzrTC~kvw$9l$6~4 zBkq3{E1GFAEojv!o?EP5un_c%TRWwt%Frj}e;&lY3?X?b-Cq*#c-X(JE?fTgoSWO+ zfA_{VN?T9p)rkd$VcoBJ%W`)`1wmU2OR6H3T`|R3u8K4&I$||AOT8WkC&+J6)Y{>V zeLjtdFNgp1znL02YHN=-?1Q{AD|lQRAyFzFrN#8(ADxEw&;&N~*tctdS@i zEAxfYHSUTvciV^rm*j#%W~tJ`oPIzpU_ z1!K3r%*8kSjxwv}SK77z{Hw^TnoP<52(VY{{!AWmQz`s8c{^QyGpsPo^4m>FI(XT; z&Z>WL9P_2fJDd0D2p&%Sn-vqd5Wh!Eiy*H~GCpUVf9%}x^ZbSNmN&qVFqv>83WO*7 zM`YoUQrK<_{1s^*CYA3%*uXKC^+(^FsB&NG*z# z^z5C9^{Cw$T!t?|Z^F&*@cQ!3+dJF?tyiOQMbV^i9ryCZ82CAGi09P;XC#&RZO zND>%N*B|oE9_=?;O64NG3`K5k$9UXjT%{M9-xBgihSUa% zBI@kXy_lBi?<{m5o54IIN^e;x{Zh})7vXdUJv+240ThY$eGW&sopgx#;jtE$te;&6V!nv z2z#g2_Bn>S4wV(M1idl+|B^su`QB;k{OY^1Z3l{f>IVN0x8|`h8+hX)Q$?uxeL%G{ z8{NF$knCKdE!Kh^bBb&s53{axjRhiIK?Mz>bee9s^_>3B{S$LfC{Asg&o9odg$0+` zR}l6=zhlwMC11%nANVgjQ&~P>AGm<5T>YP>Ny4Nka=u2}0rIa{pqSOmhpn0TwR*_3 z-mHo7O@*GDr+1*d*dh2UfpQ3Ctk_*nDxoORqEI3hylVH?{`v|1aUZs$?X_Ht^Q0|i zu0xJ2&QBVJ2^s%}#^J7{ihO*lF1kH&K@M6$a7L&{_=>Pqs9p`dv0643Rzre=3pFkp zwml7PuNOU0TxGSdZvmdArZbf#Q|1LEk@4?j@`(*^fznNQ2@;#UR0P`tMi>cM1M<|0HIyb8r``b^*7AodESc^uEAK`vEW?fCmv&6u%0CF*oxwUjHZV_io zTwW&&F~{@vc0Xrde^UF$Y=`s_CSUH54E>Zj%I3_(g!)>RhSJSPcBsk>Tad3z<|L@I zQGx*Mi6Fbj)gR=uL$|lp8<=g(FN}t&T>{%HUw^>pNMRax=Lx%s`fmFus@wjQf}DG3 zyZ7r$4*VA(cL2A0yyH$uiS6Ko#_-l53$sI)4&L%NjK3b)-qDOvj6r;HweQPck7iEg zPs`huY{|Q_*d5N*Te-UUj7TvbNa!x|J?>I9ad!)Xxg+KyjFQ~E%lDS7G##>&otGf} zNO>~`x5dhgCG_u#kCR5SYPK?pkgN69*dgvAm>CoE z5oA!QIbGM(#CJ{HxwWNWfBsdKMJlnNuMhv45wtOpBMy*VIsx6D-QlFsw6bV}_zK~) z`7ci*?{OSk3x*#4cPtN!L#e5N*t6Di_fk*}^7Hm{)_bTY7o~67qmQ49OT3@qg7OWrJK1lPLSi)5Y zj>vk3Dj2-Xsx4AUo}98q3nBr z{DM?rZdjU`4YpB|2gWd6^yzKgMRbq5r;rm;eF+{*=cx2>TWhn$OYV)J$<3nmT5zE7*9WJ#5C3! zVv8@0V7mXU> zJnAK03R3j;c64;xA8XrNT;fauEPM)gV{gLQFbJw&J(h%gA*V74zO1vTX*)Jo`m(BH^-F$EL!$60fC)%; zf2xU?5I|Rs(Kj+-lONTzmjM3&e4wTG_RDJ_5%H4?MWCb{app$PuVhfzYFiez)1kKd#&-eT^}v#=PkH)GyCcACV;V;sxb{rf$yxGjJ0 zAXh$V$SFO>1rLK;G=8-5N6Rf2JtG0{d@tGjP7&8(cbi3yOq_vf^7G>yf#4Pu+BrZW zXo+SIN zm`66Y7eUrFOYqS%R>Tr_U!Lm1t5ce#ahh;$>m2;`scYccfgGq}QybNA`{{)- zv+>HLv{CT)WuT?0%Giue-fp-UBd}W35knCcWXLDd;ZAk^W<#CIGMBXER2o9!AugPJ z6VB2CDbSb17irEZn2S-H&5{8#(47L><-));SE|JKXr@F5SMWb^64KVIA$c{o%F1b- zuOJL0SlO!Qk|IFwZ_!suwK5Uro_MU@quGG@2K<#@DAw@0#9DZk;jmc{jN#?vQ%8ED z%*l+%6^l_qB-{bSfpxl|W2cMOJ5Cp)f9v|wQ%NzL7ZY(jagbR(n2@5=xvSr zlAt6OL%;L&R`WHR&IfM8=PUz?IN<7w`|3TPC69>`VoP8L$GW(lIW<2_?3()g)HhLN zCjHBIv*0Y3yqvDZz6e6&yjruA#zg({q@plxiyM}b_TKk^Qtn{0={Gq!CUpetTQQ1Le-%Nh-qB`#LOia`Lx{z+is_2l>WW%L$*9SKyJZh)+6mY z%gjVVv_NrlcZbKt-R>_}ykwqnj0AL;F}50c!j8V$er(;GYADd>OX_!AN%&z*O9Ml- zR^TL@@=483cWD==%0|5pz0*TZ@4n2%y8X`^u?u-y+vb$TiXfwdWy~k==YX`YIN6gc zZp2G0^-jsxkrEK~1m|Yr&}#hu78V{OM8c}v&;}RKuLo8*Mg~Td67vxd-!@yzlOV6Q zaPBkFo#DR!geIMR28OceNj+8`b=8S{8K78y-nj>*3wpCZ)myw~O|7h~09jSIa$evy zwOKDLC6JGW$)4tJgi=Sd-quw zcfOF7vu}8KD;v%YJ5PfC938i-w-x`WooX(~?qIVw=WVKWbznJX>q_5D_koY%om4ae9Q-CAklapG$m_ayq+b?2i%;RnVtg8>cwF%I{~FnCUCmV9*| z?5N!?jg96<_4MCVCjrQc-O&qnLgHY>(uWA#IOT~J4nkk;T~J%giL>G1Y5UajYY+5t z#f=;EfwqA#r;y_G+Am3(EvG8l&$@RfTCS4FUnmEllVvwsO1>~me*7RG1zgU5Q!yQt z@*{o%0kL*5e7CFdpt5?R>#WHF93TWQ3!ot zHJ{d!a$sNL)CKIztnX7%ui7=4Ck;3#;Oop&r6~9v>#o;0XY>GtGs^RSDG1;%^GLW6 z?hmrd{q??D{r^~i?QmZM+7erk;m+zUtUDKCl#?B;eN%XB!*DgDQBBP8KONclqd3q% z#3KWd;8N3=*@*-0Ut$|HG&Ch2fUe0c)Bc?2+v9#on!&nU)Up?lmiWcRyPGmPY2L7`DbLHejjB?!8WT+6njTrlqfo62wkOP)%1N< zGT!}>EddzM6xlsmd|$H=)4DC`h);NIoy#rr1uouGKJlVfQFsj;cqnjrqiXZ4h(SLi ziO%M^ghW@N-&hAa95XA`b9?_(KYL|NQO)*q=QvwaeY4&vy>-C3nU(V7<;H!Ks4xYL{fQ)UXSC<&-5eG;-tj3o*bgym$oA+M2J+I9` z$m@048V(If15DUG&6!U79wo2UsPum@U&mt;i>pGO z8doF23_|Q$`~!hQaWgy&mqjJxbw-uMeeU*^Wp<0B)jC( zhY9gHI6JdbE_?Z*FF6`iy*Vyg5-!HgM^W@2Lv4rAVA%T!GGUgWX6u6iyT7M1NFC1< z;T|1>&Dop*_qANMmW}%;6Hv5Cr=;=|hM~r;#hLWw*Y?L%T1y(+oNwv{=VYd+JbOPJ z5yyeL`Jn2#ICCQZ6;g66%mq6@&YU4=h=mpf%M9X8ZSr=YU!ULU#?)zKKWuFEL86Gf zM+Ao#O4SaEREv~U<{yEp&RKd>vJ52ww-b-k*$N@a(?n&exxlXnNbVIjtmqqqXF6=a zLBv7r`0|rVv7u^7HB&pi-QT~_mj~^>_?u6Wy3LK2-oFE@tYyM(t%_JKGLt<&bw$p= z8L<-rqr`>gVH3+ZkNf{AN-ZHW&EmBy&fsU}fx=!$6XCC}1*`w^35~L!Fc#8>q2uXkx=^3m$cUhJC7!9 z9o~Kuvcn^7vK=ZcPYxfreR{kjI@3{HJ%+>qUhjJ)Qg})7!v9-iQ@5MDj}|z|Xr^zK zD(v*g3kmhz!j)=EKR*{HdG~=v|0eszWmxs*L@^UC#f7db}^R&ayzoN`Si| zWd`Urg||ciF&867i{-LnGqo`Gs+x`*Fp3=)X(>-9iux5Q$Y(d(=}BwXfr)%qLeYid zLnQBgeR67Q{^aSXHtk?z8k>2P0t5AN5~^ePyimA7SUhJ)s(Xz6^_8 z;n9z)DKLK$#rCA>Yh1bRN6*RA6}SpmwuVX;2ardUWO%Qco&Z><9CPGKDg$*xLqd2} zGn)md<*31gOeQkP|MQ?`mYaDJEeeVm1-G)FH8;2u)`j)*95N4~XC205ui-;$!2!L^ z)Z}R^YG_DB;})OQ(CD+F7z|#ENT6_klrsct+58inwd3AY{yB++9N2 zN_R;J5(-EoNH@~CG>bG+QcH(ONq568wRD$sEg_vtcfKE==li?f>w-UFXU~~)X6C-{ znd2W^wDr$xM4PPrcE&Hkf#@IC(_Dpr(RH`iX}xiJ$;(3I3|2+NuSQ4mM*iW3h5pIY zfVY2GcKMwCPki|^$kfPZDJ_?j&nM+;z#F`#BcmXJpP_co6ciV1`0A`;EP1alAMP&a z4;{Wh66+?;xH%%%S_~GKdb%XGU3m=1)3zjoAHA>BEjFNLWsUlr)Mfq7OHvyiyUsj6D36LOqLxb3vvSy9aIz1x%Kg|BTP9H!8e*pLK^zG@+@8kq$xdPx78 zeu>9Jr(g}_0^K6g$P>CY?M!_mqD6T41&T*8UEBMlg#+B8JagYMvFh7$tSjm8EC{SJ z);Yr;Bo(0{K&JYwc}qQ%>0te`I(mEr^r$r^jCHaC$ZwRDz}ePaz|=^M%uz6=Z_p8t zG<1?O^gHGqqGmXu( z;DY+y{d-KP|2ul`GjXFvBhnI*i(Q&V71?QgXtb^%#Q4W&G+zSH2Jao;bYY$N7r+TV zA;j>|Cp$suKG#+qiLg;ymy|Esz*3J)OYHb(XcB{JkLhY7Q2N44sBvc#(!(cdq<5&> zw}s7>;B*#lEn>W8H>(?4!DweznwBbB#(23i&CLOe6|X)m!|9cd zKYs<$c@L$@v3X3)2GNi$dpU>RIoNKu*}Bvjq)~b~49*S(gL?GJFfoMv zQswCt=bUZEP2hi>{cQYf zDft_!hUMbaxUC*C@$zujVv!{E7(%Qv$A2?%{)=;eEYkV@}*B^n#t+&%P#xiT(Ub`xE8Q}$f`LLuWl+QV}Re1u>V z^zCd-`Owd4FXD{Q6M$bTs8k&ExdDbN`9Hrg0fLn0&%(lLmwHoHcOq+hOmpGkFOVolq%gHy40nQ-N*&9ZQg$!o`a_-s1wK6QkIJEI}md|e>cRd!6yhw`M zON(%i-UsPMcs@SK_{c6)V?6dk)rz*}O%q0UcL`$CMty+Zh78$48}^L@)Ei39zWdtj zQ=j`CI$Ym|-i936M>dWFgi(tPNJO*GmU6p2>)Czwn+g2ros3TsIVN+efqwIIjz2XXXtk3ks zc(Z<@(HI zDy#aO+{!z$B%6$Zj}fTtZ(;o}X9Ju0>)8RL$&hmU!If*&&`4$Z6yB109rf!L#`1$N zEVt4TU=R2#PN-uabKD$|emW|RCkprN>JYvcf{s)TaO$S^?qw(9SRE&vTrObr6lx?E z_LiyrW_Xh_PoLFfY&$ZmR#NU-Nd77j`3a;>GF;k%Z;O9sBVDUFmQ4ccp%oa zRQD~V574a#WoM*{Q(#CdjooAFe(`j@Da-4}CjLL|R_di@wg)7SvP?9+i>yjB;|1wA zFY23&K=)hCXA$YaZc-(h@4PeHy2ifh@Lta{w+I13hhnURi!p8npzVCPo{BS)*Zlvk zJR#O!O~EzV;jnPprQaJVckGsFc)`%g5sGp6ne*bk6=EE&=1Q?9 zl8W8>ayTgVlA)xWQCl&VJ+ij7D9GyH`_U@Na1pE4nC?-7-tij_O?DHCRy#4wSIeJ^ zcDHH=7RvyTttgu|5&D|BHc@7{la+^Vh#c9CBfC!WcW&=|+{iJ~^0kuq;2#%qgU~m9 zyXlnFgHw%cEN$lA0_JmIe%Nr2w>+iJ?| zGCN~^jfl{#1O`9Mt*1&ou7C{ps?AGit5vk7EE-!2~tdUplJV152x@c^@ zW6Q>0XEV*@r_8i9v&djxL6^ZrrL)vtZidt(}JC#wqRUpgps7AYxyB_0s+0Ihk&2FmtoViK5m)*ff1Dl-ZhKg*`3 z)^foY8j1#hyLd9>-=k!B44}Mee{o$#LC9VRMlJ52$BOqfJ)G--C^Si|c1lwaPgJUW zO6X2v;*;nGddXv=O6)If*_I=5FUkKGDRno~9GLnCmI=v=N2x=lC9jF7zG$lG)0c?8iuhUP; z9*j&~BK`i-+J}jDFU=N1PEb?1K&ZLMx4DNt%t9z~~=JKB>t zCCBkq{dmT5j>gb#Fb=40#)^=(nQK#>nR9v9eQNTZ_T^crz@2x9Ck2NdWJLh4adPsib^oqhU=^d|#^qjR8=E7m4#n z1!a|K@A~4@Y+*fQiuxnOz#|~(yqt-P#DtAunJm;~s(cEP{OZ3|d=xKoaCgc1ela=f zkD?iFMa#Ie@6^3Wa~d3@b)B7;GY)im0aee)!`)7ZzJ(3FYL|UZ*b)~R zGB21<(gF#udAe$~(7^!a?28zkVZgX~@rKS#f;Z&vR{(D&Xc}bQ*->&PrB1BnQiAFx zoQzXgwyQ)pev#>IVx0|sDAk)N*tPnl_2^*As|~HKQ9fyu;Y_bIhczRy8RRiODU1ol zFx1A3cK8=$7XaqW92sAkfV)XL>*x5%Tf5I302J57_F49;Mpboq;rkqLMiC&t#m*oC z?U4j75qCKhqF*%n=)SDL@bqLjIW}Cn@BjPj`%uN}da{HDkoo{;DHs_!(c{+P9vsLX zX$pjIcJ!gR8WkVUhF|Et4ZKNMN&TN!lVuE4Ejuk;<0`R;kEaVKIF@j(8}lzd!0nS{ ze^DgVm{|sTsV*$%3E;6{;{IcH+4cGkkX{$&S*8cFCGpxBkD^LLoojIe5Q;f0D3cY? z4inrM`mWn9qEq=SN)6-DAz>w(0(JaZ1|wgn&1gJA1i+5F)}Ec(*`c_Js50M_N=i#U z5TI-%5@jOuyRPc&xOiD>+lubFfuuRH?FXad)Ufx<9hRCvrL%rYzxOfYe)s;rc6C^) z&}wsnp|MF{XIL-`f3Sz!TDv+c%lp5h^j1FIw`SoLZ{AtTr5jl~V^Qn0*>F>BBcGVA zr72Y4;p6MeLh2?bPQX6@@Hwx}pvSNbIW)nnfbmUT$nc1F$;LX+DnXGSBGBbD{Fq$+EO$Y%*A5eg)HRKwA;LoWgvrkze-9#yHTy~V@#;Tv`0{g(BKh()?&V$ z-qkq@>W9Q~Nx~08ihJv-Yl>jddwO-9;Vk5Y=Hl%Zf5K%gmZcg65(L3+cU6DPRbFIT zJxa$AAT-1I_;Shp{@jgc$yfMJU~NC-0-=#b%RrO6sdZ8Wu=v!|nqK^@wa|(pU*MLn zbhQ*w61Ux;DIZuLRZp_Br%<7mbl#0qb59c97B|985K0lw*PHORbb7XM-@LeLUTMeM zwCzk@x<7{FuCw!t;)-}vXt;h?YmS&?VbLG3)2ISo*n58EwLUad-3QeBE6o~cP-~ME zk{KWA&t=8dKy5fzx;vrc4OW=ZV-*ByX8k+-o1lklhX+sE#S7ROf@JAPpj3Bm@^tNr zs+hytHbns0YToAbH?61%$qsPAbWCM@-5wt@XS!{&{629Bc$^Gg>dP)T|2(d{Mpl-i z7|^U`HsKQKonB&IM^aFKd|9Bby-?J)sF8{7(sgK?vl2o&k2X9xaFm$HZ)RP@#--)r zSv>lr7Hnk?Ct6rEHLiS7IcZb6Q_K&Ojf3!x%M+ zUs$>f=MdTZSY2(elNlz1>5Lo|3wffRm@Qaa9Ld7H!(sI2!f7lh!8g0AhV8gU^+1Fk zbx-cd%vf+{53b2yLvg=AAc;5y2o#%w_>;UyLA(O9&$>MP{8F)Wd?s}2-TVo2bn{*Y zpJ83R8H3W;*G-Dnv&b4F+_c#c7O{+87`>3OY|X1j)gHz-O|-uQ|Fbj!SXS)-Ikl1k zr^g0yUqQ-(dx~LdD!Syzb=mh%j=M_C2|Cw`RUXa%l=ZiHU*Y+RoYxKU`7K^!O7zSI~5xyfQg};x^NDw4j zrH`ZFhMhUCznTysz}>=wKM5a^(XPW-^Y~);VJ6PWsx<`>JNWHcs0aLUxShTB+%FhF zJp)go0@8&K<{{@!1Pt}6qu`0?(8+EXvxIo}O;3%?H^Z~SH4bo~-7~?A2=nUidHMK@ zdRcMIE!X{#l%bJ(JQ}`w}({2>r~8%q5xNz?=pFESt$99p?9rnjCq&ZYW=a_bw8Q-uU@eoyatz=N-jQo^KUUUHShml8 z{AaKnO{H~u(Lh+9H6`)Zb5Q7^2z5fpA+GslwrotlP1j}Z7)nFVX;wum$=(l(jz5uu zy;(RzFon$^pDY2Z5SOWwbn_Sb&2hVZ%dX+R%DuIx&u}>rEv4U7Dxw=OIvy~(s0ey~ z4sfl@ObS(fqbQ*S*uT(wSO&3;nan>qtLi@)2(;NSBoTqPKfKVi0REXtOJ@1MvYwPp!V}lmS&Wkd$(H~*OY@0rC<;_1H{n{2PF3^;FBCpr=*e{bLI=C6M;lSKMy*zg3a;g_sZUO9GK>kbTG-PsiL{&^+isMU72!^Oy<#0IaEN|;Ypvq7m$wN?I?jM^ zE*-P5ym#RT;c6Z2ENplRHs)KAFW?2Wvo#=GE!6>{dk#75QLh?Rug^ZeOQ*79o26`$ zGW;XwUtMxZz62BnR$2J1x;7?`E@Ig|_g?Simm24Ls>}_vM+n?O&9U zs;yAMDT$_3f}40deC=yiets6w=fO;zmi$-o&tYxQyiqWq+u4+QYb!HLhFV}PE-xo3 zPog&14o^a$VmlBmue^K~Df+O=Q7m4ZG^6&4F2df01_=`NI_2y@c)=bknkyR?p+KQf zNVot61GmQ@WWs@UWZL}LOtJf%JH0&a^>&nHjQ_n!)AJb81*~m)vccoY0eV@Nz#Ur< zU6zO;8|fl{ZT(XhvV&SE=EmX)Nx11PijPr+B6vyke;$QZ^r1bA4$OHS&x%1rIP|R8 z!$Vj6<83xuywzUgsjW7%r!#87?L*yr~S!Z&$_+;Yy>&=9yHE&Y(wQP!db zkmwX7Ln<%|?=*+@_VxnsMgRF#TwL7JveZ;hNXlv81*lbw%u?Z`KLzJO|36w-X$ zxUX#K*;6#I*^g0n_T|uN>hWOmh2@j~zH9c!Ub2`i&4d7j8a7Ojs`uD;0bvkiiG=ZX zCth>(f>*Mj@BK!_Yl|d)bB*xnKD@5UgEbB@Jdj__QJ&l7KZW$hUhz*5t-YavFNUx- zuX8gzpIgYyi2@aKu4NxGul7OVhqe7XSON0+f?bFR1DVzTX#u#Kjf<`=2BXzHTW@-J zL29z9Xx_}PVubsK`Ht2+7bZtztmRXTBkbI0Y7~#z7sc^fbu^P!(*@I-NsNJr&^`5m znZPrJ7Ms3MpBkGbFH+>jwjjT- zQQ#TTbP}tdW{7U-XOJ)4ME~ZB;d}*jKR(!ruo%A1bNAxR%7;sk-J95We0Z<=PmWM@ zsal#?!k*7_<$5Ot%GM-v1ZHB_iT9Y8B#U*7E1tQnJzr`uSQRDqOv{zfyn~r6z-}1qEE`vJKa@X^)>Pf2*WFTK0cmTgOqQ2ywM4HT8~M3tB>~ z8E&hDN`p@>OSnwvHQL<@!~{S{q0O% zRuO9AX$0OfU`+%H*0s2==hEmAn$tJKU^3Ag4f=Xqffb;uH_!mfu70YbVb86u@7n14 zB;3D}2J1CytH-7ZV*I~7>IH(fU}V2pm0ax1q?$TwYX<%%A09curxQjEaHyW>wVq~0X}zb&S2@qc6cdu$&%o*H)G$TD($ z1i(BU3JGKl@>75LV%XL+{_eN;?)b==Thw2HNr2I_1POx?R;}!@GJYqpvY7UP0ddsY z*&A1hx-Dvlbo(q*s|&k-eBY*nKU$3Uc%+J9f;x?#^ZAlpu$otoGt^o?Bm>$7O-)k2 z(9oxVmH5>=74Jszl>#Lj+&x8oh~DP6KC^ru=^AF}8t9u}thGJeuPv+^IYX;G$ljRx- z$5fp7-)C(!)2e?&ut?cx1~p`Pc2<;uV|{1QUWpI^;K>O{HO~Ut#LRtrG4u@`-56r^ zgX=4HyWe%USV_-$$ENdKEu&KSjrAzqnO}{@1`U77{5OeqL2n6*eiYSyw(dSLELavc zCk~f;bn$h}wdl9UD6x8XqehTrNF$RRYpm3+sj8(b;WLO6!*>n6Y%91thFtCy02!WaQuwy=87}f3V=mmB2HdSjG?|^McxJaUPF>krCR>p9YVgld`jq z%kh(IA7O6sXefU#vMTDx=^E9MY+U1~EM)i-Jc1y}D|UN$lb=`iIAA$AEKLfIR>R$( zZ$NVuYPB6byI-2{`nByU1!t-9I^{u8vW?;Sj+nC$=#^)6Y&qx)!-><}o1@Fl4C!iZ zdU(U^jsl7j`uiRt+LO4M8cCJm?u9n}ZnBg?Qv)CFt4`@Bi6FXLpUXP|l6x@M z;mx{8kp^_+66^VT47!rROy*dr*lUbV865Fk3fvNa)QtWuf51;)J=R8FS4;={I2Rxbm9X6^^lTD&>&O`O^)ygk2 zJLW;EClL^0JJIT|^r2h~jfRR1aOE{S#=PDSW089oO2%6p>t)s2`~YZ9p5K3K(eAVr z#d7hRg%THLw-NzU`P$|e7h>kMh>JfT#uX^)JiYp?=$HSvlKT2+*(b#~N zgV7uJ0t){5TF|~@W`F%HXkqcVt+lEg%EA}(BKuvGi|<~*A{i+3EX`EvR8ZE1Y<2E* zJqB%-mwL0zTJhy?Ez5r^Cn}SVs;Jyr_RH@fA3aRREzggCA!d|0BHl%5gEy;YKS-PX zpr~>?_yDS|hWF{Kq~;h$k&oQU>bBF-xhv%ImtF&td_EPEG|UpUq=%G+vXrLeTbs;Z zIUJ;OLYo^FPO#r&@S2dirD#pP=8k3mVPX5fu(QQ`A%}B~x8vC@@?9H@ad>ryFLwUJ z9cGp_iUtam44XspPriZL!NY;Rv2jP$a9XrLc|O?!U)w^<6s$NVl`clPo*uEEvbU@r zntOIx-rla96tt2dz$U7wr<5-L(=lfCf6*lQdl)owdyj6!EZruJ#v8!~A1VkBntSr+ z_|Ivyi204m8g_| zQPaD>uDkzgD79`M*Y0M|r`;=w0DrqB;1`O9g+WWYkKJE8%xv5WfOh;+ULXU_Q7A~l zECZdWp$5Ejrp)k5<4-@s6V~eo^;%zrm}@Ofm+Q7W9r$ci{UMAc8uMjGr z?O6wGi%gp9v8{n+{y2VJ%Qbb6L9jnHMq#=*)xjL_G4oS!Ai>}o)7_FCTaYxWoIz$D2loz07BXju4p4IP0mDZUVB2|l{|l&GY>tA8v0Si! z%xl3}z(1~SnBldthd~ydg zAeylxjQva2vyt7W=+t=j=#H_)4KxI3(g3{|2p6n*QOiBbrJ$nERDsMd%~Np3%|hnk z$lhUtEdKBMS7dNLkc6=k3OTs8)@5)Nqb`S1^2ll`jH`qsjMv6;-THoIA`}NEYgZ~% zOm4R8MI5Y;o=BJh?H}dPP$6wX-q_XIP9&i0vvg{tfm!;1Pp zvUCMxz<3~l<6g^-;x}N{!UO=E;e*)#I9RY}^3s%J6P=trhK^|ry<$LE7egmH@Rivo zG!ILIJ)iip6kZkmFGwPq+Um!2DM@pdC|cm158xo}Mf=CSAr5f7P{n&qAPHxBj&0EL zai-zji}}inwjhdisfesby+5;^%C>{6e5Ail)e>`v^(t+qe=FrM_yb@hFi|i$h^&Ec zjDq>Vx^?yJM;QS~=4189n*8Lo9!JvVO*&iuE@62n^1Hj}n8n@gB=NCF`N;?M6Zg0F z>8c`4MOMyPenk<<;R8R+)dYJQPpt!_6lx#XVoqd@ZNu+h_uY2lV%cV^eShR}IIwb(Jf%t}kaP_XAMpk!qG=lgE;hs&peG5YT%2Q_*JLbwquNq^Zr&8A5v7q-;YqOVZe!02y z*M;I|-=9j26}nJe0ppc`Se}>3(45^#jrj|KpaLDH@nhK~kEa+$Zq&WmfSzd?DpkQy zx|reWv9k*5rkSzJ3!a0jPlAn2&Y|G;go`rJKTiVQLH1ry)N1V5*ffYO5Ca)U-Vm*u z-U;G_EL`%t_q^Rn1XYf)O4(o|QaUDaON(IOvB6>nbNH?yBndleBHwPXnc<#8M5CtJ zpiGmgp-Tw9L-4mxA5e@wa?LhABmTUIqM0qdIWnrJ$B%UMHOYjbDm<6aPSl>Z{Pu`3 z<1;AdSS7!n<*FN{Q!M$ERi#hySyVavry4Q3bdaYNYRy}ZE^1O`12JHpQtJ5j!jQX_Y4dS1hfAw2EWwA z75e$WXzY$eK5!JZXi)HdBhw|tzN(Gkf$J4^?_S`eYPd4L8=I&}2z+G8y>OYmXjz z=*U?8yUH6yGnGSds&X|X|NVFuf5X!RF_=g!+!f;NM{rZ<9@e(Sr8vMTm($Xs;~>I|PKOP-C zHGheZh(Az~j0l+uyv{@HS$m?M;u+unprC@Sc-$k4u1a!Fac9yTyjW~M)0 zBkOCpYF~3mh+w`xK-~XPuQdCHgHuS(9f~#&(Y>ADiCeHF@PLH(Y6F~e7V_P*Yn9J8 zWU>1ygbDuYOiiMVZU=cL|2yXh?9D3%(mRY3+kugR0KbG^#$5lD-aCH1^QkiCA>JF> zOq2G6euxP+ZZINjJ$+D*6v278@-eohsI2A~4^*1Ctt!*ooL4mTmj8&*sx`Aj;@!l_ zewa|5;Lqg;=~Nw34PDV={+IBYym`9x4x8TfXURsA4BepWkn@A<+Xh3&vQ{S3uC;dP z_SpoMpK=Afn04*KRiIHX_Po51K5u$z%63Dcpc41bX%C{#a%Ll5OZH2?Hy-C_Q|1FA z#D+Gg7CV+8XYbai)c5opOYm}LFxr+A=22q&Uv6W|fK^^kjMv&4?6*I+`SHnWdbTJ_7%EZ*k!#vug-yI1(iK9{YPi`KVYK^z0%?d z-Mqt_gg{ILU%Z6jfTvkx#K{l{bidVwU4zBuO581aY|_&dceZ$JLkA zw=_`Um9Se{i}f_3HBG;JG-DkoJ79~!B&Sy`Pp6&xFFs+*^BC>rV~{_^P+Ijqv5HMQ z=shnvpAz@}ySc;Z)ZgY7<@$*8bN7>A7Lt{5?4xZUY#KK43cho5bw!< z?T)C=sjKUSq8w6)6mw}~V!J2w-lmcbDhM=u+wZ2@Ol^AGx;>6R(u(Hb*Zsj)jE^4u zw_t#kD+ZK0{lxb^DkK&B1412(%uhV&do9;d(yISd*6K18Oz{y3@*_0mx#N($;LS{@ zQ;jaWK9}!VJ4;8F?H%Bk&=sn)q+A@h{&WI0U2}5mxD`PUiZCT5*HjxDLbirfm>Q1nZ24!{qLh0fzL(v(=gs^e(69WT z=CGRcjilc;-!2C0ZTkP=#Gz{M5jq|e{ZCxz;$2W1RRtoaac4it!@-F(@m`tw)NOju2{=y%l(GE@I%0)<7DXE za<826a^K)e!hB(iv%})yO51@C#}(>#u5S$`i(be*F!ox}Mz8R7rQO!h_w!#VV_?tF zweGLwz8Aa9XrLdTKN4!Hs!LE*ebG(m!x^0+6{_yKnYZ_&DuM z?3WgM9RBvrTl8Y1bgK7qV16;-!cL?gX7SRQKg*tP;XDhEQKS7RB80aXGl*=c-(2`| z;f?%~c9`Ylrxw&cIZ?_eTVv`B3877BPDly<(*5uHT3irl9Io+HX3!#>;aj>n2N-{F z9HO+Z%9<~=+lQ#Gu6~IX)~h-+1^h@$o7&kRuOz*et37iiO9@ysZDM4&xK`ZQDr-o> z7$oV^U8l0e=xIV9SJ#)*OX{43g?L?eMA6fG6g%FiUH8o95c{mWZDCK<8kfgZU06s* zo#IkH(?tSnFN^=3BbEtt6coEV1RK*#pKZq=5Xch}uxHoLNuQ$G>k^Vh(TBno*+S+My=)GeBlBYN zr>x&4b7pNXo|0)ZeLdVguGYN=-PfoId=9GyYaB6Cvfav^&HJI2Az#@7+7)sX6%^66>EK!eR!x z=!3=DUOK1c-4OGm4(TUbhVI8GWrytMqUqjrw^`Sl)m|nsV;Bq#L|MMK$aG-XV_aiQluG&LS`DJzupn{*-ld-PyoNAc zmeXdYgb$Fq!F;xdaao-W=VysxzGe$Lb-_xNwjpk~p_HGcR`OhscCWOaT1{>&o9tHr zi}6S6lC^$O!L0!mx!j*n46OM;L>@|1Dr9s&0Rq3zaJbx9sS0sXa#D(K)NQC zdlz3c&%*w5)s42fOnz3|#mFlz4dRqY(RG@9jZ{SOLKSO^Ckx7M()u~!Rf-xzMt?|e z;li;>{mb8-sgUuK%Ou@S-i~O&3 z9JF{APW0p_eq0Nc)-}AmEOUf3`TV)oI zF!a!yhJ{$9z;~~b_K+LO2Tv3L5;YL^|kUE+mPQ+kcsB5Ap}c^9w#X8=vKTj|>!yP5~KP^D(b*#>g~c|6%*(%+dT6G2$D4c0x_&qy78%yNUv*@#IBx7b7?b=7 z8O2X6a@6^3%#F{~t%pd-YuK{I92WOeceq#My-!6EVQ)3Wd4zj%)9AqbPnqoSsaf zSOz{$$JiQEl|dGdH#FPO|PU zY>t~J4fA-@M4_+s_abS`A5UAHrJ*VH=u#vLrTH6IQ8nOoA4j-kl}g!ZMz=YwEa-=0 z@aql%k2F{B9hfKmc0kOY!LJ`eKfb^^P7#5xS$!++_2e7#L-Td}=dpM)pl!fr4vaph zwaY_@5Ms+!S3cWMfPvj;=N3BR=B1w}zD-i|sY~ta%|x#?pCm+J3KqE_tEeZWkaNLM zIy6v^**kL?Rq?#7JlMp9B*$N#Az!!57YWe;xg2 zFjUk7jQBnFxLy_PPUa7BURe`p7V>632*-_tNNh zyvV^gq$)R5#>wrpCT*b5EZ1%%u2b4v1Z?<#+|}R?<@vsl-`gn>BXbj6rs+nM_D*_N ztPh;zKHvYu-c(4j>D`{bz1~;~{>M3Iq}(=4U24qI`a*gKWNCzifLc$xaGp}k*|j&3 zWqeI_Nlbe?d$P`7T%>FC-2I_j8g=1(QdOu=eFr9Www)S>jaL-Tm5G0Tk`QBOXjN-y zPMzxyQ9?+KgRl3}*9?l1vD3sIb^{O35kV7iX};2?y+E`WWz&6z{3au1FRE8m`w$vv zx8GQR+z$mKfmNqBmr!xP#7ZiQ+qA%_KRyFSw|ybPo3v`eq2 zkJ1_Hkys8e3mWQU4)C3P;;EpXurr%9wi{^WA<9jHg#@0zeDchO#uz3J z4X)Ri`e-UvAQJYq!Zi5b56pVbm4bG1A+`#M9mqevx*_Gnn{G!F<=eH=)!TDi&C9u& z=x27_vK(lL;Zr1ZS4+wlzxKCda8WI{Y?IFDd}gsXUX&YaS3q5edTKu4Z^tpMNcfbZ zN>AX~>uNRZTia4~0jOH7LxWCL9z3P?&fImY>{92@h-vQr5%q#iDk}v|)pMJCl!vO% zuf4#hpw`gZ{A8=qAIR>Bt5;xTE;7t01=Ikyd|?xu%&Ukf$*?2W&@&hrQrI@CQ;DMc zgrZxap;?ZfDDGcc5N#?Qgs{=kkS!3$s3_Y6)u8;QMp`aq*XNS!UJfVswL)lI5Y1`j zsFy`_+e- zD7FPy3dmz%aXPQWDyG7nlWZQJoW_aOj2$xnJI!NCD0Adixg9YeeqFF*c>4jxN|YEi zuu)I1PghH{xKxbbEL*AV=U8|G`eHXYhPU5Z=cQ~lQti>%ha|J}G)xgeDc{zHXBH6G2XoqnD_ z`J-uC?W9E3r-n;N2DYIf+-_;41A!c@x$vVt+{VD%AdrdIq|S>XXI@PCW(cbC8{VSw z_{oUfMY+=y(k!tmyJ>43whB^~yT*=u9B{2hxl~qGP+EX4Tg)R6=&jxTKc-Rq$Sw-G z(GZc%g_d=hhwQMf;q~OKyda6HUvRN%p(J*Gij>ufIIV9t@~mP-_6KzR41P|=V#~V)xHB+VRr)S??MUZd?K68z>`VGC3o&}z}B?!nRHU1 zHI*q9s1jf_4C$eZ0AIME6en;&&Eo=a{11e%n$6r#rV|y z=iXAtqBAOTF^z789K<_>uIo7*K<48cgtka6$eXUR1eS8ZDFgF+r7E@%PV^FWd75w< z8XX6*g4wvE3k->tJ(TRe+-!i^FVHKR)mrKHzT<`G`ujxzTl^LX%Z+q&@;h@y(XQ#-74uCwLa4vpVuQiAYxGCkVt9c=!Hh^@F+d zR5p5K`0sSG1>M?Afy=lm%f=k{tr-ZzmX83vs^eFdI?<_h1f>e5M9 zq{vTe4A7^4vJW+O5#_rNo71`i&HLa#WiAa^92yqh#&|vdkEyQ?i|YHn9z;bHK|&BI zr4f*B1{6j*q#IPayHk-?kdg-JZWy|xTS=LrBqfGs5QcaUe!jowdH;e3X6`-roW0jx zd+mMB?e4u`eV*3lqV7Wdo+d#CVP}e@u2aLM`)$+J8onv_s{D6Lm=D`xS0K+v<3_F(?;?-q|VR zbFx}hA3cXwZ0D>K_0QC)i)h#T3S?~z$H*wa9`lIO5I|ngOs2A2HXl4DZ_Ubi&1}N0 z<2pfbMn8Bd^*7@Ei15VQVWqr79fVus`H?Au9!-1^&hu~EhO{iS_e#-kSk^A00CsLV zxY9sPtWa9;F>Z#(VV}min^o=HcL97N?9R#tYL{iz{0br!WjKG)!6U!QnKQ+Va9#OE zp~h@ev=kv1-H7R)ckD~N$8yaxHBw`h^}Zw!$U?umXaw{7*<#(ZGGBrEGp+Q5XayZ+ z6SphenP6)w#zO^Dwl{8B`+-w3D~U>RvRT8r-}V>zx1N=N#*LG zLJ-T|Do=LP>n3k$_Y*XAm^Tb;t3^C8tIN0e;{|eiLD}$7&Y%PCqh?X{fex@Vd z=du;JC$F>6*k`d^I%z(v?d1Yr+p#p|VxB%jTFYH)I$GR062fsCve+-_!1`;_7WaJN zj^F=s+saRyp!;eW#O9{+2*xcy80R+J02vuX^fxBdQqc@q%b*0sc?dnJt)v%jLTb;I zm=9cgo_W->gx~UY@j82|g)7bXAdpB^xte?wsg=QQUqI;JO6+f|XA6dPXOL%5IHqov z+Vk$LWXiG8Y;mfbR<{jQH_T5BDw>m?ar2Xsc}ylJ87Q6iy~}PsfuFiuxz+O$WOT-j zp)M66*LRLCdu&&3Gv&Xpc`**&oHp#V1AYM)Qy+EseGh{Qvo)1Jg-vgrZzFWBU5XsO zFu5?rA>nuNoy(E9KTgeI8GYaU&;}$L%4}{{tY~6GzX+hWva8umildrEO0xMI&Mlh0 z;omoQc2)xz`R3WP?^%*V6dc(rj+N;8jRt2$f8Vb%enn#}otv|JU7CY|r8-SuMt%jY z4Wb(C!vS{t#sAuZX7hfn>RXZHe_n)*ZEI6fESV^6HE_C+a(1+-H=Qzb2FD?g#K<7c-4nrf_qE@JHl?3xv|cpYH_VwErHrRp z?uO@Y$!KLQ)DWYC{zOS>Gi=OGOX<++;MVSn-IdMNue4KZynmGG{`@9ZA|DqA2Rn9e z|2UhF!L`bPhzae>Jxrjs74upOW5UniZdbt|6ea+HP+o_@+|ZMfcE2zPW_kLD?z?lo z;7El@6|(I_d+QSR{z zSX19b7&$a^X7^+Djx1Orl}0yQ5HmL&3ceztGYoU_i#9DD+YB)adV&*AX3ID$XZW5< z4(sjy7cCd>)P2~*aD3YXYC947wIT$=7M-di9UpOIvTkN->_#C{gAFlLniH@eNN0`@ z2l7{B+c=!^rx{X__(g&|{fW7y9WuSWH6F@ai82vTsqCy790Mv2XNkM<5&w6{#fQ8$ zZSPs_+g}||W&ntp?_t`>d_Ry@4WkfbpY>$6a2AdLN7 zc`?2)-BURA#lj?X)@G}^TygY?k_hniwpo6?%`eLIX0>fMBGVot&If1y?iMfxj0oEs zsiAAh`!1*jNSv`DYg6fFX#6|9_WvT%;rA0u?;604sxN+?A~UIP{cuYQYY|yy`}^Im ziM!;gm4Afs8CW(~%8d|&9R$*2Vz}d&M*b%OdH&syd4p}b)#Y-`;^i#AnhH|(`a#H& zLSy#Fr?A4C(S*$F79iua!Tn1b(^%VnbyP5 z(9qOEoNX)AMb6uc44cPX)+V)ynE3{?l1Pnb9UVYw^^u{Z_5-`IclE{o;z4XesUe~;XacMb7rSInDMcb)`{!EgJ>6M1(mh((MV+4F9#0e z^{%VQVy)@vX#$!Pg_C%YnFMRtgyE@_ZhURnf)nrDdB){@ZiZ|~b>FAqF;g0I6U%6G z*@zL|Oy=>7=xYn_j!7ovUh!d>#Y^-8CZtPy&^b{Vw95p?T;zP+#3C#V9`Y!ECg8o~ z@9L@nbxS;We-jdL`au7JwK%4$bxZJ$f@T}uI^77lJ`#*0o-m+sZB5n2@Md*+J7fg2XwBTzM=`CQH3wwz(Y+3X8VXXD_RXChSdg zHH*Z??>wKxj;M9p_LG3+5w(g}3ru}@<-N2}yh{LqsO?4h{ecJCa;;_!abFNHJWJu& zL>xd79rU<{W+rA3+@yPGP}M(5;E66#u`w_^TROWi*?Mmouw6_5$#`VFm>Piesh zDsa@f>#>iRKW2|bjjzJtoi+jOSzzdMmT08|(r6~Qzf-|*}pH;u1Rn>S!#7@ zdd*z$FAK5d8c5r!@%OBJ9{GCfeMw@zf~|9xiRh2hqC6mBG%F%$tGq6KF43raWY2TP z^NGXM#r*Yz-a3i>UBu2!G|37gMy<@Tpeph*N>@;xe|Ko|=Jp(xXdnUoo};`a!Cp_R z4elP?i~R85M1!UUN;Jc>8tXU?S5d-pgw0alfxO{o(9>0z#iM!}3;L|O zw@|BaO<{(ZFgpL0Uk;^91Qo-2VuB^I$_rgG!Dl`Coh8AJ^_ZyowaCxv35?U}B63IH zfhBT)xalPHSgS-btr}lw{0^gwB8)azhV_XrX4AZS<}w#ND`oi?mS8ihte~Z}D4q~f zw$CXsO!{^Ak5+ULtv;*au5|HovTSU@UGFM+%&AA$?L|hCOLm}kQWa(b^yGOlFnnbR z_iD-N&{-qv+r?PX-$GY5J0umWMD)7!V-rK;Vx@jfjF5bo{L)|`5SiR*h`bjj)10dz znJ2UOZh%DS2x;!?dy!q4HNwJplEjic_UTp^mQ_XzdhOs~ zb>!FW?;k?D-u3I|f>%trx#8PB6tgtmam<#fsR74N!j3-Z-z6Wbd$U{+X3k_i)~Jaw zzuE`sf`Yo6qEO2D)~_+~1SM4hz8dx8JsdlOs`z%p36I1dyU#ahm=G;@(zfIL%ZS1o zwKHA~ZAevxkIXy~N{ejO5yl&^VY{L`rgK+)|Hw z)qKg{S=;7)>D-0r#L%ZiF&viGqxptp(KG`c=I-mX@`MfXR<`D!TE6}CH%fWWd@U#u z>6Rg>U68-D+uTrto6KtwAQRQ4O_F2G{+$#0@%vlCur&ke({e3}|%rMi3 z83^UBghuv!qcN-0uCdc@vf+-s4@$cAPC*S7rz?sKvcf43qb=y)#Ybzu+xIA*(bv~c zjvlj3xGzwJ-r>(XaYkoPA9Z0jGa= zZ=|W?wG50q>65d=U9)Bv5h_n8RkZc!<6R&BANogMik@a)b>D3=mml4Yf*yh)a9RB^ zW9CeH9Fx^IzWIpL^5T1vcbNLKriwQS(Z5RG5iP{qVFup~qX@ugz<`Sjuv?>1wRU$M zC??LTAIAs|%CJ>>h!TadJ%7%!Ow6~Oi;S%%qtQS6ev=>arbh!~7cS~A$1tC~o{Dq5 zh7E~3goUWunBwB~Nn@T3-F%BCi$}R};)W=6x=8Nd2S$6~)TeBGEJ(m_4b`-nGA0~l z@835Mp4jGB>zE4=y<(%zaN2;cm-5G)o$EiUV!CXSue%rYfg8*~0GH<%_$zw1dWtYL zP7*o#STYVJR}G0#FI)i@pHiN>7QXkv^s#Va4FT8PsOyJe8+3U-f1`D+<4`bKj$s*P zi}VifUjAvJPnAZWXBk!1+B$!jeFp-mHd8rylB@7i^3W{U?muy(BXHeOG+L(1OW8*6 zL*{G7*d((J_}~=cV)9Uo`3V4&BFQq9#`};&Q(SwA?XJ0d_bcu0GW`H&*B+mrZh!x- zVoDDOi=^gVVt&%)$eOF@RAXcKOo5lRKBCwdxs0|>{in`H^e#5Z=IQsCn=Hlo5F zgeGj%MuuX!kxFA0$3%m=-eQ<^#|MVvla6ijvDNCk`?c(h`ojb69C0@xi@$1x?cWiO zPa=~RR4#>2yi97}veVz5Ho=k1?4A0xyw>igp(j@yIR3l8OB|%Bvv)4g_E&IW{_y!+ z4R-0+Pb)LIMwnV7k$M7URM)I#Oy7{b9f+))0*rcZNQ9d|?mi+;AN(F;laIY961=a$ z!FXw|mihY6rOvgt?P)%rHePQso@hKQJMGY6_Z9fk{2!sTYtUDs`mX-CgXt!|5E z@#F+{%fwc#SBvH|RJ|z84*QhX`OW2FtROqK(3_B<5`>A_4L$dHKKIe^&<1bK(KZuJ zBel^-8inHpZ!$gq0=bcH$aZ?O_Pbr?EL#NQyYN3%F}gZK&x_Vww|92pBur1lQa-LlC}n<;q34Yb>ZYS{y9*x+R-f!Rt!Qn%T#Dc*$_7C$K-yd{~k z5)Mt8oGvNwGc4#44&!Su8-dz~XF zq$HX($Atm{d2`om;^|Rkb)A~sR|a|_65Q~cun)9^4Tpasy^2CZw|DGr2NL1Q3C=1Z z-v>OB@^p8XhH98>%|o;GBg1dLlAtAwPV5U5X`vziT4St*#EJgxX6NptGYw>cu8S^= z>~o;Sd~Gd`^xDZ1UX&8^H@dC~+u1d#mWR69_WC`&2~&vvHnGWP>eZxKX%{ypn-7|Yera-7h&p1{vNvoDLZ@4vNi}_ihf&p94za`#; za1IiAQ+MroPUp+?5@)@t{EzboY>cPT`{Lge&y@EsYx?vT05}1pI6)#N^D(U zV^9{)Fvj=Pugm%=b(B^yEo~Z=F@jf-ijc7MumEkWN7vY=lb@H0Em<46!0j!- z3ka}U^#SwI);(#ZI@6Qj!TRorwz#9VxWl{^K9-2M&H-G#eyl^y6QbaYHYNF{-%fob z(aBPNF9fu;{h6?&4*5tSC5Iqa8crhF`bK zNCZ_%|8QWSXx8*_G%5IOAJKArd~BZX+4FpkdUG70MC|w-8K_0Lj66^2%~>jkS1?Wd zId1{}C#-ry%1OF%#L9zA;tO}RF-G`SxWU9$^)+eo>jOwrLQ5RGt^RU(?qpGy^w3aP zcI6vR%SWcx!ac#S9@@Ps2mImiEI#L;pn5+t0ZkZ<4R%99J}x-f14cFaY6l z?O|u$BHSiZwKb=v(C%(%eu2^k)K?k7Bn7J8)FWud&|Qwn5KIMF#{d=zVcUqlcV>?J z4${$=q@<)|r21)X74?rIdnqQ1p2mFc%^we6(cX?{XnJF}>&27ON=yNoqr7K9m1mou zf2!O7QzaZO&Y(T?f4u-g+;WKY0t+_&T9ggRj1ta^;w8`GY9oaz(K@w0G_}C?D$r&) zah+4>%x90KuUf~>XeNF>W!Ej1@zT-D!6k&WC%~l}-*|u0hf8*ZJ#=aad(!0NZCbbA zLjygdB8*0IM4XRID_y(<)WeGi0%6i{oO$4H=R?c?SV~8aHn(C12jKR|{)0x`%A z$Y0reLVWMC1b+w9FBGP2IlD7&WS=A&Kt{a+E9EkK4&V3@`v?=j57}9mi>OT^Y1CvO|Iz?-W~)ssFRQ<94TvLVfDfE}@b`YLMGr2|fAo&=Fzpwgo(9H2 zQCu8VD7hz21W*#f$&!PD+f489`&BO2QQ3i_mlA%P)KI@?FH=1IMXp*b%J>eX{o`yT zW|zGr`EX(SQ{hwFlj?X|jvt8~Zr%}mer}Kep`*EnG-Z+7eQ+rq1|4RS2~cDrN@2D1 zjUyX9()i#5zYT=Mr#ZHS(bj2Ms4V{hnX!2Ebo1QCJ`f!ObevVk-1t*8KoPHf`)3(u z*~`gZInp&+=vo@zYm1G6WAqMfC5Z?zfNgzRco*CN#$mGJ4m@jSGZfj zh7ED3vS~H*IrysMt4M{z$e4rQo>^Hat4(#(g)Z|sYi8kI>aKbZRUP5|K+En5M1P}G zAJ)Ax4>#O8*L4HulakO!2dWOoGcR^Djz6hP)}U<++*qG<`gfe3Ux0Jt3$qi+05T)( zJ}|^U0zB1dIP-b$0-5AtExXqx1A%${$#+yu3(Vip<+spN+NzSzg1tWaUpKM+9Qt#F z0jo-_`J1x&fD;Q_0x9b}DozCfbIpkttFDuQKp_!ECV_J8H3rvfwZ&e;a*BeQq`~};N-7t zrxSg+;t3PAzfCia-W@DGff3QFD%|(jnw6t&*xWZXKb}ZSO)tF(GimdxN>1tcEToLw z+S=l1{hK9>=tf9zQ`|X^wV0S!avJ0vmwGZk23y%k+bc6xJ2JL+Z1L!#{lqO&2Q*WA z^BI}>d!aI3;uW)&_<1>o>jomnMVg2!Ux6thAxy$ra-r{^eXr7Twnw!P`;I@hBja%S zE9dHsW^3D(R?<7_-4Aes@3Uv(h-E|xj#dgaePDK_8i7tmLBD~DooSMSE|rtHh()k* zaH!9f%VAV($b9yk^Vd+y*|G>7?%L#DOYe>^iNE)a-`RbEds|G$KI-9k6{x{g{LU}c z%9ly6E>gFp3|01Iir2Z(X|D~=l8vuF)T&%=tpeJsOjScBp zm$oSgG_A*&Pf2u4((BS_mFds@($ZgZd^_UyN<+vM|d$n$|OnKGkN|IOU zn!P<*KO+-A;>aK`lH9Qi>ltZ(w{p;07iJ-EMUZ>eW7esF4f7J9jdK#k7riRw20{NHTEAbM_hV#L6% zIXbd=N3a|Ft$RPvd&t%ACDXQkDs_A&^fSmS(C@L@3|rnW52fom^v&Wv-g$qh3zLXl zgM6X7dI%?2>9UgT`||*+A&}Rp-)el1H#J=U2iCwrE^j$W!eH`O`hRBcZIZX&d@aje_f?1V zJ|sYLt7jSonlyC)8ZSTLWVy)=XbchgYQ*Lbygn0cSw4GUW3$Npdi|lo`tsbE%_k7Z zk8on2t2Ew2Zd9P-9ZT=|iSHB1*pMHRpfJ0Q)IGCvSRJLrX(2qeQI;Jd7(?rOJ`nPV z=de0=z=E{a(4msDJvs(u?bt8P{w7s-WL!usI{QBqKKVd;Qo`QfR2g`(z+o3zB@N!j z(+J9-FO>nK;ml^NBy1%0RP)wfi4+#g^ZF8Id$e{D>tR+}1}as~>}ikn1>mhCOqP)L zA(r6VZ9&7yPWje*r$q^e`-#|0%(hXBRGk*LU>}Fyft5%{I$q`4E;8rX)}@!Jx`IV! z-1*m2eg3KD{vvF=u==Liqxc_**f}UHivk=FXQQLx>x!{7ED(s8`m=|i5#(0Z%zl0K zRjL1F=UMrM(P#VF(p~=f*8~82$;$LSfm0|w8bd>B!%uvDcDDVuP)oq6wwl_u1^*jm*EE)TBH{x#o z$-i`(NJAc;Vn7}6JFXm3{pGPb8|mazVDH*0^o5aFvCbdH(6}nNV^|L$i~eXL>tY#%>PUEAIG7 zA>3FsR=q(3C2Q_jnJ{lrt_m3y8YKVLehziV_B(vy_0}Zwss!FoH4YE%^-w-}iT~q| zep~ofvj?!Vm|>G9CfTv^mQ>IPVz)4L$N@5WN}Ts$Pr#D}5NC?$rNo=Z6Sh0&fU;e{ za$RL*8UEYnA1AOV;WS)bS{KI@hK3Gc$B>`JzCi8KXi}3o(tX?=yFrT}gFBVX3g<#~ z`|KdmE((h_2PH&m9n*vbIqV^Kh^o>QIv8syyhxhydMk7urq1x?)b^A^aGx?H1rVw`jEEHR-@1I3wi z?nkfsY>{JOTZTzbGxk%CnjDgmaP?Kc+Jyz*6UXCS^a*G(=E?Z@%A{$dgKr-s4XWDQ z0>Dh8SlX=R za}AceSG2auKUCg(6wZ%)H+LV}qeCgE!AvTrM4seFwNg%vtMWbIt}$yTi8kj*T4;L- z#pMimEAys)nmoX=;MS0hnn*Rp-{ZCDV`{p)$uZM8V&C*ln4<)4tPfxj;%?@6P)dMx zwXw>Wx#t}p#?JaqYCyNNEHWyaglqGqGsipK_tzfTNEZ_ac+DQCi^%%12m%`vb;TY| z&E0w?r!vs;(d+xV-g}M(0@lEQFL0b^nTZGSR(iN*lj&*#I`%Dv6+e!)m4d zyLR$R+lk}sW6DfB6Q;b&c%M_F^WG2+u%+YmYX9tlYkD=6hO!uaHhySdVBgCkza16c zi4zdbAe>YHb0vb$F-)RcFI>#8^z7>l;pK0AH8A2M?9EPpK&Q^4WWS+Sbx7_1VtK~F zBJO)a(GuutGsbP-blm{N#IU4G=FrxMD^=WHbhZS0%OzKaqP1_)Eo>xruVsN=+os|h z&OI{`eA#S?-`@iCH?QWIP+fP~rdz+J9p62tS;KxeF#>&e`8&xk{Vcox(60EP6t+~T zhjbD~|NIyZ=fS!T+wG13GE$uHmFxQqoiFL^Vu0%|y6dXM<_P~u0x55Vrh3SGSwTQJ zvQIDXXK{l4VsJXKVkBDgd4gKVq8`BVuS$h<09VHUbr{GDp3K?N;|wv5p&g&?SQp~z zGqUC@Z1qS4hIs-akTZX(zjsb_dKbq7-26ZEE15iHOtW<0x(5lc1ZnED<;5Q#*DmY9 z({o?fJD1W3>Y;hIwYapVb;5ffdOwmD^2*Y3TVg(>q){%(TU$N_mr3=h;WOr&_PZLc zYNDhBURhpVUMvZw5&nvG$1Q@Ot>CO->OKT=-CTC3^%WxBoG^`52V9^x ztOoqqY{VN`BG{Gs55JPo62pV|%~HQhr|Nd#t*+C|&AHSfb`%tB{3((-sE%ZUf?jY3 z>PJC!N9XcWw$Llpt&ygXDC~JU+tKQAEWcI|179=S6iXV{fAdDWnZ9W04!W1WKsF4E5w=pv8FTxoQY84PONs_ueQWjeNYnJ z{D^r0Z^ck!^iikbuO=M|G&RIyfhWJRqBPkRIom~~d^&lcUw#RIfi-3t?%uk?6o z380DZ-JWsOunNU)&*J0kW^_5TZOlEp52^0t^f0=~$$H&mc{77fY$Wq`|22=}2Pjbt zL&VdkU7blKl8ZnB>@`l#(XIE6Kzy^|P?Us%S^o5)1{yN(Qj8h|GHE#Xd&2;p|Jp__ zVPLBeBsOM{y->3H8*_|$Zvd{44i&_FIPJndS3Ft-6Z5$_BeJ=S8hk8Z6hzYEg>m{a z{K(yr%ewjJt><-B_|^8-JoST`R{z(M^@TUYL*%gOnlE>(i$+9MmuMfo%>Mgs zS?IcBi@0R1t~R>+qupF+?bW@|)GybT<73Vt)n+?{J%)bs`3+{0`lQT`jmq=FI{&i0 z6*IYQ1lUHmBVgmH7XP?_c%|IIuj^C+6({Pe>4wfROzQ*vEu5|(Ko7+^jePOme6lE# zgIbP@Z1xj2=C{&KiywqQnC+~HG!pjLMtHq_N}32m0|Ska;ON=I z-eTXnYO1JE{d=h;G+dxl-KT1?`u>jv)b_7d_20u}z}4|I8)*j5|O7A45(+!~-=XP+Hz4{dJ&24zzSJ~ zJA%coGo#e5MvzZM2BrJ=d)9&MVWcTwT?Q%WaQrMI6AQu=0mOTJtaMu2(FTTRvLIo2 zz2y4DbKKKi;rI<`#FU4z)l|w6waeyj5iPkt)^|LRbdWV-TFL+ zD~igVS1=RXA3eN-tAVjhIqJ`eiyNc!U%>Y zfhWv*;ou1FHn!2^wLmhkjkAheQ|T8_XJltvK00zZu2_}18=oCwGRLDn&^r0)c`HLB zi8o<6w&fr3Kv8UDP3g1w;}9_`90gno34aGjfd50uHM^WSnHRF{Ep)qbm^L*2rf=dp zY~(7}O_~ZvR2m^>wlVjH^SSwBoXJUfgXuw1>rEN2AFgE{^7j(Q@Dh_C*LG=i7VBK9 zbuyfo=^Cy zawB;#m=cPmbGay3fsiFcQJUp3s3=rb?qAkga};Dtj+I$gF>)D<-ADD~She)l7tzwH zs!D}uDo`bxj`G*m7~i&40LrATO+nxu)fn0VXhH>&JcZP}uX4ya-G>aP5diiA$7^2< zefgMw*oE?GwvvyW=A8Wq2e+$yi`^vR)-nE*mflBP?a*L5hJ|i^s z;h}RL`sr>=qTm>ub>HlX3211VBLG#k=ER2y^z<#8QjMl{uVByJpUJv;U*!FBd%ZHju=)H7dy!(J49YD<8=pwRWv0HTPH$uBPVJ$m=N zi-qjGMt2JPF5=NJ88O;*QbQGjsNd$)wIU1+Ku~2P1#KNL;89_;wgl@^d9I*|d&+M4 zv$)rh2+$w~>YDEZ;eP0|O%w5ANwFo0!zCKk__IUp_b>g03)A(vx(E)C*ExXf1CpWp z>3%C*^!2~EF3DtVhYU0?Wf?nMb{(BoALWVq3g8$2{^=c@bpi|-Xv>8je}lC&WQj6( zznu@r6xOjsVrwGME4dRFPpIuG=Pwq)-aSPjE0{qIWg^vT5IVVx9@_B(;84u-rSmUP zsRCcI!-Qr#m@;gu9T59xMvw4A;T+PQ$T2S?#du{e*M;vMbbHR zEja(wx}2$ky|Wkn}XkaG`td3!6t{f{DtC zr7K?IO<)#^!+2qgv=O!6KK9sAE#bAF6<8v3-+o8`r^rJhaWQqHIN)W#cq&DWyXtm%QEsLs}s<4%DzIlRxC zA>9rWog9*-kwZY^PL0W%M%`p&(>Rwit_wu zwO-8!v`39YJ;|7qjmkkqE_Y@ghu*TIiZQf>e~BOC&XtS!2aI@6$AA(*U{fvwDo1-` zV*`-FriC`3_W4d~&^W}bI87^z+l{GU1h4TiSSLmd5Xd}hyxYI#nH(JJvs`b#l!e>) zfWh`BJ5hg)iRbGL6*HNG%S+|~#D*x`h^GhZ>RNLnYKMq$-L{x1%;|fgKi)Oq?zMpY zsz`E=Vhui58Cx75Jm-+)a@^{Sd`^>-a`7ti9B6!$O)1H+SFjii^(evPpt_+b7^}>a zlOiv?JrYZAnW?VB*Jo>UsBj_6T$5SRg3*YQn|6|^V@}M%l!0$c^Zb*q^ zE^(~{F6s^0HjT@cSwf#+PfIlo*5i1g>B-SANu<_$5~HwFAzml<9<-lx7nc`Gw$n$$ z4J?19bZhhc*lECR0(&y&)Gjke=57rS%G-lyibzyO$FRAz4tdDMwn&CJyo&}CP`zDY ziM+2o1|L3CJw|_4_(9W_eqH#%Z%C?r90_*E)}NIaC}idCdey%^(5&!v6w=ApCbMN? z1$lvvYhSJsgY0)aN)k&-(_agCiqgMB@UEu4t7y7nr9ti;dDE%fDr|b_URFG;xV4a) zy0d9{`)QbvYt3MNrxViwM_lv?U`RSwb@0fA9CJ&lTV%eU@@xYWW)-ol~~ zQ9{?Nk@@M(O=Aj*%_rwUHBfrzM3ZgRQH_{R;b(3%e4sL}UQ(9+lw*mW&bH~`#{>t( zQ$pNgX?zNHgs!)&u9WvjJ6-R)qT8{iz>JReh!tZtA1!j^*t(~h{;&&|4Zb@psS%@n z8|o+Y25(0lEWep*=IcHaDFd5ea!G_+ZxTF2vF9SmSSv=`C}rwlM~D$#+TiN-E(^04 z&F#6me;-;Rsj6d5F+;Wl$@V*z?)#tF72OnN?c2(zDc+|wghYW5GE@@AJAoV@s&izSJfdgYKLgkM@Er%h`}`BISdZ z`P{^zd=6VEXB|qDso}Xy`JCv;JSS|AL&$~htI7%>tp^=gQemB|V&$qK=mEX7W@-9*W1QvLk1iR7D zXc~(&r#yUGgiaR@jtw0(w9}a+XLt2* zc|Uw5)_h1d61{kd8EFEDu9aC)ihm#MTJyJTNs-^Ch4fzx9l+>v<4Pjskk}5s53)2mrAn2-kVH z-`+syNl?e}>ie%3FA-~dK@1cD!2fala<}*4wumyBfxw5KU-;*ses>js4ablGYoPC! zZC%cE-UYNW?zo@VMe%U)-gRN(Uv?@)X39+s65%hy2c&q>#EI~7!WuUJGBGy-N8%j6-*I4ax>g8};eob_FAW@uk_aWcq zaNeK|W{+*c!3oKvfZ~F46dWn{h%70tYYS$pI<6M#t0RUnvTx(*VKT^0xgs#UZ~tWk z={Z6jdqoVb<@leiL?$e=VuX0bswO9UC!YQdHzzYS)34OdVI~J9lS0Ke9Q~lanSEZ? z;62q?oV#naFF=ry<<-$WU8#u+DtQ@&3Y1Q&V`y1;k)i|0!~?<*5lO1Vgv@X76aTLl zKz0YmOUjUS8C|KrvtI|pC@Wl?(6g?sNjy13&d@MU5T8BEJ1a$3xTO&AO**D3fOUk) zmI34ofpP8ec-8n1)!Hx|i@EPI2uD>MG_5^UL;irlG%3wPn<+$&w1N-*r^4mPA%a7{ zzzrH#f5Cm(9|(TEyfxj(|7LeS#&>4_?UOu9Tt(ItGx!#u`R7Y(EWU-H$D1JC;_@=7 z$jd|23^DP}a3s6s^}XjBH@GB;qyPR11HCubo6bl&MnDrj>+T~d1NtI-f*)y7xvaDz zhn2&zK9rNZTlr1jKo-|7y%S2m>cZ}@5&NTDz<5(7WP5&ZH=RLk=h%aex_9|=dtnhH zt>WCWbg*(XJOo~1*+!0EoK5}8gkVykn(?6W?YV#HSFh~~(B493z6&DG3zWsJcn@^jxQhOMP{Kbs4c`USgkwrxL?7q#cQie$A(iW)h zODj!d=fmXTHNC9w!HG1|P50wthM5#mpBP1qA6hBv{-boPK$Y{|Y* z7T976{Gr$`{kYeOCBSMJFuRUp z_8$x==b%m#jCDZbsiuCiuzo|~fzVKC$nD`xEQo`(@v^V0g{YrR!AZBGlYk78shvA$ z4bT%6q0N1~xp>wi&b>;|X8`&iuM=gnd8vWr72#Wx`c3*6pLkr3)Wqxb|NKvjEhxF@ z!9iYY>FpOk^mFlt*Auxz3&oJmW4cD=F3C$t7y=N4j_rOI~Tb^FpEy(8Ka z&DKVYIcW)fLf)K2e^@Y7GSJvqd{*?B&x;odo#VM@SvnZd^QFbmI@h56tNTUB)!yaP zk_!Jv!C2Tg@Qkr&s-E_7Hj9Wf1wgG!KTr03)%-E3#$KzN#y2-PY2fazVW`0E$s^OV ze=hw+!E8mvle0J`eqofiD3F6TQK$38w1EGy_bwqJ;pcQ}$|tnKzM{%9o=#hOFc$^& zbpdtUiYG%0c0zF5SDDtejGfHIpPU-1(e8N|sy4T8Io+fj?Z3+}fYTFrC`rKP3KqB3Z^G;{d#daQS9 zFW1VsBa_Y|!WbiEiO2Qt4u#8n95+Lx^6ies+#377y~^hRgl1;(2bLq93;4Eq;dW%J zddaH4``}=bIF+BLgagwy8Me7B5g1+A)Q5!kq?FLdZ!h!w2#bz`$(o*|5SXA70<|b# z^33afbkFkL97wLA8b?QP^joIEU@+vJLxCXNeOHFdgZj%U;hr?)28mltssszX^#Pcg z>g@QwWMK|kG7$A7&=Si(vu2il? z;Ymfeae7{5L6hJ4Jd4N2|M~Zg13j22;?gj#Vp{^3_A+ChEtq)W$z;gAUYFEFIKg(% z?41_%XSYJYAVUB2CBnnN&&Xa0hs779WcD{hEdE;yLP9FC|GsL-!!zEIDVg*xT;BU^-=5a*7O1xLgE{Q-+p(}^>x#6s=LHLg#CM9 zB{sa;`qe}pHtKl{tYVqvv$bK zi2n^x+QWp;?y<1~lA|OP)5!8j6CE$IYZ&I%F;4z-4n!$YaKV4yz&v9FgcKTzwe^Y^L+MBLB9HTBR0%|6@jvPD0ONy_We=Ad9)91G z7x#>sot~~;{P8kQE*Crt#eZ}7^Vyk&ZU(mcFoz{ggjr&Be!+T84vIp+?&kF}SWt>u z(a0l6`?l>kKde*v4w$L^&b2F+r`;T2gy(S-8G7k zimEE7{iW_jX5clrhXmBpA0&N|bh~cxT~mwCFO5^N%t)wldHEn4jj0v40&3{6cva^E zd2Dp)=|+Z;yn9as+Q9?%ZaNJwDpVY zPD9jPYBSs!ANSN;%;Ir7wr?vfHyDsg$nLuAx92>d$}L&s1OrbjeAH5N5g7Ky((~%v z1B#4k$b;+LiTdU=Q%c{Q;^`elZy@Wjac0KMgb>d|b$Un-pprc5UVO?oU0POCE4t6- zIWJi&8A}c>RUJL7bTcF!SKQD@PoSc7G$&>+oXeeM)0Y!fq{A?4aP@!yARm%0E^2mQ z;2`Lp%`v6D0utxPAM+_|1U!k<0c3Qgd=~e>TojR=TgI8hb_8LX-Z>DKIi4h5< zT84m%h+=suQIhTTqjkY|F1NO+PKg;ROIusBi!$>*7)!^<itP8;i8~qjPS#t>KdX&z}RFtDa!?_kNMe|Ex;+zIvD=}_Ye6Q zVI8o3>#ZJ~L*=l)wSo!E-_pnbyJ&;AeBW;9YX_HN?&hq6uZsq}-EmK`Y-|=L)`H;m z9?NO&^YB0t*TV}F7_UuS0$#e z_utHn_7bn!zPN}K;LlxnHw1nCmI5+zBYyEw+A|!VcfhYgBZtc0VxaVwu>Q)5iQUI1 zWaoZ8Wk&uYg0ST`HtF^NJ-wp;vLlv*=IC7RfOUWE`O;kK+UdQ!!9Hz1$AH$Uuqo%r z=a;GrI6F+4YM(|23ONTakYS;JKI#ao+ls8G$BF-J{fTd9DO6HGwdP)zZ58jku#CzP ztr~ri`#mHc;Bd|(Hu0+7JbvuSy|riWM-$rKGX%^)i?{P_4IB`ih6Hy(i1@irUSlWj zn`HtO+?!oZ_MU`?-A+e4jBm7;ZiAZ%CHv|=DWobwtq9^V%I#FUis;Nwn;zX*CVm0C znJ|d=07`Hf$q#W-F14j8W_0+H7IzUA`dQ z3oAL4a?UV@cPG6w_Szd(C=}wl(!FO%=(2bH=KZ(&+~hAxX){(~{Wkm*;2|rvjITd- zgtu*;wIX%AF-;lA>CYorV;?w$niD;~Aq)i$ke-wTg2b1)1wUX4Aj;c>UmSq97c&bIKVDl?_tKJdM`juuDjV*r@bNUI$J+VKU(nje zdgq0T_pfTm z_v{cHeFk4PxFqyJppJb2Eg^(rgHb{m<!!}#>tthMbt>Dj< z%U*1TGXD`S?fbfQCyC4r*0`shgM7+=1f)i%%c8hjWX57>z%+i2otdK>@N}P68|}99 zo>jjOCeT569CS3_$G>)AT+Uz1jCG~(xjSjId;gE9ua1iH`@SAfB&88SLJ*|{q>&bo z?rx;Jy9WHw3Mkzz4MW$Ef;31D0}LtM-7)Wjet+v-i{)bRhxb1Bo^$R#`|fk@fRKX~ z-cPBN@J%<9!slboMVhuhbM9sqp!0T_bG5B`x_+lfos_?RNyK)^Kr}ow^cOE=Mr<_p z4y!ykO;zvH3|-R`iU%jOeg|v>{@&+*aO?XESI9e~RSwlo@Tg13ZT9aJ9>H`?Z z9eMmPmlKWx-??3O6%P3N@4Z6uiF4z~!T)>?TxUsv??_{xUnzLLlhEMl#KR|AIKU^= z3+%NU`L5-+Gy>HrM=wugNHzGC*PoY(xpz;JSJD~!H6nY*YPQ3H=t0X5M(#S^iH827 zzQ4pnHc%rq59btH{$>qM)Km)-77O2JjBpLBM5ra^933ecZEjy!plTx?HZ0BpSbJcT z>2;e6l8li3NEdzqp_Jt7on^$n|yw#HfvGT&(VQn+Hs#oOgXZ`3v)_)!FEYG7?Q&c$&pw zb=S=1MdB!<=a+Gwy>fM?{E4l<*ogBY=eX@vU^&t2Qe*D3+RJMx=628hUhD!YZ)HDx zLAd9b*V+!Y2-%s*SkVlt@IYZ96)QK(piNzZe4p!b`>v0O`yf<@=gUultaXcpdk-O; zPxY_IjEJ1*G&K|1^gnew>HkZ6s?t(Y4E1qv_j7PYzRfyfZdItNmimSZwTheedh7)t z=PJM_1H2o0O!bGdf-zP+SMFV&3YU(VS+@p6*G$8#V4s(M4A%>Z^t6_RtONuz)cpp$ak&lGgdIOJ=9X7@4)O1KXB*{HcvjK1)z|QeD?`zI_$56ZF^Kq834!YU%!iVm zsSwEBiWb}50I!k1K(rIB33$zoye{{4r&}_A^J573VtvKv8f|1>GS9jY0pThyP}AcU zdyz|AO<&?+U?uxJ6JHFKj4X-LoAo}cHQ6JuJCiYAIV~dgP}7e}TU%)6fhsuS_61l+rk|uYnqQjgg-^7hDKHOQak3=Og;a znUkiIP^xj9tD;M@R>N=+zvNkMBV=*K$Q&5oX#Ts{(7ev|A9_Ovxo{`>6cxShNJW;k zK25FE>b3a_VSLrEA7d@(R1!2M-f_?CCWE)Ahml&InRC|}-N>fhUD$|0WRrlyf-qAt zv88qtb-|wab?>s1)277rv^#U=h2A+XQscqzs-6(NW}k$%rXfEqAKd-XYxi<+`GCPC zFx-B7D=Fs~s+qVjeaJ<|iWCqj{Gf+?Q4)?D`byMN`EUdcttZix7-X$9=`BIz#I!rp#tl>=zmot|Mq zznNR)oGKRXpKXl?A91aUV27>xKFi^ahn!^Y(?%K@2=4+WfE_fev`#xDNN|2 zGYmkUM4U|}9ki_stw9ZYZS;m6^6pd}_VWbRZI1F68^EV>i_cW~Gg9LY2hSgvDkdkEWu3myqS|)ulnO{;mG}&cBE4K_1@A&RYObXM4IwuNO!IOyWZ(* zKfeQcU>iff3=CpmE~So&sQ;|{0H(c(%4)sEJ}~sI7_$+4D|G31<-w8k4#)JT%*dUH zNQvd22IRS~YQNZ-415n2UrbOq;Ehg+90spl%k@~s$O3fSmyPC!x~!=5`-EZtqf6JZ zLsrG~(%G|WwG%UX%Zt0TfT`=CWk-vppm1N7<@_BEgQPz65vtig zf1*4Wym|R#P5=8BzjI%EB?Xy+4r4iQJdN(Q;Nx)CVS_fUMlH{hEo~nM57tE&dg0az zA+JlAE%wDm&HORp5^s<+2o<&CSnlK~fiUn=mQl@CL(Tc}jtRB(QMfw4K?O|f>sfJs zjj?I&Tp7RW2MjV;vnG6WZKn7t(PTbMLcPp4Fbnja)FVMF+3sWu_>Kaa77Q@lvgq2}YX0N9FzvGiqwzw9kDGtiJ;c4krU{7m)o<&-Zk$=pK^)>0Y zfnb`Bay?d(Tru_H6gAttul;^$2pLT)15Ia0Bc5G>#JYc?*ujbZHAXR%ySIgVJ4lz@*D|mjBLn z+(}JZ_b&K@UibogVDv<>yG_XYwUk=!m_1*nDJ1cP8yhs*UhLUSEVk~_BxXGCv1{QA zAfb-<}HU1Bv3E*4$J;?ttNFhMZlx=<8elhR@ zVk@;W7GWj{bu!>pXK3-*ak!1^W~=xOKA(ckN>nG6@`~3#58f5aQ?`Os@MsQd&Q$B| z$ebK8Ti&ucFB_|5BiqYyx{}k=%MzLIGx^<1&20Y2?!TU#-1a$=xf^sn7F&9j)qY_H zWu@O;@*QXVrAYW-E@KuOBTZ30Z?Yn`xJxHK@SRIG@!X8fPsw|1&BJZC8Us=mxi~hT zZ}DZ=G-J`cZH5IDQqlaHuW1^R8$2lyGz=D^+8dI#)$-mhc zN&Z<@xASRg<=}L0^F}_){izrJKfpjVki|e2ML%vJAS8sQ1V?1dpbuJ7mzB4Hm(Sr9 z*D89VeZvm+W6sUs*9e!lA~tv$%{L^DOUofL$WQm@F5oW0W;;F72nk{2>PdbA{Z8F~ z@0Pp`%j-PA*ZOa%!U}%x+?hWP!#S^$5g_c4_DCwzWd2D*PE_`nvFwNOrAjZY|vAV{w1Z5qRQ>-CdFK zsNO9;{!2c@o;Nk>Hl=?pAt59LP-e%9u~rCA?iJ0*CNteTg{|*pnrU_5;Er2&{V&%K z`I_XeFw!7kDRQmd=q~WA`DA^~hG|{N_VmQ9cT2ro7Eu-I`=MTHZ^?FPf5y%yFGjoc zH8tFDAb#J%waYSZS-Z6=F}xdv0bcW#`A10E7jwO6d|JE4Vs+?3kz((<)_iXlFBsps z{V6Ei)7MC?wd@xuqFp!x>(yoHQ(&WWO*yV=L|oe@WVrRJXBfL~-P39=V?3B4G9CARJUT*~{ZcE5T1Ey?x%n(jV9ELnz=JW32h0Zw07xC?wf zWy6XLqq{+v`bCH&=NT`@jmFpC*297iM>5 zNwW{>V$K=OQ?Dk$TKo9x2)b3Li>Rk67b&Y{2FE_bzvrL1Zw2>Ju`)VRqwv^HdycHx zUeUdbwXGX8B5BY+h)^uV#!#@?a^ug8-U)q^k1uAW`t`YmHg=&{e@LI)=L^Fx=QapS zJpr?$yyTRvas%m=Kg9X}M-g5NvR$IH69};_l3aUAY?hZ+)UR)l8u_2?Ptt*kt;x*_ z5$b{XV%XNo1K);%UIfwj>b>^;Udb+qAqeHz%F1YO9bW``BIX`p#D9@gXm1g6wJ6w` z0l5{E5eQLWy;h5m=DL+!pIu5cjvBSl$xtj;i+`YCH-iB#$0#mmPz+ree3qccX28^A zQfH@Vql>_?9583dw!yGuHYYVaXXhP8S4)i02tPQOLodE7QPX#2;YG3~ydcnY80C)7H8s|W&|5Cxg z_i{6*z&b%&KQ6UcD)_%0AK+|xuiw4EZ0T5PhDYe}5^Yf+t5o4N3eL666I~W;F=@v9 z_$oJw`s&gs?a~PiN*W0UVikk4z16Idp5&g2*Ujc=g&y#ljUGqJt7wcX zHl((DfYy5uMX!ObZnXfVIDDz;x7os0Es6xf0EC(*L^o~p8~g=VU7I9sJxp=1 z%NZR!MKvC7dFKn1x6nk1HGxEle41Kfur1Nyk1k)jy!{HYsL^Y~%JBO)Oxe?sP>FV5 zv&;W9OH*X?Y4V?qyBh@fIsc>{fz66xV8Cqje#V}E7hm1|Nr||T$yIT^oPS&BzR^!v zIyZWE|p<|dK@xKA&(PU?X_G64Q6kYxO4dTX6 zTI889UxOI(=c4t>HQ}0?T3VX?d$>+TZ87%oCmgA4%s1vBf%7j2-Z%@JJlX6Mv>oABg4qQdn+b9*7p=B~Ek`eY$Vw0SngBhW<2cU9ak$+QnOtUR?*O6}S+T!^%Z@4i$cz#q)sy7a%SF zpG{&1q1{*d%J_D;XRNK6FE20Op~F;*m9dUgOS5H3tnalejRHj+F(CW)e@U?l~K`^tZP!&}Si@-I305|N_ zvKOuJ<~|=z!0&t^%IDGC2+)^^y3QG&|I-3UFJH?MbVY`(h*T9kd-J;;ymb~H9(?Ac zjrV9&-kw$nrQ;-i!&_ArWL4xzf4{y|F06D0PM4$r4*V5`R*B0;y^-cp+Gziwxgr;?T>f^gtw&P3Sg z>?OW_xm4_w_llc^5LZq?_Os^T7s=tJVFV`1%c)(77gN9DR0T-v4bz{zR9nP`-RG<{ zUe!M1i7#C|I>iXoZJw=1{Px>T2>S;5b$`49tvUKwPG=InNdW4XW+KKlCrnv`t<}$a z*cT%9c*=To?aeO-r^LRbHDtN`wN@?@M@(;p&932rthYnR{b9T?R&S`Pb@@b7%h6gM z_68eY{T&^lL$XEg{5UrYb6v@si!|e~0>yPrp6tmu=9*!vX)bvXfpushlK8h-cg>h& z?@hz=5+AmdaKnt$=DNpAopFE02i0D{o^skS<$sAXQC0egqxNlcSW-O5qBxQ3W8S1! z_wB6Z{I@&LqRj;|X^BbhoPeTw;z>OE1e30fWaGaCoQjWJ-_M2bpzWVZjELxbLA?7RX`0-sX-R9-irMo+rq{Cm-p;dlGi271oiQaEj6kb< z3$nlgW)-4MJH!2EU!Ei;Zo*R7FPpO{yIZ8|i<6U+atrK^q*9~T^FNAHVCy!5RB&Tri9i2=2p0ISiOb0GLLLinQ54;CdrV zEFO8e;9o4$>l}Y)nd|n6>M7MLeF}2fmKM zUu%=B&wNcIN7M1%{qXcdS(%^tb7Lh&ga-=OElC}Te$mhIS>Ppdz5S!7x%H|AR4Fo< zI>~%lJe(S()w)Ji6t=#7&nQ11uFDPD=p~+Qj^&|WP~YCqk2pLpm(8EEsavocNHll1 zN2m>)wV3#}>O)W&G`}9Hzhx(RY95)Y@y*k7^MY?cqQATQ1#EkiLV=w6AF5?w`Pqyk z7>vH88}KSk96Llj#z_M1UMw@bUn?*#JuS_0kw{B`Kc-z4k85+? zHB+kC?AcM3&k`}o%6neq81mgSZ5L1$|FQ892ZtAy`8I|DO?-LnjoR zeVI0Vjb71uem%wMmP@&%R!G_(_2QNhps6KSJQLLRNu4*S*et(Qq7P>XWYNX-D>JPA zh&^)*5I8YH7F;^sH}_Vw?R7lgea`tFhPWUQeZyb%&Kbc@o2EWp}9F3 z5ovedsX5C(!-dw{H$ym+!x_yS*ND&rxz5mQ*l8pLseJQCZMf5hH93Ef)zr8GZo+2N zirN*I$%P{>!_9rl5@nOST9^g?L;XW_YX{!s+BeN-VC_4Yd-}lj+BuvLBAyQFYBSmi zdB2-?kP-!%9ACrv$CAUljqcZ*YeI%$;zLDE^#B&#Ri{JCo`USh)ZB&c>NSY8p3PY9 zbe}mi?C{mEKxMs4w1%DmNB|}O*1+-c%iznG)TMOd&;oP&yCm@$*Aq+24a=_O?;GB! z@u`p`_@D({_1Ieyx$YM38sfdXK9w;c5SetnLzY+=vhP8!;K4bk6k9a;Jysa_{~~#gbf%h7ymT~n`8Y~!i*LzEo%0P8`fD}wZ=kA`v~3)b-?YBWtP9@+h@)5 z5K{!uV^fwf|M5#ZM%q>@E(WQu_clTJVxWeCTzuLD**1N(3Q_dzcpGj#10eE_b7wg5 zrANN8-1u##(T1b~Wz%+5;94s$Sa9|~{}<{^2{!4yC+2u!oCAcfH$(qZ&AhmxzW;DF zp;QZ?ROCw58|pHYcfm2=6bopJ0dfs^A${#n^y|G3z0$?%E)>1)2EFb=BPVh*Vi=71 z?R^p7(|*oYSYBMFyznCC-p`7-a=fwmiJBc~QA5TN6&$lUwHrMVAu(hp=xMzF->Fag z8afdx$n2eO?Iw3JMZZNXyUUMn=?_;UctK!75GkBD^f!fQjgA~$EJ$z-cE9_r899i| zE{i^%B%v2h%lsN*3hG=wRCO+n=sAq4w@><#uP1W9d%lP0RvjCe0l$7Bdv^2j$=;%< z)XNr~p#}L_aXC-yCCT4qbWcHBx)*!n7S*01rPi~O-ml2H5fGBEzoImqC_7#$#y@^% z^~TuSSD)hS6##^3XNSWEno0KRl<8i!`A(yu94xf1gqbaWk$g+R{VEZrNTM5rZL?>S zqx-x}-b80l>Ra3G>4XwB_^JqI|2}#Jnpwz$5Wh{|Qv=uVynL*V0j^&lY`k+72VC{; z1uJXA?}pt0$!-S$C`4SXer*#tKO&%xdyPKVSWQLZx`<%Is{OInu7&fJJYuxWBmb8oJ1J zJY(4~1;++FFM6d3A_5;fz=^rL+->*@+N8vwf!=l2i_D2&;CG0-)?}?F)FpELpc4{JG};BJvPXV{mfk|cV(R- zpdtN+2+Aq1v+XeYVz%jipb?-v-zN!pj1gNs|6X*?4gkaQH5ntNizqXPvod08uKMg) zxd58^om36+%QTrD?7uk@WrgabA4fosi0~d}k%aQe8B|7-=~nJ1T4;UH2{Qk=TyklDY)< z9~R}Nwz?W?X~C?XXKaV_J{rTm$s~Y3BbwkV!UJ9-#F!tr>4s3Est{~JF5O)$B5!|_ z4qLp6k&fq)4KzyC3}g!7QYv2NsN1wWxW_)Npq{Ki5i!4rzQ)u$`_Jn@k!C;bdfr+M zMYi}#fLRev0s&=v`}A(vVCp!=bN0)t|Elh{W8@{12~kV2_m!ujAYGthdw^r0CFoBA zTJmz=nu(wlqd0Wjxdulze%O~Cs3zii97l$cKV!f1POAGX3No)Ta1vj*Rh?Bcrqq2W zX-{)|yN7p8CNL_5isBadvvV2@-Iuce53BDvx?v^U|$3A(b!h+!>qs&&X^G%}HKSLUN2QY*keU4i0c#yh4cQeT{9Gvs! z_xd9JUESYi_v%;pjwEX)w)h|u9=e?b18Vb%g)qB%gnh3o{~jwy^^R78tv`T=Oe4@9k#qo&8Z0f9D;-wMQ#P<|Ky(*No(*sf`Lm*c42F5q&Hc2=Azfnwoc9siEbHq$a#EOUn>FSRfp zpH{O3zQbKQbFMY!;K`q%*sRa$7;4u3y*xgvCSk+g!Ybc~^m2?0ls(&d(#{s(+5h2| z3i@33Os|V3*y}m>{;2?Wky@*rR-cp$?}@Su9@-b2%6^H-xxPqjdiE!p{i-S|A%U=g^$UN(c8ct%+qbrm=b; zBO;mVa&mKKpSkXdg9dyoR(Xt%8`j)8j#ysscMeh6b$-O!A|xz%Xbj*$g1w2b0RdSNnI=^a zie9x$`E8D}rtv+m`KFnf5LawAqb3ed4;~ZA$M3>t?+w5v&jN`%9g%_ft$ae#b6vzs zmPb?~(THb`nNl;MHlda}8N9h+E8=`{Bl>vhLMJaEgu1F> zeFKG?qTw#rlg+@f=iuJ`J_jG~)of7B)^}qos9*WyQM*Nh!y}9^@fo+-N)FHfBVO1w zyQ!4j8#3%ymp>j3?(-D@qum9GU&J*=&)aaHsdMmhQ$|VFL|{IBXU32;Y@Pb%$8O=) z0vlE!KDg)EbBWDiFG`$Q%8utgTN~E-^%i@EIS8a~D>ktM+p4V^V{yOyym!T%Mn@3a z!J|?4uE9b=7$%6XWP9b?WyllFAf`#Y$(~-u$^iu4lg1apHk$Ng3B` z`C>ON2z&Rm=nW8)4wHUHn^|KH0dUFz(SYcGABwv@dPfJ@;ZxLNvKK0DnCEee(XH^x zOqDk0Dn8SbzAm3CA+11RXdjt9xgKjWI^3VHe*GD5|Co72Y{0Oq0r^Ju=K(5uyeede zKU%E>3^9S@DMUqR!<$0QnVi`fe_}>WWwh4~) zs5)Gc`U;CDo9Y}m;aDp$uj?G^J3Xz%zw5pYB|KS|3((C&>Vl@nhxUwCGy*j3ZzFB) zhhD}%y6@S?3Od}g^c*=698p>Ty_9I4Z)$$0la+-p3f=d!&6}|HL<=skrY(rgh`^(T z3|#0o_p5t- zmpSmqDZW-~ox%mlo~fQDCdL}hop+r(QE8o*mK=M+#x*LuVYd1zcxazLsCiXL zE+{REvIS|CCRj}pcaRnX?+IC#+t;SnTZ(^>sQjJ==MM!a<5#mQq1cXDey=W*AM6cx z!|9H$WI~6DWqyJmgi~zE!(XmBp~4eCptN51Q@`JEeV>w{ZiZ!iZ~$y^zS02N^@e3^ z8lZSZl^R}NfG1xvfNS`=b-ygQY1-N-ACFzGo< zlaUMo#&s%WwoiJ{H$Avl&4cKaYZVA~DegLM*aW=L7%o92#^E%3PjjuE+4^I3{)A_$ z=S(v}Jl}@z?NLt0oss%TbKb>v%_}s!%`7oSC2v{pAbD0$0OUu!s_a%p5hZ4rYg2l> z7zSCC#NvqLfQ&eZ9g)VsMT5_QLvRH71!4W@D`KEejH5W$U8df z5<^9_(Qp`fITT%##zYb{smopJ5Hc*ylN1Mbb+720$DV05sXvs8Uqqr{zz&|O^rVVJ zRcrmCl3fAa-tQZ>C2|nsDXbrpKKtE%yLC$$EYX#mp$EZqKr9+%ONP2)n($1qs$#mLDq`!@+&Aj&G&hl|r!qwMG za|uaS5ms!<`gvG9RYdSedJ2q7;WDL}y1}=5cR045x=e@x1~d}97e4*7RGWS&j)Fn+ z13wkA6PlUPXHnCn1u<;(S=+8Fg#$e3fcHQlx1tgv>{|B$)iG;&g@;ixAJ$6{Qo5+z_3Z5{gVOvu?#Y3VCLL^4*Wa=cM$_dI&;;i^&Q@lf-b*Er!42T-uY*Fi*k5VdYsITB zmhcWHl&F?iOM`s!{MTf*PG%_FTHKfEt1dg*cUWk`u+PK(zl^f~pO|B05dhS01l#9) zbv7M;A_PM3gKlE5_kIt}{*fy+SLs0gB*-*dPl*-6k%ANG=&>tVy6oM`J0rarH1rgN ze@A-HRzl2qd&tts`#Ug<;Q+I={uh(`?(+Ds{R?mNISUvpZcG zbEk9vD42*t0mBQpc?JCH;R=4fd;?|a+f9&V&4IsP&QZP)wO*rD*+NpPpU8Y$zBj1g zWb4*VnChF5cXe%*%5l=K^Bsg327F`@h>#pdm^7evdSBX%l=Rdu=}~SrjYh2IrcFP& z(~|I_L$wXC#pLPeHEjlq_^}5MP5Cf%D0~PSF?276-%Z z)Jb%Wg@j4efK(Dl2UPnV5WhEEQz2ak3skd@2oEi#ufKk=N`<_DW)7|yHC+!RXc=Xu zXGBUW=#WZB3>WP!P9iO}i*-)%hQ90AYmI*0AN{d!bk%&~jOIq3VU`14I||Kf2714U zI;!=nEO#R4pZ&YMcvU=^Xt=Q_tiJFGx@w+tP%qry(<8YzC~GM1U3GrYv|~_#y+of# z3_@#kf+tR8(-21dP-8@C%-mpHW82+m7k9i9R+s=DK#ys4Sp!%t(2(Qo||t-H~Wxp{(W-2H999J=U>v>a;^A|F0}yQ%^dF!khV={u&kZ(>hXB7YUPn(%R8<*O#t zz4Zzc>B)W9pAn8NiDKkAqgSrjaEO5bukY_j$&lTRt$W?qt-AGrvP^b+BwGeeU+vy% z*(ZtTe8(4q0}Z@{Fm{kWtW)+LD0J9o-orD=t&c%uL(!~}KsYobpFs!2C=y(RN_+H8 zZd(J?w?7Xe*dBv?t5qOc{291`S{Vz+FR@Cd%BGmz^VNm3;9LsQz=JS+6vFM5hjlyf zy#Au^gy2H-zlvy4b}Zl$#3+Y36#JLr0Fap|IYw}HLV|EEu^D%P~U|9Q6K=pa;6(|RKVzU&HEqYj52 zc9u)Uq;7yZB3}(z0irCy5j~bNAfn)gRnMf8MXXvL!z&C1*IdOgIL)58)CUO8#bqSC z4-V}6q%<&phP?rj9nLk^1O12xy1V0t0>yfq?3|oxnIj}bq2&}HQsMR&F7hN~YgD{T zto!ui3?iQ%a&i@K8xc&9w-o9nla8nT7SzEfFC}e$4pO~Pbi)|n!Vv&ozP%lqiJIzJ zDl_U|(EUxdO>$&A9yHW0_uNP83En?#=;*o+%1>9FO>`%{4$^aecx=E|Wyi$DlAUFfr43$KkG2~owg6$R`hhLpJo6b##s z>n0_}k*NR|(Q9Oog$9bSJxbpXRtIx6BXIm4qRo{Mvb7Sd#0T@E2u$Lr(BRrV))S}&Sl@irei2}F zkqg)M+A~2R+ke+>yF)|r=wauzS-=!n)c2xYD5Mw@QU)bL79Q;E5?`I(A!+tm zdk4_%VVKDC(>VP`rUUa|`6kL0_6?GY79 zS|zY;NsSLMepn?{Jyg@p_qA`bQSL%<$}ha5Acl7I!7BL)VpM|$JqFUmq{Qtr=!SRZ z1~<9FV6`yV_QQv*xGVU;@|a@$ssDj*yAVa=d(-3hDdF~tc{sD>Gis`{vZ1KfLyvIeFt@=-sP zdR^u{+pVCc1MX3|8$zgo73SciMQPmfZWSu2DFbFWD#C=NR*?*GZS z<{h%eji@h&nCna#4%30^yRB4+m;`Hamo$TR9YWu!TlDDSw9p(SMR^+= zSEe7TRCZpFno0FsTNqI&)PRutJK4|hUxCdu3oDqIg1?Lsa7%X(%A~+qr7>!t zYMkY&^$mz7 zf09dKf=83buGw~`{QENw_X)fwM}^r!tbr0x}j7+SD)mjy8Gm=kVf?mwbLNgF zJrR^KmG-gdnh=Gh2&SdHu(7;>R<>^;T=W zkAXPR65LM~|IVzHv$O?qS!#k5 zSO>}-tsb<1GW;+piRCmMz zi4C4=bpuU)hO%VedWWSa*&LY}^3{vARb^qvNBt3VO`5nJ!+sSlt^Nu}1XyoXI-l&X zxaw2WJOBe{?9({EJ4MG2wgThD+`E-jDEM+8xz*G%(enlK_2B?DdoWuMvu7;6wTRvG zuzTZOBGlQuC{KtL7Fom^61XUb%7E6q!T^W44cBFOzF0>mxY+-1FR8(EE)T38n#8ai z*}vi{JK+JqzrW=o&P)kBw?Qd@9?UYDZdB=*v>v@67d|Q)p(=~xFVQa2e{$$ z$SaR8(OrvgYM1^bNCkc^w$s_jDOlZL$SFfl_i{*^j!NND&Y!u+rcS>&aq(MYo$l~i zIyMX^kXnBFMG}P_A`iTZDi>e*`Gzlj{IAN8EpizgYXp4(p%Vl}DYl+0RkhD9teP#f zcT{LMciL;a_d37r#oCFPA3$^kJ4;!Bm3l-7a@^_QYm*{)hDTgL@Eio>R7VnjhK5q& zQ+Df{mD==m!PV6*ExYwBYsE9SbNa8C>@k+!m80N?KvNextt5{z+H z=4Y9;YGG=s!0&E>m?akOL>DV<2f2VBB%a5sQWgf~)FDIBfI#CcC4nrLN4m0{ja+DZ z`Sw~6BJa9%wPlM1VOHF_bsom~pM2~0W`-qQ-&4Z5Skf|+ox3c%&4DV`xn?b2k&hI% zBAAWEH|+l^hN>E7lvE`x3{Vfa zqMij<@8vtLI2^=ATdbZ~3qH)l+rfb~H?3HGmMgDc{rGq?-;R$SG24?@J>gDa9@a$z z+fuYWxmWl~>eF5fG?rX0*zetVF2X}Dz|0J&SOK8P&b~=cumdQ^i0b>MajC%O+bSSq z7Qu`ySmYhrhcb&&a~&|JjQY2|Y5D3>g8_t%9#TdrfGthpEkShHa8Zh4p<2J2U`n4P zy%=>V^uWr% zK$5OkWd7l*G7TwP!I@-PhZuVa`yioBkN#Y+oMdYM}Ldh=F1399Q`3rN0?f` zt>JItLQ9~4q0ktOsD4|x7i@m%cl~DxLM`t;$mY#=4<-ac#LCZqmW>YBd2SnMQp|Z;-~I~s3Z6dXfsu% z0`~NkSt`521jVq&Qv^;*Xbx}(@!dLDeEHYx^~`3|PZnyrxn{Qa_eahbalj|W08r?;*|NA;*vo5nr)!*_PhEn(^WTHJyXEvSW8Bd-g9vdCUZgD zl_T1`^y-W;D+bj+%BYNAh-L79R64e@wcjlW-UeFap*RtZPXFF8E;-r>`Qh{BBqQ(O zK>t(Z8pnL4pAA1qwA`?impljGyt$9gH=d)vMB@H(#U9bn)T1Vu$}G#1wvN?MmYg~I z#lsMO>P;Df-|_k-#Ym==|4Ngo!=&tiXjU+;`=b60vpo?|k7D-1pxHyn=bfOR7mO%v zuO7$79TeCY*1mF?5W*zBn*Jg&Mg9i}$T>kY;gWgF{Ly>7kFn4uVbnG9s9d@pS9QX5 z9xZpuFv+#)9MiT9YbY+L@7>bp9I`LDLuob)Xe+m7RXLCSq(x@^lH~iCm2SpXa8G46 zl`j-(>x@W%$_6oMHQ>JjEh6t7E5I(CciKIsORqm+Mwg9dqQ-EQhn zsNI?yyr1l65?}vN<1zled}U9qP*Wq07cPX)Ss&hmkU1?MsgOvMc{{N^axPU7qZ-O_ zYSV^4ezXlaFe|syYVq%Eg;=yC;!!#_%+Zp?yd;vGb2Tu4qlgC6E`7GvNiD!;6ldg8 z*t2aM>Z;v!@Hf3QneG?HEHhLQ^OP4(VL`?M3xF@C>u%BFFY~4OrHy;I@AKoA_cNqz zE3ZuZMu(Ea8wKqoKXvHC%X!H?3-@~_e;uDCsGLG)vr1{{W-Ej`#Js^vOC5j4329S9 zF)<*gk;(gfzqN!g;hsO@o1kh;B)-7=PZx%l^@~+^bd^3IW!#Dc6dI{X9~NKdjl>O! zSfA$Rv{y5R$-uKE@hPci8zTYWZ!{%eOrHC=az@w+xYnG&D~z(zlbx`lzc6)(=br0g zrc9<(EqnP67k)I4?ZA9)+OJNCg0BL93U_ZT@%fAw-Y;t)d-*#iVCviu=rXwI!SAu~ zv`k0E<$QP0ZDQ3lr&eJqMzIjVMgSN;gk7CnVrN~-o;z-fw^y1gY8rgCitBv zgUnGW2o%^H9rz>=H3uW~{+y`S+0xQttShBSN96Qr7se>uo$_Uu^>ReX#!G8;Ws zHQ2br4#Mu=b#zYtx|z$#>65ka$aBu8kMPq+$K;3W_e|u^P)R{PwjOy?e7O{k0h}G( z5?(v-mQ82$YdX+74j0HCmi-eyiGTK2{gnURLK|JujqwFJAxLmNJ_&2_dWM_vW4!=k z5$zxQMLe!2o%6s%eDKtl&QKT5^efR&OcrIYYkSo#_1Ngk&PSVVuUQ*Nvzy2EpT> z9hd4&`c3XDrRTgAjpGM{A22hv<0K>{e`kmwRa`k=DzAf+ae-dbqijfyc@;TeN_K^~ zkqv2(#4Zzlb+=*X^qQ=sK_c^tKXOJcJ;XgV{j3@qoyyt;-ZwjE19W&eb4A%Jd}pEd zwe=0umx)$!o{mZ*oquRS*_c=i4x84AJz~K9dY}_!;S@ud@n!6p%gqhY(>j-60X+2; z)zk8tE@o^D`=Iq=Q7>#xv^zFxZ}H#4>~Zt^c>CQNo_c-lL1<~>8tu0CS6F?fpX(0s z9&rt@{mJ7dE&J9+98fe3y*oERXdBg)s zPSh#a1hMD5@!#4B%_-UDZf8XiBXdI&=1itH7;&CmZ2F@=#fBT=qU=$oG%nE{DupP**0CUkCJ~}@OWtK0o52-x!&kzP+@gBR((J%bprxiv3oBEjMMdp?4eDBm`-$h^SZuwe z6db3^N_erLu&|Kb6#a9BSII^bDwhwD&Bd*S>M}wc6KKj#Xz;=#G6OivZ#%#*E@Hu%>q1UcOh7GJ#3otMqnzoM;bGLyA)&$kMH9gNFH0 zV=CD69>i@u3;aq7DK)UWG5iw?ED(;&`O<^o^I1(pyIFt zEo9tAb(CSskH7S1k>3Z^Qx)rr95Umdr?<{E>6c`%kGo;jZyW_j zJWR)DW5g(u>R~?C<}FV_UPJ+ZhDLoMq8wwG|T(8^xlEX{?m$U#PF$t>7jNx=8q?(~z1iHVJk z%~{;)y-3zKk$bN*&fs1DFULz=3>Y+e;q2~KRv-{ZO6|edrY1mZBUnuK-BJYwguZIY z@k#3-`;;iiFwGDO|ALO{yZY10v?6GRPK1yt+<_!+>!{7{IaWexfA;`^ zx*($F?g@x5dPTs&)6>Dh0m7VV3l0aU&TG}vM&`t?Z)R+Be28G(H$nCwW%{HnEbWWh zB(e&Tixa&?=sB!ZViZO2JJil(weOw$7bKke$p&^a!|o6=Fcv|UT!7c*b(UPNe)-9{9yqGqTgE9K4V&Kw+jlz~m#i!DEZWAsczj4bMA;uB(? zeSX~3hXUoP!NrdXr;oCj=^M3XOUAI`$w`~=!JRH%j{Lqy6xH0gSU<)uuf{#18(wj( zE_hnstoFx^J)@FE?Bv!eoO1&4!L9O<*3Cp%+S zO@T@$e z4Yg5S$vAEu<{-J!$v1S>6>Hlm<-v5)lB-y)!;c_P4nCHef`crmVwu^R^~0Moi7tn? zENeRstxLpWuTQmWjSfGg`V)%(qp%RbtqD>9~JYYwgzlWav ze_zndLhg9+O42%w#_x?dsEC+JDpN?4mxL-*2SFm{_CEI$LsZ$b$Di#H#bzb{ucoVj zYU=;u4^Rm~rIe7435dj0Bm^X-JCu?VknU!nl)z|^6r{UEYLp-d!azzGFghKKk{t1W z`15~ucFuOrdwXy9d%yR7?&scjZ+)q!sk1<4z|re?!>+pNITU7ua8+^8Fg1LP8EQND zhm5NBXjQt!gku7o(MEMeR+2@gw%($Ne=~pe}FujLeIJA)yRNEJ97ZO!09Ajz44-V5>- zb$r2bX?AQt$9X(j3=W*908}$Y1VnrqXw;;Ckz1t$OYsBWP7?xmwEzNP3ErkR>a z+_{~K8kX3nqxhH;yX_tv_7%yjd*o zUy0l+Zpd-cSx%#cl6C68q;;$(t5V@};^mc?@Z6mE+UQmBb4<^Av@bZ7=}>lIf3d%V%uU4i;#Jl_m36E2g&M_oTcC!M+=4l;61-_ z6mm>#CNxc~gK&1oF!y& z7E-*!&%%ia7Q0XG45?KFUV)Z%tn|a7ban9X;};>rk5Pm7>?v!cK|hNC(Fch@i3349 zpC6`HU8)=PwwNJNsu;B+d6%?W$OMxT$)>v8I*FemeoL7u=K_w4ojyBb2i60PRIg^g6T9a* z8S6Xfcpn7Xx;6#&TpVY6EI6{ubqELTlVJrUL7{U6UY{yZpH)d$`9L)K50wKul16r;MLI)dI^??7nvl{USs$GBHI_>w`YN{z=3=p5EUSYw&V zfm`HwKqtR;o}fue)(^D-?Sjqh0b1!RlG@Z9*93CMM^)g*_kG^QYLc+zUkT(VRdM*; z#FChe;0p^+Qsl7eHiD$|sNKAIx6y#f_WV7gtU=aNC>J1E;GsJgnq;Oh6^lFCNjN(T zJCs~00RPV?|0N5F+**~M0fEOJxIgP7Ro;u6EAQhuvu`du+%>WM0ah*$B7^lxqq~km z82kG4I}Yr)yvyGd!o7*mO?|PvI>~NY*Msl;PzQszPl?PN%x??UNVJ}4Y5#mW%lm;_ zXw~8VuiJFbo+dtfSih2CkZef5JNethd4~h+phxpA0ya2AinKZ{sjIVq=5RhSg4kCap5`U2o|}YA5?j&!1%r7 zj6L#q*VpC7R^^`UE~nKE?)PPgY74KU9@J;P4}JN5;x~cMpP{+AcV5nZ=^V04FOvcd zR2KLlmLcE0IkRs+3XXPwb(x-=i}pj&&&0{$tI;L}2F& zsLxgaGo6cLh?(;z!v|rH$n)NYbVzL+FV=T-_quSmr7#ukDL?q+HY>M!I}i_KpH z;rEi`bC1Y*Btv3jF3aI{zEc;I*{>@Z2p#Suuvh`uUP*@$0m$CN8-|lDun`Xv6B8WA zWhAx1ULJ;SKA1d|lM}awb-hl>NPFVv)ez(kwGts)&7!a?!pk-nO!eammU2|12^Cp$ zFElRKp|0Q$Eh%9Zv?$^x5qwQ2=cY;~GxY_}qK}=PeCxtX0>-AD7graLR_GLxCZ$B_ z*N74WA6HWg^7)*N#wzKB5Xk9L|BKU((LvAwE7*-f-f#5l5(81u#xx8@0jHC;l?0Mt zBV?+Ysg0%W7Faram)TA?JoCJgQ6wgf9o+Jq#4MufuJo@s6J`>pIKZA4Ki<7lqsHF% zE|Hjc#P4J$nb)8D=sg9++u~0dk90yKAVvsN9&SRJ5Z8euulofUAGa;G`+8Ezyn6Dt z@W}JNSz8gC6NUHO8qzK=LnWDUv6b5zy%CHHw^|tTjf|9aRe%>Rj@VW7Bu970@af#S za6aF{!cHi?C9~LTpavW&AdJePMt^vadFW4mbE^3VW^XNwGBK_-3RQF%Em z43aTID!E?q^Xd7$yj{B3+v8i=y(D~E{XTszH~N*+Tc0) zVMlddF+Y~%d(;c$o;ACS`^K_1+0Pndi)9Ib7GE$lnGRFq!UeUo<`k5qjBj}_!}+Nw zqPHwKHA08d^hHF|swbg$>P?GnyM@uUqogdVi-6_&W0i8(8RSdRtt%N}Y3b<^oU@=< z9aUR}=zIwzG3aE56u%MB%4l*Y4X?ZZR=*Ue$9lgP4pZsKB>Dm~lQpyS_ zSuOU3a*qpAuin}FGU!5_NvqoVSeby_(v4^7hq6J%LpgTV=i$Fu!;4(mDmXxiXF$85 z>uyavo4HnmAXgGWyV?sI+1eAcslorr$zuAqWOi83Dc+F{Rszbj-mamJ@`=W2y zupm!)VLLDruYr-qv6Bnj`$qp(1>0Z%Vba6EY=W9;W7uKfdJrVJWCX0N*7kH$V=tRNBBB5bxJey2 z|FBCxeE80lvE{z{J44T8+e5Vig?qgX%6VnAtKQJA)R5uk_~nW>gGjwHhwC?X`?3sM zM;d1Q&I)|D1L7b1a=OYh)^DQ?-D`%fGhY3VvfsdGpm7W{ook9NSciUw61;;;P+a#hS=Cjh35^yre}BP2X$55Ji?>wqFiHL--a_ zo}}D;PD4CZUHH0SH;E(lhODE$b>fSj8~Xl{lu9t{1@r0eoHB3#;TDbymb zbt3?fQC`*pc=Ym}2oxq4Uo~yN`|FN`^>`+e(eZqaD9_%OyaqkcfzktJW^>xl!u{iQ zk^N*<20ZASbsDSeS%dPKvAP-N}q2H9iF}K z?M>5Kv>~E+)>*njA1S~))YW7~G6HkPgk8t(<|H{CB&~piuZ(}nm+#HU9ewcj%+vv( znY2nC>X~Q1ai+3?xSTXsxiLxTVvh%!L43xnh(Y4ai?k(Eqmi5u$lAg1lz4y zb?4z>-3G8}H@&70lm|n?`%$hJx&!j;*FtEhzS0MIHJ({04%cp})_WhIz&`Hxf382K zxBhr8T{so%AMTnxVo!uRc4_>m%t;0mYw!LZE8SFcyf)|>68PE5BsC@VF2a4UxV7-v za?a}9S2JL5EXB-{!F~8M#hV`nyY$PUf1F$S^{lCq=^{Ba%50WNcp6KfV=4D0yy2J^ z$(VV zm1xo%S!)u-=`Z!aBEArweH;=A`z4%wqNNQBwFIJ_p5x0;^XI_Wgp{3s%!h`BhM7t! zbMd5iGBH_V-8T_4kN*N~#NH|&nB0?N!1B86|6UFX>a1)%!9*`c!Toh!_FSBD=`h`v z$Nr*MA8$Jq8#Md8lTu<03~QPb-IH=wXR4C+b>_NQ|5NC?eFxYs-4iS_AQ<$o=lKYI z* zeLxQa%o>A!B$83$Jj!$psB&Ml2a2>6P5gF*S#cpIPclga%Ms;;WNP3o!1HXA@?rryrn9$6Ju?mKg|4S(Xfb>M{yIo+w18PymSxDP zbVg$`kF10^iaQ1pN*P#x>&A28(eqKE!}%)ur(W)cCTIPe)@b9J+1n`~lW^(wE8I3G z_t(CHd4Te%YYn&C`auV*X(lWv-Zp{KbRgc=3jVf2h>et+IF&xbE}cPFg~r9B(EnT; z&zI!flV09np*WSAm4e@E)+u9rD3>D+{6H}-Q>~Z{+~U_|*>@UQ7W)b5WweOS zS)#5!DMr|?(LK@WbCoIEK?LOTKCr`g9Ua$Ag>0*1CJG~6Hrje`GipU2j}+z#3S(LDvUi<@1@lhu{0;R6O*i&*6>&~#V(4*pRF zNe0kFS=^bb0Fw;cZS#7y%a-0#!w@|EVrK$7v$^OK_WWS$I!h5pzA*&X{}1j44>nAj zToG4be@S#t%~1-D+kbl^KVDu2%n;D$2lV<=aIJrky=#2}s0-N3{(+$KbW1UR%Ud{x=zH-{3E;iy+<-gPrVrp$| z8H`_t76)SLQSuv#mfqKz?foeL>t797*1~g`tNUZl{#>`Qv2h2|vWL2l_YPHW%>G*k z3_Qy3*3-39FM1##KsI{4?<&@QBLM&sUnUdaKgaRL!AzEBKO7irRvK1!%1_1=@%n8Q ztq^BUt6l=CmRDeE%q;>}tOb#i=L35vbe;dE+}X;CvmwBnJC@yFnDdAZ%Z1K#_Tv^N zd3eT+HKKtu$NE-Mz?iQ{esvU-2^NW>Cx3?zO_pRYpj zl(5alDnCz+1^SK=w5?2v1x&sot*6(^Cp>L@JvOA z>yy~FrY{79yROZ8q4kWBm`HgKz0E9&S5EAcyua>ZU%yJ5eAN?7{(PkxoCnf5btTB>JryrHtw zGvdT)j=9GNZC$gCZAu94oP?SAz`TAmZDL*TNmEnPw^`h$kTLm5Y%|wmI-AN!!9!h;KKiRkcJ_1FiP!B#;5MXvWp%C# z_eiq)5*A%ME}QC$aa%CB-0DOqIW{(?3<+5EvH5phXCWLru+15vWcz*d%JcE^`puk|Ck;QP+FS3b9`uEti)(>QLqU%!T6i(WAU8?x1Hy# zf4yOajD!a#IEo$|3h0=#+gigVjr|qpfpbm&#OoS%6yUUa*oo2u5#!tUxQp=+v35>B zGu^_>Bk!CJ@Z-~Je+lCt9`an;Eu-l<^B~4 zP7y-jX`8hqr19d+!gp?lg>Ccu7#)J8de&U%zi=eh9slr`{WZG-h3HSizaT-$I8GD3 zqCvhA(KmT#4fi|<{vGz*U~Z;KXS&=!esw$wbh>|d&wV9oUq$=xnNN6vFwnuKjau1| zl=A_$MT`5;XtLF5Ug|$q<`w|5|Hs+TLIkK{w6E;_<7Z`-y|pWP<|^en-EF54lPA?v zemo6(xEeub9s=L3#2+mO)PGasew3hX5T$GwztpJP_Sa6e=8fX q%3=+Oc+%qcb7hxq%ZR%5Lc-^!W*UPxDL7UP02E|ZWh$gzz5O3V?9r_N diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png deleted file mode 100644 index fdb75ac0c6eb8bcf93eb3341f7de19e2b6123da9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 183400 zcmY(r1yq#Z7d4ClDhdclgG$3t(j6j*%+N4HgLFwZ5+b5>4_zWd%+M)~NP~2zbc4h& zH1C7{{@?e$vv9GHxp(e8_nve1-se07t0>9g;ZovaVPWCPzmZYH!om^3!otS6e;fFp z-0f>c;M)U-H`>lvSR`+Oe?hk-nkSX9u%2Vd%e>U^FxZ~;bfI4JWIC&^nk(TSWca}J zAm%a4%ZGPk=qmZJyW`m-euWjbM$u0bF0rUaoro~2?kXhKU{X>0=mGb>UQ2VQwAd}v zk3y=(pitwVkaxoork;ch6QqoUL=_*@VxP#D-ipDZw9Le8*7`kBW%q{8t|MwyM=viT z@Cp7v??{v2h8Nx2J11Q`JndYFpcZZ^2n!DnkBsCE9ix2u^!WVp49=YHA$@I!euRgI zK0f9NU2yPlaf#C|K#0FT_Gp-!oSe+hXLU=tLqXug%?xFELP4SQx~~Q! z7E~V4wt1Pbn8kg@KL(^#dwH~pL%=< zb>KUS7-DtHe{LA7{LF+fI^NW3WRX3b)P5shHQ}i-7cg}mM^T#vQhh2j?CgxDmrInbxO-b@aHS_fQJsjXeP~Q^iRwie z!?7_Bm-M!o$<0ErK&Jf{f$ZUL9lGB6MTDU!-CAn%9faPc)-(dkaBcPw_Fv=Ck~=kK z|E8ECz|E%9hsf=(*T{K*zfM6A?HJe{-r(e9cb#^Q4kc}TGF<-m3SePno^4b7&^m`a zOW;sZrl!zLiidHth5vL}t=)h8a^GR}F20#UWf+^R^Z}HyeQC+&z;h;DaR-Gjl>YM; zRwj9;Ay#IDFjtYZ6+GH;RfG_afFLp~>_w;wj*a0xsRmHlH4ABE%?zj8Xfq!bD1ciD z`H9>578X`XY9&|0;~!X9LUD(Spr!d#s+tNgzl6loM>yde{)sgPI40|FM^V(wJWs>H zTBAXxwq$DIp&Q1KQp?_M%>^v1w|>A!V_|_;O1|SFpr?sdca2xQB(T-UO|psZ-wpAu z=YIX*?(H1r!svYyHr1v3I9OPeQGtYE(9?(7ls|sUJ^_wa#7Rw$pO5d;5c0OUg+)@7 zbXtu;`<8%-se1ZZ(Ax{&rqc1UH@;0x0|^}W8G5$q0M8+Qct}>p`H^)A<8dqKEwF%Q zLZOWQvGO-ZP>##X%U-x2A7xr<>PYdEx3+gpdY^Z{54X7x8(_KX?=2By7E?e(ccj6`j7pGZ%#?GlQY(^=U6|PfBviW2Y z*-mIEAfIId;WjrjGJ4t9ErCHw($M+=#>D!7!%R87g_TKKQ2>5V6-?56#www23=3L6 zSn1hTW98ZCJvtxW1_AHHlDgwOv<>=jw%}IIR;66PzRf%|QC|86!DT<_&WN&YI}6bm zi7iTSeUy0fZmdk?W6hU$w0Rx4SMdWSTNA5Ztb`0&j+~IwIq?fZ6cu}oU5xyLhDs+E z;cUG*2bmd`ir7vpOC@4?kB1ol&cH&n2>QaBnr^AURjw#G#;3rl3uV)@{taCF-tNxM z`{ionhZKPM<>chhY{<)JS1;(kG3FK&J?iXhv z>H7BebOTi|)JTCckR>FF^Tv2sQVowg+S?~8N5|M4RPpfexM!gY4igo6h;|@|J4301 zWyUaC8$fEf7w~d*;PmoJg~c?3YsfAP)4{hI8ULrUq6C8D-`5AM{m*vqBWX7Nc;vVO z?k(cKtNjpdx%Q_e5&ClfwVd3SFJF>SXIEFgqJACYsw_{8BcObgh3%!dyAuoO!derb zTjA>F2rjsjF_RhlDW7@T=Eg{4enWl|jV^G3Z(d%Nb~x<8+^8~nE4aFXk`fPxzi*SD zrRDvOfj3n4*`-ze8pArqch!}H;jegEIYNe%9&m&pUuQn}H~csp6&CO*=)N#SzP+O( zoVUvB{rf>8OVi%h9Kw@fc%S|Il+4W(m8>3V^s@~|s~z`d<0i-~Slsw@h8xc-DC^%_HiH$HKyfhb`@G}hregERxbXPF2c3C}CYdxX ztakxyar46KiExCMR^Sqkv6;SmAma~jKk_z#v8&26KmU2a!^WSnxwn@~`C0u;3fBs7 z@0*w9J2Fk+L@6NpnbJADQazp48L~6U4SxM?v{U_~s9OnygsqIb1SieMng>B5 z4_(5#K|a8BS}M`hGke!V2g$vU9UvOSLL^*gUCEu;r?T3E-tpmjA(pa%@-jB zoZ&-Gv_%n>vT)CmDjfc5?9MH^&AD25P;zq0J2U37V`7d<%*4b9W1=GG3B_08RcBXOJURQ9HVFZ4L+K&++G7SH~g0c#>$ ze-UJo2H~Tutgis8H^fVw^Y-as&M(7-oo5rHU>nahh8~dLzgt^vXKQU|V4$O8pu>}& zXZ%E=;D4Y0;c}9$h?0_$2M4%w9);G+@y+}D`+)o8G$U^Tn;;$nK@Z{M5AqNiQ{7W9 z;q5DQ386z9>%EU?Q~wsDHDGZegjA*H*Mh%tEROToI4LR zcQ8amnAYUr9|VLU3k&lKQJnt<3$>jAPyzvk;^LFzO%ng-1c$_WCDXC(%I>Y z$Ez*+{WT4J(q{*-UO1;2QDU^D^v>l9PMnY{2!s|pslHZbR?}}Oi?u5PKXNnJKa>7` zE>@?a+fJ8&th)7@&LWAVc%1Cf?pso-Rsg+~XOU`ghq`u=$H2AUf2Jy)WBZ|Ue0W&STpl*d zn^rS-9~+iK%UW)XSDi9sSYh$XlrAb$l^Xzy8WUjI9KzMxkvMwK5O&nvhYE;|G%+sb+-l{ zS+d)I-IT>aNI^1vRU060(<<*$_BU9=VfnDz`8M|JGT#Qfy5uhj@pmV_HV)Q$T{RRV zWPN^a9d3-XeQB5aZ~0$!I-mmY?u@AG-lo6ts#yTu-+0w7k&uv(mW3k}8YoS>lt!vZ z5deZNZ%?A^3v>i>&2%e7=7!2RK%8^Z#@PR+a#P>>-pz+9du0XBL7_y6gnQU2Z-~sD z^xOU)uJk*SQd9XN3II~`l!C&DG_A+u4C=c}lA)%0m5F?$QzgsTuG>DuVF>9-zjJS~ zlwA6M1`bGWhqlAm%jmdDNOf+bL;vQPPP_SU2jt34xIJef1W0y;{BD@q2I;?rG>ahh z^~_=gnq}yA(M5x_f$>t8#y3a$sI;u)qVOa$B&fZ;ee?JFzvzNBqOh|F0O9T`Gf{DI zpPP7BN(cbCV+>~eahNAek|)?3o_)-i7&ELw%SYGol2-+r1&k$OL&(Jdq$Qt-s3O21iNLeAD{>?ANr_9XENhH&oo0}0beLSJA#k+e%TFnCkD$gIkNUwP9_I>`ps3>)r zZ+F9J!W6XtknvLU#PY!imq-QUfCmxfE5XXtkY1)TD%!mNTqQ4k6F7r*mfVV4oBZz} zzyHS;Ix6oLO+LumI}d&R?M(4ew#I)O;8$t;-o0V_!7F@{=#7ktiAnEcHsHOKa=8GV zL*p%d04-6Vq*eaAI4ZoOA*jtvJe6W2-P;`i93bwX86hGE7WZJ}KoGp?U+yFSTmHKu5RiQ7?|=Cj!C9#0+0ZEd z9>4x<^KkpKm*C&nn`Dmy7~T8n+}2~;+Aqs18|RPfOb48 zzW1Mv>S%NK-9HG6tWTN6TvEAB<3gPH{`;KHj<6Abp@y&ySswMc`e;y!^8vxY_f z2h2)#*&|TfGdPy;^mGZj5ShN$-v;?bdp5h4m$OS59UL5@nhqb@2hCQ%oJK4w!W7;a zHoVL|p@)@w0qpa?g=xu=0{KQ8IvWSGQuv}Z>f?f_y8D`rkf~ydOT4GryXq4zla^+i zscDp*I}f4gC~Fw^4~6YJ$1RsFl0t*z-_MFJmy4Go+3*BSc_Zd|TMip&1ezV`yE z@EX=@qQT!eNK|}5fBS~81EJr#g#B-ljVBw`rUGEa0INKwTji}p{8GBC^j7zvH;M(u z{a1qKsC+tmdKSCdbbTHci8d@2l0MFV6Ht~j6?F@iAvqzax2C41uEvPRj@gic5O!ht z(uXU6I|4rA8xh`5K4|IUOKH@{PAP;AzRxpY~n3UU`P$W2$AmCVQD z3WPQ|5lSrpgxtDi&HsT~G2lP&m1zzNK^=r^7Qa?9g15C!{GKG)Q7S07V-Q-23a~e z#Q?wgW72P+Z;Y_q0tjtPEAk}M`rW&CrlzeYFFxh|vk_K=x)Sf(#{Erl?a@x(?MVom zJI;tYF)BKm(7d69PWL)%a2>eJUSl^LNq0v@=Rc>%LV%co^EaS@v;WQIN@XatQp(by zN&g&${vN(G^FXmYE-c*pjZAm)gZi<7t+_4l?W>uv{8Nvy#Mt=C!jmtySOzU{t07ZS`LZd}vo?DQfXRtEnTy zsj3&NK6tg=g~~h$e=Ya=^~7jpqOTJ$>+GxlCUjM%e)_a8;R)aN%?MCKdV1r(gDgv! z|0<@fCIMXAW=}0KV9cwR|BXR|kIpZ@s&r~`jDA=eWs}c8I^Gukvx(|2N8v5ePhX1L z%%c1A!dkn@zl`p8J>VyPghL;FzfOlnvCwu~P5Y>3^kA{2Wt-%f@ZSZ9pd(WC^OGb7 zM6h-t_j)fQ7(#=xczk@k`n~lgL)|TyxdwK?%cTdam~()S@dyZ*KT-}4do`x2gB@>a zYrC_tAj!0eC?)<)Bm$c9`8`mPnozRp?14Gbvi&ee< ztB4hkZ=t>J_)7sg@b)%4p`xN9VAuWqwjjT^boUuwz~+F--NUl?5WCgtB4TMPNtK~7!$>+5tJ`GRA&s#N1~Eg)oj zd7X{qtA~b$PGxzCBr(B&K=kU>E9^yP;4C<>Z{MPuYVvDJ*8NpBZL64}YxMmuWcW~? z_XCfxO<4@lrUvZUSne6&1FG6UyxB${g53VJH)4n1ukNHlrd%g@|GYh@EH(^BjofCl z4!gOG+UAHy009Od!t(*`4nbTE)F0ATMeIdTVV3pv)uq4GhkPh&suqdmBR(dijoZ6h z8k~>sXA4}Hl`n$A|6jLqNPTS+IQ$VgGE&}aV8Ik&cC<&#FL{)W`8{~{roj9BsliD% zty;=0D3GGsCpR_Rwc(6sXKwES*fOf1to%&-Nz|lVqZ`1C(8|gvC~&^c&dwbXH0SGb zlGa|kNdh>@@vx+;$T3+4BJIQ9QsPz#CmcRLN>(ICC*Dsp2x|TsLnw%H<~~Q-hBNaF zfw(-IkAuc|p@S)@#!C6o5j{Fu%ah=#Vut9~Mjs9!Vn5t;t@mR5_=Cn@in%V?P*c+# z@JDTzJmZhZPUC~ij1)~-?uvaW`}+OYKmyX#Bs;%f-rmgLg!Mtkn((wrN-ErNY5)6@ z6RHN15On|F0w$s)@^rk;2+deO_lE8{1VM)FbgUyWU4W^Wl(J2pMIyf@l34lhib?Jqz3U}7lN(~^jXB) z`d4eWmQJ7y$vf$AL(Ja1vW%>f1%_X+9Kt_7H~94`^k2-`{wAe@7!qt{+{~lud;f<8 zK7E+zvFa$t3_BYFb(3iV+M0t1Wrco%l=_>SQ+bB0z1o7fj{>E0_M;4hsITls#+@YV41$50 z5}APq?K}(HXPqc)6Zd!v3Y#KwT0oI5GP|g!+vq5^6VyspLW7pKJrs-$x^v;D}$X z%3_tPedd7gF+~WA=crOZ-ho$UTDxNa@y2|SeCK_lekJ$bk8epm7KyUQLy)$aP`td4 z0#cuU*+0n>z)GHDQbS-vN2|<@`NhR)24(Qs~HP5B4TiwX-YWzt7A@FA|kwvsxaK=k{n za-SbYnS)nC5>%k(mr5+ z*RxCLQIr8rlqZW#{xQSLKhY^ci}_CoN6VH$6p{2$!$8cP)`uooxhsLZM`pU!8Qba@;J<^b%UpBJ6y$uu*8!6d1N{3)!v4yHm*!(af zmlfx_Q9o3&F73^79H=>xtvjg zuBdO8=mTy&p{f`hSr2_o2!z)UuQvAZ5*qjz|Hd`sc!=vHt{mH}1NKMIH$?8UeUU$Q zmX9Faq14G*+GTrQ*iOV$pfdO36B+r50S?=_!YdYv6;UBi4!J0~ZSIV@l65N}&;aAduE$@ScuL*_|jhaRW9NSg68i}p3Q zgmF+}SjQ3s(i8eHC=a*SM#Ed^$~rPTufL<(69@uVMS}rbYjShVU_$&8P(0pQ>-C8bzESq^JE5Rhs=n`0^Yqk(qiLegbPJy-c& z0UjP1aly>G+f3R>Y+BX(UHj5mrw)^Ecdgk(GgLFw1hd4-6RL6#!W*G43>!%7Ht%6! zp}PV6QSw!{fdO^?S!g)3J8tapTI)wjb$Bajgi=8P2eFWm>i>EHxVjBI-DiI$F9K=s z7b5gB^j&n=zMN6cAkm6^LL!L{4F}1IAyrRY5DPz=ea$YGj4ladFjA~}vJ?AMT#3Xl zMu$lB?8vb`uYq4ww64BBwYV7!SRV+rfcv^tJ|A|Gf5s6^ z3w+*`S&~vM0MHuFX-CQzZF$psXd{?r1W;2+~0{cfYCoo$FNq%{QRRoU5H- zDXGujAgPT$_y;peCaGH&;?TA&froYDvCOLdm;;;2vvsBS5_>b*3gxK zExSDOyb@DKl|?9gV;n+2T0Yw~GUmZlihS<_UaLr!L_*hXkUVrx9{5GyEKF@xSD9V% zoAn3h>Wz7Q*9Hx5f4FMeC{m*ikdopBarKIE010pb?KL_2G0ZBiaa`Hw=LxxOX?80Z z4;hqqtWC0pewcFB8bNg$&)GLBLtUJm;9P2TdZ2OK!Uh(wf5|>yH9C6!l6E3Pw>I^` zwb1(ovtvS;*3h}jjHPLT@-3OT9@ZooyVEl7jh*fDVo+DsXTRw$XAg@7nml5<%-r%} z9)oFJtUPit>#nL{K|}e0rntnzx3DN9;-|9v(_TbO!npda4{b`#6#_u&I&6Aw<3{t1 zUzYkLpO6@siingV9p=$x2{}krl$vTpSv@k-U5`YoDH>TaYvc#tK~A(=P>yU zPBSh=;B<+iEBPJqMegwscZ`InqO@Wz#?;Ig6Dxe0u4+Or4;ves!Qn-?WLgy5CWSO2 zX$|JuaHPQB0Al$if72_+kU3TgV70ZiwPVy~l@Y8YgoIonKW>fVVM1rCANr@I7N-RX zMKDM7v{|gMEo|3h#Z?UCRok)vnIK0uSq(jMeOquHm2xH z>#sVvhC)}Xe3zAO5Sg%n$`IrL?#^qGuAJtrlP-xmS2AIJn zpz)wga3!vsprFNN+WDL+j{R1m%ApoIA~q~bc7QzTZ=5HkH>cKaHVk@<=I1G7PjVSH~~TU!`gazK;k;9bvTzSgH=H=0S; zH_LAK^!IdC_d_zF2(s##_G-I6j{0K1FoV@2 z86t);#C_sC>3>DgGiAet9xwO(97vr~dTh@_y6Bm%uVbW;&y#<2a6w0iSVA>&b;awh zdhNbzI&f~Zn$B5q4%W~~@-*`FyfsK76_97SEN!bJ~Ds5V$WzNl2pU+Tc}20 z0Ek3gR|a2!C2ZtjA&*-&060;cJfp4MNXYzDiS;}*ejKUQlgRD3E70E@aE6;>Jj4j+ zHld^QysEG8tR8#R$=98~?dGL5-H^us#^)YO*ua#E^(p$I-63z6K;67Qkk!@I4qrpk zITk-Sjh5j>1rY_G937qB&_uhhDl7mU?JO!P(S^yHW2^V{^k6GVy2g>zfn{W@J)aW> z{xs4}i*L!<5AJ+#HR!z2WuHBN)#$xK!>_c+P(0v@I$w>f#atw>RegcCdSB#T zs|WWNp8Ww#`QsL2O`_+Xg}05$eLd!#@1p$s6<6F|N#$HjhQjUML`p~Z(*!+_ecK!M zc++Py6q+QG!|QYWKKQH$fS5wm{Mt7CP@XjW+UhWtSoIM>7C#vTxN3%{dcQBxT^+Jm z#(a!J$e2>)sMuP$_oV)ZTh^&5&-+t-IwFH}qVpeU=}E6QyERP1t;lCO6uDO>M# zAFhSpA_l7ebyYjg1I0K?**oAoGqXM~o{kckO-)TcN)8nh z_#1|xP6D}kG}i_xErX>R{uWd z_^)TNMRm*xiOLNJm@dr-)?iQDZ!z+wT=fiw!m=NiC(kJy&-Lr;pkvI6_0R1l>0M^& z43oi4r?!qgwnJ5-*;|rvzDv4b0oNTP8`ZL|cgvN_sO#Ugr{7X@6=!@C#Fs#5f}ZwF z&@=Spuhn2E6Me^U+4eq>DigeqL48A}n=flfrVjsC1wjP^r@iDg4L|Cjb?!T*4&zcO z+a78ZdRz4@;VL3SRKssSTp};V;QXHJJ$T_4ryaq^(L>J92=i~j8gg9EW?*&P@c_=4 z7$~$4a~(hpsacsZZG_t6&Y_wLM$5oR%q&;blnt4Zv0R48P^UK6uZP2X9*vjX1tX+{ z(Z?9A%RAKF)q4wz0U$-6o0w&3)j>NuxK^;Fa@x3+gr8@puwtfQO3F*Y%QSR3DfNDw zoVW0FsX$^$`+a+NX%hc+)7xiB!6wFXhAUQeD_!e~`6`P}0E9*V&pN|@_Q_3`&m?P6&CjrHui zQo5%Nnpp>;1XFuhgMdh9CSZWZ41wR`9va)5TxfLd*|zz@j{nd`T+fQRCL}@0VzJ9b zB#n_Sp+7dgQB5dI?WWwwLlMawA7=Yu$mTkV;-o^u5L<5Yj`E9_@Q^wOJ*|e6gJu)p z%Qapr={3oz9nez+p{4?u%WcUKKN z)r;n`$&IoxnPg2}f%$VxNXjmVVbJ#4D@F7Zr$y(ti%A_DzX!nveWy=P$^!E-BH%=U zJ4A!q+Xaq9QNF8QX$XxQZ3{Y$Wkaf=`r{uOEZ0?qck@|+25>sxFc9@ioWEmv0$c{* zFytbr^9?jK8H^6?8u=3;?PX+!K(;MUfr2^7#G8%^B~8bJTREy9qzU#oTa=M0gYpqG z7n8k{WZCI=il_(}!Qm(mf9LA`MmII5nvRo;u=;{4ppZs(p zHV!09>d0e#wio#+R3`Z&^ir}%uK+9N6XfOA=Kx$b^mKPi*u9Yl&;VHo;f}Kg&w`<5yQy zyx{Pkot%^xt)D=jm*`@6*uMJQTeIqso$uk$<7?P5r2PolZq%Rn&MS@%*lv437xRsbCpW_# zP2;pvFDZQ06nDgPPMaf?PAu*XNpP9H)yT-gWzd^mJ9U3_(gmV-sF8e0|4&kfb*6`7W>)j$ok@&(KO9dT8KvN+IW;D-=aR-PeF zb(GiY`0JixzgO}ci4km|OuK{RD!ItDp{|(5b7ZaXZ8N`1YhyE`aNBTgr@(x164Sz` zGwQY^uU)<34KFlPO1`Fa8G|}%bi-<5HsIckGQp3&#^iL$$m?_C!8N8>k&VY}=N3)) zTB7fIS~7ByOaCb2M@U3hto>OOO&%Q&2h_t&CREmKAi7lE72xL&l>X{k-&dS&U2$uy zEENnr&);0k*_uR@B?{~-Dl3z*6oSM=d|X^A9E>X?%wVY<{lV#a-UjkqrPE_{6?>2C z&VrX#Hsn2b9}%*41-@HG&$M9E4$#}x(I4(cPDIi!)>GZ}t6sEgs9HXFup?fywdYRY zO_va4K6h$#oF$I)z7V!t?kq7yeECtf2|XUCWI;+A59n=iVBTSg0nDl&hXi5>$X1%H zFCz;(??e(tpIi{Sy&~MCFI6*ij@wsPc@_)@blB}9Q;Ire*XZ#)f7waHYk<*KhokAamt0{huaRr9)8>cH3s&Q#Agen=Z^UqGc9VftAaO#P zFO`f9uxs70b$ZSg-Juzs}+ei6nMN*Mp-P0I)%0(zTV9+=C z<6EGdb3Eprl3XX1CL>X>dajbIt1Gvw$X}(WGriChUQ&fua{Q8nq=30>O~bVzo;3CW z1}M`m#DR-Dc~EZ{j2EIQo;~A=B1a0nq>Ip8=IhdSo7Txre`z#~chDC6&h%qkYHebu z>`?C2X!)MtO!Wnr>B2;k$H|An*>WGal!oxr4iEvuzuk85?w~Hh$N=a)U zZM4m6pHhRJ1f(_COkM_&H0|=j+3VfGuLETz0F->a{JibY+zs*G&WtJP+5jBg&!{M% z71_e(1_(yhT3to)biRwM%&;*_&~-awx~Ev(R!QBSuLaGmp5hmW2&!WSTLO+NINVAW zPQC@tTeOsq_~o!Gz&-GDnZI2nKU*drh$xUk)k0plWYS2?Sx-;Qo@QXv>v7G=U^vWZ zxnS?T1aLMFi8}zLVyMzKLx&AHr}Y`Oi>-Ij3$%_efpUtG4Gps%JG1li_6sWwG)L$i z^Mr1Is+WH!4+kn^ThK}a_0hti>FJ(|w4qIbX7H}4u!sodO%HvhmF4L4&5P<0j*Vwf z+z4G4tI|Qtx^Xp0Yw%O6Y5j}OI~&!JJqgOu4(Olo6YtgDM8PBNjk9y1$a$eU{d7Mr zvXnte0%7IQ-}A5Qqtee_UVORMZanDQ{4yN~Z8BdzJ%nA_dNx{#mOGsu)K>!Cwh&pF z1osR3q73iPvwCz3m0V^7VhgRUV2(m$)G#p$mrJ`6D4+5;otG?!==%&B?o`xLg4hey zgaykgHv36H!+Onq1r03~$3=hmn_1&8Y8zjtOJ?ldf0D$xA{wZ0{u>k)pRNDJ=lm%r z`mDZ0kH>Bll}XvDC1{mW;LDRw0cgk++;~4@48LumMq0s_`?Oize*RP8Zg;cc=bHoF zY0)ba3O;LtnoCG;61JtKrS>iFrg=kUY#2~|Ed&*In+{c`sv=AA87u?p7=OS1YFpaL2(GsUKAx%o zc>%#Y-7Tb0WgznpwPJq~9RTwF(u}ZAj2Sc2Q6%EeND=#IDq*PU$o*ml2!Mu#qG=|=)KhCm9A&@$Tr;2O5jVKdk+YFMb1*P`!9-)*4nGW=WJR(^9gvcOuO zyosMuR2e$XdwG`ObF5u<))*W3{?4Uu)BIlXulsJNL(^byrS)2<<@}G}r;NHIG>buR zHX9P=OX#aTxXDsr%P3a)dxV6ntrqoHh+~>ve?$IuXk09b@GG`wF}n4M53X6tO_~NA z%hz`MIs7n^6NSW4+n57sTTCcg&$hWDYQqxbxn(ep0dW)#Ex+?FG`>;L@$8T9Ih>bo z#*8|;b2CG(nNpL4R^K0aeAKVvhk#K>sU#EH=WDoSXG7IffaJw((93mrmB`MvNDYuBq#1nnY4txZ>r~m%x5z{!G$V=oPQcX{nRsGe#aG2bplCS55Hy4CEPy6|34pZ;<_iGfBamY~yX5 zG=BP++ew5g&-w~kukNXEd@K1wowv;2>{WUk=BoGZYdi5=2s44sIV$^@2r<8)!^VRw z-~KF2ocQ^>$h7v`pzV)I`}>Y2JTZG8=U;Z)+!={fZMwdygV`5E-}Vo^%tdYi9XHVM z5X(XyHXVu|1`S-VyBgEE!>?j6oCUK~=pE7oq;|@A47# z;}YUE%e|MSkcY$eX)|J(e=cJDQYsb}^YLaMrr5oCFKFsHcrsG5Y~39+G@X7geafLB zvFEXB1ey7ifT8t6^ScQQxt@%I^PZ3j%pHq+*S`m9h^H4HUUWNPu4^`V2?=N49k;lD z3<_$TuU(nLo1Ve=ywtB>8DgD%wa$?1w};d<^o-G`^OAjBQGKoYRgzjrf%#ggI*r9I zqWws&x+?xcCR*7)4jj8v({WjNZ*mk@2vy%XH3V`p7tIdTB(t^+3^<^C2tlO+AxJCY zm(WTI6b~o@78HKg<;4QM{Z&Q}^Xf#TG0_Xd>UkVCR)@h( z&mAwmB22fR9`ZhXN#?lu2Hg~vep>F{IP8V_mgP5%>2Ems1qcTFHSppOK|!(gyH}Bd zKHE*s>0|D^`+k5XLPtki5_?!dg%KOC4ocaeB1(SbTg)UPf~I+y<4PJtwvI@Z7J%c{(=<9Z5tu z=#yjB=Q=)jK}J{2Kord^AXf_gGFZ8@a8Abgcn~ui<2%ce)aM}PmlRZ+uUOru@2QJ< zN;v4f9V7OKT(TOJ%M11X5f|GXI%Dg-%;;8X^rjBKuDD6?%MvsnsJ_#K`tgoKtnXC3QjwJbdSJ*Yt=YR^NU)@ckELZ^UCN~yHPGu1M*_9*6FXm$_QdQo={hd?#DcNr`MX;A z^>unRKu%89_0G6-vF;ol<$5=%==9m+rFPAOx3|Dd(P`$V z?nz(5A4mUoazFOG(@+!2Y?w%W`Cuhz?KDRUvR-cNY;iI9&F}PV+-YA}&B^7IBcW%h zam7DjwLd)VJlH!J&p2e{czr)o3~1_et?XZOlBr10H&_uk-E=%z%xyaRu^y-!d7W`q zSUi6mbk>e%qquv9kr_AiIlMQum=r-(Q5~Eo37uLgp=>84v{hY;)IUV8ax|qX1RIN% z7pcAyp%d}xVYa|Nyv;4%Ru^0~Lu+pq31ft60_4Xn{|R=>cRd@G{TcT{zCMM0VH!e5 zvWPXDiR__1T+DV{$4gJVy#p=Xhp^LMq#+vKbn1!U9dkEwL9AtiOS&H$?===Mn6uU6 z^d;`UF`@=e|Eil8C|i{exnL}SC-2hrp~gFrSZjFXk-@fR$bq`G0-F8sEO|(n>MRn(Y7Cg zWyGFFj$WDj<=|$6j_t94N@6eGRoHo%furuioYcdf0+{L(Pk~gC{py1i*8H`njy-mc zJqAh#QCTdL8g>iPXTSWq>d(LRCS|O~7e{5i8K3=G?P6vz7iFQ$M)4}+F4rGhU2*qI zd}gmQGNqvDy~QwbJ8CYMIR-TKV}adenMk6HekEn|Vuh}Roa`OizR~4|b4)_x={Z=S z&G&gUdHtyC5-lC$p2P(P1vE3ecM+FGlg^DTbQP zrHr+GUKtpGn=V6qi3uG!6jPhvLB|a0qDi(QH35Ff+8)>Kh8N>$J*&K}5@iSNb&8Gi zHnxNIJcxJV444^a2|tD+xtc6S61^I-g(mHh=77BOY#m{yK4~8WT2+a%2SH$$qb3+=KGm$4OU zI!3fUkhEoE4i#X{RU=u~{)UElDwwVHl>#jSeEgN0vd04hNH%XMx*bJk;!;Ss4Rn)| zT6_d60VJtfETzFi?T`IZJ(W-wLCRi7b*j>S4-JY-rM})L_EvxXewWO6?H2%W;a)hwWKNI-me?mB ztHBS+;`Cr$W-Ac;+<6H*o!B-{9Yh)?B*opLFU(9y+!=lRF-Cc&KIN|F@dc!2BJ8UD zBbY8(QKr(pM?IWu>!D$OTPWI(Zg)!k3$2RH;;CCgXwaKWL4uXbQpv3v<#)DU>9X?Z zHpnx@%{18(DG1^qmq8OU~+?Z`;u1XJ%WQ}{j;?fk!gK2!gnoa86Y(nlS z^^d#iF~FnLw-w#}s#;KuIx#naxoCN}ZhlHx3p$$jd1;12Y0?KCxDut5`a4#_y`_b| z#Jtx?nS==jcs;xArlX4${57Ot#C_B-;w)qR_3mfqF8hBRo?jUdMc;taUJ#($7tOr~DlMxcyiP~f)Lk{+(jDP(J?6R0r#az65tkRA zX;M-0U9HZCduDx2ak^nqyL}(FP&iy;JID1uIxFYjE)?RR3Mm`j>+!%48~QNWw@JL? zNc#~RS2n|d-J5(>bwCV@6|v};DuzAv7` zz@JGsge!oj!VHWN{kJyxfEMt7e;2@R!ZxB3=ti4zSHGnBdQG9~UX}grE|!w2j-IRx z(9$XwQQ~*xHqeW{ZTmr>{x_eSp>@_^9!*5eL}R$VPAK=Ikk{YF%%$L3<-JHygTL95 ztdV-gdra<|$FWT(AwczM5&M{1W^q;D7_$?nh?u_s?Cn>W9Ul~QSg{gc%tv$9zx~Zs zNIAu3?aRq=`ccY!Up*!ZCfoMFuF)01mt0==uBB#b6PyK|(_u>1-EBE-!;*@M7wT?j z;bp{ZKzR)iS5QS9D2#D~*?vnBulh|pV}lcla-K4#3>^iPe@xhw;wHjUQvRn(1#}bk z%`03jb`p(9fXssSR-+=7xTVIQaR)_ff?lVy*lDb^{xhBoDg~7y|NI=+mk)+Zcnp1Vht z1gwF9<0z<4sYJ#vS$d1f(GVb!4mal(cH02TYS0^x9mqBg6`R%Oa5C`or-xjk>-V)h zu29tOz!TUW`L~g03@UhIq~k(%7${8NPs9GZq5(SR`+PB|mQlEWn> zj&B?JRIq_971+Z|h*b__&vk_FFdP_$r>1@6^s+kcf z)3-T3J_|gY(|FTB9}yltNz1|-V1;Emy>9E`aum#*-sxU0UD?~s=Yyi?o25fjJIs2p zP~co5a@FSit@nB%)VQSfcEFT!1kr$Gyvf2K(hk?KIZ^_ zvgx;Z#p%7GGP})#^#R!%+68o2n#-ou^s!HcG~x{)GrP&Bfxm5m3q06Q#Y+Pfq6Qu! zbCe-T$-f~Sg>gKSV}PL>TSLYKD;7N*5AEEqi=$GN8V}+CUpu}fl8Oq96$6S^3fb@; z(EcfuO~m^g-|>)BZTa0Yzvsg3I^hJU( zVtP(Q)Fhs{@tvkzKUB{*H z^7-pP)^Fc!c6OvoF&^yYF@C%@vqbpL0p)6zd+NnZZ*)iq7MAM#6V0e7Q5OkB8#MdB zSuE6Hj3@GkWav--D)>=N0{eJ&?H%|&j>^7S+$2m{R#+)k5U3ic-kRks417)UAT&q~ z#K=OTSUguHN0+N?B)g(klYktLrqAx(=@PL;ZoJ|~&Q`>l%qeHuXPE(7e7-Jc!9Hj2 zt{Sgl!ck|Z^C)*9jyr%91B7xZg~x;^31nHAO*AutfOIC+AiAFpY=6dgR0wf5 z<%q@BDk@W)ZZ`4ZCgB9o$1mkF8|C*a4;xZ|&ub<82ntkf`jP(B`mi_qn z=%)>>=FIR@_(;}wFq`^zZh#qDflo7A!93Q?kl0H;O zog>FT>b<~wG-%y>;%5sq2)#YjC0~D5Uvu`cEbB(c=9DBweXQuL?0QpiwLmz&C37)w zvh_|~BCmT3hwWbbbfco_E--&*9G)Q0j75h^Qn4iw6CYuChe%DnwcHWmKtrrv#bDp6 z5F+1p9e-86at{9;^$YIUKE<^ya7`XTxC*}wv{Vuq6aM!3bKY{6HQzZopK@BftQzay z{KKDB!-sgmz$E{4T#b0Gr!)6GbPgO!#eptVQ&+~u|2fFY48P~!txV5vZ(j*>hT7xz3;*j_GJ8X+FzH{ajUT@e`LfJL zRCbug@R70g9&C}}`mWZ#`QzucWftnsjZ8=J>G8Q+iPxp$ZQ^r3-uj+UJGaca+n&)q ziXA&{=?PPX;z=$9BsaJl+6-l`k4Xbi?Pr1TX^kpvr!1NGp~7Wr7DF+O_oe@FkF(DLUspOQGWK4d`?`NKwp{2FSlF?l*|-(dl8_r;B9!h z`fOmQAjVI1X^M_b%FBQvbIibt4=|>!AKQ=GE^r&SZ_M`N{~T>DjmY_=@Ur?o=3mFa zNf`KO^6_06s0-B{{f4UV5)|Q=5&3}u8ks_hd?}8LtF5kDb8e=a!)GpL@pG!$`MA_O zO_=m4X7}NSZU+yFnqw44D^jH1DCD@FezB0ljh0=UjoLyl!=Pt`N4B22+>aLi))7#r z&BmYZQaUO$t(Tag1etSz}3mggtLjNsi+dO#*>o8<1CW!f&?J<=u< zleM0@NPNVvRxwlUp@~}4wh>=1)xWou2p?1g$SgkxzcvNOEf5s8=_{`|05!de`OeeV z*Iqy!efiuI3x#Hx>>G%=k7H+LWn~jz(8aIk-;_DBfud+lOPy(>isgD?`ilSx!l+}C zx}m5zTj%MXgcQ##Tz-f1rOO{ccAG|+&0$_V&nb^uS#YQE;XQytfY{#&i+-j+;9~6= z;7l6+O%>q%CGHZIm>zF1$|6<%C;}-kWN5TIB{alFoRwV^w{O4e0y61pE@FL(EwgN6 zVF_$-{Y|kRcZ?9~nk(SR=4>tL^27gg}vi)20X}RT*vGv{Kd9mfhk>Fn2#hS_0oAhQ$SqU!7z6nQvO<7i;zH{dm zGa}=C!k!}VtjuAAP2TZT9+mD(DB0 zX?#+zJhyT*D-3pH+EirbeduQckgyr-b-8q}7<~hEzX`Nj96()*|Gg25Kakv zYUJBfL&tbEMLAVw22+uh zIvS2g!kuDrFNeFDl9fE+Lq?k9s4?0;xTeo3$)SFh+tFiQypCMvefWMTZj0x~AH~W| zj{%ZOXe6F;0!K7_L-lT_Woh~Lo=)kpQDcp_f!e^kj1PBw=@PHGzq_TUSUlipm6e&$ zqBcgs&^Wx4Mc-%}C<$>Pw(g@?S)j4ori}Jlks6(4wa0vUFx!&_$E6W26as>1gwbg3 z$^Ce}`n;^=` z-^mASQl)?-!E(1lk!OMQ6Jx+`#5-qvi*mv-t%w3x;d4=_HHi^*)r2~v@E^mA_F8JA zPc~HWjul(KEG!;ql-I| zr1ssWo#dr@k(|8bjsCp>^)W!O+U!e!;P5I?-#0(Ga~uQh7R1Kxb3TL=-(45i5u^gSs6CB5Dpm=QGweD_Y1?^1n$SkvF{=fAxGJ!BnI%2SYzWs{3A$uG19 zZmQY)QMphQokAAeJMS;mb;t`G#*~olDkCS;kDtTtx%@*gAXD>H9m~v#8r~Hr(;d;Q z&FJrGi7<^;hPw7F;;M!rrJ+i&L{j%PO>Lf8e0oWW1ZMRBDO-bs;QH??;?+-61MSM~ z7t2c%=Js#ty!jk;Zx7arXWOLsQa&eYC^Q|CIiDTw`>yTOx1}{Yg{-4**{r7V0Kun| z$1<_SO*@m!&%D3h+BF5AA#)Z!zDxeHQ>fysNaA|b`pxHoWIn1QKAkdJbJf+PPZ2Qr z&O?VfyPzRzkuocjEfcQzQ@gJd5#5Yh$=d?Bi9K=zgHa+j4BZg6?!1N3D@olGM zi;RTaOsR{Uk~*t=NS?5TqS_e3*g<=b@B2JDY4wDa7M{2VMw)s*8lj5{8;GO?pv3d- zB5{R)%GW_x%PAaonpS3@risPy?-Nk_E*$UrE@JVJT2d)IP;77-(=gj?^veL3qh1+> zx(g6M6C~NB##~vdyp4NWBM9_IFsTPD!Tm&%GNzAF(PdxeTm=KTtWv?#4Pj4M$qFFR z3TyOvhgtUd^YBq>A$@OriC;I1Z%g(V>YMikg>6}>*IRn$q-P+SG&K`0&9u8I=u~{p zI?(1LP?lHDLy3cJJ}Jke*z&!{EWJc~!6P|d)_g2FF24CvhKdGzghg)()0~bk*KD=> zC3RB;i%yv+ALW16rqw^#5c!$*iA2MFlfQb->NQ;nRSv-P;}KzHXZJ-HF5(UX)<(m+{@yN5a?VlLsI9xPR*I62y|d>I6G(4P0bE@l*;Y*> z1i;D7K1*6!<)-t|dw)-2tWJJ{ct@dD!y}p$&!p1Z)97cirI@}x(ssoq&MBEkFZUQz z%T-?(*<<*h=ey??op94|WHbtMb5DJ1HM*&SJ$2z%8cYWyHjETYzg_WSQ^ZH9w47{g zoD|zq6#M?(*Ez&1&T$7gi1hUhiTWQWJ~(=ECP2BDb2;s$>Bag};?{z-WxsW;UeBML zk}oY_Pr&6o9f;nu7^c-Jk@mfJ#Nk=?vi}fUZa?zz$^onSNQE(o_q~yqfyUE#Y?KugxC{ByQ9!NGKo?$3D z1E>Iq?9(>KHBFeV9l=a$gPjIM;j?-k&B2!MKOM zchEO5f@mk+a|UL#GOcKL6m8{%Q}P!8UrFac14$xwuQn#SeAP?m)vr%aeZPNmepcG9 z-}3lz!x65udH+5l5t$>S*)w45)km^Z0%tYP|m82W(QLU@?4e8gIpF_|E-Qt z)}v`%o9l)NP%xZcc4T=y6GM*yb@?S9aRk?m{}z|v8gca4b~FnQzTifPo9{IkV|yUh zoqdj;@VK+Go^vGd>Oo$(CF^LAkd-T%zn3s6p>j$Wu1$J}Eu%d{SSLv~-#9WzJH;ax5G4lHO3n)Xe)Be zrq&e*vol(JuBahRX?RkGvZ0ag zxU>;)%EwAX*{E>1nKnTFz`-tvl~dQYy4&1nBw_GHuKKOt5CZ5YJM+pd_Ev}E$s5e7 z-&m%uh?M1YaQoY(S=aiNxAUJ)KZ^BWHg^!a$T~eq#jGFzml)RirjZq>0dx!ex0*_gmLDyTcv|e&cXypeulb)mPc-v%^E6 zBU@Q{Jxhkr+w!%MIYG~6W93;x7#Rii%||wKVZVsH-Y4V{y-3~w;LRC2WV19eh{`|RJb6}F+c_76=2PffM-^OObjrH_# z53Ozgi8VAf_}Wo#djKg&28g)X{YbN&OG#^D{(UWbc`A|@a2j|bKz8!5fc9niZBK7E ziAd#v4-V1HjH{ScAjQ93Tua9r7`0Nit$hgF=s7Xw!$uNY?`ckvhcBOWR4ihqE5Oek zK@^^M`a6e`VrH?D2N}};F(;H72peBZK!1i)xNZlW7cH|pSkeL2Gc<})+<*#VHEdJB z%*N1mv_dWsQNs%}-fIrp$h%3S#;04g`2w5>b+rVieCY^_tH;4Lsw{PUzfTvsV=`_v zb@M`y-XIPG+F%UbR&f2t5&5KoS`kzb6OB^*i%(8pn}duejvn+c2Sq+6ZlvClV#4dn zu4Mbfvl5aE2-Q}`ok;MEy~wv0~y`kVDqE6aFIvO1{Mut zB_>o3qp;13oND)dY)|2XE5;86rR%2TfBv6DtqxAx=KoR=H4geErMyyzOpSRxM7~`Jj$21OpO9t8yni* z-aMXr2TSMSqGok%A1fOZv$pQv=zZ5U$b?!*izb1Bu+#0nr>%3YUhkc%X(){%Py$LO zoQ@p1{5e*YSR54cBUKmR zlIk<5^y`77E2i+seYO4kBbe3u zuZM$&nK>7Od^`v3+=1VE;Kt9p52FY}AJY>ioxLrdeOAarClscx@z+RgWQ=ZqHSrJ; zK>aQYxR?8PfjuY3@WjUR9RBiEUCepUzz{OY|LyoWK0tBBj8|mP47Ix{g&A3e3}#=C z4;}#opO1bC&!!_8!`@kW_WWRy-@*R*LaFV5on)VO;O4xsU1Jq?hr2=KVSXWmA$8+S zaTOT#GCnfF?LNSc8lZ0gvoiHK+VVW>HxKHU3n@T%!VqY@9o?TklD{fvdV4zIwmA`{ zXGOlk*WoGn!X^5z-Ln^_XIRdD=D!W?xKAELD0UP#DW3xmo)D3*F;3)BBXP>+R*u2Dg4|p2uS6)QH5um z?X656vkcYotKLl$q9mP;n7{VumdQPCmmia>$lGc-8O`(Op++yv;?}D`&%986G{s;i zq5M{=dKs@ji6b8)qa8cbD=wFUANSz^wSrhPm!ns;?|D-Ymi6It?E@6$s-gLk6%;X2 z@*C#aDYOuEgG|~TD0N2Du4m0H{D0r>H)eCHMRyR|Ql={lN|2owV@K zyTf>b9KVE^1<*fmOZh2w!)+^N!>mr_&-nOw!H_2)iswBhKc=f0*%{-+!P#MuP9v3e zvi!`6`Q3m@{J4!ChVsslCX!%$5a-oEMojKzrUl?ja+&No`U#p*4QZWGbLGHH@a6PN#DSp|NJh$oZgnhL1 zzghr4b+%UQ|Dtxv5^&CR)6A2VvY&kjfN$C~J0yWSA%=vGu0o27oxm@YvV?^M1@(Rq zHjC}px$jODcN*UJEDeWCj5=coefcx)&^6auTKH1SK&e+oZRNXNsM`_$XX_^oQNh4# zVn^0H`7A_SX(VBT_yA0>ntH1h7|#8kvPWuG@574$S{KhzOV&UEz-AYQ!MSgC+m!)} zK%CYWu+8On=I}8k#)7wV1}-0s5}4pV^R)NdvUV!9;Kr~2y)U1bRd*UtdEjEf-c_(N zMML6nn{L1hnL>URHC*N);X%6c_m8N9@HIoPY9WSmLs*7hmr{Is!r@mO8>vhwK;^}2 z16PnEllCB{`Vk^r6Jv%mF+43OVt^C2@!D5gQzexod99?!5WS0c@8(#z+&P(3v}$N# zzjnViS$(UGwa3vV*kOhcqHBn6ws-SwEqjdPl_7AGQas^I8BzZg9xTQ*ld+{zbFC1( ze@blo*Xxhk_%L(J(R5W;CctAM3QAh~79;yP__y-I82r&P@P=!!Ip%_U!AH2ac0bvo zeAA(=c(~tm`9q(y@SfLoJ%Bcg>M4}cp__CKVfuCbrll2f+r+x%30j*+v5 zBO=+3T|}C(Xl~dX3}ebxTa+%rtXq{U?t<58rSJ3RNfV2?Mlv4$(45SqT?MA)H~e`uGt1cHAmfUA4#p4?GeW^u zZ(KZz9mWB%^TYuDO^I!C!SCeFzLyL(Vp&fxybdMESjHm4mail93IW74w{!5{O}v19 za9?Gd`-FzqIDI_H&DAsYmaxi#IgzMF?g`TY!s;OY{kp#|}h0qMa+@N;cVqXWqQ1b;Bc#u?uZ7K%7h z1@jU#7|yXvTln+m`y&TXc#*;9+Iu!!p}v+v{z&=GB*LkI3D2fb+C5!~P)OrVqfS4p zW;n8pl-im8VNGgh6n!PrtOXq_xrJy@ksJAte;4VYP>DgAdw@A=t?SFAGMFoFUC-uv z%+-_a<#L}^APIYE3pcd+CW-g4sf9a#Sxs4KB&z$j2oKQK zEN)Sb=;3R>;$2Mr)oU>Np`Gx5Z&5qixe?|UCc@2amK3J)aXM#g3h%`09$@6x_yW*% z>ZMH^lbBx5OPF9@4J*dG5O;1g|pU-;Wy@(HZyxFQH zEOBshVkbi1UGcO?RMH~xmFMKCx4$ZERn8!A%+$T_t+3KnwCBGiyq{n)9J#-aY3S9z zXungZqTOt(;tEvM{?75|GI38Rgr|1kMAqj&?7l)r4I*2XVew5#PgX!WGQ_@x#v zX+by-OLbpcXM4{EK)e4>-@a|8B0`sKbj7o@?ybCK|n~gvoK{a1PlHSHW0%k1H`TF-zc^B%U_q^KFR$JCR$+ z>k4NZ;_m_R6q03KYGNfA1iF=iYo$oh;d)7*8G>?rWTtt056!(uOs{@vQvA>D|Df0n zwm?G$o*o<=Y%@}}xT!r2kp2rjW9Q+4loh^xo$(@c!PZIGh?z%-(cQ=$8(jY-~s93(ZyNkfVPwk>k1_d$i&o?nWrb4kd9DVO%Wqzb@aYP zBugC?XPiXu@*l510MR6oRLdjd{3mB3F_)ba3J8k^|f zajI3f2G@zILWymo%4B%r8t*aZG22}OB}RkOC+(^tdf=<{pj-oLHT$v`5rCZ96R*nW zc!~L~g727P9n)nHg1%veY9gbTVToClz_J1VWi*{H*N`3gsQl+@ujcz|WsczLQs3^L%W++?fp66+pErTkO}TZjbQDZqIMivXK1 zl&6KhTcj>QOwh>bzgUA=4a`bm?%-8pfJFP=o_~%DlMaj_)49M6$|`;I^>la*y3c}R zj9hS|?fn{5{Q{Azd>XGXXlC#vFZML2u2oaUx6_1SfNrXxnby-op4O!w-?#I-GXq;3 zOplNS+$(z^1wELKS=)Y(oxyJ-23>=M%FT_1bmEjH91aPD%svhNGI$BX9rt#AL5#|bM zrqe4b;EDZWtMaxpzc(D5FPA;SwnDiY$3PXBWo^z>$Y>1cWpyk!e8iwR5wjg8EU~n& z@0`KxM0w$I9=&GS9YDC>c8#%X1#yv~1OVggOGwFVh6UjYL^I#!L@r5%^4`{v^bz2- zITv1<2sz$w70w-M^z+Ld=dD9}K0(|YF?U_a-3r^(6)M389p3?A!h&J%yAyy6`Zqph z5fWv>-Ld+KvBjD4R3Ndyk&xfTpMm;12?w&o335wJNQLBdbO+Gb{kb(R`s>ut z+)M%jvN|lxKh(At%aKF{$=F=7n?mG!e%$(SDYeJ#mX_uLMa}3diAE&s4{@7jQRM%Rjl5{IMwmvNL>Z`#|1$rP72PC z2?*F?{a-w2zZ;8OBnV=H!m{x}g3j_*t)r$^wHpIt1FMrc3-Rz2%?wYEO@kdQs7p)j zV$Qp0G8&XuG65n8L9+&HW0~gLELbocv{l&e-v;?jj8M4@k-*HhCbKYr{m)n~LL1*M zqG8a9Zt6Oho}-+R9xA7#s3?_-JLMI3-dxk4X}eJ(&80CDnN1Z{Hq3nNi}2kdq4c6a zgYipAEb*5T;MK;eG3Oe%H7dq{&cY#MExSuMiKZIy>@^GVMYAt^PQWMxS}AIC=;9G?cs%x@eYtcQ$4vvD0iw6!54Sc4kD(BAo z`;mQWs3NWJGO|$y%fDe^xbZCj$S7K<@f-uB<^R>15KE)2hOz|yeR@M!1&#@lv$e0$FL z^tn*j3{b*yAK-FM--*bi@s{~>NxD+uZ459`>BdhqpSg#<5)eW90xQWe_JZJ%*eR`k zJG!Yyvd>aPT(&~n?O@wK;p3WoW{U$)oR|y=2e_$6SXzu4= zV(_*fB8YX~gMsj@#7F4$lRHDdK)V+<3A&gXM+If_Aq8bmC((+~6}HC~NV^;G#oh4k z@i7gZ<1a#uRr2`*1U)b9{$9Nn!&kA979ZlD?qbT9`JS2tY zLUZ^0_`cO@l9Q1Ygx7^L5`gVd1_f-LoUkBKWq?@^h|3fd4DhiPNi7-fDH(z=Cx88A^J&rU`|MKc5$CrJt5;T>T z;QSXI?Z#t|lt2=+X+F>=H@AbGlakjT2W(jEjGym^i&UmVKYlD_B(6POFtf6vjEMjY zS1Yr%gv5oOAygK@Os4AR0A6P9*VD-gNijHIixE;zDZeiTzm~0fT7iUW*XR35&`9Yg z2x$1b5s{A285IZ=21$E04c53^UKV77fTZ-Jo&%yE8QqxV5x7=JJ>WBmw&V zu1b2XVSr*mMAhYQUVs&f%Vq$&Ua_xcpi&X4 z{Oj`M+#QSag;9;}gP&FaEhF zpXEiFrYzfs3+ieUz-cX0F1-&3?>zti?6Lwk~Fxso^>=dYMfUumnJM8qR30 z1+O31(V_->(3A^b1MjCc`ic4_fg;z-1km2Eqg7B>&NE_?3|&@Rp06{rlIUkDW%-3CtI+5pq>^({$*- zg3Mml4&3$@Af)~Zg9wpcNjn9GQG`L>DH#H_s6}e&(2beEK4I6nV!@sYx6df;GSLAM z%fb=UVUe&y({H4dkTwKtor?HX#;%A@yJErSRl%W%K<&`(VaswAqZSKhHXuO1#LWr5 zDqZ_M8vW3ISq3sf`m5?DzK3L@Iz3}_t)!{Z${ZzErIf*+|4a+iQDqxlw7CVKW(KZm zu5&C9=!>GpEk+a|Uf>?C3Vy?T@4YC2rz_|oywNcZyEHF1tC0jFe`K6SYh0>sxAR?9 zQ?fR32ZYPi@FabNsNAYGKaohIY;_yq6JtqU!yt1CP^w_g@{Hi(Y`@u;s@rSvo`L z1aQ8;30R$25g+5#tKG4bl4kOn>YK!In^vx8QCXOuCBZLFX|;cNgc$e4Gux(Y7+S2U z6sw@K69QONqo!RT0WrwZpsbtU0WeYY<`6oyF;b61zrkN!z{=h%ybL0F0mHL2zX@Uv zd@Ny7EKNi#$=#nx$FY)C#itZ}4la_i6D%L>D%~B_c?v2ll&h=X*F=CZEV#iO?Ce+( z5{bmJyRV9!eBE1%e%T4ThZ%8XgQvC$&ee(ms)mZm+!tj~x?vbZ8)DCi);`>e|LrMu z!5F5db1_^pT9pJ*1+F3pI4+}uB~kP;#+_|f(M$p;u^-7Rm;)~ z6kdm@9&pk#Fo=|rWM%Ayw!@k;)OgDU+_;6r2;9qz!rnorpA>fOqkTw7NQ19bN6V+( zjsX8{DhcZOc)uqd?H58e{RyISir#s068Gf7Fqc?y+g$$?Pa~w&1{)^@rhH{$Oo%e3 z2XZauIf;-1zrm9Yy?he%9r2Pou4f!Iu*6(u`8JlvKN8PDnGH1TD>$Q%l&vE^8PE-g z?7~grS_E37CV%%HTY;zW2JgU`?xt+_eBg9W`in%Uhdaa2MvNP?>Z`tZKuxtV;=&i=!+@2kwGYrg_XaJ@q(3V8>VDR%3;wVKO>Km%WJk4^Hx zlBQ_)+gQM5HAxZA?!f`e^{G#;N?CR&IxbVIivp6M`)=Z;i6EJX|80#&UgWtpG>7yq z8&7V`-AAL(F6{f?7|pgKx%`y_pxMn!I08g5^%}>HrVNF2hm(HE*2XR;9AZom29wms za!rfsF*zUSfhgQJz4=4=fox2;4?aLh@T9-9#FN^}pH2M52s6ymzMF2F`23KfIa?!i zW07yc>|oy)9GX$Zd3O|{i>PO5`0?%ov}H1NeAn3sK{TQ(^R`d?a8@92VM5H&EW>0} z`8_j{-r;W3#>MD_W@(cr=5HS~R{fm5+NNgDP%(4#JS;|Rav=JKf-*~D(4gnW|6McX zCMa^UP?=Dn)P^OO;l00APEqGWY@wK3Nq-$gOCyvAx$BR$sfC5*Fb-4Kj$PQt?*n!0 zV`BM3a6<39j)(7|TpRdd;g*ZIP}`$6->dreV=53mOQmh+`wpWAUYZ)Q86U~JqgUAc z+{tBUsHM-60S%qCCNxq!l|DkiwAx)abAB$dxKREp_w`Xb=E}`0p(6Yj+;z3?4a;P= zsGn?JVuIpi)&Y+AJvoj@>jHyHV7>Pd;OWIk%{kgZ7>MF^#_`R)g*qa`Z5?Exro`x5 z=wRo9^&$b}4Iwk4K4EnX;XelrbP-DNp=ic1DrJ+}W!TAkRY*P&aibA$;TZb#3?rTmN)P}jt=z<#=Y6zsnztvDoOlI! zd1Wxl32E7$e6j_YkA+2n2sBR`n=wr@(BYJ8<=~=sO^AytSFsno`!3%I7>xtJ9|Nd^ z(;vcl3J?{^&~ek=omIY9v4Dn8?v$?kb=*_M^>=i1@K_VDb8|~zB6P2vSaCP~<&`4u zwA0F*lf<$+S3wYRs7L#=RzgTVW1uPEbc^(4uvN(H6B3RDTNPrcG^deS9rN_vz^vFbp?#q5ZCsqzq;d`zm?+ew)I-M% zkX#0`vRk-+b!I1;(k!;S_Rnu;08UZH{Q4??Nm?iD)bHd+*&lL;Pt3o#xF&h{ZmvZ( zgchax)x_&P51UlszqZmqMgvEIo)^p$$I4~3GZ*2_mDp5qTK*6Aw~^qXA*U0nmYdB7 z?A)Hu^P{70&b6$Es}Mgin~?(8;CD%gijg@}{h}f!aI9i7o>;|hZDVES`HKE%;e8=i z)%1@;JuG8CL(WIaul4S_H-rvNr6QZt$)KzLe62h4;D!>XRe3I74{gu|ckpT1}iWOsG@F z?)wceQF7Lq#?{#J8p5so17}me*?q5}n$=fjMyg=JSA=W?^f0PVecw^-5r{OiZ8+r( zW>#F^fQ+meRzf%7@-)+*Cz-A&B*y~I@o7En zL+Chd2%Gs{iX{7 z>?+YY4jOAy3XG($N|yQ0j}-F?9bdo{Gk8?j0im;MJ+kTyGG} zhCaqNlOiPf^!otJ;y;S+<;XQYV4vuL^%C>eY>&38Lyq66PDN{=k3Ndaj8T+F_N^g{ zAmBzk6EZUa=7Hh$*zw34RtDV8NgDR%JQ-0bApVX)uCZgz1~hU_v1AGR>-bid0^0c^ zhKVdj^HeyotG_=Kh}k;xvm6>?q4S`891+eU2LT{(T=Q*WGEXd`B8v8duM^47{+B?6 z&xZjl6Zv|WQ_f7*DqnI#dPAlH7&Pmm4k%C{p!h>40PN?JpJhy#ykUbZiVOe&q^eTI znR{m6L~|xRM2mra5xe5(I%*&uoK@HdP}(~=jkCX0V`gC~uFXZxS1Uf-8k@|85IsRr z5HM`*JgabPG-Gm04g_E;VAb*prLdlTzJ+~lsELhDRdaJPS#5|~z59AUok^uN5c$jZ zlT_>R!&T8I;(LOk)bD1Apr`myJDa3%2;;+z5+5S-hMu@$#c84;@pEu3&z-Wep%M6R z<{s}IX0{+v@=#4s4>N`;z$%VUtkbHxtyqT;=E)XVn`mr;92&qV@?f7z6Ewr=cMW0} z6fA}B)yhJxD)*fdZBfTq53CL(OM%x74J2v1vc-~8 zTEyxFzsR=V00f*6k~CPRz^x*{NUCG4O=g6gFi>taRkE|#oG7>K(%8GZ%epgIVUyCf zb!(fW1<>jP_CqBObrvHN$Z#-|B7o`_muF`+e+&adsI-YRQ);VNfeN*boykHB@=@AU zd@C=wF_Q&YWt1Tp&(5~?9X(WCPB@=5eEKJzp!-ee&5d`G`3FKigaReNlGG(Y6uDKR z^$L=pjy^^oW<1(=Q&Ozc^4e{+=W1>1iU&}fm~r?#_O&txKEBJ3S4Tt}ePk*xf*orM zis_1~vboW8-_#o3)vC}-7y@MN0G%%$>c-2mbR{|=4Mdomr153R#V}%nVw@K7Z`ZjT zZG4bKE^fApuQ_U|=;RDg7fby*L(7*2#v;d=@9}M+!#D{%#Vsd9q0YLy5}!R2YovR_ zN&IAPGizKc>YQd__ds1`@i_`3Fw1681YP;PMyHv}3Y2N;PyC7q_N%@brKOX*he2!| zj^zqi5vR~Bu->S?zk7y-D6>E31Fd`+7|RiZe*gXrWWn;4D3z^{H!D?nN$c`D;|-qy%iFhvj5Dqe_cyaUlo}QU zVd@s_U!S&Yqqy^-1EN-)jbB8$=6m$j_W4>>3l?hreSntEg4Pw2IGDNJhcekW$+$)x z(U-TJ{Wmg$I3m?9Mg%k)`qMIAmddE zDOhX@I5pZi-_YEhH{=`rSelCSxf+gDC86pJ9oxzc2X(Xz51!V$d;PB#;J||k{+$5h z{Kk(Yx`Y`xgrZ(trmnl^1VWdJ)H;t0!E;qGQug$xN5+b!wQEq=%(vK3)^MW1R;&C} zG>vvlS0o1cY1j$UdXvEU>OYHtP&K_WCo+-J6Z}b=lzn{kMgbUCCvXtvIGy-3&B`!5*Y^YjCgCw zo^BfMw(2JkZQqe{f#{2DmYpb%=G!ASOU_hV6=S(MO9CAR=9gtPxIDGYjn1tu&$JRT zo@w1?s2u-&+WKI&lRGfOu5zaXn93$dcC@#bTLA*5^%+!ny12Ob=`Chg&|Ab|2x(NQ z*_1L{&S(b6KPT^r`WFDTMJr_DKu zoMzgF=H5Z0!H*(X!+ap%sbG~k>D97UYVGgOSEFE(X)J0MFFAM`8fGmXJkHd&N$NwT zZ*(BUu()o(9CVac`1Kr$kMIXRUc8kS{t)8;$gw*UiEG!;;S+uUiK_m}AW#;T#qU07hb>f{1P&ufmJNM6;~AQN zjv+}Vj@IAHU6OCAx{_gRzO7z@(SL#LVD^ZZuSQ6P&CV3y%WrnuS-&0IxAcX|2WUZkLOePZ~bRx*5{rj-NBs<`CrYmDKv z!!)Cal;*-HRaIP;iPX4a*S z$dnGYrwXg^5TYqs_{lJ>nq+UT-BsnSA$ey;4AL>1peQ4iHNFnN{<6nY}MLz z9Z=^Ihrp7BjzrO6*m-2uRsEX~#*4ix!6E!ymq|MHi{7!&&PrY&?rFeaoy@Zv!jkMk z97bDIiY{IP>e`yC9E%D&HA7}BUEqnEBKg4Pan7%$ffz#q! zf3%TYvB?7a`5iSI0~pq&UDDqzM~?mhSrTt1X*8@^-?fdo6qx7=6=$+4pmh@N2#|7nx4eH@0ULGX{|mft=GoY zLAibOh#Gjx2S6pDxMQAz;P7ousYJr)OuS4J&m@C1Mao zdw{hMCTQWi!W?@`4WDia32~zn0EV|!-xh0}KAF^C2f(aMSm~J))Y|jh>Sa;I_o#E# zXxmx;2a-Pxfyl?v`Fr-WDN91`QfcwaDj#*F7zPrvpUXba3|OtBv`4aL>3XmE@fR`L zw$iuSRW0k!Dj2$&3(&yVZ?`APanPE7)WDjetL%`vuC+aaW0A#*L{Nu5r6*If+jO^$ zFwkYvDGv&=={G%-OM``mZYYH>I}j$?@28xv>qfwDyY7}#NM474{B3cWm|vh9ndLKs8m zVcaBjzu%g|crvS!*A{53m97*o!luo?Brm9rkzdMHEjAfyI=syNW13?6rUbJS;SU7} z$Y~8uDMJx9jj*?r0>l!Vvt_t|roJJE`R&T0IkB+;&OStt<>^w&L-xks$IH^?^2fzv z0jHN8#lF>_Y1^?u@gQNgs5=*yW)?)m)07@-m;#Ln*Xesde{ZwZA)-70motFB-s`del@oauH^sYa^UMH+7LJb_d= zsnRy2mB|$5r@qza9j~KOoAWj^_wbG9`LrD%he4YT+n%A82i4!<@_#L~4-Beyc)pvt zw~IkVm<*F?&Q@~jWiahjG7I!EZ7mRg$8D^IIO(~v;4$ta>i_&dn!W>^>i7Ns*ds+E zLRR+Pn-Iyd$FcX!-h1y4Le{Yfna3X4Bq5HGz4zWBgz$g*{;vP~>bi0X)%&@hd%Rw+ z`@SPi9TR`wJtl&_=VwN0(+wORbj;&bl17@6M(+5OOzb%ep-Zj$7`-5p<<1)BU}vXK zmcQwrJ^_cY8oYT`-A?o(a!ZK3f6hUGWVCJjUHlO8^&iLej=aSxMD>;L;(bw(CUwoF zz-kBi3CY;biwTMva)f$+7gH*BRQg8$BQi>?1k?9^+~_; zehij=ue!ECjj8Jv&#nv-dW#FkaBQ9R%jP~ogV3Bj#kpOD>+$Lec}OY2P1bNlLQ+8D9}^$jP8Y zdy!9zr?3h6ZyV3RgtX*ZF1hjSZ@~?Z*f?(1#1uno`j?4oM@<%OqwZ8N_t zwVcrqI;6s%u?IB97xiOHsrkh7fI@$U_I%?#4~JkfFcZAJwrFO{rBwW zcrCX$=T9Ct0RJH_ZrAC$A=EZHqo+MHH`!2~pYLRUxGck$`*dZ^;dR{TFiJ4VSLT>~ zL6HzibAA1&g(H+;AZ~z}WTHyz=kDeGz@;PF8O3(G&XeosF5D77*x!ET>o{~q+=DcTueJPAqm#K@1*iny0;LXZ9bXyoLx;N z94OO1EAM{V*mpBrC#=E{`}o^;3+gP*&VCboh>L{4I%{SVC-Ec+UVVY{GF&pSj zZ7sDfDs~6S9UTcXQ%mg&&Ki1pq;1|(Ll*09Zl^86QHq}$VdR=+4YAQQ;R1bss&#U& zjmtFE0=RIWTX1l2NH0gK26jDw$^_69jXt)OwJ zxl-nk1p$QmG#|HrfI1gg%ooPeOF`ph(UNM(s$~M3?t^(M*%ne{xI!p`B_$zsWO$X1 zCV?tvN8i^g(ADt@m5Qg4b!dOt=|&|I<8ptB`5AREi}s}4e|Qx>9T7A2J0wj)KcA># znWZ@-0(W_#{L?eOfbo>8bgA1oHy>ny4hSwaiT{`d<$VKCH^UhLXuDXVEvD`F8kS9g91!e(es!^7HjI;2`OD z0kyS{k1$!>$mnRvgdO~dHCI=)C^Ii=&t_F@aXlaZL zt&UZMD)R@>|M%g;&o`FIL3iE%%i`AN{iCwzwFX(DCL1Jr*opbc2g=mTG<6Y26}}y6 z8mJm&n*u}SG1*sGjYOKvaZbpR5Yv=7DytP!2J99Zd9^z!y04{l;>_5CuXhioM;S?j zHd)B%gu8##TrOxw%b5e8=CDOING+$uK}HEL7kxLq6m>y}{Z!jY zrj<&~<_lAtq9lYMwpj^<)FF@T(Uxc`x7pttFa*HN9e>!!&BqbT!S-5$TGi&uLMOYN z&rAUu;&m$Hftmt>=sIX@TUOj+m>*ITU#ftLy=z8oD{vskPre&gNq~G(b2z?_84IBp z#iC8D+UO4m2#5;^uyzyfZ*lWs!LfbaaCYtQcX{}NlytVU&?-=JGAOrai z>3aPnV3Og9TR16P&gNEVGoPXZuz)Z5g(3VE3*%K{MZe@(yGoZg1zU0CxrW%`_fm~r z$@B3GRR#tDs`C=Fl+r0jhT+ZFOb?LY2G^k9O%4&8`(a8vtPdPQj0Ns~uH)kH4DR`B zJ;S6!+RZo1e+UfhLM+AKRwrYGS))U!t(*fd*VoEe$==0>mnJjKC56h*q#|*+E&;$)qS#B#ej=n zQ{m-+e?qIahT2=%Hf?&(#acXw^@)kI=d4OtzCa6;i)gdiY8VR{&a|)1Kb-98fHmKL zV41G0q~a^f=;6bDG>8V_;zTNiA6n^>2Y=p=*gX}>%oJ+M!g^1$NlG&?mB+(6 zU%vG-X2+*%W##8j5XQ#$eor9)_R=8&9svP3SX2}JeRGrUj@O5ntvu#`T9=1_-IJ1P z)Zn(dc4M4!t*$1KuP(;C!mOGm8N|}$Z-OMW#(}_aPCru}84dK1{C-4G8&U|VqiR;% zl%S{wbais_=HAi4HjA&61F5WNz8mDQby>D` zkvL`98_Vty4qg@ShFmbY57yElbHpCBB8}o45~$tJ{ubGLmhbuHolqGU{C-q>+szSepn&rwL7JLmKd_GSfP9-#l+5lTNc&76(8k%T3{?wcb1<@ zjSV%}au=zeI|PRl^ec?YAA|_)DlmIc`ajc%x_qz?R&W`pJAC)-h&93k2#>8nPGUV* z$cD&9Y~xqjUZyWNt)Khht5uoQ#%kT+` zQ(iC@-Pof)VTD)T5Un0;iVlapjbT$&&tUgQlWi&+bbCZpv~xofFKT=yY;k|a#7Kjl z9z3R&mZVr#n{wuKgt=8yWf3!&)PT3~Sq!Fj5R+_FOZ?}}bUznGPsM=%Ak2o^*=}__ z<>3k+P!*t2tbO|gQaI}Ut}UT{)yX^NnGQzNTal?x^~h&2+=CoTw>Zy94B^qSrg|P8 zF!G;$=gN_4w{ts?0?13sgv#1PH=*515B%xX+Uj_8lwea-wk(VvJc`e$3w51N3HpI^ z1q_;Ta*&!K39eQ(NwlSI?hb~OiLMq=uLW2;)vr;OqPdG9&n$H7Qnzu zD}QX@qTW~j(`L*i#o(8-1$E>Y__!7o~vyxV7l{N&Rg26K*6$b|RkU+9?WLUcB@Zj9Nut{LX0 zlz(f~m^{{{{qBOHqVZIEVUf~QiP8!{uQY#=txM|t5<-+S@)CsG653C)H#oBP~v6Du3rwP~^d^p<1MlTOp$B>3F18oum?B z`9h1g%wvo}Lmu;QcyrwGs(7LI54ONT4M>sd;HPb^Hi;?a%LXGiHVwu%S&9NDZzQo{ zn8X~PTtE481(Y86G({8PwcB%~4If>ihvoLYjhe}FZS!f%+46}r{g17UPJYnhy9G~2 z&Bxq4uc1-vooyf>;}0sc){VBTm&nu9wzjjieQ#&(Ez#7Ro{^)p)Si)%p?kY<{OoU_ z{+qClmbtO{K`uo{7q#q+)5T8q;bAH5w4YO3rPb9=HfuMxx><4W2x&e$KHN{2g(qU626xGgbF*JLf$J>>FIt+wJals`$WBQZpps5s51Gfrp?%F(B4y9 z7mJ-p&zz>LkfG>nN(26-F}+D{ZlZ3&9waDVt0_e`9c^9z+=aXp74bT`Y+DkLT79wo zeYvBf#lSsK;%P!j8eBa#_NvM_FE5=-v5gI<9FIJx6Ubl?!gSmAUjj?q=8kfopzj|X z>dHh&Sg9=>={GaeK!;XOVg`NHU{2c6`|5xw? z+@lbF+}RxVWfjmLkKm=y2aKA}IojCvt{{ zhUVtx0RbKT8!jR_gGvK{9(QF(mM>C&^ytxGb#7J`(yG39v{B}V>r^xXaD{vMQxtlB zE(i2lSxsm473U~wi9^dzQ|2?Sv|nsJDJOCZUrgK*i9CHu`08^!!HMlGA1AW@_co+8 zH2{^ZZO9G9XUmbvQVQDe8B_5wk37#1y7ipR6kNU-Z@9+3X>Z>Lfb}dTo=^l!&++M> z%&Z>2t1rhZ#w*j?kD^{0Rj<0&v9U&*38X^V+1N&hhL)STMMcQ&R>R746ybEb_4?8j zI~UhxZJtw95{EBIYg(3SqoZ3Mkw_RA<+l4wRJ0>TPO4WLk+(nJIG~~7^|PX}MV9w0e2hl6Qa-WpzoyDdPj7QE zzZ^^*8YfJ&l>V0LK+EE{%}wwN z>*2SGAOmBWUWt}`Xt(`d{R2d&2XtWodPZ2v88a-QscB`o!*8a_(6(yRwdK&Wt!GV@ zgs~ zKLl(I*g2oG7m!aEjsin+0aNI}O)oY~k{Ix+8pnXAvqi@Rc2k=Q3krI;#CaNH z>a$VKZewCXP4R@h^C{B;dueE+L-}MNuAZ0Wb;W=b?*)5yjBR609s%S%?WPC~<1?I5ved6hhuI4n>y zL8<00PpE?3&jtPdkyw^HHOcY?PD0 zE1B2HlfzlHm8By*^ptThSxs6e-aK15VPenG-u=(rGW@xhd0|P5PoTelpc!r20D&&1 z^rnIGpp{$3hm?UI95c`)+5gz&T?JU93)tk<|NTbTXM;hRM778`GBvhQP8(BBDlG&V zVFQz1>g)U^;p9t>ZKK*V)6>mndq=X)f>OpRnW#2E@La5M^<@}KxoL;+PpY_d}NwCKydtOvPu=C|_VZCy-2LTd|t)&xdy3 zYn2LI>%jF29;GInttk?B&?4;f#)0HKAYb*o%1}H(qV;@C&hX+wpoBLWY=5hr{3dN{ zDmAjDBjtSKzr1Z_%(VF^LOLKoNz@B?w1@7iPLeJ+tUBEc0_5mlkXc>M&3&IGO{8Pa zxjbBCo}7BB%aBCWgSs;At)Ra+d0beM1XcRbL6ORPDfe^=kDYvt7s%6^1EMP^Icv{oy?B4 zJFWal2u#V$QWzPQufv1HdL26p=!;OQcz9xZ9j)67C=*!7>*eOgue38WB%ASMq~|D& zj1=?rnuSDdj-Uyvbok4`cRnni$^yOY*QejMasDT#)u2r1s^|6JRlPD#;6GX(7R_Of z%*gxqXm8&!Zz()}{CLfIcF!F%th=>UB%$B!_VNgvvLeIA)om&dBF#8Z7rte{!HDGP z;iBk26$8RY)DTHIxqjfjaA*KFU}c2~$yT=3(9i&mh?)Q!GYqulG&Q9WxSnqhM?_%Q z66W=9?CtN1`2YE}k??wXVFB2)4m_@Z1AMcKiwiL3fi57-1`ldTFrm%G#RUKiIe;~D za-vP^)OJffkpoI|5XD+$svfOA6C6TRN#Z)?=d)8`aWHem=?#qAvEelY`CqC&TTa`Bn! zj&^}-dh(XCFCGx>&ps)F;q^ERWG!vj%(v9Q`#Ty$#b&zo-F6&Wq(*|ZxIvC zGBQY^kKXY47qo>Ao$Ty(_s;|b>qR|Sdh}ovgUE>zglM zwtJ#-ZZCbjj_JZdl>L4TLdp5|#4$-^&+dXeF;son7IFEwDfZtV$ zXpK47Oe^n-nk9Gr1NMNnT2U|8P!^usr_N5NmCosez=qoD(W%+=?3|pqw<}#f=K$LU zt#uiSES9PbKdAxd@P9i39RBx!3f)FMuD43?mKrf$UDNGpce>0KS8F<%P zp%{bi++qL_W8lTg%5Wf#ORdBS{Uyc4gwf$_NN6kAzyM&V`T2RUXmH^uUWQiG^RU_D zVEXK=uFjRV-zAi~p`n37#CQUK`vLGY|PTMATyKUFLgYKy0WcX z1Mb+^*xv;6cv7kB@od$s_;ukCQmH(>)!J~WG!?)k>2YD$*%hnTQLJ7&O8ta?Pg9mJ zKCX35GF`622_DdNnbhM20t8sC5)?rSZ){o0jf{lf-!DI7Ta*2Qe}|w z;-ymWMiLV$4Ic8$v#q|0|VR% ziyRAyl+>)&Khbl+l0#Fa?f|M*Dj$ zfxlKoTNbbVt}bH=0^C#bvMn(3#VM&4TPB+9NM`K|nBtdO+}6Hfm|9uc`072E6;4BP zaC%idhuIu2k;xLlDqoeV*RZi-f1B#-E1~qSx%g$O&6Tce&<=8$C9jo$gZ-(s=xE?( zHPvuwV^@mX19>);ZJ{ukrPn%(Iz$nY;t|wj3HUg$_~UivA@51G87{TzHxn6 zIbjS3u!{_>%l+SL!4-dvIis@db)V%eR}U|*ptIyWcOeSkSD|4t7 z_5x|hMgU97QTl9t4M78*5M=JJ@Agzy{7yQ?#>N(!oMH<~pSw*>O zdsN1%4br3fOnEf6eiwm-@u3f#M8GczzNNjNo;J}=OIPF=9$M`5P8_gmoH$@hRHCa= zQ8__h%~qB#%cBjap(9QhUFp1gsK2_bb;-WY**WpqFG8$j+1Fj)GpH9VvmuilbZf<) zCB)H*Ho2fOo_b$lh9M7Gnui@c@uNH(IisWqhK?vd9-_v+;p*-VTC#U^;>qB3R<=r# zKlHZLe}yzh!r7wXGBN9R$+nlbb{;VC(Yw?Cip)Geknnpg(nDFD@fv zE8+DM;AH|dNV%tHW=Kd#%xh=MG)nv>@@5Vmqk}N{b?3aSd{88l7fg>W9AlFHad6>E zq0N#i0Fr#*#kU4iy~Q|?Jh4iqAB5vUZTIZiGr($wQp*&Mz2_4F(i2h9Sb?-tupkr& zYQP@?LC)dPQKc3FWcmPdyxT2IfWzTBhWYVy@=0`H-Ee1TCopI*4*bcJCzPU|Y{>&4 zie`Cwy4au{O~Bxm!86syg80JU^mIXt9cedB$gE!2X>>M_Sj< zO-+42JiJ?Ia}clj}I%(&ct zqgx%|1j#YJa1*u2~SKqn0Sl6d=-g2^} zty2TX-_w;5s->|T;4s?S+Camh>+PjO^-QdQey`~Hyxn)lqb@wVkMooJub+W%)Yc|S zfSrQPoCc+kv@w4L;Dt`V8GR!7d-VES`IMa}+(B5BP zzdGWgOMNA+uBrKPeYz17 z903lv+oVRl3`m8ChlUngJr014G{))bjPL)e6$Ag!^t%9kX5u>wUteDbhoha>4=py< zBxwRa84N9%?Y6hK$(j$WDl6Ddj$R!(SU6rQgv6=V#6}*8n!`BKvSvF6F(8L{6*$QA z{X}cIsh}a1j{gWCf0&oltZe0Kf>TLosHAi4> zj*fyE{mMc=O>;KTCNiBEBCxL)#1~Us?CiveEiIf;!N#6SLc)qbKpD&zmD03~wOICw zikSMx!mzk$5>0-x#yqRlp(Y@Z9kXy&6gx$~Yc$q)^;Ewob@Xe*XcG=hZBUS*oU|gi zN|kA7WMr_;ACmujsV&3rDhA|K{xAX#vV9IqUAU!ijxr-*G^n(lh1g?c>Q`bJgqZT9m-s($wE#}jzA!yp1hRCmQMmxcEI+wDnx5*YjJV$+qZB1 zC5&4PtQ_rpeCBvWKG|dz+kh`l83!epYs=!of++Afe0*R8zjv-6WpJzl`TGe!#meG2 zwHGGro<8*NwO_d@827znNQNtSck491CYk0MF2`#3IDq@?)_z};8F$eUIe%JAsfH15 zPvDBaN@Xe*OwjOEaq3&cWN3Mx5QoZMqwN&G#x1H~$kzJ$`nZ8@AuPd`o*H5jf9~NS z8yWdo6&nK0P&`}iSntEE?ed!;D*C8coR-GgLLrTP-X8psk@UBR7qWt8#%swVJ;Dwnik;UsnYsm22EiX<%nKrWy`qZ0PbVH6eW#%>HFcNVTSv-j*(j_C| ztCPzPw+_Y8*4%S{g${WdZiXEVIfz+DgM8?=rJP{<&A-jgt09N6c6zPZVy@e_izoTv zqvc|!N`j$*!6k{36XE7J?}}ygr+w;Nr28jV=%^6YfgN5})?W8{Deb2)cI*1<3y&6^ z&*9V`xchy8DQRmX3SBrxm*rV012ILZk=jf>Uof6DM-zXSKVjm%qSJN|L zMe4FJ_R;6iJ;@@T&o=jFiKQ&m-*G~B&wYBNf(hMvTCp2<&BcyVFD>A0%0)!q4$xTTWvd|Qw3hl zbJ1Hgc3!QENe9_NweycCQJ4Bh0})5LOEYNGTF}>8_I6^t8Hzj^hktqViQD_mN6*9{ zG6cBbTquJb!)2f-lIZWACQb608%GwKuxy2ilwUit43dtjoc;ac*V>TjXePP^EZD`x z1|tCmawY=l&>7YU>Ck>Oh;5Pjh*hfV+*&Rbq_o&3reLs6ox?5kYc%c2>AMh!lg8gE zwln@E*#%xhQw3VwBy?<>7i1^}YiPVTR%Lo#%Vrdz%&8Vqw zD2FaWQ=UBIQM3t0OT>CIC$Z+MaPf*1VluU_Qjgq!t-#eMHX79fW{9kfudccU1gO)| z-rR+bMq#Ys#NQ^VZv)*bNOU(gHpbp-5>Z|9TJjuJHZ7ms-gVtAbb;oC{yrEi)lyfD z2)YN5Kys&cwOe_Cq7H;U#g4vnaqJ5-|LhG^Y#)dWWJv`DqKXT#glh9u*7pAS zz-Ll?_@_cI07{gA`>jx1?!hDAg7E{O=wwE!Dp z+o(6Nl>&{J{*UJ6;5xUWHjE{hpx@xb%4nmG_TH&;4nf~tEyu+16fyp{7dqT++!;819DP=Few%4uRdbgOu64l1vWJQ z0Ux6-6v@^B1$OE;cVK14?Sy(6Y0#c=3;(O#3g5qk_paR%wU=i89Om16`Z_>7^L0l9+;N!L79wk z%{K+*Q%9pSeC%>RNJmSsZEnKaCRLiPjE=|I7N0Hj_7*+YXu$n4_@CUf@N}E6q-YTO z@KTn_6XGO7X}-8<_U|s))HPT(yeiS_D-F#rvHH?Ce8Rb@(NhRv^qGAU?iNDtSX;0C zZ-kCk8k6QDv)M)Rp2=!a&!snC=V_q^R?vM+_4 zSNBTta&vRRO0wu)vx1eA3-1)ymYPmwzPM7BqTf~JJZ~mJd9|=W{v_(|zOpMRBumf< z%shE1;*KqFTSneA-&=8Lvc}2qV{prrB^9*hFg*Iges#QrwBS)RY-w&te!gE`Z#_DF zlXJsanKM5AO|ngH#Dd4E^LiWH57T8;D$mCoS?}lcq=0<>xRT> zLo$a*8|GQt;xC7$)R3RCKbiWO1z5@h)uwEDE&H>}CFo<024>rIlD;u1+KZOqw|RsP z2ea4hfw+sRRY^{Acq=Fl1+IMbRXkc)$h<_6G&8-7#uQd7uKAG5p%j^^opWEt{3|;T z%4~7j*B>=3JaO%9FtUT_r7hDU*1gwM z!=?ew!yc#0AsL#Yt_z>T(elfj3i7iXhXJh3!2u*U1Cg*tO_pG+QI2w3>tNAcgR1t+ z*MW;-laoAO_4F(%*mzZc(slhTFn8o{tH$zQtoi$l_tL4^n)rg|*H&m^oAG2+<|CcWMq{)Q{R5;vtuis2-O{k-d3lk_!5Mj`uQ$*=}cwhe+ zi4#6Mf=?F@eD3uz!CjVdr6v{RwR;!apx+uDs87&rud|PKpTCvC!j^@LI7It0T|wP6haEV zodc70B!K+-ZbFz>S76zize|W@1dpBj&er0hp3ns7D*!zY{tlG4E zhWiTT)#*z8?fm}qyR&|N_*u^SHJ7w%y|=M=I0O^>#agrDhYo=W5(t=0R8cQ}K%V1eu7_O@-8&3uXd0(uxJJcbcIxoDE4ZlS6r0=}zXxFVHywtk)tf>*pP z6n=V{i3j<*-jnT6!rB%>Sip=s#uu+{I4(@JuOur)N`*x_r&x9Rl>M)TtdYj%U|4`O zX%tsq)){*z=EL=^^UC}h7|wwbi26q%)01LSOxh;=_?7$cDHqu*pkoH)_2xh_C{PQS ziq*@&`{}wr=(_*agRjCgc+ST5MgHS>-T)6PB?Scqokt!TI0~S40xG)g#}Eh?KR>wq z2Q~Yx|HAP5%(u+LJLgRR1@yl@1B4ks0e!Unbd<~-ejs~`rW$0l8(Z*xhQHA-eMfiJ zNAC1b)Nw(ld)PqIuW(Kp;c!|Bb&} zn7%QU`t=7a6g>Fl7DoVO)hB-Q=zKK=OnsuyA{L`u-dK}W!^M>C%Ih6G{7TV}Bdtg9 zbwdg@fomO&C-Gd9dxggYT{54gut;_S&Q3x5M}F1R4NCl(@7*5L*9k~0X_v;zxfWw! zSCF@N`qDG*XYN4tn3|euR{N*3fTDX=DB=mqUrcG?T zzrj$nH=l)oGXMUdNPR%;x6Zix#vEzm(de)rA6jxLi^kynIqi2A<6~xM^f(2LTlsv_ zwZ=h98I!r#%D4)f;i1mIoVjVCaIm+x7qe-wPFJjRj0J-GDFwNu7+I;)uaM*=YKVdD zA~xzL*53chKJYtY(A7snyL&oU2HU*d&_0GlR)yQp!S!WICo% z9$jXl;Y8yb)4@Ou0Rm+mw(V1IEp6?tzh_9m$W~TY*XL@iOfM!$W}v}Q%*R4^#Hv0*nuY)yJCp!7;@esclZ1}{LT^!zO=neId(6BlrcP`R z{ZY1d-EEatzv=Ah?A>qWgRW(r+j0YCW9Q4U@A<(gWBc_#;xE&gU(rBd6PQd&&(=45 z!0k{ zX~MSsIHFZfPUF!dgJHLVFrVd_DPl^pvq;c-r=-RwTSkOi)t;5n}${v(G)nB5ml?5X#B$tw#;6J>_ z7`}c!e!QVvmytb;onyS7BB8?ZgmDB#ngc~pX0?&BaCdV&i19KCek9{9WuQ61hD&Y< zMN_^FgrK-IftE9X%L~`kUYke^`lAWQMr$Z$Lr981M(sN(Ym7R`VXxblsa`^?_#JG| z@mX%}%&31IgoOb@0k8>8uiYq|JN0F-!BixTXIEym&7GYRLPDf*Zv!M&z-T1UFLzrpC|S#czho2@1*lhmZy4)dih*)gf#q44^2OQMlrY4mBr4Ag=EU< z2lsG?-I+G!_3fiLB-3-J`+Jc5386R zX*jC?CHT-=U~aC?B*Q#aK4n{`Ibem%_@Kvu)~_brV4GUXLXYm2 zy?PNNk!QFYnTqS%vsN`WrfN)ea%zu2kYeX2Af~GAU)sx#dO&UHvy|A`G0eFOY=HKd zs@!Kr>1HH9xodVxke|l8?di90CcVZ|EjQqUn0J`Q#$Wu|BrC=6cA5X%0U_uX3O!9G z%Y}J*vIwwRMG%bJ-C)y9*#h8j_*ccfDlCYEMu7MVti|l^2DhbKhm90({x1KZd(AO% zqxtyw7&L4jyy`V`@$m4lu&}VVA3C{8h>x$Ts6ao zK7dk&7On5Iq+L!}7+&lnsxzbJjWFM@R~}_nAE=Q;87OAOk>BciuG_n=TpFt|ByZ=- zVMHZIjo~h}SX;%6a~0`AIhk-F27K>BpQR{2`z8Z>-LG`k{s!l5#z$i5L%!+2@CyT{ zF-ADYlh0hZZC}bQX9M0It=Dxqk8T>C3CSTKk{T(C^LqYP3_Lv2e8c2VYc+*OY3@2C>qD5}mYjF_$S8gWt zQJN-*Z~x#J+=(eyU4+)-*HnLj%`PwR{%L+qM%-?6fGY}(F6Mr~`1OfO?A8g#1f9lw z=S0h$>jxvD9WQTUcXzk#)W(%p!Uq{f2HIDzQvExVM#=BUq<61ZdX~7IW`1~E{CdI6 zhlkBtBqQ9WIZ$Z}O(eWferT{ot zXwf$wEs*Jqy>~Y^?`a-|NgG|>`cw=0{xW%pewJ9vod{A!diigp2WxB_O_O1i^&*~! z=|1FNfBg8-)OB|>`ugGTco7g=S$TSTIy?XRwblbJWUY?9zrVk&Eeq)9PnOqMd(`hj z(GOJLiYh8#62lFcm;jQn3`I=TkiK;j4vx0Z86`PITT972lFurxTesHsh&@le7u9W~ z77SD4-`ukAen^LzUj!#mdYX;>;4p-VAC2mVaPwkhS?%-ZsyHYo&HliFny17&F5}p< zmg{7dJASa+>CAx$zIV~usOk0XnI+-7=Y6covQ=EF_1|v>Z#AVVR$lE7qRkEe-IA&V zZ$DT25*LVEpd(3(|1NHrC7rU7q(9YXPF#r!QG)Rzkrbo&;-~0pFlHjc_T}ZWvf1vi z%!1M>TMtAPA>9B~+!G3M5dcXg=F>pmSy@`14yOJdPvZFUA6we^o;pJzGcF@GK+$Fw z$UpS{9b@{eZW&f3jSXEx@IXz9cR3f>M4joPv@D4=-^COxLcX7>I_#b88Vh2JejwZ1j} z6&d+-yS!H>@XnUm?doRu%sB924b2)mk(nOSTDOnlPlQAHo9k5Y9~xe*fS8Xrgdg%) z(f?DH4eXp7Rcj}G24)99iPTi$4T&_Sy9h~>(x#?|@6iKkMoF|!)mdQZAv-?t8+7t! z%Y%Q|FV3g+oqWXpRdwf>Jxa$Bk4UVntN=6$WbHt|;^lSq{rmUmXN({gUL4FQwF0d) zkQMCy%m)|#8uY1yOfj?ghyik|4~XPqD`J3G69BC6w_n4-Y+Cki(L zB;&6Pw+t9Ms9gRW@D1grGZzQi)xc+3miFef_)5zjfHf`SCFX&b%wAsIAMMLDY;O63&_;itxxMY&Qzh)^;~D+x;GWJfA)u`Fxqq*-liEz0n5i!yWN z=DE9%Ft;E{mruQyE6?o0f;bP)d6XM1?IG7rNbohy1Y(| zR8#Q78D|F8>RvD}vK?j1mzFf!Is|7giJU_!sSLGM~QxVXHy z0PKBSLP8pH>*B)W9KSRSP_`^68`A$@3(yZ*8mhbQTWcYz)~>E~U0n}Yum5!a{rh)l z=mS#>Fb3d6`V*+If=#$cV|y)htF#cL=J6ZS`Kok;po?!PSw&)QX{oZ@mM6o&$jC@v z-!09{YwlTQF+!vUpom!Jmh$8xj~!y)@O`Ll;zqc(7+Bwy%boC7<*KIg9ytX)Y2(sh zkcOx{OA=HxvLnIcsh!CFg0uF6S;F>x{ahlQH#Z|R-?m7*k|R^FwE<2_gPi?~Vp5Sm z(RNpw56ScUtuH-!?a~ASxtv;-Dq;mgj7L=(fEek}N~1202kzt%bMH?8L^&ajx%LL@pZExPn4UBR@R(%**Sxwe{~<>1(p#swxhnmT_M0HA{`3 zl`mMK|AE$-GoKdK(&w?EGe|dshs0MUU8ixy2~42@>!*>pcDhREQ)O>EE1{>l_1)D=>YIDaQ5ka1JcxE|g0ErUzi6_Z}Yn zsZdLv7gp1lcq!1L#>PhdCdU9UeFtc8UC6at4sn#P;1}l18Y20?Tz1-%MvT~3tfK1Q zXD!Z$BXTB<@n?S>IAN)eGFzD852sWWeNyAKT&FII!ahaWWEw_;NWShDx9mE61lh!H z(J_9bij|VVIvDs-%PXKed1`QWyaIuk@8fxE4QY**HGlL{A!BQOTzHZUC9SyTmaZCU zGHk7Op&u-V2`wvTa;;5o_9KCCjXp}+JlQ*q>`C7VNW@N-2?y1Sc!*?8)66qG+bLUL zo4xxSQ9I+n7T=Axwl>j(-^dhDAh0Rhmh8BG?an`;X`hz|27sUXR1($O7*m#_2Vjlz z-HVvOphiuWV)ebPty`~SY{~={WP5+l^!-E;U|5)-jRqrZoc-2T-_XzwQNUj(oXlJ_ z0n{YXJE`_s4;`5cZaJkaYOpURvk01Mlc6aX8&USxfNhq5_rN`ZtVf!Q2Y1F+S z+h9xI)Xw9#Q=i~y*yhdNS))3*^KRH5_US9yIOn!sd8XD>LAkV&Hvh_Yy(tU+A{^69 zD?@P`sD(iC0jkxFW=U!;At9!i^}Ce{8uU2Ka}$)6JZ zRo}b2H>fh1d~jNBZ^>FHQe=38%`M<-UBk%xJeEFrAmR1>?7@YyiVB!c1)3Y>lOiJ{ z$M@VN@<`C72*Tg<%}-1emfH$s8S3d}W@WYcUhMz<>rb0ldRN%o+<Mj}c z|5p$6h;2VY&HR)JH#XLW(krR)Ad$6udmzo|d?)k!w#YgCBDnz2sS`x>jWr*Q^q?GU z6+m$oc%bF!kxG1(LCM?p#dGId#J9e_*$I^^DhUd}G)4B@zt_Z#N_Ev`PD5rW3Q!tn zW$0#QB*w~?+e{6}m)l@N+$gq%%&AzRWqM`b!P`7d&if#7_j`A5qF{#g#vj{Unds5L zCQDIBrN;N-D+5l3WW7cZqgpO5POb6daz%DeqEADOai5?<04}T!Wm03k_V#r+9U1OL zq*-lSJJM-sZ@ETKi^+BnMU~3da}-9^J^CX^UAdp23lK}71C&n!EFD8K&eIOZ(mzxxx+<`be=z9ZZR zumcY!$X&d=yqJhufgmW39IQPpiHZWeO3li@)kY9W0nma0lpH`K0bBsUqjYt2W@l%q z!zb?nO*bEW5z+DLQuf8CXn-4MM&SYc{blM5a3EMgV+LR1bdPp_WJ%{-1h)m|KUaq^))rl zppXQQ3@zZ{)v_|iX~ID$&}8udvitXZng5zBzNfNkYr-C5Qh7SU{ynm4?MBsXNI>R* z9Ul9D8aO(#Y*kWAv2Dy81+?*BAbAFY`^7~H1d6+1Dw5JHKz=5nNMvt_NAhKqLF$NO z`{)<^P6ZwDLc>1mx}&?9gEA~&-rM;By+NWpJb}lHrA(26qYm(l@qsiX5`idd2gjZ| zZDl2-wkexP@U69%gfP0%-FN=aV+a877WW20>G9n?_t~U>0WHaTJL7j8i6I|?ZLmv{ zE_v+!vcJxNnS>|9j6?f}MMGtYR(gR%Ogj;ZBu!%T^+aBk|0xC|w#-D*)v=|vHbVbk z`}YREnb`MpON8*bauKmMM^I~>I!h{m-&TSi?#w_N?DI4@ygX8t9ECb>bfv>jFcrGg z86ZlE7gO-#Tugxl29VUEBxN8{bmvIBH7YuDl6}g@-qtP_wDt|yO6bZ1jyg~SELTK%VZQ328MmRrG?w?N)`p2~VjKneQYurNR zs5DC(2RL9+PuXyJ!#R6rvZ0Br{5@tGGMXaI@)T%B)7(cDI<3w>-^5yR=w(KB zw)`cUzI?G?{sSqq^2y#2&s}PIff0O9vb&kgN0cv<9L>O*swnI>+WdwGjmkI-K@w+f z^$#t@Ul~@|`~8hEkMzretA<)UE^3zVTw{5uvEJi>v!Cvy*&i!J8MR=|gVlMy+1 zX9e?!*@%gj;Z8Jp75?#I)R}I`VR&@(;ME9IOcHqA|C(AVY&0CchY+Y&YU#$r>|Cod zZ7#F7x(jU!=D(~>7=*lBe`jJmEcky^%9BI$-q|l)zktH^eb0I%kg9cct+Y`7nm)Ey zj`gP8!0#;Vgrw(ALm*EGA%AYw&h=+Ro%J8)H_OSeVIG+oJZseDdNal48n{Sk&$F^#Up-ARtJGBHi5} zC`e1}0!uebN_Ps<64EIRyL5MmbV)4T-5@Fbetf>~kIR3IOI_~!o|$vz%$XFA-=UQ^ zwDT(&X8_^-mj9FX*7_op#S@KN_ph` zki5H-pk-LcK)z8Tm+;v~VCjbXsAFslC;v!D*OskqZ#Kn@nQVgxbrP;DN9i~@WXi+q zc>H>Y8ov7`>OyxK@i;`z5BqUrf31n3E~VuWrtmhOeztC7%xNNQ6SzG44tm~JkD^Ms><-h-`m zA_Z8?FT_4vqeb@$a(6q75~_KrjOi{UCk(cA-8hyK=8~qQrCGZ~=iLYa-Uz_ny`kK+ zWGOKHjG4{#p%<0<95MRhvqK*o03^oIMfbi5H_lf>@dqS*!d@?qXt$H_P&=}l_1*}e z0-}tP6X1UEAD&ffHe_`^WTxA)z|#?r13~fl@-S%57eeXzIzx*@xOVsehP7^f*POKC zsrNn54LAD9mbqPvV)q#p6x1*MvyTSL{g5?bFgGMk+i6$w{1TklFmCmDdMEL?9bowq z)Fd==zQ*%@*O8JdYlqGmPa;`PE$8i)M1R>`hC_%e~3X^Z*{@MqWd1F`Bt}=47s;@N_2$1kqa@U%}hDfFo1!rMY%56OVcuFCuj7sEM@C3;#87$G9s+k=`-k> zZd$Fep}`r~I`vXu^R)cd+cn_j=X~VD#o{ zb;$}kxE=2TJxjD-s^}HSyHy&rf*I_sAB+8z3~}%#;TxhKcw-*%A1zZAnQnKwTWkq6 zp@$p);MTPCNpoVq(bb^o7PFAB#qQ?uO%jy`5Yq4d^e| z7D^R=uf3EM21u0er}FS-jkD)`b!vAB(2+0Q!r#lj7n_a}T;{}m{=DMP&2fgFE;Qh< z`5R^8wliV3tcl=`k&KDQ>yWvo0`jba_0K02+A|Gr{49(O4MCs-Cx;}mo ztU!Iz7O`sdy*T92g0yMq&(JML%dufG363n{GRE^g(d1acz-j4Rr>zU>!U~N9Cy;&i zpF;Dh@WSdi@Jr2=!C6m6jlep@8JQMIvQ)H_2o`40i!Kz}9a+&3UL0Guj3Xi@sms`G zR|l>&-NCJ@H+IZe`z=SDMl--fV!pIin=e6%Ga^e)(eQ%0)&N{b_t17;KCDJ27lk7WrUX&k~__3lqV{}hdN(RLkr@Q1b zZ@USznOue+uo?UF)t*RCH#P9^R_Xr0qh{cgY+@ExG!V4N_x$#kR>1ukVc2`J&@dq_ zxD7wxq-af13_kDK1FuzRX}+h!eRuX|wuHp} zcF((2z3j#@__TW)dNv|;DqKZX`4d^LbImu|qiw+n?jCx_Al-O!-8c3sGseZwEq8+w zl|SpX3eHHux*-fDW=a!1n3#lB22~QbNw_u|Vou--?4SBX6U}tK3?26KHj`J zYlz)~Jf_4DhBZsvk}`yY`~m0mql1ON&mAa0zXWkXmbGv)XDS;vNHoEzPW;kO_d+hj z@uBLd%NtyQ$k>m0gf}S-q9e%$$#wacqD!#{mh5am0ygY!#T}j=&ZYeN#osY$p*d7+t<3mkXfvaKFw23KlFe%(u}UCc9x=L(?MZ3YDk+vY@NwT5k{E?> zo^rP%F%d9Cs#RTDxR4itH9#G#M4-=c77|eAS4lom4u8ru=ItM;Jal2TeoWK6`wghS z>s|Pf_Y~I&PMZYz;IwC9URw7SfkjqK3C0Er`u5*qjB}||s$;xAya06^{c;sVkcVm? z+5&gM6+a3vF`stQx%VEXu<7F*S3e7?Ft`rPsd*G|nU&Qt2y&eq_y+A9d&bH^_l6DH zIGTNZ)7CMP$`i?j$bd3as*4%kx&Z&Xi1dsoRR8UVE~m$nafxJE6wpfA@}v3P?Vqd1 zq^n`_)J3CvzDxn1aG+xF>u{)!>M7Bu&x;rbq7Uy}0X%o*8M=dDq)!{AHZvhq_#N|G z)@#={r40f4YOG`FhYaELOZeBzMH+{w5TmQbCej(PC^mV$UCN1+oWNlkB9LK#Eb1sL z(L2$cDBVRF-h<81ZY8u>wr6^m9JpC;fviSTR^w?32wBZ=UVD$m9(_+0kQ#_*(Nra)jp%CFb6-HhZYNO zzCC*n-=&;VD#HSC2fgRCqcOkWroG@TG8R;Mn@y{V9Cfh8Hkt*jL`b0QR-3PRq2zry z=W9n8r}BFRWmVR?W~Q0j^csipa6N}F{I`kF4^R0M!)?baG`k6I$<&F|k>kQb>YL4` z>_cr^p+ghlMRPCB4+3?U-P$ECZ!MT34zhgmMRKbRmYWpND+MnI*Cj-*KRNj<^F8p? zJWv8Z!*VUk@D5_n2xBRwLYev}LH%VvcJu{rD@Q*lhazb~cw+v0?W1c@v7C3;feiGJ z(cC3ACcE@)K=W?nlGea3Eih{Mw^+Ti^!wq-@87j9g=DCNDZ>(-&+-AsMH6)Yh@fOo z7aXJKN;h7OqH$UV?unDasr<5tbg?mZ9r*O9uK;8O0hj~st0F5ZxshmfS#x&#k(vfR zL=UnN1sVp;fBDWsc1jiOQT$Kqy6=j2$C%GvbX>g*{!r%nvKqb&KHT4H7fw^-Q#7d! z7y<&*sXXIGVdHD2Bw$akLokpvGCsQ?%a{~Kd%mdHhpPH)gl(v(@8xp_K;m`gn1Gz- zO+f4p;?!pT`tvEKr#q7HSGC_!pBAYe5y)~THvk=!YF&~Hs6z(FcfQcV&WFN8+CA4R z90X=`-^1|wFMO^b%lmlIgdmW9%8i@_8KS#5t7Y*%&S4{AWmj2ZvJ&0pVj22({TotBC-v_Ry7Yt8&YoCsKl6c`RyVA)Pa zzL_e3UryCm7HBjZ$+FG3XkM&ji7i@{eU!iG!EE1XceD{+<9_PmVP;YfSd9{OKcM}YzF67(DI^K(P0Y&xltfnxG(6CHcP9?pl7L-q6Lv?)N&czK#3{1mh+DY<-} zxxBpU*1#T3HT6n|%~dX)eJyo>NY9BsQCYv*c!r&=bQl>J_?1PCf_t72;S zo;7HM3qcq!uGgzG-Sz@ZKWASYIZ0a0-N-!iTF`xYEbra2n?49kxQo>&L$$>#lX`t0b(;HvYhMzV@6Ui%00MJnvg?zg+Js`$ z-X-e|hlJ#ZTNODG2956Ls{4ivR)MQn2>kgg zyf=wsaQ=p5Wo$5V?GuURfo@y!w$4A22JH+B!_W3BH9((6HzHoYJ8u8B z4>>OsT+obUEpGy0q3tPW?)4)P$5zF#1Cxkt4X#uiM zNt}^OYWqyi>+{RWH5AO<}ZBFB26KIrlG35aO4u0v_x0<;Xd0CeLD@dfWV@9{DYcymOxe&&c zJ6E?+A_p2!vuf?L-%Ed@`UGCbhH^nK)@~vg99lePGXk(qz3 zF5Sj!+SHuJ`nQ}zpj5Be`f-f57kuAd1mjLP0desKj7zdzdQB-7@= zW$6?tt058nuc|?{h^Y#vo~jmH&{}69o^x^;_ay?Jzd?$tVPAbFhwA=&l|u5_&bZrL zc<)x#8a>`=9N@S3il)%v;l=4~#g!5G2ihbTG(Y$8PzW>_0qLAKAVd8o{n}NJljpdj$b2w_vS{-m=Ee+ zn0=wD&{@$r#{3(dU#wjO7_l`+Yh5rr@-WGGdjUCkG&;9!8Fq%JD1|?Ft)XdQqlc4bc#%%KAnOuQ{Npy zeRD%(t4FL@!L9dbOKsvK+tVO_tGxL2CwL&kPLm}+miZA1eDJx?%QRk1i<+y{AA``zD!9lYnc&?M~f zi(90;>{Ir2MiUhEMe}qP5LA$q=y;K@Vn;RpF39j~pGoQ_)vf5lm8AwSxK>8fj~i1H zfrULep)qd4o_cAfq>6ib_rp-6J9X9E7 zF0lBfJdwQm1W#i8SzS{%Mvs}4mYiWo2waWrvp{5SAPA(Fmf+8%WGxA;Oa^DmK)J|W zf?uq7fci-Eso5FjS%N0(w0gKx)d+Uh)EMTM>4nmAx2kL}47P*dd%*N>%by-{V20XA z0dIaL9&QA@TY3}kl)6Nq7mMXR_y559UnypeB~l5B5jxnA;NAQv~WMd_w%NP6J5_T4YOY-fIK3_?6lCrqJVBHXp zylWQaDay}y{{0Zh%gwT!=U7r%KI61w(-SDTH@kugYZ2B?g`}^YaFMb@GEP%ym1o_uuR@oPvy^L1jW2I#n1MLv=*B@OT9#v%3sNSLoAkx@wU=^{-U-X-_&SL z)+FjV)26}+3^!Lavg=RGx@E&}j2sI;^!FELdRiqV4m=T=GvwTPQ4N=c9@6&M?H^yX zqWgf-%B<|{M$R>h4l8h#q996(?bIdObbq84C(4sB<=}gPG?9P2G1d#;kHvp?`!*%b zP+L3>(X2&+pGpcEFETVs{|SVA^k1p5qhWi60=o4E`a%2>_Djz}pxM55HU-V7@olV8 zrJ}hMcol03g>o-IQ=H0IWY`Cm4ixh@Xhb_Y{$Lferkaz79#EoMhCdn7zt!E@C6Y1% zo%9&X=c9svrdMJ8PmN8vU^Y~(h##B#yVbZLDmL|>I(up^qR_-QX13GzDA^as-h*wU zBPj#Mem5L-QGB%_zi-_1F*ED1StUdGpuTS}%DS>$ae+UVUJTQVfFJ={{ zU3Y#Izg5Zh{yF;8!dZ2q?FTS7+T-W_tB1iu43Pf|ZNk@XAYW~- z;=;dWZKE89v=Jv{vw*J?Wrg|&rOs8SWeVDxM@@WG>8@V2;oZ(~{b^pMC&|xFjPFLK zy4pVWeb>2-mF4tZlDDZ1P)K4&7RW8cNhZ}9J>sH(AY*U{Nw}vJ_^_nVS{RTDIXZHG z@2^>d{~G}ZR30cab1lEIZdpWrmHepAM*+{|XT-#GkGzNDU9VyGOEaq*g zF`W}ez+BpvcZT7SO4L2>ZP@D(RV~AG&xKAx7>Yn>r6EZk&HRti|C)hzis`jI7R^)z)xpZeb40yui%OkE zyvgsza#esL?Q3am{Hl?^aZ(#B$(@B-BKAr1cz32%Rr2Dy(OX+peu4oR;P~AvTwI=3 zl7JW!uzJsuw;P8CE2eZD@}7fgd*Hr6^PYm~HvS^ckRL+D#sU{nikvkr44|rcvQ&$2 z{Te{we%(v_-NcI+F~KTuy^;1%N`QR6-@R?Gr%$#J6!4K%f&G!(+~Qp63XK4b{IR?`>yY&)0zdT^&G*x+ z%OtL>de=-i@BWWDl13hX%}j85{6U>)7g$V~E&TBKZNmm_WT~uM`+`Qto$N{$~2kR2jT` z3=Rm!dE;pFGPyhcVHh5AL&93F%;W8bvrfYlHIvJkkMrNh<~M-mj@FSF~xD2CaM`pNSg zHosebp=%Re!2=--PFYgYBzj{?DliLz!ddKDd-UIHZG?BW5Usff37MCWlw1qT4qP-d zKa(AxI_xAMW{v}O|{~*lc;0kVCJt z+hPF03s76_NpCF&e6eSqk5rhmkH{z&Ro70}e++1$5(Ej@j(lex4iVVE@1rf`JN0)bc z@jRLiTX5BD|9oKh(*Ako>io~SK}GC~9@(eaL|I>t-kf)6j4e@#ywL_j0Yy@3Uij79M$6iuE0Brb*m^&_4! z@Vd|O%(X-*INZXwE)hB%--0Ojc(zuRH&U$83kA}o%>oPGT&svEfw;7OjtGvghFE#K z9Cp}H=0ea8bETi^m3r1`2-k<+1i;~_ zlUG!kh=0x#z-Be%%Y#u!;?sg+KuxJuxqGXUYhL8i#8>&Ai^hf7=*6D(-_Rso8Pxk1 z)e&W&4)O>Te;T>>>Ri2OXOL2xfh9Fp;dgFa*$P>|Z>Dgb39phK)inE{%UHBOa15JJ z4)}^r0`%pTeCgDi(t?S{hmh0Y`LV}c6I9k0RU-Ds3;a%wCvhjh}bFBl_OJ0rY4+xeGIg>}X z(_HEfFxHES8mT;PsP&&|VVQH=L&fH&#^Cgg%s}HBJc7COZ;Z)!7jCs}E2pGj1&v=% zu52oYxptr3riz8>I<&Tisxj--JB)c4mb4JF5NNqpROMx<;nNJS!j!NHn|{)Q7*T`G z=ZieuUtg=M2WM2a*!kfv<@Tp%Gy&7Au`GeIQWVi#^?t1h5rg76`ASLDwo?1c4xbRV zhB~lK4n1$U^Pl3x+Fcvs#99Q~aEUhLk(9XK=hMC0MUL$to1Vt*8_nzDTpfuT45Nin zhqB7KvEJt*agZOdW5Weiv1t_lMNBeT00EO%IKr5wlEU*jwc%{HH{~wik za$9H3UmAw%@zJWB++ zbXuSroo}V2=PQ-O0Q~Lm-jvsOG1xX|+s3k#)xVN`O{Zs%ZmnJu9^fOsI$6Auz!I^= zW?qGnfI=+va;?#+3N@bi1snvw>J=cGA{^kY+FZVkS|v_;A`D!#Aju9wtjeQoRRdX$+JQ$^Z+Xi-DCmns3&EDu-S`sAY4D?B>)+U4>BW|Xl zC)Cz$Y#%y7pD93K1il=cWJuEjU@n){Yms-42dz4vDYQM8uO%3GP+o>A;L~9Gzw$SX zebT=bGi*Nk>Ba0ss;#mX&t(l!OtaYP4yEk@yJjLUxo3sYYKlw9PcHp=mfOx#nU8pp zE+wY3iJmqkiC9Wr`CA`LX+tKc1e()w+)1nYws2@>SSv7M8o--Ex1T@tmpE}(S5;M& z3AUp@+tWaKQdPyR@^Jd-!;n{VV>WSj?fuX`<0^fjo0XofQN9^XDFT`5z7^`pJpK&w zXN%8K_KPj}^XDO^NTY~K9`cx7D+RU_m6%~rPA{_8DZ^^6E}VdkDKDu&kq!Kxy}fl^ zz|qZ3JGrvecvK(PiyT8P1eBb#8jW0fS$H;AcHw~^h{ESJgd(2h{Cz(Yr@`U)RyRSE zjBNF}rx5z@Hkdm4wuFmIDP*=H&LK{H8fTrvk(|WOs!v3P4dyEGHaR~pslN=a@4*s~ zTLu!`V;-AE|B;J$<^QfL^BW&ol)2Iv*|)f~5`27DR*EEA5+St~%uYbiYTg zIb(Q-`R5-RI>mMQ9x61|UXsc{TR-kb0Jd3y`^RwmQI}fBA_sOGzS58@bm`ZD))*BU zYDjCuSNMWEd%v3l44aP$_8yFf+#7ItF+lB!ytzBHiZZQEV7Tgux=vw|FQ5 z{I)+;{FtLr(FOgqg}R=qbgwKIbc%h~dBepbptb?mwI`z21i#D#bVF!^L4v;WKPgDG z9{(=;uGcNpNL3iUeN!9k`4ProK~BruvJkT|z| zbdL8UD@$Jenyb%IxfNXg?X(1$5_WEWLfXIwB7e4YJHscz`Lq_oZbAyA@(3;Qio^Nq zyHJ>U<=hoB=JT|zru_WEpdmDEsq~}c)RUlC2T_0MND(!c~cwU?mk51i8{r9z*bY=Kd;Ey+%b|4Yb}) zk2wL}v%Ig5^_zAk0Kx&iD1dp&AVAM?aOBplP*#2zQCO+JD)t+pFxi&>;Jd(uxQLgh zE$N|K3QY{v4Z9LF-53}JySN7zCSp2V*LukGdq5YPw0Utc@N*;qkx>ymcd>&dLx@t>U)awRiNi@Y_&74Mg3bNQIhHN zzAeE+#^D7Bb5ioy-Zfe+DBI_y-We+S`cIx&m1&X4`t2r9BkUh!uRO`3?uR0I4Np13tc;_;N~yxxPL2%(N^U_cHLuBp*jtUbgG9h2YOkHFS^+96k( zYx1`*VE<^P>5GNiC9c2yLh{bx(`|YhdAN;KBBnN-sZarCqLAppC5CU#z`G|Umm7y( zwp3p6^rFB4|M70x9~_AGiwxvE{CnLFyR_$wlQTvdU4>p6O#>?Wy~=_-@MaEH*}FqM@h0ce$^KzkSr--e&C!=aIZRWF~kS8sPkz|sa}llHK(_?R;{%( zB=TMW-+?ej;VKnH#RlrvoKPZh<+qk81wMbjT4!8s0O-9fjr{c|i96kY z7=ICu+Tm#F9as~%4m%RXlW8;+&wod0fJj7}1O3wAF}fq0=A?weCEdo5Z-}_RKTO;W zx3BUe6Mo=dg-Iy*MkuSjUO@mEk2Zgh#a%RufWRk#z#Tu_c(XR=T@B? zJiPZFd)RZx6@cO3{-D1N^rW&1{;Z$Js}MD^X9X%?4Q^q3ekQog6~DzBBIym#}~ZzsVZRT58ZR3DKYLhO4{C{GEjl>kDnOd9P%t z9A=@3C{23clSnM02<8y*YS(`gcqvFd5PFszp=Ib6>i}d6N3uLv~e6Rqf$kcL@!}BN{rKo)PQv&H?K5r z(^5DnR-&ne6ilsBU$UX_r4GQrFd~H_D}mgE21PG2tV6m<820s#*^z&KdLf?VpDGIacKc;D>qmCYBDOSrGl5eLP1Fo;IqescbbFwF^_V0kf#YCMsnG62C~5>kW5|Ft-Jc_4LIF_heI{9`A`5#&=eTNo-9MX zo(t6k%TS+XtXcDtMHK|YfNrxO(l4{_d{(WV#iG79ot!iuNd zpQ<^a-?+aXlZ8=lR|m18agg-jVTZ#n$K{irSiuMO@E3TX`5(Z1B;;NWX5B;PJZ#6= z`9}v5H)GK&%TDq%WKbZ<-P(o&qna)u&p(5=NxXE+JnmzmjI9&d=tkPoQYD3kpEVU<=r~nOc+?MUfH;k~2 zh{=%2)wcfls*KOhA{X`|RRh{h01vOc8U4QUFQFndemA=mk8+EY4xr7qRkVm2r`~@Z zlP#Wsh%mP93J)OFpdT19od*mke&uK#;YZ0-cpgA-q?i-b(8b0QndzjZ=h4yY-x6e` z3=QQgI9U%!i^L-O`{h<;?l0LZ*8$__;0 z&r<((uihIGYVifnE4!oW(Yui)zD(N2Lc3TK$PuReg{PwDxTd8nQGhTIvTf1QN){ZC z#w<<=#TRl-@$z#$ZfWzIwwq-BdHRl7zJ`I-G*H~HI21zRRvM2UInPRDT0F}_-ZK*& zK;)kuAKX3cwoQk(V`Au<7m|I9D`N-Zn~Wll$vo-&5&v^L5*@~2M{yld>9UlX(*u_Y zPu1s2dOuFWA;Gk1!vzz&fG9Cj*hT(0;w>p~l+Mnqu{%#bAI|jx9j+wkm+Y17{LU#8 zV0pNsquTx1VxC$t@EDt}6jd~z{xBUaZ~wa#NLCsiETE)ri}N?k7HwynLh|wF&sAs7 z{l(^SYlqK0H;sQvY_ElU zQ%~sr{rhrkjBDG7p65-Q)_Upgd%6J?Da@c60^`9mv%T1{FM6kPEQyv02Ba%OJ-DBJ zG2Cf0jz-M$UkOf@+;I478AJFae--~4_jSXj#PKv=@@>7X5Oxr%a_;4Mv4jD1_hx5d zwli9G9q^>e(#U;(@DpKd7AY%c)5OZyR9PmzRQa8=M#qT~2QnTQm|Fvh0X$>fZ<9`9 zqDMd?oZM75D9=l1CaETLx16WOk26zjO<*r_9pAgVKC>dE#qZX7GhLU;Y~;ybcKKch z?&tu2T=+6w=5yeEIGbvxL3>AWh(qjq7JKlHVJ(CGvh`VpmbGX~{uBQf8K+Lb3Fm5e@qVjeW`h6z z_%A|9w4uNIKP|x90J95SJh}dded`xjiOX~YAf|hZ!NJTyNlZ9%sd9!eQ5D^982dp* zuv$r!R(gT1Vy#1MI58L>2vL>o25nNVIbc*3JfDM^%G$c(57I0WY@2eDUM>QS(;K8R ztdvt?gCIYVq}#&yZ`bKmPmr1C@4LicB9l{)BM#ErIL1r|W|gn@-Yz76TSRr=AL=En z7lLN$?Zl|5XZ*`tM!I5v*ZUnv8@7}c%t;{*$0=m*^z00PkgIessRzY*pq%0%a}LvA zu6>ju&>X!m+$RHVIu-z=CCPB-& zJT>`nf0unvux9X@WkSbdBa4y;ur;1>^gRMeW0sr8P?I?fk9_^1mR&ywi9jH##&g`>gHg z$sRcFjCw%2_I1x1unZ-Au<>eMDZO2O*GGPo3-SuKN!pF!ukir~N4CP;?oIW`Zm3$D_ob6*c>SbPcy{x4`s;^Zf&-zRbU;23_Di0WAueqAHJI+U#>S#y+5>IG9w@y0{q1yy`4N6%cv!C^j_*#=&v&F z&lP=0ZgdR3d6E?6L~WNUYQl= zDEUe;H~P<5%YBSm2HrSOILH0cFDlc<*3f|--U?IClJd^O!uKRp*fkrsn>r@6D7Bla zZ`aCbN7%;Niw8n$Wy#QMNzPuJAin;YFJm)MfVluBg4x-$Odb{Hxg@CrOu|VayLzQz zGW0yT5L98^CTBS^?R9HEU>n)f2Ic@QfzQUqQj4D&CxrN*7YY^x;~yIvqEAH_efl|N z{E5mZIMXs85UpMkiutJ{U`+N`#9mazBjF=H9mFFcLdTnTn6x}WL*1V0Z;Ags^O>Jg zzUJned&q9LWj)`=`^~H6dizCq0OE854g<}6znWR*^&Q&Z2Lq3NEIy0}J1*<9>d_O} z36bx48W79Ps{ZA=1~>r5?UPX@6Kblu)gGoexPjx_znJAIAI${9C3*)CR>b`rrddCK z8)xq#SrHu~3uOD+wAucC7v;lJ>-W*e>dj4ZeNFbjjIVz(E?uu$uPqgomCX}2$B=yq zGK61q7P)8;Ie$znEk$U>PAya1J$Lw;FSq~xb^pxugZ$3`kma5U)ZFCrgz4Ekzp&D* z+6(#&7GYeJf{Fa@y=FBb-Tc8}*Ki?FSmdZ4m7Fkj{hyzzFrl zRiW?abM*1*=A|7;GnX;@)Pkai{nvTqI|L*7e>Zr0we*DJHSw-=hwY_^%{^YaRJP|z z^38os+J{@|u4&S0Dy{cn&3~^yuDw>y;A1xK{VvN#rldf)wU9R!pC<)F{se;ftD(Jsti4ngZle%sbL; znPU}B)^elr;g@$_r&auu8`{K*yPy{Uq@7m{4sz+rd?BIcxl6?vDS+xX4^Kq*Onl<0 zzXRh%5naAU#VY2tLzM#i#z#UhMZLMC6H%ksa9-Pds5IC08?1ak!0ruW&Uut}lMCSe;L zHx6M{M$lg6&Sa0aV|I|=;?sGa3AUsN%HMm=jrdnQjK#mJsM&k`&}^?s^#gQq@Oe+; z(e~o6-H%!Lqo}F^s(OJonjTWR_@gGK9f9Nb7|L|&4c(1WD3!}#bn@0`b~g$Pen`=` znp0NHmy0RKekTFTetBaJ+G1)}z1ndY+05_yEEA-KGjJKtZNZ|8>ilUqGd#$O1dAHx zi(V!}qqDC#X#zIMp65G-`%|>P5?^M+>GE?bn>OI)q-iDx3#V24BGAOffMfG!JcezF zgA@<);AEtyya0&|wO&Rz4p~pQ?X;lsreW(j!QqiPHa6RCAw?Z`8-x87@s<$)<6yuw z#QSo?{88OZ1BSfjDLMWi66;;2aKq?gE)U|?zMGDC3x(USI-^;8R<4nr70ZlXaAKIa z@J>DKj~h%2x?k!_%q@M}+~n-R0>?mn7gIR=XnL^+!(UoX;nF+TFh2>wZ6$c8kv#+y z8OQ32Kbr<7z$h5snVj;7ymP=uA;8D`ds=4;xJ`_ja{Im>!UwOd;>u^BN_J*=KlHNA z<;ri4j2vejdEtO=^t<}%zp*Zord^{AwfKl+6$YKFHiZFH$2Mu&c1xlIvjDK#aU*+5 ziU5q;t9g378`q)6I%$$+W19yLX(|t$B;)1;q-f!|tj=xwshEQ*GQ zcfA!}8(+Sy;>omK;DBcRZieb^g$!h2==nZ}hXRg`vyKHcsWB7={fHcS8qc!jTsHAP z@br-maqIuC@_X~;>Fd6cd@o4}o|_ikjxN@R@?{iBHz@Dm%p0?+NmQgCb0$}oqXO!o zPW{f!g{{}+%P4s~Y&IHDG7pampj6xy9HEl%MHNM1Vf?r(D*I$}ZPbJN z!jY?{f`zG6YE7F!P?*;g7k5P5eT8b$QbQ3~1~742Q4qK%5rQ$s9I#yoeR)%--y=`p z6zD9hH)W72k}=pyzYl-V8O0g%=AJEORgRU<52`^m%oJy%j4;S?F5LHLuUgp4Auk=s z$XHI&P3Ss~^0xMqJuXYJUo^4_tMu)vU=*92sw)uoK>7nTi>0_F#BGqb2Ep8q`i>!l zQ9U7RB3{m9O5Bpyh;je5b}nYu3X7;q%oUyHaj2<{h{^nYj}z>IGlJSLvfXvq;(I(j zEVjlf3b+z?#^Po^Bu=l`JN(!vQP>s|=>Zz6YUpA=A`2aBS^OzoK$MBeVUVEa({G1R zA3=#@UyL87Er>DYZz$c#9P|9o-?UUp{iwkrEF~!FmQEQN=}Hr@*2`xK!(0Kp2?4u( zwv>f1#h}E!KRLeevGBJ6|8X-dbBLt(F5oHB{Yj1twZZ3L*hO%5_NZQCAcwER-q@S5 zZC&mbV@Of9AO^zm$tgl1dNA>4_m)uZK98H8JC!8js`Y(1gsP zKl_KxRLvlIpX!117|!JR#N;Ul%q4f|N|lXjPnk}pw@(jofA3t%>O_Vx`dxNBIp^v z{mgFxK}LWmu*+QbAqZBr)`dp>SGz#uP=0j%45WC=_G(n6)?!zeCub}3lNFPsglH}h zOaIA;%XJ&$lvTt$>0~HW^S_n?f7glB>#;VA(XI@Ud$>ue+BEXv|(QRdpmU)Xkgg;J* z)RME&)s79v+8^1}RdxwB9&~ehkV%IE-K^RK{rzih5GLPnJaiWYd3tW+=`JAjw)mm?lWRTyl;)#7o=u*>}Kfk$X#32_p z@aUea?wzZ)P)b07`~?1~-jdfRYD>5;z#zMnuf*X0J_s)=p6|!4s#DVIa{HCZMm`)aYl7^1y`OAC5-$6&asnx>DW zL=p+>h^JOMhNBEdL4+ET##2@3RT(j#RAdj`ydNfeHwD)E-m~{RTXPKyj0vod*_?PQ z{ln=VE1^|*`_eVK~Eh2WdFFlAY9Z>Y(s({P(avQ7LQrL=9jDgS>w zeFZ~QUDx)|B}kVj0@B@`k^@K%-Q6H5-3SVjLrV7y-637l(w%|`(v8%2@P6KJe!=W> z_E~%Fs}?>nCP9v}+SCz%(KhRJXpJ+br*GisSk_#VJW>SSiOx;+ox4t^{ESUGg*CmO zf=x2L{zVWI)ZMv&8$O)`RXmvLTxvfl=MSDfF>#H&~6 znlx!#UzQm$0g=}cFh&<^aox_o?=!w5FmRLph=)t94pGH}Y1KHeR?RBhD ziR-4fquLv6tJaX#vY3Yt0npX>X6~W1S8dUAIN~ZLN7-T>G%KoS9NsaGPLzE3PEKMmL7+tWmW~5Z?rlBFI zP3EaFh34?n?^Tm7hffcG``^*-T7U@#IHlHO29^}JW&rFJ8wO}Eys2-Q+g;zst$l$1ay4exfXf z9O7DE`V%C7I5P8gJ##q?`|#D$N04k?`VH*v`}`$^c`VtB6X&gIuv@X)@UXGMn`IiB zBEeyu@a&r9aI6ozv~I7nhFe%bQhe{l*43zo)jP0 zk9i2S>%bg9XwYVF6#dG|p;ot?=V5QAa0SqEgG>-{YdTf*fcQWF6_EABjOhnXzOF9E z7=!zrsB2C7L>aP~``au2_=?lzF6tv~07>!H5o>EUgt}>Zd>CpL*7oRW$V57P(QvT5 zF=*J9-s&^6So_h_1E6gAsU4t?%R8=VBi+JB-&OdDgas%!?=TB%Pr2dJE)X2EbXqIJ zv7Y+=F28`L*BT<;(t|yn%_03U92!!JQFt>*cG@!nnv+Eq*qbD}Gn$bFC=f*fYEd@X zCAJvpkVKlVacjgJLE>vjqx0hW!;_$M5TnXau z_zB1f-A3M2_v{W%WA{}E3Oi@&7ln1(AIXFzzW1qLfth2q1OfbLcYCF^uq#<<(1vO2 zhKfeOYKFY`73}owDY)8YcapX=0SIvBQ|uh7wS@3x#QcKc&YOz9)}(D3pMR{ap$6o+ zU${LBa?~hXwJTT0c6J0B`JCS|bTo$vJIoYJ?!DdtAsRroo9He6Fdn?IFdZ!klkAaC zvl0$HsMQwBJ^#{`ot#cvrrVubnqcEmI8pX8Oj}QGmwE@(+X2mYOp&z|&d(-=A8Dql zLSI-@>d;KWEJlj)_y5c-B(u)f$OKU1>%PW#_VJ4@@3knZS~R2Mjeqj?YKl>VBWXl& z^(THkT7kfayAx?M`x6ra!zDXA*$K|~{~>+{Y)S8mfnUa=7aw5q8U?;FV3az0R248q zk+)B7v6kO&YefMt6Lk8lU=l-A1khYEs&&VnlSll343NFBawups^f}pcSl?fur~iw^}+f%eS*Haatg-4?Kb0 zh5}3s(h3D?28+4Aa&7D+GF5E@wu!%`BKg3(?OMOalG9#1$SHw+#9kVsa%XYrxOMh< zD>p^eb9 zUrHr(f_7BUbzMby=O!j<>%y!`kO?ER{?LBr93XAg@q1k^TQ{_^Iz4UF=%%A1!L@J= z@FjYi{uD`=NH6DpM7N(=2VOdVf2*v>eQ9u2#u2kzgDExv%l6GDIITMnJlb*HAr%If z=ED<`get(9*d@$1=+e2y*Hw_v+R(GZR7}u}f}6tO_St;|rwOV4GxPW}>GuNP7Iyic zK`^(-euj(w!J`FzDXXFhx4znT1QE+6xPh|A7XoWXN{>RuSE}MfAORaqHUoAQrPww< zK~-#DhO-i|v?_znxt$11c=h_wNK!hqfZIhE?E(IBgin2C17RZ`z*pK8f6F0zvz31oZ39ShZPWwhSdK z-?s2f(SoVku$2X#h}$@=bpWY4m`qZ{QiL;I7F8e6M6IAYur zzqEmxTy}+)uC9*0;A=vAakr?YVeS_jlocL4NOztIFvX8^T)Rv>rsEzn5Xf}Rp8LBP zt^3KeJh!YDUg947qMaP(plJn()Y<@DQ|90_C7_kE3UzOA#RQ3$D!FLN_cu6>X(U5m z7krG1zVp+VRQOJ8S?pRX@x3_0FCG_*=+bI0+ML>qC?K4#6VWSH6H0*)L=owtvuPUQ zhN+5!R3(7+17-5TkD2JviZ3))9{;+{I^xml>Xuj~(z5GOju)qu6`qL;Lgv6gFhOED zch1_mvn;%B$vqY@4YN{c4q_iHv2CB9MK!541?7aflQiso@D&bnxDlVCs)$g=`69#0 z`1$^WR#)~}B-v>-8B7(l4* zY@1Ui(BfTh`0j_Q)V`S!;}N6uKkrHB)vZLZQ!weV>jnCR?{7N`6;rlyF|YsO+8>q| z$GI+}9EIxKvi{`A6i*}eOUz)g5D9RXIMc3B5mQ=?hBsu zR2X0{T`di-+Pyag;~e-8`anLzN7Re`;?1d}0)fKZPTq=$-K3YOO0*xI7oUi)O4jD7ClPrPkbcGbL*Jf)=olv9 zpbiAQDC_QT-MK)Y!?aG~4Hg|w`)DRV+mGOzn-=pvxNF$q;k$%j#a5N%pSsvCr)iW{ z;dRz-difc7OM(&@0pp*FUU<}vw8RQ$@>-yHMYjZqJ51nyt`9vU!*|x(z1^QVs5y&J zbwX&7SAw;FU(Kfi>G!WY0rMjwBdtOksGBVv6ge-r(vi1*;HrdPbrd~4S2tm(-k!2C zy4o%|L82oW5+A4l=uY-vnrgJ1{W|pP3)ygJz_(>7Iw4!WX2L8-6X6<;(xm)FLbe0q+jOq`TC)w#~II7TR2d9@Z zg(vhzRAK1e=W*b4Zo)g1jzy;^0L8Wh)??<{Q9eeL+6QCwP6Sk!$42#hTS%|qpPRQ= zNS4wu%_vK3VIL$vY;tAM;ku+_sccbhdVl5=IrNhBmm~g69}`0sZ_jC4*zaey-+V}S z*)4%P+2dW&_EJ$%qu;*qR;%)Rfb+dL=-B6KW8;OfN1$SUu9Nq;*@$WXyYwQ+Hh>Q@ zVi-K0+ZM$|*mv6ND;pk*u43GcMBbX#szS`6!{tdWPM;G0PrQRolo8!#N%T#qOwlrk zRtAz>O@fYhG*x1$pjXgc+v=jS!Hi5$O1SDrAmL=kPSl5pkI~OgDM3Q61vT03 z?EUX>Lb4#f0s2cvA0zW*K3$Vz*#~)#sky!@vLym9vdt7XF*4SI+fA@H#WZ}s)+;tw znJk5yZ9pJPGhCD4n46rMtUsbjuwABLhG)^tR|JL!f5U0UY1Xb z%C`au;Gnv0ZpHL@jieQFc;;1sgTrUTx4`X~hh~(tN@^w=LdT8tY&akCYk#2@_#%JG z+sr@^N-VNZ_NxxRXx-G8x^j2l&;c1H+Z5shI$HzoXP3{nf|Kjv+m8;gGPB%aZJSOp%iV zXWxDK{*};x=am7&hy#qb0D|pP(Hg~X<dWYy7Tv|)0)80y+dmcg&b6>amihGJ!~D`FJz3L?dQZ^kuQn~3DJqGApp{Y zyFT^+qgUlzS($yn9JX0>=b_%-FcIW}DO+y_3OPnm8`8(UdKBB`D6IgaeA@rh0$7sW z9^hJU{){GTz@FOYk4C1NobIZ8VL!@|sF2%e)~JoG4l1b`uldUm!~c_*1_3J%!1v=! z-!MQgsjV?vzkByLta#n{FgP|g8}6x}vlV*%%)%FlsTLAE+JYN58LKLQ={n=13a^M6 zvxxXUTl-q6Fl#G@Tr~`UjqliSKxava-$|UCSt6I{g`68o6x?w?i-Wg_i5I$IB{6tA z?+UkHv1WTDA#xaYG)u}??(k+je;I_Z6-2Rvr*|VS*O#WHZPsm2{Y@1N4 z`8&P=+Ubez;t;~X+qODv?mqA{5|z+~`T=BO+owLGC`5@~Kw&Ao$J%u~RSHVkT3Dri zT~gSBY!mRxetwc_Q|KFs(b@99jvP@5O33UjU@y2SkayDlP|qXx>P@N zu87W|VZR-j?CVK!d=a6BWPWjy{jl5Oe_PP?%L6A}Cyt%uUUgLdEi?-{e12X$HI@BJ z=p0O~X4_K=Z2RPocHzd>)k5v;z`Ts=CMG$}sE-}D>C4_HK$m>w*36LyKCW>@O0`td zbjA?E&|Md);OaCvUD!_qrWqV(mcOB%hl`o8n?qPZ=Whz+7wyvT!?iyR{-)k>i+;&! zv}Kf;IP*Cn53}>$uO0T1c^RF1+lKL^{uTuy#ig-PKTQBu`=O7++-W|i|4rwEXM{RP zC6gX=+K|asFO^)Wx5q`zFAnZmT4XCk9jQqr%3Lh>s)QP;ufr|q#et{4rs#{oD`M0o zfh#}BZ^$ao>}2~JxEl@_%fGI<%=3H%PFhA)SBmF-4~!J>03nnt9l zzKdwfDRLQ@9>c?+1#6G+$wsLHJzm*iW!@e(@dDkaDI+BzagD+A@*vTDoi;8kwa9qaV znDM?ZX?deaa&OzG0UMs&oCFUl%)he3qQBP%-3~a!?az#--~tei7tb7!djJ=b*A3jHNgM z?Q4@`KkPJamTTB5HmxA8!Dcb=5}!#$J~!}^gH!Yaw~q%;HWHN`)is`oqV}*Eh)r`4 zGzUC7XCJk5t4@Mp=sgU}PinU#s@G|LXrtxTgAfmp5lmrCFb>{phDV0L%BDv#;|2)G2^p;x*bCkuQE( zr-)-p26kVucH^Dv&o^_+nET!`9o&RbcJlD=VReR+2KFhI2lXs!NE@%N>I{$5bs{VP zjEja4^_R7kk+!@E8=H68=q>UD`{)4^ zqk^+z@B#ae$9`(PH}__h_VdKSu)s?uPm!gXzZ=sap~(KNNs|>u-FuSPFp(5>VrHZ< zVkrgx=$?A6oZEN%h*aI8qO_;<)Z}AE54|~gYd1-fGF>a)+i#1Xz{{Ba#K{KcI9JCx zmkkuWGOf1?@PrXAy8A5ui0ZiUk9CGn+;R?%t1YyiKM_Y|%zA_Gj)!Zl%TSGoRe|cf zJU8n(UYzE@8x8$r-I_rxKWLLjW!#CDKQuNw?~z9a4-fa=`J+TfgORW23XC}ar-A0> zi-N(2tZD(VLUu`rHreYSn+iK)s=E5`%`~sY;8)GM)IjfaJA#|v=4xFDVkw#`88H&A zI*8TMdNuEPOg+SuHC41A)P|R(uE3$Ab3M-a{&NM%xZ8s*8~=cy)VYld;vNRrH(0Fy zrOY;+9{~e~b@qF`*v|ngDhx!~*>b2v_kA8e>7S@}n>~4`LyE?Tz-GFlJAz>t3r|$t z(7a~|?v-daGSz*A+HB<;j|t3JhG)+xYljS*Kqkj0l!$?IoLcuc!kt}#F1P%~Sr2P= zKfchg6=eM}yFU+#SslH3-@kgcmTA^iyE0mBK49nV2)D%@Y8neui7W2cD*zj`UY-Ep zTTL?7voBgR^PAq6h46(Vm(5-bZ}cbnNu=O)eQCmRw3Y%*Kp7hfI_OxFskU#}l;<_1 zMw{W>r}Bppbee~0tR~tCoQ&{SftD8+=P?a@y{5I#iuLt&h7Xm+_;+fl7`RVL@6g{t z(0b|ANe59urg<)gfQm8rx7MKzqYd{HuuHByjJM*s?FtH5squV)ig{D!k<>jiBZlC> zJF2_nS)|09ML)jSpou>(XRF%+lalH$JLMi1CV4LQ(9QsRto8!tr;Rc5u`?tD7c{ zYqjxa$&yNzjly}rzO44ioL)-1S&qW>Cmw+`BK1WXg8h>>->yZ&(_HHanNnw>8iCN1 z0oi6qQW&4cKPtwC`dGi2!nJva+r{#9w#S>lDoVXW*zNGkuRUyeYuPspUPg7D&8?_X zRWm$CjLJzcxx;Q0J|R1t=O1@F4smD^eg|CkWNlx8Mi8gM01%na&ZWIyKy*%~1Lyr8 zZGdGl)_W~$PWwJdJ=YRwA7ydf9e*jjte3}5&3bV6`8x$rj*PZtA^8xGuBkU#tvfzp z$qbCNCUx0*N5RL1f`;PZac%X}BU5jpi9U+Q=3q@cRO z*tNA6cF_GiL@|EAj%W};Ir-NgcAReRU`+Lk<{Km=u4Xo?g5q|T^>(&As9Qn}gLFh$ z%F`tv?o1`US0^g#Pb&++=oP#IhdS>8z;jR>x?)PiK<%3<%eqjyH`eCxb3<{0NMNOIJm9vX|0~6|7j#Rf!c=NY3|1Kkp;Twqx2A<;n zLQ<+2y@zAbf6JYY2HA#(G)n0&9X2%V8aM^euK&^_lh<$>C%ZQ9FChB~IM0$(@VY(w zB8^RRTJcq-(i!+NtML#u+V1NSFzdu)P8Lwg6aRtVU zMkg%=8gA23J!#dN*WBB3f9GrJ!Il}aN(7C*&GJYG;JLTRm zAMn$*@E^O> zCKXPW;Ld@<*`tWxExE=tnoAi$&9&B7!1h$e6u9a8Y<+vSPV1@))(nr=Sm>^}jy$`K zMv!mR)yfzUEB$u_$!f5J!OS3}B0&=%k=EDK5=8>i25miSH0kBB=W|YqGt)W*cMec# zIsPqBh=w-Vw0x_fzL)vOk_3^7bb5cg2-0VOw!mftVsdSHsP~vurWSnQiazA<2mn|T zsdcVa{C#rreg*=V9R?xLvIh;BC%IEPTs8iFo2sX>?Lj6tn0_&wjKWrwuTuV7ReOH zEbXx5&n!DX?tOTMw4;15UR*Q^3M zxoxhvfVMwgJ~Hsgammwqswiwq`wvvR7Yp%JcP#R4Son<)#x8TxgZF9bnOrn02cI&d z-&PWb#+T%f*tDmf3#di5LV!{lFiY*RT7!Xb3ShfVDz#he9KonDkrX#?UW_4XGpqpA z7k>u)W29D8#$Q0bmlc?jlW~TLq@~-B$VQ4{r%IPG+V2Y-sXAMVe{1B6r|cL@Z%yqv zUivh5_DlNPn@N?y+5vFTm7o^VdrKC3cf+^lJ;J-aQwHA<8VUVCvf z`-rie>D{`x(~N$}ls)=awEk@4EpP@`+a`)2cZz4v1YUClU8rPx8n&W#23(dEA0yrl z5`Y|hS~%8~t4j0`vH$^Ib%t3s%YMtE(vz+Y(Ef)ev6ctTx6J^S0(AuwmyzPj5iUOJ zSZ{7DC4!oi>Y0mp@@J-~nOL;-q}(5d2VPVyu5%lvfD!vh-UBoZdD&cKVdOi>U%p=U*P2@qG87jarTK-!dMG8Mza0K{|4OO&huZ`u}FO;<* zCXSINl@y+0e!r#R6o-yWbTLi4#yX&?hux{w8*k9cg2TjAX6E=K3P|S#KVs)t=4Ni| zs*4BUMSZXyPx$T3bk<_L`a`d6vpDk=@^^Xx9yn zBz(>R&nz&BBJ-42KD;-8)5co;?^C2@)Ye0Y9M%UoC80}$%C8w=`|IB(qM?MqVdZoa zl=bHXwd@Yy&%Rj;lPlZP7|*ACwl;Tm6ncSBKSV+_{684lKQ{pZ6q+_%0#fMcdvJp4>rky z!>p)n3f*yfvUGbxY>@S*Vto3%sLvl15$WmZ3Mgkfsw66n>c_G?7VqW5@F0k{ResmC zV>(?EOf!&!T9*1XPd!0o#getWsEAsQwcv(^_*ik&xDV&wy*-nw8$Oe$>Db5OU?Xt& z_-2y)s9~o^YxmjA!Z%UguA*(18k~t%N}MAjX&lzcj1y}b8L)P z@e!iV2Rc4rh`e~FS39wY_i69_aqYO6oA~s9g`<>Y0$Aqp(=u0->((|BWx2GnfU~$+ zbS{>=;V+xEtOTf=;DACei_{&8qr=OU#lq6*j9GOdUaaWDJ; z80CGNTXYe}ew3ekC?sSu^ZLV3FFI|o6Cld}A-3}qHl3)!@u~u*NtRPb`1;!r$a&{1 zs}V~R@sLQGE@d#uL6&WT8?eL#R|fvzWD!RI3DmgDy@FwMS%C|U(^^?v*_vS-7DsDn z$Jd7|3*DNsKCxxy1E9#+BlCs*hH#s8WR z5LBKy>1X-S!JVO8_f=1u)UHu~O_-+d;1LKBka&0uBcacqPLNluS+kgsB&aTF14L^p zrJdgM8%%NXtald5C}lvbnW%3ZKO#&?I_+o-=%%i_Uz()3&Ug!2kli|FzfGmY13-2~ zgzn;JKaNZ=B}A|J(9O96kGsA%ZmF#U4hlf8!4%scV^KuykQdPNTch1x%e&*vFH)rA zR8Dd3ZH2>qUC{kgSDZKrPeM#}Ys+zV!3~<2a&!CHe+w!q?qeJkRF7iQwBt2a#4l@6 zb!dGvgJRfI@?SraD`kt4(&*FEaIg0oC=o@6%{V3vCS?_>dL-r$E!SM83^wU=BH0vM{L5&LST#dGw&rUo#nCA}z5NJd1i z8m|!<1{KDG$muojhC&0sy|^Ce>xYq7z+AbvqdvmT9J($76s%wgqhdCsNXgJQ7U}AZ zg|1D4yhNti6qJ-+;z?ZnlcHbi-M&ooM*mmPL`n_x5U#UKOZ;t7vNAhfAv)a9j1Q&v)N{2SKIZLMCMoo5jS$9st4T z!EW6&{`UhI^=GCe%JNf@7$A!vVPFl_0&VB4Gc>KSLrug;VVJ4--h1B)Y-xY;qWb#{ zcfXjCZt1d;0=ing4JmhL^xYN{!db2fIDi4s1ndv`U!8mLl3kYqy>-#c(f23V-!n|8|R=;)wTtQ^uB8E_bb#Rh9Bo<2kVJ`8) z6m5s$+#vc_v7K$va%AUpjw$dJ>^*!HcsixC=xe`^5KKDC2{xi5H_xSIgYX&3wiYX-&RrnshV4d$)Odq<|f+Rt4|6iXD1}( z(%a5SM*e$Y5Q|$SG%yc8)$tBfFtJHb5%Bo0Gy#@n(YcgLmZhG{$6#^6^O;Ad_1kfF zyy91)>Hfzc!0i4(242RUY+MIKVR*~J3-F-2{jyutKEShadVN<8bzRCH23I-ow2{mHHc9zckHj>o z%kQG0i#M&sYQ7aIeaccevp;m8M1WXW|J8%&9Qs$`f$>7skdMBF901EiyNzrm;+Ag;8 zmVb>@6ifMP{yB(hPiP&0VcSLL3SDEq`>DS*hdBK^-b8&XZZC$Pj}wE{ekHYo8*=ge z2^LmzlG-tfF19lL;&q??EF{uqFT7aA9gMi(T(vyscIh(lerJ02Po=*{2D*;F`!?7> zUBUwb2s|&`!%HlKV)}8$J_?A-F%ohU4d1XovrJ=zx~5n@3yst;e6z(+*p-L*9{GNj z<$WpJ%iV;?oEFr-Xp5KxlGRp)uM-CajIn^qw(|U97xJ{bW0ZJo0b2QU5hE+f?}eLI zJf8|->Gntel(@ENON`PzsbD;yURH0*H4&X{o?&Ga6-GBjWdfD(PEck?x0Mw9%RuU=lL-Ly9?YEW-Ui6fJ0$1gEA zd($6&gG|(phySGz(FM>JI!dV#xlmdyI3+bFg)wC?4P?@**UH!%SV7+iY_hH3eu8h5 zEXB_}gY?g!D%{MViedq6zI~d_B-oIx>b*~e{=gTqtD`A1c5{c-eSgt>6UWv4fF|T+ zMARVKs}d3|MlXWSL&cP6X|rF)8|dO@sPlT?{%WCdw0JoeX=HuBkdIZIz-|g;S!!^! zouZpND^#ObOiz|=*OC(H2Y(E@>gC4)+J2ii_*b6@)Gbc{=jqNT73S<# z*KKwjO3zr$cSm<3L(`CS;{IoD7K|yoySBD$3`}ER)1)QHt2i0SBsCQZ)t`(2a`y76 z!$IeBlO2KASKDggjbeVxP_RO7^Y?;|m!@+xB z?|N-j$iLNl*jr#_A^#;IZctJ2VrP@O8APOli9E_aHBe0$+ys%Cz_a^7Tr*^YMJ7zk z-bHQ9Ce!5bzGPv?3w8eHcw@G;-RqPOiQT#uNTX`aP5oTlss8>IJusxp+ET{9us>#g z5$aH=WWD3ZwYz!>0-lr3;P|vn2&cVgo^qkON1DQPeEQ21nz)th`|^%6{nL`?rQ%=C zVl+?|0LK??4D!0S6MRcHSVHI&m1blbmW-(St5HtYhB1jtqn_%L-wdLO;xyQC`ibHx zo&vZol?a`u0wUS7R&>uX^d4G?_(H;x}xk27} z7MAW*aR5&cFWsy_o7z; zQ=@;2RbDvuvz3VG(U$ZlYqJlLXSXPRbuCr4sUx>BtdC&O*39)wA&j;@*hu!ZbdSdO zLR}uAPn`Jj4fw|m#Ia?8e>LxzM>I#jWT-Pzl8-BumN+BlWg&*rGyIqdOs|)wt)-l1 zf5>@ir<7@>ETv-n%Y#XtvO-cIFLThUjRqOeq#jbq4^wYAR?Jq^xAk#3d z%zF9rHO$H$k#W;(S=N0ooyUFMqvfyHn8PL^iWy(7>gvi>t zv0@cDv3tUxZ%zimC}UIk`OjNhs%k=@L^r!!QGU$%EYdybj@abM;nsPU2DZ~E*bo41 zp?-dI3`{ByYy_uW=98}1`Geij>Nt^? zP$kDN4chMUI9i`zKRSYg47Uoa%NIpO$w5j1;w%5B1;E0>YVsVtz&HL{IC9@)L;7)X zahb+n!s`8mDB?O!;Soy33G0U`o@~NO5<%~iyxUy*rw>(2efF@FcA^EA774@>ovm2| zVRJ#ok18EmWTPfIHpjqI*?aW5*G;<5_VEcW?GV2R?HO7Oc_g4*)5WJ) zp$y&)C0NGtZwiCeIp^6Qp3aLD@!!1rS^y8U9+2X4_D1LDcq_VWD$ z1Axl(xxXpK>pFbQpP{&V7|?Uc^u1jANYL`M(cPRmEUrd z2dK%Oha-NMX}+a}U&h5=pxz}#FRdqiUi<2o`@!~gV)e*rjc)<|Gk{apX1G|vr2_0V zBRs&3s5ygwdnfO-vtfty52Kcv+|trG(c?i+G*wtd%lQ15nITaGz)QW92Mom*VFec) zQbqh{f{8L(rmrNn&)pr zDS0#1SVj@qYpw=^w#Daf7)IyE**#G!jWUgN@oG=VbM!Ju(@=^q7W!{ks7~E-$vBn6 zvfv--GshJX;IF`dMqu$2O`t>Pfjuy3(k*&0zfVa;Me!mC$iAz*#3?NmwE{9A_ulvB zev9`i0xk`JPyie{DnqJfxy)H6URCtyF66;d*upeJEAvx%3i?yG-CQ|ZyVSkz-F2B2yWR1#IwIIRv}}6 z9C}7Z1b$|WFmngUG<=NX*jQz}|LCLM3~_soWs6rD&G8o9QUC%VfhN{?9ac0TT44IZ z0z*Wc!-MKuN#0`^qCo7~UG@h*zK6rddoOytakBTtrdvjdG3_3*o=+0$%TvP8h>cQt zCh_Nj!H|po$RFyFc10rIEYEo;vz(;|mw3Gx4(#o3^@Bg&^pim1hwpn2egMJYE55jI zVE?+~i89`>fb`VVph+P;S|~VE#G4D4%gmL=yIqc0FhgEGtES+(9=g9Hdh4_dG^J>A+sW$A{?}Rt9gpvNngH(KoACO=c;C;$HIiHP zwfYaj4MGK7k&4&c^`5H3pdC`?8(EQ>vXvq-T$r7O8bl#(sMN<3$9+k*k*H1T9}W>y z^tv3Rq@+~hulXhc2-`~oP@{t1zc+Ww3E>3Ny6j&fj2#MC-qE0K1q7$JM)@J!a$b|5 z8=|es*=8$Hx;0GkP%hH4ahe5_y1-M7RHe+W&1uC@jMn{-o8EFXZcrlp_C9CdB4OOm zCuTUTqNv_{gd*E!2}>`n0R9YbTH`vgNvHk_ltT;gjs2Yv_hj}orT%g_=-c(?^#CRR zC)3FAh;LFb#?#_9avs-CJBR(gv9ZGsG7v+Pj;`ePZPV~&9cz~Q2R1LgS?s41eJ@r+ z-ptIb`;1VBcp=c@@zCCtHpipir&llth<|w51Bx5oMnzAfl~$L5QA-lRD(?ewIEBD- zm1uFTE|LLGF&nz5qz17IPNas8j-d~Em@$h*Os;X5D2g-aX#D>nQKR8Y`r#P*2)L_u zK0b@0S5+*p1Rm|o-qAeIdPFfhbX9<}TqAX(3F@NZn26^7iMjNQ6K~wMkNdSvyk9OU`Nn;d(bSl~|T@V4@5NMCaNYzx!d$ zJ9F^H)Nij6pU5ylVaK9?d`4WD<d=+yh92G2yaP%3hSlP=_)e>fihOi4RV zCj}|UBw(BQCXK8N;tX*T{gq?tt~V>S9+QMh2#LQf65bAg`sw`l@z@}56Jr#qmjZ@| z^2}dafxVWt9F?8258nn>xfeal7G-J#3&g|M6t}Z#x6_gYFthNAzP3 zIouyub8&iL>+4b1kI{Lq}0ggk2dkpZvC$Wd?yNUeDCb>>0N$+3Ua@zUNAdb{E(9@6(_o z9%8}|gE!CY?~k+|J#?H-v3}Io8x2u;-;k!-SiMKn&ru&y>hWFFNV*U?RRzS>yWwIiEPbSwNDtF5IW&K;|V|JU@^DjSJjzl|(eSLz+@H;^{ z=t1miAX_l5Jb1RACZdjIV9beByN`(KuJ**kafUVJ&moQPk<)<_ zWOJ1Dm(z-YFq^n%bAzAdFQ*ad2Kgz>w*(0$;3RZ0$&lAk{2ZWP6V{Ic+@i(fyNA2p zS3w;rxvHWa0ZQhmpao;Uj*?|K0bYYgN4IUfoq` z`nEv@o*rKW^c6dwzYo{fv>u<8!*I(V6p0^MX|fPram)@kqnvYck77MOI)vHq z4j+i_l~Ikn`8X3Vu3W1n_&dH+)TtSa9!a&(AD#EM;u!(K5u>++Sz@kHBwx~0u?qi` zN&QV2jAOThLyE|+t{~;1IE5~!AsXSsLH!&MidFb*c$4uXBSBL+1gAy%G=Ps;38G!I zAUQ>71*bQ!rbm$X&}NOVuvoFf{S6qqUKTC0H5fAb>dR6A6V86Z9x0XbUTfZzYIene zWq<|YN>8KX;qwGf21b4Sc!l%)NYv-N@6VjGlT+=C@v+jEpFblHO!`I4^#vM0_ak4S zlio47<$7be7mU`;gR@MM3u71kL>0`@F)x>u4w;smu9=D7YpUf;@N}8bx(43gBkg?x zN9KI@IJduE>hyhtDnAZ>uv6HKAtfhQU(ILIlu;2J(U3c<(*joHyy_*MO;VFYI^?0v z0M;I28#P_(lt?&R>bPH;9Z_;v;`8umRlAH4Se%$}Bz;cW`sd79Wq2wO0@ozGqCpRN zjZVF(Nr;ckA@a>@>Lc>nMzfLC^7^F)hcpzz&OK{VymFY;AEk9aVk7M})0){j9shi^ zQ47O86gt^#WV_)*+CRV!ETrHsOj)UR8wR|Lj>|>+(;0InsL=aOX+tOT>YIH{969Wt zQ-OB(2ilW+m>?od$nj)?824FPqp`O>%bz1WCT$`Q!Tn)tf;DYfqgf_AB+ZB}FQgxtG`A5n-?MlkHQ<(C_QcTybHxyp?~Rc-JuX~b-Ng&B za>cc?5$ldxw7Rv z)7aAGnBN2Nw*xO0cr7729sAGNHM@%c?k)EUVig**{q@z1hm{PQ8jEF^(6dO~dr38F zd4u0<^wH541JN!m?lX}iCiGRAXSDsAj~VDweLufjL}Sh*&Td}GMxGl7mBPZMh)Om8 zeMKS-0*`8sZEL>3@W|HUVx<^ZnZ6_4#2%W+71{{y%nHBBTF||H-WlAUaWpwTg2?}D`kwRfSL2D_>=^SZWtyHe za~dIcaQc_^fvgPUJ7qt8wK9uxSokaxnkatLK$TT9t9u(L6!LPx;sO#Y$QlPB@FhsVV=rm)bF53egdzOz=|b-VyZeLY?M$f-Tx7~R zMJBbvYO94=d>32>y}}%n&@Bgd9|eR=NCwg*MCazSM;vN-}diDT&>{&4!FQF1TV>sV|ni6q=k?pW9Q(|LxL z3dygB9Ue}f*9kcg%`$6w&RoFhJLsJQM=Kam(b-uCh3s$I_I=m`7REe8QPE8vNrVs> zq#~TkC+lJQ%?3dirFJ42i+#1sXG;aAKh?e^ z+2h`ws$w5_bBN^Ie}9oBF+eeW{7Yp2^K#EnRZ~+=UAcz;OpzoJdU`~07n2TVd|FmJ z#(HTnPSZd}+F0O1^Imk;OJlDz*3gsb1Vk3Stjs?HUtVH;h;{#0UO*MLutcZw z1WH7mnuEP>@1WFKGR=b~jiw?Py;fF-A}7c}%^&V^ZE{^{jMACvm?U}1A!Duy)tS|# zL9sOpJRIdHAbo00$(DO%-EuoqQv^`>!&40n`QZ0`C-7 zLUWmeJm&hN*Gf*<5-T#y;;5-)$AtA$SXrn@RZEcw@@_`0^P0kEdLAvyo@*#9!+-1| z_TYS+MjeCcA;40VW=BkY{#to?!8!sZ4Atlp2CLd+M!T+COdr}AV|eohuNSfu@0vUMqlY}9e7s{ONjA6F0JVcMDZSXphLz5ieVZfD{79YJc(u2i%uBD(Ac~-m5bwrsODb?&3 z8x5*S%-I6!vaAb6*^6%<$w1_;e(V?yUH8(pMoR``&J3Alvzu0Q zyiAR^E=@1Sw^vpDff@kCNLM&OWd>XpNTY|jdZG#YLd@coyJ*zI(^zZ zl3t3?1pi$s7&gsrbrhUs5@avZfy;iYgZ=6S4O7=Kfu4uw+x^jcT6!yY+M6G3P4n3M zx(3KDt;J{$X_Dc~BT78xL9J$-awUj>>9Y0cdI@$;Ig|#IFQoqW+DpDLNrl)Xx-z%9 zwUP8kEX0pDGij-Y+SGTRW!(tB|5{+qW%i>bb*~e(3Yx~bo?Ae+OP)y0(Ixl)nEL9l zsJid_A(axO6_Ah|8tDc>N+f6K?vxr*Lg^4BhHj*0Xr!g2q#L9W>F$#FU47s8^Zh*! z&%=Lk?>*=2z1G@m?_)-&tKK}K*PK2C8~z4M$>8Gn_6zrRWC!^fE<=$A#!xPB4`c{y-Ba7>sTU0p`*8U10xNO5o?4hO9i-^%}IX-F76bnWFmI^_dnWBofM(i}U(n zA@|_njX$B1`^k;b##91?ePiS5Y$>9lY@{iLyKUe}=E2GhXd|K>L27AbMG_t{J0;68{iJ05 zCr`T7`l$W#37&XfP>nR@G1j*K2_Sci;cul8bQWmV9}^nnFdp;)R%w zRjDH9vDgx0<+4p_9L3by3K)3lVu);yF3e{shU~YPW}N@7@RuZ$-z)f&B(kH5=9pQ% zmZgQ6+dBI5uwR$~1_F+3ZtmjsFxLA~Ijwo0nuxzFq!G_7>G#L)pz(AZ03Jw_pejQW z?*1a(57x{zLFkVe78DQk4}vQlyA!>j9F^)oKOn;srM8Eg9~E668N*M65t@%y<{3|B zh|O@e`=(sGh6<8d#&4;akO4s6!3diM1Cl{2TU%Qvr;74&m1piA z9`{w>+9q~)Z_TS%Q%VXhW@CbbXW;M(iA&C}htgJsI~<-8_gBMfp=YbIKRU` zs`oNiI1AMJ6>YfNa45EObiWH++#2~jD41jc8Pkf7q#1m1krFSydjCGZFf(K;XQ=N%YZgz`ZDP$*)k>6@Nh+fm>-*LcigsYbME6{Dn^Hxcr4^+241lVm ze9h;^Yj52-E(A(hzv7P|fU5ERb@{!wt*xTLW0MuCBbh3v4U`WfI!fghFVr6IU;#m} zwwo*aR;`|~%;5LtN>?OMf6dA=+T1(4v@4T-`xa3raMr8h=Q39d3~h5?YCX7>*tRtN za9~kZ_4!$MOUI?*kneLaC?Isc#nS4RWQ>o;gUHIgfn763G(EHjPFWjT?H3KQWq5}o zUx)nBp7E7Dvs|pLzA!#my)n71g2Cv~#LeqlsC<$e2KFF_#7<3~L)2E5(v9)U!k3(0 zhEGs08}98qmjiZmYpSbHR=Q5cu50Pz!&iJ}Uu!mJGi<)0HmOh#v1ssyy>sW6m-@l0 zU9P?Ea3)Y-wW;!F-->CLasj#_b9`kb_b?N@6yo9xH!F?s!*#M*HY$29z)Ix<5Z7wG zT73%2cRmM;FYN4+UZm(X%$Mr#_iFC~KUbbNo^;M%^2{cxFwrO;>~s}bh*8JjgoA-p zTLAG*9=>l)84#$Nf$~A9gj`l@rVVjM5T{Gze~AEr%u6BH^^Y&C7B5dE?oR;T30%2U zjBF+tgfgl4DV&gRZaaQGuY?XKru*Iwk1m z_T*6wpO$JFX=78~l?Fa&%0qLK<@ZdvitlQDFqk&q*nuiE2B|Y)9-FjAvyTZZ z@Dh#vWOO60KtrTE$?4J{VQBOgu8OhzJ@z>O=uX&>y4u=;9{ZFwkbgc33hykX|M~#M z()E-;uw#DNNp4}GUVcji@wHTCjvNOyv`6xt^1KV1PuLW$tF{An3s54$5&6pV;yksM4u| z$0+|;H2@jIuHfGtpyV_FrG>FNGqpqiaNFD10&ObGN@Uam)dfA_D8^S zIR!p)3O9+g^ZhcyCvH-4t$lmuzl)G27%v3$nH zWSj%eH2hOpG}FX1KW?-t1DPhurhqaNW_|b7u>J2w2c!NCy)|Smh~|$ZL?9zV7mAJ? zDV>0QTzw!~D2FQ19#w~%N7sd&YQ3iLYvp}J4R#x9#nVYqngCXJXgGSr&>6=NRUrIz zn=%MZTi;EG)!Uoyw>N=F@%ryc}~%Wz0QyJ8Fq>Sf{mc@`oMJ9a5= zrf|Zu0ygEna-n}m^`Pf(ni2S@a2lSCsE->QYJ%tG z_XX3dmTL4>F240eu^w_jslcVW)$U4kehTbWO7lS% zZoDxdvD9>2CX8`j_OaflTBD_a)dX@K#>KN3cYAB7<5~}5`-w$-xuqa zfmkBHfd6|1dqyyiUWU*~x9f28;k+wn5$n@HqYdGJPc=Kj)uR4`L*U#=Vg0^QqL3>+ z*!GvPQpg7kW2GSAQ8RY@Fj+MXt@*f*GKJ}8)4~3X6hV#vv;n%%EC}PSr^@7r02+I( zHNh_e;_C)cb^3g^gG}k{T-=A!*g-_PL3NyWhgoc`b4gx5lDwE1eY6%AS}tE+K<`#h zAa)SYO=p3z%(aStG1av)QJW@5()znGt{^BwP!}T+C5T>wuzj(PqCXv+QuXI@TMOxG&ayt^V?*PhsI( zaEJWp(Q7&HnkcYUM(LJE?l%Fy4T^2~?x^Bo9srg zEWP}CYsozQl5z}x3+{54h=suBhP)Nuv|s8V(Yr*AyNbIDoactH8wO1}D=d$90HaO~ zpfZqCh%jqG)qEjML~a&ygxhu%(gtsd$#p(V76C%gRKG66NPGwrXNIWD>UaL~uXSdn z>g!6i22g(+p@nqhQe@7|7pe!km0O0~X1@hNoVKa;SsUq|(7*=G^?a;Q`-O@{_BO|(pg{pS)-pHNVYMrDsa3NOo=vQU@tIMMoi$1o=4X~S%+*OjYX?z|Mo|ZS`iuQn zoV&5G5Uc@HuTW(-gb}3%(^%0Du)&0-AAlneMpo8Q=z44MY#W0!jo^>;`6}h2iD46y zwKa0?)9Y!cyte&)=KgVp(;-;<+w}X7jM_+0ROc_>z`#C)Sgn|KY9kcJn$)zU5C4qq zK51NvP(w=BuOOtxMKk3$Im-tCpm5V2;#t#`h##@AZS9R)u}cN&)%>eHqaP(Z-Q92| zgomMnJ1`%QG(1|CgC}USA7<~Q3P(WOr+_IP`Z2&LiJb>JCH-PEI!yVwr8~&5>vu#G zR13y@{QL#4!MPj)*ik&*8`poRa?kw*^}%H%)p5luH@nGRB_=sPUes(43ybMT)2>~v zLZIiV$z!D4Z6-rnh}%3x$AYPYFH(Ed@@pinWB$jgKcO5RmJWk6YOCDTT<%)ejj6>D zHINg`0&@4=vdThY;^ki{R?40fkc!zkg#BgNM+W4x9V-Ykc1#-@XJHbSUUzR@wv5d* zE38Snbs2!X^^8C~V@GAOgNR?erI(ZWnSdq>EgcZ#r5dWv+{`sQCy~E^4Z{>4F|^YU zpcR)mxoAq8b&~osD%N}WhcEZ#e&@aI2co_XKHC#p8vCUPrr+MsI;hYo8>a^Y;W2$? z|3}@#eL?`URp67a+)yK~kBR`9EL+8Alv4V|P}bRD29?zS7%MVif&Jp~lif8bfuP1d&@VbyIT(}zSP9w=s!^gGr1G!a zC2=ty>z+_)FEVyu>{_(q{Z#=75fcWt4ezc>jqcCxwKE(^qwoCX_BiK2cah`v%RLIq zLpM{U+pqWl<{+!xecA%eyOfIH{StZpgsg3$@ zo|-F9D}pk7=qz#`^Dxom9X2ykd(g!vMi?g-dldZjZvrQhCrO*m>m?CMGqtRnkcAuD z6MIr%#82{DijMIFnj|NC9&C=P6l>&)VKtsQumh9Q{YGz#jXYp77E7N&j3$;pYm zcSV;xZ%12x6cC+t`+A{Bx2oLg#7Fb7`E{0Z3?&81NY0g8jCX@Jn#J?bwj`+s3=d8nkYL-K|_x2xoWqquRWt2+4#sa7JZi<_UC0K zVJ2F1qXL4-$(j4SxCX9A#2R$+uqgx(((bzPV7fwz&XBlDgUaN(topDlRSe^aswriS zQA8>!8hvR*n7D~~71!L~gQ!MDM5IL=NRmo{B|2a~V~nxvp|ks-%MwYQvQ9>E9=iA` zmqc0*iH_6OGoiCekg-$Mj@`x;Wi#Pc%p>miejbvB2~iDubbX6rS6)tNKQ#-xI%^Q( zMK|8RyX`pJd^kZdg%U>b2z>B3z(B-Z^jAJaD7=>Wc?o11Fo$fb>o7P)AcItEUZ^5< ztM>X+qOzcT)~Q(ifH1wTjg1aP5o#r?lxlH@+bRV*DG;*k|fmw5#i*_FruTcuQ$WTGLfOuhN z7ks0u6B2Tc$lG)VK+4rmd!8%SZqR4kUz0AhRaKt4$j%S-p})#RJklWs;hm(VFId~| zi1-lI(BM%-N$zbaTeK?N`1Q@o)MM$%tB-ii#eKBJHV~XzW!-OQkEV#I9>|S>4@x z4T{A)+?D)3ycO=>oR_(p4M(Z+CzhKEz7qf4F7u(0=4m`3bx5H3m&2wDF#qzTX-@aPo5o zMn$(hS6B?yfD_$&NH!UATI-edqcx7pXE=21T2jbY2rXZ@vG?`*M+&XU;#VFXVp(4v zGb>1f0H*t?gqNkGsLPnaETe|f4!(TX?9*>&XWC$8gVmO5@kEwdzo`=hvxCR7EmgfO z9EXh}{v~inp3**PV_p7cAM6n3juatf5I!bM`F}SDx*8RG3_2LVEv>Aws38p0gICm5Jg4?s3b$AYnJO+QKsmdZq3p7ALip61a3}$)3n(%0!AKcSuMvO_Vxj)r;w^FVYxm;3upB$|Xki+P z67Zh>#Rwt-ZwK4;;vkZoCg9AIG9X2s{N>9%LbQoeh)Gd%mF+|oagL$_s`$W02Mz?3 z_+%%t=fY;poX9lbGvx6+b4d-JWPTe*}0^ z2Z@+M$XpL=6m4_1h}fn3Ckzg)pZq)%&w+S7-Td!7c$Pf8-53hXl|uz`RT?Q4+gyWR z%{QFTsVZ!@x(OqONR4AFVB)T9X5L6GM^V0O22fo>!KgU~X8C^{3E2LSDdIrjCxHE$ zzE8`sj=+Frgb%gHn54>8>@$$W`MX2#e%W-$mz5pAX4w_1@eu&o$@yq=u+~5=fEp21 zu<=}2C(z zjr!5~>pzQM&)jWKf`9E`J_uykMv}iA%-G=ppuT&;;_pTe>B&f-)4*aZTO;F*Cq~x!J+5 zCN%mwX$4-yw>rPfz#PkZ)5;~}b+|qV%CYUOrCvSJXh?TuZM$-EfsY_Sp0*IY8fff) zL6Y|a@YwzCWl4i*uO2u%|9EW`Ynm39*7n4a_CZ_RX$?okHZBzKr4;AY z=C+pwo@bw$B`W6U>NG8;UxVAf41Yuo1yav*JOij5DsX>7U*~WXX^X4a{fFy#lZ+bR zTgl;>{ora0C{0IOMk3ug>e3alN)-u?M3+^ACj%jx&^@2S<>lW89$vj+kLp|+PADi4 zv&4^pZO~HqzmwviX!rcRg~)WELgn_Ioe@g+z6osg2g0Rkwn|?dAkCk1~|s#EN;zhDlCF;=c3yc>wXHF8x3zyfluNt z&Ra<$0Y#~Opd(aZ0bBRj*v+2>*HwHl*|8Kmo32zb8R5RrkXQDp9^Rj!qt_HS7_Ez- zAup)kt~CK!`{9220{&Z8d6=8?g`bdozM*WM+9@$qQFbEZQv{q@|1D*eU_RT<%g2~* zyPDEP;9@OY{8%G1L_Jh?%7%&`rL}wuakFQa0$gLW3n2 zjw0_4j=>`r?8wb&@vdsR%K`23`ODbwJ-kORm%j}-U3Jv^TKHQLE0b=<@SpmrJO zdz6K~)qViX3ae}MRUk?kfZOvIV)2ghY6D3Y`w1GcG{h;ZkpMCD)_y(-z0>gGyiPh& zIkWHie=27uV|H+C+w#zv;tuk9N9zek#eu$@br+%qcr3Fjyn|O@225s6utZKDKehn+ zDlTi(F!vd}JlC~(VF&pTxWQ6AgU=8bkpR?1H@zgUOcqkyrvVyekPnN^0WMrhN!S~X z!-INnG#1thbGpCi?PR3 z2*&>}IHvXj7Ow^4Ng!TJZd^~cN%#olG+_s1yg>`2_S7}VQ7iujlMNc{Vu9&|sg`_J z-)a(}7=G$ys9EA@BW*(VBRgrXfUc+o(aiNGOT3g78p~c8XY&QaezwqEOn5WZU`E$_ z#u(0nJ7Y|;s0*9mI#03eyT$Pys@<@skUXCkS}?ZQ`;qfnS4qbXK03!LF|g3WE-~?> zrsP+6XS`#chM$A7pWx)2kEMe$83KfB8yD}%jpo^w?D;&w>(~F6cLq1~maYqgZB6O9 zvRxO7%TsL>PdNiF%UesLd2PA1oiXS3g47dOZmSD36qnSD)>mXLlEaoIkwLk#>q+-63JW{l5liWh+xrud^uJ+8)f zsMhMlOD+u10oN3^odkMq^e&rzvRq&YD6CVziZJd6l)6&EXT_&sL_ zY;vkAnW!5#e6eB=klI;f5nyNcZ;vQoQ`3xuoKnqhTv#jusUh>85Ziqfx(G)Dy^zfEXj_5wW@Z12T)#vBLHTUx?3OL0P1M+9O;!nF%sC*^-yShJR$K1p zKTLi5d&mH^xHo@R=gWEPu%v_%0WWO(+^_OXn#7olf$1RdyGSEGkJ*o}ml5tyDG#}{ zg-ixM0S8!5!@Cgnn=n_?bn@mJ917H+5&a)gcOp5c6O>Vf-@R<4SP&n-Ih#Idtmz{v zWGRl}p3%iHUMvOeU?Mk(%e2f(k0%h{9zv9AZxZq}(+ zN)2kp{l&sqo6A){ceVU60QrwH-2Cm)MHTRAF|1yIW?VN`L&IMG^v<6G!-&gNZUH^V z&+OMIpd(;&g4xTi!%e=kylMa7ARvvD9_=nF>iA#2QC|PU&^`lpCn3y#TmVeTqqCyf z^+MUN?Ty68wrWl0zdB6N2gD$z1!cziJ06d{uerBPJpTz9-z{nZbtTfmO^(c zt0QoBm3(4QnX2%pAD_fBt|L=7PCOw)b-t9lSOk+&=Cvrk`WGlln3Dg9zmZ)P8L&e( z&mhMy>H3PMd;My5lux)Z2*h`5w?^XwAm1NI3|gYxOj;Ruln1JGG!mhqj~HlbQxbjB z*I&!tK+$uo02G3%jSY)Zu=(|Y3!|%_*>g#I?7)r4tr4;qpKj3bgMA3!wa3%{V!aG9 zIk`SJIv}2@^>g&o0IQAb7a?n_C>C*s9R)e8P?U$UMPG^f4xOZfXVrurx>Ct39=WsO zD^w~Hb9w{9BXLKv$zMY0Fk1UYG6^7wrl?N9wXe*~&{9Ns1aaex@FTCxl(OvGP<5dl>F&t#TjmChh^ z_{<|B)3W3mPrP~l;gB`Qsl2$g3yKXdggw8ulX2(^7LwrSg!eXq+$?yp>2!Y|#}7L) z6G_;?Z=A|aBqLBTvnfglQ}qgMg6g0s-C5!bBkia3E^nZZ{hiJ_l0qX(bqtyHe7*N<_lw93j`byZ-!8M8*-lN&#Fi<7I z45XFJHKme0wF1VT^;RF4f`s_r(*J?sz_MzkI!aT7A=EAZ8FM-za3j zDAHDpQno2^JFR?s$~le zaT>@KeLGpPDV@C!egk6ZaH0o`VTK`Q`_4p-;{kV52?R(Myx9d{dV{0-Kj>=$N9BP9 z$&%$iTLOJl@KoMdMdjk?SC&@DN69UHBTP)Zv&P~X;yq32{J12cz#5<7vL>T=e_*^6<*mwjlN;(60N-=9a!?+d+VD?vzLst~iabbP-y()8Hp6Br6LI@0yG? zwu2WH1ET7rp+CL>=+%0z7bd;gzo544d_wKO1djVnh@vsVIdkU)`h zqT(O>xRgvhu*26v@t^FV$NxqU(w5cOwa5A$FwE9Qk-4ar9gy}0oK97eQujR?W8nT=AFkoLYS ztHES75V!l;%S*IS1__SN)V_M(<9^TqmkhDgQ_;*L#A1ALkFBp`-i4 zMR>``xxnCrK`CjZ@w7w}C5$A2W#&yj8%~t@nD;uy(5LCs=LTl#NqkHRbP`v4%=rD3 zpD$@!UJZ?`r8iPs!N~w`d{(k5r+oP4FP~BljpBAi0hCEH196|%s_)FN)6_{-?BHh+ z7`+waJwM)bc#f5R*6-gKo;&yRcV;377(w>8v$@}XH{MHDYrP)A7dK5ztt*$Mbaa|n zs6!}i**1)TJF!~_=~ikBFqMlJ|3+^a8EXgNQu8}Q%qmGHZT}8pR*5If9tXl!&)mUs zMTE#sdT}meDo?yDU|8y*xU*E`pS4Ez;Jz8kCnm zrLeQj;!(qp((31FlwP%}5O!K_TVBoO3fCUO#a%sb&Zd?T zs#?t1zt~N`3PCvwOgJ--fZMgL*iA|a-*F~U7~9(&k?mA>Az*TJ#kuu;w71O%Eb)yLB{zWclWBU%OT3c! zC>5Nd)~`E_*ry;v3jz>8%0HDl0vU802)(M~T_($;oymqFouawznUK%wSPgQd2>L>J zbvgy*rl6{7iQ8kuYLE+K`>>&CuP(m&4G5bq$z4n{cY6pHnwhDY0C3KrBqYJC@#NA{ zmOTB_j0Y2=!{+fhNGy{4FF+9oP*J^l&v2F}wO`Me{@?;|X^exGmj2qZTD{@hK=_cA z3;vzwn%r|c2{kQwUiMoiB2|5$SfFA%g$U^eG}y^+-%xds|I+nZ<99c4jup0V{_K@S z=DQ7pE&X!hq^i7Pp`j|#fpU(QYQ@QVl`crFC)qyM*(YWkG4N0#MIX9hD^B@0KOe1Z zbP)Dq=zMHV#*`9&5CVAWIAfrL>5^u$E0- zIBbfiW&axUhgGU;db!g^5*lc}#sL&6NR3NS*O5b3*7MXRl1O?|sekFUg#`LYhF6i} zC|!;s!6$`3EmPL_-}p3-w7_M*%3ecNS>i^FR0Pvh^%Fk|b zT}dBalq8q2YETUioh{2}zc$}NrusQNRr}Twi)uiB%&X1!J|apsEiNK100nR7Q8{U# zOWm%z-2!Y*+&&dl>sm&pHK?E$BE_ly;M2P^h=n?tc}`zU!KCKa=4{r9X|yi1&SY~6 zd}ZQ0dLSqyB&0C)pVrg-r*7Ey8L0D*-ZbmpNW5dx*4ngl(5X>N6bnr+W@KcZ0uR2) zFVb>X3*Dw94|AYCpGd~WxwBgNt}^uE`dO!)-1Pp+L)>_%p*@Qs>0YWrSGDT`C!ruv zi~?9sWQBzEhbm0gjmA1GueKgUi=sfQCjAdDUF2$LdAI5Bh*n(6K=>gfANN<0$?lPQ z0fN9Aa5&}LFhEZF=5_v@g{#?{`=@N0>@(*nH8rGDnp?A3p4@WmI|_rklbht(chxWd z6Y)pg|3uM8!|bj}lT7XUv2Bi={VHC3avJYMGgMO^Oha(sUrUO$bh!G_L66+_{Dsdu zD^A!@hB-DaJ8iyOuoy${LVK==oxg9(Yg5@}KZZOwkm{1hduDHcwbWB*$7boWNCS{`1={6qlpWJ&M zmW$aT&P)6R1@8^yw$${Qfa}{c*1~QQpl@%GACd@lM?J{?MeZ`8P+1@&|K_)s z_maGnLxo`UC=JGvP#PwL2DSXMG3_hMC&7XL&^CIdM!UjXvVEPbR2dgjk{)=uD{nlM zvMF*+_1P(|>m;_$gET!U3{7k$>bAJ(PlU~_J!96W)W;}C>X=lxL?F>MjYuAU(*{-q zv@Up`PaiAV|6?@zk&PH=K#M^OMSHx(-x8$4Qkc;!8>!!s<#c{jRQHP`m+~s)4MQRnC8PgNJ zA1G+W%uInv9JH%XP3^DG8#MU-`Yu?ewSWq+%HX7>85!jxE%&1DNVYgzsDW;h#u~+T z4dk^UhsR=VhWEi9&tV4W5Wr)-@Bo-9$N-|y$;XVumg zDE3s>EB5N<9&t-Hmu5Yk`Uif5DYyM!tx@ysdYe`I8cxic?rU5PX1+{QWvO!K^>#)^ zWhIxy@e4;0k>gzXpj<@;#&ozQcusYa)lP{Ac4)Ej{n^pWd#ejdaFdT?9*$G+IEUlR zuNK`&5@xAOATc@sb&cGpp5J64KpWzHZ`Mt?C@_)e_V%{gQKT10@O}#Va=^`O(U6@! z8#3G2o88-O6`*S%4od1oA9t|ka-U(dPpk_!0m<_uu2W8uY6*Q_@+tqVkrl_pUAiZd zEH(a4{FzoEDBz88I5$YCRxG6-!j9zo$S~*rXAu#j+>#5rvj4@3N-T2fR$gA-B0+?= zcVm{%{vV=zT(SS!*(Zi8nE2jksV9nem$&|TyX2O)~#NuN{%p%cw z7M=IkuU};J=Y*_)rOxLY=Gy}!WGtve3dkyVaQ}GR3Iq}6!h-&tS8ES(AQ7>MIj+v6 z@h{{wUt7w*HJ$&Hvmer}qyy%|-gu+!t*yjRz+Cdfy219*4aaWt0H_V+(J7Z%LKm3{ zwUt6!DK*I?Wm4{{K9L~LCv6T6$;ED+%*;2PwTT6@COE`d%`c*1I%O_03^e1FOx1#D z!&X?@Q<+D}TR*w&Vke3c>gS8|Q)y;-IU|~FsIk_2`|+dy(rGF}mw>Z)zM`!4@mcWyod=cp z=kKE~%Jcm7!>t(H${BckyBF$Hsfa5HLBR|jgBl{1z|2`|~I5U%sn zu6Q^1@V8sh7r2|lD|IEJc}tf0d%i8gpcAU|Dx31|OWUaO)O0jMFL9%9Ze=^Kzy_T( zbkYoOTV9a^4TC2Ez?7f}8QALg#|GWDST%N5kVs$e4q;w9_!rDW8%5#HD|3#E1juaV zFxQlQ(>b_kx50JfH~<9`3B=`gFi8O5VfSW41MNdE!M5`b#i)rjr{_*YJ zIxdCM3)AJ>-4&X)uMpf|`82UA?0uBV{x23uZj~$1)H+@pG($JzR8uV$N^BHt=bE#; zY(H|!#g|r}Fc8*fb%~?sMWX{I`0rklfU?DguvB~O9SG;r?v42K(rHaCie%m|b&Ub* zUM3(66@1=HU#fFRYw`<+O(@{%rlr5GUmIF&4~$IJXK+j@#3e~jMVP>pKW_;r9~~r` zmVzBdK}9wHxH3O@zCMgXkN)_PU$YFg1JRDMi1Qp}FVN@N6{%0sZ9F+5x(uk=-QC^h%7y0-4P{0QxFQ~HDx9AIp_@k>%pw@t`~@r#{yFjl zXohiZ>2BCHq6+WYrqS{uDZ>ebkVumRh#Tj>87gP2Ko;o%{r9Z`xrTr*D5&J$)`7Il z)O%!$7qG5CE5Cybz0)&yPFyah5K+%WSCE%efHRH5A$rus0L+VQ=9Q_ zPQ>&}>2#OcqZ>*U*cttbWN$rvB1YUph_J4Wl7eg;Lv(Lh>VU? zWO%J1@^V1!GET_{1q%(CFSj?>4Cl*)Er-GU#I{?tAzWQok>QZY@;7yTwccSz!%t#9ddP%hP_0>aw%jf$( z8$RS_Mk_&iLeo*veJT74U+3<9Y!>&PQFm2qlm%y3RZ__=r`e2%<=q=Lf2PDN9vo^9 zQ!mE=isb-yadN>x2V!&@E1k^pVIwld6xCF0>aLT=_!(>Op1q2Sw5W`1VcT5#?It(u zG-H({(LYBVts`2}^4_jzMOS`qXy6jT^WiOEXz;IY+LVGR&@>sbn?q0} z$xBwfX2grR%!f1j6|j1I@t;w?yT6?n${1q=|FtI{?RrzMyvw1QhbRCv-!$E<6#KA# z^6_mNQ0x3heCsTb0~}p{{I=d|pLDSqp!u{`m*jQzD0)R|xV0#A0fX4oUT9w2+@Azu z1x(T^l!@J)S;dE>6kpauz;Z#yx}+}2u88BRs^7JRnftHtnlk0BA$`^T{UJ&>$BW%| zo(!2}_$X{?WvnB{cWq&SyRex{e5C;d5Uh>Nx%9-O+JZ+e5T2B;{`W0Bnz+!wz`)~< z>)c4ew6T7&g8IIf$hfCdtPv=vKg{Mplu7Yi+TmpkQdD@*+pW|7B#ymC*9QS>&$X~} z6a^r?1I2;Xv@*Y2Rw%fw=AvuB%O8u#{&blznwS357D)5#0btZMX!X;05+R?>Q-X$@ zPCHnSVcuTd)mqr|4-+|#u%jaOSajeTC5Z1ReqN-oW($3B@e>IAveY9+1h zQNaD5(R`z}o;SMfwHs=BLyGqaWsvC~T+wjpDoR`UngaWV% zaA|G={$nZN=rRyu-R5d>Yx6yo?VCXds-~Hh_RjFdibuV=5H(zaHrgQ+Tt)1p!gj^Q zY~gE8eNPjYW566CLi8e*YyPgDOL~%PV?4GF3R`I2=>(w+@Nol8@&AQ5DN#mVTEfes z%}tgfevp+mh6k1;u8)J=gBMhMiVxLmx1a^Q3w-yV=vMeZ1P?vS%pju&@84GMmfz@-*v%A2pye2lfS7 z3nBc}SpKR9)b9@8`+V#-p4=48j^?=dLI(M&k1~bOGOJWH3z!pnuxvhs?s|2T`Wy4Z zb3Pf=2g(`~nlQi9*eXSSZLcZKn&-fR^0NT#{FAk6L%*P$fNdlJ{U1*~%`5la{pH{IlUv%Y$9L|-f$ zS_3^TNEVKuf79TRG>MEhcd=gTKh}s09*brkTpR8?FSE$IBz_~2G%^&ShZ^R}Rj#S> zaZBQl5Jgkd2YCeGNF=iC+nwdpl7HP`WBceAB@gtFqBRKP@XtxE#F0qKvGmphj*r{? zQGij#CCl5-Sxtu(7Yc+apcg8W4kPf8GUo*lCJ-Uz?ZsnsB<`e+J&-wwLsT|+%lz7W4K0X;QFu#0`RH9L6%b6zQKaSR4boqN%LwQD z*4&OZuRQfr&|lc<^blcPeLp{S1Kb9)=>5eL59DIDhu7rv=uxt~FID|KKe{HI)KB6p z=+;zJNdCuXm7_$6rHBQALgkeSAoh>uaZdFc!^qUhRaFyUP`rIM9Gms65(fHbav$R` zSXB5Fji#uDBgn1PyWp;j-_Rg#(j-%jfG#~VgNeICv9%>aE!ybcJ0t1%+2yomtlFno z3j?k=XD|~&rULm{Y>1-zy>UoS+_nEi(_T%LXv0+TB*x7`uVR&OPlug>(B zf{T_^CssfqkI~Q%h2}z<>J`@$8DYV@`ea)Y!+O}32a6;)z$^L;i@MsFo108?Trlnp zwmiUhU#!o;?f0JF4t6XB>jl61FX0dZ9pn4N=41*Kv&Qc}I_D^a*ND{~g}34Q5pUW-53IJKX7hGC(KDG{Qxv-*R<5Pn3s>%iIBm+D=4vtazZOWLV*?HR7+Yj1Dw?Z761MSX*Y zArcX|&rD)W2~rbxXy4?W_K+R(X-z`-!oVg-52IY``t7?L)JZK_%C~zo^u4(y%LMin zw${&7%iV34t`QM#Vg|^nA>Hn2JWUET^opJy;oZ{=725|#JNlfgnpi*~@~xAf!*6#l z>%AYe5~q3i+Tpd(nuGShq1Uf6%>%N6qJ@F60;OYb*A)H}hMRvdKQ(7lX!N$8nI_bc z%X_>%Fs{?@u2)1XrKpy-dXuehVL`^go`cuR&oQJ3hKrK*{47~cB*cmKu4&0^kvMCg z_$Z*2RQ`Lm_$HWXh+YK#!r2{5^m~VSCK=~}sif9310l?1+6@8Emi+=SAd6{z3%3@M z!j{$%J@G}sWF6kyk(I0&XOtxSg%0SHlU*Pb$`$EvA#tMFGGa(0_fVGOkVu#2hkN zrgvqBCd=>WM5yb66P{0`YcBq5}^3d`JoUB^uyFNGi$L7G_Apn1A)mE z&wz$LI|L-j+}cU9!=XDl8QVR0!*&mMJ|a3V~5_SULkmaoZVkJ)pp*G{f;_d05k9KAV)j{d}-^yF67Y zkTgE6Bo`mE#VJj)t0{}}X6BV4^WLWar$CDJyU8CTsqOD6^p25?!`uPyF$|2Ly_fZM zEJ0xpC;K6dXy2s-v~xC(t$|ZkNVS7>3s%x3p7TqS}b z*}0k%Zz-g8y{(YQ_J|izB|07M#jXbLfFbIG_9P?rHC5gVz+uBrYVQLH7;m(RRJ6pl z_#6bL)d36W_Go46xH8w9Av!RQs86l9Gi5UihlvKMH8k)0DIQi8~6I#Jds(x$_<491M)3$K9wBZYNwjBEPfO%yt)IsX|wA^0gO)2|k)VEf zXmTG70#|;mjmt#T^9lvz1)h_%eMFTp>mF>xKO-7wCzpH z{MwfXI>RlQlR%4~u4w=Ya~I@MbUS$P>gfiEFp7aMrJM7%FmFPuOTBpc8bLc$Zl^+q z@rs?bwVpXKV+Aq8t_RY0;kV`Z4@i5ytDtZXR!LxpH`9+?K5KL8%+7Kg9D>b8yQ5_b znC%Xy1mh)#(vTR}f=ht_X}`*;xsY*kfOLm+ z362=^=)U0`!(YkI8)tqQovh+=t9%?E)c;C(@>jqU~C@6t=GatFbDJJ9pJ z(Cojv@5L+SO@?e$=^vo{01Kx{Emnl;LNJGSsQ&BC`ci9ejJ_Pm#;bzkynag&y8UMo z*JoU-MB_ySeM8Q-7VIMo=+Yy>oE%N={H96$9o`pIG>6X8d`CwIa4!^a_suqyai^wrXBpS3l zk$`rOSKb>T=4L-2$ykv?q}}(+qDvdRg9iDwZf~D0^hs}-mKUutZT!#0PXbov)HH%% zxhu^3%um#*=5Y8VM=VZkscI^eKp$#KY%edP2k%6UsX;a9t01{KeJ2Ij6)GQm3|FpF z6%Fom2aQd0<1avdvZ$@>x7fwp%CTo=BEc7q;(^vpHa=P@8{0WH;c{JiaUf~1XSJ?Y zH|zm?2zc*mxy|4&>3WDf!+rJnC- zoIa2aDd3VHNpr0(E;IICAUKcC4O>=1wHQ}TriMgVWfy!h4I?FP6?6*bgXCSG&Rj74 ze%mS6Yr{SB-eYYw0iRn3E-931&sMPlvZu$HKIcSw)s+NB-CC3?`SZzLzo z75C*1mN@u1RU@!BjrS_@@}2?b%f*XE-+h1lB4u?wMSgrO1<3!TTCm}=Am}G zzP1c$zm}K!Upo-do$S}VWY}}K)}00ok96bMs;Q6>AFqW5X;~{Z)$s1x8X6=UBu*X~Ey4 zG=s9N+44Xq1(e`j>}{tkO<{p7S_DI$adD|RILWOnH&Zy-Ht79xF$IEmPuj5{fa4e( zk;?z|d3-jj+vlMAjkj7e?P)zjzw?0QYPCekuOa!B-1G)c|cxk1cG-TwRM+X zH{Qp|XVIgPZh5A4oVOfzrl)%>m472Tb6la^_Bk=JNze6)tRrw=NIB~2e40iQ-8~^& z*oEK9HOmSI2L}FnfV;^mmcym&japdvd^*)scH}4<-X0vZj8HJi@YT637~sOA=ANSX zX+LJsEEl0jVDG7#haS?^1{-56pI***cC}2*@13V8(v~ExE}}0%9uNpE&?~2~99^ye zw3Ua4ldzCi|6hW1@3Z+W*ZDyj1$QamX6Ir_xpw!=_UTGn1MAZMO55tv-&j0vw3hFI z%jWSno*TuEsS=V}%Dqp@vL3D8lGtk2I*^QCzc`!**58Sz;8joF5o{`g%lZ+H>$W26 z;OACOmwT=Fb5j02)bF&@8MKie9%>lyivdz~!xZ-ER?YWr0A2AXqE-9moaViOyrnE~ z?lCf?4UPfMHqE5yray!T(AU;=?PI(P;RhQ^JZyd~2QEQH8Ytt09VYRR|H^vS9%x#( zCm>%@Jkj+p=Wi5unD(9ICkMiWUs+C{P9d1e*f+HIt-^|MHdTAKnXQWzUjK2YGAJuj z^70wS9IF3?M&TcqP@=SJ9<3~OE^GEgo%MUK>&blyimc{^#WWJ)cxu01y!l&0HJ}AKssQt))SaNuV=xGo1E1bGhqV$$6ew zw<*aCVqNkWgR7(yN}-!?X+GBE5@V#h3pyTPB*k-ncx&3A)TEn2FEN`EbL0+KaOXBh zZ7w)p6G+&|M-YAFd_@8j5CNh-3}OvvS;LxH)g3{^eX;Eiu6y_Yg--lz*X%EpbfBwe z<8(*L4A-i#GJ__N&tvT(swUB&+yJPrJ*9kh9A9KGh|`HRP1p zfb8>5ZhjX?%M!kpSmgE5PWQY*idX>(dbs*;aOYYp*eTcCb7%wk@LNjM?ZXi4nXctB z6{Y8|>gK^ZmTo@*8%vFKL9vrjjts*j|6pa5{T2t`Ys$SCT(s~OhzvuhT|N# ztw5IF5vOkkBdWSMaG(3Vw_=-B?yJ51#K~-QVpGwon2TfTXO~I6C1rX_Q(GK0_&88s zt3o;_;uWzSMQ-?R(&b4(V@XD(X`W;aeJ_+V%npGPl9;=8vlyL2w0uUW4>e zh`@Fw+K+CLv?|`L*@O0jFV^v?m6~&X57e2FnC@frxi6g60$f#!1{%qM59|#o@8_9% z|EDe9Gm13KH;`z94>En{4eAs1&g*sVwKpGdEK_$OiA2Zc3P#t}3ZAR2{|U-@d#TEK z06sEb2t0gdC5@8ojJw`KE!Eu}@hS&yP^Y=>E3@u=xT2AY5B-I0i`6@gl|G8L9d!1d z7?@L3b5N1GJ5V`8YOPcI)hi+UZQkHf)Gq(HfxzF4ggT5)I_I8v8`Eyd-{x}QlpT@0 zpF+_7V8jB*tu(hgO&F?S#_?(t5pAtArKsvI8sj}PD*}9&e^4CzKb%cDvu7bN=bJA? zFR*LwRYv{kvni#`?Go%SHoZ7jD|D)@2)5$l66hMAcKOIqE^c`l?ytf0X7(&qcLljm zcIUZK>oXX`hdM#j*5}*7Jd9wb$$3c45-M^`a4IZ`mK5#QiceSnX z8JJV~MY?W^YhNvn^|2#b#FdC9DR=LYFDnbRMDD9MIqkgrU|%Kvf=4|UW#}k zWrRhrg2RVpnjuO_$X}IQo(cS_GtE}6+2HsG23VhQNUL{>`wn2(Sin!Jv~cfdj4qfV z_Tv`FhUW)k@%OO3t$04A+@Um=L{3||e1T@8SLn5a$F8a0zy18$$9^T+jw6Gdk=S3YbGiux$i&rSy?m=WZZfY{pwc! zra!crh9zY>oi-%TLG$iH>YMzb8CCM zhypHG|3gktP;jEY{klo6p1$^Q5>I2(g3w+gg89|c%Z+`jcG#*}lVRxxl(4O-_n@VP zID4tHKm#js7=>JRovHlAO4E4yl<62zA|S=PacNV%Cv@+|uFpGZeCcJO!?+r2Yc@x} zla6=oGUKl;CB?v^FO=SH`z6_ZgThN(%j3MZb$w>zP=a>#p)-T) zX_d_)d7pN}7fBF`?MNGWd4`m4DQlv zeVqgS9rEt`*=q?RZ&jl2GXdo)8OVvJ48bFVdo)4^J+Lw};gi~9`HQw8XYbY;n%7NY zQM*?1*~9@NrVx_wD6cOuA$3J$wWq=gGOo%3^+G)=Ie8V~=Jjn>GR!R8R3}_VI$+yGbv6kSMSuT`qC~Mij(Q=>lM4L5mKcO& zxr1ds4!;+{|5Q}meiEq;d|6ElEG}}CMSlg2Ntune-9L`(4@D~|)R82?%4!W~3i12u zdlW@{Y_G9*pOq7P(G*nqTw>sCkVCW6ry_m%KI4qe9UlpI+b>%cZMq#p0zww0onJrw zeQl(mXg;`8w@#yzQ=X0jut3p19&$i~J67c<%Ji!yxPh#&t z+zA`Oe}{?nvLL-6_B?}^wXEU;BQy%l^(W?o zUNDd>BLqq-T;H9Zjl&N9^b#|pB{kR*aZBI)L^06Rdq7m=QZY$!=tx_oSM;Be(b3VG zcmA91D^HnyCWeT$CvW!zNmQl7k6+=dwy#8G?GTO~nY#;N0; z#xX9JFnAkZ!7W~a$F6X$$1Nei&E@*&cu5?M(R`@c7Ra@|Ma;;o1g$)qNC_WlG}NQ= z&Tm)ADTD{NK8uW0|0(KmLVC$Hdp(*ge{~!qDS~Mpvd~pLhk-NmqQ?ePdi6L&t$ab( zU;bgCK}$`tU7d!2Y2NH|>;~PV(_?xvJH?0MT1B568v153)T(x$l#e|w03frx&;bfv zM*%AQ?jrIqm1n^mHCmT!oCJIu_CPu$e*av$@JOm27OT3z)Z4&Qo{5xxv!?jGDy8dM$b3 z)~H#9ZV6@?>`DxQ3$)w-hWT#}@vLrYeUoxidt|GNZFRicls(fC)EZ#*4d=4N$^7ClRI4W-DOq1z+kL=rpg_Z-1INQUwu*mswrqtRQ7XxaoN1W z1TVFiiB+{Mb5CX~)~hi=Oy2VOt)^$|RrpjD%q#+@y4{bFn?FPp_r} zNhkGh&{78E)PpZItPXMcH@_nbr(`FhVKU}8{FZ7oybWDykNyS;@74GmT9 z$+!xvWwdEfpv_fC#}HnUEFwS4c56W|_t82|c8_K|$wsENanvoi@)G9|yG_!YO?UL2 zb-KrByf-?hidU0j-zF1iDrHDAU^u4VUp$f37;rdIXz_qqnf0#G-|YQ{d*|5<*L)xB z-DRFyzOUhUVFlWffoBE`%SM2_S+``HMDvVaY?1XmKKd45F3vHl6i4qQJJ!~Q@w@MJ z%ixK~W1jY?&Zko37P&;-x@5wg)Mw~tJmC*hnidTB>jbn=5QE=6npw`K>9pP+m& z{q}A!521bK8NZ9@^^C*eMf)lWL~GRD>@raf?!;*VNg*30DsA2{wF^9%kIx2tOe8NR zrcaT}Z|X>%mM+W5$N*Q>zUMuA;M&v2HC59YJXefej?8NIMQ!B6Dz(LjDbJr?k$y_C zbqvJYFc#EKhpjc_d>oAEqf=2`ABs~?{0!Vv_-sk(M{GuIU0z+d_kMeF?75v!gd6(H zIg~pzKQ8AgAx3QXBR}Z7MxlVz&>U#1>bshV_XYC}#)br^F({QVG6Z#g>*c#_?FYm_r_o7HUBN<;urN;jH!SGrH>Sz)vY*6~{{+6t< z1D(Pqf1pjqYS6%X;_esq^TyVZzPkP>TZQI93toOAgS5TWQ>lO<6*98y*x1cu7pB;c z^I2SNkizYsIxWyFHUYEgUUPVLEl8X~_eg#f+L7!nRlCdryM(b^WkT|)g4RdEpqM#V z0w%kkdDz+~h>{s7IKuovBe=S{y5{!HoPA;`i|rV*K=gHHv$Tm8740V{Li`_W4sKsn zi%x6oT)i&}isH_&xuYiYTjS@+iow@ADS9R%2F@#Q4Lv7EO24=ioPrqkS?VlJO~1v2 ztgNm=>T4{`N))d93*`-ebeY=2+lIWQ_LLhoBPFl6__#`3T%T3hL5&CPBY(-g9mPWF zCuxqF*Gi6FZEBN#L9%b}{TmnTjX>b{>&bHV=XVX$nFfft9CY*nOn|5Le9sp1p&+;{etV zhiO#S;bwtYyS}prH-agiF31e;Z^peT!^?6<_r}Cc>c|9b!yaxq1odDSvVg-)cu>d` z&&raS*_A!!C;zeUwgmP8p8#!A0N;#w;T_8dM6J-gm*YCOqsZw@|g6DL8hDAl>5oRzxnM>{=R%vx-m zge_o21>Nl!GR_5aW&?Zfek!(PJ zbIE#n+qnNEBR&Vtr$uPN_G!BO8tdDqGhlMNyGMtGTCmy5r88PQv8HLA*Wv5tD6={T zWzWf00V$M)UNRF0!By7Vlj)zwm@2t*-wbAQlUEVwa@#_WkA|PXn9(8XC#e8h)2cw+ zr)^~Z1;qw8Qod0XT*~Hrr#E|r+xA-P-m_qvKetnWzzwrCHC6W30SHe*!bdABu6KK2 zfajFY__(j`eK@k&8NmWSPYGf#9tpXM5Vdlw?Nz)iyqAY&M7xylsS8_AAdB>IHu=L= zobBPKF}MClx&fC*f8U(jxy;LT)M!NZBVd>^{j671za7GX2ShEST2OGP zWGO1WbgyL&OvF(o4seUw!&&%FT~Pb`0yZTI01h!_ zD2P63gSe00EAGFj&JfmiUP=AvY^UNqxuFmD;P^G>zRu6exbH;Ioy+PPHo8GYxrj{q zF5CJJBznS#D4{GKnOD5?*PXkup;GsETU5w>3LJ&16;k_jUF$9(@P}I~rw#G@8G)*t zAHYoZVrR-HUyl%+owp+#RRsK5gtB?HVAJ0X64v?ZE!`QGHXA~Hq)z9wZGY?G1S zy>W&47Zr3lS~(m%0?^i@*JQ6YYPVkm!Ja+Py?HUW#_*q`ftjnJERK3S{bL!<)qN1L za6{ji#1QGoBZr2d0NqCggZthZ5J>3GUSI|88yPMiq?F9E<9MGyLzDwihmSoRQCirj zNcXcW0ipmvhT`{tS`aDVX(OGWY?mubJx0z#hX2w$g3IOD%kc554|M5YpMjtcKC6x_ zZ*B<;4S?WsI2zh@VVH5->FH3#pon`r_(z{n866&r3=)6WR{i#67c_9Jg;t-PhcNf{@6k&r-DH{ zxH-5TMkR;|bGPZm{mFq~HfoMB6uQ}I1*tN% zN;tmRuRfl&jXjwJQvlE50+OKjwZd5ov<@Xf0Y1la@iHZ9NOuwK^a1HZ>Nbtw9^B9* zwsYT+M)0E)y=f1Ucpr@C9B!U;tW67N@qWyrJPSCbXcdvE`>M*m$D;k+U_kSY;x z0sO}J10lDSpk6vTD#7{MeR|_2O#3ETKWDz%uudU4E!Fq-y94I~7OXtIMMaLe;{HEV zQx}y^HJjfuD2pW1(jHU2|Vt5IZ*{n znsSRuI&t3q0&)E5>TJ0_%U|aZkPuik6ioI|Rr$Q6Q^Ohc3s}3@=jHOu&eSI-$<52# z+1g_pouVxuZT6iqDa6gfm)v#s2V{ez&OHf((K*ojBb{fqT)j3G_%8>zW0fwBX^~1DY&1@ z6YAN+i?bP&lFxl9R>)t&I1E?@=$iLi^}(;B6ORxs##;CD)bj649Th=d|A%E%xM3Yj zy4=4%0@o({qSw+A-=<&S6{4L>6r8WGUO9YS>VmW77)4SYJ}bl09d<71Qh5aVg2Wip z>ZT7u?`K)o9VklzK)y{!k~?8FmWUru&{)Wi7;G+`UEIZ}EVJqzaZ4+Z5JAmxBO>qv~&cD+#B2#Y$ju#Zfh51u) zUz~2~ZB{J~fI@X}G#14|BS<|sy>THgOwGvp>j06lhEbE$18nR`SU|>6q0plx_b+T> zJs40Sk3A+Jm&vVeX8hGkc5qNTy>=%rIE~Lj1Je|96&yBO@9yT-fgT|`CU%q0{2|Hb ziY~#pAlD0C+FxRh*dTcYCRxD$!se2I6pEG%t1v)G1`i-+PxtID0PZvg4pY)r#y!fe zt>f(L^N*0f`YvG{K7a*^K|Ye8%Y4$y zXZhz(6#1PVQ_Kh_;h^~{x?=Mh!7@=AQHexbAO_2=Z8X^kpvDaJ!RmlmU6q-@t%q}w zhAOJZrFvilMZL_YxLI*t{hMxapXeUTM%~lzDs1W7MXXDI3h>y{bS~nq=NAXhfhUK* zY4cMsrJNJ*NM5dI7LVs#;i%iYgJEV%!6Y5~)J{P>P4a{v3+pk)TImu^V_`;d4 ziZas=W$OH0l8)GEQk}2G^&$ULGQ3*vcXL9(zpQOz}OOi8|V~v&{pw>Y&0T$W!RrI-lkSzjo>F zh%`S1A$^#zMTA;W=6Z2bl9;%tH#pkqu2LZDkaf0F+@*aMr~L9eb2igcz6YY4zXQoo zeMP0jk!dn&*^xm{ylU=FxE=l|^12V+iAos;3FxCN^72_?q7UJ~`ZXzDM`Wfl)4m-g zs|J1f4?=t!5D%bw-M_YO8R)dTkdq`n>T2?u zm$Gqz!XyF;qDNwV21bl2EPmspTpQM6>~>XSYISaqvZB@J`50{=aw2=O;Wfu}O>2>_{KjIPaaFN%!YV&bI(6N04 z4Kp3FBmol=utTo~GnJ^bb709eMV;GaV%7~$oq0r4fLV%E5e$x>cx9H6k>S>v4R8m` z{Gb3%72P_ylaQUmW{Y{dhKwKcs4$PhpW;s6AmYzMd)BzT9OP9QH}FlbOc>hfJcK%5L&L{y+`#xuh*9*psZe5v87*>LQ^x0oyo z&jgOgco3^^Dy5EQCL*&AFHz%dtT)R&BvCv?K1ENTu7U>7waChV%Gmp!oe& zjxK$!S|K*F*sKqcs&;%gM`I_yC{((93X`i-BO@bo-)^swUXr6DNZx~NK%488teyZ{ zwaoM+_~=NkhB1ImK`US!4buH-WhXH}Co#)=HsGRCq0WvjmRE+Sw}NiKQZbV6Gq zc{Z2&YJG31lWZgL-Ns2!f8mYJU>~l|mtby>)cY}A<9_LseEzwP!M5DD?`tPnAZU$_rG3%HAmeY=lFcJ?1HYrN}u|C_x_;cxXxh(641|lqy)#R7VxH+`#2d=_nQ)&U3gpVkE#-g3E_5cOl$EB+ zySON&E<{G12_rmV@~%)NmjC)0aAAYi4YkHHXyG>{xLbH{2fL}G2$jc>a?xa=UsS?f zzcg)59=ml}$xDX{Lnp_#uZ;t&04ACj&+DQiHkeaUu$}Nkq+pac=7iwfN;?Xk3CO$Q zadQw(ifU)v8$2-{AE}3YkxcPP=#>a$cvw2y}>G_`A zh>S|NJqDzhdlL)rJq6(RL(wgUjx;lkB_T+k)}0Nxe81w$2IES z$MG%Qx6kG4(Evgno|NhH&=<^sb~HC}CdO|wrc|V8I@f#z3J3cJ07);)lCkW?a1eiP zxOqI5SUP{*_=SD$$aeOovSFwVM zhf@6@A8jr}$}}5uw}Vsm3;lh~Cbvjh_sU13*Al-H6ONSieWSe1l%)j zS<^8&Yhzc_g_Hr_18);@cec0m@k7RRe=9cT6v~F(yV|JKdp&J5dif|BD= zQ2n}Q!lDEuJZOAcsTspKDk|(jaqg=(UPJLNH9fa)hdyC)ih<#|^WfBTf9bqyWmK-z zmUhFd+mM@O;X9WpTGJOX<=}{Q@_Fzy!y;b+rG4q~OGJY^DdEDVFhK9bwgePDhr@hH zR;@?Wa{c^D^5RJ!5}WKR4XZUSWW1i@U3x1-Z-(dWqTVqdB4FcEni5z1{l6K+;@UJN z)T@_L%KDV~n66l~HShd|_UpePOEbOi6m+*)tFS)E@0$B0p4g4F#`63^kc%Xj>rqDG z)%slWA+eq-I9lb=hbH=p(H0(5&Zf)6-NTOJ>gvjgfuCUEnD?_4lz92>+$U+oc_LA1 z5$&}go(gntqUgUGmH}eRiuIoT(bwOV5jGVtF>ESuugZkcW|eCym~Q>R_GM3e_^#-Z znDu#UDW!WSI9U3;a;p0@f^R|MSI->ieDoG#B3=b3`igS_{KwKBe0j<=g)e%oXzWk* zFE_$^^_%C}<2I~6zlzz>8)>;=deEQHeUB1Q%reOi@&qz24OKaNzcBsTuO@P~X}(@$ z$~%a~>u&ptMRRfz8xOGuj761rZ@%Z`B=^MFP(h$d}M#=$AWK^ z*R!HS${G)LvFkFR=nJ_k({q31+@|x)mW&|WXA-Qv=}}o!T36_?x_wT6wSZ|Z4Rck9 z7iE&DUb@3m*ERlCJ(+j5I=Np=ujefbbqJTJ2nzU*uVXc5y>ADJUAvgCAZw^u+hn-Qt?dqY0<1pLiZ9EY?c`0+uk_Lpcy2AxUjDkw_*OWg( zy!9u8JEe6q7+^pHK^stA=;?vqA0fBdMxifN6b1V1rhN(XC?e{>7?elH+eZK$G)p(off&S#cNzm0F|&w1I`$acPaHF)%P;;?B@U@v?fh zx`#&{ts<=ckOg+lf`sa$;xtBRk$xyY|HB^;y?qZP?bBxBR&B0D#Y=Mym%!d1p>v4p zGs&r-o;5Z|d9`a!l3n80f#?4Imd2>dCUz1(X66#t%78l%T8|5b|H&y?r6Fd8SR&ME zag6Ig-E(ORyPX4%u9qOSvvm9iA0?MX;ReNUV&hRLiWuf_*$mZ%xZ<9_tueCL7>0U* zCFzmnhbM}#eY>kASJ+iGx)}(DF!c3QEhsICY#_3#T>M^H{c*$Mrzhf~dtf7g015Ky z*($1!VrlL97#@G=Oub!bZ`gaPOu6<2Ih>cA*$7^CJnM{PF;~5TBLbvn^8glpk+{6! zka}bUOir8XiBNqH+4y5F=hU)1%>{7&G*T_QMX~JYpfF?1=F8vtN}s)mh_g7N_gU*0t|#BH9b zr22i5X z*0vHg2Za)KUD!6ei1+%Qpx6=d%i9|dNCx(oO*DYBcABG+6Zg-gS7>4nuG`Q2$|swS zW&rf5W*;?A6(bmVu&VWZA7wyXITw{|)r#Gp+01iHkdD4x>0(<@-w;@4IHxkf!?p_7 z?PPb3av-bj46W(~m#tC0DaB$*<^PQ4LJ=&guTK7^X$j*qFcfNq=7rFF5K0LRJ-Sah z6^MHaB5VP1pGZf`B#&|$1+I@yCj{<=0rvUOkgWVrufW=5!MwC3-U)phD z>FMI+qD8hQFEG)x0J=ymB_4}gXp>*%afVf+3dXykijh`f(4%8=hQ6Ajpl)2W!q7`8LzF}tb{cfGK)nCAL}^4aCON|wC%Vpr>3vVQ!> zw*8xOGA@lS3XGY<=5qc3*vUo8oU)?b{x#=HiDncFTz+A5@h|bRACI4ZRIz&eLr;Kz zWtGwm&&znDCf6lf;-d4YK@g!~n_mzFv{kzl{_;`i7Inq@>El_gbLByjy3zRneU-!t9jyP=5&)5XvoLh(in#`gP>k0Jtk-$5z51a01USa$u z^lcQPp`zwho)*6*u7mb@bKPs2Mk4RG+8qoQA}8&Ng2sU6j$Fv{!b~zN3qKjn!(TBZ zH?wGNOo%d!0ZhI2E3yB-~c@t6URZ>o} zmu$(&60T&VV|i?Ujy{fGFo$3LR?x#4?(qDkdD7n^Q^B2?FPuS~r{+$p3-4Zb!@GIW zH{CLdmRFCYu=cW!KDA_3e@@RO3-2j80=BV4!4IynGbuCtvs=guv4;w+srj`0f#!cL z`azizE+oocF`kJFNq-pGpDrc8UGM1}A7K7z&E+Edun}h@i(%5rcT2lx<32W+BjSQM z4;0g5*LI`x6+G!)IgNwc^NjEtzswJL@yUc9pIgzl}+Qvqfe)h%6TM z3V1FoJS673*{{c$TG@?Yk4A#LLB;?g#z=Y*fC?D>IjenB@!p_@3JTP<|D+4<#N^&R zZ~Z5e8Ysj#M6Jd6RFcY$y}1NutAlbDHor^8dvoqwRJ#qsd5{$atz|>MyUE^WgoA+< zO@UF-S^c0aW9KQU2akKRPCs&j#`xcuJ{PUqTZ}WOmrX0}l+IP%{PF7@A$K1%9lq^R zWdaZF&L9`A+Rg_JOWbH#!aQmb0H#H9ur1@P!Zexq$9Kp*$IIqT@)gzOuc>Yx*YKyg zq%#oL!;yYKu!rf}klP!$ilmR8LWQ1z^&j(gdz zYXkrI<5zc%6?IjQL*c7EKA99&zKLIlEcDT;ZDUM1C&wG2;e7{oGQedG|4`39LwDr> zpIcWsOoI*QZQ`Gu5MMyJ*mRVNS4bahpu`e&=ObmFE{RH1#3`Laj5*{ZY(xCiCe^Yp zEEs|q2^7t+4R3&Ey9#$~#*2X~X+%x~pzWosX})05`u!Vousk>d7pnYYGY-3aPGvvS zyZj=n(fD9BOf+Mi+hO}n*OHxvHw@_=gvDwBVyCb4IDv~IBWv(+crCXO@JY5D9rX^%sxo8?-FxoB)`sU= zK3h`y0kXp)B+Es`WMq}ugD(7}&r-5o-Xp+FdXgIsZzTiJaMSbz_Jokk*J|G$ab8vj z1aRsHJ&+ILeI_q+nC)-1ijaGuwAK9TDD-@MGk=im`3I!prjs+Np4jw^R}=EM;6;9w zjLO%mUw)32VnVB4W%vL2Wa25);Bobk{|L$;RJ&SX$-1I*h2r=1Ovu;SkgugYNKN)L zf`RmGKWMsIm=mAOp;2iL&>d=+CTsk&uA7pGh?U~~ED>$}-k#rqJOgi86^K?uW2=W{ zY49VQS{EgdH{%@p@f$ekb>!^xn-|_ra7&+F_XzmWJ{P`)bSuHJG-)TYSY-ZtY6HlwC3Chz7x!(!@+>?zqEx2ln3Q{Btk@k zf23SJfSJZzQv|FNq!87D;5Fr$Fsitp_7qSs_YB?}nfTfejhmQFHMFx$^~0L9 z#fG#6+q5mJi9{qR&r&7@?OAQPb<%IJ-^5qFT&zlyYB2pd}n`a z@tRVlIEZ#tXRE}P%$|*raI5gnq$D%qo95}>`qv)k@0)cz*&@F z^s&d2oty->7lf!^{6ZgO#mi^^7%n~Ks=@!RcL$&CsHD+aZqHjX|o4_`Ho=i1O&%(xT&sIs}`vcPVm2h@m^01Yp?z1z1^ zw|!Rl#ukF`>3b;%-2%#(y8^#mfM!&8yo-gcM$do%KCSPsGQ_}BMO|MJ!eo?c}(1EYvUJi81D-Q8pHJAmr4yj3rLYW5csR4awP9M0oOk!`M^V{FN_?I2lvjV z;kj?-Ko6C3>KUPaZT*cin?v8mI;cvu>lLKt<$^=`Syi5Ir;t_ zef)2tuCuF5DV^Vb`-A0`9{|s86w#3R=;GR4@?lvd7$|+agw^>z2p6P22e#*;%*Cl{ zJ)pInXP7kCf%RHrRap^$n#UrwtcreH=LZmw5OW6oo`{Kd?r+pN4yvv7m@$x#uWIjG7lE=HuI zQ|?t2y2tlu5!R67FL#`OvzW0O9&|jH;b*Ia@lTFvt};NiH07Zk~N0<}F`(o%jyzhg?1obZkhKOl>oZ*5J=ORidSePz%(E6L~vE5By zdPtcd@i{J)ZML_a**!1j1c~_$R{EyaGSyK)?!w;E(}IyY;0#E3uVDNl4E5LNmqM<7 zucW@+rtf8s70hj^-qmefKmvVclCg_Fn*8l(ka3c%qgf0H_JoVO5$D{KN~asB%BJ0 zg1@#$Nj(hSHVe8LIu=2&cjr=wpupfX!LI>Z$cv5?(z`{v$^MShiPby6tpSUgUg%%H z^P?8zFJCcuJPxks^Xw|;VH*-?C>@W5j_bgzY+r0n6r3XREH)?_!TvLLcT5K#>EEnV z-+9K|H+L~QlVLsEv0!W|v#3e%uqOpv_=mv56TIHs*-^{GEl_ePJhYfq~`|qMOZi%a)5XQp<~c3=+EU6e|bxUG^$+ z3(q9g;&e>2BYek@@VMMm8wmyw)9DjOA zHR=p2P_Y&0AR?xj@I_T=^8DY<46V|FtsU)7tupo zKLgW-a&`wVur20!N%Z}PtI|dsfdS0OnIv{Bz_x29lK7W;lPc`nLAUB9g(oG@1z9*6 z)wQ=Ffg{p`l5Gr}-?h9EDCQJX)Goq@*E1@bTs7;po-F+MG_?6aq(j#7lqr&A+e(!q+^{9v$Zt&G>%z^Ds6tQ3jO3nn`r7ty`=~uxarJ zeWoGG@|JEAij!6+gbfCoQnH#U=REAeg=@RgufUbo5oiC1!5n9{bQGS4N@y!2k?za4 zHes5}9oua61t!H>30OfMb^J@rZMGE$_FhGi9%{Q_pqn1XMY1tmQZ!UJn2%jXLwL4p z4pE&&;**t@+%?6_-sUG)&UEi2sD5P6CWe7QZ@k@bH-9t!aVf5}g;(*}y!OTynyuvP zw4=FiHJ5r<1imk+E*DQs9U{Sh>lZ;ur(PQ$j~lhQWxvqV30{5Jc!J{XhQbxt&UJ=J}FETGl$5?`?qink_9Oq;*DWN4xXA?9c{>@sZ+p3gB45)YxgWS z8VRpzd}A#StM3lUSJreZaz9C(&2xMJZFMVbT%`aS5y1Fucge_2TzvmLES+u%s2z874gqU-KoN{g9dx=A3h)?{X`@+Oc*QC&t2W;x8- zGBU*xozGEvl~arW%!*xaYLyee0NYdC_O~ z3q3TdMcg9+q%t5l4U{;jhdQqjUE1jV!xA?{?H-7W*2=C1!C%*j#3^E-O&l(1!TjVE z$t*6j%Um$zqu4@79EpUQB#+5$-~nweN+beotuD1)vxeDP>k_R)7Cb+`@~{DYRx)L5Y&Nk3L;p-lAwQt;%){bP}7z&B5RaW4=G2H`)oSN+1gBFackv+d` z#^~Ek|7*;AU$l8rKi(90F4F{ek@;99LE-NJ*}ToMci-z%{nIi{cH*Fx>N}p8T?vzi zegTf>&Xw*T$>>So3!RZ>hdoAr(0u+qeUJCw?K`p_>NCETIXc>=ai1~V1OE=h160^J zoD>~XZ2cQMxHt3kJU_+gswLbrM=}Xl`(ywo(X6h!N2Kv$nYGo%#@rI6Uwue>?PmBe zcLu6gSCf-$U6kYq9A_O-xfh_=6MZ$`uG;Kctd-y5RIAr)HtQL_Ysz}~{Hcn!hDLz7 zhOOj1|B{4#sPmeQmXkMGfgUne|6W!RQ66=GWo~(>^35Rb)vafgkP(^_cU$FeCMOW0 z&WgrsBfE@I7Y_xU9t4&9o$*sSe;CN)E&XVl{T_iabvW1@FUBYU{S1doFL{8TvL)k6 z?|$0M_kE-uvJV^HQ{}$?*GIp+1H8;m&%iy`ad(yjDnKWmT1D6cxxa12uR!1 z{#%K#l--mHuVq$;RL7?BX>+{1JD)nLtcR>|9mA+7Y-9$Zep7v$t|&nQDq+pP>H}?7 zcJ_09YJQ5p4Tv&_9!POy2c93ku}LqeY;U4;nT`&7Pgq&b}UY)-_3ciVmxOhX& z`z^@AdU0*=@%Np5smH!s&v_B9A|El(N8NM_yLeJuIn%eX$hZ|X!P^TMl3wc{Hrl*DLW(Yc3 zYWq!z@p2p>JOZE*!ahuR43?}mXLQs^oq3u+Wg8MU)WeYp zP##&Kl6B^BMILxVzca3V&#^Pd{hI@Y%JU?QyadyKiBa$(tUn@e|dSqIrCf{`%_+o%*R6t z#X`?L)#E+}4a!)!@mc}*<-28Hf%oL;;Z-$_wZv~mZrQb6jL(dWnm>gIEu+A`8?lzR z-kffI(L@ghqbS2dSYukLE7^St>N=?rXY9(?V_;O%B9JNbtd|?KuCRUmCD$6;y+X|< z)~ScNy~({zy~XQGf(T=pkd$>-gV0?nlZ{)yWAimQt2~E5iTd-4pG1V)(h(6Z!b341 zFnmJgRnl6A2aH7BVg;7dYbEgm1@v4BD3UEGnoHlpU&t7C^YM*w=>BEy!Ym3`Z3y`Y zDzxF7w(L})?8F{b3YdBtXT?fsjLRl^l-ziJo@ViqN-pQLAvl@0q&(};YVZ3fzbjPD z$iR3HT&Mw5!rKuqLHl=O4-G;d>*lWbtrz2b(6|*b->0DDXP<&xP4;KqyO&Zb%p}}w zSk!SB3z%HVL&yi-#lWBXrr|w+ia8iJPJy#uJ%nlF%T+X*)4pN-ke3Vu93D2lH&0W0 zU2J2h_5&`|h(9YE`;_!1+&cHRniKyuQ(A0+5zCkCz6vB(pVo;-GR?*N{+*%<+_Qod z&*%d&FETEJxA_`R2~V=s$Ba0$KJtv80_Esmk2BLXYB5(ItE2#Rmro6@Q>?b|YmB)~ zNe$vGAST5WYJjAgA)@Hi8DrM_=$(#v0tVw0 zBI(>K{d3V~kC)eZr3*7@j2iQ@dut)1oGB^94?4ZM1+yyt^$*F~EQUO?R{%YV$}N=y z#frv8+{g7c{oa=2Ew2@M@SZ?$n+yHW5|E@QT(K;Zm3HHi^D;MAEpVu4$`G?C`eIjq zHcyAUWOE7X^d)i_GaVniUS-W&tmk6)Uf~AzDqLgvz~g@*45YvJu=R~xB2Pr$DExo5UPS(uo)k=Gky|gFJ4nY2fM}ILeg7jRu#a!$%Qa6%W z+gmoV%=4kkg_qFMX1#NB3*TKA&_lQ^-NrPn0c@(QIhB&X^rf4lEJAOVXwXa~;^8Wp z5+)NcA|;@7frv24B~3`Qf)z+E2z%lJR!`}-;L%ZxVBXlZpZ;1GWa3JG0*M+WlzjI z7kcGF0EE8vZHA9JAH{gwS(7ue-LeaR@_Gpn*2q`_G8Fi=LaC9t)*Vn(fT01G4sU69 zySBem&7bizuCST5)A;0k?dsM_`O9c`ks28Lzxuh5;AjImst+KeOi2FR5=$fFAtU&U z+KoFO9ZEm+O!Yl{wK@(b}v>(NPi!?|c>zxUQBq=`m*Gt2C&b>BHES)LZANalk zxn}^h6g(l_5lc)R{V~41>gSQ8&Hcv;9Zf=%(&W-JuUWKRIl)HG*UXMND0o&6;E1 zO;I>2h-IuYAmvKV_w7yQ4QAlJ9rXb>nsV6s0DBoeg1I@Q?2PB_l{Z^0D^o8hhmulh zd5)v+@!W0c;zBs66m#!$`#pXCA@00wmX}ZLw1sLqSWJ&AKe#t_>g*dk#65;{{gtX- z&=FBak2yIB-~HzBqMHRn^#wkoFUscwUjIQ?jo$L>f`!$4^l8CDX%V&U~*=V23%&;1E9rQZ$-xCDwmIFvBBI?UX z^$|nkWqat4tGU<2Q`*3Wm^d&NoTipwjnFJrjl)=X$kSW-Iuo^}c9AcL z00+}^GE@un^>~j9J!y}P@6bw*E>yKmV95c9uIRZG?fIAEm>;^T#o&K&%jYqTuCpXO zLz{b*X&U_}G)(S(-l7w0kn&Yvas z?<(e-=(Vromrw5l=R#*+LO&8=Y3wQ0^|jn)l>Hqw1|GJllFfW_jg#X+{N#iaV#2+; zo5X#*!R3>qbBtL|^JfNQ{8!6Pg1258*uC}^?-JRT*^%jH7_laG-KfnvjW1fh-?A1Zr;%QXL>j075*zhi(aNff6DgY?^AoIqpe`b~YZ^7t_?T}7SEy|Zgs z0xDTwKcmq2Y;X>6C@mg6*F7Mpy4}~W0Hs)*YCDgqrRphxZwh_uFsSl7YqdJbr{TBP z2k7;?mC(L2J#j}P2P>-(u(tz_mbx;@M`6+`U^9p{-;Nk9z-G7`hx8qAo(!w;%P}S) zsvaA-azJ<71*`1)0?XrQYjn&`p;~zc$it+yXpRJo|JYbGGzBcNuV~r#w^?-RtK;kU z{T@TZRN1ID7g*q+-a*<}wSxOuW2gnp#OIv}LDa|)I)CrN6M76XpMA~+7((9w_ZY(x z02Az+5Lj5a;KJ0Z#`!fFVr4a3wqVd*#Q$_(3pY>#?f7Fm)6HhN0iPIf3B;xZkk=lr zDXSN218zCmZu!9bvJLDg#eDIk>cxGC?UWZ+u6ydn+#Gr0e{LzP^2U|p{6?8lZ|^Ri z9^*Mf32p*khU)sO32%dZoOd)N*ptaOhFfWM#hH38IqEE0_=;yX)wXM;u{Pe&w_W0r z!q*Y^aLGo5iQ}Y2<9K)?b2M#C>p$Ku1HqA2(y=?2g*Lw3AVyX5Rd*%UT)0`C8A_nLOncD=mI)i@&S6wb{BUc3qD<@WKOnd} z8?lo~XZKgj9!H1{C{T_fJ;rQ{m2w~<%zY$fS>=x41{ehJujQ9eRP(J44ebL@u|7cp zn0Xu%67HKC{P^Iu1uU`g(KU;;tOvii84w+Laub=82(xL-bpfTnh`44wuslQ0(kTn7 z3IA77<<^Zn^!=g^PKuwO1-OFA&d&;fHS~&90ZOEmaC@r!<@Enfd+B-kDZTc-#j6tH zc(zpQ_v!XWSsR@df5Cu@mfU$c)ok%sxvOhxJg~gU7FzfNfuq7eI&XU$zL>Wo3hFwk zUsf9_4de3!5+98V-z=B%wNHTEN`S23Dfqv9X5Yqdi2+hj{B=MAlDGO(00DTcODc?V z*26qwWl87M2G{M1#=F#^fA5eZA$WAekr%u3<54G4U53J`t=>~;;zcpf5T0syP|*Hz zi;;?hUjM15Hc&+J5v$60(c&>%#z1z|t#`$XjsE4&AyY%oFdxJgrREnO^d}gnQtn%D z!?&c8{Z-u2rcz-hGjduB2u0DHfe#9SWh_BwuwmHA(u>RCeW5yK6eediBHNmR4`6CN z7Z(6)>BErF>oEjFGCsGxWap+PtfO<>4~g}DEl)%!$H6+>pm7r}F7blp5Jx{ym8gRv zwXMAN+WzRea8J~izk)62V^8LS1-*VV??L?_a4EvN3O^A?Mb`Hs;LZkZnKf3F-SOAy z2XhJB8N4?I*8R>a8aL7BM1})97qB|{PVS}8z!?ky&hS7YXOlf<8zM+>U>mP03c4V+ z^ov$)KyA&re%e2@{wF6jT^+4U=1ubBwr48^9LNd+(JRD<1qt@+M;vt@??GlOD2q2x z<$a>dPDu$7XCwD+nPqY-ej>aWeM9$edY!>f{O~j*EnN2NzgAV+QQ*SJ{+P9X&~z37 zO6EcP*J8J6WwciE31oisFVz&7aiYtBF9ji;-yx=s^w(sw*njT%?a0%(M+<2Z>}bwx z9UGfZU%oyhRpHnN;P*oet?G+;UqEfUW~qnhOVA&J5->zK7Yi3gM;}22Rs?G0)t5h& z0sE$Sk{V1$YsF_R_&TB)Khz8HxY_=8KYrjAZ)sIn0Iu{=ECPajl1(77*-;GdW&ENjdC>CHdl2w*@r@h7Nu?vC2(qhV?{h0(M= zkZ366H!cVBStqtR7G*3H`u8T>m>)Z&K!VNjYd9XYz@c^yq`Gl@uC*IP*RHpl?!x$2 zQ0meB{L&TgCs?2F;Qe82+>|@Y0p2cuR7B%P7BX*61wE)T@EnEG%Cv!L&;EV|6Byja zc?5T{UdQ5vJw2p@gON2Z0EW(~E@PWRL~5DzyA>oH{|d-9qRr5I?t5`3>hWP!y8C1{ zRjaZm4vdzT*32XjCIW}*v;0Tqz20%OdC+g&=0>hc3y(3;yUVeWzxj>nr3R3+P_aj& z&q7&p_t+L*{gXnZG4JK`^vk;lJZh@H{?=f*`5&c;)~YCKkpPrrwb_X>44qO~CX#Tlvs2?Yf6TwYa?~q9SiIJ)(6Pe|+NA5r2x%U-1C}Flv4J zf_r_Y?qs?bWQ_HcNBa0Wrj!8hbDcC2XzxC)m9ILs2>(wcq8|JMD$m#B+ljGLYg=(R zjsGU(WCQ#o3s6I%*~xx&7ZUaNcPld18=1Up1&v1H3PVmPUE45(?Ug|_J2gm18(k-#=GbviNA&AIHxGn|8##ytZw%9NCK;G zWwq)Dw}BUE-vKwBoJW>O{uH`ZIRATvs`?OLJVN>qpQ_ZNDokX|Wg~;!Z%4yBPA3Bs^_tZQE{(tRzUHw%T=;_c6SC=9~Aj-{bR!S7YBx^Iu!v?hMlI2C#I(f!_? z7YQkU82*w^ft!+&lNT9iH*|LkZx&coZFRpxNk5T|h>fid&%-o}!79}5T^aur*6?nh z-|%i5#U0?ZE35I8&>}RT=;_1c$%n9V4dC>c+1?@TKX+DI>v6E!_@~Ts^vq8S6CqYl zW^#Z2?+Zl^bmy{ggr7s4KnB2O05!V7d*G{fp<8+Qn-Hqt`4K#|fVd1XgJ&zlJ6RUE zyMfB(ng?3mU@O{BzQia2OjP%W95W>cgGAE_?|Y5%3TA6Yu~%JlnY{5K_`RTGx0mPxz%{p-|~WzpqNh zx@h>FH~2+@2?^IT98_=8YF0Gcg_+ZHb1Mvg6RcOy2)mB2%O{K0=M0`1Eac)7#m{DATWlnu52)!i9Bb*{;rOPv{I!-| zfS0$EMNi3PGuq#0H9RG5`C1xk_2VUQ^+m3q1$yxd)Bwn_)jnAa>ODgP8_1kp&my=Q@4N!(wl1o7szR>lLSC1iEGYu0U!j3 z+W7j>zh@2ymg%l!wNXVtQC}?)tnq?ir-CM;zpUGfA>{+s>7_KtJ6yVcv!#?6F{b@y zm_9$#L_58iY#5*Txqr~VJ8+Zw)~);nTY1mMg`%5^LiSj`*|zM++R%ftG5=gPQ(*Mc=Sz&E0$kp-Y?Fi-i$WUykYxZnc-3?(Fh)#mBadEASP_%D@0| z<%1@CZZrKi*?G#`B|l;yF#82e-sObv@$^`(8}L1Z3<|VC*14#gO>E%cfluRV)a#5l z9GCri-E2kye-Wa2ii{OyWky?2p(=+$pYLE9@rt61PTGv4tC42XC|2AP`F30}f+&2+ zh#-+l^@Qo7AM7+W^TT$FSHFf#nghYd9yq(=wKp^G2a*sb-?)*=mPoxLmO#Fye_^Jb zT;q~O2yt1?RuS{uvu~QvmSc?B1#Yp!A$w6t%AKUR*?uLW?e)m}FL&>G5(Dji38iol zY(-Rj=|XrY?k5Dq$HtmSyd~E3!$7cFYa_DaU4Jz`7ScjVKnv-Hm;6jKgq~Cj5)<>{ zT*dXKHM{h(W%&g`>%lB>Q(gtyH0guN&dU?D!;kguwdAljokJqnX zl{}=!%cZ3D&EY2-3c+yFD`(F=5L@&-GThGgiyWh-m<7X$ry9y4a(L^pNwx0{#RZ8d zl{|(8Jy%FOIO1df${tZ)yRoH8+ah0Q3{nR^bID|1I^|hz7LU|V#SocyvnunG+;{fX z5Wd3l?Ifif@0Qy_v^FJ;`HbR^$%3W(hClrHJ*KDlg#xgeIk|$j%{Te>+fsD-tD#U(PWjDsNimZS({6rpS`x1UvOE7P+b&Gu zi!VmPE1ZTNP@DK;x15-Z?TJ^@4K=_?$V3*>&~@kfDyO}fPJFTR%&Ou3gGT8l$FR&| z(Rv|+Y0C)WsIT!k7V`-n^TJgr??lUsE@Za&9=plt=_0&K9)>I1Pp_=3EG`;be>wsq zJB-*kfF1E|7Ada@MrEY%Du$VKftNOACzBk@36&XQdW_2^oOD4QwzXgQid^0+3)5L# z7=S?ZJDZi|V(gx(>Wa(;)-u6C0`W(>+0SU(@^Y1Wr%Krg&nA6``c#FcHe~Rp&fo1k z&-T_6TG$EM-h@W{{&S^;?0L|ubJqH2f!pTTK0L*M4@#a{5DGnKPv}j`LY<+d1W( z?MW4n$FfvX^70s~Ryb!0PI8}}Dk%JD*qoR;qPO54gB;O&P0h^k+=@FY3T_T3IuEYh zcwjf*e6`=pQKJziCqZ%Q=1^~|1a3P3{fXFwU0kP{1^>L)eaXVa&T6UEMhkmdPZTwF zSXh%f9JA7mRXiT|(%?<#SPXuZ>2y?+j}h0n65nw+R45ti(_#c2tx-1?GXw3O^lOmh zvv;$6^ZJBxOe0Coc~wr=hi4f#iCJ(|3g5~fwIZ+bUE!7VXbU}%&RFajig=&tXZipxy6lT8(^@s1Q$}*vF zJ11HPSZ2hRRieF3M&{MYP~6sM4Z3M}v&OBbx|=n}qx*jh4ws6#kmr$QIM?V z_rcU&4%<_y>7qfAzEXfFGvmX}|I&pKh0iN&L9VBAkf#ZH~>Pp+4-SUSf|t z#U5=Sw)A77GUFl;+AfU{gxHDOTF@GL-nKB3t4icc!C67b7rta6TdLoe>@H$iD89SqU*?{Noa;D2c$4V?`G1(dxy z$l0Of{fk}Mt*`fM^+0-gs>)hAcYVRJMe>{BtqreqpMPiK`I=!jg~9MCp8XfWXj37o zj5N64ez1pO02>E~0TBN$C~kCxKiO_KzT)#YYJJVy00Ysl)&JVEGZG&i@!5``Yq*#? zv2NVx0epFVV}mij0+KTZZYaEpr!f+cW;EX;v}mE|Na5S~1z_ z?#-8RV>(cfXi+=_9^{TIE9$%w{_*gYr`e2^L(8F6Ybf-NG_Bx*Gcp|{QIex3SHZ(u zv<3A&+rDyD2bzZuk3I+PA%@UoQFnv)CbbCV@iu#d|;RmRM5ZeFD+LfX}$jr&n#i)25b|B8q2VPkZB-`%+I_ z2YPQ>e`0n@?48!L-2R8UO244!0xq#QUNVP~*MYAX73jsXrSCs25)6V%t?!$def$(rBJexA{dO1M%n-M2`K`6*<~X_$2>NniiH)M4NZ|4KCXaO^k5Tk$JRN%67p`8VA74D{vfC@w#~4deMw7vUZE$00N=f7^tI4$Q%zto`CTzi3?_cK5?M zyJPx>23VNShEj|3Y>}<_eq;GA6Z>XA)^#ZWN$}=++FzEtZY!L8xnM^rGEebG_+-LY zF>Nu#?nhZjbN22vOkjU(tT8Bv-D;)z{oIxyIV_nyDqehXII#T*oU>V|8=WaZ*riaL z1>D=VFdm_4<23aE=hF}LNsv(53(`3z}iNWG+k{| zW~CJ5-ax}{eVgSgov}S~x{qxZzvXVtjYLCv#j5twZ;z9KimC;Z>@OC7FMmAIzb2uh z9?Y%q{f*0dv60Tg`CLZ!JwC~nmc2Y29{h7_D>W!btspb8SIC4a$t<&hq6S&EiMQYP&eq*w6E^bZhEJHzLUpMG?sM8G^t=c;jA6 z-&;&;Cg?^-Z_6Ut94EB>ZN%0(-sXvL!hkrB0(qvsE99Qn7)C|#$Do`Mg|>DFff*4V z3Oqdn7l~c4N~)j(xdUynyFPc4cKPmVFcjVSIS#A%Kz@<^*&uBS7E#9l;CvkIoA&)efk0jUb@NQXt3 z_>g$!Gif2@@*ZGp7ck5dp>bMy?ioBpYt5OQVao-q$P~X{-9k@cknCte(07n2%+RlM zszSh9(|P$_y)GA&y(n5X|Ft`hdtAO2+B2 ztVgSywtWq#;35BlI{Yjnj_^Tz#W*1So$bwm;H?W!2i}nd|wSOp02T{5y5{zC>v??|5iVmwzifwTk&Gd@a6Pg{HHEaY~i`6zvK!HzVmE` z(MN1BD-t%C(^hE^$fS%ZJdJ=S5mS+IKfBCTNYG{-hv{wldU<-iCq?#$b2;Pm1Nj7m(Y8PE^k| z9nkn*HU3X~9MVFE=gfhO46x` zx1YN#*XqnXWZbuyt)RyHWa>s#+Jm(%@^A;gw$d4Pw5I-T-Q3yqSlYLnI=|89qFS}i zbvqe#69Q)wU!P>KD>)FE=5m?CzCydrDI?g zf4<8Y>)w$ZgHyfk3j$kihLqn0n1?cQd#hkB7t44LjyW)$Eq7ne8 zm}8B6_wfPv9c~t?y(^@aD+boT{_-mF6GdsNg=i2o*=sDYw$O*Dw7`XWP=v4gb9wWI zVr1ULU?G1^&rGK}H}Hyop1iY)E{V=+G7R$&EZG{2=*{>lE5LT4c;~+MD!NJ8X-6Lh zo|zAcvPDldd>E_pdwdZJkor@5E4M|DS-NIMGUo2cnKXQ0pIZtnxS?Azmb;LX| zW$Xy%NOf=nUy#+L9D%n5$&md8cUwGlD5dTIx1}E)_JvUjV39v~TomBZ8mwi2Xs&sX zZ4VpAh{I%?6<GK@Rd{@Y%m=Pa|EulNo@7d35d0E;q!#G#x? zeBCA>={S&i&j(KLCOOfp-=!upcxiWStokvO`_5V7iNn(#M$rI|`oEeaH8)l+O#CC7 zO3Tz_Jn-U0h%7zjPI(o}U@B&6A|Mp6P)>aorW9aK9JB9GgYkDYauZ1|_BRr=)FpZF zMKbEmkD?t8&01=_FJ`}h=(7L|`g5mnXmGg(xg-58UyC5{4RkBuYAQ$TMAWkas=9Fv z?y8_+Zte&wu1G3Ii_#G3?4Ca#i?XRFsIyWO%Z?<=#qG2AY#shqyIkK|#~0u!+Lq91 z+gz~*->b}{j_{!!?h8^ePxLwsZ#0pzpMliowg_CIS^(BPYpxKrcUfhq4W5TT_Hu zbWs#t=N``Z+k(;IVZnn5a&3Km>WOofc9AO$x@@26bM#GU?KgVhMb5NT>X{_UMAPm_ z!2r?CD2G#bVBcA=k0|qEU>BIhb25&3xiODi)x0`+hm_SCbaTALFy0d?Tk52ivX`z`MWyq?ZHn!icmxfk zb8%0xod31A^7BWL-F+MGR`WWe@7I0t%D*w)|7(jJmtmN?>8UCXr*!JB_o}dTK`-m} z8-cBllGTVnxk``?qwq=6YDSA8wLlg!;PF>}=@W5@{prp{A@XG&#Po|-!=kl`=`X;Y zI($-;6`VO$gAv;xTBfVU*B;BSPg+m3ntdg6=alZ;zx9QED1?o+CaKekv(QnmC66$B zLWgWiLa6vgUTRui)Maz*H^g;~c(L%q24knd1YAs|Oexs(W?p(2#aSqkq`a!0>*YCr z0x=3Y_Z^xGx2m#=AFQhJ6#dEfiO(G$srnB!>WxzvC{<@@oOR<+EKGL$PN6G8yXp;F zP|$N``vl@LkO)zvl*y3ns7RG{m3EaT+o+XUu@rL|TQG>|w}VLBuf*?Jok`a<_r5Xx zqi<3Wq%#!A!6s5a;bNaQCzRP&ND&KUc5>IPDyu8g&?Z*sARVHOh@EwsWL1zOjmAkb z$yH!w#eW=LZYC$d7SGVk(aZtUah-K4sN@rF_^M2^YH5wIa`9@=F1UMUMNb{sVLY_9 z$IYvl!;s?Ff$WOYlrRtD!xa?~MAZE-b1S}+$PpAk@RM*)N`z2mjKw<6bGh#a#gZG9 zjoI>t-2_`5HiZCe#i(Ae0 zUxR`KXzO)-oloo>P1;ZOV%RAfzpwQR6(DUPrxNxjmkJ&SirvgjN5fy+7fWT_7|&^| zgV?Q%)$~YbWMpp9KOhvGADJX%jP<$9}WTKGV0TLf(pUhjNE(&SAHCyXh># z>%{hCXBq(i2VsQ7d^k-tb%J;Xb#j%vE*IL4N~yC8Oqs4a(Bu!nq-CHVY7-kQ+C+ri zgi&dvh5l;7b>OehEZAv{wHE7_waJ(#%)b#l5`Q$PP2)M>c^)i zpUviLtyX2ZldQJav0fI%%X>6H??a6pm9)zXpXOTmQi|BvQWqld>KuQpbV(QM#>dOT zr+i$B{Wulq+0-}^tciyVKRK2GxC2F57#`l$iqj(51Nz(EO#)}$2z7&jl@^xKe*g6K z*N69xj_n|QgH7(ZUMpqUE zC=^XSJUzde2)+lvJyD_HIN_~rfr3YFBagpcRYX4B#c~#5T{BgujSq_6-guVw2EEv= z9x9agLOXO!SPM*`M^#i?&4}6DXKrzi$4tog;7G>k=40#}DSe6Eh8L4Pt=BEiCe5))vQ>hlFln_hgZsO z5x{_X$~P>DjP)cyA=3Q;`iYL1ZjN8jH-X_wXQ{*hSEcqUSAb)p7|w{oK_~G-556qD zdO)IhX33sD{wyAQXL#izTHdVBByEeVpb9&Jk&HAed6scxEg#>hB))|{;Phe zSHV-rG9;RCJ#?+#XOwt+wI|TxuD{`B!rb&kyXu(DgBHe?(-87OtsrbuKD&%53tJLu zZil!OND{deG}-$;5&(ycYhzL0r&0Vn%%9C~sPC9Y_?VyW{;;1+gitr#>95d5-fR@&Gp{mL9kQ>KM4)Q&iT<30NXDlej**R zI8;3B>ssm3wgha#-RHFvCm?URkHnKUW2bswlGETH+skAkcS3?}6|$enZ_ls}o-j}< zrwYE0y<~l?#LgBwHYP%-(m`6LqgG{j|4k@88EIEjRiU1vHzT@2==@FFr`?dB_^Zt< zv`)Vp<~46BfS7Am!1nnVa8=_A6qCrFrksLGk1LiD>Jr><1 z7D_P25wd6HsFlRl^bUUoi9C}pU$^1kL$I_lGJ*nXN z`+oD6&9auZ@Tj!kQaT+|;o~Avqx9xrlRrDlG}}4q?7jjg2z%Y@p#@@S-4J=c={3>` zCcbz=tK!D7lvrJ%U7arGoNjmjM~n(G-EomP7(^Gfwq=8#&KK8{^D+q@ z9`2c|#+ndFwZ|R&k;y4XznGApW=74i$hoiZPP=^3{oUj3X^s{kj6?1pPF~-l3tn#yH>F3>(fUM4KEBGu};b}L>1w^a-xk@8;vBgjk za{VN@Ek8Zwa}hT3|2d^+_EO?01b6yH5u9g?+^}Tz^`VIdp0SsWUy#3-mWW-KF!a-{ z&u-CJg7m3{a)9fm@1kYydT03c-$ygN(}^u_K;_&5Mqw-bAZXVFhTp^CQ?mIcCke(X z&9hcETn$Ugx!1_Xh%$eL)jBQ?k57TQHOI}m5 ztxwSP+18;IpGeWfWq?}MymCY0Q-7n(@n3({5PS-@mrP#NpS29c>i{@L6`zm*SEJEw zaD}rSjp{5BSJ6WZE{->>Y0E25uW+MyqyB7IugJw%dw85JCjf~u5Zm


!plsER_WS1P?J41NfhQ@d&Zw_i!X@H(Ij_91ie`J|qU&2p0H zu5`|KznvFIuJ)tYQ`nD3Nhv`erXXfi}no25IVMqO~@vW~b5a2vA}@$dmp2 z6LpBbOG69SsL$ekg+=_JpKg-jT8MAjG3U9l-VY_pe+!_hu-QQjtPNb8sTGyBNh8sQtxeL`x752CZ2GqA=WB zMMRUvcSN`gyhf=AT3AJKzTi*3tPonPiu(`ApFPOyjD~BXZkq`!GfpM^W%=sgMXOzE zQ@a;Cg-FOh=+^-@Dfl^@tFO6wtEJDEi#*Wx!@3y+2Pwp#EE(w^iE^g9zu&q+%Hb(3 z?b&6B)?@$3x}p>UfGFowSmS-M&^>G-%E)@&B@-=yjNB!}0vO|BJ zsWi>t+XuRSacoy_)_!WXzuUV?lgw~PQo*JK6{2gB^;T>BAk3|C z$7dROMfMkHkJ!+^W()utw6Rjd=C(ZWx;{*0Mr7-xfi_IlZC($6XAJ$vvULL$gLHQ) zwIoY`wf?}3sa%Hg8l1Ru5yLM<*?+#`B#F0KNkRo6ZynQj3g;9~A7TJa-3C2qVL(!H z@2%f1hm;t34nAD$>Db4}Prx1k(!~RfpSvFo*Z{-Y1jHri))SY7d$979&)mzdyM ztB02*Fl%)??f9V7$?$w2yR{I;c_^kNUB>i}TjU&9Jcp`QYEPm2*ZQG|jcH!EI2-WV7tkg4tL*-*WEejsyZkMQC@!6Qu`o{-HknX3s zHNL)KPd!tG0>$ZYoC_wtd==!{qg|-(vKlSkS;KQg(7TK5H%Y=dS%I8a?$`-6uTX{O zTzu8`#U?FRZneyHI8uK&+pMZVLN~-W`6iAe_rq$j+sAF+#RpNc_7z&_?THYcSvED# zze6fHC%k-8u!2WPeamGvx|YUgS_Ihst~*KpMN~~d{v#O&Aez^C-ovPThSqqzEbi+Db z7GzrODz56$E3#gj>^G4a3J}_56R4}m4DU+0eEE~BvaZs-_8sn**>oexZ%)s+UIivp z<)$e>+$d-)tpsO-3=kVvc)O+sdM&<7W5s3_A#=}Q$%;DK3Dd_sww2)X?%Jcdjf$K7 z6DWDM?NAcX800GZ9(vV%5vksuJE6$O4MR;oc zMN*5$-Yly*6;ezNiPwxEiXp9HF?HH~*Tb(&=;t4RJc-N6ex$F!csw{b=qHf43r+BI zzHSFJPrChK1IoW2s>8=p*k4mcDxdjX+ib5d>9wl_(Pq8XmXg^^&gZFMGFEuRZlr8Z zL+wgbFYf)JQS zouOGM$S+a0WhHc^)-s3+@^F9jNXk62)XL{;5dDX=|J4F4>S&m%$V@$NmQAH}B>B9q zfM_tsLi5*ulGG3hz?V4;hG!L@kE`~&qEE--{tnES<#1*y!!Z6heYc-|8M^jtk>zk4 z$dp8piMca*&LNdHG!DOS_@}HklPy5Q0rnDu-ip|1$mov}=0~LuF*aN0k?=c=#EvBA zJO78?blk4BoQ`-aP!o<>lQPqrtLAoDwvelp2g%E)FyX%bvXU3}J%jM5S+=B|F;fAU zX9EDY=84YQ<~l-daj7!w^@Q{ON?zsKTkY^aJ1mM=i!2W%osO#POPU#JGe*wSg@&&f zkgIKIe8gZQSu$H+<$bV{0RK zYl*Yq*KG)&7Q)-YT7OchsE=A0_W?8i63#`9^owYT&V(w>b^RJUSfG5AJ8XR_qMUf( zk0wNW`;AMqrEfgksXy&ephu+x9Ag=8B!PUBoR`5BilO&x6!{Opp*?s8y8{Brd(zu| zM#|K%uu;7VPSo{^B@RgQG5>!~^wynnR<8hyg62rVNr|+j$i5RT%xvcnI~0-7{cL7t z(mKU^zMROW(Z~aW-f5uS4MOQZTC2Ne862;w4XArC$GQUDf}Yl=Ho{BXKQ%}xdc5XE zgHjy9p5Aln&XKnYjkaI`e6Zapeo(jrjB4?rB$qthn_ba{--!%i;{OJB-}r432_R31 z($jxQBD65vf4}n&{BwYhDhImTLvIn8LzPUk|J9+9BraH3X>1`@Jp_P;a~l?^aDo} z;f)sf#;NNa^J)CB$xE8LO0FP1jT$@l6ox}!8zA2WVy6F|ELEe**kPe$Oo0Qa3lF&> zmk1PYk&yYHxPD;l!HN8p|E&NTr{urCkw+vk>BgP-H~&&Am0L$69;xZ$a~B*LYN@z(uV)g;*e6-Xx+Bn(?T&Y^1lep5EQ7$#B2NXV4M@Uu z0m}2Bh23YpC`|Ku%diXmYs;MA)Cttr;J^W=Yq>Ma09$Rm)UG_oUc?dqxuQ%gK^Ta)>5!h~a7+aV=k1Gbl7Ln+@x3!H95B$NC3BVC zNE`%^!vKu!)yo24?&&vwH_cs4Kf+OF(eRPz|D)=?!{Pp(_u(Z$A`&f1NRZWAi0D0n zgy`(*y;~)Etg;eGbRv51ZP$`uiJs^sh~9!A+UmWo{VmD+^L?K4hl}fSo!2RIX70IX z=A4DyEv;DGNc_EV2DF+TYzm+8$5~&+tD7-!+;c%4v1pnlb)d8;c5bZ6_2fD56D4_! z;SRUem5w0W`9Z8WiZtvIaS50x$&m>`@H2h?HG3674_|tEIR`+kRz&JU(-hWt%HY3B z5pd}x{8extmS%Z_e^5j@n2XYX$7SN{%SDs@)5BkOv^zvzCW*F!z6IVTCitgICdqUU zbfq&zUSj4_2-0-qz9250PT6QDiI#hY*V=FWJ1}Z~UYjD|;e1M1!*_oc25MSC%_w z?`6l6mw-t!hs*y1@NC^7q-zErSX7g~s?|L+qO!8%qft*zN&z$CQ|90)ue;ocp&by<%gR*|W zMt%IBS3^{hj!yk>4G<{Zxu}NInfR_$pUY_WGhFR1yI84drF`@Qk5YyTgZht@2LL|H zTyDi>9zkyQQ@+b{75HYM)T`q&wXkmBDkA7>R-I>fLLA<|MKzNRDCtcjkd?S}{XXbl z_8Z7>sip*rKXtA%86*UHU9L;%%3m@jMrU@91771tZ^?7MO8HO1_|>|f_}Xw;5&)Z& zp8e*XkZeQbXm_IK;9w(41I&*G2EXa#QPoSbnQ?)2N^TbF+VvRt@wm~r<|B|)3K8Gmze#+F*;cvGAa!tA58@RTJh`?FH+}s|2^>SNw$U- z=kwx}QD5-krGow@c(a^~d?3H#)YjI!$0g#m#rvDjjNU)n7v|~?(KA>c&VVVsU^pfT zBA+_@bop^JenoVt7fze=VU_phwy+5ozY6yUb1r(CPIrm&v8%A-?OBKz%?k58{N`OP zuF_##?r&wj!Uo}es`v6*1|ppwE_+cygdN`#%i}fEJKwG7jmCbT9nFM&mx(7QKbbE( zo**)9tT>gyHW@aJNt%ajzE`y7V#C=V*8OJLT;lz%Yq;x^FiyxI)7!`vWow?b-z8l3 z`q%p4iW9ZVPT|9qk01^C2cxaGbuO3lTee5B7=}IkmN>aD)K2)3Y5nexp$=IYT$#bm znO%%ff2vFJB=_lsAomZ zlawdKjAs($b$D1CsmV37JC>AWaUyJP%02T?L|1hGotHasx$;8f`F+B5rB`0B$}aIc zfJD)A>!8=jTAmL?yrwK4{$hOR7Arz0CSI;f(*8x5>z;#7<{%oAYiw^3hjRi*?x%!5 zfXazv+TBC?mLzKjUaKQ- zojMFmlBQM_GFoww%pSfb$E(Y>&8%>!L1D&@4Gi23#zxorLDpiLHq)@x25OS!i4pfY z{nNx81>G7Q!#hvf9~PQl3TueMlyk3hTxai#yv47@)lbzEaXFSt~5bfEo>uL=4WJ5$Pe971$iHY!)8;Qujbwl<5i@82HeGFE$AYG=xYF`9cKn? zsMwzw2|dhFMg{ObW51K99KaVGur~qolff)LSF1-I7o!(yOfM86iyCVUzMze@Qj;6e ze~vE+y1+M`iwVv+=Ot*zd+gcMp`Y1=cS(wynktOf?(vewg>;h3xVRo}L#jJ&?&bX0 zW@_Au^)v6OshtaXF@oO8BmeOJD|{=g%|cviMaU7-h{Yv;+jzcEz6?1`Y^8w6L%XY& zE|f04nX3ZFp+CFIojebWWhj9D#t6ful(_2LV973k4ckPCdf> zoJ%*A{Rim)A4+iP@ltVLv@1TXZVyDRP(C20 z4NkQqFCVamS%Dfhfn3_;p467ATT?sDswtE&FZH#j*-0{ZcUNg83|AU*yiap7E#u0s z99>jaI1_(Nc_dk8^k^z3gpxQkWW)Ep?@_F6-*`ekikcNTZ)aRq7xSW3OIf~qQJIZ8 z9E7mV)wJ%7=bqbz))BVdf(|B*bYd zYGZgEZLk=V>o|7wwucSb_GLYoUfqTQXDvE)FT7Ad1L3joFLpl$!IE^|Jhs9aMjuZG z4`ZLNaaUO?wYar*7uiYDO*_VQUyN2^6mB5FEP1%str1bi@PD>XLI;#Yyri4`%DMh6-{yxLm_$Wwq8#bD?nvW#OixYeLjB>z;l_$1nXOxM9 z4g)e@Kp&gjgnG?&q%`-vK?0`z%WvD2$3jV*{=_l+_;vo*UC~`TArDwTV{vTak7oYG zzZ8e)CB-p)LfUkZ|Ci$^f)zuL+PuqX+hRTmURmx}S~QYteiIZi?-2KSffSnxwjjBD z_bwy7w2w4Za)(RM$Dbnj^3@dN$jNU8x8!di(Xm3-t8m>tlr4A1fpOW~bD+85lrrbb z;`WOEVS1|P6XqKt@c8bCLTbJjs=`}~3&{~--ROw)ki4oE*PBZKg^VBh@~tDz<1_Z& zZm2rG~2Ye9@G3pAFk znM`X&A-zT$BocDth$pgzd|0Lii@vHIIx+L$Lo-C-bk`$>4e;>OBoEHW5Ey5;msUxn9y zbMQdr;oe~j%vgJ%7BqeKizwOsOqwz1DX_FTu>N>6oSwI!d%Y@@L6{))t5|{IbF8Lkp7wFwhOQFi zcY;}Ylv|Ia#=KE08y`YK?8sTG%7Y#~p506T$c#e`ELL^zELi`tqjFpEZg>t%GXgJFSSigIdEfUm zISjhYzN+FdH~f~k*sRVcx1gJf6PZXuO=Ck@F<~_d_UgQ&@QJ*`OOnc`5=C)c$spXW z!57waCr(Sku=p)jLWNg|TRF7TE1xd>x##wE;FMO(WMAaA~f1)zS#wKnuS?K7P|>B2n#*k@()w$@oM#!i4Dc|_{Q3ni%;tZ6c(VvV4R($6QFRA9tc;`fQ)f zj1i}!R7xtYba)A4AbQtHK3_C3btrmq=nDkfRmOv%Xz2DoqBLTwGt++{n}&gqzkpW%j3%9w7_H`3c#4!CXin} z`9X6I%FcM);6xN_q5vw<5Qr0nHED6Mif}nE8ZDi}pnDR9B~Ot3Mo~#eO06t7ADpa> zl2j)5Z#*^&E8O}+f9aPqWsYg;nZ)ANwh@+SKWp zs;Jm;vvhY^sf?x8SJvlxofStsSqz0e@X(V;nCUHJNmi+?O^e90aDK6`#tt^;#twA* zrpDjq7BtihMcIA%+_>tq2|Gk!PiQPeey~r)hcKKg`PyF*+7MiTx8S4xw-+3j)zgz# zZ=oi!DU6kPtm4?VhEy7pM|Xv(%Xn~AZgU#S=SfuM!WkuH@nF=U=SXJH4@lkP*rb^0 zlg4YQ`Qo;qx+VoqT_wHNcqYq9cP;wqNxZC7_N|kGr`b<@MrzFa6 zc=1S$_|f_)=MVS2!=>hrJtC+2ahrhxN)R_GC6shFHE>!Fb{FM8z73?v4Aosrjf5_o z|EhWSpn{iud}~uklHA8A;M{et#W&yAWLO&Y%Gn>Wo1EW&(VjosC%We=BgS_7-$7>H z&{fBtZuy@ap`DHUyIa`XoTxmV&gR-1>fTEj#BD*ylfw(rHF(4*RaxeN<*Cn;gM5@Z zS-FyKRr0)yBgQXgK>sRdeY%UHx6mK$Ze z?t`!87Xzp4o>QvrPZGicpgSitOVTcqM{?-9gZqs&MYn8Gm}ckHVCxf=BJ_;l#oUR$Wem8WcI^>)<>`%<#90)@(` z{d7DLKrK&*h5Z0l#`oxuS;=cT7;`4U4io^ocy4W`JhT*uHUo{t76-ocm~cXb5Bs+QT?{f&PS2vI7xfs1O%y-%T?vz@SByTWkKO&!ouM z0?`P}aYNQv9h0Sjsp+h5)se^6PYhkHh>t(i`nG7-w z)s09~44w3G#ip!>F8}2%LYJ*pT1H~e>Rb5vL9Z#+x9Ko5v#-JzvL)FY6>zbh8+6i0 zoTiO;_eQgZ&K9Y+5$HjtG+lJZ9v7}Mil(z$1wh-??PKsm;ZHM1cNwv%he0MEuT40p zV#ylnRb`$R!}WdHr)8{98V7e%zzf>Q3b-D8GCY_wU&Ko)h3(E=dHEk`Ne z-Tixqrwb2OGK~$^6{=|$xc&|>hkp6x&J^sdx5<*cZQwQA(5m03CHF#fE+gnR^o!;+ z8tHUfMB4vY6RffoSyh`00F(<{`>3mLkhcdUcqJ?YJ&;dWs~1UZ81G{Z&MMl4+5kUS zRUQ86T43*&4*0w`diY9PJ|jPv_?@N>)#AeHGeAF^dL>6k?!|Wx8QAg8w?ntYkrtC& z48~s#Q11|d2_6`|9^zS-9c-#6Ja&n*_7O5Ye`$dD$7XyC!y4d|~E3Vb@g zIBkfHZD?pw7Zw(#=_s&wV16Q&0d86X(y7%f-QZxWC;O?jJ!yg`J&y=bMVJcQ zb@T$fzy8MEfV!=|(+ETj5@t|%M2^7Qrkm%gC9G#<|GO~Ibi!D7hM>c-ru~hDebFb2 zU5;9cV7w;$I9hr|Db4rjhJh-)!)O^0$Wk7FyB=cZxo~+W-mN%9yeiEeNDW?FJ{mvk zcQHUy9K9c|hesAdoMk{{ix{h_`Eufj)z4U_ybl;(caimk1zczP{DxfH>K=gn<_}rI zP;yIiZX`AH&ve&57=^rtlsIIYk{s6tXoiYb2<2c$-(_C(?C)F*$#o0x9UW$bg}oW) z4}*T$@`rt;>e$)Y-&tL?zpIct(8;bUT+Z$DvpIPX#}8JPc=-s)%QMX{;Fg#C@pk_` z9Ud*@oZSsGfn-@L0hu&g_Nm;B4J%6GqOce%QIckU#F9@2BLN{{`*a9bnv4IM#5CKf zpL6Rh_kb$D%wApU-(8A7i}6Y{h(^&<5Pl(ca%>dMEWxdaQhGp(msx0rt|0SZkR7k0iyWEC9e6Du_8_vuoHnE2EYSJ3 zFzCQ6;JOg}5&B?vLjLW~6zS{jw4$;f*TWkNcNf-9%sduxuJYezj3|-o_oAN~_3(Eo zr-|?#swBHDZyxk*@@GGMDr~I!6K()$1^qf8&;m=7m6V3iW6yhHFiq+>za4J z7iwD=l=Y{9y3mjTG&{+o^i`j^9(DY?^}kW?%*WMFD^?vJH?vHabvycgtzo!>G0<(# z5{!pmV`|qkf7th+waztX@*VE$R|kdgbvbt5LtGPtzym;#re(@H1gH5s{*WI7tL%WV z9FA}cNjgK?H>S7I3ZCxy{T|yd?Vsx=Ue}|irw4(kt!r*{++okG<(j&;#qv}=3rO+q z&5#&?+*JF+Q!oFM_T1;Bb*lSt<5^Sof2%DurrYeT!l)Qj-;MXqwFDhV{8NPRs6?nE zRvnMyqir&N?swV!6Z0Wuo#E*dXd1m4t5OL(wkywA<1_5E*!`qoAPP(cAc(4_c&wNW zE&)hMGi*DXR3CHrEKP;6` zY2|4~xTLD%Rw?jhHe8aOc-KDn4T)lQ|kP}rYv$;usd1$`|Tuk5Hi}Av(FCy(4c9xl( zeA-VbuE4X z8d9J!Z-(8b$vmHb=@QUID7-QeJ48wTc(i+_f2JNQ^j<>gC>$OrHzL)vAMQ-w4*I*H z@?#E!)o6Z%Xjah>^|3F}{|w5R5_3}NKlA8VTExZdaUN>@AD+NyuxBn>!>_@bamcM&_B z-qJK6vGzu4*_*M!vez$1VO+2vua z4+h3)O^f_?_iAzl>JPG`M%~aU&>O@yG0Vg$#b8XCpJM?lgJD*jXKpF}Z9e z@9R6IFaE?vig-&;Vp&!QTq3+-yL&RyqW%%kX2vZ3c9p`RhKX3@!ofnUCDrl7tEzIo zySmdwXB};AA+zAD3jw-l(&##ECQTwEg91uO375RQSyqkv43eu1C(1noZVLKS6F#LCZ2qSABwg)HNhYM3 ziKK;T-+hHGR>`}SCL`QC0q_Y=Dr7cbZmfqB7XoA&B^18lNJc`4;V0SUxs|K&@_=t4 zLK8BqmLd5e2*CvcjjW}Syci1{`A@(^6s(}G!-&e2_XG4(brtI@o4mUBstYnMs1*h# z57o-X3>j`(#h$Y^7x(*p+e>?5<_06$wnAo=~P@Ri6ja|F> z+lYW54bE|WD{eQq-&b;;YGQH{Ej+N?f`*Tod3#q+{S$1{*K6Oa05?1=zY3|fH*kn& zY)(*To>@)QbL?he{CG_jJk>NjKHM--cs$&rUjmpFs{?%QEH4?M0Vw9iz`={%VLFXz z-LPwb8(BF&L^kh&|FdW25J<(8hqW3Xhk&w*g<1MgGu0Htuw&?&v1%MOUZgu6yK7+r z`mH7;bK~ioF>6=V+_|5;^l0@@EM1bRM{h-Ml(?f4S9T+KsT|G+L4iUx)6=b_FZhC8 zsWhFIj&Iz&IvLRPh!=Mi&1rQ?*E>Rm;Q8W3vVK|%kfLrl9SI?Xel5LadC#XXzt6?l zO2f1G^lb|V@mr?NqhG(os#O+nC2Q}28X!j9nl*p6-#a@4lLkl2>SbjA2Q24S{)mc) z7PhVP?F^+Kqz83T3Q~bAt_R8r&yI5-93)NF?yuea$=M0D7e9-h{*y{^@z@5ygn}#Vkk7IKNM91p2_M_R0STZLB80S`=BL z1^`WYS$@Jf$~WEj?-Iu;JWf~La7*{pXVV$s4uMy`E`y%VI^c%a?~TikPf;thl?hZY z3(IL$wtCNmzSVjoBFP5NyHgym)kl6+%Kf4RrxYV9J{e`%b`^u#wIWjdq7_-qM3YWaUewmQ608OU+7^V@^;{`Bolwu}6^|kS30RIe7Pn?{+36L+7#P zE?bL{tB401xTFBbYouhX356U*}Mt}w81(SUcRDmV2LNu zBiSIZ;fnD(^W13WATCM2&k*n1(U{_pv=k5CkjDSwre-}#H8DH8B|O00hI=ROsx^j0 zMfaC2)({4#Kfe$J~D=;I+ z;{~-dgj?7BcDZnlutQSPivgMAGNZXWw!w93*nPf>YXI_{flOIP$?JC{ItF=hGb`=y z!put1`TLSs6~f-JHw{gz{&Y(NdoWixb*2J!TS#24Z58HtPE8|mFyDm_KXB(D|x zEb=R`c3-06<$Y~7GLeVSgX>9!dn~I`X%EEv);0s(KFZL-z z1MmS;VcJhWxZ4n#Y`(o2-M`#FBtH3I!NvbF-T1Yws|^HjV{6@wMrrEUB#2(`Y^(G$eb@jmlC zHghQPzrHX0VbN;-W!NKuR5iY2kazOSV1n(#;OO)A{-&zB+GYIZ+j@U|aBs|wx(hu| zZFVLZ+jN>GefzEY#OD(v7iDcL3+nZ;%`*&pi5!ZT5JBu-ex4DA)NkKfx+i>4{a1zP zI{4e*Npc@i^Y)EU>5+~F&++*$q*u=b<-p-zleyVHJ}IMFkZAmtEukJY2j_T1*Yz3T& z*scmzDMk5A=ce8+z{skj$d7 z6|ggzi`~95zmpypddrJ-KCIQ&cGv92(Fb;<17988+<;U2S9Es+_Tp^zZ04vISvI-v zex3*$$=HV#{|6FyuTcTC)4$ou<1-(AUwQ;!ZV!1QSF)F3fZ61AA)rj9w3-aGjWgNn@nGGs^aP2UP2J ze?Ocpw(GFZtNNfMyaiWI($^M_Ii&qA2q3FuXrSqIn~J6qY*Ph+PN?zj7FAwUTI=I; z=*pbezrf2=kXqXYw$tLh{dJJB+2GCZQ!6F?Yt>tV;QQp{=*~_+b-MGzc96&7W`97~ zG13{bKt$9u``1PTYrPM=7XZ*cY}O{HLZw2Cd?z)H(C>3UIakt{yM2?VO5lAOo@;nF^CE-cD73#tyZsy`)T zQNqvS>aj2(32tedGYLF(;?qkO)&qmgHVo>kL@hrmT7w*qyt~=vQWA^R%UfvyE)Ud1 zx|Jy%rNp4M6UYsU-#w-m-D_b8FYnpo-$BmI4T6{Rm^s}(lll64E>K4F7*j2M9#DPI zuD5XMeQ%O2wcnTbz*q zf&KiBcV;RYyc>7>7P04pcM8wr8q|7q48b;qg@uob3RZ{TAz`0MV-kvQ*2Vk`Pfg^M zyPqF?a7K~DeCLyB1Ob2kgFC_8L;$7xh4vNi&KrZ#UV&TkZ)Vq1NwgQes z>X7?rqajlk>7H%g^an^r<=P%D8a~ zBqA!@oS_SBTupph!!UNB9X?--6KjN6U+PL?{6qx?^Vvl^llpxTwf@LjtWrY$y}%Aq z#+liAn4r{pa{SGpTR_4V-t-T>puc;!a_i6c z?6y>ZMr{tyEl=t|q3@bz@H0bt^^D%<{*+3N3%)I93wFHgWq$<1{kr+yHhzqs;FHF* zy>b`j)0XGp3jofoQLzq~LysMI*N2{yVn-)uQ|_za*w#odqQ}6G{3InPYtVr_JO_S@ zMBcAPKVCi7YLVko%TANKkK$cH5Ax}Nc;h}w4+H&o(ISc+Qpx)Zxw*NGLK@@CQdC^3 z+Bg5a4v^#Jd{*(bZnun7xOp~lf~vStygpF~raff~8xwGJRLsdX2Br~Fkq zCnqP*)D?F#BTri=Jzw`&_ba;s6pya8HpgiaF5f8EH!jZ~Exg!oIf*Z5tQd_ilBk(64PE zOi#ld+RNr#PwZ*5_=Gc9SqDJNtYDJ#4PamcIwNy2`N8-=>NLDV#=lJ;M7WWj8D$)# zFC>-0h)4FuG+S9dEa!$JAS=Zd-dEE-vM*%9)nM@B!B)t^t!B@^!>$eG%0e+fOH{u< zU7JzE-7?(orYAd>w$>&ELc%FlcxzSF*q#v*( zfZv+P7&N|*{Iod5iWj)*k-+je<(spXYFOoK%Z1+V8aTW}h$D|9tel4-YJso#QGmsc z;FJDTHl=EU|GcnM;N+}~o*})rp=mWw|DcESHALS@3NY9qp?CBHq|^g3|j@BMwj=a19-1QM@4?_R>v#ivobi>ufLY} zE+NeA%aEZL0lFCa_4f}XIc{)@f2TuoSJvs1B`%IlwnYWzhArB zmQV+O*qC<(&F` zK>f;UUWqdqwRCO!Px-_mveuD z@tfLFg#XWZXJ^g(BVpg@kaUO__Q*gUc^c&`A6OfW+$4GkZ8Li@jylJyw!T?kIrH^iu5HbHWpV6h!grT z^Rw(W5xlIDFs>pN9a$A7E-kx9?s3-f%lg8Zj0M34tNlj-;F@kwKt5vet_2;~TaG7KLqJGArwSKc$o12#TN@bGU23(@qgZ@g4F2is>DN=-$Mcsq( z`P{d36F~YPkbb;1C>|7V52lXa)83~GcgqVH6v5xA`9vCbeha_T23(p(vb`F6yakjF zqYyN$XR|Vh%$`iqhN{92QhOIiU}$ie7((W8mSQ@BOBd$a7aFo9l$wF95nOt;DNQ`Oj@Ry!|xOW8TP4}$L?uJLCWT;=caTKg&Bx=pA#}i z^0<+f8%%@se&I6l(JAr(#}X$&DH>yiboV}mBj2Oh>3cG?(TpS;or)0i)1@M@bU5HG z+)eZD7>#`OJzMF&wvZf0uuDdgBgDyXaWF~8cJKZuM!+e+p!6W_@WC1z0kewk*ZO}x z76jPqw+=%Kxo_p3>DZmjL@zcGXT2pEH!w~&)@9(kVQK(!8JW|mYXYF__~wP|sr8N) zj)z8kSyZ(x!48mft8Yv<3MNRtNv7+9d_4S0Cd|$+OvWIt%$vX0$qg7EwT_f-N8cfj|TNS5)vnOf1*bv!JqFS#eH>8vbx2HWbxjZ zy380L401ZdyFvOHiPp(#wuLTDoIqkKDynbxoE4+}LC%lcLEhJG>HiWs(|FoXj8m6z zSF=2ZqaoSNMLe4D5vD3(euHdr&Nk%-r^k{-Y8m{gYGWd!c!CdywYXn6v?-+jw$nVV zwA+r{s79nB{kbi9)s|ZXuvJnX%Rk7Ja`LJl;Atofs{7H|M0^=_c6M}f#GQ1~TBY zlgxe`MJt}EUP#$VmXfHTnP3e9^@+)R6es!?>h4z6Tog}!Gw)^`dQ=U*XuBbl4Wi^j z7N`t5iL<|xOLyly=eSU>_UNIMeK^QTXqfi=`ZqhL8)lNUcx<WO{B( zu6U^yNpMixji3S9{y)z>8??2LDobGa;9V|&=j;9Z%Zu75sIGP_E1)$IWSpR9+!@V0 zpBZ4soLaETM7x+`3#wenhl5K_RG4AXIMU%9tvkDM2^IYQL%{_fWqVrWh)%g(u*%ll z5S6R zdQg0+z?-mjQ|hdw6;`4ErK=SXOG!$HbbR6N8O@UijpTGkin$Q@);furM*P)?D+gzh zH3T2K9Y5$N|7n@ySY^K;VEW1Q*$XO=nx>ZK?y}LyJIJEZ3tU^VQN$OE1)+*yLcdLE zihV`OyxQ|7qkcSMn8!~{yBm1ySw+_II500W4m3i)&&9cCVZi4@0Fq^T^X}<492gAz zAKX|wQUlFqOBmj^uD3gS8XJjofHf&jgy4R@w?(z_SwC)4tcJgGAlLA;D0sy9{$!&f zT|AWP{O7XaK1h-;4L>2Xg~%;XQ0AQ=&Y@3#@)>-MlIUQ0-;@eh;^g@pm#t!uBGPo! zfR~84%6_P=V~~RW!bK;{9aP-NhTV$Q}Cni5nRK%Z@h*Z!SFTKhX!dm$un(Gebf;?L_eb1oGYG5h~XK zZRNS}uo!P^pOY~c@1sbZX6KoS#AP`Q(8!HQGNs|H&WG3=drHK^b5Z>{&HNFHb2B?b z-D2E$fpf2hdyDBja|QF2kjCL0=wBMP6R*9nHMRyQXhid}<)r)z+YY0Fnn8tBz^i=x zkXSuX?B`6-J*MD`dm)1)q#<>EZKJEiuFC&{*#oG$<5|su?;Zll)Yc}1`Et>0&)t87 z*QX`wQ?!CW3Jqkk_uD(9qbV}43w?>~_j~lB{C8gQO{@QM0W8yR9dh;EiYLw@vg&yv z84Mp?7;ETfJe>C`ySN`1LNZ3E+RO$5DFFzKH1Wwo`2GldM4_7pR=mtT|HG2EDW1Dp zoMzv?c3bY$wLQ9U#1#d&U;aNPv>{-vLfo$_|EDtY ziC%%KL+ttZn;*{WJd%7NwFvPw?AX7ySfT|2sP|dX5UT9={0A4Owb6cIhmAuJH6J ze#INtKDo}H(v{rS@ zuENMhNI&DAWy;6rc%s@TBKFCLjwEK-iAI2dXjAR+{BLIl4>mjpb%0|qc)9jf$Dp#_ zB9T#j%FPciFSIZUo?azJ#c)PBfUYROoUaH@yjcEHKTej?o%61^pWAkPb<^ou(?zP% zp#HlH<@=0#ng+V8E5bji#%E_uO-;9|{#s`8^uiZCaxXI{Xe|Nq!YM#1JpAOe43eOM zrO^U>iMpc#nbcF_61B?VuHwoE6rN{~UP#CfPQc)?Wy})%BievLY+_Fo_gyj$9VVJ6 zKL%KDqYm-U0uzT5&Fg@3OR|yv3rGiTwoQ0jJjs`V(D_SSoH zO0Z@VUA*v-r=kfiT9$C*89<35{PBERNJ*T)2<2i*kPe=m#BHquDplKC>1gUq5T59a z+c@sNtItd_tZ{eSE;FS|hDkCN)c5+~fO=V~AfE@?dA2i0}m?eFQ%*T!T$LBTu3c?Y1 zpYdo%rYp2R_0u+Ocb2slpkiJyY55nxZeMvzKa~Yo{kWmF@jGem$OFYaRfVaF?duwNI<~Me)qs3^1Givo=melyrufW@ z60yhOR~Aosvg8#4rW9l~00xHiaL<0R^$p!%R3ly96U#EcuTLX7b}AO8X9@2VG-E1Y=sNr6MlQT06Bv2fVx=->!2D2JHck2ddLpBBb^ffgBN>x4SQVIhOwHze|14^V_DvqEshkN zP=~n;Pa#h3214a>gb_8>Ub3i}1xom)l&*Vd?>)>jybcI6o_v-pQ+BK}DBT_2SFAP* zM+l-Hc60UbA(0y{ehaB}buKJQlK1aaIBvo;Jin5+EW;32xAT+7BQVOhLuVhK6gJD8XCIZS7)QN{L#S(J152BlICf! z^OKX^Y@d^CvMVB)sLK4X9M zsHq2a>I}N#WF5|FXMKK!AC=ZgE)! z{OlU>&6dK-+$qI5D_VZWRi;7nseFk#f9`3q81o|SQ)Kj38?*3 z{C=6*DKbJyUa_~VgZ>lXO7jm)?=c&zE!=Qo;le#hUpkQxH#WKe|4k?Gbcfn7AeWL&=r;F}G{r^eJ--RnrbnXe zE&?qw*T9xMO%LC09;-Tx(pgQIlRKV>MTC3F0&qx{9I(oBkUiok?sO>9W)sXEPe!Z* zT2wz;V8n*H)O)*l^V3Q}_lu@uokiP0`)K1&jCijNttds$tiHML<-XSy9owS#^5RS; zbo+M_W@ruT{ zhyXv-m&c2VLKntEM0fJFx3%#T2Yw2a8zA4|i$5I!4t~05ikoNHMIM>}Y>t-)vASXI z7Cb!t)oCsqcGmxosPB%a`hEXDwnRo&R5oQMd#h|AJ-oj%{+>+#^xU&q~f-S>4rpV#wwU6*Cqf~rXwUsJLT9c6?dGBVym z+HWT@w4C>uP@0yVR8ICc5m$aAmNB`3lu!`o{X0UgO(37M1Io^FOtOXPVc09*paUcI z53MPKaY61^O*uGE+Nbc8W&{Z9s%?7Tri*Ah0thknM%0%t!@{dYf=w>Y>5)5 zTqoOZYuHVW!1*w|8W(pQb;&#ZNH)t&_Ph4sEN;QR@L=sD(m-iphWGE^$LZfpO4eP$ zIG2D48}ce&e+e~eFNGmWOVW zKQ&L~V6`k4tZlCox*Inz5c$$C;B1GeS*=05E@Dp3)5Ivtnc8<7zm{X#Bu1kNNE)=T z8DUW`O3bKOAbP=`s=Ji3=0OMf9ed+fQbA?249i427ger-Cs>zrr?DVT=Ii%_f-`?A z2~FyZxN)^fCmy);TltB^DQ4H+iuV1azxK!h_Lpe5v(85&f(hTG2zK(gbL_W++aT4B z92=wapuSjC%Nd~8_4A=51*K#0b)JZr}e{ni-(%W)@!|L98FWLVP>iqM0>JSI5 z;3xf3SHOJXhRT9r=9sLFnhr%I)Yd+rJkTSG(hKMz;LYc_(lF*@t-bq7qMBRb zB1M1IFYaog6)c~tsi?QiegqkSf7@@B2;bqOShH>hB}bGX{Fmng0h^dlAwcs_P*v@~ zpbdl9ZZwea=vwX_)vFZ#*=ui)CmmM2e0#R}$<3jBx&rv?7gCJiedCHSem z%EpxmireGq?VwV}L`S~y3NIKq>(i(0nz=>K*BvUWde86nffCr$M#gjLgzu$yGlMs9 zqCuGmcFmX@{25{jOVgRsHqn z=ajD54%g}i!V&F_WI(O7N|qdTcR6yEuxbHBUKyA-0o?ueg^I%x#TcfCC1`8yiVrF& zStEZU!TGXASu$CX$@+;?A3w4ZZ4$%zXiWTqx_AATUiIDL!~N0@V8Ny9}V>lhHY5`rYvm&Ix8B$r)b zN9J5eqgx!cR9vvU!ros`b2v^@{n*n`mzR>^U%ms^^xFP zluV++Ph3EtFoZr|lCIcY(o8R+c2NN4d1kB?0zUe>r}0FSUMA*=fD7YNF%m_7D<~(9 z;IC%LYE1cSU-;hPyRE~a^L|hX*Djx4djLuL!EHfXXzOo09wU5J!?%j+Jk1H_Tksjf zy9+MmVkSckz2b*RcYLcDLCf?a)Lr$0^+tE7@s#3e)$$=_$m1$dLE=GP!b7$#>t|1$ zVw)cxe>oVVH-Ll#W;4K~Cyxb1W?<%eFgX_&9Uc8fG)$SQ3Z5x?tL0Ye3JRW~r2G1> z*uI)pBB(U))KirxrE5j`K4f)}Bzi{|!9pvocy$7Yn&~x`nJm8e3I}0Kf16 z!%k=?p}GadTMK$Z3yQOyON}AX^q(=ibhZI+8;EOrc=@|{k5Av;l-H)QF=B86r)zyL zFa~9F3|bG+=K~o7;lyq7NEfDsxW#*=9-n98o_<{@8;!q*hSz z>^~uedRQD_o0CMXxPS=m^ zyP7xAO7;3%0YwQ>%0P32EAk7y;y)6D2!1D)&++CzqVA-rm?OeS)xZCv2!>_pW|4|e z#z#Jinqu!^W?)v3+k6%RQcYdU_@HHi7pP=1jS`PT05@YZeMm zqJN_074pP0hsJozm~O7!z{D+@0j<9jCSygWXbeVy%o)u4S5v{(0>y%&P7u>XL@ye|QT*DSg`wRb)O*X;vH_MM~63;6zNE3Y~Tj%MO8h6@tr!8JxC zGvKb>F*Qz3PPi&>p9H5W1mdT^?RWonvp|uA`Nr+npj4W}W#WyOz^g3|Vv8JRY(B-O zx&aJHy9Quz`5S^iWm>KoMXrH9d*&%Bl)=b}2?F zP(nclQ=wuyZK+n)7^}vYp5U+utt`v+NEJCuQyivsOI)tdnBvDbVrU|)w)~N(|4V8+y}~6jJt36>gL{|y zLrCmD!5mO|ooe`X{yh{U@g*nRQ{&~DLP!-)Mz=7;}QY(Sx)s~g?@fk+%4ZYB?=c))R zqh^IOgmqmI2&B4j|EIpLM`Lk0{xVvGJK-m?Iz@iGSpQu$qE2N4M^shgeMJ_%`_euy z^H-KMi0ZJfNdp=_R@v^EXBcuD-AD+aZJfS*j_w*$oK4xgk-kXVdBm%ySiq~!bxYi? zqz@?$Q;NNkh-BU*FBcgOL`D}gz8j3A!z-QNDLglFIw+y?hun)?n5)ch`$%zks90f`@VNjhak8RaP?|58sGR=; z*c_~T!hzc%o04QE;OJd28}T1NS$`9FkSB^D`zr=|df#Qr@yu|!RmyF^y9hseWBYR# zOp=+Isc%yVXMGjcB8Q&W^hziZP~yJ{rJ2V=KFV|RPq!;q(_Fc4NUjlhLin7eCZW(;TS({`z^bZ6Hh!q zqBkBGzF1;3pW3mx&N_I*S2X-2Jd}8u;d$Jk%(5>Q)sIoPK)Lei!-_HRv%5~RLm>QW zpVtr6To!;@Zm@6B8&#$^|-{DlUF7DFLcv1 ztJ!6XUVqz*gyT)fXTlFafW_{k%Kn7h{La4mK6Mc62$ig9)qgMjCxq*k?mJy%=F zklR#U;da7fvWpZ{6lEeMLO$C5Jb!ZR?VXujN_vLt_owyE$dEeQ5yZ(~Y=?>Vngwen zm_Aw)oy_wK+=avSm`Olw;%oR~L+{{u-_$@P;9?^YvD)mn{ks=mwb)xPWbG&&_;5?T zz9#*4$n0BVc_Q`_@xUEXf^8m?-r{dWoz}DFk;u~>yTFJJlg~0=S8za%ar>}jp`Q1yrWRn#7Ss{`wKbumVvO5Tk zuOyl}NkYB|*stg|KhX|c$*Q_I;gZYNByW*fKl;zqbtit1Cz5~Bzc6jI5i?sQOepD= zf=woR<>L?@YP+){muRpA)D`WtpS%2@jpfK~CQvPy;_wY~iW*LYxT5{?qZ_q}q-6xU zu#dWDWHeUJ_CL7raIu`3dpGpXo&1;G-{|WcG1wlJ7lBzp1!y!UQaduW!9=zJlsqR-^kPc;8-Io*I+pA?=-&r3azAihi(0!*#liqp!?}RD`Q{TzI zysw4x`t$G0N*ShCpHy8h-spqA-^3{9nmtOCG!M)u9o(wxC92v+j+m4oDy99@? zfQ;@fEj)~wQZ-MWRZ&!&I=VbEDPHiz+13?te4lTjZr%6W&!5}BPqFmt7CX~I9zw^& zz<94=8L<!rchg@x^EPY-+&?GjcvU90VZHEgD_AF8&}frtt?3ihS%4)$j=CGM zvyJ!kuW`oOq&mB{>xVC1(ewPpicWQ9h-Zt94@e;Oj3PsgX5_}Jt>&(&AAt5_U{Rkb zd14%=a}Wa=bXGdxPfBk)E;~`Ntjma7{R_692KApR0+MX*OzJPApnOiM8Y$=pxd0i{QvlujZCJJA{^8(_ z!aDZhSe~OgNHxKeuifYiTD0J2~@PJs(zNHuw zuJN*pXNJ-Nx41y!Tv4#awTr6d7Z?4l5eQw@*^&D+dnbBHJ~v0I67Hm-sy^JzGkxa| zy3j$Ax8HJo5fIuajVg#tRmpcEBRmAA72_N6|9f>8W2vwH-Zrd=hM?-n+nz?z`jj?M zU*?cGzR4awqH1qt`H%KlTep%&!Hv>aQKrGT6JgrWjh43q5fSS~pR=qJo^vv;nwWqa z1Z``w6B?=h4~?1hIeGZ`(SB1ZK?z1|P2CjJ{pjYMN{isJQZT+2!ak z8+13yQHhUbrm{3Wd|nEAu-7^Wk1@{o;z|n$xLS^rJ3R@lnipc-fI7CPHbQm5Nyix* z52^;c!GzSaOzoi?q^*xuCOG%?+Fe?IX zdtNF{B^b>LLRI#uh19~89v~7l_(JGezr!R|y?-yQH}zxtyW`*2amUWLEX*Bg;e-*A zfk>a*4=d*{?a>RM`7eTJw%>dC2W^{z&ZinHuH}?bS`uHA;Q??)B6rA_m|I@tLMdsJ zUMxuw#0BSV&c7FkAocg3un#?spzbH`)VBuD4~IZ!ap~ibklnqT#|!FwviOG(S}x7Z z+jc$Eo?<YPts4{EJ*JVD}`*UAMyYt$qO3M_{ z`ab2pefRBK`if;`5*qocEb}FY~=zBsE4{k}f;))7_&f0K^9Nyo$*`zT(kv2>3 zD#SoTH!hT71bSqP#T;McM))~S>c?@YK2F=@M}8mIU$X3MS*HBAQS(~9Fqoj5hsc;= zB^fWKJ{=9aW;Y;6pGP13`14X=aR+#ZXei^)dion3@xl_T2+^9?MGol*2irm8&Q{8$$U@arKD&i8%S=T?Q4<#+#K0T~<7m>#tSn z$zwfm;Rf~v9EnC$z!3vucX9C&fA_n4Ayl7_3s=Jh8CF4tc4b9oEiYQzQ{m17+wb`I zY5})vJndk2Z!0|ZHfVYxcae^A9*vYOrZOUcfxe6B@J-=GsSsbH7dB^R))y8otJQYi zxzUUgR;5?k{9)?`0fRPy$3^MG+D4-j3&tp`p{{OO2()pNK(R;Fm^v&dZ(Uqt+|$<} z+g5o$Ut7|c+H8>9*->t2_KH^C_l$!({y;h5Vt%l@sIs!u*=U9XJeb_X+xz%|!+E`38kgWuhF%Xj5Ro?W$!IOU`>Ivik5Qwf} zVuTBaqR}ujQ{_~8ZP-&BBc~S3Ei17EN5Po6BEpbkoG8nR7PTBYJ{ku>6>rbWd2wvT z5Cf=Z-Sv*V(jwD>8w`U`Y8SL!U}*8W;_0DJ?1AA`+pF&avF8)olr+^toaq{#+}(Lb z{HbL=Om|okg#EZnfJ2=Zq0Od%xbbTqGTc1)bHal!Bk8RBcNco}U6Xn_z_ZM_2geSd zt(qnm<`EiJ?3lDqw@)wYhI%J3MO#2cCw0rpwF+VgUXio--1946+^#6q$bh=g^_)Y=^*%%C;@P_F>!3 zZA3PIUZpw~A6s*4qaLt;&)f7CcJv?62A#`YS5wZu_|U?$IP13|g#X*D9T2Q)4$~Q_QyXVIuc;oR4xw0WAn7baXs( z_w&8arq>@=IixA{+yc{hi>173%n6NBP1&ap#}9F&wt6})kY%zx(?kmJ95O9GGIWrYAwr+goR-oDI>jTi6N4W$j2dV{ z@(f`r5B1~B<7%m2$n$G}tKiKI?+0<3rv6B&9ng4d>`Gm43f#E+ka18EokZ|Dhf01! zoW%^sM6ZZdU0u)#)xJXq;U5ui!n+@Sh1;&Wz5{n|Uc}B^jdWxDnWGzmNT_}JyF8oD zlS0(t?xm@#y?a0FWB+?){S_C3zCl-UOjqa}*`Pm6;ojG(^Ju!^N%VSJqP0vqJj0RZ z7cU=4B>S5nE}4Fu&bDq9vpa!{z#k~k;s}hIFHVpZkqX|Y4FtQw9pAOwX>7kom%kbZ zH*Q@lEJ|PXZ8vMS{Rf)A&t8>s_}!E{Z;-<#cJJVJ{`B5ezq&kz=U|b`SJ2~KCbE$h z3D@fT>3{dm8XOyBb0tk4&E`;#!%QLHFjAnvKjLL9YH~P>XW7jBUGiqG^FY&P4MU*0 z5-8VP_q6vBhd)zP{nvSdl&=F0)hDQLbGwj}YhEZ&;*iPi*$0U!HtK*LiFRaQhv0Ln$v< z>u%Rf!t;9n#I`<=z74dB@HQ;0`0^RU&j?8u^$z8?17~%7l{@Wny;`pJ^MI?jIA8pR zo;|)sX$H!|g76~~9JNKmkIm9zjDb1=YEV!;6tKfqBV?Y|A> zxk{%$Yom1CRBb|L;foI~PQ(sqeWlM1EgXI}a_CJLcQ9^t)KQd=VjtCmgS+S0BwID&7YjR4ej&N?FCoj?{x7gOUioXLY`h$-8y zy^xUWaVb6DpPhvqM&5gOcD*cvB_mlkG$0bY;HMghZk^!7nzpzm-(H>Bn(|vu%&fg+u zlBG{x;F4g}pY*LqrdBgl^MDi-ur~#CbX0MC7Au%GZ5$>ms{Oghs%y*_&&MiEoYRY3 z*>nj$h#Oev$L=R%@1!t@v>){nFtd;n-5#d}!c1|dDXiK(tlj$p`;WUsm_2`7;s`OA zHa(mqHxGV&*!yPxG+-+m`Z$%MNA5p1ozKDZP=D%j;0pRu#T9s2|j$p#=nqz&6MvGab| z$R7q5EutRxU-~KSrI_+`oQ(aF$v4fhk!EiyTQE9{G|*T&EM;*^C)rK0%|s^b&mFKF zBlXp4&SkMl61Z(CmTJJR!%nSVp#0;74D|_ z#me@w90SlB>F)yqvFS9ySZ3g5Dn0Ed#zFeS?>KTR#g1s_Nak}7zAI!9hX|_{*$Fw7 zD{pcQRAou44=FJ;RY7NMjgBzjP=lZQBXZ|QO;;}s3%&Qh$So=C^aCG{4vblh+MTOz zj{6${?7M%?y=;}7FpblCe_S(rkHL!KDKQR({5j2=vT?eH?~ghRpv@UOTkpN&-e*I# zL&5R14OK!-3|sfXbmQgLG~hPR0FPwIptX;mTq+#})ZXlD|6fZ8$`88T{ucxzo5iRdI^N%e|V-O;74(WbSma22jf!ev5w4Q15&b*55<^8 z`i54b<7tBH`%|nyu`GnVopE^L__@d-QWcK)%#%Lt<(9;)2ekzG>@<}$z{iC}l5dwP z=xI|E7$1bMnUo>CW#&EHJaoXbq8hqY(c~@l1DzD939rw`z+iRYX=9Rm_>PVlPcRnOVU~8Su>}ug zsL|&_Z(1?$JnMyhG~f78(?*v;=yNKH-YUN=ZFi8cOfec|Gte6{`~OSjpu10|KWn-= z!_0DG6Gm%US(|xC>PpIcbq0eS%!>@iPpRd9BUn~;6db#xip{DPZ~idt5PEt1fn61} z`JNNICyzo|$}7eoGWp4WTxx0IM5qKmh645F3RNE?%|d!X$Sqi8!X6^i}ST3D^plsU=L*L8t}N3F_GH6B^N1)5!7f- zpTU=>I(@a%eW;d$_6!6g3`yzFX*@K>rHjqi8DJ8|$7Rj~Ps*nJ3R@te`)C8u;}*l< zl5`uRbdE%4W#+Zz^6fwuYn{Q~Q26MdC?BV0i`Q#qv7sl|_aot!rWh4%f9}4ahzJOW z`Vq48yp}(OB{om1%=)m5aiB6}qJ4Obv~C4x6~k{}Ox{75w0a-tf$#pR(QMtdY*HgO zpk~iCUZr%+y58T+%yXymiljs{>n()>fh9AsV0KnkvW)}Zvp8t)&UNC9aumur9_`RX z`pQTL#ovY@|E_4Hlj>HswO9YWr*anl%6Gj?j4b1q&dQ3#c=RnXbdH%;vMmS$mz9-0 zs*sbBlJfJy&&_Ix%aL}lI^Vn?eu3jWv0s-Lk0;+tPnj0Zb#)Rq!q3k?CVWSBr(t?_ zmMM9S47dc)-%XA2f#O==@eIwZVWnC|6Z2R_slM(DB%KgrzJXus@0xcLQ!@ zJu9*p_u!f8_9xG+%*YprGZ9`0Z-frO=Ty1ar2I^SjebeQM0|k*9w>WoK0RJ1`}RUx z_x}DvIy@JFpw%_P%*CtaKJrW8`Zk%LMV7w3{=)|Kx~?zbwToocgXJVmD)DEhdKB{b z8g1$Bs4%0n!3r1*BCyf)(ecWujTR-D0lxc+?tG%TkV!_Miaeci$(zF)aHA&MDSg~{zWs|JQU+`f5D+kmmfb|D;7+^QOug<23 zR_D0$w`N@9|Gxc&QJ{Ub3%LhfLLXOLaPOtN_cSC&7&^{JUOu3PKyt@_p*^*5JJ>9B zeKspRY=q~X8uX!=cd)j0p8nNkdm9#!R4MRH0z~W>t5Mq%_T3h0Mr{v{xqJV9_P1eb zZn%wj`;GZ64x>A+iaVkO;qV4ckl^0v zWoY7QO+zJFyMvQm)_B2Lb!H4#H&>v{M*R4o*^>W@bE@gvB7#aznLQ6!S*h3+VwZPM z%3EK6BfpMMAoQ8%%S0?=;DVeQb))u~tNFE=x3V)`2b04zO>fU2b{-2XT4gMF=zoiYD%GDBnvdlBhn*M zJ%L@YOAkiY$$~QwTj=GAcwg{t8*b|Ayz-cf&>`K2Z8>YVH9am0yN}rnJ;$1+AK_T|~yT5(}C%R7o@i66-bNQIbZcowk7R&B4BcZ!v}ukZSr*?q&n z=dTDpDw;ud6R(-a8ABo^OTXyhkWf%6*hmIVV0TEjad6Fy^Csu?HM0h4SbdZ29MX+f zdx$|(6%{7lElp_{okndzM@uKbWWWG89_qXtV<>ru)-B4dd`%l|7>l8Qo>)!fMx1rg zY2iPbY=kD-%={^JU^G43S33yG)C{sS^n=n>sbRIu0=^{DEuv008g92kzkL$SsRT3R z2BC!h8B^tq(xVeygO)RxHiQ3oYhBU8k<*RPI^HvBn30l64Dxfc1 z{$>p;K_E+rj_+%3L>D=m?8JUu73GH?2{j!Vh!Ni`$RGLch&Y5Kg3tq?PNtGYvFuC)ToNbzO)hx}8n~V74sS2j| z_oWBpfBxv|YM06EGy3pC#3p-n*vJV&s*MM-=4X=KVH~^c@Sfh=Av0R-DHY*VrNXf! zRZZ|&lyqVX;DI{s3G=m)k580xlQIWJC*iW z$n?5-BhljjgcPOYIh zS=@S7_&?grWqwM1ZY*~^jr>jLv0oz?y$klu228dQ!ZoyCA25xSr8Pu89deg$VrEuA zt$X^(%!A|Z2krvE5d)-;evFyp4bk|loSbJBG-KGyisn+B5et8WqS()zoVO<9gj z@Ojk~kJ!eEjy||`L?q$w3KRrV*d3hElTFZayr)z4)Uh#MUQcI+sI>w&Or~s&I71pl z2gi5^%WIap`}=Q%2oF`;bWh@R&fpuqb8mb65lLTG6ec!m%P+T3*C_-VmS96h&D@DY z^$DvFZ5g^MxJE5DI_<5E<^u_iRC6^Gmn2|8>YD9~*jm(xi;4cBo!~9?sU@IHb+Y<; zJrjbj_ysl5KVnrZZv!W|F%mWTXUW(r#M`!&RLvsp8m?^cjW)`NVR=UOj3zT`T5Qy|liljtdX=s8!&;+H2Rz z_+|_9nMGEl9GMh2oXy3X_?mqLrx_YBWW9@?v*WD8#raMEW-WTKR|KyRguH=a@5^4C z?2m*i`UL`6OhJIV-A!IQ@->$my_SeTAiJ4CRz^^wGwYLp`7>m=0qWjp$+8h!#-KOS`)zq)XL>cQ?bGf9?w^ zN%#Bso&~qF52@^0SAWh5#J~u_gjGcV$t0s-D7lzM5}?%8#q-&d$3Q6}A9bViS6)g= zNO)b{zQwxImT-6UXGFzlUbYx?{n?$s<@}w#RQB{=4nKb=d=THrJVdtiG`j#5x-K=; zF3r_0p%}~*4@w@Pt@1n}T_J>i`RjYp?G~!RDus@LD!Ji0=Y?;Gg&I_rQ^t*V^s>Ge z`0%dtT^~E`A}EkBct30NKZ!2`LV6RA0VcgLGoL}N=vE#4xv42-#fWY=B59(aqH({n zMa^1Z)?DUAgH!$9Cynu;l67wOgj0&AG4Rp$aHD4s<aaH+f;xjlN%q+P(dL02m zG#b4OwhJ~lY0)EFG74=R2@t!1&D5sp9rBXf&b-iu=Z1 zEMJu>QE3!Z6^#nm_qrt?(&*6AE2_QZDN6QJLTGRi@`nXEEgY+)F@zF(h4Z!cIf$|b znLAjlpk^L*ppFA<{-dAoJg@9x)Dw9}fDU};Uq{y%{>&-~AD9J2U0cf9l5}NikT)Jx z*~!*x<5A0=P_V|>`o3$Z(eM&1cXaTsz1eAOfO2gKUX1Rgw~BdD;z-BT_Wdlge2Os@ zC46YF$J=!AZ1FJxC_M2Q2r`)DvF($l8W}+!J4){qBRKh-Gx3ri&HW#-ST?{yi>KTU z<-T11uNU-}H~#hntd-tx9EyIu4M?f~0k0^n_LH|D+@y6+66O&z ztFitJcC|?~y;a1gL+FG>-1NH?*%6+hRctEUhS%HOO^2P$sR96xDbHpacQ; zOOB{oUTE_Nazr=&V@yZT#<=TblZKmPVh=|o3^~KD72WS6Ht0^N9V_c2h|9)msc;5< z1N5WN*L!JJ&-bIV>`UpO0%Du{PIqi@e>9PEAWgOpz1DYWHf9{Zp4%@N5x-qx0?_(1*LOGS?d{K zJrf7-frrWZjN9@h^&&l3@ROBtnGsdKTKH~p_N!HoEayZO~mK}0o`dg+w513i=Lg4gw;`;iyia~qqIpIxdO!@men1d!z?rY1MYW`E- zFs5x=f6n-61#cQFYOoo>o1InSmRkUcysD;z<7aE61bkZ<@H$?Me#I&eUbqLSkmS4HJ;iaJi>r<)s2)!qT*u2ar{2T_X!hT5k7G}nrW#cY zEq$(oRz1!8bgo)@BMwX2Dfcob1n(faC@e1>WjI_+mD(%e2oufeZgs0l9KLEfEO&gi zZy}9svb~Zc-!R}(*X3O(ro0hYl?;M^&wF57H*+>+(VbTgxHtorE1hbZn&fy#Gki2Z zJn?>qhh*)TY=|7&I1O%Hq&YP}ep{%3UdxJWu)A%@AEvjTi(&gCCN!24@Bzs1_D5UQ z20Fqmp&;K=e*}k^dEQYxmub6z_$Ml7ZK(A@KZ3OwrMgmfZ9sN~#S1b03XLEqC62tsNvfoi`arM)B_)G&rnH*<0@1RDa;*tYjkQJ)ch!&5BSbV1 zllli0@(pl!ZCV*-=G50Y|8wun=K7B+V1S<}EegXRBr)VcK2%V=|5)W-@n}vj4>Y6| zZP#LRD@1F7W$Q1>XGIt<_=Ce(fy+Q6hVq3Ibfb-2Ry6_6Z8hO0$WOPW0tUmj47ovn zj?FLTfnDXlY9wgWHaU&T){=cXQ_lIUS4jgQ`Q(eoSP82@a(EW&J$=!LU%qAqY_S%u z-a7|t6PZac5DB z?JCy!V02tQ`p%Yk#(j;PQaELPREco|%2SR>F6-DlBA28D_YM8>@bItAP5YBp&lX_8 zod2hR9~uYDrt-K{oMD>LVNutIM_ulr+5Dwd`IEIoMoNeDA^}{I=U!YkV6_kS`YA!s zS$%LAH5i<rDLbCu`wYxujoA$>CMYq5B5U%_PLL z$kaP8Rdr=g_nair{$ARRv1uYnuB?_ZqXX+=T5$Sh`>3pO$HUa1?{u$X=fR#0fCiQ7 zf4mJ?FnDafUAHV;Q&ME4oT8mk6-$Iq6&eV_MFL0Z6VbvJBXnOnxU6$6 zO_WaZoDXzf+yMgVcHLvUD(mtEc`@aXtM51mJa$Sy%Rh^Ee7+%BFL)zX`?fHBO|S25 z3NB;3K!w8jgTtajqep}q5b~T|M8MfPFo5Tx&LYW-{C_5%GmNC96f3sfi1Y%iMn_}y6d zhPbrG4i0`W4NvCmYXsn2E=@^nT+h!gpt{_x*0jG<@#)yleMmn(<^j$v$twqh5kOKn96RvRPZ}7xKa!)3xJMx zbIQ{?i`eT}?Gk?brN`%SuD;OS-(rf?*6DOv}@TBF2&TEUs!uhaxS;A>Z3Uw zrX6y696!>~?N7pQ*g=UunJ|{1p`;~IKCiUH+&*!$JSs!0{eQJQ8ffU+=93P6%e!vq zJ!iI+v7Ckb9Z`8KD;@C%EJ9w9GuLt)x9=fR(?F)6lMx;7AI>CPGT!<~>2fD$aAA8v z0J|qpA-6iamRC_`{^!`y4@anuMHr3=G;xB)sIvR&%id%uaU^Exd6~Dna6Z}8SOG^z z^pxa}-t2DRIRIoc^Q*I}TV)50z&;b9%Y8wp@2o++>G(y0^D}vp$|l%QT-; z`0A;MlyuN)4ddE&P@pdromLD9km>X3DeWRcf)770Sd~Z`f9T z0R}UCCb#u^A>lfln-?MYMVUOeoCnCRlM43GXL|ghr?Cq2gW~Afh-7Pdp5=iYWG-sTp7<|+kX zGF|4LFn#c7vPJ}@e2T$Cil=(9xRjK{c{i36f9u$lTQzZ?br*{RD_iO1PyLS(GQf699 z(|vIGtn^|9McaM7E_nxaoglRC!X+;lt=xZUK*A|9J)pDi=s!hhXEc%tp3w)6D>$R*H-;g^_I7RD$0mIHG!JZ#$2gCBk8yoglo7^6%+Il!}q}lCGe+xD{=fc=6_?tJOd;|TYrQqnt za8_KBIIqkYs~E5em#Q%eHZQC(E9>@0@E!eAV!?Mm0>>LQW}o)JGT6;pfR+dMlh+ym zdAZVeAk6vtYcg5!q&gNb8`aR68-$PbmayQjCN9s62I-2yboFgs@I?Wbqnn6G(2>!E z!1Ou1c5Z$?OTUgHl>C##kc}jOS=o=<=@^QI8 za0>5xEg)$@3e<2o3$o)Xr2}Y&A5Zc01G8DrCpetqDXF&ATSwg~WGa3BafO20WWyF& ztFE8&e{sVf$^6zL$z|9MxF@o90_+U0FEGEF=x8IT zSDi!%0**s32-3+A0VmFsml~H8iIxo(p+F*_JjaR4XA|`Kjh_hW4+`U;O@mC#xbk3y z0l)iCooDsm0u{#1vT9TpNyh}o3smJz@KR;YA2iK8K zh0xBwz1iEjPe#NP6zbdB#V=Vk5=846p6Nl;iyRo)kWI2m8g-NYOqS0di@E;R7V(}r z-E{V@r(14ygfGuTO4P-QE_+J5vk9`Yy7BA4BfgEOQ9dlBr59AfH_CqcBHWmn0)z{q z`N1q?Es6(v0ucq}66b;L>V$bE(cXU~!T?5aCFVqp$V@t<&C zL;z6TvgdBr{Vou0eo^L7oiKFPD`ER=>DQ}Ov&KZu{2sk7aW*Brv)n=d#l~3p688LJ zf219|B}cEn4h1BTe;8;>EzP9kwnz^JPKl#L)t>gP_(lhWS`1FbO%}MLOH|r$(8WQ{ zQFI^=Et~`#TW2fjYF9d>lOg{hbz-I<+8bf5Vo4o;TE9sJZ|^NtuVAph^-xfG#sIPD zFuzoCKHsNL^8#vB2A36u+glyKp#+O4g*k4bOLHMQD4EbGV$GaPne1SRJ3E`dTOQ?6 z+6Uf7H$q3s_Q&fIyUEEn;78DnP-Lwddj%Q}O+S^!9TV1oq+p%$wz`12=X3e99KnP1 zY>4{7btInf=l&Yr@cKu<{iwPZ;XiPEc8bSK)lJ8R+kvF9jZCoL(ZOX`Xk|``<^T{& zkBJ>CZpRlndzM31wJTt^87M&>l*H^ck(94h9LL(T)IeLa@H6sT)$(NW1huWN_U1p7 zg7pZPW^GO;7E!A)N2z882d zR@v_4WM$oP3YhP)r@;V3XMa9%(tl=to@a32{BmU!a18vf4rX>JP@>GXp_E3j{~j(s zx-OiE{Ed@I(x`H8-`=i+hjHUR#d+zA5blF=X~sf;x~t(cha9Ny>9LGuv7=82LHMx~ zAZFV;JTQED*6JuYd6lRn+pp7Ds!(fqTt%|?VJsLven3~T|;#Ct-gFIUZE z`4wKqs6s`Xm~MEukIeyd_zfignCTw%(sZ~jynCP zQre7MMP74Tg{BD)?;Flu14K-+C$*Ph@FN0PM*^4+=XP z#6REngoSLsw^`s=qbjTHfX5X|mZ~$FKl@%kRJUKe;8XGx0c3CHI}Q3=0VMP1+3))%k&B{vtK#}H)?>9{f!|_$s4lls>V%+t!Xl8GL;#UUoEE= z)VFZw^PZ4(8MpWnQ8NhWd4PLOSHsso9p6V1D+E$xh$qU6yc1{8u>6JWG>HT>7`-xg zvL7ghwAF*9Yda34cx-rQXHgEGU8K0z5We`;^k@jX_{}S-ZZAMD#)~U4=i-3tT#Ber zpl^BCQyQgaNeqmh0t@aCs@ymeWv49ZN!+9F1o)$rOF}cRMxAOS&l_#YqXkAQ);BZ; zr(=>E9Gy@v%}?ep=&c^qUM`+R7l`wWkcc^Ayo}B3q30{(0-?KhD|d1Ql?Ymo2TRoR zaqUxtMjLqWl#Y&$zAZ&LpE|4#1-N=QIb^UtEU&qLIm6zUPbGM^7D`AEbedmvwJ&!C zh~w<-!FG1V{{H9P+-)>S@YE_`lnlO-y!5euG%(I#L@}EiYD%Vlfk$(yA7mw5*b4#zU++m?|n~YRmQ6EpurNjk?F*g~l zIKAetg~vK&ZogzGs(Yl!7RTRC!F=+9oh^b|HC`dbF5l6tdE$NgJwXZ)99bpBi2(y` zONhbb=aMteqtE_m2anMzGCgn!rM6;9I!*}O*|gGeDdF&$d<^B{iLe%3gKXd9hFDI} zBg-+~3LpvbK-ivITTmYi!NB45lkYmSaGFNSu4Jz@Jj&5nf1O~rV9(&W=e9rdNLK=n znZuL!saQ2;e=E9FY$fChtF9XJ=&^ycw~A8op`piS;85~t7H!s$r)|g4BEhxK>oix& zt3aS{Uti|=)HYs@s4UhH2qJm4wxW#EkK(qCTdTjqCofI17nQYd&X2NAW7N4>LzGG) zBUN9+4{WY{3A%{bXqEI}VvBgM+}(d=I=MKz%KP~PwJP5ZJ&mv7^631Jy5BRW<8im{ zn`Y)@ebbUHk)`Kil7F7gP6w-?^i9T#AVKjn7J7sfzU$>1Vumz0uP;l5Q=~VLhtnrc<=l9o&U}`yK}y~ zvu9^!cV|Xurf}uKQ>NGLpI|~*m1^`AG$7Yf#fld?<-snzb%PiV4nB5pjn#eF zgZfa`+Q|0hF>Lkq#Q&0Jjpr)9(#;N*3|ad#!_w0r(I$zpfwTcAju8XZ#^5W>y-qdm zjwJ6~ozQ;`4v?WP4FjIyQyqkhpQwg?AFk$X>2(ws)tEBhtu=ePs+TD2Y}r1?Hy%gTq&BRA1(GJj9hDkIEhP!M_Ov zLf^(_|NoJk`5aeiBQXp3{^ic)&hONghk9+)IbZhi`OyXgzF4#t6xgu=tlMzKskSmL-un&9~wW(%s zAr8(IE)1%z656HPX>@gYmGA^#%X*iN9>5QYRm*&?RHhvF$Vc82+wb|~p!WYqo%6;X zogX^=CcxFuP%jPsz|6@+*R<mOkb&^m^@1vH(^DVVTQY~OB>aLH1GL7F>y4hHy7 zI^=Kx2#kt)X`WbcnDl0)l=l)plnARp0k7Gidk;4{R{-Q?7SYNPR%atB0qj zfxB|p#I_U@%(#_V;Azbe|)Ew=qjR$9?6M@nD{6O z^K+rbg7ex}mv(K?kJZ!UjoE>HCrUm}2D??Uz$ikNMwQyNPfpHpx}SQ|)8pa`zhiP% znIp*}B);XcG1xLivd8$s>6$>t#VnH865efC8&=|e>ji>KHi_)(^(p=MMp{c{9~0#=2m!Eg7G>Q_Wq#9a#8r( zy&*dt%-&0cX)#FvYSNnwd-r|xCpz`%=-l_E8N2I=r9*;7ng6^Cz~&Q_nFvdKh5zX z9#gU2xC!XI%QGIJL^mF-Qe_ipKLfXydvE+AEkn~j1+QRGovm3YFs{#BtZ#>iV<|2u zlt@7pm~~3WL)7uoHQc7$N@|Q(KdmdbaPIop!`bL8p59BmdqHyVSf63}WVfLX3wTtr zLU-yF@A68wHgy02aokwrDv>yxFd$S@`_aCjTPg3Hev3OS2XA_v(lS&==T`&c5S;~J z;0FyQeNgs-^jO~kS4BTkIak3jr_H8g>+o1w4fXUZCRqK&&28bA`xasxe!P6&8Ewb{ zluXm##P3118BLPdvNA}SUX6!Iw`?xH zrZv8mfLl;yN5_(d0+I zr~-fDM<&xYeW@xHDmO7Q`OnNW$`lQgji3GSDV@Dxh(M2cZ5fl#VE%$VfqlYY!SdPW zb1Dk9u+3-pQ^wTtD=Nk(U#_52kMfwK^M9mE-iZu1y`_|Il5a0$Yn)mugce4pI0OQK#$kGzi&2(_{;r6ew=)A%0+@+7MoJ!m|Zy}N?8w}ohu@;HbMdfC?_ zx61K;SC#8{Njyg zrxZbRQwxh>gaFv?u6kz()Vn5tyC>s_DP|8!`x=!$TaBgeOx82b_Sy2C;>wm`O=WM> z$Fc9h#8`gzQhDLX1#+ET(sQxXah(}m1{mKqJ1 zKb(jv2`isppg9NX98hRGp1Oc7n|&17Ep}Z6uJ1>q%gEQsU8oBsWH)=*SrBaOmW+%W zEl{g`YEX6|s+0*`sGZsXkUD9*%D*#8wYF%`n#+efR-y`AtZjD>vUupGLRHd9qlvSB z6D;e<$jllM5s<4ZDk(QUU?N*)TBbiQ@{@@zTwM8n7I(3pP3&#&cX6H=m{82{M?b$j z{yQIV^aK1-l)b%GgujOPaM{H(pjP;{#JBKzvzAP6<+_#0gB3yII*;?EcC?#c;iDvy zq{lz#WU>iO+JdPIS?s!|K)7K#`e$snDn!QmdlbL8F@VQ&bkX}a?iLST1E;w`}FQyo3!Qce)HfAY;eWV+0g!l6eCrW!U}zlvr3C#gC3d zkkRA{c470de&?~v<5FMULZvjmb#__F01YpEHYIvfOM%FX$gdM>%Nn zmfRB0o_jpj%~7A4G^F%NG&-LYJNRV$X%T=MctV-{)I?b>bS z-UtS(=Ly+f*5W!GIIc3kkS|FO6t~ZOx8DYh_Jm}*(oS(#de#W4z>E!{6o)mW_93;y zO2QXfek3GWPnT6Tl>ytAqTU;mLOW}{(*$I=^p)beEn?Bc549U-bt`>n8N3tWC}=Js z8tkz&udQ&PhJguhz5bFME0MDcW&#>ZdhY%aw9dF`nDy*U(1o*xcuZcO`8u>Q@|w$k zb=EJtvYbkfHVHn(YsgBIQ(C@OxJv!75=*0du6C`JOpKmy`ll*8>XT zWlJJ2e@-5?aiB4H#rvOQo<6>2185rzZ)g+!gF69F`%6);>wNq!9IoVz>44rBS5E#ZJV@OideXi?)oh(nU@z3&U1)1sJBKfDhgNMl z_j{#uUgTH5ug=~5x;Wo>D1;f~-Y>-?096DcAgBihz{=pjLWu!(KkC`9u0Hm+=tO&j z{gQl(O=SKQ$$Ww!c_+pu1q|_TPM+LIdhF71y??tq%lfV>3pVGv88X|nB zrW4f@8F?Z%g&;34XAWnUOJPC;H8%~;*!X3TRDi~9wLCvrX`aj?1RRI{I@!1KI+Ari zsmLpNmfuJwr)aN=ST+|3XB9fJBFS3gn{o&>?uW6Fcoy{E|c&9e)^$rROR3zbqgmYXCP|g`mPCj3Fgq zl+g)tm?ea;zc$-qu|HkivLtYdUw*(sGfVF7fsJKY8m-BV)GlwwZ6oLAj*KBfhIF&J z^&n70gDc#7D9ysdx=QCDTz%Vav8$fJWJR2e55E(i@FG#>GSb$jSoGR5SH(4WBE%_O z7=?_rz*fUF9p%_2LFd}q5yA%YX*T7&o;mVxMc zQn80YaoxtlzkCUF*d?bOrHQ75xOAKJnb1+aX))O^-|Xv`iWKc_9D){0E_A!DE@S$` z+597HDry^RYnp1n3#+;9GW7ZJ-6#&26*Wk&25-~$s1_o?3dx2Gg4%7wZ}W7gY`>BZ zgfA-cEr&E#52b{Zj{uR1E{tQd+-i45nstnVDi1utE5}>arzg!{12j3lv3)asVs`l) zR?S%4BX>T|)0G);#wK%!-HCgH9!FeafnI^?2j48-@k`0>GObQ9P4ZhpIsI1VpaJ@z4$iZk}oMr6|Gavz(<=z=wGhqY%F`g8XqeW z&KbprH=J;D_bREzHp-5XL@hEn4QEXI7VrjYk0+uZy$H4QODXyy&?K|j8v7uy{B%F^ zBj-`!VaY1{BAFi1P|M?qFPRx!+77x(_l^>fi*kiM+dlY;(%^$k=x>T>)XZ+?v) z|9k!sPlLQ}#c>YgCrneyex;n`0BMGMl^8Cyp@{0HC2iI}0#8pX$<3 z%+_$jVTYvA8=EX_EzOLGEBesf7BtxcZ#ppbfgOLpC0O&znW)H zY6Fg^S{HXPx3cAS+H0^sTYj9hDtt0I{t^5f8eQ;gsKsGr&*^KtYlAQzW<>op zY2{U`a@ZLY)2aLd>P|De_pEm*9^M?rR^6Ls!K^9cDzJarmOPyx*_ zx?)+}eRlO#%HuMIJ~&tEd7GE(3yk4c=nf(jzpk?bbwTl9HM(Sq;Zm7hV_5v{1SRxk zqn!ycn7;0q*%lqOC7UG{BSWrrq^#5rrP8Y#$7>A?q90pyLdk>maP7Kx(`!9D%2t;r zDrBP$lQv_5n%9opyUn(nt&l#u2OXmB58Z?MaXe*@-xwQUCr~gK%JjqmXYz z`Qu??X+sH7HT(2rh`2s}G9s!#TrTJK^(^0Qh=S0U#jpCxk`qlSTDA8Ouj zP@H{jVX`F*RZxT&sxi+VppUy@DZj4#qlwcobM=={Gs2T12bn!mj_~y84`0Yar2Z z@!BEcdn=GhYQ=TVXB`<%S zTA2-~MoGd(TObIhKlBxgiNvwDsYyerKoU`hc6BpLQ+kW|A~5~EI`HA%DdaSe?^kw# zJ{{8fw=(XX(^E4aT5$wftq7&^Yk}#k1vtHu%;Cm_O~2nGenc$pa1!fByq_i@D%2#s z+6x9B>iLbH93wf2Zox-{sae-_;rK_X4zKe4CGXtWJqYYj?GudoA1b z4FkD~>bellv;LKPyFHCR(1HA(pLB=(R`h`Pyi8v9%ol4hvpkqag8#fFH-DX!<`_}; zIaZssB~NYFwVA9M|HMrgg z>)3()R=-NH_}2L8pE<@%sGTTnpe{(aRH;*1Cevf#aWRY0*X4v6$&5;Su+cG>8bhzY zT868ylyB<}48EJxZJGryhoL6_G>3X{t@+*iYj6QJ-cRIo2EW&dj!K`-Y0nu{BJK0- z5PDDMa!z~~+66^NQ;+rbk;Gs7e~2xo?zB0R;OT(X3aTI;=DTNH1WeVu)Ffo4yWd!~ zuLB>?k61QsD6)P|jEQRUpNk0H!MFTKP`L5AYWaY2&=mJpMbYnk00X46ubs4-1o1e9 zfDJAG5E&6qhb)Zh`Se0V)+4G6oqUG_W>;E&2Dyo?RcPIHxm4J?cXEUIOqZW(%Y-`o zo7T4-iV_gqM@0#^E+N4{1QPH0RhXCegQ%!kkgbQ$pG^>1l@nkBT zkzfv_RFVEXM%KcZbQ;3Jl)50$L$zb@^PEoT8jJC<+h$Af;kTC4eD~woel&__qlr7(}n~QD}zo*<&*XI|kqpWu#Lmn&=n2 zRZiUZ0v7K-kb;2^66#JT`aXxLJYeU1x0y?DJqwMsPfF@zS&x@1b+ivY*B7&sg(@#{ zu;|5pR!r&Pq7VfDvMcPpge_a|-7S;ReE)tq{rn-ogY&-vm$q_Q#)A}9^54hrZc+?c zN2C+((%A#YXvR&S?n_u!9OJ!)g3 zA)%DuI$B&5fS_ULCv#@OPoW0V%;iEmL?f|naNG-pRzyfDl z`$WpiB z;Sn%@01;kjb182|h)$PKn0{6eFm?TmiFJn&E2xG8C&JE^v0{dgPE6p`FkPIWPWpnEO{*({BK~;^(oRQQ(P-Wd2h^Z$9 z9n3ldGo=hFn>dD#Eq($M3YXfn_Ab&p4JU|)U6g_!C5v~459KF|h0TA|CHSxC~Wer9XBK(|mu6C08{Jt%4F)aJSpxrlxymAz!xqP5N4oK5Tsl#Wk}l`gekebGT2DW5jv_l#zD$|}y!mU9&qc`K=t`8BmVU_)J}o;vpMh`@iGm295nQuk gW)b~OVb#CHi`RlHybQT+p7(~Dk`|;)(dza81N!exKmY&$ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png new file mode 100644 index 0000000000000000000000000000000000000000..920d913d98c17b5ce0535e30c6c98e8c88499cc2 GIT binary patch literal 23635 zcmYiO1yt1E_XP|OAc%B#cXy|vba#gcNFzwMbVxTyGa?K_m$cF)(hW*Vmz30V`TqXz z`#iIjBCPSwx%cj~&pz=XT0>196O9ZF0)b#ED!kHyKoChF5QG&}MDP>6&dvAW%d>Y1 zhTtn9-s2yHvoK;p2!sZr`09m@x7q%(k3YFruJrxvN9Vz0M)7pc{1ejcc-Nfb!=w^c z&Yv=@so{8Ys_CYcj0euFsa&hb9n$IFYoB5+LjC7eErcl+2^y6@2x(;3+f6Vz?Jh;G z_e3YmrDG4a2qxPE27Q#EO0Y6+v^Gv&9h0YO<((KSz-a{{8!RNC+atH@D+UfkI${U)oI>wlpKRVio6|F_#;$AG>cF@s>(=VZ>sf zud$Ee*Hf90$+v2&e>w{}D68t5-A8u?hbEqwRb39$&_gQpTIKK`OtCTC6I!3y&i}L& z${`Go*1EQU9L{?t)UqJ-yWYLLgS3dXN|+@W{COwR(}~^P-QC`Pb_q**N6STl!LIxa z@*K`V^8|u}6`^aNrUchA%jA{|)ie|s@|}snW=G$oFvWss;fb_RY_Z!wR*b6Xs2cye z7{2$8JFg(@+A1h!u)Gc5jG5iL8;&>bA?HHzg|uz7LVi_7?q?{gL=Q? zXg}!+DM5uOB`InoCO&he{gIfli^OG$f`Y=v#tw-($AkDf-9C3#ejwU8X@>?4A4oUf zHH>vIr2~W0s9_kAB)b73_dUGkyo(+7?*k?o)sw(U-*5bM8eUZRlID=E#>JMjY6-HObR=~uK zN=9HO)o@z)d#4_L!~!4Fy4h{QCokA$?dv(ojpN&VdbTg&W;I5|(;wSyK8R3YomhB# zd*7z{d=D3~#!V`up~a7pD>8{PPDH7+6E*NZ{x#db`=p(){o?6C?cVW>Z@VnP-L)^UBc;*RVPot+E{5-G-X64C=npJDKG-G7XC zEd?Yp4ct?RR}1Lot!}GnI%`%3+71XJ)bD=0-J5^4u&^j$Ha0N?g)}RmJ|9mmD*R2G zzxwpo$TdGFxskik@)a>BN#|G!=_`Kq{%{#L`dG5IUuL+v(-@i&rlundUSw=ETsCgrEkm|bj$L-JM z9zy19Hb1Sx#=|#Jt|wj2O_%4FaHE=`j-Hj-)kqB6dA!92nQt0K_r5B`(1BC~YXsVL z>o?GjrlQ&FU~NM*0Sf!(yQfXV+OI0r@imATZPAx-@U8K}DZ`EbHL)n;dpoqReV8k* z`z4X*4NH3Q_6rQY*SzBT_ewKmuw<6e&ghf6R;wP3$T>I5LG8)W!)-Cyvn&|_yg1o6 zXNIiLkY8#&Rb--xk-D4FRaJEkYXzl$){RlT}By~ z#(KrPdNY1Pyq(kQm=qDpUNtJIltiF8Nu;RwlURpnG;7E6OJ2u8{jJXaQ2HMHkL1Na z-dSPOm{S4YgSx6gZHBbZaFstaisjpK>aLnKMsO4jeQn~{-c+vymp@VMt{xm3>MySSR5lSB zUUIolj$ZQ6z^Cu=GG&~57AM~pU0ZL<13Onvg6Vhk?*m3}eo|21!`jk+9fmZJP*$aV z2?}_azBErOm5p(MCH`~lAz(acQ)I)zpzys*tR-mnyjy74o9$Uo$K+hE94#&?x{5(L zTdkC3<>Mq^V9-4igej^L zmAjrB^+XE(P%ZySYQloU34O_yCmqqdr{loyM~3ODJLRIk%0Jxb;uvOPU!D?a*O(r{B zuz*5Oeu`x>>R{p`C*f`g4b8j6xMh3vrDl>pKKGLFO9_LA+=&{3EJN8>bZYE_24x)e zX+;xjTGrzwCEWOBI$D$AWDPdKAz>d>hq#d)8HiZB77m#JaCJ8b%C)J z*}To?GX2PZYbZd!XHtHDu@X5~>#5(LZ$I1B1GVibkd6~v4i>KOE>%i@hOWuwvS3`QRYrw05c#YT_d6a@5_f1)JLF@L1%2M}917{k7*h_{O~z97d(4ITKXnV6WB8HsB$(FK1e;`l?^ILO6FLGYs)3yjRQ*6=cV8rSFb zXH|zWfwP%P**K%R7cXRNY*)ydIc#EUZM9-Pmqfh8T>GG-o#nQ0E#Z>Ttg%%$ZELf2 zfUi|N!|}Ly&K^qT;NWFrvbNQ8OXb;bYoUP8miol8>fU(8lpgJw1SC_+UH9l>8uIDx zl^ zYmMbE`SEVc-)bJ{!IIyRw@b1*?(G9@C*8a*JZ2p!$;9$=@B_8UW_KFm2${Fm(y^!pgVrck* zM?TS>;a>XUnqa1j{~h_Ma?tF}Pv(xB6_zVM%iqU%m7MRo2W-hdLV+9*BvD>i#A%OEVVJhN&<^y&P|=f^m;r`jNNuk>ao`x*)R#2Rsd=>trgn5B zbqCVxXqEZ2T+0|pGZh&KK1M$(68Q3AihLN|wfsTvdW&iZw8N|oBVH3Q7O|qgy{4_h znpRK{DQcz(yP^zt#lb|0eS|UVa%1Zw-ySGe#IA5Y5fTx?zWboB(^Z2;B zO}^h&Ku=e<{r=xxlESO1*{1sXrDoUSl9E@j>5hv92Z=FaBBDx@ueHU+FN?<==c<4I z882>Ht=wlDehtFQ=$8AFj3ox+w6{a8H~Zr$x!Ks*SXq7c z;7t&duWpP4Xw%cviqvHV1zqbWujp_gg&I-YKDlb!?qW}$KK02XM(_2kwiWRG`$x0p z-AMrr?M}uDO69d-SUHzHSHgxJ@(h(=N7M0}Sq!A*Z{O&0H^-Eko)i`0P$M4$7+-$k zW;f3Y8Tm96So{!C%fkQBTb^z_YTgP9C6suP3$dDbe$Qb~Jy&v*!hOs5w93;&7dCa? zaL%lrkMaI>#OoQj+1t@3H;U59ofa2&^A`VTYeSTeG^qXR6vR&o3o8p@b$kCB_At7q zIN&DjzSmhP{W=&l@3`-`GAfu7tmmK8bgZbelvH5socqR;JK&$)-1+$UXu*hsYis#j z;g&COp1epLB7O$cD>Gl=2lg6vzoOrzIiXmtD1)s?)@mNVlwWqXjR&n~L4$@~UfC{o zE~hlLjT_il)vvzqxQz-R4^~|3X&;i*k(|#wE%{0m>3yD$t+xVB*oSX5+kWaU30KZcp@UWe;1W)F)!;UrlpvC}fqT=q{WPI-qm^bxhAhq+ayV$rWitpe0H`PEqFS#PB+;zHWS=x8h>M7^=b!oQDYz@3@oNT>0y7mh9@PJpRnE> zJO-b(uq}8ikY>q&4kxQI(1B(j`;bJx!icEhmO}}prNBb6Ah9{$orV}08xt#b`fB0d zN77rRKkC}g75F8y8~B2K>GDe$5*UzN(_AmHBZ4X-PXePcBPfB7SHXVy4E+zqTanhS z)^=`5%hikIqwfGotKjIBIyb7sgJ{#1&NbQ{!eJghdkoT&y@C|7qN1j6(naD!gTEEN zfN%_xVaoX=_FR$RbfVF4b8}N2|yyfv?!1x-blB=HEgp>F$$S9%Uu zRR|W64jxr*>@${0#>X`fQg#9?gm-?+(D;ehmpo%<(`nPd&$p?`wTYu&egFM#bRv7D z!wjxxY;GKM@qNCgDG^uR{`~wL047&D$PD&+<-F3X!CVX<^$HR--*fh*vZB1A0#AIg z*I6{;H3mxPydzd5NSC{73@Qo>fA__aL!nT!Dq*77`2$bb^uoddo5%XKzf_tM8W?#<+Z65))Wwh2%qmJ9l;k%z6DB+Nohz ze%E)=J&a`F2sXnl-$u8Esh|^Y{qW3#S60{UI zovT$}-ikc^^aG*Pn*;TG!w-j3SfR$Bk+1w~yklqZQlrrOno*XUe~&Ln*vl7Oh;Xz> z>^n0Y8XmE@nW@D^cISbCv)l1vd8odkcV4IWNm1Lz1XTG{J8AJi&HwB0CZ0B%J_ti! z1zjeUYSq>XYTdK)5hk--igqH!+Fz6kgGD1g$iZJTACf5&=WVO!Q_Y%XzuCI&1QeXB zM<;y!QM%VtD?&R0?TsuPP84j(4=c$NxgB5ac>iL_JfO5?v#dNrtD+!Lg=cfr(>Sorb8HQU-Ju5ZJdP{#GUwjoZ#tnAAC+i*1Jc6i(aC3Rjuyb*ezgU|vL=tPAyl zDROXJ^|RAcj6U~!^}Hu{);VuM+IVKgMb`Yel`&dGLceDIMy%r(gZPs6%6sx7k&%m) zKJh>TNz`8{<>?O}DX&Y)k%PUD^K0nWl%>k-uhn+mp9&kkyI{OfU~nsRdd(!zQ&h9g z98XM4C|ueLDR z+XXVT4$Mo(R{0aXXtSGr2Yipd5ep-~4#rhm0Te`px_Ohjdb!?m=fBH;_Kx_svxbL< zNFxkeeGkg`@r71hDTrg`?wp&T1vCU$!f-n=j|+mav)+rfiR1|q>b?D4_k?EJp6ncF zDZl%rQ|sZB#{Dx1>S#H4qg)+2wOuL_vM*(ouMN|;uU9%&aL1zB2e_7tr)`m?23w(& z(1F`x8rrkBQu6NvDeN=-tqBH?;v^wLPbnb_(`Ip9_d)SDk(M1~#qFH$ipLEanX23v z$V7Pjl}y}~m#PC^Ed6Q4MGJS-Gd5LS&U*j$2`Y%bMsba>Qdm{zSb?y~S5Mg*;*_xM z>%=i)Qc~O^&BlV~!?nz6xf`T~Hg<7(Fv*~uwisPbn7QZXu4t2=MzN-#(3EMLdrOBi zbS=R5lO*yrGE&C}4HlhLbF1OH*X{v+dE4E;s|RgQ|FuQ4uQ)UqA-tzznEKK{1EAT4 zN8UWdo;r<)T>OoN$^c$=Xpza1Mvz3o_ZM-F!rk3g@+EJ6(zw~NN9=SGUhYACm3Es` z@+R5#3lV}XpN^u6HKT1o*R5q}qw=WgsHvpsT56L5gC$>fDmN13l_-~l#K>`5_G<`+ zmj{X|*NQDmHK9qfI|x|sO`6viuCsSr__t9=3fBM4TiEs-y+?Y(`9Ts%GVq&u7twRf zKfE|3QN5PRr~N{-TXdh~@Q(;IHOh3@Je|oKzi2uXf(qod%@nyZ<$8L0@|c`jM#JoE zwthBmpi;4!v}}D8rimomWzL`Ll9ub#`2aL$Q-g=q^7ny#2?ChR-TO20ykv1uMriNF zRoC16RpzSjf!0>Wyd>OQx$aX5^y;-;t#K0cSBNj-ypY+-5gjwp(I^2$CB=(IzVbM|Izot5%Gt)~zZ4##Z1gZh&SGvJ0>~GeSab~J z9ZFQ=BDOMkS(+MV*{B^42_{x#sP+7d*@9XAMpfTDR`t?ZyLz(Nc{<Z!UCjDl?$_3JVr3f|Za7hana;JQxOqA>Rr}7__`Uwo^qNCy}fTe&hLQR+XW* zp$jC$Qi8g${glyjke7Ev-x#SEeffg=Tvs>E+xPC@xod{}yrYnHlFGMe#5(H;{5B`$ zbe%6A4S8#5vDm@l1NtOv1efn9m=D}j-Ny~%*XxZAUTHJIT4Bojj1Uh(8*x`N&G-H^Xx?Rv%MR}xIcig2yaaQ{iHXQAFlVX2Jvai5FI-NM!l z(w!V_|9VS)=z3QO4<`OD^^ho6Y^Y_GAV((#*Mn09yp+X3fP|P-|J1M*Amg-&9kj9} z>9ZA3GNt7h-pV?&9MA0EGi>lr6Ce;d0LXa_0s%6QPrAFiyN{Hp0FxjoKDV&&SXe1i6DlM#RUS9i|NDgW7C9o(c$i4q+ zGE`Kr^syexU83f1N4x`N5)>v@>9J&9{evEZx>G2H2kF<>*6SRTvzfAh&OHdEN5Mt(Nv+^CiV(;^jWRNH*xUiioOe6F11Qy77x)^Hx(E?$a@ zQ4vKyB4Ss$j!LbwPjIYU@ATBPtSnZnENR%wjzSh{LUCn-JUBvkpA?2@0L^L^IdX8Tq8=( zO52Eujdo7p{9PZu^3lyq192*MCUStosnD0NpYvK=6=8b)N2FwK*qDqDwE)SMy6d+; zeKs5B4LbwdNs4Bx%=PQ-nHpcl*pOCQU4W~=;%i{eSLThrL7#zF>*$ak%p$2l{3;(# zm>f)lvAOv(mbL2JrVN7XQ4||<_DE?JH7%?vQnNXp4LYfFw7Y~u5xZgom?0F@j(&kx zRwPL-rhbLXt6q}7+HgraIxUugmG};vb*0Pv)}z6R6`=alZ2Y+iRT!~aYoycrX)@X^kE8L>|!@)^r6G&e{8XDi-Rj}Owp)n zGGr=9{r48oS1Y2&9Q^~YHvaW_q!-GVc8purOcCq;F84-e=OA2dx%dt~|Ix5E1vy-! zLMH2eKH9G_Az>V769bhsv}S7-nmBG|V zpCL5rch(mEs4_|hh4ys?4ee-UbJg^ZK4I|;KH=`%5kTE@2{hB~i?Y&l*4Lo!@+3Lxnv#Ih~ z?)B*3O-O6!Ym|g{{>WeXJ7M3Ts;X+=;Om%VY5}rHj$yOTz-5~{xOwOO)yaB|!H9E{ zzOJqz2a(<4t2ntjyUEY-@$nx%d>9%Uy1l)fELB%_N!GMEhB2duhlC|wEuAx`uXv@D zuLZjvzg$^p#Lo+fiboEibuP2$dokUtG9RyyeT<_Z08u0a?jfY0N8;G$mbK-Rarcex8rrzj26j%D;SRe)n4jM6|B6 zwcN+pSn%s-;Y&zFWMph??Ah5_WMm}xTRl(0=jNa(wh5tn-ceFga?R{DMZch+pkfAU z7VoYja~6xMc$`mlhUjAXuAj92eBL%|)Ssd6a#TNe1lm77ln;5WOrA#$Z0_#b$M$}& ztx$q4)Z3*P!Lgno0(&qqF(t*j^b&ZT-qx*Hlx_1>ZDCOAGCq@00X23y>g4LRL_#2vGb?vyDfqzKM*b2nJ z!bUJaDR4%)g>i61qTj4$i?9*}n^TA{ygmCD!us=pO>!F({bEx_nL;I~SkS#ha9^KX z>7>v3t}XYJz|o{+ z`iMOgTdf>S@BiN{0EFo7@P1gId(V4$cNzxlo|v3OvUqpgm(J;h5{kru9*=I)@)v7t zPlooup{kweA(f)^S>$vu+E1jKcbRc=P&Hi0?{@~JIhJ0&AY<3p_c~Y*+(ef7oDdSW zkxlAlO@4a%QLb37xDz$#jn&ep7scbYe1?##yTF=~FJBa(T8iuLATSt79-5~pL0hi3 zau8mv#J|Hjj95nrCLt!T$I#;;)Ih?JL!|#nLxEw;L6kD6V{D9mjM0r0B8T)S1E=h9 zu_ArUdX?ClBD?K-yjTfx2y{Y%$8ESE7~RLUldk~A%F4=GTa9;NV-)CGq>Od1UdSkX z>b0M?#~jjno>Gc^jfnD+3Make>P%u4luwtJCGS^USG?Eb6d1lwyB_4*J}toBMV8~i zB83uJe;|ZBk0YTL_c`4d7*G({6(spNH>aUx`LwGR5t4?Mq=2D;@Jm$fR(=>lf|<1$^UG0`$uky*c;R=#$9^auQoQu0S0L3f@GM(eVs=0Uqt ztgSN>dUO6B`;H7It3xbK<@4d6UMj zZ`Fj<6^>5q+_J+|I$1_Kah!4WmfBwrfBZRSKq*ztc-1=z93;AC|LfDwsyUz^B|`B| zLs@Lq#a@w_7|OEm#eOJw9Cw~5I6e}5^x zmUty392<;UTU!I9@`2Q>v%v&r>s6Ui#`gZmlLS!f=TR{=&HXD1sG@9gN62yR-SMv% zWr>M)iuYp?i5!;p!lNB^%SIYJnlTU!yD7Qin!5Kr+vGPd05&S%Z_Vbi}qA74Km>!0Gy+YIt~;MN^0$3Y4fR&OWW`W_|IzZ>%H7p$tI zd~(NI%JcX4!H5X^yvSAQKbJQ}nh>$h)rX5k7bFYa@}tpM6zY^?aU z`xYbkmX8zx8bXv@F)_Cp#a%T7C;HXG;vymCzQowm&=+M#k%^?4$L3hH^R~&N2PwnD zW3#q@A!PJSpF* zVf7mqPuY{iRVXpu*I$jHJb9t;G4dUl&xj-pCyR^NYD$?00TyCWW3cb(r>>r`Hkj!t zlmq|r%ALpL5xvmGv@?-WT>&CRQ9%L8bNvis zxSD639&E<`+5iJ0zIO=x@^r>{t;jNLzqX;K4J$!LRy>^CaR-(6Zx%l-crY+Ac`;J*^Q&g}KqMI6T=VGw z>{mJ&jkyP@H*yLLlp3xL>|EVGdyIC!-_2R@0ESFcg6hFYBS2J^%2$VK8N&4%j3}`p zdr6m#;2^Vl7ShG@aq*yW@qnJ59&j*N`~2U`%naPP3Gqu+mHAgUs1g+KNnv$04rI9Y za>ehcD)1b3bJ(g*W^Jr1C^q*Dl9->*O_izg=1iif<%|1m$A`=56&?26&r!%{HQ%ze z<+edx#g_^)C8NXG%XZj?3TU5@-OhpMt1X0AuhkjCr*|Ly|!2LxvTt0 zF;GrAU((=c2=J1|y$S7i6j}rn)?fr*J(Bi5F7QX8qeYJmVYnp4hyZ0o1CFh;YY_M| zIE~Zu^H*nQ^|iFL%*`J_`Lc#%nCE01iW2&I^0TVt;&`p~Fqc`|A9pc!HZ~nLa5TGr z{_v2+AtNJ;DOd?Qz^Sv)>BGxJ#w){D@t}E!gu8LU*LRBzcb>#X%&-Fftem0O#c%?QCi@9gVdz8 zVYZo`&n4RVgbd`vK7|90LhMQ7A0n6 zcx?x2_IIXMX`bwx!*8l0bd=WoaIrgz-K!^1JUA(?LB39OVHRForZs)IP)Tiqx8ymlp- zqT^i6y7VNf*-ajyFhu3GCPc{nqQA9ub61T?a{*aS5w8wqe%!dW6jxYZpl`O0p58zI z4t+Bp~670Ma4Z-_bS>laB67hJ8-rKkAI8%5@h8rinnhPV?>%6MNv9hVhQ>_NtA zhjp<`XjPOMs+0NQJqWVmUTP9TBp9);6VsZfcn8r47-B=(pe#73Z9r&Dl&vK(pvpKn zz~&Zd@%UffV~zhY$baSKbqU1O*F^K)R(CR&+kSj69Uy=QKZqvb8bMRiKOq)b&!?P8NV6@gpzFw8$3c@WooShSI zvw(BmO+j#S(+Wfx&uIY1dJS_nfmUocIG8t08^R!vt-1|!f*t~DWVf}obq1GdvbiqK zY>vINGZo3Z1@xTeYGyJd?&lCoi6Y)V9~&24I!#Ted8DN~>+5y)5$zlu37-50wR-(Z z6T=qwG9{={t0#QgUef=H2Xd0XEU$V73l(1)ZPGTmF+}RQJI{b9?ny9DQnNt0ZlzN!pYxZ5Qx}lZ%VA z$8PE=87+Douuhf^*C(Zg1{F|d%=ByEJMI{V|n zR8d4bp<7SbQqqp#w6uFt0#gQ9I)Mon(AF9Qz3t5}tp0m%#T z@ceT7`gn4(JF?Mxwz#z#pu&+2rJ|*iC43sJ6Rnseko87M@h!b&y$PksX>~OzV&I$I z1u~Y&kaMzDJ-Jik+e@=a-;niE_88~>gP|hL)1SV(-RgstDxs@K;Pn&$y?l=mNrke#=iDB!!Og?ob6)#cKgC-{wxv5xZxo`qg{`3Jw1G$ zMYQkoQ8Bv?l@>T1LoswBkDj`4k@}GPv_~JEs+Hb>b76kD>~=+Q3#f{$;q?;=k$2Ax zvkNYh%yzD1{>Y4dV8|t%Y-rr-hFq8jsF{ge{~d|$Iixfu=mNEZ3=aHg_6_FRdB?A~ zVf@v$50P&L(ePxn1nd4GY*Q~b;H2>m?NEK(rTMH#0E zCg?go9b@b}&zZgTtoQSCIE~@H@%0jRd|C~2%0HEoiNXN;cWotaY-$njnY%LU?l(52 zlqMBnOMgS;x>i-(prR08{FyU(+2&_jZfYi-U#@&Aaj>b=jc3CF{(2Zra+Ey-L+RDt z?UfYIf??5eiWa}VWlXh(Cs;5Adpb9{$UJOu5PDUHI!FX;ZruU3IWf=Oa`#^9CClH% zCvL{2n89Vs1k%*`0{GLi8y8{;`_)Y8Lnwah7%GI zXE7yql0mYNv2fAro3l6*7k5XZJB$d6c`+v)O4_fHAz?URiic|PAN4vH5~Sl}K1(br zEf{(k@Xvn17?C(4FNi182g>}A4!65|W?0@+$$!rj5kMKygll#R`{eJ1jdINibO=nJ z5^$!noUx{vOAb;HFodbtAe_CyJsjkPPrE8Sf?!_tq@c-Tf#S$@K$+)c&O}sp6uc!g zvEt(hvL8YnH1 zXUogfW)_{%BSF11NNKac*cgt?Km}-VaHP+z=hg>_7c&If$kbATTYk@S78;j05BgAH zIDG72KR7Zr;SmqX9O)OlnrjTnVs)Vi^zo3qQITIG)H-rtuq!dqgnx7DBzl1VjnFl( zXi%;>uS-&*qr9pyLoD=h2xB90i}|p+iKPlx1_C?|(IT>)(Jn>-V8gF^jmUaO$3}F* z3zrMZ#c9t2UiWB&wo~=8e6u5YOfRvqet)Z3o<#uFS_Oj^&17HQH<9huRcBGPsfn^6 z6}PG(WY_=OF$c5#rM2II1u;f|B=n7yw3qi(;|h!~CrPVN2|+HrD4qVzO;GzXn;?m# zL4%$RDn6o&@Q~YGQmkFR@oy9{c1KuyFrQ=N@93-XFa7V#H2IJ=t5S_Scx2UYzE>J5 z4q#|dg9>uW6fG+4S?K?r-y{+3dTOT@mPN)^x@YW^@4$f)0Jw+< z8MpEKzlb6y>l0UF8vRJ{lCF0Vb;GQYE|3k>l&4-BMGf& z1gJF7_+YnLzW2C3Wxx_CSzpFnJfZr{zv3-x6~D$jMWEC&FHUP12h4eHf(FGL6WD+9 zbNA5Jx1H>H?)>=S!SZyYOVQQ0D>luEtE8s@Acuqoyq-^KML&S039iE~NO6dj=3l#r z?sPQvU$>mP@oCQnntjs!5C7dk&omeIBx--O=on^WO_cb`xIF^^2}?8tv+P#R!0QHm zz$V^%xVy8&4y--z{P##bwK{Ie_A9vR4J_kQ z_`9Ij6L-$Mv1FlFGQ2K*?a^&6ax*pD9$T?V{OkG33XOnwNQc(5E^t^O3z7>PH_K{m zvn>P?ewg|5xc+i0Zi00fiDpo5QKtkEM%RtYk-&2+1YpY&FI;v38tB66or!YMf3;NE z7%;(b!Q|ipYkgC7hMJ6=z;gb}RksDri|F&ps+yl$q9f=AD154aMUS*ad8u3WDwRZn zuBAMuAavre;g9#v`^iEb;N_6AIqCZw;0*DpCmnU=<0Y|H8eMrgDvZ z`}FdQv}B)kH`T@q#=++T_OVu9NF`JyR@FOhuNe4Oj6L+5jr-$%s*3$}s5%?i54B28 zc)`<(;Ai#N8Qf=DZLTVUF;8xU7WRugZHVVVOC%eqV|tU>Qk*QiORr-OYVEkz#VzGJesCKl#I&H z=wyPX6ms8p3jbWo+7kagQxF2fs-iL6KRrR8&tsAgU6v7dEb8MdG*V)8U5^C6NXs0_R%x* z`n@_0U&G&%)Y=#+h|K>FJ$%ZVnn|^`RKTH|x>x8b!D9eI2tLHV$-ZN;Isvp_6Ves_ zzp?25ja^Jff7Gm7%-L*vy=6Yff}bbj5_x_?&cXz4UHD%!=Zv!}rjH~~ zOiy$w;-k*+dpQ)X(R*20_15SZGQdbPhrMNt3IQR&+c;BemxVpGiEb86}gnO77QHMLePlBQYFG;A%5i*(joGcwGq62>+w65?U_6F588DGp9TSe5E-;z zZwI-K!sKNFM^r3P2h~5EP%^N(pW`RG1sd5? z*fHPsF#sZhb(MA&`0c&AJt0~)ET=%^gtw@mX5k4sCG{#N(Yaavc0_R<^3jS8(&=0)>#m;f z^*TxuBBSAn7_V{<7}#0Umz{#@O*@dIEb-Z*{Ug2>MElaM3*}8T?G~oHeRym|J`vi*GCplHI{{MJ>S*$4sm8qTj_%m%@?3wmDzCn zk78~ZhK{}obOQyY?Ff}shzIO9AGtWlDn$3`c#vyV-n5o5aiPM>F}IQVq^&6N>-TKB zp(wnU4yRmyFXYpXq&e%AX$I*4+HbB$IT!-QxOJJ_p$f^LbwWyX8UF`;UylbJ zW@*(Wc~gOLowJhb7pRIr{SNxZP(}3wOvz3-@1kLe^fYMoc#!vo-kHh=c^|#lgtL}T zeeAYd`86K~G&mL2m|I{-$wfyLo z(YLIwh4A`J|5P4YQScm(Rg*xah79^09v}bz|9y$gqV@}P4BOx-jpP^Quqmt1o@12ZwX zJf9Sw9qjg}ydBIEyrM?SlmMR5n_)Pj00iO$0nCG~T8)TZLbp!0f5)#Lf-tswk$lJk z(8pAh<&qWqtf8&|U8I1)t%QwBIejcfbaw3oYy{#^4LaY zxkgRZ_2L%uB*9yaCeTJ-*>WKdYJoeC{mNzN1gflhHxZa(e(V~zZo zApui4>3%P{k?nXFkF#Fz@iBHFN>@ngch()J7%6fYA|!A@q>r6KLjmr`ESctK&r2B_ zAo;C|K72s19;YY{@FY(EOKEu@bpGFv2hs5Hw}!HKStf>IKr#QLrDWA)tW>4gj|XKtk0_@Jl=L!8HFDp?~B!3%R5-BNoCi1Mr)-sB`-siyDBLCSpm0~AsL8gY`rBq zZpHCe=ruUWi(tyHX!7s?x`0A!_Xw-$k|CEs%_GLCct*T{?0Zuk{QohC;!2o-zo`+OGC$^-;FV5&ewLdXuYPmz1lt-EJUYT za>!ZAAX{sk9WUIkqI-;{R*80!svz(&!=I|`@Yb`(Zgq{Iq~QWLzv3PwTT+X+e->s% z113Ej)6%PM6JVp$KRvU)ZsW$aYas)I=tO=GJhyqme4is|z$ zt%dU3#CZT|!;d{15K!D%wLXdiWttvN#gbEGS~$*2g-1t^{c#v^06<_l8%08^CHyQ7 zg~_S~T=iOQ_ew3O2(@{cuE^6hI%}rm{P(ye`{;7p34n&(PN4d1&yDPN%Nmwgg^R}= z#Huo%iB(S!Py*|UBI=`hCmmQnVTr|acR6Tmw|yxy{ff*zr(Wi#6z*?p0nzNpSUC@##xY&kRcf3SliSXfh&p0IQU4$3q@ZBaG7tji&k+gq z!?Z|+mf=Bq`iSv&tibOIAU}Bgy#UwbC(j^P%@5RlX`Szdq?-@d*JD0!gswLoS3HDw z{uv%po=hD=NeZ*V0yiZ%rB8id@cDQ>Zd=HC&fs3@da|RGx}BoRD+(Ry!C}4=@d}pL zne1t&x?JvqLGZXcO@ zN?T3ti*~R7Tk*P%-SEOqz5(Pmb5#_$4kdxK`RuD^LhvsLj~2ha-%e4NGIV4^fe1qk zIxKwt4VHptG3bblqeJfQ?#!=;^qX^+I*c!M&Coo#_$jI+Ry=+9vwt|Vcl9_2fQmoA}&UMZ` zeA%&V%-Sh0mY1%SVQTnlfbNlx`$|D%^M5M?CIb_1C1RzS&4o58PxozrNj; ze)v17Ue$$ml6TL1(|MX!1xZxO>%w1qVYTP{%V1ji)`~gs^fV*?g23*tbZ1-Vo~`vX zCAZ6U7xlw$1Rvw9IRyHSGzHh}xoWuqx<`J?xiSd)w^NFbjxXDIh*IEVo#EYbAfErU z8aT$R&yyeYxbL4e9t&Mp*k3@Yd|c0Xn?OMK)-ZLI*+2R+{NJqesoA zxYg`4TJ1;1l?C>g-mni%oM4P~2zxIUPY&UgiMh3%iUhlum|kzy2yZ*9D$4NTJO&nm zIHMFEihE|~^U$FQ0v+GJzJSpYlPXZ7q5!^YXlJDSrZ@da!Eq`(YWKU@xkW39MA@IC zBVz0x)|fC38Q>|}I{Kxri4#kjr?JVf9#U%EE$j9HAIAWDF0E6B3}heR7UIE?M9*L-j&!nF+JpaO4QZ#GGR*NbrCd&CW-yj&=JB^Bb( zf@#9QIdKJJJ_DL@qqfA9exmUJD3Bggcn=4t{seXY#-DI16MmN~;wob(fL{L6P2&OP^@^ZxVZ&t$W^Gds_- z^O>EQGuUcJLm!`N-{aaWpQ?Bu^$!@UAmaWr>lxKFKsQOWZ2)EDsKeK%@Oeb=;gIM+DutlaYCrGYyE;Jz!k zWW`;241ib(JZyOO8r-GtbTtH5grWi!o(o-|!5Y6inBSYR1KAd>ed9t4XXuR=+?<{* zug3D8b~2HE8ShdIoHqetM=4JMI@kwdD^`iGnFw*7bzF{XHH*!a;0jXJY+dof;%Xfc zTUS0kL~Mtj=UW=(bs)i3OVE5xy_QYWe`jlI0 zIv=*f*N)_jbBa35rc%!*AAP^`VgiXScP2vBX>rGJ23c4d9n%q#PyS?VcKm2_H<)addIdxCZu^ycKam3T z>lsU+cg=z!1#nOFRfj1=$q7xB%=(`j{ER&*KZ>}`-$CzI6cn{Qf11y*ao#!aS`?nF zMis&1!Cn)TfaU|SKBG(19UbX!oM=}L(gRF@_e3Jf9%z=40&~l`*~2c))|Rg5%dgfi zS>>m&sXGlGi7PJnm=p-AXcakawFDp4A5R0pK+gGUF~4SlrNz-j@a|v$Y#$xZZZcH} z-WLt0biX{|g&sJ*8nA_?WUysezCqfT1*z3+gft4_SUktjha4V1aI0abN?UJ{rZM>A zTr!4zj-aLE|2M{S6RUtdDdSNEUEVj!)(3mq>raSn&I0gQGTd9TUVEu6zX=X1u5(GOhkM+|U(C?&HSM_bf0~;e_&`!z__JUubqpOKT=c2>fhM1M;6q$glRWu7sIQs1Jtzcs>@H;Nx}=}%MoHlYwhZ*b@blC;*`3bB3H9Td&e$bUKgJ5-Y8Ui)mC z*skp9jUw7EMj$Gj`TmpBu7nDOGjH5i$QrTR`HBj=l*Jq|&DB{$t7{H}{!NDQuE;9+N3-?<2wKg%IzlC1$oyl(?-A4GT&TlwO^UN_KN~RCvn~I2U z8|iz5<1pRJn{G zkRjYHn8FC8W6K*z8nSw$2-hD{U+_)y>S0Bd-Xx2m&#A`@ahe}Uh_ao*l#=a%ID})e z@uw^6rPoWKYf?PtT#3!5m4m=T?)eNS@hZGgrN}EgS$<*m2d|>+&pJ2Y4p)rlVXSn) zT&%t;*u&TF-_bSvOov{Ewr$feCKR(Gv<5RduJC89&x9h7mU5Tqfr0+lTGY0%Nu%PB zpU)#uFID)c(~J%vg->a2u?|CArDvszV+$&Cc!Ad%Q^FJ2ATXp8e| zU!%0%2DDvGjy?|=B{yu1hZK$kXr{rbU8v>>udYmgR6Qb8zGM?sOVP7Kz4p<+-qW-q#)6N_$`8z$4E*)2Jn=ih{RO)-pP<_?+Z3J zP8F8w$2UoLK$LvPCN(bcjq{6-jzmochF&VW>FLv0^SZtmr^+9kVfA&WKwJ;XO`6gI z67hQge&-;~P~=ck_^NGG_iXa7k%?pf1OJ_|Rao8Z=co2sjWxV3y+3rzvhM z>7Zj-O}zP~U#$=)Ww=wgUwk!FD|HODJ}<~)!=SGnil1umF?oPP`=AHdd*p6#hb({To%<*~cVnUN`kK=X*`RCx`$3;F;=qZOWDkko*5`XGRz&|gn zCn&#$9~dA5f^YeTCqbgrAE|IP@ptxrDBI``6jgK|PK&f_>brNNzn-bpyTgyt+a>yD zr33dorxC4x$8!CfsLwe+lP0!|^ltNjZKS>AGR{UsMMVlzr%DS5g6hLS z$01K#IXI)4;7Pci^%P%-!xLr+BE{baeR>5@TH@uZNXXhJg7rQmA8*Zk*Ff?DyaIhA zAUby7)-|P#i70T&yG9+sF=H5!&%kfZQ2LhtX=~8=xbM=$0qS8s4a$SAP?(8ZWp$vY zmR3apamrLx`(q#b5QD0jpw9;aD%tviCF&t00nxQHfJD$Pgt~U47Cx9;2zne+X^9WG z>7Vg|T(=v(x6=y|PkD!Rq^`21Zy`Zny_sZbDI_nXZ}%&QiOZ##`#dJZxH+|G~jx0m6WTg ze?ZR>>Irg!W|(V0XXetS2oxqBx?dYAE*L>IH0XLljC@4d>3=*BMwsk^>9V93DA+$?R5YfMIkBj|~XI_)Oj?3}SANB}tzx$qodME`(#No*u0o;zq{XCVD zK@`_?dbe7?Z{R`7tGl-ZIaJ}-48JTgLcwWP;A z@x8>Y{7V_;9NHSNJF0I{HUCh+mm@Vb)u9*y!8b0M6?`l*H8O0s>)PC0^QBmc;@9{R z3pqAp<4EHjSuE+Fqs{!h!xMzPb(4cp-h>wnTbnm+XDE2OZM~CP`zvl`jmF$E2en9Qyb-G8m$^J4U|g|D+HUSJ>51Bpb-E32V+v0Jof%#B z#EEk~NkHeSacGvF-!vEMXazex?E@Ws*7Bai5k`d2V@(mw5`sB9Y#bKYZ!E`-Q0&oH z{r!W-SR;Ky^Ui%d?FiizHehw?7h&MFUT<~kDjrx zD#B`$X505Gv8gyQHFUvpZ1QfN5`Py&YdYJ(u^q?-eF~=wyr4lT8+_QNcfdzniI2&f z90{FCMy$6KD)(MwP9AhU;23{l4XHSdn8!-4EVPomkYa+ zo_eE@&J5G*SEU_#Ry&>Sh+#0P(qt%j;CLWk&LpJ>ikCn4`4Ul>7&g1#X z+R2py6=`Xy<4U$6UCX=n^;(R`~E}iDaQ2$F<-+UE_xgZN#w*2}^PwwSpM`Xia#@b(Uwt=e zMc(|STe+SmyOW2t!-qX!ZNyLDVR{MR>t`L}of;Y%o;yxBZPCv)StUk^JOo8juXNF- zJMk0?a|GOsU07Oryt#OD$-ifFEjrircY~H`*m~m)t)-us zh&)BL)-s?|%`J!TY^XSXjV#>`&87u7fwiFMhuw`9uYy?8-A?+ZZvmWCQu%G=7TD@g z%Ykk8X{i8Fv4OrY@(z`9B{Z|URK_(OBUNTj_kmN(T|o6{Vl8EsMM%hq>z4PluS(5z zo3`Ap`a1_l%040U7W_*+*Rug~Uky=+)3KeXRqa7CP8L(xXeVJ{{iP~mR0C*PtTs%& z7Cz8|SN=lTT7KTRCa|;T7+Y+x<^x%XcegAp>#&?P;d?qg_XfxKPC{@F?1RBo5Wj8= z*prW4_Z#m#eOd%-C}pgTCws5Ic?dES1i)2rB49oRcf%>eGGIT?9+pEh(L0M7q$;FW zBHIAN$?Ot-n`a|YMcG;VX&9bZ8b9#JvETD}oC{5Ctr1g}U2jgJg%2MX>f34=uZOf0 z5^sHZDZKp2ud3TayguRe>z>kqL}RTa{#vWmNl4=Awu$4`HjC0L8EAvRufyVq{SpQ^ zbU8)L?#F)I<)ardA1_YqD_l%|zkj3$b;`|j8aR9)zvJflAbVHa*luYGy}Q@@+u{)S zT+EDtcYh7%X9ijLzR>z2iXxF;XGZNQSI_PzwRI+uZ+(_3;?F8d5K@CeXvI2|3x3zFpK5mVR!8 z{o3>OTR*4y;qYw^{MoL}BVoZ|lhHkwA0_>gGgpBNpcrUjGH1fc#mU+G{K4`M%=7&v z)Y4vN&Ydg@&-w-R5RlLV>uGfM-6tUh-6|}Y=09u!K-96gdd+6B)k(?p!`VMv#Xj=$ z=P#(mK`khO0$|QB<>kn)h1JzQz0=GMPB9Qm`k6~AZrZxyGBSQ?(xr7N_~>2~BO$yc6@>4F;>OV))8c{O@GU595c_;c@&F9Ujw-e*5XbfTyYFc9KqWZY?ommaaskTL_%dc}fj*VWrccOb|Qc(fXX0MLiDoGcDGMN?C>ytC0kn z@4CFzg7R{5ZCV(W*YT#Ndq|HH4PUz;9L_@Q^~Yob9>KRFf9gyxpxCdU<&Sdm+pdZ+ zZ}N{$L=w5-oAoNc;M~r!49;8;>+|FN!?aQRG4Di}nS*Ac&%P7E*!}S+0`(Qi>vBS_ zle$_bUSSNL%*>y?*zVzyJWP zOwo@J@=MazU7vDS%SXm^G3ITb5>|(WZZHe$I12T0DO+o8rIl9Q;Cywfihdw?J<%3EzFL%Sju-IK`^dlIg?*%g%m7IMo0b}^6@@SdF!PH)dSK7cG}IL;c`aNqdQd>VLXL$HdPx2;r0 z{g0VeQwK7rveaw+&L0hEj@9`fkOEV&gfw_^sd#@-aj`trU2Hn4%1OmOiAPfSD{I%=C zx*5^q&q|ub2BQ70?50ZDqE<69cdZ=%XqPM87a-ajbJYqrOjLvg+cVo|Z%8OO)Y$oG z8)+8CLO3%nQhLsgvH|b_G-GI|X}4fPUOoE|kZO!}pe;E&5^=IXK>)~z zGuT-6C0i|z?hx(OOER+0(*CT#{{m>eps2?#G5Kgo`c)k7NKR3lU75m-6e!p_=qSLD ziki+!w1^TEF6TlI$_Ir0qZYX>T|K=VkwB_+HP!zojRxia5b(dhl50hbPrJKIG~ZV9 zlK2POkr%(_E#$Tr1>E?T5z9T<-r30!slT8R8P|!Vn{oLU1^jO&KguXAExlt23gFiP zfplqEK;bO^%&Kv2Rv^OBd&Thyg(N?|=OjHr)7u znc1>5g@<|)h&7?|j2B?kf6?~WK>odoMAQ?#{}co0cUVo$F8E(N0anpc`cI))dr{S6 zLqoG}Agjp#e|!IT^MALIBzd`R!Q3hs2^iwP7sa&wW#1Wt|JG54&6K!8ZEdZRUbx-` kVGKl2JNe9i3U&lufz@BQ)`kX(fI*`=6-QAZ)y1Tnu3F+?cll9DcIf&cJ+>%VI$uEV)I zX3sqHOl+f6m1W)_6Cwiu@J3EnQXK%G@c{s89T6IQqTRde3jRQHlGOu$;$Xi1fw~IA z!vO$tKu%Ij)9b_Wny;Ior9aQZM$eDDN7>@XpB=ihBkAVjEyq9We~V($aJ8#J$IX4C z2om>R&ETdyD#af0UgAH|=PYEMhTok|PL~#iL11f=L+O8KoWtvEI$ZD9Y92?eKswqn zWyRUrZD}+~meADPER&JMNjPB@kUvQ2nEuc8 zR`aMGbkN1cMOT*~z($}H?j8QHKX`HD%WBm5#WBuxa}vg*)BoGa4pQ$jCgc*%|0Kf0e2o&CJ3K z69bTd%(luHEu4JHfBgtoL&I@0306c@&CTdYwg&7=lE%=$&GE`WLu?VmM!<6O?Xif{ z!C2|GBWZ^Davy=khel~b7QA+RGO~PsI;q7SONvnA!~*ZAch23<|8{)4%>?DO+4bU-fs6BCVB9kYb2>!@8Eyl{PND<#!qocX4Gw^ z*GcRXw5Xce%;xmwO~;86nO)VYI)XJ@gVa!SQPLlqK;Iuo8fI$v)K(Zr%^JT6iRYWA zlSWFP9v33P-Sc$cKg!zIv`BSpE48g@(JB8i;7}!Jq8Y2laF0-m z1y|~Se|5ww##z)wCgMZ&kxW4q8AMWvIGG&83!+uv#niT3(ZM;8OJo|o^|_Lk9zsFc zcuo;fqkiYI%MJuBi6a`CVk)yZK!7tvQ*s;g~C;J&R0iDAmw0}EvT0lxlO8=Z=N-$GH z6g3_I{9~SiwdJnP#oYVFCu_Vvob3l)EBPWCxZNY2ZZ4(frqfO%XNoWVQleSE^5vmS zvtO*{J9waBiBK#N?;Ful7t*&c+AQjT#cPqEF!^x~j+7IFR@*ZR%9!N_$0=c;0CHIS zuV??DQ#Ph=PX>-k(@!oIg;^wS!%s7Akkxo; z^zUlhgYfVif$Ybp=H95={clOEj$07R&- z7OoVcB_=$}O0%B(&zBKv?SU_!Pj~4#`1mRv_0QCoNkB1}50E11$1gk&GN*m~eYkg1 zg+&Ju1A=DB{5DpWP=J<6BEZ-|1i=CYu)FWSb$xl}3moS#s}s<-WRpsN<4bMDHv%kG z<@w>nNsbyaPF;Bz%hL*9VuiG!q4yBm>^ zHcir0D`cay(rwVqO)6A$k_v9T0C$rze4}0?*-eeY-TjS|DkD9c?6ka82!_8#1Xgv` z@7CBv`;!hAgWCRncRe{_U*l+MIPlCXV@WqD-MW!mIt?CGN%lhQYLXj1Y!zrXfPhIY z8%Z`&iu>lrt0kqa+}jMNIWEZ6;!l8*ZacXw&(o&;zlY}AO-KobZTIAau>tSaUg zn>Fk_qqO`R;shB1)`q8Jy|o{FQHdaeaf`b-7x_p2t=}uZv4B-fqW<#2$x`xRYswssS_q~H#Jss?{Y+>X$(I^p&3+o0 z;wC?jNskb4iIrKKX)5R=`7Q^iIO+H!LXfI=IJXq&G}$v)s?nCJ?{ayLfVVa@Bsa3E zv(&8)(LT6?RaN}XA&POYXSWcAb^qav5l#5+&*|Dz{u2{Ul;RwpzzGb zzC*E`?0JN5lXm!da}qazdlHX>li47z4v0h(f?}RZ__r03nG1r@%n%ZcwH&9VY=r?Y=niNpU<-hJn3sAjEKO%-ll5f~~>r{&5E{Req zT1(~mgJ)>Y&;PxU(p(X>3w&*HqeS{{Q3&N?pSG5^`>oqP-&Ga2R`@rH#!=!-RId&p z?HKn)Usqnt7CrkDyw$U=?aBVa{-SS1u6UF6sGaQ=uAIa)Fxrm2?&_HLp=iQ_UXM2s zai!%d`SeUoO!V~LXWh3zL3K4FVO$4SXUyg0C3LVT6D~}U6(_@Z!;BR%DJdxl3C*_7 zj8$q81VER%n6K1W=BSVY4{k@{6u`qR)TgoT>^C=cp`;x;*7l{wY!BGx2e5H)7c`d) z+x$$t+<1qR=GNvW*zJ_uC+=hRy@SgkHabtWzdjp^p~p%Wd-ko)EQ`%?!hsW5u8R~y z#w>344E$St9BiEST!f1ndU6u zBFQj}F#rJMt1i=F6F2Y`KE0?S`FC>VF!oRToBE4)QfkuDmckp4j<+eEjoCHYF$*Ui zyuZYCxe&{^rJ`nPwG~l9t$E z8FjTrNCUdkT%jxkGplN6ae1Ng2}0K$r^+iy8u6`AmJ_-$Lz$j!fsdTVFQmVK9C524 zpQG=m?28+N9OoNilw@l5A6@y8^}0Xo^6m#m?6_0>8?dDomX=^deSLk?e^gIdulMqX zX+s1FS_GD^Dl{>Ne=Y8M#NlAVLSf^R5WxZ2Wy}^a+_Kbq(3u@50C!GY!X+`!?T^ps zI9_>Z@S)q=+x<~n#GO&wWx@{-09h0Yeefr=7$zd@D?PNpAF|>E%?kKg|1pvrajEuw z&h_zeC=uoi!&t$$KF}ZB8wHy0F8AIOy=3Im2&_IC1%PCUJd>GsBadB87#Vn$dx2kq zuU@d>&at(%xw^V+o{AbY6`azsuVT;n!59B|C0l=y%@Z{-O+Pd=)S-3NqHz}o`^>&; z%4VFVQu5g-y|Amx^lZI*hsL9G&7oBT+nhV+#6w`%8C-cXwLQoPEE=_RbX1g;<&!lv zHB)nPRyQ_O@>D*2YhY@J2XZE)31ebnh=_<5SgoJ39_vU8OGZ+mYLQxfzci(48kd;X z=gMrHM~KtrbZ^h)FJFe9$q;%VC@4^1f{x?2qc=RAg1W?J__%)t<2a*rHYp(iAt5O= zAeTH+(pm(;V==0LRR2_Oq#2W8{m>3U3>h_}q>z-nufWF|y^%;5)=*bh*U`a?8Dx1c zxKBi6YK0gnQ3O%IoQ_Q@BVgB;n&Tv>!IY|R`tMU$H+6KKC*PSXJB;fzR z3Gn7l>N2(XKYCoN_<>gYMcelMdlDdQU<(8ysJ?@_avC}PjiWZunH}nHeR=$xgOnUo zg1G!!SX;lN|L9Gg4}!;OK}gDO`379juin5(zyJKVhrBuyHuC!(?&`M_=OgFmBW&&3 z*t-@RN+)YpoIVF*G%n2JE|1|ivQ}j(g1oOEM8J=e@_W$7&7G*?XlP_}PNzk1l_@X; z=6b^Jhp7(?X-wlwmKn##fBsAhQ~wJH{5S3|yuq+Qs)WVc6t2Bgg$u9E+$kB!A~n+T z{pb5QvojMgcq_pZ*S1dz{RI_7+>_HX(uSPv_*gh&*0PTcWm~Q*U^&TQ;HvB49$1=g ze*b$g=3&ttHWapoU-(=3$*2w=DH;+QmlV9b!khB--~*Rl{lnms6<2vxAN?lw;u*8O zSPP$Lq#J5=Y;%7!dypV#>e`flf8{gU!=F2)-CPWe$lY6I%VB|7kOsxLJI>_tC?t=C zs^cnSq#EK=LvYkN`kFOCMb9$UVFfk~#rnU{L4n*96$kf_u*Sc;1IA~+>G)l1DLX!@ zK+DNbtzLydDjHs@R>!Fx&}ZRWSeQteh?#(_8pf6!&7M1Fx#8b(1C88(W6SlMP}ovg z!naN!Ure6uJ%k&LxLct(tUm!gpeoTqL;pcRMF9jiCb!q^12`tN8voTZLGMPd%6#5NkFT3eLXN!eio?I}atyn?E=;&6z|WJL z+-m{PvtLR!VIauO#+CB%@d+Gx9vT%>Ac|8Hlak=07tQp2mmG+PS9dFEt7tQk8Hhg- zaB+2k0NKgyD&tn znnah7g6=KXjc9Xr4}s5LXn31XM-^Qpi8P;j|+i zh4IkB&CTh8jk8{#r>YkC)O4ot8Dlm<&XO>3PC#Z(hxK!YdAp598po1%^LADF zxQ3qE!B^)7YW*fuIhc4GiXPF*WTXVct(vyKa;tAvEwC}an@E0W?Beo zX@~3@Gp4ec_ikL-Iy1ZYf2PU%rGhK5`?x&OlVi63emE{(=#8(#^#-NEx@kTBJ#hjZ zGPH=W@+iB48o(A%&HDRl6xTJ6<4k{;D{mhz_^jQ#xoXz`U&fx7P}D9Bs<;-G^EF(F?DZd?5wp)fy4kJv=l)r(prdcc1G=b}!FX z16Oxf9tKb-IwdySzO`iZpQ4|(x0ZAo+-lQ*tk>mEwS%xQ(4vJF7PR28?;C3xn|`xm zn{H5qnJ(!_h0Fl;PT!5$GF!=?@pdh%2H#--Az~+;~QHc0}xdRvK2gK5+V{N zm!QQ5H1w2@n2IzAQfjm*ay28>5^D2bM1+@}RBc~l5KXFmeb$1nU(o>uhB8_TAK!ga zNf-Xyhq7hj_%QBbP_xWJs5g#i+8Y-3%YSHxZ&!3Y)O^Rw~%k;K$z@{05&U)SXO7!e9dygDy`QXt$Fq^he z+9wwos&5-Zc|C|O&zP2$=K0GR0f2=L=2_3wbIx%CpB!HAs`%S*jE4-m)E0ePT;Q7i zsq1%2ynQ9*ak8>7<7_n55Qstqb56N-h*Wq5BnG(@ zUpKTwHo6G5DA<_yk4xK+&w8JbuvM}8qjZ^u*kb3lV1WpekqpjLvT{gO$yc+<&vTft zCRTQz42L~8_lVDs;Uu2?pB}VR#eY(XSx@Ze=;JlXH?2_}Z9LnH1fBo>GNaG^|n z->;8oV@fMZe${$s2Xlpm2*->ntFaN_vk@`F!xP76iA;XadXRaPP`9#CRfJaUlQ%fA z5CFcSqRf4C<0zkH5T*S&YP?rOFJ9r_R-r~l-7$!#0k`iTU{574go+tvvGu_}&8X9% zgV649B+r4`X(qToJSs#K1_E#nsJbeR!yp#PR#i5JhqFXd6?6*W5@VSsDW*@ezyDy! z60r}7t&j*|er9ruF0#r_r?*eI@H*vwCO||alKEbdcX)5e!Gs*!iEH*wQ(YO zi6sFsY!GoM6cAzC`p1zf%wnLBIqdJ4i)(TIqhaB)pvxcCJdQxaKr#wW6nG?Yjj&l^=;(N( z!7+Sj;qQ?%WMpn2sInCgkpAE!=T9sCsgGQ2+2L~8av`l}s9FbwpFgM!s?V4cx^HLC zX4aw0hf7}#3i$RhVWJD40*pt|k*3&B&V#{WJqnUX!kGH81UF- z@{z?BRYXTeM?^$qXA_<*Yg;sW-=40m`1DB^J0C69bb6drRa9i28GZ;$2N_vub5atR zNKvmWZ5j!0tUv^GEgpWx9!%*qE|+P$7#6riPgpQAGv}TGX=Yozr;`F_KgP#7axCKq zs_N=I`E$FwyBnC!R$CLy!=qnwbMwH!z}ngx@LEP$dhhA(;qmbF+|bZ4GouDTn3;wAAKa)h zp@7i-uhw&Apg6P3Rs~j`)I{(BEBs3|cMnfO^N;@i{yI83fq^1GZ2a3_o*Pd|BZx|& zq`k-7RfsHLsMk+QGpu`CDv7yJv z0jR)8h-iS-C_8YeTtxmgJ53)qW*4-&bw-`q*tocZGm0iAUYQUOF^4if ztejUHL8($pedx4(3FKP8?@k~i{CT{GZ_&^-zp^&qBY1cP=EJxhe#zGI#jm!zmixq@ zOR2rr($dr8YaCY1dkY1qf(#MaZ(BHH91cJo$ey_Q{Q38RrDCCV^p`GmHy!{8LJQ}O zr&1|^jG5LeDk}cT2iXa>)X8e=*|%_%4(yp)d}*u7udgc#TG;x!>WZw=BS9Jf+jl?$ z05Upgfb2WxidCXT!QS%n@}?%Ym*=No(SnMKit1_wS1e$2rP&rVn&I>Fugi9Oyr;RI z>n3{X(8y+h^@9$t3rXnY zBzY2&i>=@un>q29bOlCzNZ9aWK$Cp*FN3-#?!`ZV38FDfJB3UmqC4S zxjXLAno|U6U9Abo1rLXZFwS$`d;em4ctQFR7E{RK$-MQ_3=>`*f<_9ayS2;X7W9(t##f7S>*ie1=$l;TDLMR|t z`1R+Hv3VAJ0TebMhb^oJeGJ_fvJO1BH093K#@CU#tM{*dcK5k$U@`=a|n525CyhWlytH5 zGGvhY9c{!t8_E|rrk#JTa>*d90V55;`(o%pMUrBPaKYw!%IW4VctBA!bbaQ?l}51| z6ACWM1lvWRp`YNn;M7%DEf_IEO3p&3!Sp;i07MR`X==`IY}7rPDe{-k>FMhJTwbmW za9Or%DJr6rQiDf8z`L8Hk7i(DX<0o9AxA|;rS^mgqY@F}@wCC)@8mjaNY7pF5f0tfjZdLL0{-BrIDR*+zg_oL*@#yC1|kd4 z2O5!#j11lfjt+5bsn^0GHa2gra>B4g2sJCK<7$ijhq{cS3eaG$!1OBg{TsgyZcP&t zimWmZUSduqnPN2%3BfcE=mbw#XBe5vw?@V}ra566pRfH(iQI|}w5yd|1KkPYXn}%? z@brN%g5v1%$f(KJU^RZlu0@vGlsjj5Xh`-6HDwfg5Dg;!|GfY)gMPyKOyl9<;nKxP zs9#_}M+qhbIF%yB3ys+j0p;?PeecF)V&riA2+$;oAZpm5{p15|V2I2#ekrKp;pY0e z-?W|~T3ju4K(#o_M^E>0nrLXyxJJy7%h=KUGy#Xn}VFbv+M<$NQ8`7HqN&Arlt9 zk0-5ENr+jAD`DE4IE{ZiwLN6hV5-6HG#pO&XGaOiJ|5%<7qZC7 z%tVBRrlFzPa{6h;{=Ua=*@|;-e_sO|4v5jd)1|@E((>cAdjn5LOIyNhAl>Q^_sLX_ za2|u6l@&}XgX9AS=-t@(`LiMrUfdQTl$sGSM07|!R+?(q`F10)*Js?K(fYOw2OB$a zCBz2hzSPUbMcp1La=?sx@W5?vZ!g(1g(kR+f@gTLzE36u`;!IL`Hb9RdU+4qg!_i4 z(QXu0Y7x*EuaH6O>*Mki03_;in>F(N3wT0N|1$=jL#-jjl0_pQ5w6~~A|8h50UEdj zE1BqTTj!l;J=MbV{?zo*v+L{176QVwa=^KoUOWW(yXl)`SU^or8+OZC4m#*9P`9+Y zyi6}C5qr!*7zDk1>LhO(TNqp>iZK9O!ABKALdYwMc{r6)YNw7ZOJ$de6C8LwVoMMK zFVAC$qa)o?EQA3LZsXzCe$QQ;Jh*ODpLB$yXxekk0p(kb0Cj4q9~DbeWg^vOk9hYI8yqxHCW2N7j9S3sNX8&EU4P>hR`}pDQ05NBetCV9BbC^7Yuav^3D==J>HN z5!4&Axpr5;seH+oi-X732HK#56 z{<+h&fg@DkS-zi(hNb29{gqJuo#fV^KTo|+_GiN)r+@EHMO1BMzCApum-?=6!{ec-E# zGVWV6G`pXwGpn7Q-MMZW5UF?4#Rj$Sw{_FYtU0Dut+LgzEqM+1Zec{1mm7OKZr8C8 z(6n!E;E!(#lQF+8$A$pF#^ZN7(!eKo88+U$90mA^2X6Z!5UWkB2m##)HH100XlZE& zJUj)|0ohq6lPw}N!ShP87v1jalfMl_~q6P1mVF(nb4BN z8*V6?;OMD|s*TK{3X=h-yu>u2q3_~jG8MU&>QW5&F$cOX5CXrR94{}+ej8PT{#zQ zoVd7zl#5d3&RliuP--OjP`z}b$A@)BhG>^x2wfilUTrlK%gk;tbaU$J@+;ox$5txz8WA}bWpaw?i{-HZz#_5_BsviZI8YYD?Tcw5)42!{uv_d zaba3Mcb~U90me~m>9RXX3K=2r14$1)aH1x9`pMW*%l;34n>#wb&dFH|50eF+G=KJ% z|5p|YmHzbOSRw}NZy}ohr!OhOes^D=N#%9GJou>OJ9xkj8bdsD!Xjp{=slmduI?WQ z(=iF@dZW3*eMA;anYP>#4BDN!_f-AIl_62RW!d-duZbM3hhKVZpMDkpvahS^4qj*n!BvnH6NRyP)DyH~=;#+;Z795)Gzr zXQ>Bwa+LmgL}rrKchX{y{B}8@^Wo~=+E%U?s(=%$txsdiD8ztC(BQy3gaT{eQ)(K0 zO$|l{3J{G(5~B5ojQZ&fhCUWPHR8l3n2Pkh*4moOkLTvhbX;>0y!w&-&&Nv41y(ZuB4|Z#6mbQ3gD!f zUO@)p({T|*H^cFWrv!`b=Y6YpP+6iVJ?c=0lf2ve#pMVq8w0 z1`_KYq|$e<`8nvCnhOo817j;Q$&IGOHO7z&**?+}lRp2yW|0k1= z49Xw;-f6zi4ZQoh5`wM|_LqwL#FyuDbMb7)B8nq@#tvIBQen!!aM5IZdoN;eE$9|N3w@9X*V_j%cBhKEWuU0qog>4v&XXXycQu>)Hr zVWqG=3vf-E8dzQzQlP7zHgvjY71tPXkZdSlJG|h{3-IX){e>Z}4-O6WV}0&zBTrK~ zuW}V5qs;jxR;rql6-uF0k+{J-I0|gEP*{qfdyTL@m{p9|RgZayySh>$#OVr=9;cFX zf^tap;MUPP$kEnlDx^qi&<6t&H(jh)RYLH*msyfd5jQKf5huW5%sXKp36SE0C{n}0 zSWVtaN;||mR2BEX*Di4Mcss(UKfj(p`}{(wqrQ1e?TG%JgNq4{f2uS1ID19oeT}0& z7pPZjBWWJ|l2#6&k~4M9z!us?(5Qo1C8wsQ?`Mv57^XIk!`Nb0P#{+MU;q6J)}H4y z&1>+CV5N}S*A^q-HGDfOyZvj*q~)Wd9~{=_TP-57!4&6fGu$*2cqH(EhU=C7ZlsM; z)t@@%^0`V!@ho6p7Cjq=!Q=*|kXUFebI?AxU*W5E8TF|W387efr!rv@{ zu?<@|xH*k0FHm_FpNO61icnNsDpivg@}B~ZdAOE+Iz?sF@bw)-2FiQx-ig1ix8c2C z^!M$R6->cKFz+1ZN^O;k*oBYSF0r$6SYLHg=8@tv(fy-xNkM9oNsrS7eeAVSP>7uV zH{)$m?eik`dk6yHKDmBC?!uz8h?@!7hYlj9r4Ew{}>`T)05K; z-xb<^%8`|Xrmq6Yb@qau+|OVBB-3u5d#6V~2+dptPgLu$f-PMN6hWX{M5`XIx8T-c$(~q-Tut@qDUnP;nt646PFvHj}K(J$dCpE)ko;8mrB5ehlhw6|9-sbN< z3~}4nq$Kvtsh7-uJGOFX_U)w>&jO!PbSJLXIEsU&mGM#(oAHH9&FqWV2maJ%fxnTrCD&LhYhYu4gAIL$ zIjRx5-_RJuk8tEL{24(zJmkJIi!O6NzF$7-Q;JHiO8@J-#(;f)A|$FHh{WSO7h_s7;3c=#!s z`5-+7~C``x5P`o^ZH?Uah(mBEgQM(vElC zy45`$E528IUwjcu|9cyf4X?M@N*j85x0*#%v!RpmlDtWQ64Kny;qfO>SBRriZvI$L z&Vszj0X**?Eti#c4U`JLvI6a@p>)$Lhdvc>oFpX8b1AY3!>c=5br`P-GtFOrOn}%x z$+$Ajw%_tys+F;7@Av}t18QOnj<%B+Bo|aXPAw$`17s=Y%}nEH^3(}XH!Ku>GljD# zvw^uMbP#(Q6Qk+JSA9Qe7k&Mzx)H_>n=UJ6T~%E!v%%T>H$OPj(G@A0hn>C1QTzaG zfhp8WHpq8gjv1SOLxWf<0?MHulXbF;t8Q7<{y^- zJuAVQynH%SCpNw~m`i{)XDw_efY@ve_81zhHh89gnLRWMn|%X1BjfS)QyEaD6!#|& z47L;buO76+ra29p!)H;H<_aJWi-TT0f1FA6|9oA&pVT*M6A%aAi4w#rJOYZ_N;GA&yASLg6Mk}`#IYIQdS9;7KKIzgHr z*;__MwRxm4QU?YY@(LjIuMRr$X`=9oo6?7 zdc;D$_lJkGJQS%nAQccttU&~EM8>zO`dTT=PA*&veT)}e0G0KvJ+(7~!2i5y3<&sE z5nSF_YghJNGFDHo{uU6ma=^{bk>KL;QWg+b2pPZX)pI-MZZY#dyQG>QnH5^`&5VtQ=y z&^7foh6Ub6!T`|0dgalDv0yE+AyvP^8A^_?#(x*b5MACCTxKJ)FTA+HZpNpn*gKzi zu*eNQ+di0tmQxKuN=gO0l8oPYr;35x+nn2|ed<;!{}kfB;P-@6Jxu75ABt!BW;pU! z^uiperzB41q%{$`xDPl$9Aa{bWA^xo(T1`UgKtmy{g^)xc*3~E_0n8N{9C#B0h1Hz zUs^4Oab7AV2W1-(hB*$nJMX3ow*B&ZzxyOZ*Jt{RIEAWBOf~FRF8^vp+||Q}UOtP~ zhv=RK9r6NpIG~DwK-*hVOZ~Rp0O&i+T3Hr0s-qNUKp%4f*AQcM+vhrsYh}OtVUIV{ z!EWuu${H#&ng)S)&ycdqNCW9|FAhnr@cA3L}e0fxQH&@rTvb-8_zm20D76yVN(3aA;lF?#CAU zk76m|J!rkgJpsQ14)$_NWvsftf$axn)EAnJ3!ke~Fu;2lvZ{oIn7px)tyje54NC<1 zXn0-bd4qut81mgjF={vVC>tz2CiUB_r{SVZ22MX@im3k5^c z&>Axa107f?D+g^xTRwe##gmg(qd@2H+S{pj1GwS*%zr+y_ zz^R#qKopA;pJT7WMu4{A{pz!s6kYdr}-`liDTs_K#5=XFp#|rg*<6-toI%{&E zAfUq;ha`Kth#STZ4ITpZL146fcAz(64g4$U%O|8|uPBY{4&%7A>I#`L{+?f^=(()p zee4lFl0%WFX8Yn-{Lf#Y`mj+<8xw1mc=ANh( zz%kL>-ZZ6lOE)V=Rb2{Lma>K|zET}I%w?5$ba^nQ{O=1O zs@zZt$O3(<^O`=#x=n>9!PyY{0_{&?kjB@ggKKoPw>QI*J8;uuZkQ3$a}J5jE_iK= zZI$gqh}+4XU2a4N8k>6VDgvqEgT0HIa9a{yG=LcC->_wmq^f7T;S}S;&U1si4j`W z`n;ApR6Pmbnw#TD_)Bah!7=Gp)ygjYW?+owd1#GO&Z2veHWkiw9?HD)qR?l-3s7VD zAS>%ZqDX}YYr3IdT?RMkG6?AVx61gO?d@kG zBJNv=YfYjh&jm44vtAFE%HEt=ygRSaZH%4CcUwrD00EqW)&6tl%IZ=TRfuXC`2FSh zW9jc;EVt|w4{KhM##AeXNP`Dbo@!Hq$Rwt(k?@6X5gTowr_!;LL}W$+f5Qs~aiD>d zhb`s}Y)$hN{s;zX3!&UDHPrGiQhO`Jg?Ul+1REL1YRTz7ZXs+I7DTV@+etw1;v#t0 z2H3Q+uJ`bGWyqA9_br{Q3-a9SmW`t11+O6>c+2Mq^eXOGl!pUcOi3ZC5n$*_5cS!n z^l8wjvr%%@Xoh(pP9+J1mA6v@`ubsedt6hPOjHT%V1JZ6-nUr=T$=#^B!sJg2zLsILVC*_Zy_nR?v$hTcBtbvb+)oEwt3w6- z%ZlV^GvIol)tz)}RbAw3*@p6G6h9&XU&rrp$v@HwB>s7;@%}M^H2@Y6uHOc2SJS9> z;V!MgbHx2Qq4)3a8zL2)_2|GUFOi8d-H0{*rF;6!M_Icm%(7T{Gu%d&-Ok zEC0_`sf2n{DD+&58=CQz8Cmom3k2i?LdT@g_D~5s+*RY5TE`lz$~S4>cD5Dw3i2O_M@uEpU4otF5mnUqn5yZ zd>{y>4@wld=%0px!Iw&$Y<>4!)EYiV>(KqTOUx4_sTE^m^8Q$35YXkN;0tnWt3_$R zkY9d3+Edt=U8gKhMvwT&oJ9Abyp@|{>FYGExI)m!2FMA%PWg@fm&!Df>+g}Ud{JSW zEF`#xXx0ua4wDYZ`lR`2)i7q%pqk*AD%F?)%#QrH9ndjs^D1N+OdiT{xy>ahNI=-cFm|Mla|4zf>D$*F#+T=>IR=9rs*Z;5tw zN^5=eDrJU|V zLjD8+0DkxD{|msXKSin1MJn<-xPZPzQMj!w6~a+6lbRz<8{yske!dQh{gyChYA&c) zdl%f^3Pwx|Efvi*O(|Gr-F3AB;tY>fXkhSlC;{@L>0e*`q4nO_eR$>3;M%FYbGjNy ztA{s~^Zj!IFL-`2dp7kz^}w>(avrbFtX<)1?SO%~wC81F`{GasA-Is9zG&8Ffe_V2 z5Y4iJeY56B6MG;>7mvfj7jddv^YA=Rd~G)8eK1buhc*wA>k@@VwxRnR>O0IHOj4{gySi)nx`AFn(cw^{?{x2cduX+P$vk!__TEDaEwlRV*+-7j8$M%n zU3)&@QKhbfLXrOc%10OYz$8(0Wk}foV9dLyj_S@46G6Y?`GV4L-Lbpq`7vFj)U5aG zMLtxY&NEKX;1%uHv+{V3Kw=-WMGpVn9#56tYI}+@U+%_FX$bA(b>9y~CUPGwjg_`u zjxx6nRccIZ3rUcGmy91R zgu|^b$U$0mG6M-Omd|J(Z1?WpzjQsK7*)UoObMIhx{C zlXAuq(=awvYyu8O;u~S^~I|ZL9sJM z(0F^hY6Nn;5h{7a;C^HPoBnCsNpvQaIHzM=wokw8gDeEu$z%JTOy>3(t>p~%liJPR zS!Ur?SxRv+Pb<(jIs*+OaP0y_<^3rguFZ)LTyQ$=G+mI0n0zVwRty-oU4C>Pm$6*O zCBGcGMO_M1e(Y$D`_H#FDa#t<;Qe0}R~`>#^z|Q%GASCOkZq7Hp&=wYQI-)QOURyG z%93Rm``9B%)<{{R$)2@j8QGWY8L~|FeV>{4(XaRY{NDeb`ONb<=icu*_uO-ybHBH6 zO*pzK4b0y2STWx&DgGQZOH|XnkbMaNzm=t-NETx3;29L@CNrYc7S1iIB0?Z=QQBOH z8OC%52vpFsw8}SE)|8v(4`exLHVO^zxo4HULXz};zIgtEkc7NtEtHGoEng(Q4F)9l&0~9P+e@ zDZ7XWCV+>DHN8f5=Q1^r>f~~Ny)xaXsMc53YCg5VL+18z#*X@)hkc_6lawk);NxA! z_X7EK>%Ym5t2bD^4>=Vx4Q!oW##t*l?11@VXSV5b5n?LGKxlP28heNoPVegLzkbk2 zGPn^N@_p;J`q9&R^MuxeSZ^7VhHQ5)?4pv&f~bAHdB`8RlGOCEv8JTAUt2L(`KX%W zTdUfi%C$2f)-yLc6*Ty2DQ3{Y({Os!tJ;04<~hzs7OGA*U@Hb}7wJ^ymRmoVDV?R& zj@8O-yLoAC9E3~_N>TYrl6dF|reCP1uHy9;tbs%o!}vCz-37fp_2vk3{TQ#xC7Ry> zrs7>#%&Y7G4wpa4du^NKY@b5c-}b&m$$ng$BW+4&f7A@kOOdY23*{Y~$dukNw2vAh zia(zIMW*vH2MN@n*H3{F%4ck+fmV#2jM>e}eK$vo&i3D{okBg(&aR2b0fK6t^*>qS zt(os83#XHZALu)Qo5gmkg+C$Q;-~!9R7{Q?sdnDTV&KN2So1}fsqq}AvyWJOld&hc zY~{hvqbujS0Liv^sEo$Fv9a`W#JFHMh7+P9z}UILi0(~`yh=3MR6SK;s4Siuk|o3A z>T8Cg0)S2hKj}@10AeYa*}RC;yoW<_EO-Up1`o7dX##8Hg1nDiP&!8udZrzb!}>2o-;i$4+G4GH-Cz$?nNVg)jVwkd-=W`0=u=s#JpJqlD!2VLJLum)<=EpqKOpBX|+WdolSna}NkQ1%k|Ua-#J*6U*stonI6= z&*;ILBjyt1}vV%6X1i*QUh=3`mj}!Vvlw_=av!wcmApY4sEgiY?kl1$ZvS*CZrnyeqEv zX81{>s6CJ;HuDXv3hIi&Ep*}ljr4!A0YTWcgiaTZ@tT3zqba2Ya+2qa z4B%Nj<4d)(09fwVm|i`iZ^kkMYNK1eE%R1Af&3{09mHMHX~wd`Jg&d#x*hm=muvKg z1CzH=7qa2<^Go@aACk$m2lnK8V10c=XOkc`%ek&bA4Hw+^_l$68t-x2`Bf_UD2zXg zsO7HZSY@JSstN*&uRDkA=G%N<-{^1@cj{1=0aP zsggQE3t34|?b&n-3gqV^owDk9HATRVZrVwajARo6n!XlC0E)Y>7o-Nv-p~SOc=$>= z*YTDV*|r(QR2HIeBNVCIe;xq4Q{3LsLj#2kX0-+K@}V5#n1<#4sS@o*M)|g@vYAJ0K=u`@T zMeNyL9wS1c@Zfe^eVWu6d)k0Qc8>ungqsrL+o}S6z~aYsbyVSlGk3;?y&JD@g^m(7 z*tXl5p1(ChSzr4h5E!GIc0$)dJ2^$W{<;VTn5kdH)9M~s-j`8cNbj4IIaCy%d3o|M zcfUgTsV}fDOSf7sfA$-8DfGs0f;I_6`4K8{!XPMUNkuKl%6nvGfPo99~k$^+Gv zjOmJxWfe7-uXwSuja$l6vKW6BqoH^awi>ZIyc^H>el8luFEYF9cN7>)uJ-eKhUg@0 zZ>;Xs_H2oMm9wBDF2(){%Q|fP={K09iay$n(#ZFEyp8B-9~CiZmEV*am5KglYDAqC zAok@^)js9Q%F01*MRP?BvtZD$yA!P|tjnfz%Uf5$8ydjcVa|ljl#K9G<=q~I@HBoN+MnTezVV+Qg*Pm}@s3+<=}AiZSQ6L5oT;Q7892OEV<^EbRP z$<#LUMlHuha5z4`Q&Ft*O9Bxv{_N{V1)62D$6`nAU={-mR%GQ>Stv7EE%a$Eq9Lg< z+GRvU{+Zv12-EwQXYkY$W9U~8MnA8vG>|ORIrg7Wl zt^S^Br~c`o6KTyIthmI@1(MSa@YfS|dmBGWA~|7L5G)YH){(t3}sIvXR`dR5iVKI@z;B5q$j)%L`{&AcoQN*lz@Wlqy40ubnS z(u1^w$}*u2XJHs@;FWWIsnxs`KXeMB&8Xu*A-&{6l>=4(I2? zMsf(m$jHe4{QdyO-ezFl9hqNvu)OH|u+h?Oogneb^vas?A8H;R9!F>zmj?bC6Lsyv=a6EC>2qlB+8{jXM^IeWat?v3_S;&0w`H`yyTJ#pg zojy_dE3JN78HI~Q42f@M^E1@F3)=uuZjI~+gb@@DHwZA8Uj3AAk6hn>@C;$iVvM-= z@?7S9om9yiOTEDrB*pF58T6}~I0E9u-LN=LV)lJ0`a0JiYYaPn zzYuDwHXj~2m=0HtO^^B8T0YHpSEF3x*1(^^6`W1W*!rG6@isCb?YVhi@pJ!`;DagB z0)||T{45B&Q^|+GB2D$!GXvIFwkww4^!u^c6qbTvvLYRah1~k4r1sjXyw`Pyxc$Yw z!Dx+gnY1sD5tdxcNXM5Z@udd`D(a+1r6aVntA2jMtbUZJkNP*S5D}4=rcmn zXsZF!IQi-qD_h@yx*6>s=gFos^!0qSUBi`Kqz41>_F<=waYg<)u`t}bbG1TJ zzaIW1uGRE(zQ5mXG*<*haBwy4!ts)szxdD$_O>eVQ)WMp6mWAWNw1yZm=Vi;ey7gq z%xl&gFR}HvOStPIBk$WFrDE6#Q3fo3QpFGBh>Vnt0n*Rr?63G<#g>(MTH+~12*LfW zOwhaOC^9pdB(mEv^IO4%MrT_cchLUly*aC#*rtwKi>&C#5~(EXs5a2GR3O=xS9azl zRc^)`o1~Qs+21qv$Ynu#&t|?uD|q2>klN@7RivO{s7B|kl=u1mq^Kz%*Ye(ZC58|SQf1kPFM7}oT(qb)rX*v7rG_%}~$~V6Qt||#lxyyT>yQ_}r zvd=q{!_?Up+B=Los=tH;Bi@#pTruGfOrM4ROb;Hm*yfAtk!ki@IXQ!cN0@dsVC+ zD~r^G5OKRp7ndv8DeBNGjlEhv>#|Yr==nJs+)E&P)Io#3FvyRh{|HgRsN5CIX>Dwzy9wkXvD~gGGIKM>%-s;i?*VPms%!4<@o*&UzYi{07aEFZk}W+c}P>!ADTw ziajcFmKxRXWph)g`f_kM4Fmpd4T|J8$bhGSK;8RpZSNXfpH#c3XaO2Y!_?H2w6l31 z|7OT-gpRq;hGRKG3dY;iviL!&J4SJGVt@OHThP4 zmX5BF&jHOvarw{k^8LRNxT&R_$GjjVNKZYXiD_mTMP06z0K^FhuXOSRgP<#JJp2?b zkGDHM{KnL&cc97YQ>!MT9rm)T@SUEKK}#yj%FA|;Ypr_~)Z7jp_$TdPjoX~nfl@9F zK;6;NakDg*6jsSI0JG$PN_-DhB`nOY@XvWwq$Xtr9UX1enE-X+T)}~u1m=aRnP%Zk zKT^%aQX0$JT`SfkFN%5(Ct3md%(l><)$riJw8rtvBbRlH)cX7SxEYIhgD!fgQA&S) zJaFZxRpexEZW8?WP#x{HrEwu%qOmwdHxD2DCxnx=ghrxdyNeX&fooNUwwF2ux>eUI~hPjQX48OZyb%ExLu=& z8BRhWTxw&9)~I(+v_MYNi_`qEEE=r}hgCo(35P4xKs7{(Qu@his|Y`VM9U7^M-8ze z$)M;2+S6m=U^&APx_$}`5s+v1R-p2|HA*La9qY7IoY52%0ftY&J(PGQ?8oO+u33MwZD6&njy8D+v;;%*b5czjTT9`qjfH~>V;Vc?%n>z`H z_UC}WV+hnN&#J$`FflgKa=c!B?XdVco2re$`xGQ;5DR$4e*4lpXh_DUdl{ z0SP$I+k3~-Gh2tlps0m;lkEWBSv$lap_-7rub1*J1t5fQQB1r=uQv8F z{bHw^<2!~=oq+IY+-Dti8t=}rs! zY5s|_PQ)aNLVJVl?0=i`-+0_%l_I`|;C*x^X!(C)g5E}{!X2Tkp!>ng8>yeFCIGHV zamt{&zhiB=XwLyXfn4CTfXi%-%s*Hz7?&Kmr9_D5i2OI){~uv@T2R@~_V!25XBX28d^W8I{BOI|G!26y^dQ$*GABdp65>HAMT!2dqOl91qLT}K&R|? j%s_SW_g|bqWJ#QYV-D8ZD#c*`3jpq@>8O?{TcZC5g_%M@ literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png new file mode 100644 index 0000000000000000000000000000000000000000..3bc4465d74b0d454f377dd080dece7c24a88a283 GIT binary patch literal 28315 zcmaG|byOQqw5GIFplFfeZbgeb1%kV~ySKQfXmNKh?h>qcvEuH~AjKs(!Qm~xciz8m zPtGCPWM^k*?%eO*?|ws=l7b{EG66CI0s^YE6i5XD0Z|J9;l=V>MBq&7fU^Q-qG6ZRmh?{T;5}5{g#^S%BdeLH+c2NYZIkK z<>SMMR3ov6lIa)o=mWhlu;{;I3-#6Cw&j)~2SW1N0X&^j+6D`@TXsj}tVF(n2(5+H<63NSAmy2ui%-Kp(LS>z(_t z#%g7F47-{G7AtsrtF39Cu7C&n&PEq|3xmOy5bZoIzuerNeR%7qqjcS)sf?{5*x_-S z_b8-AnlnDXvNHBaf&9eu^=9nl!Yby|Rl-9||Fv)%A}~x!;|o97Fb5%eYhw7#zZ72g z#2^`vVbI0e&;9^zAm3}m932xgJ~EQJ&b~CVU}bl81my)MY>%{M0vFeKR;ER4Y-|J> z|FaRwaRk0gwB0PG8)~qfALva>`2dVFS>TQd{1cuAKeWE57co$n>#WrcrUQGlc%CBO z8l@2h(2`sai0gV7O}K2a%TNKBkMErC-@o6i$buM~=+l^ty{!lY&Ieo>w%wXu4)bo# zkS>u$Poq(U6UXcwPZ-6#KsYzbV7Em7(BI#GK#6v~We9!$=!8XADg3I2#xrjh=kM$$ z!M8p1Gzn`IBFf)8sZP25L0vL&rTawV_ zUxuSuQi>L$_6lJ&Jjgg%)EMTcV(ce!Va&k~PPzPRg2zb;yTevPd&{B2Mi?blTs-^_G`Gd^DFYe!;tg0|In^%~N zelRQ?02xt86+qW zlxExUl(62BlStg!9N~dhyPs^6wJL{As#_N~F9r$+u4Wu@Yb$;t45}GSiVdJ1;Ki;A z7O%5GTSGnO#RD$g;|;S*!(0YnR?O@ zT^WHfJ_nd?^OP4-i-b0M#d=Gfzc>}0U87ii%nK~#o)jsXW;+L0cDxvFGiI_-;FpA- z43b}qyscT}{gLS+1&&Q-&;J@~Q!G5=`>C}H;w)HN>gy0aKk3(0KK{`qpJG0gp??}R zf;gsfr|!||!fD(Co#|@k;=dzN5G`up2ni|>#VSGe_5~R?C4R1NWFT9Uwi{%|OuBS* z;F4-O-GybWlMybzNT;10`;zwM0sd{xNJd)Py6yQe$&X;$B=gAMh{q}i&+9{kQM4Yv zlwtQoZA16@IS_lhi@x(muESE z)w^j_bDpQS`EJp z*#RFal@ZtSeFiobrwS*Fk9xB5M13bbcBBJNOB}@i0bxv;8|fxTj4uQaMqWa?A9uzaX#WO`*SvMAd}$>kAbZ@;pnaf#iFT` z+ksx2M_e_8j+Mhq{xkbg8s07vR9^`Zm^d@LF>TKdo7lM}OD+D;O=!WPtN{%ZM(l0c zfF6_&biv$yK;$&_hC!CmMXaai2YOw{1b#Ys4}Y-e3&4dgPv@VC(H;+;KN5TP$z$r7;P+kD# z&Y^i6FD+$H`+EDomH8%%TT$Le1MznH%^6}$nRc|F{gf>(I`Iu8=lg%lRUm>o4O{LCrv-;(?B(iDxGUoE)LO?VIL-}Nk40H5m zJ9O9LV!Ql}!K}a_HkI_5SG)h0@1ZukIj8_mTx2H8RmS)IoNqOCII^I^DxHwjO)|}< z_q2&kFi)eUz?^*d$rN{L|6z(PC6b37faRKUOFT?io<7K|n~{nF4p?)u23GAavI-ql zZPyhf1ScB;15WGtg@wNh3vKoFyO&3Af8fD^D-|JrY!*IWkK}s$68d7kl#@9* zBW8SOxf3khTB%Pn?obmlRY{Q}z(N0*p{&k{6_yImk^ct3LWX}&x@qX#!otYo{Fc*? z9+Y|kES;yD$J_i8x4w8mlj|vOm`H*%UzS3#D*tzbC*ce> zQ4G;VqnPX#W8YaBrrSUwQZfjOZ3&_TXkVzIzO*YICnMM=&1jur*PzX#mSL$-xMfnW zs)6vkycUl*24X5+4rR$%>fl>_B9&5{nole**Ru4e6;TPAES(gWwU&be@c@tF65O`a z-t=?|LlU}b*isT#9?Rlyy7g;EpG9vlJo0kuzQau>VQ;D8u#HviS6aZDQeLaFb^w7uFZcz1!ZNc z$K0s_vxf49@Y1gCM!`HT{oqiPH!KrfNvvbF5)|VFYv~RWju1|qo5uaBppK3=YOeHH z?=Y2l+TfmwLS|8k|IGEq>8te~o5^iC+&C2bs&Bdc=n&C(mdxcA*bB zy}{(<;20fSQA*_X`}@A^-Y~PQtgf!E*DdcRM-!I-f<~|t>%6xx6$!Qov9JSM=vun? zmiR4juJkqS7i~4*CT+WL@nuDUsD_D|Q>Gp8{+-fc*3SLw)_CyaLJRn+`g=QP3xe+# zwOo-#p#S33!^v8jnj#xq)&c^>Nrj@K%#CzL-O6h?yBYEEGU?&fOS*U`Sa8j+$bdE< zaE@=QX-f3X2bgu0_vppc^-bsp7GY?uP?6#D{)((mBr$(X7*r=2pSZa0>j8IR6zXu& zk8JYV)G=SpSvsbyOg4=AVUp3#ajLXVwMEt6L{odSr^;$zsM2oeWU5e>Iz@LrrjK0N zSs**IKi}E;JWh&=NMj@+Ac*WQRm}};BIEPygeggdNqnfQ;~wa(O^M>})o{>cwExCZ zL@)$B`T*^L_T1)g4R`;Cpr2PlbVliW>{|Z$PcI(2a1A@XQD(`}`+Kry_G&$(bOM}= zaDW#hX<9pTc&JAO`4|SWrMq$Yx}!*N^oHt6KGZid7r4;Mff zW#iRG>BVSTJ+h+|nH{cO*Z{wyk){y+bWt24!9`P?sq*Pt3oj>Up)TU?>9rPkV%GQA zCdN`#fxen(sKDshxg7{Qp-D%jf3*RK{H>$Hz+wI|EU4Z&=+wi+m|U6czTU&t_a$X) z7oR9XiCBxv`cOx--_BU87V?mjWCo|RNLOb4DweE>n=T)@=eV~fi6pR&c9sLGOHZZ( z0O-x;b++*F$xPP7*KkRg(i%}hF58b^6?S^Ky;D^+CCmm!G^j;+tI>m%9oF!g!3Jo$ ze&eTw?TY!@jY{lbTClC#?MIe-z;nczlVbwjH}Nw{gbsg6nXLbBCR~4u0bw+e63y!i zWP}mNBdcw(#=Ixq1C`j&Z6Ed}mgXu)cN{4Z2|n`6%PZ@RubZ0#>DpF*pF;xumR^Ue ziwhzlACJq2B=bh{Tr^MCRAm45BflpI|Ziq;kc1wI$LcFPitUgKjIL{wWZ7+SG6FK) zthCffOEFDNO?Sq!OvQS#v$HP^>+%{yzViVfUh-zCRD=>|z(iU_*B_fIukVq_TP`It zK+d0WMqeDlvBb6qL@u(!-RY@Fj1^n~HCRs-b;f1yawXJ_Z6>zjfm;b3NQ+3M1ovo$ z4D)l$SgapGTQyg$rC{5nmK<*xlxYr& z|A0BkWgA1qneq);eoAk?2@3!jcfe0m?CJR#~!2uUPcOJvTAEhy3A1 zpoBv7F1os0E zJldzHi%FMn_+wBa1B&bo-PkeUs_w3iY4f11?vB}H*w6VPf>L7MSRq9CSA^GXI>gYh zyzRIT+oNAF!MiviEqjD*=qlR$W)B|jeFGbwO!_|GZmqpi{@a?_o8MCu&E?JJJKj~w zVbR@#1JkBCRrJ4K7cD0^f8u(7JAc4?i=dRR5rAQIUh-(Y8j@MQH&#F5hIPKwiGkVf zO!y%Asb_(L78awIjQPIUcMHgwo`W~2#W7@bDWO^m`8kYTD5$r5xyW0II=N3(!c_t} zF!JHL;GQl!dEyJ(tv8K&H@R?{+Sr~OX$xzpzQ5LuS-qLcvdk9f*@oTTvgefCLoNZd zm7TBd9Ct`TvPCiJ{0wjEp#k0eHP-f9c#c`imknE7N;`H?Fo9&gQ8nCY02rThgX8h+ zLY87S(qE*jlASaj((I+GzAZmV(3PPAACl-v>ghcWvrJnJR$RA7@U!JwD$P8IZXYPk z57X25`1>rz1SACxxyVuGUjPx4Ee}aV77;%AbF1&@&liXCmEAK#P5MoJLOt{56+xZz zqsM;{d>1V$V#svm#R#Rk7uRHEQJzI@zv4hYp4WwGc? zcMENNWSr^fu455gJ`+KS`LWK>qjq90NJ47p^~4##c2l+H0KSF|4WBYb6$A?_f;W*g`FhSVYn*NF7H=(;5cQWs#D5jW2O!2k5t?2oY z!gfc}*zaF3rg`NYRCZ^-7C3itEFKosA^!0iJeBF;ua@y}`3e{$&n<@VvrN;U;^hf; zqRGzDm}!~p(TPtuG-fw)x`fA=g1{`f@c`4(nWk|C8y0xnwP$!p=sU~4!isYqNMq@# zr@tO?&pC~{wYtpI?l3FEcywzMOCrwX=Sz7YG!oXY?aHw?GWxDR+`)`e&|UqoRJ|92 z&&saa?|OO51pph^d1XhJpXAnb{wk? z@@!Ig2dilDl>@+FOS))iy=!DufpE4Zj}G%vXkNFQjE9gV*5*g|rO0)U@V(f>=Mv_| zjk|43EurZ*>~~RvgDE|P-yu6Ff|3F)A?a9E-O9HS?8&iBymX#k4wR;)oTdAM0u-Sy-t#5TPPJ=fKwv;6Sw z=gN%0z*VnJ%m-zPA(;yw&znE5vNHbQbX@4tpQTW% z2mHYfby$Z(AorW&$4O|5<`|j>+}S$D7Q8T8;RP5Q=Z~yTT%o8Bp&fBjHOpX&Izd*! z_S;7sWBJ8|&@&t<{q}Z-CVsZoM9vD=qf3!tnfH+~F&{8n^RmZx2;01pI_EvBuY{q_ z=-`66)+e~WfvL}ZWq;+dw&BeZ1Bk=J`6SL!P!t3Zk8Ohg_Se*P`sJvqArKa(9^7Hi z{1oY@v8O9ySV~OirN?{|dv*T#Qgz!OFa?FzcI$YJdzzn7`hyk71#n@F!gZ(ptij_h z5yW^^lCEQh&u-9wH$x+GO>xF`6#J_HE`OshKjwpeYHFn z)Q6DCeW-?!V}U9Us#P51`_ic@Z1ZY=`)Te_b@p=7%KiIrw%(>Yjz+V2@L{hlz>lh_ zyxI@Y)=g#lyB78zfy;}c{l-p-jJ{Oy;?8`+ z@F;XmI5Q8Xevf=pQ~l+-b^+xTVns(~XY1c*GK|Z|KlfBE|9%+xe9&O5vj}L+%4Cd@g9OLC3sI#>rK4V8?vZDaT!)PQoZd~_*uN_$kB;%YM2@n}L>omh@Fl{> zD--8))vzF4b>Hy37N}S=F5KL^w)uvTogK6(UuhY;tl6;^2KgZkkxy zXWD$dos7wA{=T33?|}H;!5bSJ2M48LswCOo*C;8SMvJC51$!U-luqgYktho=R0&kY zSBTARc5FsbaxbKu1sy)HtR$~86&|YzFob)9`ie1>mogmuzRe!Xdslbmd`^;ab#ud- zgu|94B_%K2ZLfVg-jI0w-Z>A;qYGzXDW@B{JMMhi&Tx#5j#f}mcpcbf#9HEMa0&2@ zxtSigB&j*v*}-MYzD9m4m1W+b(~9jnHd1Bm#f_*=Buv31sl#RuN)bmv2H#c2vf#Y!azonX=LjiSicuoL$f!HeR*44^Qh> zh)IAK>;zzHP3az=;iIa*V-A)M8n%4%sByOa5#@)irNcWRnXYS>##4Yq_Ta1KOD03_?k%afu`2EH~V zB){=AyQcS1y50#9?!DHv>W@oENa*S5S$aWHo`MyZN9Wjf`WiFLvJWoos3?%61Wn6U zq%e=esRCl{ZM=*{^!Q`RiDc=*&-8aMbe2SZG7h)B8Y2C@pOeC@&o;Qm zLJJ^gBI&qjQ<+eb)W>&?y~0-qpXbVP^W+iq%GSq)tM)7RIx19<>J zn8p<)g*`)5m0Y@`l6pmWvREB3x<0~)Ih2e7A|)^+b4dV8`oZ^-b5G5;wHD8%9pr!7 zyQj}&^&cZ8|7La87oA2IS6wYsYYXJ z%2c-plWMESe*gYrXqdx=D6WhxuDtA~EB5RjwEHa9wUswfSe^bPY19Ua#*mp^4S%&8 ze1+M5yI+34wz+Ahs+!Pef~i>znczyQphYPjQ-CgcM?jec-ZJnDX-f?Y2Q;!~utzR_ z`Fb!{c{qG}da7yY>+0f?IEvj^U;iE*z1mL#^$P~#mp*_fYx~k-kuP5x*qwx%@kavM z^cl#?CH(AoO4@CmoSa--)c866cKCXKN(#SM2erbPy}ub4*KX97v*^txixEEkQhv&n zfuL!-!h{b)u6&M;H&51k+Hi-KjH~pTyN~`I9N2zS3I)c>W^F@&QhQ)ybU-Nv9eJKe zi0v?`Qlp%i=eX@$0a)1GBCu}?y7V~WwE*W+T55gkJuQHu-o$qvg&!!^gG&FyVp;*0 z?JTHmYmX`Y2L>kU`}agVU%wFgx8PuQ8O5R_J6Bb6v%5qgen}!a^@!vSJ~KbN;S=Cp zL222xwW&?I{QLVig6_*~7Nq9q+z#go)Jq^kTuj_PetGt0^RQ=T((Q*vGg11eb8io` zeb=j&mrKX1JLkkgKB>pNtU^NB)sz>&QayaVtXdyp1bT}wt2*=A?$4DzLmA)DLDiDu z_fa$pJaK0eF)<;8{o`YI@L_h6MFZy_AM+_xmLJ;}d!#;P4=Shh4zu>ekXxUQhr6qt zieQV4K+(_RMYcu3z!;VN)3vKkd!CYQ+?6&yooiz`IK)eczXTSio!~H61B>Fa$K7U3 zNG~8N%gEW0C@mC^U22MI`#Zi%Cf<=$E%rAX-e$~_{*d1_ zfFOVZwY8Thv*%{Qa9Z4GL#!`dJUQtBG2GdvgrKA9>gaf_9$zj$EHQ3Qnq)iCIbQ~s zAHFu^Tv%Nah6p=vVOW?wz0F{mAz`clT70HGqKtjmr`YZ74<**oRN$=o{8q-q!wkDG z`ve$hSL8oQPid}R?{7E?R)IlrRHgFqY{DMYCv!^2HzRHiFJHbymlOU9ggE6Sk{nJ> z>Ks*J?kjULcXSd!gk${PL86Q)7MBE@pp66xZ1%6JwW^^}CC;Ah#;W*zQ;fsvO4~#G z*i}6`-GqD@wY0syetQ7f$f$XhyrJ77-7n|R|I-2xhM&Q<>{9GBugq?BcqvyKHSAH5 zKLdnIl#6Km!mpFqRj|zD6|>WQH}-veCog^{Nna3Sr}N>$l^ZN?i{Ugm*ez+jD#hJA zrV0`24`gFExCAmP%VSyYp6%@lmK!r_(G6banEWIg=(MAj&e}lF#*$6yYC@JIl?jj#R3{9QxDBIb20Cop%!^K9FJ5gX~ugUU0rHv$f8{ssM`Z$YM=42c_x3f8{TK1bGILNA;!TVujpc^C=4R5 z_6W6daQH+JWo3|WSFakV=ps;Sfz0Lu`TF>~?Mj-ZJmrj60a`7kjBSsh5;cNN@%F`U zJr7m64#rLN0q$*GXJVvfRePZFBY4~)tBr0-dPEZQBRFT&V#6JWFbIVG{&mW{S}3vb z(&tq?qnBOU)_e~bmrwAHxiNUy(LvqR#Yqawa?=texG5JL<}{&z`Z&eksg_GomY>Ba zCy*5TDE@EW@b6iKu0T}wpD>9>h9R`>^pF4BjgYye@Ad<~J8Y54@_iH==8R&I)?;*a zCC$@tggqbkvilM-fh=Q<<)|BFLNOs-C5>iKTH|rmk+v?#{$}os8ot z7XwHREeeR?TO-}wNK=SR>=n#>+}yNp1E_`r`q*g0NqMrC`ZrAl-cpy29>8X+LMJTN z8#P;*g}(U{H+d5Qh5^)Pu8UPG-lm;nDNq~r@WWnPpIL4m3*2Op`W^i^UOBH~hPn9n zPaj2J9qkG)gO~Z6>{XlOT@*1UD>&|&tNp4rlA*+p@D&;vsvA2VZga-wG6 zT;@|RlIB1WlZ8#c8~bXiu_-?+ zu))3@M5Q=@ih>HfbXOLqPTh(5!7X*?urcqao_6=A2k7%m3IpBat>Pz|CkEa$xHUo; z<%AQDJPIjYy~BNZCk4A8tcDorK1y^KmzR5h2qyIpy*TgY)rUzSc@9d{HvOHIm2T2% zceQg%XL_YDaMs!K;FdB>J$%+^zr3`x6dI~;OuAeR6TUo(6FBekcIn~2lJPb z=jR?ikW6|)Cq}H$-Mk%IOYk|ho349sH&6hwyUc!;n3!oOvH`HzobO!U);9juQ*?#l z2zKUnKs%SJu;GESYT1T%XZ@ zY3!C4SN0r0jQe{A*^#dYr2uKD*g^eaJRTc4*uugBe!Qv(0!qzsQbD2HjLH6m)D+>1 zcBb$oHVdIYl0kBG*dru(Wo7$rtzjjuMe;2xTo7<-D0WU>`;zi`#3=7@LG8w8*Bmd~ zgYsAnWO6`3efY z$*db;zj@HrD_DV#*n--pzT~*n8oqEqOIF7a8|=f(YH1khK#X*Z*Y0(>-%kp*t6Nl4 zhczt{BuJyg#aVZo1jag<8#Cf=Bm|G0hJ@4>o%&-^qzkiFk9KF8Pw9evA}+srjeGMy zR^?yzS5^u;K;eYTOHXa>H+>dxNdX3(9~JpeibaSw0Qa`oSRWPor@tS?&`Jm!841xp zEe#)@VQpnKAsi4Is`n1B)q-5H3m9a`GSW~p5LUu?ExY&W0PwQ;-YBn@63oKIT~|MR z6!CNRfX<_HH^Z?*8uU|%4jcL5&URkMzOhPa_ir*&%Z>#D`P(qyG#7W%K7r-6+4>>j zMw~q+uE(PGt_IZFF&zer_xQ9<@U2$TE9U~};vqU%JGz=c06tcmCA=u@i7UI=HXPu7H*f29`3}SJ{+c061W7ANu(Cn~EO2ZQyH+UJ9ETJ((ydF)6rKi!m*d zgPT9Jq_lKzn-pr+>ZMXeHkmA)Hb>fIL5pf$Nnl24qz_LaBZ%7fV}~6#)(whMIBDwx ziEZ4B^5}H?|MCi*Zj_%bjEprEvCzx8wKb;Vgye%fy$+loyu*P9 z??fqNXcFRQhB|$AvPi81jjgT2s@(?AuB6D#3n5}?na_#&^|%vY+gN$ z{vyz0gj*CYcCh<`u)P>S{PdP-DeFw^MFiOY*yIqDOaV68oLeC}^2C-2;CmO6j#^*7 zfU0LI@DqK2_yDv4-JZz>u-bqF$k+Wk!ESCEVE511=3~d>jEQo53BE`i%@?UwuOZPwV&ST z>XwgyeBz_7VOO$B>MI~{Q8EoVvy;#7 z+r>fn1VG~uZt$bOl`A>7x1LqEEA~fB#4j*jfKdNt>`wO8%_f}GQgf@Yg5j!hfDQBV zO<-{KoG$UwH*!pUpa_8)zrdWEO-Uj&GUSP)=f~2zF1(q;$B)BLVoEOsit)Yr3|9eI zNK;c@W_vnm`@@+24Zw5qyRY;;UR(-J%wK(<&%pmmxK5;_?feg@^lk|61@(3adWz05 zt?UGL1BEEt7)P?_)j(y>lxS((fk@BLd$YamWU%yDPkAn#b-p5_l&J35TWt=$J~5`S z;ZF#29!dzVZ`*j^X(O}i4!p| z3dq##HZs1rf6*i^+{&33(5#XKlAuaHa_PldchPtnv$RmOn+LmlZdTSWAZv=_O*410 zSZAeyY>09_yQNT$BDZ!bJBs$m$va-Id!Qgda=%9A{oR3!gGj?;1_w7R=;FuwwT&47 z35Mv!2}fEm$uUpAl}Z1X7L^zaprGG82%wzfNad%nSdyAa=rL26EGIj>wV!`q>A?GQ zR(qE~yTLfaMReb{stG2iYY5J95gpV1SM{>{h7$IXq)P!$NxwXWph`syFTK=p*xp_bw+!16ECHTV4- zAZb+2=S;aIxZ^Vhx)NM1NcjZ0fNo1DOI#I3N(+ z!0Tnjd7jjluo<#p(K(IVv076^Ow7@dkqM_+4$F6mg6-TybF0eYEzDR@Gjhxu^qZSo zQP$Ki>ydL{I8*{&iCY`X#2+#6RzbJ43(-O3ACGl%JRm{c>R>YG-QwWxdrs>V7uuw zAg?sFw+Gdigthxn3a^+X)K%8oXvJHn;GS@L@~y8Vk#-GyjivV-NkMm9S#&l%7JGW! z@iORqfIqpQ8*Zewy9JoK8hMJ{x&G(Oak4FGB_%?4Wn@t>A2QPL^%bo> zRh9Z(f8Gr2vD7ZF8%AFUo_z1$Ij=Af8gFFb?kURG5_*BqK)#rs{WNPel7TFUrN~)G zyulDbgi9JFc_dxtPBqIP9}#$JdmMo|_%L_68*_Z@;|z|S>h8RmPMJb{xJU`o^y`{C z>6o>~K_3}^8a!TPSb ztdwJFvSkt*{jRp5-Ph#qa&dca4i1NxlW-EDS!>9g98jU7qn`&7KG#7T$nTBv_Ly1^ ziW~n7b8Ss}Y>aDEWido+XOTX??43nh$e9f43_PeVd%ZOrd&v9su6!8R9efKA}(^XpCOj7Mi6wxJ_>}AuZ<(yY&Z6A0An?|v4r!;gt z*c!L$r*D4Fa+zYPQ1xn|*q9>)igbKv;-b1967A540pc)7yQlX-!yLeJA2tN?is#3{ z;p(V7BmYduu-WPh6f*(<_u82FRkxsg&$2wkU0yh0>T25V{Gu0rAn4rwcnq#+p9fTh zW>@x!5-)POI657gR%iz_|@r^8I2FsTLTzx^dx&emB< zsVOnju8=@xYa1wCj#6!c#CooG;H}&?H_h24Ony=#)}NkPr1wih@zbWGNMDZ2XKmd` zl1sZiJWWC77_(!1USO$fDfy#2&UV^Zdx~7|&C62gEnC*#H5L3)vplSX9oyoG`+W1u z4h0~0j*341gj5KPMTp37DTR!o9cmm zmDV5jT}C=UPEMOhEV&H?Pi&MwC)An$kt!Ymy4C2{-Pl8zw zO2U7kjy1#RL(9^A8T8aTdc10&Bj_MYu3b$E<>7I~qHmV{=qAmZ#u(27*DHnP&qZ~o zedm?sX&@=fAebRUI01t~blE*~lsnzsKr#DX*45fDK*bD2r}sePuAp!)K(K{>aJ3xy zOg~Sg6~bD}aC#^^4q0B*>|!Fb93Dx}V&hf)Dqn>%de!z#c*{`x*E$28)4eGo0_)HE ztnHZ6GyF-ejEz7Bm|U@*wNCUW+b>o&wloyt${ni@5^g-F3 z?4&&GV__I$qKjp^u|R|fxqKt9EX2B5@Q>(yA2$*D&-tbf1<<(96+YZtS-XS~+hQkA z!5`a9_MPxyTZLc=&XX6<&X8z=U3=EX>Ia1H@0ig3WRfn%GwuE2#= z_1gAoV4w@714#Utg^!rpKPnt%N2@a8;6)jRb~JfF!R~N-VZSF7$W6q0aBMeXqn>_Z zFFxQ3A=i(hM4zgYT16Qb&#z88)rB>TpA^SLH3(f;M22?w*d85vi0#bMjH`t+<>9HV z|Gj)Y-cZ!oJc22c;4!*%k{u;^7&5?1x4G~)!|iBdtwffeKDADj#!Y|=fS0exSjw!) z`G$$c^aCdfq(a(OW^cZK`u*IE%rEDPlCy$?yRgBNz_5@jd(m_sAwx?`%c*p)tt!%B z9g4~2c;MA&9YIZ_XH(a9M+h&h9Q?t|bcESAZ?<%{rHznmY+uIr$qY5Cur!sNB`pkesH$a+3 z;hER-bnqduA(8d#L9!c?pmnk+#L;7zR(GT(v4#TdiGZN~VKp5B#oFw|(S1~?U#;nF zNvQuDms3NXNH2cd5%^#%K6CQe8)IOd=E{XNN#6O?E_OQp$O^xRh{JmlXmL>t2z~T% zl)VC-tv+u39enx}I-i0PiJSf;GxLq|Jgxaet>V%Vv{xbaXsaxx_O)if8z`MJ-d)Sk z{9d4ojX`O^Yhd}_Fke)Nl!>uDOY%H{m%iXs(iRRbNifVU`GMSIu@`#OhsQr@vF2-B;cX(NnFwP zZLQ~?-K5@64IOH#D7^cOEF2pOli|Iey(XJw%DdjWF|^>$6jLz3G)K7%9}=Bo%Rfk@ zCr7&ayC7RWKT}7NW*0pjy|Tkrez@xQ&)&_{)HY%E`tBt{Nx;BL5VZ{48ik2P9wh`< zg&88ROEh2E#nSsPi-F-Ec(PRf=6%bY7gwJ03Cz!A=@Lvh33oU zyB1DA-T}oDpi)>X3}^_!XMbWK^9q|pXlzS^-IK)<*7+$|OK7A*6~f8EFie93IW`7e zHdXxz{NHwov?kX6f1m1Y`qO$n>MuZt^AiXs7P?1YSMs zMNb@;`_Z4GCmP^$%**eEE-3Ft=GC!E`0l>3 z1F8}x()x*%(9jv*vOuD#chW)(Z(3eHiaoAuJPT#_f;I)WfSoD8IhW*m@1J{Cx)v^Y ziNHoFNy&2qWS-?8St;&BhpzfoW86fW*WCBrzAQxfrZ5(V&Cm&r+=~%>&&ZqF1J~Iq zpxShRK1-HRk;9~ouZSGM$KGSDWIQz9S8$1RM46U2J@@?!h(0c;B5paY zvC+`wZS{{WcqbMKN!G)uWu75w|C8NcFZ1$qXAso?OS+j%aTcXUqtWL*1<4}?u6FBM zP;h-z(5u3EgMu1^`6~VA?EuRrArG<>(K+4i#$i-I{xyxugHM(hmq6K`$c^I3UD~3! zl>#R|8f*6=H+*%b9$AH%;yfS?f>(2#ijW(!DSvzlG5mELY#EaC)A{y|TGR=D=Q;na z>6Qj5FS3$uINy#I`x}=Rq^@Rk_O=X&TV7pO-hWQ|?T3Ef z(t23`7**YQdOJ72_3j1*e2wHLaN0>_@aq_fBA#~hO~=#kH?6{NuR_j)wT%G@&|(xb z7!OlBgq_lQ_~!2ioAcGs`;Es=@;vavKh44>Leq$dTS*M%xf{c?!A%B3@8D2iw+okF zgR-|K=R4nFZ#0n?E#Yl9_JPi-um9fgO zotzVRSt)aFlF#HonODPrWfRVmkLJ!g?XGIh_|}@Ye!+gDUYQ$^Unzp&g_gQPR@$DK zpSyhb&ke6>Fp0f)7J%y1-tm~@MX56GN}o_|WLb-;60EGbTW!?0Cqu8+QinQo7u%J> z;VrvK%^{~%7!<_N{mRDn$yv_h6Asvq`&U?Oz@8_zgvvRY< zy9o$%+tv#KTB3hX?xphBgQ#oDg83WSn)9mGj;ndF*l@M#8flndSoo)pw(`K|H0c36)@Ko$ld5v!B25^5>|#Aao_(@s%v$qH3vk>J96H%ixZ7b4|;` z-qN*Gt>t;Y>Kj5wMsb25@3wXK@#gr-y)_nzzVf+(Oohe*T|*2?@A$nC4$Q)^nbvsS z4w&9jN+_I$cw;V=g+5w~5Ulfvt_5_*gbd>?53pr1G_(XJN2th8;S`&H<-wwh_}SfM z%$e_lBaqzi$yU_Ocn>jT#SSF}EJB`Ckaur#ceK5d&DWO|+hDv&SN!-NKd#Xah(?=d zxb4@LG+Chk!L>zDVh`v71QWnvMulZB7e{n8m z(!5!;V8a&N%-tE&&n0whgZjCpj-jEr(Fay5b#gtHQ-hh>#jm0}u=^XdB#2#B1BFGxd&shZ+G;b{_IDBqUQKrS0|d zY#Dy5EdsVmoI3K{-L?w=!ro?Jmy&W%2Pd%IJeOwcuT${)Y+bNn=qQ-iCI?b6BhE?T zPOSp3=dr-SGRtUS6e2M6VT9L(Zdi!P7KmIAZQchleoz*p%5o|UqqEPysRrQ*6FRoU z4k}Y13ldo}9Hgn4dOb4O*hx-#R*r}a_-Vl|KC=8c+xpIT!~9|(ejM0w{0Ex@@|BfT zD51X-U*E%4_2h4}^On4bC_wbVJ_*oKQCtc0Ej@KxcN)JV9nkCK7R&9E+^B`oH~Ly_ z9tF8-SlxKPS#G==31m{>gvM)q{MH;=BCTb@`-!UL5~=n=mtp zPlyf920LCEZPhSY3TKhE!DQ}%YZrR zBTt0|l~33^2l?p}D9Q{@w`BPx1Qx&X8WSOl+dy^1!==K}kO z`O2S+0!%56kcpr~Rpiy<42|NobmzPS<;Ef!gzx)=goLIjhi=C!m05g{e*1?V-v~|1 zDbbcw$biPQLV|TIi6%KR3<({FU8HZ8#4sx+9YzHSrH7A&5;OPWdlgmT>5iqrrUoB_$5nx;w*(Qhn4hhLr$F!@% zEr*QE479c_w8pfz)Y(PrP;O&BWwmm=H;s%R23?cb8z zWLgh%7?8x^$fWNNpm}dhJI!V?j?DL^CpgJ?ZrN6!0K0=uc@+2o{99-T_<8eV%+cq6 zm$0PqKXtu%Jd|JjH$1JhiLBYlZc@r_kUjerBBLxL`p6B(t@B8|1X0GL2=X}=p`F!5<5tVD6fVpD$9&T3Yqxy8=AI;R2 zB?wGG78#~6{(-8Ecq_;>NnT^qPYN$Ye>KErKBQZaH4NlS^b@>Pc*_&fu`SEeD7gdh zjY-gK@lVK{rda#p31ImNupaCjm^6#NLfiF;Zb}U$!QnsK)$tPz?L97e6P@q1_h1is#w2B zhV!E&%e)!eO=}CEN^sVnq6T|>Mx*qDeV8mWTq7&a4NTDs1#Rg&GoAj}44>L76rrL{zyF-hplkk^a^vp!mIO)Mwx58wj zRW`HzHRuPj6zc=y7p-94Xp`ZWJ;=O|wLw#<_9iJ4G{U@)GFangw0}_Uuuy4eSrHS< z`=|M+Srnh~^Ystq3t&3YR$0#}NcZY^E+rUTWFt>*WX6J;G>}$u7Zvn(C>B`-S18 z<7+Z7!;O_3CzpxYBg&^Qo99i2X7XG@&wR_QSJXNO#;|$j@DAyzYlW^c#mqzow@0~= zbA$sWfU-a0624*dN0Q@S)w|mkd%T$q25+>dH;FX1*RIQ*xu{9U$p5A!@3D>I$Oah< z_EGGW@8@gtRs|yeUrH6Q%zsNmdhuQihAe6<+j>UV=++evGQ8xTXtJ*Q_MJin_lO>Cqc$E26oUbT++z&yZaswJ6Y9Zj!A4hE?!x3dFpFh(6-x)N^KL1nKD z8N`6z-d;yslgf1;1)F`dMB&Aq2W){_;Dd%}#rU%-rmzKp{8>;l3d?_5KTNwwyNLF| zxOn};5uKE>mkh29OQtGnOJ&R1LfvLB_F78<3+3u%lgaHPYAdUPlv(sea75a zX&`D1T_$_f)CWIqqd~|$9gb9uN7{ImzBm!!J-v>SfzABlK1lFkGaPD3f|Q2oc7?H{ zg4_R%|2%873m&6=sF!~ZdfJ_s8H&RUts-3gL#Wice$x zY@<(}8U2@hJ}^_Co?A$~*V)44LG4wrhxB61)?#Ikb3L7Q47tGdu+0}b_@oR*yD_0* zh~ET8$}A3denR9+$J{j({mw;VyaXu^vcNr6>k<7cMo7l^QcJXKte8}_+8-c`UV-U^ zsmDK)sMR~X<7ZmJgN@A%f=;3`()vLLp~DGa*Zwf0rwiKPO2mId{S<8dFm(T}M>!qD zP{Wt^`ZdpCMqeMemn3wru-VleUHY3vuW?ME`x_P?cb!qS?{TCEw7+z3;Nn#>ajaWB zG`0g|5u`?fpp|h?aRyVWmHU18r{Kre|7!r+)6?uuw#0nNBy6}S6C{=7DzAf?CME1& z+jC9r|2TkT+t{zUI@n%jn3+OBEKYnG)U(4P?%ZMKdL|N;+{kDr0L}PXp%O74{!}cg zyR&NOz5%-2rg9!o@7!Yr9jeo1ZN3&GW*@J21dc+W0M-L-Cc6hx0>paNdOVNIQ|KLN z&^#rQTG$gA<8Kv;YJGSAC48>^M(^ zpDXpY)J@*%>cx?Uac5*!I(J$`0f9bS_-*LrzTMQDmg??jGDI!{HT0Hysuy2Z_vt_j zv{tVwd0^L!>#(w5;4obgssXm1Yx+TZim#J=mJOhnVG+RbNcs|05Opd>=Yjzh5gO{P zgJt*j-7E+@%J0zk5H6y5eh-&fj~0VW4lFd324x;-D~c-lo3rsD>6RKOV+Pi@T^mnZ z61B%GJIp5VI(CMR2{K%|a>FK(y~ZraFrkI3LsZZhD5?0LJsZerY|7$>f4IFnlqdm> z!e79`REXh2w+RdKDKb86*|M1D|NZ*uW81H`MZ71IQ2y24`l~YN4$#dVnN7vYLj+7= z|CDJ+qq?~~kWeic*bTamhVw0;6|Yl3FCyqMG;mEUewsPY82L3bWHxmHcplh~;_taL z;FnEDJ_BlKwaUV9QuRl#sLd`Qi-ul;H-gC+u^@GjRj*I(Y6R{&cGG5|Sx6m>1J*^S zrS!Y|;dN5x1ABT0+W$`J9(1o1cm6`HcQ_ygsV__hx7Q+0OA_SOy zwY`S$#Jdam??cwpw$*uiR#M|xp!K{{WoNALBQ_V9AU8mgbA$J8;Tj+n8A9d}5YRJI z?tguW?AB9N0$q|QWJEx_+Tkf`U|(TBcmZ1ukZ}*Pzi>TaJLul`#)ke|PIn5)rau6o zn~S)Iyb?E2LdX}q49P=HHuXC{Be4gce|`b?)-@g*AK!c-VEMHl z_EVG3LT~%Ob8~HW_X3HbQ66B!(m^uk6vL$!n4kOJ(*&x{{XblQ##jBXm9f7)v`JMB z&C>sk5=^&7b12<%jC2E3lKu~4*bfd+rNI_-GP(a$1 zUSi|F*IV9h7Pt$L8mRN)S+Mola`qGerzPW9AAXGnv%_tP*2}Amop|w|UyH?~CeKse zhV)Z66SyT$D?H}w(DuEXkUqzE%{%^>cwq{;QNCB5#KC~Kc5P!P{_xBLRR?-VuxToO zW*lA{8u;()e>=d-7RZZ2_7{o}c%(@+cnqv4oqyKoac7Gfp%_(7MY zSQ46E&Oc@nr$nJ>`^k@Fv|bzf`AInTpRl~pJ5S1d&r@_0S~$fBdPI3>ChjEuVy9P5 zVq#4jWJB5@cv>By@uEKR`P{vx`PHVKxd(Gd5UQCQ-XC2rC+eS z>!U|QT=nLRwY9TT%Nxw(%hfONMl{#fO326@E;TGqHiB1w8xa*HBqX%(xakg{a&r0s zQ1EY4-k;A)F9}c_@rFd@vK|ea|Hgo= z2&f~KmXcD)_!h+?t)%DCFwt$T57_i}Ba}GDkjYPNYyf#&JfQjuV)yX!no3SxURb?( zewLZy4S|Gim|*i;ITa}M{uB^Hb|NStt{GpvdGn@SioY1mf~_4#rZ+{gc&XR8Y}Rf>cr*R_B6oE+|k3D)S&xA__JmsN&F?`JnPNZ*m0nwl!bE_8K~2MRet zMjJ*o@axx;r%&^WTWO;@6WW#Yh8D_3&&ul>CanEyEbUVO+WD?KyWJ96$_eMkreTE( z3LB#Q>@txXFJF+X2hvsu*V^F7o%j-5{x*?rn7^l=f_wbZA>Fnf1 zRJr%oR>$W(l4ZPSCLdts9UqdPHJJagp>UfvTz2Q1yga3Oz%J^DVdNf|zmb2D43Db8jXFTLDIEpL0CTp_Eho$($r zjQ97l|4!`4KkYm<52=Q+v0S<9ZgplSC9rmE-74NHWs^y^B0ZJhhCu2otD7bkFtc=Y zot?alEL-PWzfVjwl}iu6EC!umBfZQNox@SZN|-MFUW;mU?ZkXednjYM^uGh)j`e7w zvR*L;gZb5~8QlJT))_axsDXV>n(d27EX{#~ztziV~LAiN!frb;G%VitL}$WoUq-IcbD9bWYpgPR_&t2NvFXJ%%At2${EU$ogUW6{)3A4p z$QL*~UYvO3!rVE^yOM|9`#C7{;S9G)Y%t?DMfHf+#}Y^^EG$>DT;1I{b3XLXsq?#WI*rfPW=6kl@)Aw2h8OZ( zs58X{t)<1p}^1zx$p{&XNTL z)tBt5UOpd;#m4J*yq~d7&YtfS(g_iK!`@i*%!~2ti$J6arjIA@P z_Fv)+CDN(d{!=bSTDHB66A)jiNBr>E_Mvt4ntya?2qliVV)tMUhf zaC%=@MNx^A$Fx;O!&R6R7Ot^WBJw(f($KKo&2OpVjbJP)DPCWFUMdP@f^%BDLKZyz z1i|Ve_G(cQHUBZm4kN`SryOk)q`^ zzG_B5o4wp6Yk+Vy2irSIj+4(-nLE?wMx&5_g1Q(glUyzRVS^oqcn8_>fCPPPi31@) zK|sC(H@W0+QTk=zTi89-R~EJ=m|{3TckHh)tYdN+4MUDtz^#Yz_S$^&iqC^J+r##mI`-tPI@mD2!;FO&Bczu%|1_Oeq z%g$Pfje%pcuDS_ES;;4@#@OTsnnhV}-RT`ypU42BKaR_em5PdOSHt=&m4DE6?1~<+ zhTrT|m^cj*a%h#SWQ`_qi%m^UJdBC>9HK;@e8ckiB_8}8PIqJ?y^U@0{-G?DvfiJ4 zu#2Y(LD5g_& zBjgC@VjYUnW#-a)m>E#&9Js%=7~RvdJuP)d?cH+o{*qVAK8shnI{y_tq+x=vLKt5d z7z>1+MPW%&S_U}}(om+POl+ua`NQ71XI8!Y`nRLXe1%;#7+(QE z-KHiP{+Y>1bB42O?<8=a`BUhX_ivP;PGn_?UX&{=(@e-1j2Yp5)QA<}6u?)oywvjP ze4LV5_O{9M$muKxm0j^}&|}#YZI({4*C8|t>PP}pxZo2!Bnf(^4oHFmxkf<+c6Qyz z1Y>A;-D*cr)l_2b=H7;U6oT|i2#Sv%P`lxldJJF?jnq% zIF=9#6T__4os}7lrNSSkEh$dSA&c&1byLmW+rdg)Ie+4FHdl3`0Do>NpE_>$)Ceb} z;}4Q^8_mDroI2ew_#Dc%3b<8-(>T+sC(@G=6ym2#)mpa>bA>#Z=Kw#!&rfb2%uBsM zJ^rdU^XuvP`T6N-i*>3I2uSdtSw3(Fy{yx&JA0d?6mb`K_-c$fwPT-gz3Wo%c?$g2 zx%5@A+!SwuTkko5m0sTW^Y*_RMLzz9{eWCw{hLqAW@|fKCLdZXt@r7mbRUoJp9O0TFi=S~8uy4o?2L2pj6$hvBEnAT>#{mJd zl!!mJh{3;(Ypa_oOh@pRY^(sVzPlaoBXhRP{Gm0g;u#;4$t+T`GZQIX zenn~OAp2IKImu%%;L1N3h{fvh>xVYMx+Ua9iCi?+&3RRn*JQmllE%+?@WtcrKi?8Z z)*ENsM-d77xPH-)MF`?ky>8XU{%`ZSUzcfeZU@8CIj5TG(#To8!H;#j%{E#e8LirG zXQTfzS}}KCk5swJimyuV`&kj*Wt#fe^c`eUwWCiCnSNs0_YM_KXTOGwZjB}trCd?&A@l?m>%D53Hm6?D zZfP>K=@Pg$_G>b$czw4lnBdwbCvCRQxo5cj}^UD1j2t67M+zmVPHh2Xb;kTOk!hZkx^MzsX4|D$lLVRv4*^zj)d7s1? zMPw)EiMvp|ubmUG(xTQ=+H$m~=`aFe10Hx1p)`eL%4B~1K54@gPA5+(a=aiTe(<$V zQoB0WWc}-`sY9QE%J>^06HNQ!d?tnQPStG{a@YiS*T~lR^CzoZ;&QUTn%|M)ew1)-i37d@)CkBicqh))3+Ygz zm}5Ysb=~5!MMWGMty7h~8bT(!p1ZEh=nR+~YUc|%tG({BY-`(RJpHPuhBJR+%7VFiQYabA-wbt6q>?M|Y~dvn>v0w>1ngt3jH)lwhVv&_{?5 zRlv2Uwu?B~gCv<=QR&S$vH5Gnj>;p*laOJ98()pm`-^`oWv5 z`KR-?yHbj6M+%cz272rH8W}s@581cpU5o0pYUclActpPQki0GWMJftba$SflQdn7! znN?0I#{mYT;D`PrfOU-_gDCNNIwtfxoR$kgXwal-mY$yZDPwC6IwjX;G+5t85O?~> zb5Jh0;G0lL;bmwz<71wj3mlCO8I3~k-1@ZZLqavXoAdir(z~0H!U)*tWyLXEq;T5= zbUxv_mG@~4YQ2Eu^M>ed$9<|~Pz8H5Q2eIM=`ZQbi>2?TE|Z*`oVT>vr>AEp*3ZtP zwqK0~ZuM#m+JxjF>6@3MPmR9}1HQq*%AW7)gk5p^eMwWc-XG3o(>A5sf|-b@V?9ix z*zsw61sC4FMYjlfVDQU85d_H-In}c(4%+FwoN2cV)OK5u!+XK<^)2Ze`+x^%eN;N_ z^|YqCxkQ&&OrRV!WHuX;W!0iS&)OIoCYq?e*Dz70qCyo8%~n?SQ~)i!PVqDJlh@M^ zZDJW9D_l|^jF;ve7mox8#^UmF;O$E~Iy&LO!R}%ynmj4}Un`uX0bNqbRPpI`M2n{U zg>(u5APYjpqHIYG!txu#l}}C8@#{j9=RC?EO62A7CXOd~=whTUPxT=qsFs)o+MNUt) z!$+O=7bk_%Erk{7I`M(~HCrr|vh$}sA#`xUkbuUZ6v!#sJn3iJQ#0jGcTPUPWRN+W zwD}%h`RGJgZN8MqELcPccktzuc=Cnx%l`43`7%SoV!x@@KQi7;zYhELSi|77nBEuu zF2dr`_w+6_GA+T%1VfoABc9t-LFoy#xTG3kawvnOc_W4Odv0I8B^xU4FzUAzfDj&H zpjIxI9KYi0;jw{Zab&^h!0ve^pmzU_R!+N00QTiUJ0#)r^a?PM&2wZH-()k&7F8WP zkTl9^bH@jBa=dZfmgPG~qjxPdlXJt{GYKSr*H%tH{gdSbsSZ+HYmiF~gP*Z1f8Rf6 zN}93XT^K67>Ri617XemEGKyMxz*XYk_P!f)r<>pMq>StlrROr|N*1DOHYYnXXyV(wd%i79E+gOQ!wYhmHI`&pBJSRmKwPbIY_ zj}mg`d~w8$w%aTI#hXuV|Ee!;nqB7oZEiG<^KD8aN(Av;Rv@^A=3@n}%GVkgZ=I|F z$U)FZS|5u?bk~VKX~cS;G!6b+b=j?M%;Pv?HYxugTIE*d3@4M0ze576h<=C z9*LxS1#*JVqg~{k?~FL7^+~(LFUwbh?vZo6@^I{|fTL1d+}UtvAYtatsd9Y8KO;fW znK9?1K+gYVX0}Hc3W@O9y#3A7?0$o0lvFdyZmUtwE6_iTd~68gOjL+R6~y<1w-xCq z3G`(0t>Kw9A7XNZdHUsC@5?ODOvI=7=+%}8-lx3IDux(j#6kPu6FKpBlu(8jIGn~g zt-LEP&wclhk{Lfxz0>i>r}-g#=MhJUa4uX!(faZQ{>WX|-)(up1?p^MmljTyQ0ElY zmz;|Qezsa)K+Aw1^)45OYI(jXa9PpWgix&?W>tY4ce1sK!6kC6@l2RtMA>Sb#-VI3 zPJ};v?V|D0=jazL{=kW3@@1OqkY8)7xQTa-tSz||%swJv8+2pEpZ|VwF#lI%v`fT= zpeJ{d;+0!VzoU^3si=7ygOfDHOfeBLt>fSn!5`-S>5+?Zf-b;ZQkkqG*pM-=HUM3S zPnvX8rSp?_B16?e;o+0RRB_$b>%$Px|FNM0KG!!Wn*KTYVcbAtqfv} ziT(ThqN(iw*(x{ z=I;rpVP#|UO*5uZe#eD# zBACu8r{xytV`{&^8v&=R%Vdz?NrWH}W+|02W0G6#$;^BCGaMhU55n3_M0A5Nl2GlG z60A$kk<+_=&{w}Re4m4i6=a~*!-j@-#p?+1jun5aUO(Bn2`wFM?Y7%AK~d2<&zs6h zNV78kWk@9z@O6YShW6acc=y{3jozz4p>X{3-L)B4iAMi@Pd%Cs)^^Ej@p@@1-7b_0 zKhP8A$4?@r6L$P8z!F*3nE@kM0r#Jpdl8WtdjA2+gl5Kl7rQIr$OcWTbNNGnYMGZl z9rvU>YepZXlEtM)K|uk>hY=r=3o}NBQ2vx2)5J*1$P{Dk0YxDi+1x#2m7MDXC>x(O z^KcT-+uPeLP%dO>xZ9kbJ3sNLhE?|Y57MTPPbP=o#gi0IM5}tZr50VtbMdn-xyAUF zdmR7+=BE*olCk=LdHEuT-xOP<3I^rYsH~@?R5+yW(6@=gpg!0$-PK6J3iq!g`aj>+ ze3xB90^Aaa=NtJG*KoanSge#)*00uwY4VIT9%gn|?VXa|#^=`7(tur!scqi43)@ex zQT4B9Z?39=lv{HU{7p#JZmrX}pSQta(LBAAO`ph3r*R(6Vl?Ghr7HTfQ*5jt6Djgx z`WMm&vL8TdEaq|s=Ame42$0k$;;3cpoFrS!7h&Lw%nSg&loS6O;cx=oIhkNkCVe+L z-IDjCh${|~s9^SdEH-~(dUDde?u%60L`CS|)?hMlr0Bq4QlD^(txwn^-^!#DeYXE`UATgLaFrS6}uN>^|;7g1)q{g;n&90MuwtE{XN))?fu1T)Ht1M zdd!`V{WphZK?@rNA0EI!qxM783jFQFKxXeMZRw77W?p88$CbH{5=_%)QcN96;K26B zyUV5@&-u0>5C|p7+GpSsHI>x;Qy(jzH%-Rz>Szx-x$z9>~^ z_K=bBai-`_L>J+~8wK*EEyuOe0><$v+_H#Ue*7B3ijQ~sgl zZJ+dHINn=PloK$U0kLxZ=)i~MJ|+$T4Gp0L=4Ij_%R`5`Go=Pc>RWU5hyjI>)UZ$J z3NxYV;l}~HGsk<|$NR@o=CsPO{q*UJQ(YAiq(%S-85zENeGQSwP7W~6^gI3G6e-c-O!m@Iib_r9%ODW* zyH;9+w%f3ll97`7Zo0g%=hm8?*7BW>Y`cYeXCwjmGZ&ZA64HR}#_#rUUY#_}JOfA0^}AJ) z78k(iVM-f);!}R>ed0@zI2K&Y6>q05^IfS^n^N$+339(83KFLC1QiTruXj;!le*N`@Q{c1) zK5|IQ=^1!H`37kr6YTrKYPWS0UrSb0wGIDiYkFXA2dK9h$XlWz+V#koeh8&cn3*MXAlSr_!$cw zqSmfy4Fn`7{9H)|YOVP-Mq{NO>*t!!u z+G*FFcq#BtV652HFRZk#wA%ZvtZ*&S(waq+W+&#wEam z6!^oSJ*#>3v=v3tOKwTAP({CRx3{^8FUS@xUd6ZeusZgAEuyTp77I!U4XRRSq8Jt~ zfE3P%M@U!_4N8dKS`rREfb^FsGCbM)`z2u|rO927r+|L?8}`WZPz4NQ9WyIPBLBYW@BBsLn`WarofTvMA{|O5VJFJAxyD!(E=CoTb zAg0B5_HFYjkd35};#b+-b|ROo*MU-${c{LmMDqzQ0CO}vqA6=Is_g>4OszBgV-q_vM0T_{c+nfcXn63@96Gc??u8Q zn4Fw!Wo0$bB>Yt0KHx&q?kn;96!W+<@DiF2@xE>{cy5X?q#;?oVo5HJ>D$!4vgZ_1 zljC)p@9Wgf`bk3f`0R{?n3xf4?LyPFtRW*Kv#3zT&cVd+zRdLcRfk4?euDi}qj`me zg}J%V2dNorXM*mhgwh&Ulfv(79rg3b$SMvoG>uU^rNHnt@#>5Fsm_Bh>wnv1X^@pz z^h-mYGb*V~OJwkfs85zeps;OPc4n zt26oU_N6QY?fFa07owEoAiO%ILlWx;N7$PDqXo|fPm6d)dwoypni0G~5JT&}{Hg!d zshNIwBOvDY7kc-CV1JAajKfT^EDNq$8LJ!kBS$*kXo4g=rx8iPbl9etHTANlQ(LEF)-io~LNwL2p0CbdAB@9?H<`rQQrR(8&{(bNcYRgM~ICt#(GMW zlds*y;Y=oJo-y9&F}s&-BwN8;=q(qg3jA>q&(TE(N!VWw@nj@S`O86}w0V1+rFlaf zbJrOIuRRbf9LcKf1mn{dvjMN0UZdAv9c3n-J*sa%7nZz`1Fqx~|1octigjLWnS8?F zAX{R~c%;+--OBtD1c=_Ho0uCm%p|E2(aSUKv+Nb%COmC@jsLqQsw`t0nY$!!pPR8; zIgkFD{=P&M7v|PiGDd__M8Mog8TgJAxPWLzbAQ6g6^m~djhr_lnbREg)wzAq5*kg5 zMB1z@t#N}xMj7+z@%>WTsjxTIXY!hn!1*=p@@+!2 zSFV2KT(@No4!o3X{Dfw7#Lq>r3x<^RA+jh7oG~I3d99i>{k3$eACe$$)>3>&1dS{a zfa5PF!=FJ=)KCl}D;2kbGogyj`sLZJivvgeQ8k{pwc{bEWq!ynl`VdXrZT`fe7?gN+1RbC%Bl(Vuj&12an+mg@b>mDvfJsOE!D1;CXI^! z1aCOess}g>1Vr1fp3@1YVUME}+U6Da=BGc@untUFDT$lDUc*dd`~>`K7WMAZd`V%U z`|p}Ed`L;EH_jF zz7&T=xkp&)!(MMEf+55aSOzVm8lyX_or%6Nrwg#P#;V$l#dD*V@Ct%K=ao`{h3UUn%Y&Ez6wvSMX4vBVHCTh{4pCbO|g=B5VX;ky(Sv3xe zuAWCFQ$^brtgB)tm1MHg^q$?Ft+n~>W>Q9=e4L2Q9iAGsYm*T^Y!<-aN?sMTMuC@HG}6Xr@HTHo*fzE>(?|Rp zhqXrX>^Dp?kZTYx{LV)dGBSG9LH5o(IT~EVPdLZ7(oHQ+US5-1nnZB2sa&adWHMjv zGigSlGC9=+y>8BTyKKCdxaxV*9VMeNU)MHdqGWvJ6(7upYMA>%L`xUfJ*Vp!X)sEK|}8jsA%9~ykeI%b50IkI*B`ebDW}ZK=&V7*TNK|ht|$0 z3NVo0ho8=5#6*A&?1*Y3zzd6@HHY|4B%tP4F#K0a3=c(aBvdNpn-(wwsocz}vP=|Y zNf>!HQ5Y7r?^W+Nl$8Bu~Cvn9dM@?whgL}CGL1jVT3L2!zgNf-!FAAH|Fh_~+^xbF=tjHTY#%1di$VX1VKJ>B`d zq;IGPWxS1F4RpAGgFu`<=3UG|7~kPvK7OB-ewdu@T;2%LNG%V80dfUJB<#DzG$yJT zG5#DWxiE7tFIKcfNnSEVC{n4(54wvXz-rOMQ#eO&o=uWo9Xk+H?AD z5RuJFS6d^6I~d+)%ZMQN4-uoZO2eY=?p)h0~VtdvMp1b$^%R4>FL(qTh50m)MVOG?ZRMx(=A z++0ZqhNxJu@B39rlwNxWJ5t3MwaxJpV6^@P5(O< z`y<4_9-8h@iH3Q#^kMzq9qm$LBAn8N1p=h+mu1!Ch9Y z2U!ypkAIPJUVK8vqR~6W45joGehVvx7ZwGqE1{aM?>yo_$PRQ!QeY#-)*%IV^6(K|;!S{u0 zU(6_7Y5o2*kuAYCV}J?47_8PZwNXG!M1%+v_`_c?L7~v%y~bcc3^tzKR%XYK5I0s< zes$pHWOah}XR5MLpV{o12G>u@o1%2^>oJ`jI&a9|tP*bMHcy3Y>e;hCxeV1ZAh!nH z4_*9NfvhIhcM<+ANs3mhMOQj2t*8Ufel^e|mLX3?MiEaWmTpTcku~8!5siz7hYa&M zu;W}Q#Mvr_S1ufhwgBn0w#Uf0*lth}t`Xt!<+YmJe5Pqnw21nWJvFcvRuOR-zPYVH zD8YhVfD#s>;%%z)GY;aHG(K2KxT~PC$MKt*Z?RjVi|A$+1@;qX<2XdGb7@5ZA|fIs zgQX1EO}1WINWnx{n`gFh4qT=$%dxZ#es8amfm-gt|AJ~DD>MzwmqOG)w2IsIMgDVT z1`g6Z61ZW#R8&TT!!*c=&edVONdN z!Qd~hEkB^e`nkCiOQ+85_8EsMRZs_WX=%xrBplfb26dKLg+%3>Q$l-Btv_wS-*i&A zPwIpM~?@ zEdCEIq2~-rknmKr%gWwSi^qk^K>=yVE?j~G555pu51F#xsPM;wKj+j&ht@Q@q~uhy z#6@L|RavuEwJb{(wTsXlabCaGZzpEegvKCHt*N&js(2~BC;%UT;|`xA6Q%xB0HVsP z8B>E=LStBSVFxsl^|3nu{oqedse?oaA`~-BbIs$fxt1N?RY{$ex$A}$2UrLC>FG(8 zHu2G&;TTgR>{<9;7|UJb)WY6gJpwzq_`>(*+d<_w;eL(rB`zb&uXnOPIgeSZ{;tKy z(l+eiuRa|4OMgJspl4dS3HoMSE&Ty+81s@OjyBOaBSBN^eg}Nx03=t4IpEB37fngh zY{^VTpnRVES+Ag6h4+JFO=1R5g;MyKmj@=bLPLJ(gn{Acq}sc%K%+7%T}-07$bhPt z^cb^S|Cdts_R+bg8xFU4kx}}{Jm53_CcSA`X)^Nw1z!#shmiIuQ2a9=MZKbLhCK$?c-Z$5gQju!+4OnevMj4oOpJnmP4tAVumU- z9s$?tmeWFJVSr`mU0lO$BTxeP3tJiAPl>_j3Q=~*UR2SR985^V+2=Z92T0? zv9$NWZ{-(EYoT&sT{_VE5CV6;$KNr-VF|^vKl*o(Z5IT%y1Fu|GZ>726Ur&pRLM%N zlieL1j;M*6KRvapizoAskB?vY;+(atiU#fYQ}fLFS5?=nGX2$~FJS%7w#;gDa* z%$q&_S4@yYCbG9aD$DWLlM*@t>xL~iu1c{yRz-F7J*P$xRG=d=*0gwGz(@pFb?@5M zH5ebq>J$-L2rz++E6W6?-gGv80DUkhu$JVni5z~Lm6BSVMelx=LY_wZ8Qu9x=A4L7 z)!06>hA#Ix+IPK^M6~TP_$vd5R3zBSmZzko#Do@ZeY59B4F_0LQELXMQb)Xp88J!4 zi)_CFS*(~MCX``%Bb%u-1fd}#=9Hc!+fWqdACwyq=2`#ThB2Ku{=6lNPHtnJ*6Kt}bWER2pTM($dny%1LqZ$+WoXqaMP3 zFXOm4oz^HQAxt!ExSdAkt@g7ehw~e@ALBh#wb|Ngmp9Co8GeWXvBrr@r&L@|kvDl*lXpyhYATjNTpaS=v|JCzZ4|KTd@!ti?2ZPX6Uv z`exmh{(N%`IpvVQGuqa2U@!6c3H9ypd)?K5{s^;!_#XGITR)rHk2a_;+PB%4!&B*r zAu4Yw<`&JB1Yd)EQ=WHJ@}m$R1VkTZSrrTPzw;>NnBWCyh+@mXaf^BUelQTfox&gm zIgmHf(#N=!{na$R47^|eeExgM(Hq1St|B!gu?_N135U?fY*D%_e4PqR6Hd;x$YmRV ze5E?)@;iK(g16kvJxxFoWQCKc8Vg&QWvugYoSCkbJTtfT4|A7b!w++9Yj#XDt`F>) zB5Xl1%x~9=vaN=kH_w95*C}jkd(*n(;M{lPDsYlcYn7gnHOyh_L>KbBjpruaZKYrm zbRM89G{cyRewX!8oXEM;iv#+yl_dv_?7lDl-H)CC~J`ZXX+51DEg{LudJ<>E7M z1QJv--b4l@6w0kFPKJdExfe^A-q{(Z+Q!5&Q6^)V7pf{b)ADK8*Zz_3*CM zVF(eWc#GT*bG&U0+8}~wWajOM!8w45ss8X6iqEt_vocY=sQ&1NkiNn;M0}F&iqbf~ zy2==mwRYBbOgJ=+9y)!k=o{Q|P0s|xzF~;#(?i>!cCm_1Hcoufp5>L0mtK7pQHS@WH+{Z7DGvsij? zXn&Y{zidK4m7VO-aTFaXo(0Ij>Qd4kwcMyTs|!HG@8$Xtf?^cx9221~&BGz* zT>rIX^;3)+Fuwz}0Sh)TXum~!`}#gpQ6**}xg(|U%34>tp#=sg7HI35bEaVY?%v+c zp^%E|N4_(t)F>)0K5=X6Fqm&}H0CBmfeBoDIdy-4Aj~DS%8%GB4*1ht6B%^_!fO6& zG`cc32n}GM8ncPAc`5d-4^a}t3l)YUVq#$Wp$UuY=|W|}$BBq=5<%jKK7Qgc9D&yh zZELG@96!hQy(JnrkWFpv+QG5SOQ4`fm$~3m6UOH<{@cX)MJsmvw}XsV8eF8)#oD7z zFygSBoA{>^iNSn-Na8Vhp;B^BJ~KU?II^3bo__ZI%v&Oy@V9t2NK|pT%5;c4f=@|Z-Mm)o#;b)w3KoSBO-wQQ z_jS>_Q=%0Dp0l!0kP@OqeZ;@J96w_0*-^UCXy?;qp1c4Kj{hKZdLb9ymBX20!Pkoj zE>2E?x92N39JsK)Z#dldUd@GWKp_=;V)$m)CZDfutZ}umh+3{yc{pB1-D+EbEej71udAygdD)j(d*0f? zo3cJ)@8fbRs`-v!UB-L!8$QJS8$tKRQ<&yp6dnojZ_3pteS)tQ1KqcIszQ|3vn8JA z9k6}Il^AcAOewzC*)W>ED&=pzb+(&pFDoL*sA>e3gpBmkL?J%=JT8#C}=uM_w zyU28JraJ@u1LJgLT@8k{6_1q7*BV#G4X~Z^nXT`a?@W>E$jHd|@86GROW#eJmz(?k z#NMx|wUxMidV2c){vH_oMSaVO?aIo^V$g4#byQbmM^ovMqBO`wt^Ut&9FrzB2S-Q7 zBMk}LCS-wX8Kl2TDk+hqa;n%TED{tZqzN=Js~)p^~3qIWM5cU z#~q&?1*eP2UsP;|!0qtt*1CJDcK%ahzci?w|F9 zow))Ru(jz|GsG;Zd3>Zly5Upr(FCr`@741HK%=F+?t?zk_A}~sWdMN1=(q1QPY_S` zh9*eZ8Tns9l98Ou>wcQLV&~4A20CqhIt9=%^NjCxSy=)6QtIk+h06J(sXSAYlS=yf zaup=QE`0nnm}n$voh(ufoD56g|tHpX^C%CQ350Oa>z#E!3CuE)>K?Xfe6wR0aw zr~cuG|A?8l$fpi*aU_@>h%cX_W)Cd8x9UYdt--!_9N4fWS%E-A0{RIa*}R`h5m>{P zPaWU_94T&R}rFZMF zfI3g@s=WQ0191=gk*SRyghpC{?_cCsJh_&~)eoaW8Z@t&8b*3a)qL>c@rF=R(Qfqf zLVme0P+n7mHDrPespli?`q84bB63!(2AKrO+vtbcy ztQ;IRoNdQ0=|JTax;aM_jx0bzVOigG@lhz!Tu*qOeE+R{b<*DQyT0{0-4EnlWWSex zZMU6Yesu_3hZ#_WSRiWIRM3nf3PB|yu$I|0vVset(6jAHPCUI82p##av*{%A^Ygl* z9Om&kagjiy8G?SV&kvQAl>`d0D7gq)5!#587#d=Rzj5=A< z20y3;*ZB0u>Pujf1b2N5?IA?zJE>ngbsPI<$16wW%>Bn$zdrk%VLu3?lCWnby6UT_zk)Gu+@i~G{AVgTA9I$wqYf`LSW z5&Z-iunre|l%?20zxELU{KLB4fZ~$3-LBS7nj&1gbR=s(E(ay!tP54({`!xtYom@= z%c>107YB#!OG?z8@9h{ks`h>|!Hf5`7Qf@Jg$2TZ>DFyHp8UH8s>~!G3wbU@z%Qf+ znO&xrzmKp3nW|j3i*t+FendOYz5oGeS{k4P4Nm)zQ9o3lPDUrq;Bwr`0>QHfFHFf7 z=mH#iptw*!V>G8`|91~ZQ$H+|vUBSzgO@VG$-%MX!aG;0ZC<@nApwA&I;!AG7M-Tu z!ZLB{pQ1)r^SC~2m)}&uNuEOG6rMyVqS=uLjEz@42!BI?SaAO+$jwyQByMbk$NrtxrBl<~b1uic8`(kAAYDG_YSq*fM4^b<_T-~zENuF_S z-~2rTj{O4J3G*yow(G}f?FiP+fEOuTOLSBEZ&|ldv;E3H4vV5ABrAHQ2A2 z^?siGe_8;6oB7W1X%}*D4?HF1E~;ZZ(hp@0CD?X#RV;mkYu^c&f=@%KLIT-waoYa75UoPel;>?+J~-%D zCp~RKrBkB-f6EW-3%qsv^JjgTr+W*O<^NG5)9cu#%y!|j8V^gwu{JYPJU&X26dTgP zrY~H-re=A0a?-%=SKpT3`8CNe7M9m!54rEi(K3et2ZU$kZeAmngd&?@(d~}@F9Bz8 zK3^Q{_w_&+^|C4&bc<&;Tt_2#j|Y+N1+3a9f#h+V~k4NsB%n$Og=Slk)nv zfYq2J0;Eb83)U>qI5ix?Rh0f7^T z)8>Au+I)q9p|j4`<96YoLujb99>_>qpD%|9IBnp-!XkqBPTYh}`8L|d*7urSwJBv} zl91VTPf^^?yTe?q7hw`4->YjPct*@`!H#OxB41B>SP}F|vxNF|K&XrkvoUIQh zE_zZ>;? z{Wt3t`X$@CGvB)=AWFY%;N>zgkW5>#|APT3M53 zA7jiG?py4Oa>PdEZP*C|fp%|jFP&Umc;XgU+r!9e3qZ1ZYYr+zGjI*gFEo?NnD3Mh zm-dxHdc(jlJ8Y4GgX*sYG`z>J`aGGoiy@AhVAg@00o>AK{zF79hXod11-_bLz`>Azm4xvy&K>Jp&@ zGwJ@j2I>>Q*u~4|su8MD)zy4&J_~ww%@lK%&qYh#Ps$;lVsfuYMd2M`QTju8vZN9#hMdUme-+Z8)2E2EW(aAJOZ zI4BT1JG-o`Z1Z_1BF@pF-9NWdLEPuX>alcQSA=%;w#ONOD36MY8W3dph~0rpQ)jxnS zDI;!q`LJKrV&*0%FM)apyIpRhf}9u?7imv9q9f+g|_%QO+v_yHbY5}GZ=lvJX>z67sqVdcdKrviQxq#WkMD< zHY#Pkqf0^OAH!xDURQj}{zGP6^I{A02Ts_~U`5s3_0c#cgXTUa-zBC@4A)eAy8;ik zTFc4F6?(<1y)`_@@cVuwlaNFc{c-R|)J?a!zwXYXMdUXW>d$b9Hb`H6MZ;Px^IT2Z z&Z0#Kg_l1=&kr-jtCf{M4iAG54`X5bt4h4gQ2c&#_P9oT5kv`1C^{znJcC1^)z$*xLk6h|Li!|5Ub=Y>8*A{CfpdYha-!6mboX;^PenIE3m__U z2`4}z6Pjn|MbNyJRnTX~B^@%Zdd^x{Hm#M16JB(|4ehD2v_bNhh|frs!jl6Zq|y&z z$5>A77dU%87SpMn3-JU(vEIx4OdZ`~t9=8!9DoU6VPRolV5q99f{KcY=7RwJm&<Id{5(a)65{FS&6_F9_~?K<<(F{=CETIug%9S*4uuXylZ`GTOl(owv@L zp^Qd)ZFO=o})siNMT@ojqpAR&neVxo){*Mc0< z|8~UifSCXiA|AzS(&jZdj!t3e#PUW#O3yPNG(VhG7pM}=F%+b#PmOG}cpx(D_5%cv zleJ@UMFIF0++v)W+~)ZO$)qZo*WkjqSId0C+6_%MY3bz;MWlduD9fOLRhSDV5I_K7 zNK+XQgJO*RW220Tz|kd|JcUt8If#))b=Y}vsf52>#Fh3id7RP2;_G6hCO@TpG@T=W zNs%)N^lV9({%Yap=T|5PVFnh?1`eV>YyeQ^_o)X9*Le`OI1f5a8o$=(qq*fc_NrFR)Ain4Ohn zdTlsc^w!>uL?ik6m8wk;hk?(Ixnj#Xs(uRw5~EH>CB`v= zzWVc<)<2nyDwFr2Dv&qL0^Ho(8j6aU zb4Lu=GDRHQTKo2wIHHI=vY2!kCBrh9kZBN9_A^XsY%j`MU#WfoDE1QQY*IES99c0r$K}IgGq?aVzK+gq`b5T09dnt$GvT>@+#6OGJ{f*rDta7{?Rm zO1@;-tI)w_+?mhqM@MYmy>gLw-j$`K5;%zncb<*+!o*j@J%^6Ui8BJM^K1l2Fske~ z@!EF4ir~*Vn&wO!RZh>%Ia_Nym{5k&VK3w4bsFUl(^PpOonorS_zl0!ym;#F#Ka{L zrnCN|^EO%f$*_&IKxI?3Z{h9zlqZ*>LCS>lqRvuz=!vQn8$Dl|o~&sFe+>S#^08fa=X=yyyJ-lrvrn($Ta zCUJa56HZq^ef5}A4tE;1gdTL(^wgG&(aJB+YtDhqB zfF!1!=O_a`4m&6{GdNtJJ4TZI&);Z79LAd3+RSBHviH+tg)RAkXZVl|mSOu;Zs}x4 zRU*pELC@{mZ&ul&xg#Kn>a;Xm6mD-8{;R2Ix$(X7sbsDc1SC*JhES^KJkzYK;P-gG zY>-JA>9}mLu2sOG+lOTeUWAxzmL*G}GBLebMv<45-KP8b&18IfcGgMXB8f&mqYYb} zm;A?Q`@BRi0{VxMklZ1szQ-?&W&hyXPpd*9z2}eku5Ao!Mh#X>A=!_`6?(bxt@8-4#m=?uS_bjx?{x=vv(?wzKNR z|9zZ~CO!Q2c^=zhltQkFRZ1t}5%qmkrM5l4x^5WXlnHBQDr-r3xqG_1yl$crgLjVa zuuagvpb(4?a^T{>K(u>1eux?&KW5*}1OLwoj2@icrZM$tHtEmpv4`k-qQ9cd37-gi z6O*pwEVwh=?eCLUYMf<92(-8{?8Z{Xz~^GCsjBYef}=+J<80MIB?Qe|WoNd%S5e?P z|5QNeRwXTzPBfU$!}6Jdo=I8qJzd9HFwh`EV1Xw@gVJ`SjEu>~z62GD6LQ?eCV87I z{PS{!I3YE6aA3wos+zo9uKk9l)An|U0h&c#ow%*M`C*LFu_jxDs)g&Z#crxj)aBT9 z9vt+*;ym8@KO?F1!J9qOuhDpfz>LqE;63<9JO9h~weKJp1anxP zt*x!W5br(Dy~C7)ULClTZY> z3dLbN!L#Gbfe0%@R>Sx~MS2e65tJgch#^4;AJ!)(fVfn_Hl~g^)Pwn-Vw9FINrX*F z&m~HV-kBYo!f87RfvVq7aX5?@)`c5DszDzg6a=G)Nl7zuiDHRILbAs)`S|FSi#Hr(JJ1qb3By286qU$DYGOoMPo-Ar+FS zwKH`Dvcc~EO;U>)Ph=Oy=Gk91oynRA`lzt3uKesa=5v%2Zc{_kiXD~jpcwWQmM{p| zDK^g>Y(<;#GcMJ+IV2CJa5(jyIiXxI#%ks3t={l;v)U;w>EcI4NHt%zNCw+afIztpB1X{3yl6e2S$jP)gO?d^QIDE zG%N%ML4j@-Yz$t}vt&&ID!uHsKjxF2ulm;&7AF08MGuPsI;jr<%9^T?9bopEyBDs~N@$vSb=h|a@SAA+n3n}(x zWkp`Kt$HGF+@65s4eZ#IV#C=tJsk_gnxzwbEo!N`{5(6%a|ThDSoM*;f&h>eQLXxE z;|G6FAy5jcJ@GjTXn$qCc(SubSmQA-5@;Lwr6g+kG-;LT=C49-8q^~uAtB+)n?@SK z+u}QI#A91a8!;eyDohQ>7?H1;gqS@o9N6J+ek09*>3iJl^FVJVL5@g3q&xK^2y>uv@cw)zLeKOSwSBiMrMOKUx!q?XRSl61-tc!y zrxFbr(5ND5noml2?g4VS_i1|JnpN2Ih82xEQ9b!k(Pv}kT^|vS5U}pn#7`Wtkb2Ds zKp4>LY?MUWGW48R4FN3d)1Rg0R0DCC^h^l!%5lD~V5E-(lYks9TN7TIV(iCj$9g!0 zk7DE`_E43DKzpNUDJ`&|SpYdO8^Mq0+q&>5L2&lD$yP_T7bxLAhXF*Ez{Z#@B@nl= zTkG>a`wD{MbCj(j$$`U_GhxTu1(}1tp=?flO(~R^oQzLQyxQPM?w^^N2@uZ)D&_VW z=`d(4_)lh{ih;{SWX4ujd^0#f!eseV@PDhSl%jJ&)(~E?$X}@hnI@F6&#@?Y2SX`= zD4Fc$C?pk4A;pRx#+w$d5bK1c!_`n`R%IrN>xfH8=hql5ShQJ>HFGlqx%%Uyp{Q?K z^JM}Z8;>ycB4Vt8OYDD^BO!wLpkuJujH^lnJ%+;%Xs92q_QJ%CsWGkC@J}upi2F^G znf1v;c^UqQei|I;97>(J0)6+lMHY}(G->*9`hFLkFSGwmn}?? z8o*FajBUdcv)zr)elceahAUcT-q2W6kr9%RnDg&RGxJKn3%UkDrkE;N*fNO{z~g28R+g4G{o&dH zMeEsZ${j_InTvNaSKJq8NepO*TQ+lrRd;lMZqnJddSd^rq@2inaiOF10%Mj*b$mUZ zCqZ*n@3@MB5>hyz{yqF2itwIh4nl^(*x-Mki=|<+Vey*DlEDt$=}^~q)ob(RLHDG= z4(;0-JpUWQ!z~;{p<7;3qDB?fYs3Ooj{v zA0U4I{5d%2@dq=Y^1|jUxCTG>OYW7p$9_3EIkCxZYxBEJ{{!^k(5Oa6JiYj)cd|VP zZA>c!JprnCWLMLgIX=_899gpeR^s<(bL_w0I1Hw!=}el!Z5EtXte^ori;4QqtcW`` zIoZhUmmKAy4d-yzN7l`Y22zzPk_e(FvAwB{WQ(n1;liY0qclYrcwYlEzSZSn&e&Fm zh=pMUhUVy;WKom6b6M3mMiTpOL*?H`reaJ!z$t%Ujgu;2+bK`1Uk<)?ZBJo{Me`okid~|{SsFY45cG&4BOt>%5$olrKrJ)LNj@^|Zrc@v%)5Tt(a|KIE?e5Pw-Z!&6^i(C(8)2T#%hLEz}bx3 zZoQScJfO2CDa+1%YA~*N`7|#XKY~=H+K)43Ym;kCSI-q5aLuUG{2LHx2y*$H-5c8) z>lO!91+?UG-V0BvqkkCx_nGP*keoZsf2%el9|Yt1Xdu%&08T2G1AI&t3U=C+O_DFX z2DdbMIVaH!$I{@#-IuC8l|(&#ZfiSRDrZmi7lwv_3RE8KQlUm91iI{Q?QhAXRN|rr zb(izwfBi4o{*hYx!>;Vl?z1U+NSZyj0a{O!5Z~vMO5uPMV@GeaB#S67axwu7#PmXZ z{dJ(M?O9++t>`a8o-+WDz1h8en?rl*bCc35bXT`OD_fm7$u7K52nxbx-C+7i%`S~5 z>KU`>FE``P;PrHZ9hwWAAQKY`WhEe~G+y8;Yzh%)#+4;t-lm}i0jY;&H-%^TpCU_8 zAdWq?s>8}UQ7zN7#GGg^F<$z=zO}be#Jx4A$4hfYR6h%kdyy^xF9PnW9L7>-MNp)aRXNROYMXLa@J_(8U-LDJR_*Zv5562;hR(H{c#iq)9cjGbtyHDC^ zw5o>yIK*jKEjO=5s7-baPv_U5blXp6E=h={PN?01eLUhK-TxPyMO|e%L8o3u{|_zC zo?H|SN>T3^^Cu%fGb;s;)h}%=(7;7-ah)BW@YexEPNX^h;IVU~n^d%VH1kwuEE{Qv zo|F{|RD}nn9S}p8fS{K`Bb#zQu)i|1^v6s<7nXDq&(e)Oq8yjR7XQU_WNd+S2wHVh zB>AQY_Xy_9fFQPabaRs!Z=-B{fPq_^e&sd~MCrUC7)B--#f znD0QA(eH|plhY50*lwI$XDli8bV>$^WydTj?hqiirBcC^LDJnMpqt`7IUI9$MYB zEUCA-Ye|0^QQb*O zgqmM@ug^s1D@_I&CW5S-DXL0QRxN0@dyYfbzOi3agK@xD`tI&*)0rC=M`KEIY+RHA-(&YZ!&dJ2|MHq#m^op65y+v~ zLVgc41h6qUsIccIR9kJ#5OMxfZeHZfcBPciDvtK0^o#znL{N|wEtbh42dk6mtPq<8 zoQaml4`W8=h+hl3fGMqVTSWb5TkxIO+566oAlb*4A{h20*^R7(88(2((a^_@)83@} zP&9Z52>$u5e~1iz6xYHMHCxJGQKrK372siI&z_QIAhgBTy{`QaPSQv|#)J|OnkR%S zcr0^NF7WAhw63xtwI!%C>I_UR+NWkS%wCdUS&Aeo;lCdy5$y8oJ_helF&Jc<1AD>i5H!s;kp6etO4B=;eS8>U*e6rSn9@ZMJ~H9>j`A z^I&_@)m|pEpO00fXZLP<2^M$~g%QCf?^_&em&{5M4U|L0?K;qNqFQ%7TofQ_$v+6I zO0K!F2T5AtsZ?o>E&T-$D@XXgWvk{FclV?xQ@)>4%TC5}-?j{nU4iwBn%cT5-6k*Z zC?3-w^`H`jx+GxfUq(V_sPI2zfR9-VLE5*+Jp-#Baw1(ne8RnR}b_t1Zp zjD|AEC$0D-tfx7_!5+(L8dRpOjm=?c~R;*tJ(bL5RC5ctjP-sGyw!p+u z=09_!wqKrrGC9Uz5G-Sjz`qHL;xQN*c77KeC=U z2*gCHC}whs1G~T^z|8O8}{FUY{gZNtl#QpE~izRV>zM9cnR9V z7i&u~#ZpL#H?9*u8OYu$itxuFFPDN|64FpWBR~92#zR>=yA7c>LB|^nYkwgPq7;c@ zxS+G@p^SCzR>{DAN~+B+sBz|A3U}W3b+pz&9lF_d*j2GfJm!N1fKBBd&Am4RsYc%Y z)LvG4M|emF31o!R(>2*?vH}?(sI5K|C;g({p)HsTOT0#v6U`I8x2?s9R1fMJ9|AQ; z*Dw+n%l3N@n|+1lCTS%Lw=@%+`jms|N;ftX5puL4$QOI@kRNbTyul-!b-_zr|kBNJ> zZX%31FqVg9spm1EA^|qGj(S+R;8u0?);Aw#f6MB%R_wI7+MWI0rY;aZaJaRD$b< zPpfNnt_L^S{z56e&MejW_R>x9-j1y-Um*+g0z;g3*WD-X-=!iB{)MX@K709#Qd{Jn zXeX}{iZFsfNsdo-gLjhNL}~ANlF|JvtElR)p2<({tX-pji+{><3VX!?@sn+Hm+<<~ zQKxoO=<_G{RRDC+8^baA=+#N_OrZPB7e!*6H!VrD>koBZ>%RHU#w5^6<()|N=x>gc zarNpQ420|~F&gFAUumv?&h~7=6tlRzFOj%#dLiY2%5E} zD)qv7^QynZPLYXBXrl*}3ksy9$G)bBkloRLxP-oise|amB`6n=Oz^3;b-g2|GapeO zuhVQb`~oyIP}I0HXkV8$j{KbJrOAYPDZ^4aPOGF6oiI@=$_%dNdnUh^{fb2*X>(hg z9=YE!CDM9FM@OezCu4p z7>6s4g<9cWC7PZ-ZCHK#EzZcpfD@0Wv!K1by}8*Cv_~Hu9d&mr(Ek}N&ij51p6jF| zf8*_So|>}RqU&Wf=Y{V|OS_A%sn7oQ^1gi=QRE6~tgEot5Avm^=)K8Qrp&%fWtG9y z^Qw0+N+~T~nkWh#M-~Pu2GZE7oEO?a&>RG;jzP`e0wXBwIB8coyvarJ0rff`52OPh z1-K-;vEG9UPcJOw(}=-}ii+4q9c8#sH*r>m?)g1Dif6-Shy!iE(h7T#V`ueRF;7=j zCqrPO?y{E-@#VER3rdtvh=eb_&@o)P1^3;TlN*Q2R{FujFuC>)Dv{pt;gwkj_~qzh zrmfWXs_C0472jh)&tBvGSHqPqdX|VDy?@%V?<9Ef51Ov0A~!P5d*%L>jZKooA7|cf zucd8G{2HJ+QcKY}?Q+f*Sv@SMIi@ZKOpy$t4@A|=sYbaKb}~KX#@BD?Cky`60^23S(}POf@hWlPjb~|Ix=ideB6g0`4pcUR(V@4 zh%F;h#rJw#kl@|Z+_{eku2ZQ3wt}axhyHkR8c8#6fm-i`DkM@t-`Q;5qPqf=;mjz` z`PC2_!t43R2;JPEjF|D7j<_c?Pe2*W^upP!Ud~Mu(7kx_ZDJzb%L-4m>&HPjHT7QR zp{D@F94^F$N5J;E$tm7oMCyp#Q`WyI5yZg@V;nQvj9W@Vf(@Mf+V@_}(#0GP$Ei?x zXuE!5&N90g`z5V~UrNNxT-z6@!=LXyuM!vealGx#f)2V$x;|Iqz`ylMHaHu1*S z8~x84v}$r7*j8eq`;GNS5=!0456&*awPmjKF7lwr;Zp|*?iZ?9#dxK;m`yX)SrXaW zxLy^-3^A}pi2{#>_6TcFVhVA-T`c~iGK`QN?@I`KndYo=TXo&jOJB4jQ0EVQ>* zaS>c8Udr2=RF7y>s>NnRIZ}wFy5fpL^%9gcjRzcphPekkd*>sm?nX*ascmjV-g>l| z>w4m;IWhs0FSUp!E!=_4Hzj^-19&QB!TyS32Q{6OPv~16BpQYo*Q;qDEzA6m`KgVi z=>2@4Za-t`uBJ2@>^go~q?-1G$0m8S0m^+&CRpqQ>I%e)1x z5_^F`7*Fll65?XXE}hlHeJzgK18kX~?5(e_1PWEh`+&)Y%T&<$L0t;|QQ(mB`=&zt zsZ!T7=}KCGjq8N9(0lnbS}`oImG*A7i_6`2ACYw=UzUm(kDLTqEq6&qjx;4RWRMIN zx~rgNk@C5=M;#M|eLgq!ug$o@6?+psjV_a$x?exZ-w)3X=`J_|d-t6hetF(}0X^%qlEjEpcC1oufYIG!i-iLc!fsVhup2%m@EMw22TJD>uin|4@CYlb)DU_O7A&KayZd`^){D=C`MhYcr4<R3GwBsAF46cydqZzfPn>eapF2)%MWArA6$pqV6$wX=&&(=bzuR3kCDH2X_y z&-Uat1T1a2Amn+XowU1V;OdT->4XRi>|zL|q~@$aAGk+K|0ioNPXVWdwU{&h3O#MB4?e*&4-@kJS z-^6K>__$Lai#GaYXRk9_pt-GfUc7Qq9?8-LSi+ zm&GH8X9v7Sq2gN%@kV4Rhf#5Kg@v&ix_Z6h-o9S)-_Zei-r z`;o!=S^=3_bVIiOc~z1Ty13W#fbMDxfpS~1ijEddZ4@V$ovFa)3D3A3A9fjX;>&Eg;ITB@xyn-Zy5@Xr0E zL~ZYC;T2*Yh=fiXMQARQrT&n;Lk^8G%-Qe5wp4;B#Zv?BwEE!6jAacqJxlC%Fs0$p z=mNn*Gd_PA6-+`}U zv0K2>t~qk+)a6Y~4_UF~Ccdk92O8N`sbuQ#;c-Zn*cxu3m_loVB9)CN);(X>xQhTT1u5s&e^n3!jxg0Ju)g+X&yrI zE6X@4geivm={vha+Y%N8o9^mtXR6)BLOh8rC514=(B+B{HU3=$%8>jhB#fJx!~JYu zU+PUpDSG1rL+Fd ztSaJL8rc<%aK_NtXm-mhM}9j6ZEwX4Fhy`|hiVd_m!+j3m(J1IfJKcSaKhJF^`br= z-(PE&3-h_q9@iCboXghPbW|Ca)-@wsnSx#hhuVkoku2SF?obHx}* z{|&#(>rbXh-Ccd40zzIMV!j4>{A~4d(J$|^JS(`R-HYmfypY{_KPmca2M)oHw1weo zi9VV7W@@+mPy9-SEpC}KE}~t!-x~91g+Uc$q>-_X(l(E5#?qI3XmE@qP>jBe~n6 z>DY=_oE9p#+%#Xn)j^op*LXKszk;@#;2NYN$?*{i=3WOao~t0iWrlnXpKJ28={u9B z90>TSlbuEdruoVBu*j%w&l;KRc z!S!yd=*`d#SW5$4SZXL3modh(!t~JN*V^8JQpL9z1?2DshUBpHFwS_R7B4bLadwdz+M)C%3vj4h8imF3AKF#^YDq`#vYHS>;G@ zAV$}y{X~e{$-@P}Ce~}bzLiohQ( zEr0M{zs38a*l36m>^6i0-C;j^^InjaqX8lI)DJ!0J?X=Y7TaO6JR=K70_*KWmD>tP z!2==7#CS5xx`xUjKG4HqKQm8e?Bd45p9?Gm4aKPixm1&fg|Cf%n66VH0Td>E&@?|X z*R!CVJ&rwAh>1k0w{TR?7&7+bUO1gDA>jsg^j7u&Num_hSD9ygjawC20gGW614t16oOd2M8_!N-9XMs!K&3qG+htA~QsZ|N!?JMTOk3MD! zVOei;tMm1fGSSwAiS5AizTst-80Yr0_S#A&9_6-YI#xAAT;Lcyy*_EEI0@8t(>kVO z_xWc=y5S(5F=IPIX`p3<2)m)EUpy-N%gYgh4mZK+RH1owV-EA5z-m8EpW>wvEMVZCjkMlYbDw?s1mkw8l%ND{4;LN;VP`5As~(rWwZW?Ej4W6rOJ0RhPSBG!lj7 z*qTqD^c_*v=CH>(*RgNckk&$Gco#e2N0aVKB1H8c^7vv|@IdME|HyDJ#eAUU)78e< zV|la+lUDoRh+u6&I+K^`Orq(Chghomk)`7Z0h}o`OFds;I5xh?Ji$XT>W&vA{{4<%FcD~ zBdO2OtA%JD*jc`TUyK(Fmo~0#6jbE6Yfb-%k779gb&b^XvY|QWL{}Ot`-iN6j<>eD zcVJ6u==j_HJR>peHu+9p_^0o*pB@#QC_YFt=|%k=OZxhqEaTDY8DK;c?6OL~?6=sD ziZsi4Rj^zQG5Du(s@ zz^<3lU6sCMsWIFDDyJ3JXoVV*vBj$avKypH#cS!x0uQfbpk zuwTJZH5OBE&}uETa{q8=_0Ro^>+Ay%h!NXMfm$~;Qn2>VC4>*sG*?}Vzw3(I)HryY zV2Q{2a5_+3LZaB4+E=kTXhtN^O3QGS?S$psaB2L&O{}`OI-y|wp-H|Nc*m6r%;?jn z?a!$jjOF;r8V6<`{CbRU8sPc6cVSE5<^Uex1eY6Wa4#aG1f<N4Ptf(uNhP!yAh-gIR9q*!vAIW|Cc6sG>YA~@!9f-!K_#s${}Y@ z04&eO!-7?*AQU<8yZLZ4Hmno-v@bOlR!V#WXk zb8@nG{~SP)Oo2u=>lqLsjUWk$5?jT`$4A;B?Xs-&o98HGGmw4aFGf9}3{s%LYyq>q zkS7(y5V3f?5Ci~EO7rh1V}*lSeQRs$r%xxz`RA6PQ_#VI8#Wr)UTHTyKhI#nld#09 zq)@01Dy>4Kwa2V$Gg+faLIlQbg$p7yA70%Dx$izbO+}! z4NGf9!%xmsCJw!t9}2fhWxlMRkxN0YV=#eK5prLtl3!Ts>locjq!SygQ3<5QeO0k( zmvuMMF}qM~BXaRKTGhwp&xj(Uy!ye-22}mg zKIjA8c@g+s3Yw!p${AB(-ze%g%pmn%NAu2JksVj3a~c7U5NuQ!#wz8Mzw6#-rLsSNQOJ@R()?RHk zCHGkhW~St)kk9ih&t{4x#BSB`Y=Ux0+U#um0b06*pv$wKgm*J4Q&Ur4RD}t>`~UDk zq+wJMt`?hkiFfg$-`N|MrxA3+$u=TPphA8a@)*^T8c?JMgst5V}oJ?Se4b#A(m^wn);q4*N;ueE7Wj4ck znaK6J=?Xg)AE$418Ja*pWCca1YJL()Z`6f6DWRvEdkCTSiXQ)E13 zwJ*r!;c?-ZMV;amJ-pF6)nbdR-+z1H^FU^*nIiHUr|A_exq1E&M{^M1Xi#y+C7AEJ zaq5NHX09S!>4duP9Gm(i+*2SeLD8v&-H@H&fc%)S6@Ko%L-iZ;TI#NP77{wp$)u*$ z#YJwP`b;v@#fDSXiJz+1_!DT)_22&uW2rInzT1P@|GeMw#mr@^p8IY9%?RaK_kcd8 zKG+%SGl&$S>k|jR6qjjuGR2FGg)Dbdr zECWslO_*n!UdauX z23T0MwVP>;&H3>6QG6}0pu;P#*E}Tj(@IcWVHre5F!OPjhjbO_;@ZK|UO`g~E@IzNKzJcRmu&+HYE2 z8TFOGU;!@EUBC+V{SDi~35YbLlB^seZ=eu=#q)6e(UMrgx#g&^Vqv1=Oc&~Apku8< zq-3XdbU_!;h0-urwByVjq~=URRFnXcHo|Dogr(bI+Jq=H6L9Z(vi{S11!x}91&K}=|$wLDFEkMqVN z%=#ry<@Hf2)vvP@yeOO-_AV_~#@ePLRx=HoO-=A+eIy5pL>6tsT)k_z};j@a^P>o9CgAZmP2s@U8X#E;GSe>1FR0{~TIa+(#Mv5mf?Nt zT77?7Tp0nFaKaK3L5!gs>+5s2yKzw!@CYs=tXQ;%xyZ2A2#;mKBqVf9u)^C|Zpl(m zfT&Q+_PDIotbl`sWmI^jg9wc%9b+l5uC<$KK-$GsizSeE8YKIa?YddA)ty&KUz^KB(b*bj!yM?bDdO`ov=TcJUPR9_j25K=*n}SjUF7gUtWN| z5WbWkn?z4b65NG=7bbx!lRL*K^>$5>#1eGlW|eV!o=g_lqU@CraS zrRGN>t_YD$sbk-0R9Ie{tYR7Q`wX+V$V}ShN*4k52#dNyOuVw;!z@>=(&n$O@5JmZ z&`sAP0Mk@YVImL}6*Za=A-WIy&L8t#cwpa1JWKO>EO0x5v$9m!^|Lmb#$Spivql&E z14sj~JgoHre)gapEE}px;cr#i+(>jN%zD+kIbu#P0-NV_$cpBiniKBfzIsP1XtlH) zFDexJ2)F~mSxFZKA$m#g0VKmztxdBOCc}!Fw8+jN;d4PtvT1BVRaC1RMmyvUuyFQd z0ms-{QZ>&Uqx8C-Wa6D5=D$VdOt@1Sz@1M)wWvV#EPB@%Za-{8s zeqo(W)Zr$sSCd)k23VKtD3YYSUI$h=zlHO|^-pII*9j!$b;nw=LVlx7+!hWwi z18FBqU_8McZYDl&NvDHT`Rt3EpE@N?gzMRn<4G`_Dqdj;i>-6$Td~PNN4K@TO0@qXnT)CQ*qP0|MV+=ni0Hm&@zTPgaCF@T4I8a< zG-NO_jl16ghVub2eLj4vN_4s69gu4epB9gnl&!{0CR5h%)fuh!8Lmc}yEfj9j1!pf zOlAc=3^Dh+^{n8($bCnz-*C7-6LC#C;3hMfJgKY;+S7Q~t9k6f^A)qiL_wO@k3FC# z%bqLLCl%*!cm}XipOBeLc^8hsYAgr&hEzYfB9^|Gd$$I>2PV22SH#MUdTq$$IUfLv ztSO<%@ynHF>k@w+Q^2aE@g!P_!mFT8!z7~UWePDFaeDhhDK#Uq(p_qc9CyUs@IANh zuoDZjYgdEP94TqT`eVNBLnWSzWE$=nuztfzBR8Z%zP{N8tzg81*f)X-kd1duw^5r>A#^m@tgElLwh|Q)r zflop4@T|CMlSb4+t#%we-=BxD|Y0(1y;!P$&wUi2~;J` zwfcGA4f{%lKCu81wpUZd43-Mq2{u+b1E+j;}gn)F;gk7w7i zH&wYaS;W*;xq-}kr4fa~lL1%O6kKAzd_ zI)idh^70t57Zw$`xA;KtjU~y>_IB$f=1eJx2=6+xT%x<1&T5Icu8w84|KH_G!r^_o z9_l-h9zVQM95FxnlJ~GcCDp}ntc$M3$7j;QQQ^+J+%GNhyz;NlmYC|_%6ZMs-5)v0 zB|1vQUw9m_aAOm{9qJwi@18X{4tSDvG3ATNDi#KO zFMT1-vP&^cSxH9B-@OM-&o^!9&=YZjqp!#dg%tGKn)vAh-SLn>p#-~Q{LSMyd&r47 z6q_qkcl*&b}`+;E!Qp4&%Wc6@GXszhd?do`FK{y&N|l2X|GJ!fYll{2Qlni$U~CI>1W* zxm;5Pr9MaK^E`IO9#;^q)4Y$4mM-y;4lMKk+Z|6E85wDpMe$moJB&$oVyytXspB!T zB7O>c=aFu)BrL=3uu;)Rk4$NOYJu8UB}uiEriqYY%^(Tu6C}ijicf1ClR2NK6-B^% z1*F8cHAm~*)^*s=ix$t<3*c&32?D*voK6Td-(km}iP*dnfWM5I_!BnpCY0Lr7Q#YB*vn zDIE}Rc41`d1|~4R2cx!4ZJtXJyQUXJ!^BdjRnx+X7`_Yb%<|B?_>heOPaa=!o#W?e zR(l0Tt*y)hHC&;Ia;)i28EFVBDLmdAKzbZ@t?A+Qm3p-hZoWR zCc^%et+-pQ4r4Z%rbn?#cb11tejV!MRqD@i-p*a1x~?psV@>WIOqRX%NK` zC#x_hSgv32XE`ig^Y|?SfX&s~3@<->zlz{fqkMN(DmbkgTaPq3BU8AgK@o0UgipAx!=5?5iEKg0tMf33YIyozP~(9K&_ zCllzlBuQ)L7~Umo#ijOBG|af0iZ1K1%)D}p0?6-st*8?-hmpu?kCoEjO0;3@_fL)H zuB_#G%D8TByb@#$2_Dl(36>}8BTJcB!F+#YnT5(l-G$f~m zikIpwV1T$9AD@T%6eex7*7il0$VOR@-s@?GA0Ho^KE`*C#A;eoyR0XOJxhQ*B}@~q zPzW6c*s~@rK5)Z^C5aVah45BWdnd8F(gmGuH+C+%Kp8GEefQWw9AfG3#}V5WuP-b{ z+#s8vW(s0uNa_eU2`-2-KpD>3hQ;$$9t;EE#BB-(N|rEN(d-B~I4^+ity8*!$Xi8# zfYRQ-r+Q>pqa)yTGmhPQd8>0y=>iSa)rrUwiy2)>O@$iAnHnB>b+3lTP$m*tIr!RH zAfi|^LkepvrX%fux^Q`tsX}Ej=cJ3?))I+V&4K-mK#l?>o`qyn`fe-S!T(J--aSx^ zMx3A{yy-M(udH$NpCSu{C&n&IKg*z@h*qJ~lYZuRj<*E8eq-vyc`NhO0BX~>aD<;I zl=M@A0}URjmA*AI0p&(NM(8@EjINV^532l2ZbJBOM-5M>@RFDgnN>I2?Fjf<)02R? z^?MpgtTh}zL|_C@a`Dov)|=2|Al&-wgEQo98_$3staj?<-9qcy#ILSNtN;}zMq&wL zlV&BJAhZ1xTM1fvaSfYSOsm5fPi`2 zP|e~%cv|NGfq!P0Tow|QwQ;s&UFdrLrF8M~d!^{m$icjd_MRY!^GgTlr&-M;AWPD$ zej_SS_GI!g1^mc=m=C81c3~uLjo&xoM_W(?rBq)P()9AO-Nh3NI7cMPdAUBmEaB!ROC#ur{Sx9E>{);^$XktjMv%B_q&>z@L@s}`Lv7*! zfVMSPaObCJ+AW*du1r@Hh`la=rfMZHDX43;RBSd?Y$EdT;cwX2$t!00_A%3bp0LV_ z)y|8eX0BS#iWO%@h#4EW_wS`J)%|W^ zilJS^RFdTa$%glH_Bn2qzV4s{-i_JqA)gM$RU?8#Ry#$f)?6zUZ4kyN5nu1?T3{Bi^3t zqobQ@IbxDlPb>xdYIqU~_-`T5@>FbgzT;ma|I>(k3&*Y2LbsldJJ}$3!rk!v%vgbQ5wb`!uA{>|VAp8_w}E-S({=jcrC{Ra@9 z&`+a|7}-7EhwgevM8Ivcx~YI2#GA%XbYBUz$!1xYL;74%$Q(HexEMrQ?51~*S6I53 z2!LlU{yJHV=&APDBvI|3o!L*Cjv?GwKl=1}lBI_al_KftEI-kNXCa4%_93`JCe5nP zNo7>n(>PtGmr4^GD^K72rF=hJ@K02fJ6e3WCJtzYY7*H7LT3Mk7fEvJ0LI{F6R*XO zU1FNskB0Yuxtm>iWIM(cr)S&}OIaO}i?7KAsD zrlae^G`Ec>=z9`9;f*u5L(IIrbw`DV_p!1qU4Y$BF}6<-1O@cd>Sr8Bg{=yC7(4mn zmL`t_5TL8W&dJG%CSqjUtCpwMQIe>$(Ru!S4|AbVD6kYA;X;o!&>i4ZZs>(3gwO*w z<8%S!=IK?OXKfK+{>Bv0(b4gDznt0e0!~|>kArBooN%tH_-ajCT){J>ft9tLx=6Px zT~GC9lMKl+qOG+x0Dv9rCG*=%Kgjpr1CEeR_97A1hZ(|^`SwzjaTg#gqa_<0i6fs* zOG7B0mhKz zSq&T#*9>doWdL=9)=WtFo{CT?%6cuJAXh_@lB=*{6GQ#ZtseE?tzK;DP4 zA3Yuh{(4QB+mAj%@z=yMx9w)3Ua{)YRU9hEZ%omY?8f^d;o zd=wV_6l)L61DyD|-D3e)JjjMMl;K73Xx>DFmIzvKDjBhgraw7cA1%&t@6Om-RvE2( zCMSU+wZinx|0u8@tQp*I0oVYGE>yTOR1vaKwt`ciT=!3Yn$bk8JhU@YH^DsmhdJAo zx;W76Aku(*C|Y#!0T&$xolcluPDowyja%B2#zuquSgxdZ7zv0GWT_T|q?i~TpsblA zGyXUF9A{E1^#Hz2M|nr{o_yl0T6`2RFaS4+eIp}N4ZU=|3?#vgtHw5~Tyh*PAx!G+ z+Dv$f74g@%mc_0?%78)CA%6KYlo+!rb(xQUHVo9*#ozLwa^Q01dV{s_3}g)5_496iJ>h86N?82 zteYDR%UZg(aR{dyB@b zm||8+E89*%CNhi!Y>~4wz)2?}CZ_L+Uit^l=gPigRWc|~L!nlfgo%Jf*~d^A8hTya zRbj%DWjX*87e&{D02v|RQnzDHH$f_vlCPtKp0ESp(wkHsgLLJ<9gQuSTM$oo0N_h} z`G;8U;0r#ZKLFd8!u(qT@S1czAmp37B&JT*XW_SE2YYanxr1LACN#Xi=rZZl2=s|p zGZ4-J|Nblj(~n(H`GW-fCjEN|MDE~l!ZhgOa6;~2698yl94{W)?3P5G3s^sUWb zDL3DA5ov5S<3S(}yD3bp1%d6RjyMpAo?qXm%Rf`> z40EH^$CitDSj+2u<_9@ku4zn9DfQ%4yu+IRDkn3BkkJFSW@~HwygKj|YR<$1orjlO zDnKqhxZc}D{$q195Pl%K?ZR~rQWgeo2G+{9-vSAfQqdu%Q(=^-asR=*hqkZcFrh4X z1>^2Yle`F5W<2BH<(lViRuMN%M@6t(cklNAUF3~JkfFC6Us%`EAqFqMetG>5-Hlrv UzBJ(876?R1URAC_)-2@z0Q_wY<^TWy literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp index 8b03fa66eab55..b7cd55ce2e642 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp @@ -15,74 +15,117 @@ #include "calculate_slowdown_points.hpp" #include "footprint.hpp" +#include "types.hpp" #include #include +#include -#include +#include +#include +#include +#include + +#include #include +#include +#include +#include + namespace autoware::motion_velocity_planner::out_of_lane { -bool can_decelerate( - const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel) +std::optional calculate_last_avoiding_pose( + const std::vector & trajectory, + const universe_utils::Polygon2d & footprint, const lanelet::BasicPolygons2d & polygons_to_avoid, + const double min_arc_length, const double max_arc_length, const double precision) { - // TODO(Maxime): use the library function - const auto dist_ahead_of_ego = autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, ego_data.pose.position, point.pose.position); - const auto acc_to_target_vel = - (ego_data.velocity * ego_data.velocity - target_vel * target_vel) / (2 * dist_ahead_of_ego); - return acc_to_target_vel < std::abs(ego_data.max_decel); + geometry_msgs::msg::Pose interpolated_pose{}; + bool is_avoiding_pose = false; + + auto from = min_arc_length; + auto to = max_arc_length; + while (to - from > precision) { + auto l = from + 0.5 * (to - from); + interpolated_pose = motion_utils::calcInterpolatedPose(trajectory, l); + const auto interpolated_footprint = project_to_pose(footprint, interpolated_pose); + is_avoiding_pose = + std::all_of(polygons_to_avoid.begin(), polygons_to_avoid.end(), [&](const auto & polygon) { + return boost::geometry::disjoint(interpolated_footprint, polygon); + }); + if (is_avoiding_pose) { + from = l; + } else { + to = l; + } + } + if (is_avoiding_pose) { + return interpolated_pose; + } + return std::nullopt; } -std::optional calculate_last_in_lane_pose( - const EgoData & ego_data, const Slowdown & decision, - const autoware::universe_utils::Polygon2d & footprint, - const std::optional & prev_slowdown_point, const PlannerParam & params) +std::optional calculate_pose_ahead_of_collision( + const EgoData & ego_data, const OutOfLanePoint & point_to_avoid, + const universe_utils::Polygon2d & footprint, const double precision) { - const auto from_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, 0, ego_data.first_trajectory_idx); - const auto to_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, 0, decision.target_trajectory_idx); - TrajectoryPoint interpolated_point; - for (auto l = to_arc_length - params.precision; l > from_arc_length; l -= params.precision) { - // TODO(Maxime): binary search - interpolated_point.pose = - autoware::motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); - const auto respect_decel_limit = - !params.skip_if_over_max_decel || prev_slowdown_point || - can_decelerate(ego_data, interpolated_point, decision.velocity); - const auto interpolated_footprint = project_to_pose(footprint, interpolated_point.pose); - const auto is_overlap_lane = boost::geometry::overlaps( - interpolated_footprint, decision.lane_to_avoid.polygon2d().basicPolygon()); - const auto is_overlap_extra_lane = - prev_slowdown_point && - boost::geometry::overlaps( - interpolated_footprint, - prev_slowdown_point->slowdown.lane_to_avoid.polygon2d().basicPolygon()); - if (respect_decel_limit && !is_overlap_lane && !is_overlap_extra_lane) - return interpolated_point; + const auto first_avoid_arc_length = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, 0UL, point_to_avoid.trajectory_index); + for (auto l = first_avoid_arc_length - precision; l >= ego_data.min_stop_arc_length; + l -= precision) { + const auto interpolated_pose = + motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); + const auto interpolated_footprint = project_to_pose(footprint, interpolated_pose); + if (boost::geometry::intersects(interpolated_footprint, point_to_avoid.outside_ring)) { + return interpolated_pose; + } } return std::nullopt; } -std::optional calculate_slowdown_point( - const EgoData & ego_data, const std::vector & decisions, - const std::optional & prev_slowdown_point, PlannerParam params) +std::optional calculate_slowdown_point( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, PlannerParam params) { + const auto point_to_avoid_it = std::find_if( + out_of_lane_data.outside_points.cbegin(), out_of_lane_data.outside_points.cend(), + [&](const auto & p) { return p.to_avoid; }); + if (point_to_avoid_it == out_of_lane_data.outside_points.cend()) { + return std::nullopt; + } + const auto raw_footprint = make_base_footprint(params, true); // ignore extra footprint offsets + const auto base_footprint = make_base_footprint(params); params.extra_front_offset += params.lon_dist_buffer; params.extra_right_offset += params.lat_dist_buffer; params.extra_left_offset += params.lat_dist_buffer; - const auto base_footprint = make_base_footprint(params); + const auto expanded_footprint = make_base_footprint(params); // with added distance buffers + lanelet::BasicPolygons2d polygons_to_avoid; + for (const auto & ll : point_to_avoid_it->overlapped_lanelets) { + polygons_to_avoid.push_back(ll.polygon2d().basicPolygon()); + } + // points are ordered by trajectory index so the first one has the smallest index and arc length + const auto first_outside_idx = out_of_lane_data.outside_points.front().trajectory_index; + const auto first_outside_arc_length = + motion_utils::calcSignedArcLength(ego_data.trajectory_points, 0UL, first_outside_idx); + std::optional slowdown_point; // search for the first slowdown decision for which a stop point can be inserted - for (const auto & decision : decisions) { - const auto last_in_lane_pose = - calculate_last_in_lane_pose(ego_data, decision, base_footprint, prev_slowdown_point, params); - if (last_in_lane_pose) return SlowdownToInsert{decision, *last_in_lane_pose}; + // we first try to use the expanded footprint (distance buffers + extra footprint offsets) + for (const auto & footprint : {expanded_footprint, base_footprint, raw_footprint}) { + slowdown_point = calculate_last_avoiding_pose( + ego_data.trajectory_points, footprint, polygons_to_avoid, ego_data.min_stop_arc_length, + first_outside_arc_length, params.precision); + if (slowdown_point) { + break; + } } - return std::nullopt; + // fallback to simply stopping ahead of the collision to avoid (regardless of being out of lane or + // not) + if (!slowdown_point) { + slowdown_point = calculate_pose_ahead_of_collision( + ego_data, *point_to_avoid_it, expanded_footprint, params.precision); + } + return slowdown_point; } } // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp index 145f21c94c0d0..394334d434558 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp @@ -19,40 +19,39 @@ #include +#include + #include -#include namespace autoware::motion_velocity_planner::out_of_lane { - -/// @brief estimate whether ego can decelerate without breaking the deceleration limit -/// @details assume ego wants to reach the target point at the target velocity -/// @param [in] ego_data ego data -/// @param [in] point target point -/// @param [in] target_vel target_velocity -bool can_decelerate( - const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel); - -/// @brief calculate the last pose along the trajectory where ego does not overlap the lane to avoid +/// @brief calculate the last pose along the trajectory where ego does not go out of lane /// @param [in] ego_data ego data -/// @param [in] decision the input decision (i.e., which lane to avoid and at what speed) /// @param [in] footprint the ego footprint -/// @param [in] prev_slowdown_point previous slowdown point. If set, ignore deceleration limits -/// @param [in] params parameters +/// @param [in] min_arc_length minimum arc length for the search +/// @param [in] max_arc_length maximum arc length for the search +/// @param [in] precision [m] search precision /// @return the last pose that is not out of lane (if found) -std::optional calculate_last_in_lane_pose( - const EgoData & ego_data, const Slowdown & decision, - const autoware::universe_utils::Polygon2d & footprint, - const std::optional & prev_slowdown_point, const PlannerParam & params); +std::optional calculate_last_in_lane_pose( + const EgoData & ego_data, const autoware::universe_utils::Polygon2d & footprint, + const double min_arc_length, const double max_arc_length, const double precision); + +/// @brief calculate the slowdown pose just ahead of a point to avoid +/// @param ego_data ego data (trajectory, velocity, etc) +/// @param point_to_avoid the point to avoid +/// @param footprint the ego footprint +/// @param params parameters +/// @return optional slowdown point to insert in the trajectory +std::optional calculate_pose_ahead_of_collision( + const EgoData & ego_data, const OutOfLanePoint & point_to_avoid, + const universe_utils::Polygon2d & footprint, const double precision); /// @brief calculate the slowdown point to insert in the trajectory /// @param ego_data ego data (trajectory, velocity, etc) -/// @param decisions decision (before which point to stop, what lane to avoid entering, etc) -/// @param prev_slowdown_point previously calculated slowdown point +/// @param out_of_lane_data data about out of lane areas /// @param params parameters /// @return optional slowdown point to insert in the trajectory -std::optional calculate_slowdown_point( - const EgoData & ego_data, const std::vector & decisions, - const std::optional & prev_slowdown_point, PlannerParam params); +std::optional calculate_slowdown_point( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, PlannerParam params); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // CALCULATE_SLOWDOWN_POINTS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp index d9a85e266f790..6febd15ef8052 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp @@ -16,12 +16,26 @@ #include "types.hpp" +#include +#include +#include #include +#include +#include +#include +#include #include +#include +#include + +#include +#include +#include +#include + #include -#include namespace autoware::motion_velocity_planner::out_of_lane::debug { @@ -36,209 +50,186 @@ visualization_msgs::msg::Marker get_base_marker() base_marker.id = 0; base_marker.type = visualization_msgs::msg::Marker::LINE_STRIP; base_marker.action = visualization_msgs::msg::Marker::ADD; - base_marker.pose.position = autoware::universe_utils::createMarkerPosition(0.0, 0.0, 0); - base_marker.pose.orientation = autoware::universe_utils::createMarkerOrientation(0, 0, 0, 1.0); - base_marker.scale = autoware::universe_utils::createMarkerScale(0.1, 0.1, 0.1); - base_marker.color = autoware::universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); + base_marker.pose.position = universe_utils::createMarkerPosition(0.0, 0.0, 0); + base_marker.pose.orientation = universe_utils::createMarkerOrientation(0, 0, 0, 1.0); + base_marker.scale = universe_utils::createMarkerScale(0.1, 0.1, 0.1); + base_marker.color = universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); return base_marker; } -void add_footprint_markers( +void add_polygons_markers( visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb) + const visualization_msgs::msg::Marker & base_marker, const lanelet::BasicPolygons2d & polygons) { - auto debug_marker = get_base_marker(); - debug_marker.ns = "footprints"; - for (const auto & f : footprints) { - debug_marker.points.clear(); - for (const auto & p : f) - debug_marker.points.push_back( - autoware::universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); - debug_marker.points.push_back(debug_marker.points.front()); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - debug_marker.points.clear(); + auto debug_marker = base_marker; + debug_marker.type = visualization_msgs::msg::Marker::LINE_LIST; + for (const auto & f : polygons) { + boost::geometry::for_each_segment(f, [&](const auto & s) { + const auto & [p1, p2] = s; + debug_marker.points.push_back(universe_utils::createMarkerPosition(p1.x(), p1.y(), 0.0)); + debug_marker.points.push_back(universe_utils::createMarkerPosition(p2.x(), p2.y(), 0.0)); + }); } - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); + debug_marker_array.markers.push_back(debug_marker); } void add_current_overlap_marker( visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygon2d & current_footprint, - const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb) + const lanelet::BasicPolygon2d & current_footprint, const double z) { auto debug_marker = get_base_marker(); debug_marker.ns = "current_overlap"; debug_marker.points.clear(); for (const auto & p : current_footprint) - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition(p.x(), p.y(), z)); + debug_marker.points.push_back(universe_utils::createMarkerPosition(p.x(), p.y(), z)); if (!debug_marker.points.empty()) debug_marker.points.push_back(debug_marker.points.front()); - if (current_overlapped_lanelets.empty()) - debug_marker.color = autoware::universe_utils::createMarkerColor(0.1, 1.0, 0.1, 0.5); - else - debug_marker.color = autoware::universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); + debug_marker.color = universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); debug_marker_array.markers.push_back(debug_marker); debug_marker.id++; - for (const auto & ll : current_overlapped_lanelets) { - debug_marker.points.clear(); - for (const auto & p : ll.polygon3d()) - debug_marker.points.push_back( - autoware::universe_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.5)); - debug_marker.points.push_back(debug_marker.points.front()); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - } - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); -} - -void add_lanelet_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::ConstLanelets & lanelets, const std::string & ns, - const std_msgs::msg::ColorRGBA & color, const size_t prev_nb) -{ - auto debug_marker = get_base_marker(); - debug_marker.ns = ns; - debug_marker.color = color; - for (const auto & ll : lanelets) { - debug_marker.points.clear(); - - // add a small z offset to draw above the lanelet map - for (const auto & p : ll.polygon3d()) - debug_marker.points.push_back( - autoware::universe_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.1)); - debug_marker.points.push_back(debug_marker.points.front()); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - } - debug_marker.action = debug_marker.DELETE; - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); } -void add_range_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, - const std::vector & trajectory_points, - const size_t first_ego_idx, const double z, const size_t prev_nb) +void add_ttc_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, const EgoData & ego_data, + const OutOfLaneData & out_of_lane_data, const size_t prev_nb) { auto debug_marker = get_base_marker(); - debug_marker.ns = "ranges"; - debug_marker.color = autoware::universe_utils::createMarkerColor(0.2, 0.9, 0.1, 0.5); - for (const auto & range : ranges) { - debug_marker.points.clear(); - debug_marker.points.push_back( - trajectory_points[first_ego_idx + range.entering_trajectory_idx].pose.position); - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - range.entering_point.x(), range.entering_point.y(), z)); - for (const auto & overlap : range.debug.overlaps) { - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - overlap.min_overlap_point.x(), overlap.min_overlap_point.y(), z)); - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - overlap.max_overlap_point.x(), overlap.max_overlap_point.y(), z)); + debug_marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + debug_marker.scale.z = 0.5; + debug_marker.ns = "ttcs"; + for (const auto & p : out_of_lane_data.outside_points) { + if (p.to_avoid) { + debug_marker.color.r = 1.0; + debug_marker.color.g = 0.0; + } else { + debug_marker.color.r = 0.0; + debug_marker.color.g = 1.0; + } + if (p.ttc) { + debug_marker.pose = ego_data.trajectory_points[p.trajectory_index].pose; + debug_marker.text = std::to_string(*p.ttc); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; } - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - range.exiting_point.x(), range.exiting_point.y(), z)); - debug_marker.points.push_back( - trajectory_points[first_ego_idx + range.exiting_trajectory_idx].pose.position); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; } - debug_marker.action = debug_marker.DELETE; - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker.action = visualization_msgs::msg::Marker::DELETE; + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) { debug_marker_array.markers.push_back(debug_marker); + } } - -void add_decision_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, +size_t add_stop_line_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, const StopLinesRtree & rtree, const double z, const size_t prev_nb) { auto debug_marker = get_base_marker(); - debug_marker.action = debug_marker.ADD; - debug_marker.id = 0; - debug_marker.ns = "decisions"; - debug_marker.color = autoware::universe_utils::createMarkerColor(0.9, 0.1, 0.1, 1.0); - debug_marker.points.clear(); - for (const auto & range : ranges) { - debug_marker.type = debug_marker.LINE_STRIP; - if (range.debug.decision) { - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - range.entering_point.x(), range.entering_point.y(), z)); - debug_marker.points.push_back( - range.debug.object->kinematics.initial_pose_with_covariance.pose.position); + debug_marker.type = visualization_msgs::msg::Marker::LINE_STRIP; + debug_marker.ns = "stop_lines"; + const auto & add_lanelets_markers = [&](const auto & lanelets) { + for (const auto & ll : lanelets) { + debug_marker.points.clear(); + for (const auto & p : ll.polygon2d().basicPolygon()) { + debug_marker.points.push_back(universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); + } + debug_marker.points.push_back(debug_marker.points.front()); + debug_marker_array.markers.push_back(debug_marker); + ++debug_marker.id; } - debug_marker_array.markers.push_back(debug_marker); + }; + for (const auto & [_, stop_line] : rtree) { debug_marker.points.clear(); - debug_marker.id++; - - debug_marker.type = debug_marker.TEXT_VIEW_FACING; - debug_marker.pose.position.x = range.entering_point.x(); - debug_marker.pose.position.y = range.entering_point.y(); - debug_marker.pose.position.z = z; - std::stringstream ss; - ss << "Ego: " << range.debug.times.ego.enter_time << " - " << range.debug.times.ego.exit_time - << "\n"; - if (range.debug.object) { - debug_marker.pose.position.x += - range.debug.object->kinematics.initial_pose_with_covariance.pose.position.x; - debug_marker.pose.position.y += - range.debug.object->kinematics.initial_pose_with_covariance.pose.position.y; - debug_marker.pose.position.x /= 2; - debug_marker.pose.position.y /= 2; - ss << "Obj: " << range.debug.times.object.enter_time << " - " - << range.debug.times.object.exit_time << "\n"; + debug_marker.color.r = 1.0; + for (const auto & p : stop_line.stop_line) { + debug_marker.points.push_back(universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); } - debug_marker.scale.z = 1.0; - debug_marker.text = ss.str(); debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; + ++debug_marker.id; + debug_marker.color.r = 0.0; + add_lanelets_markers(stop_line.lanelets); } - debug_marker.action = debug_marker.DELETE; + const auto max_id = debug_marker.id; + debug_marker.action = visualization_msgs::msg::Marker::DELETE; for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) { debug_marker_array.markers.push_back(debug_marker); } + return max_id; } } // namespace -visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & debug_data) + +visualization_msgs::msg::MarkerArray create_debug_marker_array( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedObjects & objects, DebugData & debug_data) { - constexpr auto z = 0.0; + const auto z = ego_data.pose.position.z; visualization_msgs::msg::MarkerArray debug_marker_array; - debug::add_footprint_markers( - debug_marker_array, debug_data.footprints, z, debug_data.prev_footprints); - debug::add_current_overlap_marker( - debug_marker_array, debug_data.current_footprint, debug_data.current_overlapped_lanelets, z, - debug_data.prev_current_overlapped_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data.trajectory_lanelets, "trajectory_lanelets", - autoware::universe_utils::createMarkerColor(0.1, 0.1, 1.0, 0.5), - debug_data.prev_trajectory_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data.ignored_lanelets, "ignored_lanelets", - autoware::universe_utils::createMarkerColor(0.7, 0.7, 0.2, 0.5), - debug_data.prev_ignored_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data.other_lanelets, "other_lanelets", - autoware::universe_utils::createMarkerColor(0.4, 0.4, 0.7, 0.5), - debug_data.prev_other_lanelets); - debug::add_range_markers( - debug_marker_array, debug_data.ranges, debug_data.trajectory_points, - debug_data.first_trajectory_idx, z, debug_data.prev_ranges); - debug::add_decision_markers(debug_marker_array, debug_data.ranges, z, debug_data.prev_ranges); + auto base_marker = get_base_marker(); + base_marker.pose.position.z = z + 0.5; + base_marker.ns = "footprints"; + base_marker.color = universe_utils::createMarkerColor(1.0, 1.0, 1.0, 1.0); + // TODO(Maxime): move the debug marker publishing AFTER the trajectory generation + // disabled to prevent performance issues when publishing the debug markers + // add_polygons_markers(debug_marker_array, base_marker, ego_data.trajectory_footprints); + + lanelet::BasicPolygons2d drivable_lane_polygons; + for (const auto & poly : ego_data.drivable_lane_polygons) { + drivable_lane_polygons.push_back(poly.outer); + } + base_marker.ns = "ego_lane"; + base_marker.color = universe_utils::createMarkerColor(0.0, 0.0, 1.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, drivable_lane_polygons); + + lanelet::BasicPolygons2d out_of_lane_areas; + for (const auto & p : out_of_lane_data.outside_points) { + out_of_lane_areas.push_back(p.outside_ring); + } + base_marker.ns = "out_of_lane_areas"; + base_marker.color = universe_utils::createMarkerColor(1.0, 0.0, 0.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, out_of_lane_areas); + for (const auto & [bbox, i] : out_of_lane_data.outside_areas_rtree) { + const auto & a = out_of_lane_data.outside_points[i]; + debug_marker_array.markers.back().points.push_back( + ego_data.trajectory_points[a.trajectory_index].pose.position); + const auto centroid = boost::geometry::return_centroid(a.outside_ring); + debug_marker_array.markers.back().points.push_back( + geometry_msgs::msg::Point().set__x(centroid.x()).set__y(centroid.y())); + } + + lanelet::BasicPolygons2d object_polygons; + for (const auto & o : objects.objects) { + for (const auto & path : o.kinematics.predicted_paths) { + for (const auto & pose : path.path) { + // limit the draw distance to improve performance + if (universe_utils::calcDistance2d(pose, ego_data.pose) < 50.0) { + const auto poly = universe_utils::toPolygon2d(pose, o.shape).outer(); + lanelet::BasicPolygon2d ll_poly(poly.begin(), poly.end()); + object_polygons.push_back(ll_poly); + } + } + } + } + base_marker.ns = "objects"; + base_marker.color = universe_utils::createMarkerColor(0.0, 1.0, 0.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, object_polygons); + + add_current_overlap_marker(debug_marker_array, ego_data.current_footprint, z); + + add_ttc_markers(debug_marker_array, ego_data, out_of_lane_data, debug_data.prev_ttcs); + debug_data.prev_ttcs = out_of_lane_data.outside_points.size(); + + debug_data.prev_stop_line = add_stop_line_markers( + debug_marker_array, ego_data.stop_lines_rtree, z, debug_data.prev_stop_line); + return debug_marker_array; } -autoware::motion_utils::VirtualWalls create_virtual_walls( - const DebugData & debug_data, const PlannerParam & params) +motion_utils::VirtualWalls create_virtual_walls( + const geometry_msgs::msg::Pose & pose, const bool stop, const PlannerParam & params) { - autoware::motion_utils::VirtualWalls virtual_walls; - autoware::motion_utils::VirtualWall wall; + motion_utils::VirtualWalls virtual_walls; + motion_utils::VirtualWall wall; wall.text = "out_of_lane"; wall.longitudinal_offset = params.front_offset; - wall.style = autoware::motion_utils::VirtualWallType::slowdown; - for (const auto & slowdown : debug_data.slowdowns) { - wall.pose = slowdown.point.pose; - virtual_walls.push_back(wall); - } + wall.style = stop ? motion_utils::VirtualWallType::stop : motion_utils::VirtualWallType::slowdown; + wall.pose = pose; + virtual_walls.push_back(wall); return virtual_walls; } } // namespace autoware::motion_velocity_planner::out_of_lane::debug diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp index ea225442443c8..dc1f942655612 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp @@ -23,9 +23,11 @@ namespace autoware::motion_velocity_planner::out_of_lane::debug { -visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & debug_data); -autoware::motion_utils::VirtualWalls create_virtual_walls( - const DebugData & debug_data, const PlannerParam & params); +visualization_msgs::msg::MarkerArray create_debug_marker_array( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedObjects & objects, DebugData & debug_data); +motion_utils::VirtualWalls create_virtual_walls( + const geometry_msgs::msg::Pose & pose, const bool stop, const PlannerParam & params); } // namespace autoware::motion_velocity_planner::out_of_lane::debug #endif // DEBUG_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp deleted file mode 100644 index fc487a2626b88..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp +++ /dev/null @@ -1,389 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "decisions.hpp" - -#include -#include -#include -#include - -#include - -#include -#include -#include - -#include -#include -#include -#include -namespace autoware::motion_velocity_planner::out_of_lane -{ -double distance_along_trajectory(const EgoData & ego_data, const size_t target_idx) -{ - return autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, ego_data.pose.position, ego_data.first_trajectory_idx + target_idx); -} - -double time_along_trajectory( - const EgoData & ego_data, const size_t target_idx, const double min_velocity) -{ - const auto dist = distance_along_trajectory(ego_data, target_idx); - const auto v = std::max( - std::max(ego_data.velocity, min_velocity), - ego_data.trajectory_points[ego_data.first_trajectory_idx + target_idx] - .longitudinal_velocity_mps * - 0.5); - return dist / v; -} - -bool object_is_incoming( - const lanelet::BasicPoint2d & object_position, - const std::shared_ptr route_handler, - const lanelet::ConstLanelet & lane) -{ - const auto lanelets = route_handler->getPrecedingLaneletSequence(lane, 50.0); - if (boost::geometry::within(object_position, lane.polygon2d().basicPolygon())) return true; - for (const auto & lls : lanelets) - for (const auto & ll : lls) - if (boost::geometry::within(object_position, ll.polygon2d().basicPolygon())) return true; - return false; -} - -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const double dist_buffer, - const rclcpp::Logger & logger) -{ - // skip the dynamic object if it is not in a lane preceding the overlapped lane - // lane changes are intentionally not considered - const auto object_point = lanelet::BasicPoint2d( - object.kinematics.initial_pose_with_covariance.pose.position.x, - object.kinematics.initial_pose_with_covariance.pose.position.y); - if (!object_is_incoming(object_point, route_handler, range.lane)) return {}; - - const auto max_deviation = object.shape.dimensions.y + range.inside_distance + dist_buffer; - const auto max_lon_deviation = object.shape.dimensions.x / 2.0; - auto worst_enter_time = std::optional(); - auto worst_exit_time = std::optional(); - - for (const auto & predicted_path : object.kinematics.predicted_paths) { - const auto unique_path_points = - autoware::motion_utils::removeOverlapPoints(predicted_path.path); - if (unique_path_points.size() < 2) continue; - const auto time_step = rclcpp::Duration(predicted_path.time_step).seconds(); - const auto enter_point = - geometry_msgs::msg::Point().set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto enter_segment_idx = - autoware::motion_utils::findNearestSegmentIndex(unique_path_points, enter_point); - const auto enter_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( - unique_path_points, enter_segment_idx, enter_point); - const auto enter_lat_dist = std::abs(autoware::motion_utils::calcLateralOffset( - unique_path_points, enter_point, enter_segment_idx)); - const auto enter_segment_length = autoware::universe_utils::calcDistance2d( - unique_path_points[enter_segment_idx], unique_path_points[enter_segment_idx + 1]); - const auto enter_offset_ratio = enter_offset / enter_segment_length; - const auto enter_time = - static_cast(enter_segment_idx) * time_step + enter_offset_ratio * time_step; - - const auto exit_point = - geometry_msgs::msg::Point().set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto exit_segment_idx = - autoware::motion_utils::findNearestSegmentIndex(unique_path_points, exit_point); - const auto exit_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( - unique_path_points, exit_segment_idx, exit_point); - const auto exit_lat_dist = std::abs( - autoware::motion_utils::calcLateralOffset(unique_path_points, exit_point, exit_segment_idx)); - const auto exit_segment_length = autoware::universe_utils::calcDistance2d( - unique_path_points[exit_segment_idx], unique_path_points[exit_segment_idx + 1]); - const auto exit_offset_ratio = exit_offset / static_cast(exit_segment_length); - const auto exit_time = - static_cast(exit_segment_idx) * time_step + exit_offset_ratio * time_step; - - RCLCPP_DEBUG( - logger, "\t\t\tPredicted path (time step = %2.2fs): enter @ %2.2fs, exit @ %2.2fs", time_step, - enter_time, exit_time); - // predicted path is too far from the overlapping range to be relevant - const auto is_far_from_entering_point = enter_lat_dist > max_deviation; - const auto is_far_from_exiting_point = exit_lat_dist > max_deviation; - if (is_far_from_entering_point && is_far_from_exiting_point) { - RCLCPP_DEBUG( - logger, - " * far_from_enter (%d) = %2.2fm | far_from_exit (%d) = %2.2fm | max_dev = %2.2fm\n", - is_far_from_entering_point, enter_lat_dist, is_far_from_exiting_point, exit_lat_dist, - max_deviation); - continue; - } - const auto is_last_predicted_path_point = - (exit_segment_idx + 2 == unique_path_points.size() || - enter_segment_idx + 2 == unique_path_points.size()); - const auto does_not_reach_overlap = - is_last_predicted_path_point && (std::min(exit_offset, enter_offset) > max_lon_deviation); - if (does_not_reach_overlap) { - RCLCPP_DEBUG( - logger, " * does not reach the overlap = %2.2fm | max_dev = %2.2fm\n", - std::min(exit_offset, enter_offset), max_lon_deviation); - continue; - } - - const auto same_driving_direction_as_ego = enter_time < exit_time; - if (same_driving_direction_as_ego) { - worst_enter_time = worst_enter_time ? std::min(*worst_enter_time, enter_time) : enter_time; - worst_exit_time = worst_exit_time ? std::max(*worst_exit_time, exit_time) : exit_time; - } else { - worst_enter_time = worst_enter_time ? std::max(*worst_enter_time, enter_time) : enter_time; - worst_exit_time = worst_exit_time ? std::min(*worst_exit_time, exit_time) : exit_time; - } - } - if (worst_enter_time && worst_exit_time) { - RCLCPP_DEBUG( - logger, "\t\t\t * found enter/exit time [%2.2f, %2.2f]\n", *worst_enter_time, - *worst_exit_time); - return std::make_pair(*worst_enter_time, *worst_exit_time); - } - RCLCPP_DEBUG(logger, "\t\t\t * enter/exit time not found\n"); - return {}; -} - -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const DecisionInputs & inputs, const rclcpp::Logger & logger) -{ - const auto & p = object.kinematics.initial_pose_with_covariance.pose.position; - const auto object_point = lanelet::BasicPoint2d(p.x, p.y); - const auto half_size = object.shape.dimensions.x / 2.0; - lanelet::ConstLanelets object_lanelets; - for (const auto & ll : inputs.lanelets) - if (boost::geometry::within(object_point, ll.polygon2d().basicPolygon())) - object_lanelets.push_back(ll); - - geometry_msgs::msg::Pose pose; - pose.position.set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto range_enter_length = lanelet::utils::getArcCoordinates({range.lane}, pose).length; - pose.position.set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto range_exit_length = lanelet::utils::getArcCoordinates({range.lane}, pose).length; - const auto range_size = std::abs(range_enter_length - range_exit_length); - auto worst_enter_dist = std::optional(); - auto worst_exit_dist = std::optional(); - for (const auto & lane : object_lanelets) { - const auto path = inputs.route_handler->getRoutingGraphPtr()->shortestPath(lane, range.lane); - RCLCPP_DEBUG( - logger, "\t\t\tPath ? %d [from %ld to %ld]\n", path.has_value(), lane.id(), range.lane.id()); - if (path) { - lanelet::ConstLanelets lls; - for (const auto & ll : *path) lls.push_back(ll); - pose.position.set__x(object_point.x()).set__y(object_point.y()); - const auto object_curr_length = lanelet::utils::getArcCoordinates(lls, pose).length; - pose.position.set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto enter_dist = - lanelet::utils::getArcCoordinates(lls, pose).length - object_curr_length; - pose.position.set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto exit_dist = - lanelet::utils::getArcCoordinates(lls, pose).length - object_curr_length; - RCLCPP_DEBUG( - logger, "\t\t\t%2.2f -> [%2.2f(%2.2f, %2.2f) - %2.2f(%2.2f, %2.2f)]\n", object_curr_length, - enter_dist, range.entering_point.x(), range.entering_point.y(), exit_dist, - range.exiting_point.x(), range.exiting_point.y()); - const auto already_entered_range = std::abs(enter_dist - exit_dist) > range_size * 2.0; - if (already_entered_range) continue; - // multiple paths to the overlap -> be conservative and use the "worst" case - // "worst" = min/max arc length depending on if the lane is running opposite to the ego - // trajectory - const auto is_opposite = enter_dist > exit_dist; - if (!worst_enter_dist) - worst_enter_dist = enter_dist; - else if (is_opposite) - worst_enter_dist = std::max(*worst_enter_dist, enter_dist); - else - worst_enter_dist = std::min(*worst_enter_dist, enter_dist); - if (!worst_exit_dist) - worst_exit_dist = exit_dist; - else if (is_opposite) - worst_exit_dist = std::max(*worst_exit_dist, exit_dist); - else - worst_exit_dist = std::min(*worst_exit_dist, exit_dist); - } - } - if (worst_enter_dist && worst_exit_dist) { - const auto v = object.kinematics.initial_twist_with_covariance.twist.linear.x; - return std::make_pair((*worst_enter_dist - half_size) / v, (*worst_exit_dist + half_size) / v); - } - return {}; -} - -bool threshold_condition(const RangeTimes & range_times, const PlannerParam & params) -{ - const auto enter_within_threshold = - range_times.object.enter_time > 0.0 && range_times.object.enter_time < params.time_threshold; - const auto exit_within_threshold = - range_times.object.exit_time > 0.0 && range_times.object.exit_time < params.time_threshold; - return enter_within_threshold || exit_within_threshold; -} - -bool intervals_condition( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - const auto opposite_way_condition = [&]() -> bool { - const auto ego_exits_before_object_enters = - range_times.ego.exit_time + params.intervals_ego_buffer < - range_times.object.enter_time + params.intervals_obj_buffer; - RCLCPP_DEBUG( - logger, - "\t\t\t[Intervals] (opposite way) ego exit %2.2fs < obj enter %2.2fs ? -> should not " - "enter = %d\n", - range_times.ego.exit_time + params.intervals_ego_buffer, - range_times.object.enter_time + params.intervals_obj_buffer, ego_exits_before_object_enters); - return ego_exits_before_object_enters; - }; - const auto same_way_condition = [&]() -> bool { - const auto object_enters_during_overlap = - range_times.ego.enter_time - params.intervals_ego_buffer < - range_times.object.enter_time + params.intervals_obj_buffer && - range_times.object.enter_time - params.intervals_obj_buffer - range_times.ego.exit_time < - range_times.ego.exit_time + params.intervals_ego_buffer; - const auto object_exits_during_overlap = - range_times.ego.enter_time - params.intervals_ego_buffer < - range_times.object.exit_time + params.intervals_obj_buffer && - range_times.object.exit_time - params.intervals_obj_buffer - range_times.ego.exit_time < - range_times.ego.exit_time + params.intervals_ego_buffer; - RCLCPP_DEBUG( - logger, - "\t\t\t[Intervals] obj enters during overlap ? %d OR obj exits during overlap %d ? -> should " - "not " - "enter = %d\n", - object_enters_during_overlap, object_exits_during_overlap, - object_enters_during_overlap || object_exits_during_overlap); - return object_enters_during_overlap || object_exits_during_overlap; - }; - - const auto object_is_going_same_way = - range_times.object.enter_time < range_times.object.exit_time; - return (object_is_going_same_way && same_way_condition()) || - (!object_is_going_same_way && opposite_way_condition()); -} - -bool ttc_condition( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - const auto ttc_at_enter = range_times.ego.enter_time - range_times.object.enter_time; - const auto ttc_at_exit = range_times.ego.exit_time - range_times.object.exit_time; - const auto collision_during_overlap = (ttc_at_enter < 0.0) != (ttc_at_exit < 0.0); - const auto ttc_is_bellow_threshold = - std::min(std::abs(ttc_at_enter), std::abs(ttc_at_exit)) <= params.ttc_threshold; - RCLCPP_DEBUG( - logger, "\t\t\t[TTC] (%2.2fs - %2.2fs) -> %d\n", ttc_at_enter, ttc_at_exit, - (collision_during_overlap || ttc_is_bellow_threshold)); - return collision_during_overlap || ttc_is_bellow_threshold; -} - -bool will_collide_on_range( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - RCLCPP_DEBUG( - logger, " enter at %2.2fs, exits at %2.2fs\n", range_times.object.enter_time, - range_times.object.exit_time); - return (params.mode == "threshold" && threshold_condition(range_times, params)) || - (params.mode == "intervals" && intervals_condition(range_times, params, logger)) || - (params.mode == "ttc" && ttc_condition(range_times, params, logger)); -} - -bool should_not_enter( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger) -{ - RangeTimes range_times{}; - range_times.ego.enter_time = - time_along_trajectory(inputs.ego_data, range.entering_trajectory_idx, params.ego_min_velocity); - range_times.ego.exit_time = - time_along_trajectory(inputs.ego_data, range.exiting_trajectory_idx, params.ego_min_velocity); - RCLCPP_DEBUG( - logger, "\t[%lu -> %lu] %ld | ego enters at %2.2f, exits at %2.2f\n", - range.entering_trajectory_idx, range.exiting_trajectory_idx, range.lane.id(), - range_times.ego.enter_time, range_times.ego.exit_time); - for (const auto & object : inputs.objects.objects) { - RCLCPP_DEBUG( - logger, "\t\t[%s] going at %2.2fm/s", - autoware::universe_utils::toHexString(object.object_id).c_str(), - object.kinematics.initial_twist_with_covariance.twist.linear.x); - if (object.kinematics.initial_twist_with_covariance.twist.linear.x < params.objects_min_vel) { - RCLCPP_DEBUG(logger, " SKIP (velocity bellow threshold %2.2fm/s)\n", params.objects_min_vel); - continue; // skip objects with velocity bellow a threshold - } - // skip objects that are already on the interval - const auto enter_exit_time = - params.objects_use_predicted_paths - ? object_time_to_range( - object, range, inputs.route_handler, params.objects_dist_buffer, logger) - : object_time_to_range(object, range, inputs, logger); - if (!enter_exit_time) { - RCLCPP_DEBUG(logger, " SKIP (no enter/exit times found)\n"); - continue; // skip objects that are not driving towards the overlapping range - } - - range_times.object.enter_time = enter_exit_time->first; - range_times.object.exit_time = enter_exit_time->second; - if (will_collide_on_range(range_times, params, logger)) { - range.debug.times = range_times; - range.debug.object = object; - return true; - } - } - range.debug.times = range_times; - return false; -} - -void set_decision_velocity( - std::optional & decision, const double distance, const PlannerParam & params) -{ - if (distance < params.stop_dist_threshold) { - decision->velocity = 0.0; - } else if (distance < params.slow_dist_threshold) { - decision->velocity = params.slow_velocity; - } else { - decision.reset(); - } -} - -std::optional calculate_decision( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger) -{ - std::optional decision; - if (should_not_enter(range, inputs, params, logger)) { - decision.emplace(); - decision->target_trajectory_idx = inputs.ego_data.first_trajectory_idx + - range.entering_trajectory_idx; // add offset from curr pose - decision->lane_to_avoid = range.lane; - const auto ego_dist_to_range = - distance_along_trajectory(inputs.ego_data, range.entering_trajectory_idx); - set_decision_velocity(decision, ego_dist_to_range, params); - } - return decision; -} - -std::vector calculate_decisions( - const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger) -{ - std::vector decisions; - for (const auto & range : inputs.ranges) { - if (range.entering_trajectory_idx == 0UL) continue; // skip if we already entered the range - const auto optional_decision = calculate_decision(range, inputs, params, logger); - range.debug.decision = optional_decision; - if (optional_decision) decisions.push_back(*optional_decision); - } - return decisions; -} - -} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp deleted file mode 100644 index 455cee272f7be..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp +++ /dev/null @@ -1,116 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef DECISIONS_HPP_ -#define DECISIONS_HPP_ - -#include "types.hpp" - -#include -#include - -#include - -#include - -#include -#include -#include -#include - -namespace autoware::motion_velocity_planner::out_of_lane -{ -/// @brief calculate the distance along the ego trajectory between ego and some target trajectory -/// index -/// @param [in] ego_data data related to the ego vehicle -/// @param [in] target_idx target ego trajectory index -/// @return distance between ego and the target [m] -double distance_along_trajectory(const EgoData & ego_data, const size_t target_idx); -/// @brief estimate the time when ego will reach some target trajectory index -/// @param [in] ego_data data related to the ego vehicle -/// @param [in] target_idx target ego trajectory index -/// @param [in] min_velocity minimum ego velocity used to estimate the time -/// @return time taken by ego to reach the target [s] -double time_along_trajectory(const EgoData & ego_data, const size_t target_idx); -/// @brief use an object's predicted paths to estimate the times it will reach the enter and exit -/// points of an overlapping range -/// @details times when the predicted paths of the object enters/exits the range are calculated -/// but may not exist (e.g,, predicted path ends before reaching the end of the range) -/// @param [in] object dynamic object -/// @param [in] range overlapping range -/// @param [in] route_handler route handler used to estimate the path of the dynamic object -/// @param [in] logger ros logger -/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in -/// the opposite direction, time at enter > time at exit -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const double dist_buffer, - const rclcpp::Logger & logger); -/// @brief use the lanelet map to estimate the times when an object will reach the enter and exit -/// points of an overlapping range -/// @param [in] object dynamic object -/// @param [in] range overlapping range -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] dist_buffer extra distance used to estimate if a collision will occur on the range -/// @param [in] logger ros logger -/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in -/// the opposite direction, time at enter > time at exit. -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const DecisionInputs & inputs, const rclcpp::Logger & logger); -/// @brief decide whether an object is coming in the range at the same time as ego -/// @details the condition depends on the mode (threshold, intervals, ttc) -/// @param [in] range_times times when ego and the object enter/exit the range -/// @param [in] params parameters -/// @param [in] logger ros logger -bool will_collide_on_range( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger); -/// @brief check whether we should avoid entering the given range -/// @param [in] range the range to check -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return true if we should avoid entering the range -bool should_not_enter( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger); -/// @brief set the velocity of a decision (or unset it) based on the distance away from the range -/// @param [out] decision decision to update (either set its velocity or unset the decision) -/// @param [in] distance distance between ego and the range corresponding to the decision -/// @param [in] params parameters -void set_decision_velocity( - std::optional & decision, const double distance, const PlannerParam & params); -/// @brief calculate the decision to slowdown or stop before an overlapping range -/// @param [in] range the range to check -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return an optional decision to slowdown or stop -std::optional calculate_decision( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger); -/// @brief calculate decisions to slowdown or stop before some overlapping ranges -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return the calculated decisions to slowdown or stop -std::vector calculate_decisions( - const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger); -} // namespace autoware::motion_velocity_planner::out_of_lane - -#endif // DECISIONS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp index a53129f372e3d..79bdefee4c4c7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp @@ -18,6 +18,7 @@ #include #include +#include #include #include @@ -53,7 +54,7 @@ void cut_predicted_path_beyond_line( auto cut_idx = stop_line_idx; double arc_length = 0; while (cut_idx > 0 && arc_length < object_front_overhang) { - arc_length += autoware::universe_utils::calcDistance2d( + arc_length += universe_utils::calcDistance2d( predicted_path.path[cut_idx], predicted_path.path[cut_idx - 1]); --cut_idx; } @@ -102,12 +103,11 @@ void cut_predicted_path_beyond_red_lights( } autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( - const std::shared_ptr planner_data, const EgoData & ego_data, - const PlannerParam & params) + const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params) { autoware_perception_msgs::msg::PredictedObjects filtered_objects; - filtered_objects.header = planner_data->predicted_objects.header; - for (const auto & object : planner_data->predicted_objects.objects) { + filtered_objects.header = planner_data.predicted_objects.header; + for (const auto & object : planner_data.predicted_objects.objects) { const auto is_pedestrian = std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) { return c.label == autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN; @@ -125,10 +125,10 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( auto filtered_object = object; const auto is_invalid_predicted_path = [&](const auto & predicted_path) { const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence; - const auto no_overlap_path = autoware::motion_utils::removeOverlapPoints(predicted_path.path); + const auto no_overlap_path = motion_utils::removeOverlapPoints(predicted_path.path); if (no_overlap_path.size() <= 1) return true; - const auto lat_offset_to_current_ego = std::abs( - autoware::motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position)); + const auto lat_offset_to_current_ego = + std::abs(motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position)); const auto is_crossing_ego = lat_offset_to_current_ego <= object.shape.dimensions.y / 2.0 + std::max( @@ -136,23 +136,21 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( params.right_offset + params.extra_right_offset); return is_low_confidence || is_crossing_ego; }; - if (params.objects_use_predicted_paths) { - auto & predicted_paths = filtered_object.kinematics.predicted_paths; - const auto new_end = - std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path); - predicted_paths.erase(new_end, predicted_paths.end()); - if (params.objects_cut_predicted_paths_beyond_red_lights) - for (auto & predicted_path : predicted_paths) - cut_predicted_path_beyond_red_lights( - predicted_path, ego_data, filtered_object.shape.dimensions.x); - predicted_paths.erase( - std::remove_if( - predicted_paths.begin(), predicted_paths.end(), - [](const auto & p) { return p.path.empty(); }), - predicted_paths.end()); - } + auto & predicted_paths = filtered_object.kinematics.predicted_paths; + const auto new_end = + std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path); + predicted_paths.erase(new_end, predicted_paths.end()); + if (params.objects_cut_predicted_paths_beyond_red_lights) + for (auto & predicted_path : predicted_paths) + cut_predicted_path_beyond_red_lights( + predicted_path, ego_data, filtered_object.shape.dimensions.x); + predicted_paths.erase( + std::remove_if( + predicted_paths.begin(), predicted_paths.end(), + [](const auto & p) { return p.path.empty(); }), + predicted_paths.end()); - if (!params.objects_use_predicted_paths || !filtered_object.kinematics.predicted_paths.empty()) + if (!filtered_object.kinematics.predicted_paths.empty()) filtered_objects.objects.push_back(filtered_object); } return filtered_objects; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp index baf07e4b06ea5..3b2ae11718810 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp @@ -19,7 +19,6 @@ #include -#include #include namespace autoware::motion_velocity_planner::out_of_lane @@ -52,8 +51,7 @@ void cut_predicted_path_beyond_red_lights( /// @param [in] params parameters /// @return filtered predicted objects autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( - const std::shared_ptr planner_data, const EgoData & ego_data, - const PlannerParam & params); + const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // FILTER_PREDICTED_OBJECTS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp index f5d68c4fa9bba..564bf5de7ef2e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp @@ -21,15 +21,13 @@ #include #include -#include #include namespace autoware::motion_velocity_planner::out_of_lane { -autoware::universe_utils::Polygon2d make_base_footprint( - const PlannerParam & p, const bool ignore_offset) +universe_utils::Polygon2d make_base_footprint(const PlannerParam & p, const bool ignore_offset) { - autoware::universe_utils::Polygon2d base_footprint; + universe_utils::Polygon2d base_footprint; const auto front_offset = ignore_offset ? 0.0 : p.extra_front_offset; const auto rear_offset = ignore_offset ? 0.0 : p.extra_rear_offset; const auto right_offset = ignore_offset ? 0.0 : p.extra_right_offset; @@ -43,10 +41,10 @@ autoware::universe_utils::Polygon2d make_base_footprint( } lanelet::BasicPolygon2d project_to_pose( - const autoware::universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) + const universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) { const auto angle = tf2::getYaw(pose.orientation); - const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back(p.x() + pose.position.x, p.y() + pose.position.y); @@ -59,22 +57,15 @@ std::vector calculate_trajectory_footprints( const auto base_footprint = make_base_footprint(params); std::vector trajectory_footprints; trajectory_footprints.reserve(ego_data.trajectory_points.size()); - double length = 0.0; - const auto range = std::max(params.slow_dist_threshold, params.stop_dist_threshold) + - params.front_offset + params.extra_front_offset; - for (auto i = ego_data.first_trajectory_idx; - i < ego_data.trajectory_points.size() && length < range; ++i) { + for (auto i = ego_data.first_trajectory_idx; i < ego_data.trajectory_points.size(); ++i) { const auto & trajectory_pose = ego_data.trajectory_points[i].pose; const auto angle = tf2::getYaw(trajectory_pose.orientation); - const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back( p.x() + trajectory_pose.position.x, p.y() + trajectory_pose.position.y); trajectory_footprints.push_back(footprint); - if (i + 1 < ego_data.trajectory_points.size()) - length += autoware::universe_utils::calcDistance2d( - trajectory_pose, ego_data.trajectory_points[i + 1].pose); } return trajectory_footprints; } @@ -84,7 +75,7 @@ lanelet::BasicPolygon2d calculate_current_ego_footprint( { const auto base_footprint = make_base_footprint(params, ignore_offset); const auto angle = tf2::getYaw(ego_data.pose.orientation); - const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back(p.x() + ego_data.pose.position.x, p.y() + ego_data.pose.position.y); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp index ebe7ab0fa9d7f..88baeefba6f40 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp @@ -21,24 +21,21 @@ #include -namespace autoware::motion_velocity_planner -{ -namespace out_of_lane +namespace autoware::motion_velocity_planner::out_of_lane { /// @brief create the base footprint of ego /// @param [in] p parameters used to create the footprint /// @param [in] ignore_offset optional parameter, if true, ignore the "extra offsets" to build the /// footprint /// @return base ego footprint -autoware::universe_utils::Polygon2d make_base_footprint( +universe_utils::Polygon2d make_base_footprint( const PlannerParam & p, const bool ignore_offset = false); /// @brief project a footprint to the given pose /// @param [in] base_footprint footprint to project /// @param [in] pose projection pose /// @return footprint projected to the given pose lanelet::BasicPolygon2d project_to_pose( - const autoware::universe_utils::Polygon2d & base_footprint, - const geometry_msgs::msg::Pose & pose); + const universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose); /// @brief calculate the trajectory footprints /// @details the resulting polygon follows the format used by the lanelet library: clockwise order /// and implicit closing edge @@ -54,7 +51,6 @@ std::vector calculate_trajectory_footprints( /// footprint lanelet::BasicPolygon2d calculate_current_ego_footprint( const EgoData & ego_data, const PlannerParam & params, const bool ignore_offset = false); -} // namespace out_of_lane -} // namespace autoware::motion_velocity_planner +} // namespace autoware::motion_velocity_planner::out_of_lane #endif // FOOTPRINT_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp index bca849f806f63..f520a564519f0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp @@ -14,36 +14,46 @@ #include "lanelets_selection.hpp" +#include "types.hpp" + #include #include +#include +#include #include -#include #include #include -#include namespace autoware::motion_velocity_planner::out_of_lane { +namespace +{ +bool is_road_lanelet(const lanelet::ConstLanelet & lanelet) +{ + return lanelet.hasAttribute(lanelet::AttributeName::Subtype) && + lanelet.attribute(lanelet::AttributeName::Subtype) == lanelet::AttributeValueString::Road; +} +} // namespace + lanelet::ConstLanelets consecutive_lanelets( - const std::shared_ptr route_handler, - const lanelet::ConstLanelet & lanelet) + const route_handler::RouteHandler & route_handler, const lanelet::ConstLanelet & lanelet) { - lanelet::ConstLanelets consecutives = route_handler->getRoutingGraphPtr()->following(lanelet); - const auto previous = route_handler->getRoutingGraphPtr()->previous(lanelet); + lanelet::ConstLanelets consecutives = route_handler.getRoutingGraphPtr()->following(lanelet); + const auto previous = route_handler.getRoutingGraphPtr()->previous(lanelet); consecutives.insert(consecutives.end(), previous.begin(), previous.end()); return consecutives; } lanelet::ConstLanelets get_missing_lane_change_lanelets( - lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler) + const lanelet::ConstLanelets & trajectory_lanelets, + const route_handler::RouteHandler & route_handler) { lanelet::ConstLanelets missing_lane_change_lanelets; - const auto & routing_graph = *route_handler->getRoutingGraphPtr(); + const auto & routing_graph = *route_handler.getRoutingGraphPtr(); lanelet::ConstLanelets adjacents; lanelet::ConstLanelets consecutives; for (const auto & ll : trajectory_lanelets) { @@ -67,9 +77,9 @@ lanelet::ConstLanelets get_missing_lane_change_lanelets( } lanelet::ConstLanelets calculate_trajectory_lanelets( - const EgoData & ego_data, const std::shared_ptr route_handler) + const EgoData & ego_data, const route_handler::RouteHandler & route_handler) { - const auto lanelet_map_ptr = route_handler->getLaneletMapPtr(); + const auto lanelet_map_ptr = route_handler.getLaneletMapPtr(); lanelet::ConstLanelets trajectory_lanelets; lanelet::BasicLineString2d trajectory_ls; for (const auto & p : ego_data.trajectory_points) @@ -77,7 +87,9 @@ lanelet::ConstLanelets calculate_trajectory_lanelets( const auto candidates = lanelet_map_ptr->laneletLayer.search(lanelet::geometry::boundingBox2d(trajectory_ls)); for (const auto & ll : candidates) { - if (!boost::geometry::disjoint(trajectory_ls, ll.polygon2d().basicPolygon())) { + if ( + is_road_lanelet(ll) && + !boost::geometry::disjoint(trajectory_ls, ll.polygon2d().basicPolygon())) { trajectory_lanelets.push_back(ll); } } @@ -89,43 +101,65 @@ lanelet::ConstLanelets calculate_trajectory_lanelets( } lanelet::ConstLanelets calculate_ignored_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params) + const lanelet::ConstLanelets & trajectory_lanelets, + const route_handler::RouteHandler & route_handler) { lanelet::ConstLanelets ignored_lanelets; - // ignore lanelets directly behind ego - const auto behind = - autoware::universe_utils::calcOffsetPose(ego_data.pose, params.rear_offset, 0.0, 0.0); - const lanelet::BasicPoint2d behind_point(behind.position.x, behind.position.y); - const auto behind_lanelets = lanelet::geometry::findWithin2d( - route_handler->getLaneletMapPtr()->laneletLayer, behind_point, 0.0); - for (const auto & l : behind_lanelets) { - const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, l.second.id()); - if (!is_trajectory_lanelet) ignored_lanelets.push_back(l.second); + // ignore lanelets directly preceding a trajectory lanelet + for (const auto & trajectory_lanelet : trajectory_lanelets) { + for (const auto & ll : route_handler.getPreviousLanelets(trajectory_lanelet)) { + const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, ll.id()); + if (!is_trajectory_lanelet) ignored_lanelets.push_back(ll); + } } return ignored_lanelets; } -lanelet::ConstLanelets calculate_other_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const lanelet::ConstLanelets & ignored_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params) +void calculate_drivable_lane_polygons( + EgoData & ego_data, const route_handler::RouteHandler & route_handler) +{ + const auto route_lanelets = calculate_trajectory_lanelets(ego_data, route_handler); + const auto ignored_lanelets = + out_of_lane::calculate_ignored_lanelets(route_lanelets, route_handler); + for (const auto & ll : route_lanelets) { + out_of_lane::Polygons tmp; + boost::geometry::union_(ego_data.drivable_lane_polygons, ll.polygon2d().basicPolygon(), tmp); + ego_data.drivable_lane_polygons = tmp; + } + for (const auto & ll : ignored_lanelets) { + out_of_lane::Polygons tmp; + boost::geometry::union_(ego_data.drivable_lane_polygons, ll.polygon2d().basicPolygon(), tmp); + ego_data.drivable_lane_polygons = tmp; + } +} + +void calculate_overlapped_lanelets( + OutOfLanePoint & out_of_lane_point, const route_handler::RouteHandler & route_handler) { - lanelet::ConstLanelets other_lanelets; - const lanelet::BasicPoint2d ego_point(ego_data.pose.position.x, ego_data.pose.position.y); - const auto lanelets_within_range = lanelet::geometry::findWithin2d( - route_handler->getLaneletMapPtr()->laneletLayer, ego_point, - std::max(params.slow_dist_threshold, params.stop_dist_threshold) + params.front_offset + - params.extra_front_offset); - for (const auto & ll : lanelets_within_range) { - if (std::string(ll.second.attributeOr(lanelet::AttributeName::Subtype, "none")) != "road") - continue; - const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, ll.second.id()); - const auto is_ignored_lanelet = contains_lanelet(ignored_lanelets, ll.second.id()); - if (!is_trajectory_lanelet && !is_ignored_lanelet) other_lanelets.push_back(ll.second); + out_of_lane_point.overlapped_lanelets = lanelet::ConstLanelets(); + const auto candidates = route_handler.getLaneletMapPtr()->laneletLayer.search( + lanelet::geometry::boundingBox2d(out_of_lane_point.outside_ring)); + for (const auto & ll : candidates) { + if ( + is_road_lanelet(ll) && !contains_lanelet(out_of_lane_point.overlapped_lanelets, ll.id()) && + boost::geometry::within(out_of_lane_point.outside_ring, ll.polygon2d().basicPolygon())) { + out_of_lane_point.overlapped_lanelets.push_back(ll); + } + } +} + +void calculate_overlapped_lanelets( + OutOfLaneData & out_of_lane_data, const route_handler::RouteHandler & route_handler) +{ + for (auto it = out_of_lane_data.outside_points.begin(); + it != out_of_lane_data.outside_points.end();) { + calculate_overlapped_lanelets(*it, route_handler); + if (it->overlapped_lanelets.empty()) { + // do not keep out of lane points that do not overlap any lanelet + out_of_lane_data.outside_points.erase(it); + } else { + ++it; + } } - return other_lanelets; } } // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp index 8618d808d7d40..a7729deb539b6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp @@ -44,6 +44,7 @@ inline bool contains_lanelet(const lanelet::ConstLanelets & lanelets, const lane /// @return lanelets crossed by the ego vehicle lanelet::ConstLanelets calculate_trajectory_lanelets( const EgoData & ego_data, const std::shared_ptr route_handler); + /// @brief calculate lanelets that may not be crossed by the trajectory but may be overlapped during /// a lane change /// @param [in] trajectory_lanelets lanelets driven by the ego vehicle @@ -51,30 +52,28 @@ lanelet::ConstLanelets calculate_trajectory_lanelets( /// @return lanelets that may be overlapped by a lane change (and are not already in /// trajectory_lanelets) lanelet::ConstLanelets get_missing_lane_change_lanelets( - lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler); + const lanelet::ConstLanelets & trajectory_lanelets, + const std::shared_ptr & route_handler); + /// @brief calculate lanelets that should be ignored -/// @param [in] ego_data data about the ego vehicle -/// @param [in] trajectory_lanelets lanelets driven by the ego vehicle +/// @param [in] trajectory_lanelets lanelets followed by the ego vehicle /// @param [in] route_handler route handler -/// @param [in] params parameters /// @return lanelets to ignore lanelet::ConstLanelets calculate_ignored_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params); -/// @brief calculate lanelets that should be checked by the module -/// @param [in] ego_data data about the ego vehicle -/// @param [in] trajectory_lanelets lanelets driven by the ego vehicle -/// @param [in] ignored_lanelets lanelets to ignore -/// @param [in] route_handler route handler -/// @param [in] params parameters -/// @return lanelets to check for overlaps -lanelet::ConstLanelets calculate_other_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const lanelet::ConstLanelets & ignored_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params); + const lanelet::ConstLanelets & trajectory_lanelets, + const std::shared_ptr & route_handler); + +/// @brief calculate the polygons representing the ego lane and add it to the ego data +/// @param [inout] ego_data ego data +/// @param [in] route_handler route handler with map information +void calculate_drivable_lane_polygons( + EgoData & ego_data, const route_handler::RouteHandler & route_handler); + +/// @brief calculate the lanelets overlapped at each out of lane point +/// @param [out] out_of_lane_data data with the out of lane points +/// @param [in] route_handler route handler with the lanelet map +void calculate_overlapped_lanelets( + OutOfLaneData & out_of_lane_data, const route_handler::RouteHandler & route_handler); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // LANELETS_SELECTION_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp new file mode 100644 index 0000000000000..aef035200b6cc --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp @@ -0,0 +1,164 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "out_of_lane_collisions.hpp" + +#include "types.hpp" + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +void update_collision_times( + OutOfLaneData & out_of_lane_data, const std::unordered_set & potential_collision_indexes, + const universe_utils::Polygon2d & object_footprint, const double time) +{ + for (const auto index : potential_collision_indexes) { + auto & out_of_lane_point = out_of_lane_data.outside_points[index]; + if (out_of_lane_point.collision_times.count(time) == 0UL) { + const auto has_collision = + !boost::geometry::disjoint(out_of_lane_point.outside_ring, object_footprint.outer()); + if (has_collision) { + out_of_lane_point.collision_times.insert(time); + } + } + } +} + +void calculate_object_path_time_collisions( + OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedPath & object_path, + const autoware_perception_msgs::msg::Shape & object_shape) +{ + const auto time_step = rclcpp::Duration(object_path.time_step).seconds(); + auto time = time_step; + for (const auto & object_pose : object_path.path) { + time += time_step; + const auto object_footprint = universe_utils::toPolygon2d(object_pose, object_shape); + std::vector query_results; + out_of_lane_data.outside_areas_rtree.query( + boost::geometry::index::intersects(object_footprint.outer()), + std::back_inserter(query_results)); + std::unordered_set potential_collision_indexes; + for (const auto & [_, index] : query_results) { + potential_collision_indexes.insert(index); + } + update_collision_times(out_of_lane_data, potential_collision_indexes, object_footprint, time); + } +} + +void calculate_objects_time_collisions( + OutOfLaneData & out_of_lane_data, + const std::vector & objects) +{ + for (const auto & object : objects) { + for (const auto & path : object.kinematics.predicted_paths) { + calculate_object_path_time_collisions(out_of_lane_data, path, object.shape); + } + } +} + +void calculate_min_max_arrival_times( + OutOfLanePoint & out_of_lane_point, + const std::vector & trajectory) +{ + auto min_time = std::numeric_limits::infinity(); + auto max_time = -std::numeric_limits::infinity(); + for (const auto & t : out_of_lane_point.collision_times) { + min_time = std::min(t, min_time); + max_time = std::max(t, max_time); + } + if (min_time <= max_time) { + out_of_lane_point.min_object_arrival_time = min_time; + out_of_lane_point.max_object_arrival_time = max_time; + const auto & ego_time = + rclcpp::Duration(trajectory[out_of_lane_point.trajectory_index].time_from_start).seconds(); + if (ego_time >= min_time && ego_time <= max_time) { + out_of_lane_point.ttc = 0.0; + } else { + out_of_lane_point.ttc = + std::min(std::abs(ego_time - min_time), std::abs(ego_time - max_time)); + } + } +}; + +void calculate_collisions_to_avoid( + OutOfLaneData & out_of_lane_data, + const std::vector & trajectory, + const PlannerParam & params) +{ + for (auto & out_of_lane_point : out_of_lane_data.outside_points) { + calculate_min_max_arrival_times(out_of_lane_point, trajectory); + } + for (auto & p : out_of_lane_data.outside_points) { + if (params.mode == "ttc") { + p.to_avoid = p.ttc && p.ttc <= params.ttc_threshold; + } else { + p.to_avoid = p.min_object_arrival_time && p.min_object_arrival_time <= params.time_threshold; + } + } +} + +std::vector calculate_out_of_lane_points(const EgoData & ego_data) +{ + std::vector out_of_lane_points; + OutOfLanePoint p; + for (auto i = 0UL; i < ego_data.trajectory_footprints.size(); ++i) { + p.trajectory_index = i + ego_data.first_trajectory_idx; + const auto & footprint = ego_data.trajectory_footprints[i]; + Polygons out_of_lane_polygons; + boost::geometry::difference(footprint, ego_data.drivable_lane_polygons, out_of_lane_polygons); + for (const auto & area : out_of_lane_polygons) { + if (!area.outer.empty()) { + p.outside_ring = area.outer; + out_of_lane_points.push_back(p); + } + } + } + return out_of_lane_points; +} + +void prepare_out_of_lane_areas_rtree(OutOfLaneData & out_of_lane_data) +{ + std::vector rtree_nodes; + for (auto i = 0UL; i < out_of_lane_data.outside_points.size(); ++i) { + OutAreaNode n; + n.first = boost::geometry::return_envelope( + out_of_lane_data.outside_points[i].outside_ring); + n.second = i; + rtree_nodes.push_back(n); + } + out_of_lane_data.outside_areas_rtree = {rtree_nodes.begin(), rtree_nodes.end()}; +} + +} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp new file mode 100644 index 0000000000000..33f0842c56d36 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp @@ -0,0 +1,57 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef OUT_OF_LANE_COLLISIONS_HPP_ +#define OUT_OF_LANE_COLLISIONS_HPP_ + +#include "types.hpp" + +#include + +#include +#include + +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +/// @brief calculate the times and points where ego collides with an object's path outside of its +/// lane +void calculate_object_path_time_collisions( + OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedPath & object_path, + const autoware_perception_msgs::msg::Shape & object_shape); + +/// @brief calculate the times and points where ego collides with an object outside of its lane +void calculate_objects_time_collisions( + OutOfLaneData & out_of_lane_data, + const std::vector & objects); + +/// @brief calculate the collisions to avoid +/// @details either uses the time to collision or just the time when the object will arrive at the +/// point +void calculate_collisions_to_avoid( + OutOfLaneData & out_of_lane_data, + const std::vector & trajectory, + const PlannerParam & params); + +/// @brief calculate the out of lane points +std::vector calculate_out_of_lane_points(const EgoData & ego_data); + +/// @brief prepare the rtree of out of lane points for the given data +void prepare_out_of_lane_areas_rtree(OutOfLaneData & out_of_lane_data); +} // namespace autoware::motion_velocity_planner::out_of_lane + +#endif // OUT_OF_LANE_COLLISIONS_HPP_ 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 a6b34a1566e19..c97e10cc8706e 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 @@ -16,16 +16,16 @@ #include "calculate_slowdown_points.hpp" #include "debug.hpp" -#include "decisions.hpp" #include "filter_predicted_objects.hpp" #include "footprint.hpp" #include "lanelets_selection.hpp" -#include "overlapping_range.hpp" +#include "out_of_lane_collisions.hpp" #include "types.hpp" #include #include #include +#include #include #include #include @@ -34,11 +34,13 @@ #include #include +#include #include #include #include +#include #include #include #include @@ -56,65 +58,52 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) logger_ = node.get_logger(); clock_ = node.get_clock(); init_parameters(node); - velocity_factor_interface_.init(autoware::motion_utils::PlanningBehavior::ROUTE_OBSTACLE); + velocity_factor_interface_.init(motion_utils::PlanningBehavior::ROUTE_OBSTACLE); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); virtual_wall_publisher_ = node.create_publisher("~/" + ns_ + "/virtual_walls", 1); - processing_diag_publisher_ = std::make_shared( + 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) { - using autoware::universe_utils::getOrDeclareParameter; + using universe_utils::getOrDeclareParameter; auto & pp = params_; pp.mode = getOrDeclareParameter(node, ns_ + ".mode"); pp.skip_if_already_overlapping = getOrDeclareParameter(node, ns_ + ".skip_if_already_overlapping"); + pp.max_arc_length = getOrDeclareParameter(node, ns_ + ".max_arc_length"); pp.time_threshold = getOrDeclareParameter(node, ns_ + ".threshold.time_threshold"); - pp.intervals_ego_buffer = getOrDeclareParameter(node, ns_ + ".intervals.ego_time_buffer"); - pp.intervals_obj_buffer = - getOrDeclareParameter(node, ns_ + ".intervals.objects_time_buffer"); pp.ttc_threshold = getOrDeclareParameter(node, ns_ + ".ttc.threshold"); pp.objects_min_vel = getOrDeclareParameter(node, ns_ + ".objects.minimum_velocity"); - pp.objects_use_predicted_paths = - getOrDeclareParameter(node, ns_ + ".objects.use_predicted_paths"); pp.objects_min_confidence = getOrDeclareParameter(node, ns_ + ".objects.predicted_path_min_confidence"); - pp.objects_dist_buffer = getOrDeclareParameter(node, ns_ + ".objects.distance_buffer"); pp.objects_cut_predicted_paths_beyond_red_lights = getOrDeclareParameter(node, ns_ + ".objects.cut_predicted_paths_beyond_red_lights"); pp.objects_ignore_behind_ego = getOrDeclareParameter(node, ns_ + ".objects.ignore_behind_ego"); - pp.overlap_min_dist = getOrDeclareParameter(node, ns_ + ".overlap.minimum_distance"); - pp.overlap_extra_length = getOrDeclareParameter(node, ns_ + ".overlap.extra_length"); - - pp.skip_if_over_max_decel = - getOrDeclareParameter(node, ns_ + ".action.skip_if_over_max_decel"); pp.precision = getOrDeclareParameter(node, ns_ + ".action.precision"); pp.min_decision_duration = getOrDeclareParameter(node, ns_ + ".action.min_duration"); pp.lon_dist_buffer = getOrDeclareParameter(node, ns_ + ".action.longitudinal_distance_buffer"); pp.lat_dist_buffer = getOrDeclareParameter(node, ns_ + ".action.lateral_distance_buffer"); pp.slow_velocity = getOrDeclareParameter(node, ns_ + ".action.slowdown.velocity"); - pp.slow_dist_threshold = - getOrDeclareParameter(node, ns_ + ".action.slowdown.distance_threshold"); pp.stop_dist_threshold = getOrDeclareParameter(node, ns_ + ".action.stop.distance_threshold"); - pp.ego_min_velocity = getOrDeclareParameter(node, ns_ + ".ego.min_assumed_velocity"); pp.extra_front_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_front_offset"); pp.extra_rear_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_rear_offset"); pp.extra_left_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_left_offset"); pp.extra_right_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_right_offset"); - const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); + const auto vehicle_info = vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); pp.front_offset = vehicle_info.max_longitudinal_offset_m; pp.rear_offset = vehicle_info.min_longitudinal_offset_m; pp.left_offset = vehicle_info.max_lateral_offset_m; @@ -123,44 +112,79 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node) void OutOfLaneModule::update_parameters(const std::vector & parameters) { - using autoware::universe_utils::updateParam; + using universe_utils::updateParam; auto & pp = params_; updateParam(parameters, ns_ + ".mode", pp.mode); updateParam(parameters, ns_ + ".skip_if_already_overlapping", pp.skip_if_already_overlapping); + updateParam(parameters, ns_ + ".max_arc_length", pp.max_arc_length); updateParam(parameters, ns_ + ".threshold.time_threshold", pp.time_threshold); - updateParam(parameters, ns_ + ".intervals.ego_time_buffer", pp.intervals_ego_buffer); - updateParam(parameters, ns_ + ".intervals.objects_time_buffer", pp.intervals_obj_buffer); updateParam(parameters, ns_ + ".ttc.threshold", pp.ttc_threshold); updateParam(parameters, ns_ + ".objects.minimum_velocity", pp.objects_min_vel); - updateParam(parameters, ns_ + ".objects.use_predicted_paths", pp.objects_use_predicted_paths); updateParam( parameters, ns_ + ".objects.predicted_path_min_confidence", pp.objects_min_confidence); - updateParam(parameters, ns_ + ".objects.distance_buffer", pp.objects_dist_buffer); updateParam( parameters, ns_ + ".objects.cut_predicted_paths_beyond_red_lights", pp.objects_cut_predicted_paths_beyond_red_lights); updateParam(parameters, ns_ + ".objects.ignore_behind_ego", pp.objects_ignore_behind_ego); - updateParam(parameters, ns_ + ".overlap.minimum_distance", pp.overlap_min_dist); - updateParam(parameters, ns_ + ".overlap.extra_length", pp.overlap_extra_length); - updateParam(parameters, ns_ + ".action.skip_if_over_max_decel", pp.skip_if_over_max_decel); updateParam(parameters, ns_ + ".action.precision", pp.precision); updateParam(parameters, ns_ + ".action.min_duration", pp.min_decision_duration); updateParam(parameters, ns_ + ".action.longitudinal_distance_buffer", pp.lon_dist_buffer); updateParam(parameters, ns_ + ".action.lateral_distance_buffer", pp.lat_dist_buffer); updateParam(parameters, ns_ + ".action.slowdown.velocity", pp.slow_velocity); - updateParam(parameters, ns_ + ".action.slowdown.distance_threshold", pp.slow_dist_threshold); updateParam(parameters, ns_ + ".action.stop.distance_threshold", pp.stop_dist_threshold); - updateParam(parameters, ns_ + ".ego.min_assumed_velocity", pp.ego_min_velocity); updateParam(parameters, ns_ + ".ego.extra_front_offset", pp.extra_front_offset); updateParam(parameters, ns_ + ".ego.extra_rear_offset", pp.extra_rear_offset); updateParam(parameters, ns_ + ".ego.extra_left_offset", pp.extra_left_offset); updateParam(parameters, ns_ + ".ego.extra_right_offset", pp.extra_right_offset); } +void OutOfLaneModule::limit_trajectory_size( + out_of_lane::EgoData & ego_data, + const std::vector & ego_trajectory_points, + const double max_arc_length) +{ + ego_data.first_trajectory_idx = + motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); + ego_data.longitudinal_offset_to_first_trajectory_index = + motion_utils::calcLongitudinalOffsetToSegment( + ego_trajectory_points, ego_data.first_trajectory_idx, ego_data.pose.position); + auto l = -ego_data.longitudinal_offset_to_first_trajectory_index; + ego_data.trajectory_points.push_back(ego_trajectory_points[ego_data.first_trajectory_idx]); + for (auto i = ego_data.first_trajectory_idx + 1; i < ego_trajectory_points.size(); ++i) { + l += universe_utils::calcDistance2d(ego_trajectory_points[i - 1], ego_trajectory_points[i]); + if (l >= max_arc_length) { + break; + } + ego_data.trajectory_points.push_back(ego_trajectory_points[i]); + } +} + +void OutOfLaneModule::calculate_min_stop_and_slowdown_distances( + out_of_lane::EgoData & ego_data, const PlannerData & planner_data, + std::optional & previous_slowdown_pose_, const double slow_velocity) +{ + ego_data.min_stop_distance = planner_data.calculate_min_deceleration_distance(0.0).value_or(0.0); + ego_data.min_slowdown_distance = + planner_data.calculate_min_deceleration_distance(slow_velocity).value_or(0.0); + if (previous_slowdown_pose_) { + // Ensure we do not remove the previous slowdown point due to the min distance limit + const auto previous_slowdown_pose_arc_length = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, ego_data.first_trajectory_idx, previous_slowdown_pose_->position); + ego_data.min_stop_distance = + std::min(previous_slowdown_pose_arc_length, ego_data.min_stop_distance); + ego_data.min_slowdown_distance = + std::min(previous_slowdown_pose_arc_length, ego_data.min_slowdown_distance); + } + ego_data.min_stop_arc_length = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, 0UL, ego_data.first_trajectory_idx) + + ego_data.longitudinal_offset_to_first_trajectory_index + + ego_data.min_stop_distance; +} + void prepare_stop_lines_rtree( out_of_lane::EgoData & ego_data, const PlannerData & planner_data, const double search_distance) { @@ -197,168 +221,154 @@ void prepare_stop_lines_rtree( ego_data.stop_lines_rtree = {rtree_nodes.begin(), rtree_nodes.end()}; } +out_of_lane::OutOfLaneData prepare_out_of_lane_data( + const out_of_lane::EgoData & ego_data, const route_handler::RouteHandler & route_handler) +{ + out_of_lane::OutOfLaneData out_of_lane_data; + out_of_lane_data.outside_points = out_of_lane::calculate_out_of_lane_points(ego_data); + out_of_lane::calculate_overlapped_lanelets(out_of_lane_data, route_handler); + out_of_lane::prepare_out_of_lane_areas_rtree(out_of_lane_data); + return out_of_lane_data; +} + VelocityPlanningResult OutOfLaneModule::plan( const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) { VelocityPlanningResult result; - autoware::universe_utils::StopWatch stopwatch; + universe_utils::StopWatch stopwatch; stopwatch.tic(); + + stopwatch.tic("preprocessing"); out_of_lane::EgoData ego_data; ego_data.pose = planner_data->current_odometry.pose.pose; - ego_data.trajectory_points = ego_trajectory_points; - ego_data.first_trajectory_idx = - autoware::motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); - ego_data.velocity = planner_data->current_odometry.twist.twist.linear.x; - ego_data.max_decel = planner_data->velocity_smoother_->getMinDecel(); - stopwatch.tic("preprocessing"); - prepare_stop_lines_rtree(ego_data, *planner_data, 100.0); + limit_trajectory_size(ego_data, ego_trajectory_points, params_.max_arc_length); + calculate_min_stop_and_slowdown_distances( + ego_data, *planner_data, previous_slowdown_pose_, params_.slow_velocity); + prepare_stop_lines_rtree(ego_data, *planner_data, params_.max_arc_length); const auto preprocessing_us = stopwatch.toc("preprocessing"); stopwatch.tic("calculate_trajectory_footprints"); - const auto current_ego_footprint = + ego_data.current_footprint = out_of_lane::calculate_current_ego_footprint(ego_data, params_, true); - const auto trajectory_footprints = - out_of_lane::calculate_trajectory_footprints(ego_data, params_); + ego_data.trajectory_footprints = out_of_lane::calculate_trajectory_footprints(ego_data, params_); const auto calculate_trajectory_footprints_us = stopwatch.toc("calculate_trajectory_footprints"); - // Calculate lanelets to ignore and consider + stopwatch.tic("calculate_lanelets"); - const auto trajectory_lanelets = - out_of_lane::calculate_trajectory_lanelets(ego_data, planner_data->route_handler); - const auto ignored_lanelets = out_of_lane::calculate_ignored_lanelets( - ego_data, trajectory_lanelets, planner_data->route_handler, params_); - const auto other_lanelets = out_of_lane::calculate_other_lanelets( - ego_data, trajectory_lanelets, ignored_lanelets, planner_data->route_handler, params_); + out_of_lane::calculate_drivable_lane_polygons(ego_data, *planner_data->route_handler); const auto calculate_lanelets_us = stopwatch.toc("calculate_lanelets"); - debug_data_.reset_data(); - debug_data_.trajectory_points = ego_trajectory_points; - debug_data_.footprints = trajectory_footprints; - debug_data_.trajectory_lanelets = trajectory_lanelets; - debug_data_.ignored_lanelets = ignored_lanelets; - debug_data_.other_lanelets = other_lanelets; - debug_data_.first_trajectory_idx = ego_data.first_trajectory_idx; - - if (params_.skip_if_already_overlapping) { - debug_data_.current_footprint = current_ego_footprint; - const auto overlapped_lanelet_it = - std::find_if(other_lanelets.begin(), other_lanelets.end(), [&](const auto & ll) { - return boost::geometry::intersects(ll.polygon2d().basicPolygon(), current_ego_footprint); - }); - if (overlapped_lanelet_it != other_lanelets.end()) { - debug_data_.current_overlapped_lanelets.push_back(*overlapped_lanelet_it); - RCLCPP_DEBUG(logger_, "Ego is already overlapping a lane, skipping the module\n"); - return result; - } - } - // Calculate overlapping ranges - stopwatch.tic("calculate_overlapping_ranges"); - const auto ranges = out_of_lane::calculate_overlapping_ranges( - trajectory_footprints, trajectory_lanelets, other_lanelets, params_); - const auto calculate_overlapping_ranges_us = stopwatch.toc("calculate_overlapping_ranges"); - // Calculate stop and slowdown points - out_of_lane::DecisionInputs inputs; - inputs.ranges = ranges; - inputs.ego_data = ego_data; + stopwatch.tic("calculate_out_of_lane_areas"); + auto out_of_lane_data = prepare_out_of_lane_data(ego_data, *planner_data->route_handler); + const auto calculate_out_of_lane_areas_us = stopwatch.toc("calculate_out_of_lane_areas"); + stopwatch.tic("filter_predicted_objects"); - inputs.objects = out_of_lane::filter_predicted_objects(planner_data, ego_data, params_); + const auto objects = out_of_lane::filter_predicted_objects(*planner_data, ego_data, params_); 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"); - const auto decisions = out_of_lane::calculate_decisions(inputs, params_, logger_); - const auto calculate_decisions_us = stopwatch.toc("calculate_decisions"); - stopwatch.tic("calc_slowdown_points"); + + stopwatch.tic("calculate_time_collisions"); + out_of_lane::calculate_objects_time_collisions(out_of_lane_data, objects.objects); + const auto calculate_time_collisions_us = stopwatch.toc("calculate_time_collisions"); + + stopwatch.tic("calculate_times"); + // calculate times + out_of_lane::calculate_collisions_to_avoid(out_of_lane_data, ego_data.trajectory_points, params_); + const auto calculate_times_us = stopwatch.toc("calculate_times"); + + if ( + params_.skip_if_already_overlapping && !ego_data.drivable_lane_polygons.empty() && + !lanelet::geometry::within(ego_data.current_footprint, ego_data.drivable_lane_polygons)) { + RCLCPP_WARN(logger_, "Ego is already out of lane, skipping the module\n"); + debug_publisher_->publish(out_of_lane::debug::create_debug_marker_array( + ego_data, out_of_lane_data, objects, debug_data_)); + return result; + } + if ( // reset the previous inserted point if the timer expired - prev_inserted_point_ && - (clock_->now() - prev_inserted_point_time_).seconds() > params_.min_decision_duration) - prev_inserted_point_.reset(); - auto point_to_insert = - out_of_lane::calculate_slowdown_point(ego_data, decisions, prev_inserted_point_, params_); - const auto calc_slowdown_points_us = stopwatch.toc("calc_slowdown_points"); - stopwatch.tic("insert_slowdown_points"); - debug_data_.slowdowns.clear(); - if ( // reset the timer if there is no previous inserted point or if we avoid the same lane - point_to_insert && - (!prev_inserted_point_ || prev_inserted_point_->slowdown.lane_to_avoid.id() == - point_to_insert->slowdown.lane_to_avoid.id())) - prev_inserted_point_time_ = clock_->now(); - // reuse previous stop point if there is no new one or if its velocity is not higher than the new + previous_slowdown_pose_ && + (clock_->now() - previous_slowdown_time_).seconds() > params_.min_decision_duration) { + previous_slowdown_pose_.reset(); + } + + stopwatch.tic("calculate_slowdown_point"); + auto slowdown_pose = out_of_lane::calculate_slowdown_point(ego_data, out_of_lane_data, params_); + const auto calculate_slowdown_point_us = stopwatch.toc("calculate_slowdown_point"); + + if ( // reset the timer if there is no previous inserted point + slowdown_pose && (!previous_slowdown_pose_)) { + previous_slowdown_time_ = clock_->now(); + } + // reuse previous stop pose if there is no new one or if its velocity is not higher than the new // one and its arc length is lower - const auto should_use_prev_inserted_point = [&]() { - if ( - point_to_insert && prev_inserted_point_ && - prev_inserted_point_->slowdown.velocity <= point_to_insert->slowdown.velocity) { - const auto arc_length = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, 0LU, point_to_insert->point.pose.position); - const auto prev_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, 0LU, prev_inserted_point_->point.pose.position); + const auto should_use_previous_pose = [&]() { + if (slowdown_pose && previous_slowdown_pose_) { + const auto arc_length = + motion_utils::calcSignedArcLength(ego_trajectory_points, 0LU, slowdown_pose->position); + const auto prev_arc_length = motion_utils::calcSignedArcLength( + ego_trajectory_points, 0LU, previous_slowdown_pose_->position); return prev_arc_length < arc_length; } - return !point_to_insert && prev_inserted_point_; + return !slowdown_pose && previous_slowdown_pose_; }(); - if (should_use_prev_inserted_point) { + if (should_use_previous_pose) { // if the trajectory changed the prev point is no longer on the trajectory so we project it - const auto insert_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, 0LU, prev_inserted_point_->point.pose.position); - prev_inserted_point_->point.pose = - autoware::motion_utils::calcInterpolatedPose(ego_trajectory_points, insert_arc_length); - point_to_insert = prev_inserted_point_; + const auto new_arc_length = motion_utils::calcSignedArcLength( + ego_trajectory_points, 0LU, previous_slowdown_pose_->position); + slowdown_pose = motion_utils::calcInterpolatedPose(ego_trajectory_points, new_arc_length); } - if (point_to_insert) { - prev_inserted_point_ = point_to_insert; - RCLCPP_DEBUG(logger_, "Avoiding lane %lu", point_to_insert->slowdown.lane_to_avoid.id()); - debug_data_.slowdowns = {*point_to_insert}; - if (point_to_insert->slowdown.velocity == 0.0) - result.stop_points.push_back(point_to_insert->point.pose.position); - else + if (slowdown_pose) { + const auto arc_length = + motion_utils::calcSignedArcLength( + ego_trajectory_points, ego_data.first_trajectory_idx, slowdown_pose->position) - + ego_data.longitudinal_offset_to_first_trajectory_index; + const auto slowdown_velocity = + arc_length <= params_.stop_dist_threshold ? 0.0 : params_.slow_velocity; + previous_slowdown_pose_ = slowdown_pose; + if (slowdown_velocity == 0.0) { + result.stop_points.push_back(slowdown_pose->position); + } else { result.slowdown_intervals.emplace_back( - point_to_insert->point.pose.position, point_to_insert->point.pose.position, - point_to_insert->slowdown.velocity); - - const auto is_approaching = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, ego_data.pose.position, - point_to_insert->point.pose.position) > 0.1 && - ego_data.velocity > 0.1; - const auto status = is_approaching ? autoware::motion_utils::VelocityFactor::APPROACHING - : autoware::motion_utils::VelocityFactor::STOPPED; + slowdown_pose->position, slowdown_pose->position, slowdown_velocity); + } + + const auto is_approaching = + motion_utils::calcSignedArcLength( + ego_trajectory_points, ego_data.pose.position, slowdown_pose->position) > 0.1 && + planner_data->current_odometry.twist.twist.linear.x > 0.1; + const auto status = is_approaching ? motion_utils::VelocityFactor::APPROACHING + : motion_utils::VelocityFactor::STOPPED; velocity_factor_interface_.set( - ego_trajectory_points, ego_data.pose, point_to_insert->point.pose, status, "out_of_lane"); + ego_trajectory_points, ego_data.pose, *slowdown_pose, status, "out_of_lane"); result.velocity_factor = velocity_factor_interface_.get(); - } else if (!decisions.empty()) { - RCLCPP_WARN(logger_, "Could not insert stop point (would violate max deceleration limits)"); + virtual_wall_marker_creator.add_virtual_walls( + out_of_lane::debug::create_virtual_walls(*slowdown_pose, slowdown_velocity == 0.0, params_)); + virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); + } else if (std::any_of( + out_of_lane_data.outside_points.begin(), out_of_lane_data.outside_points.end(), + [](const auto & p) { return p.to_avoid; })) { + RCLCPP_WARN( + logger_, "[out_of_lane] Could not insert slowdown point because of deceleration limits"); } - const auto insert_slowdown_points_us = stopwatch.toc("insert_slowdown_points"); - debug_data_.ranges = inputs.ranges; + stopwatch.tic("gen_debug"); + const auto markers = + out_of_lane::debug::create_debug_marker_array(ego_data, out_of_lane_data, objects, debug_data_); + const auto markers_us = stopwatch.toc("gen_debug"); + stopwatch.tic("pub"); + debug_publisher_->publish(markers); + const auto pub_markers_us = stopwatch.toc("pub"); const auto total_time_us = stopwatch.toc(); - RCLCPP_DEBUG( - logger_, - "Total time = %2.2fus\n" - "\tpreprocessing = %2.0fus\n" - "\tcalculate_lanelets = %2.0fus\n" - "\tcalculate_trajectory_footprints = %2.0fus\n" - "\tcalculate_overlapping_ranges = %2.0fus\n" - "\tfilter_pred_objects = %2.0fus\n" - "\tcalculate_decisions = %2.0fus\n" - "\tcalc_slowdown_points = %2.0fus\n" - "\tinsert_slowdown_points = %2.0fus\n", - preprocessing_us, total_time_us, calculate_lanelets_us, calculate_trajectory_footprints_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["preprocessing"] = preprocessing_us / 1000; 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["calculate_out_of_lane_areas"] = calculate_out_of_lane_areas_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["calculate_time_collisions"] = calculate_time_collisions_us / 1000; + processing_times["calculate_times"] = calculate_times_us / 1000; + processing_times["calculate_slowdown_point"] = calculate_slowdown_point_us / 1000; + processing_times["generate_markers"] = markers_us / 1000; + processing_times["publish_markers"] = pub_markers_us / 1000; processing_times["Total"] = total_time_us / 1000; processing_diag_publisher_->publish(processing_times); tier4_debug_msgs::msg::Float64Stamped processing_time_msg; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp index 310a73c04d643..fc0cd4ac539ca 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp @@ -23,12 +23,14 @@ #include #include +#include #include #include #include #include +#include #include #include @@ -46,17 +48,28 @@ class OutOfLaneModule : public PluginModuleInterface private: void init_parameters(rclcpp::Node & node); - out_of_lane::PlannerParam params_; + /// @brief resize the trajectory to start from the segment closest to ego and to have at most the + /// given length + static void limit_trajectory_size( + out_of_lane::EgoData & ego_data, + const std::vector & ego_trajectory_points, + const double max_arc_length); + /// @brief calculate the minimum stop and slowdown distances of ego + static void calculate_min_stop_and_slowdown_distances( + out_of_lane::EgoData & ego_data, const PlannerData & planner_data, + std::optional & previous_slowdown_pose_, const double slow_velocity); + + out_of_lane::PlannerParam params_{}; inline static const std::string ns_ = "out_of_lane"; - std::string module_name_; - std::optional prev_inserted_point_{}; - rclcpp::Clock::SharedPtr clock_{}; - rclcpp::Time prev_inserted_point_time_{}; + std::string module_name_{"uninitialized"}; + rclcpp::Clock::SharedPtr clock_{nullptr}; + std::optional previous_slowdown_pose_{std::nullopt}; + rclcpp::Time previous_slowdown_time_{0}; protected: // Debug - mutable out_of_lane::DebugData debug_data_; + mutable out_of_lane::DebugData debug_data_{}; }; } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp deleted file mode 100644 index a1a722bb07f14..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp +++ /dev/null @@ -1,127 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "overlapping_range.hpp" - -#include -#include - -#include - -#include -#include - -#include - -namespace autoware::motion_velocity_planner::out_of_lane -{ - -Overlap calculate_overlap( - const lanelet::BasicPolygon2d & trajectory_footprint, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet) -{ - Overlap overlap; - const auto & left_bound = lanelet.leftBound2d().basicLineString(); - const auto & right_bound = lanelet.rightBound2d().basicLineString(); - // TODO(Maxime): these intersects (for each trajectory footprint, for each lanelet) are too - // expensive - const auto overlap_left = boost::geometry::intersects(trajectory_footprint, left_bound); - const auto overlap_right = boost::geometry::intersects(trajectory_footprint, right_bound); - - lanelet::BasicPolygons2d overlapping_polygons; - if (overlap_left || overlap_right) - boost::geometry::intersection( - trajectory_footprint, lanelet.polygon2d().basicPolygon(), overlapping_polygons); - for (const auto & overlapping_polygon : overlapping_polygons) { - for (const auto & point : overlapping_polygon) { - if (overlap_left && overlap_right) - overlap.inside_distance = boost::geometry::distance(left_bound, right_bound); - else if (overlap_left) - overlap.inside_distance = - std::max(overlap.inside_distance, boost::geometry::distance(point, left_bound)); - else if (overlap_right) - overlap.inside_distance = - std::max(overlap.inside_distance, boost::geometry::distance(point, right_bound)); - geometry_msgs::msg::Pose p; - p.position.x = point.x(); - p.position.y = point.y(); - const auto length = lanelet::utils::getArcCoordinates(trajectory_lanelets, p).length; - if (length > overlap.max_arc_length) { - overlap.max_arc_length = length; - overlap.max_overlap_point = point; - } - if (length < overlap.min_arc_length) { - overlap.min_arc_length = length; - overlap.min_overlap_point = point; - } - } - } - return overlap; -} - -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet, - const PlannerParam & params) -{ - OverlapRanges ranges; - OtherLane other_lane(lanelet); - std::vector overlaps; - for (auto i = 0UL; i < trajectory_footprints.size(); ++i) { - const auto overlap = calculate_overlap(trajectory_footprints[i], trajectory_lanelets, lanelet); - const auto has_overlap = overlap.inside_distance > params.overlap_min_dist; - if (has_overlap) { // open/update the range - overlaps.push_back(overlap); - if (!other_lane.range_is_open) { - other_lane.first_range_bound.index = i; - other_lane.first_range_bound.point = overlap.min_overlap_point; - other_lane.first_range_bound.arc_length = - overlap.min_arc_length - params.overlap_extra_length; - other_lane.first_range_bound.inside_distance = overlap.inside_distance; - other_lane.range_is_open = true; - } - other_lane.last_range_bound.index = i; - other_lane.last_range_bound.point = overlap.max_overlap_point; - other_lane.last_range_bound.arc_length = overlap.max_arc_length + params.overlap_extra_length; - other_lane.last_range_bound.inside_distance = overlap.inside_distance; - } else if (other_lane.range_is_open) { // !has_overlap: close the range if it is open - ranges.push_back(other_lane.close_range()); - ranges.back().debug.overlaps = overlaps; - overlaps.clear(); - } - } - // close the range if it is still open - if (other_lane.range_is_open) { - ranges.push_back(other_lane.close_range()); - ranges.back().debug.overlaps = overlaps; - overlaps.clear(); - } - return ranges; -} - -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelets & lanelets, - const PlannerParam & params) -{ - OverlapRanges ranges; - for (auto & lanelet : lanelets) { - const auto lanelet_ranges = - calculate_overlapping_ranges(trajectory_footprints, trajectory_lanelets, lanelet, params); - ranges.insert(ranges.end(), lanelet_ranges.begin(), lanelet_ranges.end()); - } - return ranges; -} - -} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp deleted file mode 100644 index bc5872db16e03..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef OVERLAPPING_RANGE_HPP_ -#define OVERLAPPING_RANGE_HPP_ - -#include "types.hpp" - -#include - -#include - -#include - -namespace autoware::motion_velocity_planner::out_of_lane -{ - -/// @brief calculate the overlap between the given footprint and lanelet -/// @param [in] path_footprint footprint used to calculate the overlap -/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego -/// trajectory -/// @param [in] lanelet lanelet used to calculate the overlap -/// @return the found overlap between the footprint and the lanelet -Overlap calculate_overlap( - const lanelet::BasicPolygon2d & trajectory_footprint, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet); -/// @brief calculate the overlapping ranges between the trajectory footprints and a lanelet -/// @param [in] trajectory_footprints footprints used to calculate the overlaps -/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego -/// trajectory -/// @param [in] lanelet lanelet used to calculate the overlaps -/// @param [in] params parameters -/// @return the overlapping ranges found between the footprints and the lanelet -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet, - const PlannerParam & params); -/// @brief calculate the overlapping ranges between the trajectory footprints and some lanelets -/// @param [in] trajectory_footprints footprints used to calculate the overlaps -/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego -/// trajectory -/// @param [in] lanelets lanelets used to calculate the overlaps -/// @param [in] params parameters -/// @return the overlapping ranges found between the footprints and the lanelets, sorted by -/// increasing arc length along the trajectory -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelets & lanelets, - const PlannerParam & params); -} // namespace autoware::motion_velocity_planner::out_of_lane - -#endif // OVERLAPPING_RANGE_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp index 96c54064e296c..c3714c5609135 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp @@ -28,52 +28,45 @@ #include #include +#include -#include -#include -#include #include +#include #include #include #include namespace autoware::motion_velocity_planner::out_of_lane { -using autoware_planning_msgs::msg::TrajectoryPoint; +using Polygons = boost::geometry::model::multi_polygon; -/// @brief parameters for the "out of lane" module +/// @brief parameters for the out_of_lane module struct PlannerParam { std::string mode; // mode used to consider a conflict with an object bool skip_if_already_overlapping; // if true, do not run the module when ego already overlaps // another lane + double max_arc_length; // [m] maximum arc length along the trajectory to check for collision - double time_threshold; // [s](mode="threshold") objects time threshold - double intervals_ego_buffer; // [s](mode="intervals") buffer to extend the ego time range - double intervals_obj_buffer; // [s](mode="intervals") buffer to extend the objects time range + double time_threshold; // [s](mode="threshold") objects time threshold double ttc_threshold; // [s](mode="ttc") threshold on time to collision between ego and an object - double ego_min_velocity; // [m/s] minimum velocity of ego used to calculate its ttc or time range - bool objects_use_predicted_paths; // whether to use the objects' predicted paths bool objects_cut_predicted_paths_beyond_red_lights; // whether to cut predicted paths beyond red // lights' stop lines - double objects_min_vel; // [m/s] objects lower than this velocity will be ignored - double objects_min_confidence; // minimum confidence to consider a predicted path - double objects_dist_buffer; // [m] distance buffer used to determine if a collision will occur in - // the other lane + double objects_min_vel; // [m/s] objects lower than this velocity will be ignored + double objects_min_confidence; // minimum confidence to consider a predicted path bool objects_ignore_behind_ego; // if true, objects behind the ego vehicle are ignored - double overlap_extra_length; // [m] extra length to add around an overlap range - double overlap_min_dist; // [m] min distance inside another lane to consider an overlap - // action to insert in the trajectory if an object causes a conflict at an overlap - bool skip_if_over_max_decel; // if true, skip the action if it causes more than the max decel - double lon_dist_buffer; // [m] safety distance buffer to keep in front of the ego vehicle - double lat_dist_buffer; // [m] safety distance buffer to keep on the side of the ego vehicle - double slow_velocity; - double slow_dist_threshold; - double stop_dist_threshold; - double precision; // [m] precision when inserting a stop pose in the trajectory - double min_decision_duration; // [s] minimum duration needed a decision can be canceled + // action to insert in the trajectory if an object causes a collision at an overlap + double lon_dist_buffer; // [m] safety distance buffer to keep in front of the ego vehicle + double lat_dist_buffer; // [m] safety distance buffer to keep on the side of the ego vehicle + double slow_velocity; // [m/s] slowdown velocity + double stop_dist_threshold; // [m] if a collision is detected bellow this distance ahead of ego, + // try to insert a stop point + double precision; // [m] precision when inserting a stop pose in the trajectory + double + min_decision_duration; // [s] duration needed before a stop or slowdown point can be removed + // ego dimensions used to create its polygon footprint double front_offset; // [m] front offset (from vehicle info) double rear_offset; // [m] rear offset (from vehicle info) @@ -85,98 +78,6 @@ struct PlannerParam double extra_left_offset; // [m] extra left distance }; -struct EnterExitTimes -{ - double enter_time{}; - double exit_time{}; -}; -struct RangeTimes -{ - EnterExitTimes ego{}; - EnterExitTimes object{}; -}; - -/// @brief action taken by the "out of lane" module -struct Slowdown -{ - size_t target_trajectory_idx{}; // we want to slowdown before this trajectory index - double velocity{}; // desired slow down velocity - lanelet::ConstLanelet lane_to_avoid{}; // we want to slowdown before entering this lane -}; -/// @brief slowdown to insert in a trajectory -struct SlowdownToInsert -{ - Slowdown slowdown{}; - autoware_planning_msgs::msg::TrajectoryPoint point{}; -}; - -/// @brief bound of an overlap range (either the first, or last bound) -struct RangeBound -{ - size_t index{}; - lanelet::BasicPoint2d point{}; - double arc_length{}; - double inside_distance{}; -}; - -/// @brief representation of an overlap between the ego footprint and some other lane -struct Overlap -{ - double inside_distance = 0.0; ///!< distance inside the overlap - double min_arc_length = std::numeric_limits::infinity(); - double max_arc_length = 0.0; - lanelet::BasicPoint2d min_overlap_point{}; ///!< point with min arc length - lanelet::BasicPoint2d max_overlap_point{}; ///!< point with max arc length -}; - -/// @brief range along the trajectory where ego overlaps another lane -struct OverlapRange -{ - lanelet::ConstLanelet lane{}; - size_t entering_trajectory_idx{}; - size_t exiting_trajectory_idx{}; - lanelet::BasicPoint2d entering_point{}; // pose of the overlapping point closest along the lane - lanelet::BasicPoint2d exiting_point{}; // pose of the overlapping point furthest along the lane - double inside_distance{}; // [m] how much ego footprint enters the lane - mutable struct - { - std::vector overlaps{}; - std::optional decision{}; - RangeTimes times{}; - std::optional object{}; - } debug; -}; -using OverlapRanges = std::vector; -/// @brief representation of a lane and its current overlap range -struct OtherLane -{ - bool range_is_open = false; - RangeBound first_range_bound{}; - RangeBound last_range_bound{}; - lanelet::ConstLanelet lanelet{}; - lanelet::BasicPolygon2d polygon{}; - - explicit OtherLane(lanelet::ConstLanelet ll) : lanelet(std::move(ll)) - { - polygon = lanelet.polygon2d().basicPolygon(); - } - - [[nodiscard]] OverlapRange close_range() - { - OverlapRange range; - range.lane = lanelet; - range.entering_trajectory_idx = first_range_bound.index; - range.entering_point = first_range_bound.point; - range.exiting_trajectory_idx = last_range_bound.index; - range.exiting_point = last_range_bound.point; - range.inside_distance = - std::max(first_range_bound.inside_distance, last_range_bound.inside_distance); - range_is_open = false; - last_range_bound = {}; - return range; - } -}; - namespace bgi = boost::geometry::index; struct StopLine { @@ -185,68 +86,52 @@ struct StopLine }; using StopLineNode = std::pair; using StopLinesRtree = bgi::rtree>; -using OutAreaRtree = bgi::rtree, bgi::rstar<16>>; +using OutAreaNode = std::pair; +using OutAreaRtree = bgi::rtree>; /// @brief data related to the ego vehicle struct EgoData { - std::vector trajectory_points{}; + std::vector trajectory_points; + geometry_msgs::msg::Pose pose; size_t first_trajectory_idx{}; - double velocity{}; // [m/s] - double max_decel{}; // [m/s²] - geometry_msgs::msg::Pose pose{}; + double longitudinal_offset_to_first_trajectory_index{}; + double min_stop_distance{}; + double min_slowdown_distance{}; + double min_stop_arc_length{}; + + Polygons drivable_lane_polygons; + + lanelet::BasicPolygon2d current_footprint; + std::vector trajectory_footprints; + StopLinesRtree stop_lines_rtree; }; -/// @brief data needed to make decisions -struct DecisionInputs +struct OutOfLanePoint { - OverlapRanges ranges; - EgoData ego_data; - autoware_perception_msgs::msg::PredictedObjects objects; - std::shared_ptr route_handler; - lanelet::ConstLanelets lanelets; + size_t trajectory_index; + lanelet::BasicPolygon2d outside_ring; + std::set collision_times; + std::optional min_object_arrival_time; + std::optional max_object_arrival_time; + std::optional ttc; + lanelet::ConstLanelets overlapped_lanelets; + bool to_avoid = false; +}; +struct OutOfLaneData +{ + std::vector outside_points; + OutAreaRtree outside_areas_rtree; }; /// @brief debug data struct DebugData { - std::vector footprints; - std::vector slowdowns; - geometry_msgs::msg::Pose ego_pose; - OverlapRanges ranges; - lanelet::BasicPolygon2d current_footprint; - lanelet::ConstLanelets current_overlapped_lanelets; - lanelet::ConstLanelets trajectory_lanelets; - lanelet::ConstLanelets ignored_lanelets; - lanelet::ConstLanelets other_lanelets; - std::vector trajectory_points; - size_t first_trajectory_idx; - - size_t prev_footprints = 0; - size_t prev_slowdowns = 0; - size_t prev_ranges = 0; - size_t prev_current_overlapped_lanelets = 0; - size_t prev_ignored_lanelets = 0; - size_t prev_trajectory_lanelets = 0; - size_t prev_other_lanelets = 0; - void reset_data() - { - prev_footprints = footprints.size(); - footprints.clear(); - prev_slowdowns = slowdowns.size(); - slowdowns.clear(); - prev_ranges = ranges.size(); - ranges.clear(); - prev_current_overlapped_lanelets = current_overlapped_lanelets.size(); - current_overlapped_lanelets.clear(); - prev_ignored_lanelets = ignored_lanelets.size(); - ignored_lanelets.clear(); - prev_trajectory_lanelets = trajectory_lanelets.size(); - trajectory_lanelets.clear(); - prev_other_lanelets = other_lanelets.size(); - other_lanelets.clear(); - } + size_t prev_out_of_lane_areas = 0; + size_t prev_ttcs = 0; + size_t prev_objects = 0; + size_t prev_stop_line = 0; }; } // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt index f1eb7ff047fdc..ffc06aa8cc2f8 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt @@ -5,9 +5,20 @@ find_package(autoware_cmake REQUIRED) autoware_package() -# ament_auto_add_library(${PROJECT_NAME}_lib SHARED -# DIRECTORY src -# ) +ament_auto_add_library(${PROJECT_NAME}_lib SHARED + DIRECTORY src +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/test_collision_checker.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + gtest_main + ${PROJECT_NAME}_lib + ) + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() ament_auto_package(INSTALL_TO_SHARE include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp new file mode 100644 index 0000000000000..bf471c62af969 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp @@ -0,0 +1,69 @@ +// Copyright 2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ +#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ + +#include + +#include +#include +#include + +#include +#include +#include + +namespace autoware::motion_velocity_planner +{ +namespace bgi = boost::geometry::index; +using RtreeNode = std::pair; +using Rtree = bgi::rtree>; + +/// @brief collision as a trajectory index and corresponding collision points +struct Collision +{ + size_t trajectory_index{}; + autoware::universe_utils::MultiPoint2d collision_points; +}; + +/// @brief collision checker for a trajectory as a sequence of 2D footprints +class CollisionChecker +{ + const autoware::universe_utils::MultiPolygon2d trajectory_footprints_; + std::shared_ptr rtree_; + +public: + /// @brief construct the collisions checker + /// @param trajectory_footprints footprints of the trajectory to be used for collision checking + /// @details internally, the rtree is built with the packing algorithm + explicit CollisionChecker(autoware::universe_utils::MultiPolygon2d trajectory_footprints); + + /// @brief efficiently calculate collisions with a geometry + /// @tparam Geometry boost geometry type + /// @param geometry geometry to check for collisions + /// @return collisions between the trajectory footprints and the input geometry + template + [[nodiscard]] std::vector get_collisions(const Geometry & geometry) const; + + /// @brief direct access to the rtree storing the polygon footprints + /// @return rtree of the polygon footprints + [[nodiscard]] std::shared_ptr get_rtree() const { return rtree_; } + + /// @brief get the size of the trajectory used by this collision checker + [[nodiscard]] size_t trajectory_size() const { return trajectory_footprints_.size(); } +}; +} // namespace autoware::motion_velocity_planner + +#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp index 5dbb872d99ca9..a96587c4465d6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp @@ -15,7 +15,10 @@ #ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ #define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#include +#include #include +#include #include #include @@ -37,12 +40,9 @@ #include #include -#include -#include #include #include #include -#include namespace autoware::motion_velocity_planner { @@ -59,11 +59,11 @@ struct PlannerData } // msgs from callbacks that are used for data-ready - nav_msgs::msg::Odometry current_odometry{}; - geometry_msgs::msg::AccelWithCovarianceStamped current_acceleration{}; - autoware_perception_msgs::msg::PredictedObjects predicted_objects{}; - pcl::PointCloud no_ground_pointcloud{}; - nav_msgs::msg::OccupancyGrid occupancy_grid{}; + nav_msgs::msg::Odometry current_odometry; + geometry_msgs::msg::AccelWithCovarianceStamped current_acceleration; + autoware_perception_msgs::msg::PredictedObjects predicted_objects; + pcl::PointCloud no_ground_pointcloud; + nav_msgs::msg::OccupancyGrid occupancy_grid; std::shared_ptr route_handler; // nearest search @@ -79,7 +79,7 @@ struct PlannerData tier4_v2x_msgs::msg::VirtualTrafficLightStateArray virtual_traffic_light_states; // velocity smoother - std::shared_ptr velocity_smoother_{}; + std::shared_ptr velocity_smoother_; // parameters autoware::vehicle_info_utils::VehicleInfo vehicle_info_; @@ -88,7 +88,7 @@ struct PlannerData *@brief queries the traffic signal information of given Id. if keep_last_observation = true, *recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation */ - std::optional get_traffic_signal( + [[nodiscard]] std::optional get_traffic_signal( const lanelet::Id id, const bool keep_last_observation = false) const { const auto & traffic_light_id_map = @@ -98,6 +98,15 @@ struct PlannerData } return std::make_optional(traffic_light_id_map.at(id)); } + + [[nodiscard]] std::optional calculate_min_deceleration_distance( + const double target_velocity) const + { + return motion_utils::calcDecelDistWithJerkAndAccConstraints( + current_odometry.twist.twist.linear.x, target_velocity, + current_acceleration.accel.accel.linear.x, velocity_smoother_->getMinDecel(), + std::abs(velocity_smoother_->getMinJerk()), velocity_smoother_->getMinJerk()); + } }; } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp new file mode 100644 index 0000000000000..6e84b63a3c7fc --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp @@ -0,0 +1,70 @@ +// Copyright 2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/motion_velocity_planner_common/collision_checker.hpp" + +namespace autoware::motion_velocity_planner +{ +CollisionChecker::CollisionChecker(autoware::universe_utils::MultiPolygon2d trajectory_footprints) +: trajectory_footprints_(std::move(trajectory_footprints)) +{ + std::vector nodes; + nodes.reserve(trajectory_footprints_.size()); + for (auto i = 0UL; i < trajectory_footprints_.size(); ++i) { + nodes.emplace_back( + boost::geometry::return_envelope(trajectory_footprints_[i]), + i); + } + rtree_ = std::make_shared(nodes.begin(), nodes.end()); +} + +template +std::vector CollisionChecker::get_collisions(const Geometry & geometry) const +{ + std::vector collisions; + std::vector approximate_results; + autoware::universe_utils::MultiPoint2d intersections; + ; + rtree_->query(bgi::intersects(geometry), std::back_inserter(approximate_results)); + for (const auto & result : approximate_results) { + intersections.clear(); + boost::geometry::intersection(trajectory_footprints_[result.second], geometry, intersections); + if (!intersections.empty()) { + Collision c; + c.trajectory_index = result.second; + c.collision_points = intersections; + collisions.push_back(c); + } + } + return collisions; +} + +template std::vector CollisionChecker::get_collisions( + const autoware::universe_utils::Point2d & geometry) const; +template std::vector CollisionChecker::get_collisions( + const autoware::universe_utils::Line2d & geometry) const; +template std::vector +CollisionChecker::get_collisions( + const autoware::universe_utils::MultiPolygon2d & geometry) const; + +// @warn Multi geometries usually lead to very inefficient queries +template std::vector +CollisionChecker::get_collisions( + const autoware::universe_utils::MultiPoint2d & geometry) const; +template std::vector +CollisionChecker::get_collisions( + const autoware::universe_utils::MultiLineString2d & geometry) const; +template std::vector CollisionChecker::get_collisions< + autoware::universe_utils::Polygon2d>(const autoware::universe_utils::Polygon2d & geometry) const; +} // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp new file mode 100644 index 0000000000000..df813db336a9d --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp @@ -0,0 +1,176 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/motion_velocity_planner_common/collision_checker.hpp" + +#include + +#include + +#include +#include + +using autoware::motion_velocity_planner::CollisionChecker; +using autoware::universe_utils::Line2d; +using autoware::universe_utils::MultiLineString2d; +using autoware::universe_utils::MultiPoint2d; +using autoware::universe_utils::MultiPolygon2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; + +Point2d random_point() +{ + static std::random_device r; + static std::default_random_engine e1(r()); + static std::uniform_real_distribution uniform_dist(-100, 100); + return {uniform_dist(e1), uniform_dist(e1)}; +} + +Line2d random_line() +{ + const auto point = random_point(); + const auto point2 = Point2d{point.x() + 1, point.y() + 1}; + const auto point3 = Point2d{point2.x() - 1, point2.y() + 1}; + const auto point4 = Point2d{point3.x() + 1, point3.y() + 1}; + return {point, point2, point3, point4}; +} + +Polygon2d random_polygon() +{ + Polygon2d polygon; + const auto point = random_point(); + const auto point2 = Point2d{point.x() + 1, point.y() + 4}; + const auto point3 = Point2d{point.x() + 4, point.y() + 4}; + const auto point4 = Point2d{point.x() + 3, point.y() + 1}; + polygon.outer() = {point, point2, point3, point4, point}; + return polygon; +} + +bool all_within(const MultiPoint2d & pts1, const MultiPoint2d & pts2) +{ + // results from the collision checker and the direct checks can have some small precision errors + constexpr auto eps = 1e-3; + for (const auto & p1 : pts1) { + bool found = false; + for (const auto & p2 : pts2) { + if (boost::geometry::comparable_distance(p1, p2) < eps) { + found = true; + break; + } + } + if (!found) return false; + } + return true; +} + +TEST(TestCollisionChecker, Benchmark) +{ + constexpr auto nb_ego_footprints = 1000; + constexpr auto nb_obstacles = 1000; + MultiPolygon2d ego_footprints; + ego_footprints.reserve(nb_ego_footprints); + for (auto i = 0; i < nb_ego_footprints; ++i) { + ego_footprints.push_back(random_polygon()); + } + const auto cc_constr_start = std::chrono::system_clock::now(); + CollisionChecker collision_checker(ego_footprints); + const auto cc_constr_end = std::chrono::system_clock::now(); + const auto cc_constr_ns = + std::chrono::duration_cast(cc_constr_end - cc_constr_start).count(); + std::printf( + "Collision checker construction (with %d footprints): %ld ns\n", nb_ego_footprints, + cc_constr_ns); + MultiPolygon2d poly_obstacles; + MultiPoint2d point_obstacles; + MultiLineString2d line_obstacles; + for (auto i = 0; i < nb_obstacles; ++i) { + poly_obstacles.push_back(random_polygon()); + point_obstacles.push_back(random_point()); + line_obstacles.push_back(random_line()); + } + const auto check_obstacles_one_by_one = [&](const auto & obstacles) { + std::chrono::nanoseconds collision_checker_ns{}; + std::chrono::nanoseconds naive_ns{}; + for (const auto & obs : obstacles) { + const auto cc_start = std::chrono::system_clock::now(); + const auto collisions = collision_checker.get_collisions(obs); + MultiPoint2d cc_collision_points; + for (const auto & c : collisions) + cc_collision_points.insert( + cc_collision_points.end(), c.collision_points.begin(), c.collision_points.end()); + const auto cc_end = std::chrono::system_clock::now(); + const auto naive_start = std::chrono::system_clock::now(); + MultiPoint2d naive_collision_points; + for (const auto & ego_footprint : ego_footprints) { + MultiPoint2d points; + boost::geometry::intersection(ego_footprint, obs, points); + naive_collision_points.insert(naive_collision_points.end(), points.begin(), points.end()); + } + const auto naive_end = std::chrono::system_clock::now(); + const auto equal = all_within(cc_collision_points, naive_collision_points) && + all_within(naive_collision_points, cc_collision_points); + EXPECT_TRUE(equal); + if (!equal) { + std::cout << "cc: " << boost::geometry::wkt(cc_collision_points) << std::endl; + std::cout << "naive: " << boost::geometry::wkt(naive_collision_points) << std::endl; + } + collision_checker_ns += + std::chrono::duration_cast(cc_end - cc_start); + naive_ns += std::chrono::duration_cast(naive_end - naive_start); + } + std::printf("%20s%10ld ns\n", "collision checker : ", collision_checker_ns.count()); + std::printf("%20s%10ld ns\n", "naive : ", naive_ns.count()); + }; + const auto check_obstacles = [&](const auto & obstacles) { + std::chrono::nanoseconds collision_checker_ns{}; + std::chrono::nanoseconds naive_ns{}; + const auto cc_start = std::chrono::system_clock::now(); + const auto collisions = collision_checker.get_collisions(obstacles); + MultiPoint2d cc_collision_points; + for (const auto & c : collisions) + cc_collision_points.insert( + cc_collision_points.end(), c.collision_points.begin(), c.collision_points.end()); + const auto cc_end = std::chrono::system_clock::now(); + const auto naive_start = std::chrono::system_clock::now(); + MultiPoint2d naive_collision_points; + boost::geometry::intersection(ego_footprints, obstacles, naive_collision_points); + const auto naive_end = std::chrono::system_clock::now(); + const auto equal = all_within(cc_collision_points, naive_collision_points) && + all_within(naive_collision_points, cc_collision_points); + EXPECT_TRUE(equal); + if (!equal) { + std::cout << "cc: " << boost::geometry::wkt(cc_collision_points) << std::endl; + std::cout << "naive: " << boost::geometry::wkt(naive_collision_points) << std::endl; + } + collision_checker_ns += std::chrono::duration_cast(cc_end - cc_start); + naive_ns += std::chrono::duration_cast(naive_end - naive_start); + std::printf("%20s%10ld ns\n", "collision checker : ", collision_checker_ns.count()); + std::printf("%20s%10ld ns\n", "naive : ", naive_ns.count()); + }; + + std::cout << "* check one by one\n"; + std::printf("%d Polygons:\n", nb_obstacles); + check_obstacles_one_by_one(poly_obstacles); + std::printf("%d Lines:\n", nb_obstacles); + check_obstacles_one_by_one(line_obstacles); + std::printf("%d Points:\n", nb_obstacles); + check_obstacles_one_by_one(point_obstacles); + std::cout << "* check all at once\n"; + std::printf("%d Polygons:\n", nb_obstacles); + check_obstacles(poly_obstacles); + std::printf("%d Lines:\n", nb_obstacles); + check_obstacles(line_obstacles); + std::printf("%d Points:\n", nb_obstacles); + check_obstacles(point_obstacles); +} 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 76b64c0a4d5e2..9a08616b8fe7b 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 @@ -22,7 +22,6 @@ #include #include #include -#include #include #include @@ -83,8 +82,11 @@ 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); + processing_time_publisher_ = + this->create_publisher("~/debug/processing_time_ms", 1); + debug_viz_pub_ = + this->create_publisher("~/debug/markers", 1); + diagnostics_pub_ = this->create_publisher("/diagnostics", 10); // Parameters smooth_velocity_before_planning_ = declare_parameter("smooth_velocity_before_planning"); @@ -98,7 +100,7 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & // Initialize PlannerManager for (const auto & name : declare_parameter>("launch_modules")) { // workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter. - if (name == "") { + if (name.empty()) { break; } planner_manager_.load_module_plugin(*this, name); @@ -134,7 +136,7 @@ bool MotionVelocityPlannerNode::update_planner_data() const auto check_with_log = [&](const auto ptr, const auto & log) { constexpr auto throttle_duration = 3000; // [ms] if (!ptr) { - RCLCPP_INFO_THROTTLE(get_logger(), clock, throttle_duration, log); + RCLCPP_INFO_THROTTLE(get_logger(), clock, throttle_duration, "%s", log); is_ready = false; return false; } @@ -277,7 +279,6 @@ void MotionVelocityPlannerNode::on_trajectory( autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points{ input_trajectory_msg->points.begin(), input_trajectory_msg->points.end()}; - 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); @@ -293,6 +294,13 @@ void MotionVelocityPlannerNode::on_trajectory( processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = processing_times["Total"]; processing_time_publisher_->publish(processing_time_msg); + + std::shared_ptr diagnostics = + planner_manager_.get_diagnostics(get_clock()->now()); + if (!diagnostics->status.empty()) { + diagnostics_pub_->publish(*diagnostics); + } + planner_manager_.clear_diagnostics(); } void MotionVelocityPlannerNode::insert_stop( @@ -325,7 +333,8 @@ void MotionVelocityPlannerNode::insert_slowdown( autoware::motion_utils::insertTargetPoint(to_seg_idx, slowdown_interval.to, trajectory.points); if (from_insert_idx && to_insert_idx) { for (auto idx = *from_insert_idx; idx <= *to_insert_idx; ++idx) - trajectory.points[idx].longitudinal_velocity_mps = slowdown_interval.velocity; + trajectory.points[idx].longitudinal_velocity_mps = + static_cast(slowdown_interval.velocity); } else { RCLCPP_WARN(get_logger(), "Failed to insert slowdown point"); } @@ -360,16 +369,14 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s autoware::motion_velocity_planner::TrajectoryPoints clipped; autoware::motion_velocity_planner::TrajectoryPoints traj_smoothed; clipped.insert( - clipped.end(), traj_resampled.begin() + traj_resampled_closest, traj_resampled.end()); + clipped.end(), std::next(traj_resampled.begin(), static_cast(traj_resampled_closest)), + traj_resampled.end()); if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories, false)) { RCLCPP_ERROR(get_logger(), "failed to smooth"); } - traj_smoothed.insert( - traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest); - if (external_v_limit) { autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( - traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); + 0LU, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); } return traj_smoothed; } @@ -377,13 +384,21 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s autoware_planning_msgs::msg::Trajectory MotionVelocityPlannerNode::generate_trajectory( autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points) { + universe_utils::StopWatch stop_watch; autoware_planning_msgs::msg::Trajectory output_trajectory_msg; output_trajectory_msg.points = {input_trajectory_points.begin(), input_trajectory_points.end()}; - if (smooth_velocity_before_planning_) + if (smooth_velocity_before_planning_) { + stop_watch.tic("smooth"); input_trajectory_points = smooth_trajectory(input_trajectory_points, planner_data_); - const auto resampled_trajectory = - autoware::motion_utils::resampleTrajectory(output_trajectory_msg, 0.5); - + RCLCPP_DEBUG(get_logger(), "smooth: %2.2f us", stop_watch.toc("smooth")); + } + autoware_planning_msgs::msg::Trajectory smooth_velocity_trajectory; + smooth_velocity_trajectory.points = { + input_trajectory_points.begin(), input_trajectory_points.end()}; + auto resampled_trajectory = + autoware::motion_utils::resampleTrajectory(smooth_velocity_trajectory, 0.5); + motion_utils::calculate_time_from_start( + resampled_trajectory.points, planner_data_.current_odometry.pose.pose.position); const auto planning_results = planner_manager_.plan_velocities( resampled_trajectory.points, std::make_shared(planner_data_)); 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 8debb9cbedf00..b143018bb0e1e 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 @@ -43,6 +43,8 @@ #include #include +using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + namespace autoware::motion_velocity_planner { using autoware_map_msgs::msg::LaneletMapBin; @@ -100,6 +102,7 @@ class MotionVelocityPlannerNode : public rclcpp::Node autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{this}; rclcpp::Publisher::SharedPtr processing_time_publisher_; autoware::universe_utils::PublishedTimePublisher published_time_publisher_{this}; + rclcpp::Publisher::SharedPtr diagnostics_pub_; // parameters rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr set_param_callback_; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp index 66063fcbaebca..04641e0cea6bb 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp @@ -71,13 +71,60 @@ void MotionVelocityPlannerManager::update_module_parameters( for (auto & plugin : loaded_plugins_) plugin->update_parameters(parameters); } +std::shared_ptr MotionVelocityPlannerManager::make_diagnostic( + const std::string & module_name, const std::string & reason, const bool is_decided) +{ + auto status = std::make_shared(); + status->level = status->OK; + status->name = module_name + '.' + reason; + diagnostic_msgs::msg::KeyValue key_value; + { + // Decision + key_value.key = "decision"; + if (is_decided) + key_value.value = reason; + else + key_value.value = "none"; + status->values.push_back(key_value); + } + // Add other information to the status if necessary in the future. + return status; +} + +std::shared_ptr MotionVelocityPlannerManager::get_diagnostics( + const rclcpp::Time & current_time) const +{ + auto diagnostics = std::make_shared(); + + for (const auto & ds_ptr : diagnostics_) { + if ( + !ds_ptr->values.empty() && ds_ptr->values[0].key == "decision" && + ds_ptr->values[0].value != "none") { + diagnostics->status.push_back(*ds_ptr); + } + } + diagnostics->header.stamp = current_time; + diagnostics->header.frame_id = "map"; + return diagnostics; +} + std::vector MotionVelocityPlannerManager::plan_velocities( const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) { std::vector results; - for (auto & plugin : loaded_plugins_) - results.push_back(plugin->plan(ego_trajectory_points, planner_data)); + for (auto & plugin : loaded_plugins_) { + VelocityPlanningResult res = plugin->plan(ego_trajectory_points, planner_data); + results.push_back(res); + + const auto stop_reason_diag = + make_diagnostic(plugin->get_module_name(), "stop", res.stop_points.size() > 0); + diagnostics_.push_back(stop_reason_diag); + + const auto slow_down_reason_diag = + make_diagnostic(plugin->get_module_name(), "slow_down", res.slowdown_intervals.size() > 0); + diagnostics_.push_back(slow_down_reason_diag); + } return results; } } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp index 20165d359f669..ac2e421d30cb6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -35,6 +36,9 @@ #include #include +using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; +using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + namespace autoware::motion_velocity_planner { class MotionVelocityPlannerManager @@ -48,7 +52,14 @@ class MotionVelocityPlannerManager const std::vector & ego_trajectory_points, const std::shared_ptr planner_data); + // Diagnostic + std::shared_ptr make_diagnostic( + const std::string & module_name, const std::string & reason, const bool is_decided = true); + std::shared_ptr get_diagnostics(const rclcpp::Time & current_time) const; + void clear_diagnostics() { diagnostics_.clear(); } + private: + std::vector> diagnostics_; pluginlib::ClassLoader plugin_loader_; std::vector> loaded_plugins_; }; From c46506269692d9e49714fcad9f00084925e306f3 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 29 Aug 2024 10:18:25 +0900 Subject: [PATCH 08/12] fix(reaction_analyzer): fix include hierarchy of tf2_eigen (#8663) Fixed include hierarchy of tf2_eigen Signed-off-by: Shintaro Sakoda --- tools/reaction_analyzer/include/subscriber.hpp | 2 +- tools/reaction_analyzer/include/topic_publisher.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/reaction_analyzer/include/subscriber.hpp b/tools/reaction_analyzer/include/subscriber.hpp index ff251251373e2..d2a8363e15bf3 100644 --- a/tools/reaction_analyzer/include/subscriber.hpp +++ b/tools/reaction_analyzer/include/subscriber.hpp @@ -16,7 +16,7 @@ #define SUBSCRIBER_HPP_ #include #include -#include +#include #include #include diff --git a/tools/reaction_analyzer/include/topic_publisher.hpp b/tools/reaction_analyzer/include/topic_publisher.hpp index 0c01561fec508..4517b1f793e6c 100644 --- a/tools/reaction_analyzer/include/topic_publisher.hpp +++ b/tools/reaction_analyzer/include/topic_publisher.hpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include #include From afedb2f714957ccd20a886325e11e83241dd6ea6 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Mon, 7 Oct 2024 15:15:08 +0900 Subject: [PATCH 09/12] chore(path_optimizer): add warn msg for exceptional behavior (#9033) (#1580) Signed-off-by: Yuki Takagi --- planning/autoware_path_optimizer/src/mpt_optimizer.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp index 1d49b6cb77d59..7697760fb960c 100644 --- a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp +++ b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp @@ -477,8 +477,13 @@ std::vector MPTOptimizer::optimizeTrajectory(const PlannerData const auto get_prev_optimized_traj_points = [&]() { if (prev_optimized_traj_points_ptr_) { + RCLCPP_WARN(logger_, "return the previous optimized_trajectory as exceptional behavior."); return *prev_optimized_traj_points_ptr_; } + RCLCPP_WARN( + logger_, + "Try to return the previous optimized_trajectory as exceptional behavior, " + "but this failure also. Then return path_smoother output."); return traj_points; }; @@ -505,8 +510,7 @@ std::vector MPTOptimizer::optimizeTrajectory(const PlannerData // 6. optimize steer angles const auto optimized_variables = calcOptimizedSteerAngles(ref_points, obj_mat, const_mat); if (!optimized_variables) { - RCLCPP_INFO_EXPRESSION( - logger_, enable_debug_info_, "return std::nullopt since could not solve qp"); + RCLCPP_WARN(logger_, "return std::nullopt since could not solve qp"); return get_prev_optimized_traj_points(); } From 151d5d7474db9cbef549d167b2b4f130a76485b2 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 17 Oct 2024 16:51:18 +0900 Subject: [PATCH 10/12] chore(autoware_pointcloud_preprocessor): change unnecessary warning message to debug (#8525) (#1590) Co-authored-by: Yi-Hsiang Fang (Vivid) <146902905+vividf@users.noreply.github.com> --- .../src/concatenate_data/concatenate_and_time_sync_nodelet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index e998a79b27f77..d531d1b89b478 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -286,7 +286,7 @@ PointCloudConcatenateDataSynchronizerComponent::computeTransformToAdjustForOldTi // return identity if old_stamp is newer than new_stamp if (old_stamp > new_stamp) { - RCLCPP_WARN_STREAM_THROTTLE( + RCLCPP_DEBUG_STREAM_THROTTLE( get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(), "old_stamp is newer than new_stamp,"); return Eigen::Matrix4f::Identity(); From bad00078065b71ce3ae6fa60ecff83a280f41aef Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Wed, 23 Oct 2024 10:26:01 +0900 Subject: [PATCH 11/12] chore(stop_filter): extract stop_filter.param.yaml to autoware_launch (#8681) (#1591) Co-authored-by: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> --- launch/tier4_localization_launch/launch/localization.launch.xml | 1 + .../pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml | 1 + 2 files changed, 2 insertions(+) diff --git a/launch/tier4_localization_launch/launch/localization.launch.xml b/launch/tier4_localization_launch/launch/localization.launch.xml index cfc09459a5cb1..e75e42da346ad 100644 --- a/launch/tier4_localization_launch/launch/localization.launch.xml +++ b/launch/tier4_localization_launch/launch/localization.launch.xml @@ -14,6 +14,7 @@ + diff --git a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml index bdea584bd58ae..9f840182a007a 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml @@ -22,6 +22,7 @@ + From fdd665d67620403d03bd8e4477f244acd6ec0613 Mon Sep 17 00:00:00 2001 From: Xiaoyu WANG Date: Thu, 24 Oct 2024 08:46:08 +0900 Subject: [PATCH 12/12] fix: remove ScopedTimeTrack which causes goal planner crash (#1599) --- .../src/goal_planner_module.cpp | 8 -------- 1 file changed, 8 deletions(-) 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 54a1c0830fb06..cfe5c797d7130 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 @@ -1244,8 +1244,6 @@ bool GoalPlannerModule::hasDecidedPath( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - return checkDecidingPathStatus( planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, goal_searcher) @@ -1261,8 +1259,6 @@ bool GoalPlannerModule::hasNotDecidedPath( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - return checkDecidingPathStatus( planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, goal_searcher) @@ -1278,8 +1274,6 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - const auto & prev_status = thread_safe_data_.get_prev_data().deciding_path_status; const bool enable_safety_check = parameters.safety_check_params.enable_safety_check; @@ -2375,8 +2369,6 @@ std::pair GoalPlannerModule::isSafePath( const std::shared_ptr & objects_filtering_params, const std::shared_ptr & safety_check_params) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - if (!thread_safe_data_.get_pull_over_path()) { return {false, false}; }