From 1881f970c9a7873ed6fe2154020843638328e12d Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 3 Oct 2022 17:51:23 +0900 Subject: [PATCH 01/28] refactor(route_handler): clang tidy and reserving vector (#1992) * refactor(route_handler): clang tidy and reserving vector Signed-off-by: Muhammad Zulfaqar Azmi * make num constant Co-authored-by: Fumiya Watanabe * make output from getNumLaneToPreferredLane const Signed-off-by: Muhammad Zulfaqar Azmi * const variable wherever possible Signed-off-by: Muhammad Zulfaqar Azmi * use count instead of re-reserve. Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: Fumiya Watanabe --- .../include/route_handler/route_handler.hpp | 12 +- planning/route_handler/src/route_handler.cpp | 254 +++++++++--------- 2 files changed, 140 insertions(+), 126 deletions(-) diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index b0615d8da94d5..c91f9d93ad9cb 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -86,7 +86,7 @@ class RouteHandler const Pose & start_checkpoint, const Pose & goal_checkpoint, lanelet::ConstLanelets * path_lanelets) const; std::vector createMapSegments(const lanelet::ConstLanelets & path_lanelets) const; - bool isRouteLooped(const RouteSections & route_sections) const; + static bool isRouteLooped(const RouteSections & route_sections); // for goal bool isInGoalRouteSection(const lanelet::ConstLanelet & lanelet) const; @@ -222,7 +222,7 @@ class RouteHandler bool getClosestLaneletWithinRoute( const Pose & search_pose, lanelet::ConstLanelet * closest_lanelet) const; lanelet::ConstLanelet getLaneletsFromId(const lanelet::Id id) const; - lanelet::ConstLanelets getLaneletsFromIds(const lanelet::Ids ids) const; + lanelet::ConstLanelets getLaneletsFromIds(const lanelet::Ids & ids) const; lanelet::ConstLanelets getLaneletSequence( const lanelet::ConstLanelet & lanelet, const Pose & current_pose, const double backward_distance, const double forward_distance) const; @@ -247,12 +247,12 @@ class RouteHandler bool use_exact = true) const; bool getLaneChangeTarget( const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const; - bool getPullOverTarget( + static bool getPullOverTarget( const lanelet::ConstLanelets & lanelets, const Pose & goal_pose, - lanelet::ConstLanelet * target_lanelet) const; - bool getPullOutStartLane( + lanelet::ConstLanelet * target_lanelet); + static bool getPullOutStartLane( const lanelet::ConstLanelets & lanelets, const Pose & pose, const double vehicle_width, - lanelet::ConstLanelet * target_lanelet) const; + lanelet::ConstLanelet * target_lanelet); double getLaneChangeableDistance( const Pose & current_pose, const LaneChangeDirection & direction) const; lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const; diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 6106fa86c1f59..62b02dc3f1df4 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -72,18 +72,18 @@ lanelet::ConstPoint3d get3DPointFrom2DArcLength( prev_pt = centerline.front(); } for (const auto & pt : centerline) { - double distance2d = lanelet::geometry::distance2d(to2D(prev_pt), to2D(pt)); + const double distance2d = lanelet::geometry::distance2d(to2D(prev_pt), to2D(pt)); if (accumulated_distance2d + distance2d > s) { - double ratio = (s - accumulated_distance2d) / distance2d; - auto interpolated_pt = prev_pt.basicPoint() * (1 - ratio) + pt.basicPoint() * ratio; - return lanelet::ConstPoint3d( - lanelet::InvalId, interpolated_pt.x(), interpolated_pt.y(), interpolated_pt.z()); + const double ratio = (s - accumulated_distance2d) / distance2d; + const auto interpolated_pt = prev_pt.basicPoint() * (1 - ratio) + pt.basicPoint() * ratio; + return lanelet::ConstPoint3d{ + lanelet::InvalId, interpolated_pt.x(), interpolated_pt.y(), interpolated_pt.z()}; } accumulated_distance2d += distance2d; prev_pt = pt; } } - return lanelet::ConstPoint3d(); + return lanelet::ConstPoint3d{}; } PathWithLaneId removeOverlappingPoints(const PathWithLaneId & input_path) @@ -134,11 +134,11 @@ void RouteHandler::setMap(const HADMapBin & map_msg) lanelet::Locations::Germany, lanelet::Participants::Vehicle); const auto pedestrian_rules = lanelet::traffic_rules::TrafficRulesFactory::create( lanelet::Locations::Germany, lanelet::Participants::Pedestrian); - lanelet::routing::RoutingGraphConstPtr vehicle_graph = + const lanelet::routing::RoutingGraphConstPtr vehicle_graph = lanelet::routing::RoutingGraph::build(*lanelet_map_ptr_, *traffic_rules); - lanelet::routing::RoutingGraphConstPtr pedestrian_graph = + const lanelet::routing::RoutingGraphConstPtr pedestrian_graph = lanelet::routing::RoutingGraph::build(*lanelet_map_ptr_, *pedestrian_rules); - lanelet::routing::RoutingGraphContainer overall_graphs({vehicle_graph, pedestrian_graph}); + const lanelet::routing::RoutingGraphContainer overall_graphs({vehicle_graph, pedestrian_graph}); overall_graphs_ptr_ = std::make_shared(overall_graphs); lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); @@ -151,16 +151,15 @@ void RouteHandler::setMap(const HADMapBin & map_msg) setLaneletsFromRouteMsg(); } -bool RouteHandler::isRouteLooped(const RouteSections & route_sections) const +bool RouteHandler::isRouteLooped(const RouteSections & route_sections) { std::set lane_primitives; for (const auto & route_section : route_sections) { for (const auto & primitive : route_section.primitives) { - if (lane_primitives.find(primitive.id) == lane_primitives.end()) { - lane_primitives.emplace(primitive.id); - } else { + if (lane_primitives.find(primitive.id) != lane_primitives.end()) { return true; // find duplicated id } + lane_primitives.emplace(primitive.id); } } return false; @@ -185,9 +184,9 @@ bool RouteHandler::isHandlerReady() const { return is_handler_ready_; } void RouteHandler::setRouteLanelets(const lanelet::ConstLanelets & path_lanelets) { if (!path_lanelets.empty()) { - auto first_lanelet = path_lanelets.front(); + const auto & first_lanelet = path_lanelets.front(); start_lanelets_ = lanelet::utils::query::getAllNeighbors(routing_graph_ptr_, first_lanelet); - auto last_lanelet = path_lanelets.back(); + const auto & last_lanelet = path_lanelets.back(); goal_lanelets_ = lanelet::utils::query::getAllNeighbors(routing_graph_ptr_, last_lanelet); } @@ -275,6 +274,7 @@ void RouteHandler::setRouteLanelets(const lanelet::ConstLanelets & path_lanelets } route_lanelets_.clear(); + route_lanelets_.reserve(route_lanelets_id.size()); for (const auto & id : route_lanelets_id) { route_lanelets_.push_back(lanelet_map_ptr_->laneletLayer.get(id)); } @@ -288,10 +288,17 @@ void RouteHandler::setLaneletsFromRouteMsg() } route_lanelets_.clear(); preferred_lanelets_.clear(); - bool is_route_valid = lanelet::utils::route::isRouteValid(route_msg_, lanelet_map_ptr_); + const bool is_route_valid = lanelet::utils::route::isRouteValid(route_msg_, lanelet_map_ptr_); if (!is_route_valid) { return; } + + size_t primitive_size{0}; + for (const auto & route_section : route_msg_.segments) { + primitive_size += route_section.primitives.size(); + } + route_lanelets_.reserve(primitive_size); + for (const auto & route_section : route_msg_.segments) { for (const auto & primitive : route_section.primitives) { const auto id = primitive.id; @@ -305,11 +312,13 @@ void RouteHandler::setLaneletsFromRouteMsg() goal_lanelets_.clear(); start_lanelets_.clear(); if (!route_msg_.segments.empty()) { + goal_lanelets_.reserve(route_msg_.segments.back().primitives.size()); for (const auto & primitive : route_msg_.segments.back().primitives) { const auto id = primitive.id; const auto & llt = lanelet_map_ptr_->laneletLayer.get(id); goal_lanelets_.push_back(llt); } + start_lanelets_.reserve(route_msg_.segments.front().primitives.size()); for (const auto & primitive : route_msg_.segments.front().primitives) { const auto id = primitive.id; const auto & llt = lanelet_map_ptr_->laneletLayer.get(id); @@ -370,9 +379,9 @@ lanelet::Id RouteHandler::getGoalLaneId() const { if (route_msg_.segments.empty()) { return lanelet::InvalId; - } else { - return route_msg_.segments.back().preferred_primitive_id; } + + return route_msg_.segments.back().preferred_primitive_id; } bool RouteHandler::getGoalLanelet(lanelet::ConstLanelet * goal_lanelet) const @@ -391,14 +400,14 @@ bool RouteHandler::isInGoalRouteSection(const lanelet::ConstLanelet & lanelet) c { if (route_msg_.segments.empty()) { return false; - } else { - return exists(route_msg_.segments.back().primitives, lanelet.id()); } + return exists(route_msg_.segments.back().primitives, lanelet.id()); } -lanelet::ConstLanelets RouteHandler::getLaneletsFromIds(const lanelet::Ids ids) const +lanelet::ConstLanelets RouteHandler::getLaneletsFromIds(const lanelet::Ids & ids) const { lanelet::ConstLanelets lanelets; + lanelets.reserve(ids.size()); for (const auto & id : ids) { lanelets.push_back(lanelet_map_ptr_->laneletLayer.get(id)); } @@ -413,10 +422,7 @@ lanelet::ConstLanelet RouteHandler::getLaneletsFromId(const lanelet::Id id) cons bool RouteHandler::isDeadEndLanelet(const lanelet::ConstLanelet & lanelet) const { lanelet::ConstLanelet next_lanelet; - if (getNextLaneletWithinRoute(lanelet, &next_lanelet)) { - return false; - } - return true; + return !getNextLaneletWithinRoute(lanelet, &next_lanelet); } lanelet::ConstLanelets RouteHandler::getLaneletSequenceAfter( @@ -436,7 +442,8 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequenceAfter( } lanelet_sequence_forward.push_back(next_lanelet); current_lanelet = next_lanelet; - length += boost::geometry::length(next_lanelet.centerline().basicLineString()); + length += + static_cast(boost::geometry::length(next_lanelet.centerline().basicLineString())); } return lanelet_sequence_forward; @@ -481,7 +488,8 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequenceUpTo( continue; } lanelet_sequence_backward.push_back(prev_lanelet); - length += boost::geometry::length(prev_lanelet.centerline().basicLineString()); + length += + static_cast(boost::geometry::length(prev_lanelet.centerline().basicLineString())); current_lanelet = prev_lanelet; break; } @@ -502,18 +510,19 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequence( } lanelet::ConstLanelets lanelet_sequence; - lanelet::ConstLanelets lanelet_sequence_backward; - lanelet::ConstLanelets lanelet_sequence_forward; if (!exists(route_lanelets_, lanelet)) { return lanelet_sequence; } - lanelet_sequence_forward = getLaneletSequenceAfter(lanelet, forward_distance); - - const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, current_pose); - if (arc_coordinate.length < backward_distance) { - lanelet_sequence_backward = getLaneletSequenceUpTo(lanelet, backward_distance); - } + lanelet::ConstLanelets lanelet_sequence_forward = + getLaneletSequenceAfter(lanelet, forward_distance); + const lanelet::ConstLanelets lanelet_sequence_backward = std::invoke([&]() { + const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, current_pose); + if (arc_coordinate.length < backward_distance) { + return getLaneletSequenceUpTo(lanelet, backward_distance); + } + return lanelet::ConstLanelets{}; + }); // loop check if (!lanelet_sequence_forward.empty() && !lanelet_sequence_backward.empty()) { @@ -535,18 +544,19 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequence( const double forward_distance) const { lanelet::ConstLanelets lanelet_sequence; - lanelet::ConstLanelets lanelet_sequence_backward; - lanelet::ConstLanelets lanelet_sequence_forward; if (!exists(route_lanelets_, lanelet)) { return lanelet_sequence; } - lanelet_sequence_forward = getLaneletSequenceAfter(lanelet, forward_distance); - - const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, current_pose); - if (arc_coordinate.length < backward_distance) { - lanelet_sequence_backward = getLaneletSequenceUpTo(lanelet, backward_distance); - } + lanelet::ConstLanelets lanelet_sequence_forward = + getLaneletSequenceAfter(lanelet, forward_distance); + const lanelet::ConstLanelets lanelet_sequence_backward = std::invoke([&]() { + const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, current_pose); + if (arc_coordinate.length < backward_distance) { + return getLaneletSequenceUpTo(lanelet, backward_distance); + } + return lanelet::ConstLanelets{}; + }); // loop check if (!lanelet_sequence_forward.empty() && !lanelet_sequence_backward.empty()) { @@ -571,9 +581,6 @@ bool RouteHandler::getFollowingShoulderLanelet( back_pose.position.y = lanelet.centerline2d().back().y(); back_pose.position.z = 0; - lanelet::ArcCoordinates arc_coordinates; - const auto & centerline_2d = to2D(lanelet.centerline()); - for (const auto & shoulder_lanelet : shoulder_lanelets_) { Pose front_pose; front_pose.position.x = shoulder_lanelet.centerline2d().front().x(); @@ -607,7 +614,8 @@ lanelet::ConstLanelets RouteHandler::getShoulderLaneletSequenceAfter( } lanelet_sequence_forward.push_back(next_lanelet); current_lanelet = next_lanelet; - length += boost::geometry::length(next_lanelet.centerline().basicLineString()); + length += + static_cast(boost::geometry::length(next_lanelet.centerline().basicLineString())); } return lanelet_sequence_forward; @@ -621,9 +629,6 @@ bool RouteHandler::getPreviousShoulderLanelet( front_pose.position.y = lanelet.centerline2d().front().y(); front_pose.position.z = 0; - lanelet::ArcCoordinates arc_coordinates; - const auto & centerline_2d = to2D(lanelet.centerline()); - for (const auto & shoulder_lanelet : shoulder_lanelets_) { Pose back_pose; back_pose.position.x = shoulder_lanelet.centerline2d().back().x(); @@ -658,7 +663,8 @@ lanelet::ConstLanelets RouteHandler::getShoulderLaneletSequenceUpTo( lanelet_sequence_backward.insert(lanelet_sequence_backward.begin(), prev_lanelet); current_lanelet = prev_lanelet; - length += boost::geometry::length(prev_lanelet.centerline().basicLineString()); + length += + static_cast(boost::geometry::length(prev_lanelet.centerline().basicLineString())); } return lanelet_sequence_backward; @@ -669,18 +675,19 @@ lanelet::ConstLanelets RouteHandler::getShoulderLaneletSequence( const double forward_distance) const { lanelet::ConstLanelets lanelet_sequence; - lanelet::ConstLanelets lanelet_sequence_backward; - lanelet::ConstLanelets lanelet_sequence_forward; if (!exists(shoulder_lanelets_, lanelet)) { return lanelet_sequence; } - lanelet_sequence_forward = getShoulderLaneletSequenceAfter(lanelet, forward_distance); - - const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, pose); - if (arc_coordinate.length < backward_distance) { - lanelet_sequence_backward = getShoulderLaneletSequenceUpTo(lanelet, backward_distance); - } + lanelet::ConstLanelets lanelet_sequence_forward = + getShoulderLaneletSequenceAfter(lanelet, forward_distance); + const lanelet::ConstLanelets lanelet_sequence_backward = std::invoke([&]() { + const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, pose); + if (arc_coordinate.length < backward_distance) { + return getShoulderLaneletSequenceUpTo(lanelet, backward_distance); + } + return lanelet::ConstLanelets{}; + }); // loop check if (!lanelet_sequence_forward.empty() && !lanelet_sequence_backward.empty()) { @@ -710,7 +717,7 @@ bool RouteHandler::getNextLaneletWithinRoute( if (exists(goal_lanelets_, lanelet)) { return false; } - lanelet::ConstLanelets following_lanelets = routing_graph_ptr_->following(lanelet); + const auto following_lanelets = routing_graph_ptr_->following(lanelet); for (const auto & llt : following_lanelets) { if (exists(route_lanelets_, llt)) { *next_lanelet = llt; @@ -731,7 +738,7 @@ bool RouteHandler::getPreviousLaneletsWithinRoute( if (exists(start_lanelets_, lanelet)) { return false; } - lanelet::ConstLanelets candidate_lanelets = routing_graph_ptr_->previous(lanelet); + const auto candidate_lanelets = routing_graph_ptr_->previous(lanelet); prev_lanelets->clear(); for (const auto & llt : candidate_lanelets) { if (exists(route_lanelets_, llt)) { @@ -749,13 +756,12 @@ lanelet::ConstLanelets RouteHandler::getLaneletsFromPoint(const lanelet::ConstPo bool RouteHandler::getRightLaneletWithinRoute( const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * right_lanelet) const { - auto opt_right_lanelet = routing_graph_ptr_->right(lanelet); + const auto opt_right_lanelet = routing_graph_ptr_->right(lanelet); if (!!opt_right_lanelet) { *right_lanelet = opt_right_lanelet.get(); return exists(route_lanelets_, *right_lanelet); - } else { - return false; } + return false; } bool RouteHandler::getNextLaneletWithinRouteExceptStart( @@ -764,7 +770,7 @@ bool RouteHandler::getNextLaneletWithinRouteExceptStart( if (exists(goal_lanelets_, lanelet)) { return false; } - lanelet::ConstLanelets following_lanelets = routing_graph_ptr_->following(lanelet); + const lanelet::ConstLanelets following_lanelets = routing_graph_ptr_->following(lanelet); for (const auto & llt : following_lanelets) { if (exists(route_lanelets_, llt) && !exists(start_lanelets_, llt)) { *next_lanelet = llt; @@ -780,7 +786,7 @@ bool RouteHandler::getPreviousLaneletWithinRouteExceptGoal( if (exists(start_lanelets_, lanelet)) { return false; } - lanelet::ConstLanelets previous_lanelets = routing_graph_ptr_->previous(lanelet); + const lanelet::ConstLanelets previous_lanelets = routing_graph_ptr_->previous(lanelet); for (const auto & llt : previous_lanelets) { if (exists(route_lanelets_, llt) && !(exists(goal_lanelets_, llt))) { *prev_lanelet = llt; @@ -839,13 +845,12 @@ boost::optional RouteHandler::getRightLanelet( bool RouteHandler::getLeftLaneletWithinRoute( const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * left_lanelet) const { - auto opt_left_lanelet = routing_graph_ptr_->left(lanelet); + const auto opt_left_lanelet = routing_graph_ptr_->left(lanelet); if (!!opt_left_lanelet) { *left_lanelet = opt_left_lanelet.get(); return exists(route_lanelets_, *left_lanelet); - } else { - return false; } + return false; } boost::optional RouteHandler::getLeftLanelet( @@ -989,12 +994,17 @@ lanelet::ConstLineString3d RouteHandler::getRightMostLinestring( const auto & opposite = getRightOppositeLanelets(lanelet); if (!same && opposite.empty()) { return lanelet.rightBound(); - } else if (same) { + } + + if (same) { return getRightMostLinestring(same.get()); - } else if (!opposite.empty()) { + } + + if (!opposite.empty()) { return getLeftMostLinestring(lanelet::ConstLanelet(opposite.front())); } - return {}; + + return lanelet.rightBound(); } lanelet::ConstLineString3d RouteHandler::getLeftMostSameDirectionLinestring( @@ -1018,12 +1028,17 @@ lanelet::ConstLineString3d RouteHandler::getLeftMostLinestring( if (!same && opposite.empty()) { return lanelet.leftBound(); - } else if (same) { + } + + if (same) { return getLeftMostLinestring(same.get()); - } else if (!opposite.empty()) { + } + + if (!opposite.empty()) { return getRightMostLinestring(lanelet::ConstLanelet(opposite.front())); } - return {}; + + return lanelet.leftBound(); } lanelet::ConstLineStrings3d RouteHandler::getFurthestLinestring( @@ -1054,32 +1069,28 @@ lanelet::ConstLineStrings3d RouteHandler::getFurthestLinestring( bool RouteHandler::getLaneChangeTarget( const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const { - for (auto it = lanelets.begin(); it != lanelets.end(); ++it) { - const auto lanelet = *it; - - int num = getNumLaneToPreferredLane(lanelet); + for (const auto & lanelet : lanelets) { + const int num = getNumLaneToPreferredLane(lanelet); if (num == 0) { continue; } if (num < 0) { if (!!routing_graph_ptr_->right(lanelet)) { - auto right_lanelet = routing_graph_ptr_->right(lanelet); + const auto right_lanelet = routing_graph_ptr_->right(lanelet); *target_lanelet = right_lanelet.get(); return true; - } else { - continue; } + continue; } if (num > 0) { if (!!routing_graph_ptr_->left(lanelet)) { - auto left_lanelet = routing_graph_ptr_->left(lanelet); + const auto left_lanelet = routing_graph_ptr_->left(lanelet); *target_lanelet = left_lanelet.get(); return true; - } else { - continue; } + continue; } } @@ -1089,7 +1100,7 @@ bool RouteHandler::getLaneChangeTarget( bool RouteHandler::getPullOverTarget( const lanelet::ConstLanelets & lanelets, const Pose & goal_pose, - lanelet::ConstLanelet * target_lanelet) const + lanelet::ConstLanelet * target_lanelet) { for (const auto & shoulder_lanelet : lanelets) { if (lanelet::utils::isInLanelet(goal_pose, shoulder_lanelet, 0.1)) { @@ -1102,7 +1113,7 @@ bool RouteHandler::getPullOverTarget( bool RouteHandler::getPullOutStartLane( const lanelet::ConstLanelets & lanelets, const Pose & pose, const double vehicle_width, - lanelet::ConstLanelet * target_lanelet) const + lanelet::ConstLanelet * target_lanelet) { for (const auto & shoulder_lanelet : lanelets) { if (lanelet::utils::isInLanelet(pose, shoulder_lanelet, vehicle_width / 2.0)) { @@ -1116,9 +1127,8 @@ bool RouteHandler::getPullOutStartLane( lanelet::ConstLanelets RouteHandler::getClosestLaneletSequence(const Pose & pose) const { lanelet::ConstLanelet lanelet; - lanelet::ConstLanelets empty_lanelets; if (!getClosestLaneletWithinRoute(pose, &lanelet)) { - return empty_lanelets; + return lanelet::ConstLanelets{}; } return getLaneletSequence(lanelet); } @@ -1175,33 +1185,33 @@ PathWithLaneId RouteHandler::getCenterLinePath( double s = 0; for (const auto & llt : lanelet_sequence) { - lanelet::traffic_rules::SpeedLimitInformation limit = traffic_rules_ptr_->speedLimit(llt); + const lanelet::traffic_rules::SpeedLimitInformation limit = traffic_rules_ptr_->speedLimit(llt); const lanelet::ConstLineString3d centerline = llt.centerline(); - const auto addPathPoint = [&reference_path, &limit, &llt](const auto & pt) { + const auto add_path_point = [&reference_path, &limit, &llt](const auto & pt) { PathPointWithLaneId p{}; p.point.pose.position = lanelet::utils::conversion::toGeomMsgPt(pt); p.lane_ids.push_back(llt.id()); - p.point.longitudinal_velocity_mps = limit.speedLimit.value(); + p.point.longitudinal_velocity_mps = static_cast(limit.speedLimit.value()); reference_path.points.push_back(p); }; for (size_t i = 0; i < centerline.size(); i++) { - const lanelet::ConstPoint3d pt = centerline[i]; - lanelet::ConstPoint3d next_pt = + const auto & pt = centerline[i]; + const lanelet::ConstPoint3d next_pt = (i + 1 < centerline.size()) ? centerline[i + 1] : centerline[i]; - double distance = lanelet::geometry::distance2d(to2D(pt), to2D(next_pt)); + const double distance = lanelet::geometry::distance2d(to2D(pt), to2D(next_pt)); if (s < s_start && s + distance > s_start) { const auto p = use_exact ? get3DPointFrom2DArcLength(lanelet_sequence, s_start) : pt; - addPathPoint(p); + add_path_point(p); } if (s >= s_start && s <= s_end) { - addPathPoint(pt); + add_path_point(pt); } if (s < s_end && s + distance > s_end) { const auto p = use_exact ? get3DPointFrom2DArcLength(lanelet_sequence, s_end) : next_pt; - addPathPoint(p); + add_path_point(p); } s += distance; } @@ -1211,7 +1221,7 @@ PathWithLaneId RouteHandler::getCenterLinePath( // append a point only when having one point so that yaw calculation would work if (reference_path.points.size() == 1) { - const int lane_id = reference_path.points.front().lane_ids.front(); + const int lane_id = static_cast(reference_path.points.front().lane_ids.front()); const auto lanelet = lanelet_map_ptr_->laneletLayer.get(lane_id); const auto point = reference_path.points.front().point.pose.position; const auto lane_yaw = lanelet::utils::getLaneletAngle(lanelet, point); @@ -1248,8 +1258,8 @@ PathWithLaneId RouteHandler::updatePathTwist(const PathWithLaneId & path) const for (auto & point : updated_path.points) { const auto id = point.lane_ids.at(0); const auto llt = lanelet_map_ptr_->laneletLayer.get(id); - lanelet::traffic_rules::SpeedLimitInformation limit = traffic_rules_ptr_->speedLimit(llt); - point.point.longitudinal_velocity_mps = limit.speedLimit.value(); + const auto limit = traffic_rules_ptr_->speedLimit(llt); + point.point.longitudinal_velocity_mps = static_cast(limit.speedLimit.value()); } return updated_path; } @@ -1262,17 +1272,17 @@ lanelet::ConstLanelets RouteHandler::getLaneChangeTargetLanes(const Pose & pose) return target_lanelets; } - int num = getNumLaneToPreferredLane(lanelet); + const int num = getNumLaneToPreferredLane(lanelet); if (num < 0) { - auto right_lanelet = (!!routing_graph_ptr_->right(lanelet)) - ? routing_graph_ptr_->right(lanelet) - : routing_graph_ptr_->adjacentRight(lanelet); + const auto right_lanelet = (!!routing_graph_ptr_->right(lanelet)) + ? routing_graph_ptr_->right(lanelet) + : routing_graph_ptr_->adjacentRight(lanelet); target_lanelets = getLaneletSequence(right_lanelet.get()); } if (num > 0) { - auto left_lanelet = (!!routing_graph_ptr_->left(lanelet)) - ? routing_graph_ptr_->left(lanelet) - : routing_graph_ptr_->adjacentLeft(lanelet); + const auto left_lanelet = (!!routing_graph_ptr_->left(lanelet)) + ? routing_graph_ptr_->left(lanelet) + : routing_graph_ptr_->adjacentLeft(lanelet); target_lanelets = getLaneletSequence(left_lanelet.get()); } return target_lanelets; @@ -1440,7 +1450,7 @@ lanelet::ConstLanelets RouteHandler::getPreviousLaneletSequence( return previous_lanelet_sequence; } - auto first_lane = lanelet_sequence.front(); + const auto & first_lane = lanelet_sequence.front(); if (exists(start_lanelets_, first_lane)) { return previous_lanelet_sequence; } @@ -1467,8 +1477,8 @@ lanelet::ConstLanelets RouteHandler::getPreviousLaneletSequence( lanelet::ConstLanelets RouteHandler::getLaneSequence(const lanelet::ConstLanelet & lanelet) const { lanelet::ConstLanelets lane_sequence; - lanelet::ConstLanelets lane_sequence_up_to = getLaneSequenceUpTo(lanelet); - lanelet::ConstLanelets lane_sequence_after = getLaneSequenceAfter(lanelet); + const lanelet::ConstLanelets lane_sequence_up_to = getLaneSequenceUpTo(lanelet); + const lanelet::ConstLanelets lane_sequence_after = getLaneSequenceAfter(lanelet); lane_sequence.insert(lane_sequence.end(), lane_sequence_up_to.begin(), lane_sequence_up_to.end()); lane_sequence.insert(lane_sequence.end(), lane_sequence_after.begin(), lane_sequence_after.end()); @@ -1517,8 +1527,8 @@ lanelet::ConstLanelets RouteHandler::getLaneSequenceUpTo( break; } - lanelet::ConstLanelets current_lanelet_section = getNeighborsWithinRoute(current_lanelet); - lanelet::ConstLanelets prev_lanelet_section = getNeighborsWithinRoute(prev_lanelet); + const lanelet::ConstLanelets current_lanelet_section = getNeighborsWithinRoute(current_lanelet); + const lanelet::ConstLanelets prev_lanelet_section = getNeighborsWithinRoute(prev_lanelet); if (!isBijectiveConnection(prev_lanelet_section, current_lanelet_section)) { break; } @@ -1546,8 +1556,8 @@ lanelet::ConstLanelets RouteHandler::getLaneSequenceAfter( break; } - lanelet::ConstLanelets current_lanelet_section = getNeighborsWithinRoute(current_lanelet); - lanelet::ConstLanelets next_lanelet_section = getNeighborsWithinRoute(next_lanelet); + const lanelet::ConstLanelets current_lanelet_section = getNeighborsWithinRoute(current_lanelet); + const lanelet::ConstLanelets next_lanelet_section = getNeighborsWithinRoute(next_lanelet); if (!isBijectiveConnection(current_lanelet_section, next_lanelet_section)) { break; } @@ -1561,7 +1571,7 @@ lanelet::ConstLanelets RouteHandler::getLaneSequenceAfter( lanelet::ConstLanelets RouteHandler::getNeighborsWithinRoute( const lanelet::ConstLanelet & lanelet) const { - lanelet::ConstLanelets neighbor_lanelets = + const lanelet::ConstLanelets neighbor_lanelets = lanelet::utils::query::getAllNeighbors(routing_graph_ptr_, lanelet); lanelet::ConstLanelets neighbors_within_route; for (const auto & llt : neighbor_lanelets) { @@ -1575,8 +1585,9 @@ lanelet::ConstLanelets RouteHandler::getNeighborsWithinRoute( std::vector RouteHandler::getLaneSection( const lanelet::ConstLanelet & lanelet) const { - lanelet::ConstLanelets neighbors = getNeighborsWithinRoute(lanelet); + const lanelet::ConstLanelets neighbors = getNeighborsWithinRoute(lanelet); std::vector lane_section; + lane_section.reserve(neighbors.size()); for (const auto & llt : neighbors) { lane_section.push_back(getLaneSequence(llt)); } @@ -1590,7 +1601,7 @@ lanelet::ConstLanelets RouteHandler::getNextLaneSequence( if (lane_sequence.empty()) { return next_lane_sequence; } - lanelet::ConstLanelet final_lanelet = lane_sequence.back(); + const auto & final_lanelet = lane_sequence.back(); lanelet::ConstLanelet next_lanelet; if (!getNextLaneletWithinRoute(final_lanelet, &next_lanelet)) { return next_lane_sequence; @@ -1612,7 +1623,7 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints( } // get all possible lanes that can be used to reach goal (including all possible lane change) - lanelet::Optional optional_route = + const lanelet::Optional optional_route = routing_graph_ptr_->getRoute(start_lanelet, goal_lanelet, 0); if (!optional_route) { RCLCPP_ERROR_STREAM( @@ -1626,6 +1637,7 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints( } const auto shortest_path = optional_route->shortestPath(); + path_lanelets->reserve(shortest_path.size()); for (const auto & llt : shortest_path) { path_lanelets->push_back(llt); } @@ -1643,10 +1655,12 @@ std::vector RouteHandler::createMapSegments( return route_sections; } + route_sections.reserve(main_path.size()); for (const auto & main_llt : main_path) { HADMapSegment route_section_msg; - lanelet::ConstLanelets route_section_lanelets = getNeighborsWithinRoute(main_llt); + const lanelet::ConstLanelets route_section_lanelets = getNeighborsWithinRoute(main_llt); route_section_msg.preferred_primitive_id = main_llt.id(); + route_section_msg.primitives.reserve(route_section_lanelets.size()); for (const auto & section_llt : route_section_lanelets) { MapPrimitive p; p.id = section_llt.id(); From c7698fc5d6b54932816077539b01c224e60861c2 Mon Sep 17 00:00:00 2001 From: alanmengg <104343391+alanmengg@users.noreply.github.com> Date: Mon, 3 Oct 2022 20:26:36 +0800 Subject: [PATCH 02/28] fix(freespace_planner): can't stop before blocking obstacle in parking#980 (#1872) * fix(tier4_perception_rviz_plugin): modify build error in rolling (#791) * fix(tier4_perception_rviz_plugin): modify build error in rolling Signed-off-by: wep21 * fix(tier4_perception_rviz_plugin): add target compile definitions Signed-off-by: wep21 Signed-off-by: guiping meng * fix(had_map_utils): modify build error in rolling (#782) Signed-off-by: wep21 Signed-off-by: guiping meng * fix: modify build error of ndt related packages in rolling (#793) * fix(ndt_pcl_modified): modify build error in rolling Signed-off-by: wep21 * fix(ndt): modify build error in rolling Signed-off-by: wep21 * fix(ndt_scan_matcher): modify build error in rolling Signed-off-by: wep21 * ci(pre-commit): autofix * remove unused find_package * fix(ndt): remove memory.h Signed-off-by: wep21 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Signed-off-by: guiping meng * fix(freespace_planner): Can't stop before blocking obstacle in parking #980 Signed-off-by: guiping meng * ci(pre-commit): autofix Signed-off-by: guiping meng * Update planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp Co-authored-by: Kosuke Takeuchi Signed-off-by: guiping meng * Revert "fix(had_map_utils): modify build error in rolling (#782)" This reverts commit 7075fca358203b7e60f5ee08cf20763fd095246c. Signed-off-by: guiping meng * Revert "fix: modify build error of ndt related packages in rolling (#793)" This reverts commit a235363d3c52e3df8fbb2f8f490f311cc7deaa82. Signed-off-by: guiping meng * Update planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp Co-authored-by: Kosuke Takeuchi Signed-off-by: guiping meng Signed-off-by: guiping meng * revert some changes Co-authored-by: Kosuke Takeuchi Signed-off-by: guiping meng * revert some changes Co-authored-by: Kosuke Takeuchi Signed-off-by: guiping meng * ci(pre-commit): autofix Signed-off-by: guiping meng * revert some changes Signed-off-by: guiping meng * fix mistakes Signed-off-by: guiping meng * Revert "fix(tier4_perception_rviz_plugin): modify build error in rolling (#791)" This reverts commit eac57fbf1d4e75f9bd0221b03d261fa60ca99a17. Signed-off-by: guiping meng Signed-off-by: wep21 Signed-off-by: guiping meng Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kosuke Takeuchi --- .../freespace_planner_node.cpp | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp index ce87a7281d49c..4c08be4d4b1ac 100644 --- a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp +++ b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp @@ -191,6 +191,15 @@ Trajectory createStopTrajectory(const PoseStamped & current_pose) return createTrajectory(current_pose, waypoints, 0.0); } +Trajectory createStopTrajectory(const Trajectory & trajectory) +{ + Trajectory stop_trajectory = trajectory; + for (size_t i = 0; i < trajectory.points.size(); ++i) { + stop_trajectory.points.at(i).longitudinal_velocity_mps = 0.0; + } + return stop_trajectory; +} + bool isStopped( const std::deque & odom_buffer, const double th_stopped_velocity_mps) { @@ -432,14 +441,16 @@ void FreespacePlannerNode::onTimer() initializePlanningAlgorithm(); if (isPlanRequired()) { - reset(); - // Stop before planning new trajectory - const auto stop_trajectory = createStopTrajectory(current_pose_); + const auto stop_trajectory = partial_trajectory_.points.empty() + ? createStopTrajectory(current_pose_) + : createStopTrajectory(partial_trajectory_); trajectory_pub_->publish(stop_trajectory); debug_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory)); debug_partial_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory)); + reset(); + // Plan new trajectory planTrajectory(); } From 1c227dc03a1867a2b932b6c5f3c09678804f2cca Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 4 Oct 2022 14:26:49 +0900 Subject: [PATCH 03/28] fix(behavior_path_planner): pull out on lane boundary (#2004) * fix(behavior_path_planner): pull out on lane boundary Signed-off-by: kosuke55 * use getExtendedCurrentLanes for pull over Signed-off-by: kosuke55 Signed-off-by: kosuke55 Co-authored-by: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> --- .../scene_module/pull_out/pull_out_module.hpp | 1 - .../pull_out/geometric_pull_out.cpp | 2 +- .../scene_module/pull_out/pull_out_module.cpp | 56 ++++++++----------- .../scene_module/pull_out/shift_pull_out.cpp | 2 +- .../pull_over/geometric_pull_over.cpp | 2 +- .../pull_over/shift_pull_over.cpp | 2 +- .../behavior_path_planner/src/utilities.cpp | 15 ++--- .../include/route_handler/route_handler.hpp | 1 + planning/route_handler/src/route_handler.cpp | 6 ++ 9 files changed, 41 insertions(+), 46 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/pull_out/pull_out_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/pull_out/pull_out_module.hpp index 41f49cf9dd43d..b7134413d0597 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/pull_out/pull_out_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/pull_out/pull_out_module.hpp @@ -94,7 +94,6 @@ class PullOutModule : public SceneModuleInterface std::unique_ptr last_approved_pose_; std::shared_ptr getCurrentPlanner() const; - lanelet::ConstLanelets getCurrentLanes() const; PathWithLaneId getFullPath() const; ParallelParkingParameters getGeometricPullOutParameters() const; std::vector searchBackedPoses(); diff --git a/planning/behavior_path_planner/src/scene_module/pull_out/geometric_pull_out.cpp b/planning/behavior_path_planner/src/scene_module/pull_out/geometric_pull_out.cpp index a668deaac9023..b8dde0300de16 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_out/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_out/geometric_pull_out.cpp @@ -37,7 +37,7 @@ boost::optional GeometricPullOut::plan(Pose start_pose, Pose goal_p PullOutPath output; // combine road lane and shoulder lane - const auto road_lanes = util::getCurrentLanes(planner_data_); + const auto road_lanes = util::getExtendedCurrentLanes(planner_data_); const auto shoulder_lanes = getPullOutLanes(road_lanes, planner_data_); auto lanes = road_lanes; lanes.insert(lanes.end(), shoulder_lanes.begin(), shoulder_lanes.end()); diff --git a/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp b/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp index 05d0ffe532833..271e1f576b767 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp @@ -124,7 +124,7 @@ bool PullOutModule::isExecutionRequested() const const auto vehicle_footprint = transformVector( local_vehicle_footprint, tier4_autoware_utils::pose2transform(planner_data_->self_pose->pose)); - const auto road_lanes = getCurrentLanes(); + const auto road_lanes = util::getExtendedCurrentLanes(planner_data_); // check if goal pose is in shoulder lane and distance is long enough for pull out if (isInLane(closest_shoulder_lanelet, vehicle_footprint)) { @@ -263,7 +263,7 @@ BehaviorModuleOutput PullOutModule::planWaitingApproval() waitApproval(); BehaviorModuleOutput output; - const auto current_lanes = getCurrentLanes(); + const auto current_lanes = util::getExtendedCurrentLanes(planner_data_); const auto pull_out_lanes = pull_out_utils::getPullOutLanes(current_lanes, planner_data_); auto lanes = current_lanes; lanes.insert(lanes.end(), pull_out_lanes.begin(), pull_out_lanes.end()); @@ -353,9 +353,14 @@ void PullOutModule::planWithPriorityOnEfficientPath( { status_.is_safe = false; + // plan with each planner for (const auto & planner : pull_out_planners_) { - for (const auto & pull_out_start_pose : start_pose_candidates) { - // plan with each planner + for (size_t i = 0; i < start_pose_candidates.size(); ++i) { + // pull out start pose is current_pose + if (i == 0) { + status_.back_finished = true; + } + const auto & pull_out_start_pose = start_pose_candidates.at(i); planner->setPlannerData(planner_data_); const auto pull_out_path = planner->plan(pull_out_start_pose, goal_pose); if (pull_out_path) { // found safe path @@ -379,7 +384,12 @@ void PullOutModule::planWithPriorityOnShortBackDistance( { status_.is_safe = false; - for (const auto & pull_out_start_pose : start_pose_candidates) { + for (size_t i = 0; i < start_pose_candidates.size(); ++i) { + // pull out start pose is current_pose + if (i == 0) { + status_.back_finished = true; + } + const auto & pull_out_start_pose = start_pose_candidates.at(i); // plan with each planner for (const auto & planner : pull_out_planners_) { planner->setPlannerData(planner_data_); @@ -406,16 +416,17 @@ void PullOutModule::updatePullOutStatus() const auto & current_pose = planner_data_->self_pose->pose; const auto & goal_pose = planner_data_->route_handler->getGoalPose(); - const auto current_lanes = getCurrentLanes(); - status_.current_lanes = current_lanes; + status_.current_lanes = util::getExtendedCurrentLanes(planner_data_); + status_.pull_out_lanes = pull_out_utils::getPullOutLanes(status_.current_lanes, planner_data_); // Get pull_out lanes - const auto pull_out_lanes = pull_out_utils::getPullOutLanes(current_lanes, planner_data_); + const auto pull_out_lanes = pull_out_utils::getPullOutLanes(status_.current_lanes, planner_data_); status_.pull_out_lanes = pull_out_lanes; // combine road and shoulder lanes - status_.lanes = current_lanes; - status_.lanes.insert(status_.lanes.end(), pull_out_lanes.begin(), pull_out_lanes.end()); + status_.lanes = status_.current_lanes; + status_.lanes.insert( + status_.lanes.end(), status_.pull_out_lanes.begin(), status_.pull_out_lanes.end()); // search pull out start candidates backward std::vector start_pose_candidates; @@ -449,32 +460,13 @@ void PullOutModule::updatePullOutStatus() checkBackFinished(); if (!status_.back_finished) { status_.backward_path = pull_out_utils::getBackwardPath( - *route_handler, pull_out_lanes, current_pose, status_.pull_out_start_pose, + *route_handler, status_.pull_out_lanes, current_pose, status_.pull_out_start_pose, parameters_.backward_velocity); } // Update status - status_.lane_follow_lane_ids = util::getIds(current_lanes); - status_.pull_out_lane_ids = util::getIds(pull_out_lanes); -} - -lanelet::ConstLanelets PullOutModule::getCurrentLanes() const -{ - const auto & route_handler = planner_data_->route_handler; - const auto current_pose = planner_data_->self_pose->pose; - const auto common_parameters = planner_data_->parameters; - - lanelet::ConstLanelet current_lane; - if (!route_handler->getClosestLaneletWithinRoute(current_pose, ¤t_lane)) { - RCLCPP_ERROR_THROTTLE( - getLogger(), *clock_, 5000, "failed to find closest lanelet within route!!!"); - return {}; // TODO(Horibe) what should be returned? - } - - // For current_lanes with desired length - return route_handler->getLaneletSequence( - current_lane, current_pose, common_parameters.backward_path_length, - common_parameters.forward_path_length); + status_.lane_follow_lane_ids = util::getIds(status_.current_lanes); + status_.pull_out_lane_ids = util::getIds(status_.pull_out_lanes); } // make this class? diff --git a/planning/behavior_path_planner/src/scene_module/pull_out/shift_pull_out.cpp b/planning/behavior_path_planner/src/scene_module/pull_out/shift_pull_out.cpp index 50de3ba11cb97..88642b7c431b2 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_out/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_out/shift_pull_out.cpp @@ -41,7 +41,7 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) const auto & route_handler = planner_data_->route_handler; const auto & common_parameters = planner_data_->parameters; const auto & dynamic_objects = planner_data_->dynamic_object; - const auto & road_lanes = util::getCurrentLanes(planner_data_); + const auto & road_lanes = util::getExtendedCurrentLanes(planner_data_); const auto & current_pose = planner_data_->self_pose->pose; const auto & shoulder_lanes = getPullOutLanes(road_lanes, planner_data_); if (shoulder_lanes.empty()) { diff --git a/planning/behavior_path_planner/src/scene_module/pull_over/geometric_pull_over.cpp b/planning/behavior_path_planner/src/scene_module/pull_over/geometric_pull_over.cpp index d9d5ef4060b50..73f7c6fb79749 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_over/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_over/geometric_pull_over.cpp @@ -41,7 +41,7 @@ boost::optional GeometricPullOver::plan(const Pose & goal_pose) { const auto & route_handler = planner_data_->route_handler; - const auto road_lanes = util::getCurrentLanes(planner_data_); + const auto road_lanes = util::getExtendedCurrentLanes(planner_data_); const auto shoulder_lanes = pull_over_utils::getPullOverLanes(*route_handler); if (road_lanes.empty() || shoulder_lanes.empty()) { return {}; diff --git a/planning/behavior_path_planner/src/scene_module/pull_over/shift_pull_over.cpp b/planning/behavior_path_planner/src/scene_module/pull_over/shift_pull_over.cpp index 46d0cef7bada2..05d59a3f6f6ad 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_over/shift_pull_over.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_over/shift_pull_over.cpp @@ -39,7 +39,7 @@ boost::optional ShiftPullOver::plan(const Pose & goal_pose) { const auto & route_handler = planner_data_->route_handler; - const auto road_lanes = util::getCurrentLanes(planner_data_); + const auto road_lanes = util::getExtendedCurrentLanes(planner_data_); const auto shoulder_lanes = pull_over_utils::getPullOverLanes(*route_handler); if (road_lanes.empty() || shoulder_lanes.empty()) { return {}; diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index 1d8ef3d98fe07..9a6105d7940ba 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -1986,6 +1986,7 @@ lanelet::ConstLanelets getExtendedCurrentLanes( const auto & route_handler = planner_data->route_handler; const auto current_pose = planner_data->self_pose->pose; const auto common_parameters = planner_data->parameters; + const auto routing_graph_ptr = route_handler->getRoutingGraphPtr(); lanelet::ConstLanelet current_lane; if (!route_handler->getClosestLaneletWithinRoute(current_pose, ¤t_lane)) { @@ -2001,17 +2002,13 @@ lanelet::ConstLanelets getExtendedCurrentLanes( common_parameters.forward_path_length); // Add next_lanes - const auto next_lanes = route_handler->getNextLanelets(current_lanes.back()); - if (!next_lanes.empty()) { - // TODO(kosuke55) which lane should be added? - current_lanes.push_back(next_lanes.front()); + for (const auto & next_lane : route_handler->getNextLanelets(current_lanes.back())) { + current_lanes.push_back(next_lane); } - // Add prev_lane - lanelet::ConstLanelets prev_lanes; - if (route_handler->getPreviousLaneletsWithinRoute(current_lanes.front(), &prev_lanes)) { - // TODO(kosuke55) which lane should be added? - current_lanes.insert(current_lanes.begin(), 0, prev_lanes.front()); + // Add previous lanes + for (const auto & prev_lane : route_handler->getPreviousLanelets(current_lanes.front())) { + current_lanes.insert(current_lanes.begin(), prev_lane); } return current_lanes; diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index c91f9d93ad9cb..bf980137585fe 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -123,6 +123,7 @@ class RouteHandler boost::optional getLeftLanelet( const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getNextLanelets(const lanelet::ConstLanelet & lanelet) const; + lanelet::ConstLanelets getPreviousLanelets(const lanelet::ConstLanelet & lanelet) const; /** * @brief Check if opposite-direction lane is available at the right side of the lanelet diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 62b02dc3f1df4..a124beb045307 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -748,6 +748,12 @@ bool RouteHandler::getPreviousLaneletsWithinRoute( return !(prev_lanelets->empty()); } +lanelet::ConstLanelets RouteHandler::getPreviousLanelets( + const lanelet::ConstLanelet & lanelet) const +{ + return routing_graph_ptr_->previous(lanelet); +} + lanelet::ConstLanelets RouteHandler::getLaneletsFromPoint(const lanelet::ConstPoint3d & point) const { return lanelet::utils::findUsagesInLanelets(*lanelet_map_ptr_, point); From c953392bebb150e76e461ef689f86313672f0382 Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Tue, 4 Oct 2022 19:29:15 +0900 Subject: [PATCH 04/28] feat(object_merger): add distance_threshold_list (#1902) * feat(object_merger): add distance threshold Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(object_merger): remove param from declare_parameter Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(object_merger): add distance_threshold_list Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(object_merger): use map instead of list, and use yaml for param Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(object_merger): add function converting list to map Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(object_merge): added extended scale and tuned parameter Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(perception_utils): add generalized IoU Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(object_merger): use generalized IoU threshold instead of extended_scale Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * fix(perception_utils): move 2 functions to anonymous namespace and use MinMax instead of MaxMin Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * ci(pre-commit): autofix * refactor(perception_utils): use convex hull instead of convex rectangle Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../perception_utils/perception_utils.hpp | 44 ++++++++++++++ .../test/src/test_perception_utils.cpp | 60 +++++++++++++++++++ perception/object_merger/README.md | 28 ++++++--- .../config/overlapped_judge.param.yaml | 5 ++ .../object_association_merger/node.hpp | 4 ++ .../object_association_merger.launch.xml | 4 ++ .../src/object_association_merger/node.cpp | 41 +++++++++++-- 7 files changed, 173 insertions(+), 13 deletions(-) create mode 100644 perception/object_merger/config/overlapped_judge.param.yaml diff --git a/common/perception_utils/include/perception_utils/perception_utils.hpp b/common/perception_utils/include/perception_utils/perception_utils.hpp index 70171a95d19ea..eec280ce6c6c8 100644 --- a/common/perception_utils/include/perception_utils/perception_utils.hpp +++ b/common/perception_utils/include/perception_utils/perception_utils.hpp @@ -29,7 +29,9 @@ #include #include +#include #include +#include #include #ifdef ROS_DISTRO_GALACTIC @@ -54,6 +56,19 @@ namespace return boost::none; } } + +inline double getConvexShapeArea( + const tier4_autoware_utils::Polygon2d & source_polygon, + const tier4_autoware_utils::Polygon2d & target_polygon) +{ + boost::geometry::model::multi_polygon union_polygons; + boost::geometry::union_(source_polygon, target_polygon, union_polygons); + + tier4_autoware_utils::Polygon2d hull; + boost::geometry::convex_hull(union_polygons, hull); + return boost::geometry::area(hull); +} + } // namespace namespace perception_utils @@ -102,6 +117,35 @@ inline double get2dIoU(const T1 source_object, const T2 target_object) return iou; } +template +inline double get2dGeneralizedIoU(const T1 & source_object, const T2 & target_object) +{ + const auto & source_pose = getPose(source_object); + const auto & target_pose = getPose(target_object); + + const auto & source_polygon = tier4_autoware_utils::toPolygon2d(source_pose, source_object.shape); + const auto & target_polygon = tier4_autoware_utils::toPolygon2d(target_pose, target_object.shape); + + std::vector union_polygons; + std::vector intersection_polygons; + boost::geometry::union_(source_polygon, target_polygon, union_polygons); + boost::geometry::intersection(source_polygon, target_polygon, intersection_polygons); + + double intersection_area = 0.0; + double union_area = 0.0; + for (const auto & intersection_polygon : intersection_polygons) { + intersection_area += boost::geometry::area(intersection_polygon); + } + + for (const auto & union_polygon : union_polygons) { + union_area += boost::geometry::area(union_polygon); + } + + const double iou = union_area < 0.01 ? 0.0 : std::min(1.0, intersection_area / union_area); + const double convex_shape_area = getConvexShapeArea(source_polygon, target_polygon); + return iou - (convex_shape_area - union_area) / convex_shape_area; +} + template inline double get2dPrecision(const T1 source_object, const T2 target_object) { diff --git a/common/perception_utils/test/src/test_perception_utils.cpp b/common/perception_utils/test/src/test_perception_utils.cpp index 889f92994b37a..767ba82cc0460 100644 --- a/common/perception_utils/test/src/test_perception_utils.cpp +++ b/common/perception_utils/test/src/test_perception_utils.cpp @@ -375,6 +375,66 @@ TEST(perception_utils, test_get2dIoU) } } +TEST(perception_utils, test_get2dGeneralizedIoU) +{ + using perception_utils::get2dGeneralizedIoU; + // TODO(Shin-kyoto): + // get2dGeneralizedIoU uses outer points of each polygon. + // But these points contain an sampling error of outer line, + // so get2dGeneralizedIoU icludes an error of about 0.03. + // Threfore, in this test, epsilon is set to 0.04. + constexpr double epsilon_giou = 4 * 1e-02; + const double quart_circle = 0.16237976320958225; + + { // non overlapped + autoware_auto_perception_msgs::msg::DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(1.5, 0.0, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + autoware_auto_perception_msgs::msg::DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double giou = get2dGeneralizedIoU(source_obj, target_obj); + EXPECT_NEAR(giou, (2 * quart_circle - 1) / (2 * quart_circle + 2), epsilon_giou); // not 0 + } + + { // partially overlapped + autoware_auto_perception_msgs::msg::DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(0.5, 0.0, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + autoware_auto_perception_msgs::msg::DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double giou = get2dGeneralizedIoU(source_obj, target_obj); + EXPECT_NEAR(giou, 2 * quart_circle / (2 * quart_circle + 1), epsilon_giou); + } + + { // fully overlapped + autoware_auto_perception_msgs::msg::DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + autoware_auto_perception_msgs::msg::DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double giou = get2dGeneralizedIoU(source_obj, target_obj); + EXPECT_NEAR(giou, quart_circle * 4, epsilon_giou); // giou equals iou + } +} + TEST(perception_utils, test_get2dPrecision) { using perception_utils::get2dPrecision; diff --git a/perception/object_merger/README.md b/perception/object_merger/README.md index 6993bb57b4f80..62a95ada62b09 100644 --- a/perception/object_merger/README.md +++ b/perception/object_merger/README.md @@ -25,14 +25,26 @@ The successive shortest path algorithm is used to solve the data association pro ## Parameters -| Name | Type | Description | -| -------------------- | ------ | ------------------------------------------- | -| `can_assign_matrix` | double | Assignment table for data association | -| `max_dist_matrix` | double | Maximum distance table for data association | -| `max_area_matrix` | double | Maximum area table for data association | -| `min_area_matrix` | double | Minimum area table for data association | -| `max_rad_matrix` | double | Maximum angle table for data association | -| `base_link_frame_id` | double | association frame | +| Name | Type | Description | +| --------------------------- | --------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `can_assign_matrix` | double | Assignment table for data association | +| `max_dist_matrix` | double | Maximum distance table for data association | +| `max_area_matrix` | double | Maximum area table for data association | +| `min_area_matrix` | double | Minimum area table for data association | +| `max_rad_matrix` | double | Maximum angle table for data association | +| `base_link_frame_id` | double | association frame | +| `distance_threshold_list` | `std::vector` | Distance threshold for each class used in judging overlap. The class order depends on [ObjectClassification](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_perception_msgs/msg/ObjectClassification.idl). | +| `generalized_iou_threshold` | double | Generalized IoU threshold | + +## Tips + +- False Positive Unknown object detected by clustering method sometimes raises the risk of sudden stop and interferes with Planning module. If ML based detector rarely misses objects, you can tune the parameter of object_merger and make Perception module ignore unknown objects. + - If you want to remove unknown object close to large vehicle, + - use HIGH `distance_threshold_list` + - However, this causes high computational load + - use LOW `precision_threshold_to_judge_overlapped` + - use LOW `generalized_iou_threshold` + - However, these 2 params raise the risk of overlooking object close to known object. ## Assumptions / Known limits diff --git a/perception/object_merger/config/overlapped_judge.param.yaml b/perception/object_merger/config/overlapped_judge.param.yaml new file mode 100644 index 0000000000000..94882fae4f282 --- /dev/null +++ b/perception/object_merger/config/overlapped_judge.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + distance_threshold_list: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN + [9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0] #UNKNOWN diff --git a/perception/object_merger/include/object_association_merger/node.hpp b/perception/object_merger/include/object_association_merger/node.hpp index db4f0511abba8..943a17138ce1b 100644 --- a/perception/object_merger/include/object_association_merger/node.hpp +++ b/perception/object_merger/include/object_association_merger/node.hpp @@ -37,8 +37,10 @@ #include #include +#include #include #include +#include namespace object_association { @@ -71,6 +73,8 @@ class ObjectAssociationMergerNode : public rclcpp::Node { double precision_threshold; double recall_threshold; + double generalized_iou_threshold; + std::map distance_threshold_map; } overlapped_judge_param_; }; } // namespace object_association diff --git a/perception/object_merger/launch/object_association_merger.launch.xml b/perception/object_merger/launch/object_association_merger.launch.xml index 85b9eff90d25e..43d3c71d2b78c 100644 --- a/perception/object_merger/launch/object_association_merger.launch.xml +++ b/perception/object_merger/launch/object_association_merger.launch.xml @@ -4,11 +4,15 @@ + + + + diff --git a/perception/object_merger/src/object_association_merger/node.cpp b/perception/object_merger/src/object_association_merger/node.cpp index 0dc030d733294..280f7875a66d6 100644 --- a/perception/object_merger/src/object_association_merger/node.cpp +++ b/perception/object_merger/src/object_association_merger/node.cpp @@ -34,16 +34,35 @@ namespace bool isUnknownObjectOverlapped( const autoware_auto_perception_msgs::msg::DetectedObject & unknown_object, const autoware_auto_perception_msgs::msg::DetectedObject & known_object, - const double precision_threshold, const double recall_threshold) + const double precision_threshold, const double recall_threshold, + std::map distance_threshold_map, const double generalized_iou_threshold) { - constexpr double sq_distance_threshold = std::pow(5.0, 2.0); + const double distance_threshold = + distance_threshold_map.at(perception_utils::getHighestProbLabel(known_object.classification)); + const double sq_distance_threshold = std::pow(distance_threshold, 2.0); const double sq_distance = tier4_autoware_utils::calcSquaredDistance2d( unknown_object.kinematics.pose_with_covariance.pose, known_object.kinematics.pose_with_covariance.pose); if (sq_distance_threshold < sq_distance) return false; const auto precision = perception_utils::get2dPrecision(unknown_object, known_object); const auto recall = perception_utils::get2dRecall(unknown_object, known_object); - return precision > precision_threshold || recall > recall_threshold; + const auto generalized_iou = perception_utils::get2dGeneralizedIoU(unknown_object, known_object); + return precision > precision_threshold || recall > recall_threshold || + generalized_iou > generalized_iou_threshold; +} +} // namespace + +namespace +{ +std::map convertListToClassMap(const std::vector & distance_threshold_list) +{ + std::map distance_threshold_map; + int class_label = 0; + for (const auto & distance_threshold : distance_threshold_list) { + distance_threshold_map.insert(std::make_pair(class_label, distance_threshold)); + class_label++; + } + return distance_threshold_map; } } // namespace @@ -69,9 +88,19 @@ ObjectAssociationMergerNode::ObjectAssociationMergerNode(const rclcpp::NodeOptio remove_overlapped_unknown_objects_ = declare_parameter("remove_overlapped_unknown_objects", true); overlapped_judge_param_.precision_threshold = - declare_parameter("precision_threshold_to_judge_overlapped", 0.4); + declare_parameter("precision_threshold_to_judge_overlapped"); overlapped_judge_param_.recall_threshold = declare_parameter("recall_threshold_to_judge_overlapped", 0.5); + overlapped_judge_param_.generalized_iou_threshold = + declare_parameter("generalized_iou_threshold"); + + // get distance_threshold_map from distance_threshold_list + /** TODO(Shin-kyoto): + * this implementation assumes index of vector shows class_label. + * if param supports map, refactor this code. + */ + overlapped_judge_param_.distance_threshold_map = + convertListToClassMap(declare_parameter>("distance_threshold_list")); const auto tmp = this->declare_parameter>("can_assign_matrix"); const std::vector can_assign_matrix(tmp.begin(), tmp.end()); @@ -152,7 +181,9 @@ void ObjectAssociationMergerNode::objectsCallback( for (const auto & known_object : known_objects) { if (isUnknownObjectOverlapped( unknown_object, known_object, overlapped_judge_param_.precision_threshold, - overlapped_judge_param_.recall_threshold)) { + overlapped_judge_param_.recall_threshold, + overlapped_judge_param_.distance_threshold_map, + overlapped_judge_param_.generalized_iou_threshold)) { is_overlapped = true; break; } From 80082deada2b7f32eff227f996b0491885e3ed32 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Tue, 4 Oct 2022 19:42:56 +0900 Subject: [PATCH 05/28] feat(rtc_manager_panel): add rtc all approval (#2009) * feat(rtc_manager_panel): add rtc all approval Signed-off-by: taikitanaka3 * chore: cosmetic change Signed-off-by: taikitanaka3 * fix: static cast Signed-off-by: tanaka3 * chore: update text Co-authored-by: Fumiya Watanabe * chore: update text Co-authored-by: Fumiya Watanabe * doc: update documents Signed-off-by: tanaka3 * doc: update Signed-off-by: tanaka3 * doc: small update Signed-off-by: tanaka3 Signed-off-by: taikitanaka3 Signed-off-by: tanaka3 Co-authored-by: Fumiya Watanabe --- common/rtc_manager_rviz_plugin/README.md | 22 +++- .../images/rtc_manager_panel.png | Bin 0 -> 714694 bytes .../images/rtc_selection.png | Bin 0 -> 43862 bytes .../src/rtc_manager_panel.cpp | 109 +++++++++--------- .../src/rtc_manager_panel.hpp | 12 +- 5 files changed, 83 insertions(+), 60 deletions(-) create mode 100644 common/rtc_manager_rviz_plugin/images/rtc_manager_panel.png create mode 100644 common/rtc_manager_rviz_plugin/images/rtc_selection.png diff --git a/common/rtc_manager_rviz_plugin/README.md b/common/rtc_manager_rviz_plugin/README.md index a4542849e4ce5..7a15d56fe235a 100644 --- a/common/rtc_manager_rviz_plugin/README.md +++ b/common/rtc_manager_rviz_plugin/README.md @@ -2,19 +2,35 @@ ## Purpose -This plugin displays each content of RTC status and switches each module of RTC auto mode. +The purpose of this Rviz plugin is + +1. To display each content of RTC status. + +2. To switch each module of RTC auto mode. + +3. To change RTC cooperate commands by button. + +![rtc_manager_panel](./images/rtc_manager_panel.png) ## Inputs / Outputs ### Input -tbd. +| Name | Type | Description | +| ------------------------------ | ------------------------------------------- | --------------------------------------- | +| `/api/external/get/rtc_status` | `tier4_rtc_msgs::msg::CooperateStatusArray` | The statuses of each Cooperate Commands | ### Output -tbd. +| Name | Type | Description | +| -------------------------------- | ---------------------------------------- | ---------------------------------------------------- | +| `/api/external/set/rtc_commands` | `tier4_rtc_msgs::src::CooperateCommands` | The Cooperate Commands for each planning | +| `/planning/enable_auto_mode/*` | `tier4_rtc_msgs::src::AutoMode` | The Cooperate Commands mode for each planning module | ## HowToUse 1. Start rviz and select panels/Add new panel. ![select_panel](./images/select_panels.png) + +2. tier4_state_rviz_plugin/RTCManagerPanel and press OK. + ![select_rtc_panel](./images/rtc_selection.png) diff --git a/common/rtc_manager_rviz_plugin/images/rtc_manager_panel.png b/common/rtc_manager_rviz_plugin/images/rtc_manager_panel.png new file mode 100644 index 0000000000000000000000000000000000000000..36c1b4760308b8f2d80744a7a1a2b88d0426db40 GIT binary patch literal 714694 zcmYhj1z1#3yEZ&Xhol11jVRsSjevj>LnGZ?64D?@hk$fTcQ;6hz#t&q-QDmn&U@bf zd|Y~|1L*9%*SgnTk74hXWS*lDp+O*!=W?==st^cb3IqZlje-PTshI641HT|RiOYRJ z0Uur{#-ZTPubibcoz?72o!tx_O(15rb~YwVPM;i2Ol+OZ?VJzc+l9dwaaerNbe3>5 zF?6=Dv!(c8VPgVbgh1F?+1b|{YuH#feuT1eZY1SVuyJlA`*X6bhX%9pZ5G5Pn22gY zAQTWeNwE*^KlZ#mygp1!Kl0piYteDUB?QWe;|5pIW)h+_P~?3@kL;aMzg>x)Y`eLc zsaLGsFZZ_D-%!xDv6+xBg(j&c$?8JT8$@Z4xWWkKo&{C}1{$*`(-_kZ-8~TgS)b$B zoHLGvNpT9S)kDQA7=r2 zZ*Om5aWOoEmjsiOn_K=G3lp=;w3?EipNN{8nvjg_S4Rg#hdC+3>&%XylUO7_11nHMSmaElA|V_&w8HIDXTni z$}1?qLAJNIVXglD&l=`!X=rH&&bZ&aK}$h;dH{8cpz#!(?v?5~4Z zSXe@4_Y=F2Pw!t26!ValnwXdrEHYi_Qf~96DQPm|ThBG9e19z9lFncM`1Ujmk3L_Q z49C*avf*;rl!MHD3C?<^1~n@ytFWj@Ox%)L&-a+&ZbzeC{M1iki!{BbzP*-=K*t^q zpIN6ccARzLW;^LPRjq!B<gnF`;E&6HW3{(p|(f1c;9lg z&Bqg#tH~CQOZup#>BlDc)YyX#4v||bTnPlNZ#+w5+CE=?abc}KG-^BC3e`3o`Gp*v zx5#ncZFAolEXv;<_?;eI>@P~~4~i_gO_@>uW%*+O;0lICZYj z1y4$^Ly^85M;-SMi*(Q@-Q%=B%5&2Zll3w!KB5%+Tq4g!6C**s^By6zou}z)dOb>e zbuWvryS4kZo6U!t9YPTphK{k0n~5I@ZZ#h9vF5*{N1QFMEn^)I{t_`%Fhf1?IYVw3 zWh^fVODwRz)opfoD1Qu0Mek-UQ*WyjYIqd!2}&n^h|t$f@W+Pm-ougIMP+23r^p<2 zxNxvmZu;n4Dqz`qpCoC1!r_X9gGa(3WIZ|zyIk}oe>@d=gfE|xA+29*>#av1HEtEvU&v4h&SW@kncD6z$E; z#N4URPd7(G`c}oPtr;2d(Nj`VjPZ2T)lX8_inznpW0akzx2*Wdx#tfKYW(p3&OP{yT^0g!AepYSK{9MWn09vqp0z9O3E5Fnz(q=#7})&d@+()77eD9cBV{ z7>E7VDCM@EkvP@L%F25U-@0;B)a^filzLKEV!p?RR#vh>qGe5QntU_$oBCqM13%;+ z#<@2yUYuLCxZNdTwttSo&3Np8~MOxYoNC;JTEIoU^ ziQ_51$f1|s@*t(SsjaPT$emj0`{)CSZW|(tLWYNj|4BnU=CN@5d!uN*IaeLanm@3H z7J(YIPa$N2GF^#_o4ae<`6lLf$8?*FjbT|$&5MD7fzYpC#Vsx0@Cyj!3A;^}XsI@X zcfb%iyDu##7bYoPeFF0wDAvZu41ot=Vs2p(GeLexN;&oX`SXUmlOedPow&>UmtsY> z6VC5#ym}*p+&$YIR;A}$rgZK3(+W#U;#;-%ZoSqp27V+Zh5Y>aM =s{j%blCdXg z{}tM(EsE%nz{_Ct3~oWPD9JC%N=hrc`j7m!P1|&HzK{0+vK!75Qw{28mmM29qko&R zJseYC-IzrExPIyXy+l>#GH3Q^-D{%g#nO3~z&4_|c&6+pPh@+`j&Myil57$yhy4~C z_nTg#5+?Gl@YxXi&NPiKG9R>jUW3fX7j$rep0`H>8|_QU`{c{AQw;AUdm#lavad+t z7h_*zyyAdiJO0GFk82Ysm~~xFrhlU{KNp!E!`dSiY2@|WpN)leY#|~5zVdthzh&y= z`=H>0Jj8?JoPTGFR>y8T4_EGlj-GTM-%%H)>2HtsK6WySAQcE)qD|$wu;d4_}A2bk&`WPdIGtfb5-7 z@K>*=O>EHd1+IMREzaBpZ)D{G8Kk2lgxs*C896JTmwc>*Q%n#X z$K-}$NXgl^oRV>POn5G$X$@;JMV6Di+^LFGOrh&1ZQi$cp(ac;b+BA1$-$Ug&gJ21 zq*cZKEx~EIT63y*0UG*LR>XOzlyA%DZIgml2Nb|Q4Z_`GZE<#wqoy^l#9YbC3HnE{ zo;8_&R-4G5J-!t4)$^2~wtW)uSvp3|T(j$bER4DbHI?4xrLLxC=)*&`q@k-THxe?k zVWnnte0*SFAVPdX!oW$6FP{I*vOVNT>o~8VfSQZzWh#$dVpo_f8Bw6IlB{gBF--h@ z*p6aY1(m^oh&on0N<2Uo+pFGif=|ZI2#AP?u=~G%KR`N){L~1AguZH3n`V`d$h>IQ zVWzx(Ct*y=ROOZ5U449Wb89Tg1(6Jt$!yJ;FV8R?ub#FJ{q{{tQW60|!9%Y>7($yo za2{5N_Y<85I)k;uVpQQEr?=;w(vf%A_v_a)UWGRJj-MZk?f3q%aq{puo#vL;M*pa} z%eF(;l@X+h-pWw-|Ek&A_HeTc@#?7_HkHuRBl~U2QB_rCz@D7z6NqT1BJErnL}4=2 zjjk|d1`rGi?NNVl_R{n1Cf>yMPehK1gl)gZ8OzJdd;Rup9EwuYp$WkwWa;Z$z%XlS zYAERGWr##voSpk!T`TN)NdVkoLpe@w6sX*^v|a%&l(z`|g`VA}W5Gi_X1CxUG2_pX z8Z~b#qp0|NaB%Rwo*uInLpY4m=G~y|Zv4!p)Cd)t9Y!9f^eD$9-<17sX?=EnK2m{l zhV-XT)NPlohjJr&p4+sN($XuHePrVartS~?bDyVrWzz-2(%KilXebvLm38OaR>DKF zxQ%mVj8;Y|Ya&a3`OAtmjEP}H22s$_5m8dIH5kwLx<4!sRInMps7+*9nNq;R#$}KE zM`&PgfbxYPJq>Hcmt5rQN~&#l)YowwftfFxJ{Pa!FWvx5g#RAshTGxJk$%7ZXlQl! z@oK~E5wH5U;nu?S=egURU zKQ0}-HKls<1_^cYg{F~QDdy^Z-va@bw?W_eVheKK^znDz8#Hd~D^WhFCNDjf7D|VP zB@v#bd=F=dvRw=Vc@LXwItV~_?JAE8cR$pojwj&>4zjSe^^YioejXI&>;dn|v&NUH= zV-h*FGC3BR+MEPo?;>dHY_Gtro$!qYE{6AaCBhF}A2csO>fK1Gw+(Tx0##)7Q7%*kQQXDW=7GzQQ2^e;Y-TrusEm zF^`;_Txi(0&i<`XXSP~nV4-tr)EQFuA~D*M z?o~H^J8x%4=xJ!KVtz6wDZHVdmQzzz^^b|c(JWQpo2eaAcGc58y>Vmm4o~z+6f7up z)#9s(aM}9Ylfw7rjlA?I%!LVxvYhZuW3sDD{8gvi+Da|`E*S$QB^(Y84tPXyjW4U9 zrLcoQaHJPK3c2omk6<+&8i^}!Y9a!vLv>L{SC?r!JXQb==O5ea=Fsj*k;&9X4c zWw769hD;aS*CPcEmYSd{#MD-#0!LlpuA?!FRI&H^s6|CZ4Hq+3$Mx;^-)`?xtjffo z(3CdGoYMY3!&36H%%%%!k)IZQ2-`iJ$$T!;@(fx8uBd4+!&!vMj}Kde+U;7=oXY+@ zi}E?gd~PsGjHz7{h5aqv_j%diEk1YK%U~%tJ-CcxXHKK+FEM^%5r)rfkhNK39oQyI zTOo*skY6D&xTM*#oI@vq6aE3DS>He3e`|0y#DK7rXvxJYM2?vWI=lQ(PHX3zQC4N8&@V`HS1 zySt!JoWvOP&u6TdB&4E)>!;Yg=r3@ebrjR(|1UGOL!Zg!qj`fnu+Bq4MNbT<(br|~ zwo0Sl{(P+E&A7)&WupJ?u1^m?I(}Bs(P6Zqt()DCEf=9RM+FF4w(UiN84^*5n>Rl@ z`xafn7_bRxb#?sg?Cd4S#?i&aC_wufbeJ)oKfhk*;N;Bxj+G`HC7NTBS?;l(>s#&d zQ#X7@ih1ldb=W7-Gn+eaJnM9G0%vwo z62I<8%h4GZsj?!$c7?UOo`>W)t$e^2rc@MX!t|D!NNlk7L@u#f8d|ExruJx33pT&_ z-dFL{!w^-{TW)G*_sz}CMYXkwG0BA^z#GKC!pZ@w>HPfM+}gS)UFh?BZSC-x87K*_ zJw(8DuLHai9UJQpzLG@16@!6+0dOQBppllUiPE^N@TFyBa7dXJS>+F2zI@qfTmNYr zme)Tp;Mcv}adpKzGc)sI(c^G|%$j@UR184DNZ=bhHv3O;({ zFc>QvSUC-r)>PQ-eA5X&@?DuptWdZQ8M!SXQl97{BxtDUw%nvpvT|bcor$oSDRtY%+6Mt z4B=y7VrCZ?qpKIc^!E0y&}971_6f<;)ARlN_g_qg5)G%TOkTfv)0Hh1{={wVc@3(k zpEwXAI{wm9XMk$kw{PEM6%@L=g3tlW&oiruC?SKp<2EWkkN7x!lwC=YrYs==-=fC? z^mHh2I{r>g4H>)fr^(96b*@H$%c+&=*BPrdJ{(#IRwa!U16IcaIJ%Jvp~AvU0w=r^=@a? zfBe=8gO!+v>7+S(hicT5OKjw6thRjU3Js=sQ;eOsYG-&lqKf%;HcBM&+}GnKEFF{ z%|S`s9HRc65*+QVeRL8THA?U*WOUq{cUm=Sr#q{^J{9LH9OuL7N3U3SoU&Gm)e`;f z0nEQGcicMFZJ}J~argI%A(AT}y7Bi4_odxao{xPhShAQ6(fw#6tG!*kC^vDE*UhaH zpuyc9lpjOb6O7S4?g}CI8TI>j_evH8uEm>t^&2U$}W$cS)f*846m$tqef`DOFW)m&sY%Xp z$FjZt$}%$;U!6;8VyK@b*5*C;Dk<(;AVuX4Lk5y8XdgN{x_l*q$BW#PP=wOVuq z^*8Gbo`1x1(P_xJjQqaQ`^zFN7^_N_oXXPEvg_MW5rw9Q%d+V4NuA5xUcAifErt*2 z_5<3lrnWY#wDfsxZ7uF{74Y)F_FPGGTM+y3;RV=tc{RAWxUBsAUlSAY0SGD_-~%(k z=+h@!_PoMES?NMXtty1+>FHSFD8Te{e*TniK|PVRjcqfaL25f>Z#0@baSJ$m~Q^j(DXJlkFIyt#9<@R-f z;Kn~7UxMPCc+`#}8jg5^VM-$$_kvus)WwV-OoX&8KeYJ!$EQ(^Zk4Zz~ z{?gZX_r*q;FqVZ`>>A!MM0_Q>`izQ^6)XF^TlZ>nlF9v(*~=ZwbBe!-;U4H_-7{(d zNsrT*w*=)~+41iol%elj3@l-US{>IAit~Q?$%Udp#KX^N1NNhB| z*8c9-FB)blY4GcZS0HKWugO7z_t%5mdv`}PR4{b=2U-Fn*I1-%K0%DhYXvr*4I0Zu zFVgasDnx;w#G`B}!Li{RT|{VsQ1F9C zlr%I5adC06F4Zu7S!?UP_`?^lU0)vTdSuQ}ESVLagiYK4q|~xWcvVfUgcXMCOXDnh z-`31=bWU>alJtgRjq+c_b}eunQ*~eoz^xb8d2_r^qEkySV|97aPZ?}2$gNy^2S0Ib zFj%zV`socgq~MO~ORNUsG{{!^;t{dq-Ma`$NnjRp za&khxWIw8jY7xk33w$N%XX(FOmul>%kmTbdjA|uE`B$SkYSGuzBdfmFVy~j2!aL_k z2w5}<>3?KLpYcZ8bq#p%ZaHtrKa<2hr!09uoIxH*6CeN_9H3Zio5$KHH@>`ZtH^jo<6M&s>3xcF3gi!&Gs+KIA}M5FJ`zl4S2wCZYXW&8bm{|sjy2^g?rMS% zKFa5Xc>T_ViG}HWPINc7w_Gt(ez9{vFUr=@CfChkg`jUd^*HV(|z(4MNYXplJGL9!+-b zk;^Ei)bZ^=Ub_a-0x|dO7Gz~ z=dkaizFa|94>0Ba4;Ba?J`v{NkPxn@W!i94&uG3h8nueVg8$!-kLh23#bIi%jJvtc z!0)1Crv*=&alXO#F|o-L`}K7}JmzN+Iy!0I7?@{8RJ!0q*G}oIsND2+h5g^0Q%^S1 zChXVA`8>+}wwVGLkfo;GvTm@9@4G&J{J0G0L|0fVz6bp$y2`uk^}-pwpy*?4hHra& z))w>-xo{cT@epF%(0=m~2CSQ#8=9^JA&T<<_0Qi=HcB~-O;2pg$d1&Ee5ieckJD!v z$bSE$%@oy6s2!w9N;TL0I5Q^F`ugONHDqE@yL$tTmiM@`zn}yu@tGlB>N^t8_Lbe= z$Lg0p;>9%V87b-L{8$wGf?!*(?OKsFV??Li_TvXhPfw2lSflQTt(QQ|WKI*MYhV%y z?i%0`R`mWGR8zlDy42#IKVO(&Ik)_D(fRYaJmCgg zk8gxFTMHdutopSU+nUPb?G6NyR8Y49NVXrYb%b+bqmJ+RjIZ#pt z92k`T9~3oRlqt6MZ`$j!1=nQeDp{*^%fl~)dj82MyOcq-(Ns`p87ptTG^G~=1Vbgs zc(}L~K&WIP9zUs&>gmymi6B0wjm)YlTnPz@hVw~n6`(xV){M`vE^|D6xg1S53=9v% zNo@GOUY~B}fL+I&gbtFQzB1ir`|I_jPrH+)?BeR%q_3Hnq)bie=;-NbwOWt5#y9;w zMM{|N4?!WR@94sKf!XzQjYC1*?8)@;!YE=WB77yZ+oxqr`TUA8%_8}4zgbK;7MGRP z1z#GA+^2Dl)Z9%fAuLmZVA;pB*jo7};w=uLWsk!jxRpi0w+GEw$e1J@+v5cecUM|d zv;YY%O5K|00myDPp^c5(>DhN8J|QlMPzA}bR8>`JU|$I|;>j4QQ)V%^Di;5`>`tQU zp1$k#e|kZ026{?6a@Mdh8jF0pP?C8vNAki2E`AE zWuS}VpMnboxDd9pV=0xL-k%m9Pg8sR!E3W%XI>qBs19d3=tzqKJA3*+Q zJnh%tlCWRzU5G#P{Ji`j`rVg0F=mHvVswPyrm7da%;+GGet#p}`&%<@?f!Uw2?qftIS78bfFsb=-OVN}{1k|Jofqr(j+YC6o1I#W?0dK) zqzj>cf~w5)4aR<4blcMCAoQf8%!ggn?sd#*lsvAADX zl!?TzjiI?(I}9<^Q*d&ANU)xK3-6()(?Y_=R@pz8;&*d{H8!Wi;xr-FaoVgr_X+#0 zH;iC?eSJBMK3&wur){lT%f?SUD*bJOqQzad8C!VAw)09>2$?DdM;dFW>HlP`U_1Lc z;l=Joz+kF0^z_ugUF3HU!bq>Kt~QzUI_rG4(7#VbS;BN`Cy@&$C?1Ng=b6%G}8>kkBsyU zM8^5x4?dZ^ce<*h*HwYlxYpdnK&ai<)%StGGcldcJL!x>__es5GE1G!bbg_e=Z(HP zK|DT|RMXF-JJk4|@m+q(@1BNYjQZ46RQ7jQ4%-H@Od+I}G0#Ug%u?vmWTd581qB&T zHyJIdCmoZNGOnKI&-)zRpg>?wDF~RRZ~;hZpkBei+w*W3d{1zM$Jw~bz?0f`-@%Z#rW*pml(r=bSw8A%e9!q+htkUhf|Rf z#Lg>xe63|gvvlVx1I+&MfNgufEPC5ae#uA7wfRXZ7Cws5=x4^8$d%b@gKh({w7_-z zS7$?9*06$Rz1T+D*x2}F4o+z32c-$r8_YKmzt_5E2PbWX^)$P)vvbGl@zPuUYcw*S zD?=T}0a~zS1Lkd~-eHew`iwam|LI>FwhV57w8i@e3ZHdp;lLeWqC6>KaJ zqqFkzzMjWx99oJQgU~#VorwiO#ZZp#?!25`t{H31{`?3dbHkd_MP5=CKKxfFf#<-H zfPAHh$d;do^tOD`jq`gzuV!O>=qbR~<@?J;87C)>|EbnUfgBkSAsunS@4{2I^$Km; z=;-JUAU_jeA zx|3Xphcq{!q%-Ym zQ>O!L!_71|GEk+U@wWtO-`vuYUn0=cVfCASZ<}}XdsRnkd=nE1>exH&`(Hq4CFWQX5|M~QJ&7>M1Yb8VPE8>zR3R!3 zD|R(7G6*%>bI%Fc($LXS2?>#ck5Hao>gm`B5S(b~q(m#p$%z4SYD}7jok2m<>aoV# znH?*|>w5P+qZu2x8uNCC_-#3!^H&H>OWBt~c;_MGw05iyYaZTWa&o9omg-Uf*3S*a z%&8gZejAkksR;B`I0!unQu3bV7H0qP0+CoeZrJNb(A&$e@yHTUXqAGyXi0+2s??7Ir6mqKZ&9naT_avx1h zl8hYL-`%7oaKZOQ)f>9Iqc}LI6#ksaO2M+2nw(U(ZH|V2rpru_?sX!k#iyX45cBK$&u)nG-(7Shba}CEFLKvg}caS%RMFYmDtZOmdIgkth{ZWI-MME1i`b~tkvDAKU8u~Fvf0-TSJe_;*eCm$b&iYhy~Ow@sd ztu5-sp-3qB#M$L#H^2vU{i|nnw)0=9Wg=zqhoL%VkO%%+gRy6ZnlnE&hVKJ$VKA6| z!#XRZId_U$oeiBU382lJ+f$zz*BGr~`k$i@o{>4>c>*T}{((&sX zanKD5%qdSWiCK4eI7*ZIt+!fO0)G)6&VXVYm%MPQ)Jd6EHIk5!&`+NnxJAtrG8xcr z0q#U0kqfqt+q}znphI_db}BygVFsB0udV{+ilva~fB!UDtUBwxt{wLlT8Y1KI|lO{ zXCiMaBrWN0wK*@~xP}7Scke%Z2n23u_rB|=#|Nmf z$*`o0%k#;SMk3I}<8@d;SonM>q@@>VuB4zaZgZVvG9tba@%sy^3GL#q7BlA=;D>}7 z(vtr0N{T zraaV3{dSTe;q>A5uy5XNv6N8HDgzgTPpNN8UU*||ZD}Lb?iUd8N1e#z5D2h1N^CjU z*&94?G+2yD)?AxapwO=%ivf|WLedbf(E5iH`ch;nQrJ!^-+OaDlmr)*&cQ-t$;x&Y#!5v9t>B)znsHgvYV90>;|UHTQRGTkzMPNY}|@ z3B5JzS~b~pf%s;DW92Hyc%!{aVA!OSc^`vYS_Db>ys&renh=vYs=$H9l37`a11vac zC#ULB@eD=nZzU~9vFNlsI3=|9nQKn0i6fpT#$kqW12i#2ILkOGSTAztT>v^~mzOJ7 zMgI8_gL>GYal>>HlmbA@X0~pd;U|L7WU}>VU+5w_j$gq=WYy^EqX#%RAemQWVJCl6 zupCCRdD2xMY6K9BNJ(&UpH)u-8t5(<8X5U?Gy=EGc=9*UPDD->A*5BzOj};HntH{J z4$o?|-h~gA((Zw-X+!SMbg2ZiK`VOn^0e zwNX%~)TVPXr+5K{ngfyo4PBR)V0!|d>_0cB^F-z${?z6Hl`TeM+OF6q$(v<>SU**J zAy-`uCvCm<(gDwQCa>JiiZ4){>yTu{qLGh zP+&m<1P0tWP{`>HA@?D~W{}2vt&qsP+*Cw?{-vaRr6*T%09V^M?RNmKMG1bAkFe9m zI}#z!4{Cg285ZKQpO>#aCi%KnPxg|aAPFSbEno}f ztpr74hv)6$Zdo&CSXdbQ;tAyOGn^=|G~eUh>Dbg1{q=V`$I!V<^O(4TalbYe$l_)t zl+2p&LfeenjFOHHzqEANhlT^IhWrz4Xj{?coD-~lK##2Zj~G+q(VNdAfq7i zt6DVQp%al{>1=yEc7dLj7WFn17#hkO%wmcJlB{gzrNTmu!S}b93dg`zd^x~1)|1|* z*X+u~ZMT3S&^H+T{OzDjpy+@IKcf{Q^3`n=o%;BHEKqTU@WYO`)zgd1NnD+z0ugOJ)%6y`0*Tc=fh$ZjD zoYLU$$@`)9>}>zf8E*d)RGTYYMqT$Goi_G2&*u6B*EiD zHmetfcg%z(;!-hshm35T)IWgG+XAAQrliA8R-JJs{BvZ-j9%MPf_V+{?@wQrxEQLR zrBQ|)?N3+B;M@HSbzV`G*&h|?*c?jUQwK$Yf3;RgFCz7RC;*%zrNZIZ(q0K!eF3Cz$mwu#{Pyp2_Wp?>nk}Bn}Z4Z2qC(k=C zAv!v9dW50er@s}M%pH=Dkf5`>uE5-gVApn?|6aY;je?p3-Y~`x^5s7>6URdVZW(QT z!hj#VjhUoMBK^{iWx<54r8v&a8{faFIAV<^zZr0zq|}Cd=0?fEfd}S7blgbKc;Jpm zJr%SkiwBCO=vvoOp^L-R>raI>+vh0xT_&)nl>lT4L^xZkw0%z96Vgt%JrpohI#~ufaS*ZZ8w>P}f%?@7p z${=d3Dd2hedW9suWtj)c7$}nQO@*1Jr*i(+5Q2jr51>^@gc#_Ug(5xK^x(W5<3bXu zRH3Gq3aQu%(p#)LgVWCLUipiSaa}@3ttdUdCJTaD0Kvb-q1zwqXWVLtw8}ra3ZcZ? z{|z??{g`qGp(uW`G5$_W6yd(Ec{Jlr6E)F@efhm90CFCEt|kT0F%w~RlYg{gP1t7a z9XZ{gQqy_cE<%!yBPx*OxfN6TzCzqKGd+rG#d{D|w@#gZs@AdPMi)ndwBlN*o{VX= zzt-mqu#Ob|BLYpup~m~ap~5^~b6@7|-ZsC+xmWj3d9VU+splg!_roj~d_Mt$$9+6h zq;D`s-IVJ}w%SNH1a@q^wBG1>Zux`XWs(c6(tPsP=j#cjjZ{g%dA|ZR7;`bLeg(+2 zn6xyK&sh#R;`)v(LTrADh_xPBw%zkeb2?)u(4KwLBugD|pw-aR+iPfVk8N9@x=XFi zpiD%y`b>qCp|&X2NSp--?V` zQw~#SMAeZbFb!_|;Zu3O!JLKfIV4Igz@-GlifP=iR+mH2@gtKjSL1-)SeAp|1p|$q zr)QHhAvvh2G;jDwSdp(f^T#A7hlP-N_8%tW!_p5$kYu)>)6~}L{=81+z9CDHMkVlvrL_mF|;Nn>3K4I4G-sv z8TMmT$Bk_Sg%35I+Fq>3CjD9H<;#Wxy`^g#U0j}Wm&h~yZsl&jKI$3-iUejtV({Dt-5&RKJlQgSgar`Ov z7{3t3GjjzLHgI8D1Gtf*#m$(p+)?&FlvFh>s9tXM@I`Y|?JIiqTZZ9b;FKU|S1A_g z+u|&jY7m@7k3hqC$d;+lSg0mLr8vA<-V8>RF=sq3#lJvb@O>0&IsQdAzy9G3I!no< z*$@jfvhj4oab9){jxu*(*@MIMcL#lj*RzgA@f4{{{Bg#!o39%|>oH>vY!2@G2~!Q* zTUwd0ak~oR$aFW(_m6jsTZdhsAO^Ar)D9U*Fi~guzziBCmY&ES*ZK~9C#s`E0z|lqhDO0>3<^u?XSBNpw6I9z6bRiaGjMSL!`_=~RO4#HSA80Z z1A#}B;7RD755;2W*_kt=UJD^GR7HJ#MVMQT#6blCaZNt-Qd>c%b+Y5^l-RZb4isQ< zr{AT6(!RnfsY;W4Fdmi2AcE(DT{=b(=&@DiQoXf83Jwl-c(@LCSn3d?oG!VHR@Ni^ z+4!5{y5)kXom@ym^p60mfx%B4TwMSBe7b-NHr91k=b;Yg&QT`#@o&JM9?vjO=P<*B zEL!aMw3G1_VvcfCqWqOP`he{~l^uHdgRWGoaRN4Z6OnFTl{jXd?m0wKnAcF4UTZyE z2QB4w-ol1>x8p3dM zC#5?-HRI01Ii+Q~+1POp+#a{a0=D)9{cb$3571ighXDD4gMhkblkBS#uWPBH7(Qw> zLd;Ruigf(%!=^vXPqk{2R}@u!MRi<9!{a$|N~REzZ5T@FNmc%J`ibR2)!-c~yFSYl zj%47d(M+7888!{Y^~o^_sy(xqkFn=M|FO+SHeqa2_i({j|}EP4NR!cxlB zwT{sT9F3lzk=caF-ZW>#zlhp0$8&UYGT<)A$;%T86F;WYcV4jxq@7g$IBcP8OCaL23KM@Qc?cpK@Gl9NZ()p6T;AMJ#fQYRWm zhKG0m`$q^$gT`gAx19g+e}Ez0q>pd+^!KA!T3O{e|8vteP9DtHRaZv>@CFi2E#HaR zS@fhK+HEgKNA~QToIF-zIPL9J$kk0bXx>r)$OGNPs>60!;&Up-m%31L2eB8S>e(+;ole3_Sf!tg58!f%mkjIhatE)@iid<2=_D9IFB zUZK{soq5k)7cev4bqUf0d7)9I!-M4GLVJzV-u6?K4KmqHd(u+6H{8kUh^`cuvsKE{ zewT=^1M?-$TBRf#r1f44o)J1@CD`16g&0LhZq~3iXwWt1SRSN|g_3n;q+%P;m9Lz-L zF80hLDg+*vZFetf0(++$lrS$3=3$xY#;w`v`c!Y>#Esq;Oe{ zj*ka`vuB{5X+#&<3Q-0#<%L$4#jw6&fxnP_*d_tTdkrk;=~`aSRBI^NJzgGOga8JY z7qm?HERb3|M2mblCuezU=OiYPOqqv{K4jVP{7Q?xSgh!q`*O_|2_HiAh1&1f0SGo3 z{|&I=gP-x!usrv)0iR5z4`O0AbPC4@-jJ-vTfe$M_@cw{eW5 z^J7J&(|@}F9TeJaqF|Uo<$Z;$>&X6rr1@6i2h)=@B0|C=r>Jb2@WMY+<@!;;mi?fv zZfTk1ix|EU&eC>OjlZgo6}RtxRyBPkHmE;#d6P?N!R%>T`2DoDT`R2?XUM@~ zyMEPAzW=!2#*!p((|=mQSb)ebBnA-+-L>OQ%GzkA$@}ox`FSRR&~MLo?Rnp8XwZji ztEqt!GG+Awo+2j7z`G&YvfZ7X+?FU3J}T->h-?{0=#Ok?Sxt5P=J`LZBe*Y}p*{Mv z0$K(ppH9~XBhOhD{u&ZV%hy4w%TcoU~`-@`rqv}>tEovnYApi17pc)6}z zFZ6a?k!K#Ec;byh$Yt57^Pgq=%+^-Y5KK~WU2oEzo!z5@=EIfRDZTFI!?tjEWXz=w zKlrV^y`Iq}1o0L&+0Y?L#}!87+!68mq57-1#6-GviCb6DqE4~T2LlWDJ6K;LH1ko- z^jd&6&&|(&Vw1}_%d(1!Qb5n5p`k^`r3P4)x8nDrhpV(y5CZ40t3<0hSH$rP6C_#R zT%4U?m?8GSV%tfI!n3Q6vh>u_I|e2&7;LhhwR&P)uv&E(`Pz5k_Gdwq!7U<8|AU5x z0)m5r0(!ddg9li?MytQRxr6ZG>B(6CtAHC3c@!ifA~HVU2P13n;Mr7FvFrF;uY+eJ zDkX*Z6dZaJeEs?r%wQk@$iBLA2mf~jiJ*J5wkc8eP2S-+jT4Y{ps{$bV|zqFBoTcC za34&aul`!DEuGp;C@F+{3f#XsA5k8rN=7Fo(Vq%2T1v$1sTU{QeuDxJ4M4(sEv@Y& zB{#SFj6cUW-Z5Z$-K6tYZ}htQQ=s19jND_U|Nf*B6D6ob>i*%1NELpSnN#T672Mc_{ft zgiMup&$E#CHXKxubV?-kP(QSMKJG+0^!WdHddr}yzwiAU5Co**Lzgs2NlQyeNQo#N zBHbP5&>3jI*Qg<-avG(VuvDB;&XL-Dfd98r?(EFy|5M&$ou)UXwdZzi06+Qe~E>k8zYC@#)Q%a7=HO zj&bZP4+>+TzIHV`r{@Cqz+$RjF+lP*M)ubZ98LUeb~-t~z2q6b>qgMSTd`^~q3Gb3 zBWL~(1RB}D1#V!i?ofguK9^sLZbH^CD1A@Z z5H%Q#BYd}@G~sEDy82;2?l`IJ|AhT_#2G${6SiSDy9M3&C&xEZX-%YsB)Y@x|F2W@fs7 zF{?08NcLH2gZdtX&i}Rhfr2d8pb6?x@cwVQyv~k4M)y$ICnOE9iUA(59EoSR=ewf9 z!p{H6>k7J0IsIQ-lhwV z8mHbYEfdDjbjgK2)D)2izO~B*d&U|B-HS$hcF!kON_t#@Rg&v=QvcPo>%z!w z$K|)F_4p#sm_ju}!OHC3W!I&vclWjza#-uvdWpfG;C{>Amiqr`>Pi3Z#T|D775i^0 zFK^qvML_uG;=V|>^7*mGwR+~|{*K;hYsj-7T5~*f_y{_RHXc1*GqN*6+q>9dT82RP zT9Sn-5ghdBq65=n$NfIfXL5o5*%ep3#|DLkQ#(zPWHyGCk=V;U&DQv^_+K=b0ChqV*sm!d8#sVkgR@X$lfbf?pP&EFCrCpE_YJI}(N2zF*`F@b zV$hIDh>ZmXzD%Ggl}Ap0hseYTQIBrsGWc^Rwgw1;LIW(VkMjv(1G>z8GI%1H0nOl_uff71$uffqIwN`QdMVbfzv>m{T zkO?@V01+})L#BqpI!;3-A|fokES92uHNN9>5=bnu#%nN}l5pS3$INa#0sCW)n`2TT zGiF533!uNv)~a`QcYO!vEwJ@=-TWFc;W=Jtk8S~~j6{*3sN^v-ycJGA8rsP+e^a>y zQ^iiQoL)%##0)S1|6_N=Dg13lS(Pj9b11jSt*#~@<+F}0%<3yn1XTekaO3=|f1V!i zbGmwhf>8PdlAhQ`1x@}*e|ZzZ_{^%k&ckH<_K0AsW) z0p9Gs{yLD6bl4hj~gVY!89y3Py4aX=1RuAL< zSiRh(RVbM1r)wd{L>9T-!22iLgBW8sIP@)A^J!{nm3iDdAIw!CYt>l)({zExJvuf< zg>%E*SJ+dovmc%eG&8V_Clvmg8lP)~aPeBsdIQrcD9sFjm8#v{)gFiMbtRHeas{I$Co6B#i9tqH*@TFo;O2C%&M1yB(;Ypv1*~Z4?c6eft{j| zc!wq98?Dub8h2D2`SI?L~85S>fMs3U1^8k^LZeL zL{=lqO^Nx#_h2w@UV{*CkyF4?AhklU^LP2>nYA4pjB0zi&TDwA$oh|V2=IHSZsaH-`++GSt zHU636tIh>gx9-LCBe6?iTHxS@qNicOyo#}-xzXg})5l`Usk8lmP!Bf~4XE85#SJM*({_(NZM`gPvE>~fl$Bv+?7$FR z4lwvkh%MvA9lY+9 z%_?)zI}iFLm`U-6=v!#xTbZ+@R-a`S>CZ=A>xW$B3hrlbr}4L6^Dt4MstOY5ol7)A zzchy&upk_$eceaSe|!Vy>Sl3zld1;N?A)|k<;w0;*C%T}IPS%7uQ;9_dR*R~YmKZ# z=!JJ&1wQ#I?UyDeoXoPCU+s^K>|v z;D7{Nsesin!bM2! zDzi(gva1N^_$DoBS*UZJ_CJBx{Azk-^tS{E4J4rKPInYV4}>QrkvKX#XI50;fp8{H zz{^0x%fFH$6B$KWW&O4ASM6W24P7@7^SZXUbJPxr+)d7 zMDT7{NU#Yj0`^QI&-d`^x#>0flFpKeHf3n$YK>ld95}ej>fN(G>E5b6+^mTRIh+$J zH}7^PzI`!!-ePe&wai2HTrIltBO$$;y*UNrIAcUoqfwafB=IHgKr2_vh*0{DD^5+( zExj&A%gYvbPv)o7`+c0cO*Z%4Bfin=#F@?Q(}=8NJn56k8TJk<_OSJ{`?L?6%SSy` zQCfC0n=|XHTO4l|^@Z;94ohLK48^+cG}d}AEN>_1$+8w1PL>(o3g8AbYNd${AyWct zE38B1nFH@PiQ%sUhc=IS|D5G})MD~yLC?$1Hm)N+`qlXdFV_nhrsn&Ys$P^`DU%t0 z_V9h4hZ!Tij_w%3m9&;d|CZ+`W5ecWJZ+Duk&~xUVsfD?wMF~Qn$x`vqnlkly>2wD z<>1c~Zx!7cT0f}a!*k+>YmS& z4Wiv~Gf$KxXEr@F?2Z0m%V`lEEzg{6&qvO#^i3#*qOW|6+7eEiL@nFnQx{HZ(qn&b zCkmbniSpjfyOmQSUmdjn9!x%&UDj)39(jhZ+2mcr;#&$0OzttN|C1d^wVR{~J(w-ZsjIczejctPw4dBGGIe>XN-5>DA^px1z~T%y>c(BekCp!lL-;6oIh}Q5vGAexar(3Ss;G^W{&~#J`B7ViKK=dJ!;xUKv)2>l?8Bms zokg3N&_fmb3MqRE1WT!At%=+zNay}FuhkQB+Vgsio#(Yft<|O4$*d1oJ;%I1-?MU9 z>3~;QOG`CUoYxalvk>3soRXmSTfJJ8-0GSWdf6VqfQaS!FxWwyI*;Iguu)5G_a63> zgdre`s!?TYrKlA<9y5j_d;UJ~gi{W5+nDan8lh4zZ%!pF_u z)aa2q8pxcIc6J;<7#&?&I^6aZM|3_D>mOJ!mmgqGN_o+mY}35EJ-_l?;j(qA{NL`g zm(r1gy}YrvmQQ|VCgp;|zlCUryw&V6W^z{3R3tju_DTF;gn%GxenJ)#mR!Fq4RDN#^zc|-%> z1ij#G?rh3bqcpwtkzpU``ZLnk#@x0!q^+e@kgO{=-ucJMJh>}xF-=J6@{UpHO$sPG znSIVdgPi-tT9-N=;FDxYM~5Yu6V{R8;eBulV_trGac^d2we{&%H=LVibn=UmxOiS@ zfOam4W__2Yyzej^6%PZbb4Rk0--{zd0`!)%WF3O%bS zOM^@OH%r6mRy$vuyXJWS12G!>*t2oAaphT3U7Ee{o_%F^{lmgUuD^E4oZG?#+3!G* z`pH#FKicXlV3RJO;QCCd>GXGE=aIkx*;J0d&j~c?>a9M})6tE=j_iA|(}ukfrGz-L`(8q5qDr$uqg0>KJo0Dzm>8vsJ+di8gesnsK|!S7F1DeQYr zk@lP|{@%7?UC3{qsZ3*7Bi9GzuQq5Kqm%N6{=2%kT-1MlYez(4a+oJ1y4=SQujxK+ zX8rit@fAC!wYR{8>+n|NVLeQX*h@!mPsBZiQ0~0eU~HFGlt6a>i8Fs;URLOgNlB>q~^z#_sQ0ZPOO7 z@oAo~FqegRqbfS8v~K0Z-oJ+fo=}Fqn?2jhmI*OwH^D<`(Jt%zBaJOjia|Owz4fDt zB6V-OEZo0D9yk#r_dl0KPf6Ror=8eOKaagGzS*`#5JccV-`k~?cZ*Wv)9%v?K!QJX ze7D0Q3TIorZi^t@Bje_VjG6ZXTTAaHI@u02k#}xYniWbhV_vj+`CUq1oLBGGg-P1l z0CV~Z-|q$WlTOY|Hje~i3EtDR3g7ZG)p;(2+1q}DMis#*29amdgzHMUJg!_lnik?` z^oZwesBXi%q@ohxf$i|WLf73A+Lje?Zw1_iOFW)ZEf%ZEw+_7;6*pr|ZXVbPaZKRt z(=wgE@_Ko0<6-LABcaBpUy37$p3j;ew>p{WT-M3Vb~N7C5Y7r;V5&ZzW1*uU4)>ar zX8Eferwt_Yr4KtbX*H!suwV;)6Cy-^r|DwNJN4|5OgdedRox`Y5spcwh_dVU25*E& z4&|-$EY37$^N)y@cdeI?(Pl0f;Gi{c=QJ`_7E$3~DTTFK_&3w1LzeZ?8;eq>BVcPl z7Ts~GZR|?ZJyDHgOtdU*dn$bD9OC}<4WH-je>3P92vVFEHVd~0h1aewOV3e)ce8;Gt{jsm5e>&)xj;22{Ti{A zTgPq(9EF^rz^UnlaCqD)e3NNEwRNEvt%2_MZegN6wtpF+f+v%?OR zh(_>B6qDL-g1X!vPT8!%%WHQtzs=coR{N}5+9$7 zody)XSAERf(Z88b5BfS(12n$3#q{J%i+`YpRW+J++VS|Xv#WkshDPf|?qhExswQXb zUyjps8B#xhCgQ>8a7Kv;nYYxEjZ};mGNg8ju{Kho(D7_pKvaHXSos8emXr@u$_F6WPN~W941GrT?)O_Xl8y6Lo4B2XJ?0Y>j z64Z3UiO@Jfo-%eNZm;Z*Q;V5c0fmp%g0>IbkGyq%RJ_F_d{(#3`r&kE5gcVUPUp!# z$`2P4N*}!o()xt)i`IgAQQA8)gF?{(oF#lK9txb>v*kr8Gzu6OJ2*WN$=capLU{rN z8bWr8DqO6WSRhSzFFrSO4|QZ1qUbF_-7g^R~RY*Nxk067{{4({xs zgQrr@(oSo)AT~=16!ws2wWJ!zjb&coC_x1DZ z8yfnW?Q&GV&(=RM06*jKTZu9uujxRxz)2^xJLh4+x~9Txf<8Jr8W%@tes)06gVe`z5h5H$ zLkwM?-6>#X)tWkXfsVughO?1Ghk4b%T`07V!=U@q*RLNyKO;vv_!1a%;#swFHRxTh z@fZ7ERRs>Q6AZu1w^%?a)eH{hj}g`3@V*>3nL% z38f@m`in)%@smsH$LV|k#(@>(htapEcbnc==|Ef4$QvKD zlOB{Cu$P3HGOX(PppQ1(b{&~M3yDBB2{*7D@jBVPJFL{<_P0uQ7QaGQ3_Fxxm&C#A znX6C5&`SPW&=~F`{FHH#o7IH>l6>V;Al?EhHo=odk7}Nv@wSu2Qa_ex^_WZdZZ=ZT zsUa2JGx|$sp&_hfO}kvEC?y?Yb=h+TL*4P|wR*$)YbQy(IoMAJNxUIU2Guu?^=BgjD6Ho5Noe0P`J z@ays2PBYoumHZ0GP5q3k*Yl6TJ^WFA_THJL=uVqqvVhIvOUptR&fYbV7C3AN0h6#- zTT2)p$aZ=emi|Ts7)LmKxc`91^y|M5tJ0Je*WIGy4X(tLaTjY33`$h9yPf*Wy`)&e zodfAsnU&?ipDf;9g}+ToA{%#K;C~W$I8XG=Fq_C#*3~U0C1Ma1T%f_hxYJchBiKJ1 zsLO*+I+;S=Iw$XJ`OZ_iljQw-3WLEqm%yo7T!s7XKyPfoyX&v#J6l7Im zxy6~kusprQAVGA*9k;TwdPPO$CS9gummP)*mw;1SPYT zpKJ_K#14UXdxK!Gq#8C=J!&hXScRY(&P_oD5V5Ff39~d&L>B07*M~WoneAcj@xew_ zGu%WmBjw?hH>?SVTepQVO4t*55psErjVXV6iG0_^O)Y-Fr66LXU?Q^?Iak{(5C1Gt ztL?&rvrW?=F?>HIs9Emjr7{ zlL^$wC};K8%s%@V1(%*a5d_)dvI+&3N8dkn9)BW^55EPJ<=C)ZU`V+-f)ydY{eND7 zCA8Y0P0+u(yE+URGNz%W^#|Rc8k6=)vx(S!4S;H@YglL~`le=5;(6uWglWa6CXGB#uW{%!k?_KxP}bz_ zhnB7FZIw@--fL(ij$7aI7fwk-^*$y-TDZ8JtHOzga55VKt0M=4I{bsF>7UPenhA3g zZc*N~d=EE?E0ro1fq!Bd5m2b_^OF-fpN+R*x>9{xWW`?AWH|4F%cXpqrgIh;*L0nH zx(;iQkQHBGNXxy4^QqK_p$-Rkpo;lfujsMsDB5WJ8N-$R9HGbC_YmTP%GRe*6{_~E z63}!d#c5#UC`f3#;v~}IMz*cNiue-oy&Ea?V~x6F@n2%ngR0qJ>NoSgbVrs??qBtW zAGVtw^dgi{Yj=2zFECoiE$QB5V7TdUjqdLL{aSFoLmYx+D}XLZ`mSLcvOOXZ zX(lYEj^Ls6bH|ARLGe(eqIS5hmi2f$D_m!UWB+H5*{`R!N+R!)VoL=?nk)n&h~{x6 zZL!~xk$eB}ZiQp1oXF+FUhrHg8z|nasuibzShIDwA==xH4Lw-<=&E@9QX9I62!>4U zI*Qv;cxhZAsuYc*%E65>{SIh48+b364Abttmj0;jpo+ECm&el9*ldc-Wiv32T5Q^e zOXR(|BNe|D7LF9MPtS+1uIyD@%Bg=h*Qs6Sk0pnec+%!Io2c8$MdR!9Qsj9*XYo#h zw}KK9<-oOWwtOWt^SFw(1bsNyU_e;2<@$mrhkd)k9*=vy-F?l%I zpGSx;9fA@|*e)gJyzzufQ3=(|$b33Du;jD<9Lu5Kj@T7nTKcx;tn0fRn_BPtp!L13 z^umR|)p8b8Z`gMx5C0RGIy315r?b7WGxZCp^Dm}9hSNot6$GKc;szk=UsOajBa?ZP z!$2q&z{%=Be=m0BE9gf2E-n33C(WRkA_FYv6S)cwTJjci1$<9a)%&cbRT`Y9uw}b>>{Dsd8VnJsXi2zLfy~)2DTN}~IF>=pOkNlgl zDm%+9qM-NuvxcMAO#}^{f?K_Y+}H3W;qSuf`1t2|FG?X>^;;diR>XVY2+T1wwhKy)B!NFLDwZ$2E5(<`7sC@wSwI(sacqtn$M%cdC`4 zhumtlC)Su2-)tT(LZUE8(XD2IVpFB@y^NI~g)-(HsSz3>n;~eP0hcg9)8PW*LvUCa z9Sw~ih-;pBqAN2yGklB0_W%~G(~;|2e(lL0X~|RmTM|R*D3GeY2K|O+`fVosg|$G0_1IA= z0Z4JZOL>?2+YoCP%gr;J`;8w6W;s6Xr~C4((C&=rEs1XWl0Pnpua)X&I~Hyyf4v%Z z3|p>vxHn!4M9)!skBkh{>m`h561tjurCPZ2Q1jp?NIZ4IfhNk*vs(FWKPsrA@|RAu z^TF7wh-qReSE5;q{cMi!-7gueoSew0z%UtG0Y4)5sj!FK?;JKB%jpHhglUnhk^zE$ z3yQKjh}$z#SZ2>Kn6U(7?X^M@D(*fpN(5lN9wipPI+35fK+>Z)u-(tgdQPEGlVB*uMP>H4tnb0qa@bA?JHDk+G;e#0_ zoh2)CQ6~khz#wG~7CwJzoyr^k zdu|SWpzn1zPlooU28*{JW?sR=^X09))F`Qqqvv>Ra`HZbJQFilOyz|my;7p@l678j zaX4HEQecOef0-5QNpa1a1%6mUN8m8)~F*X7T&K(h-^V$U|FKu>f# zmmGtwDQ7H88jp;u5U~iCA{h7i`J0Hb%(+JNl&=3gXqAwg6J3e{57t^=L2;hoV@}-64s1MM zuT`dp!uEWPr(ErL?w{kZ>)Zh>g}|dcTB0XPO+ynL8j83A((Z=Gu%@4l(X-i;z9=^@ zZNX@y&pJAXSMs3coCA!TsKzL4B|8}zuRj!n$|_VvNjUDfgN60`BySZf)Ij~XE+au|pM0vf zKnuIS9nTY}g+L96j*I&@#Q+(L!f-6}gURz(|6>MMXv+^0w%HK9qDQn3$n^ z^YDGuv=z2OyI2M7l6}kndb{(GAlJDtI$ zK_Q->e(AzP9+WRRA+WFL7(z)~-DJZMLjo?}Z$Z1SgEOj3`NDo$`u?c(f0vS@cM2mU9J?QUGSq!y81~$S9^Eg6aW8&(Z~Yk? zs|3ck;-C*wNO)X9F2TUq5Zg-HQdZv(oWlTDe z3}4Ct@^=$peVh%{m&jy#9$9}dutYYXVV)y=8@(KU{mpNpP2cT>BDI~JhvJSMyu*=> z(&xiDZT`0_rj*jy#PC-Ff|w@kFSVV~2%EV>8a$r~=dA@3D!0NKPfsQedK<%A(n--2 ziCk|jU+LB*HL%yE)obNBd>r|P;2vklR6^Wx2&^AVrq|$Wl7-I`ThOd zl9$Ollp)&?9>WWshttXriyjN;YyBlA{jW*mlY}j;hF0f&smR=ZY^A$c@_3%J!$f0c zS2tsb;t!7$7oJ^ITy0NVAQqdcp+X%~lvg%s>rn{@p@)QRziqb8N27VWMeGyz`8N?$ ztP0%@skV?G0t#oLp01bry8PU~v`Q%UqXPt>dLgIl;@-h^?ZI4zv}%LB8=E~gCTb_| zo_K{*;qvfI-oMgFR5cfIOUn~QG5N0fU+htiZZvv%XE)yQ%}*tm?vTb0i2vO-7gD@( zUh39jvxne{A}30aL3^?s_81WBI%Q$Q1R*~FqQ*SGAkN@yJC$?L(|J+n*HqZFU@j8t zf^bxI+Uv7{wq<{*0{KShIpnF#yHxJ6<*xCyZ`hrZjSrCJxa;YSFK{kV;5A4-C~)pX zVP>-2-i7SbAt;mRBp+!DDuoz333j!slMe#U0WL^jFIh8CQTYIS3|(ug_iF(J1cZ0C zD{vOmg{Sk*dfD8K3Iz!>2OcaLd{UC$v^;H%_M0D`;glUIQ1(eetgYExmOW~$MR+Q+WkG-m_0_BIz!3<% z?{8>9zG!_8Ty&7M(c!H|JT1JYpc^k(cmOTcH&gb6*6itytzwJ%j2tWmim;(bxy&6@IF2+&Tg208{kp05mC5b zWQmNspBlsy>ulS+Hp_y4V?Gm=87Z zn|?m)DP*2~+Kzj;-hvlMCzV)tQ;R(9p?|90)$vR>g_owYNN-8F*SqBricy=^yk z5LjygCFoD~t%$!Y5gvSYdy<%r|1yqCq!1zUg4k{|tI=M9P0V}!#6GQYU03(+JM*Rj z0ri@S%t%`2(6f6inj6x}y9?Co!FoSFtn{ADDJ%{FqVNOtL4#}2A-95R6;E34Uz2Sq zUe^T=O|RqdBv#1<5fKqTX=@JxD3K6@$kEQX?UV;!jYQ%e#g@1F0;@FIbjD?_u+#<)t}4F zfr3v@BFpj9<2aUdWiBr}*xdYQo`s^nWf(k5FFJHAHC`@>B(;Ag60x8NITlGpc|pqZ zZdTal6~tiz;_^$E(9$EUOK|QS#V*`1}|;*n5`}P0(sX<~*2w$Fbotnw_V%ylJVY)19qk+nr8&8-<5H49@ z!udw(^=Ut$7NdnDE-t=wgf30p(~p^2>rdE~$6KjdXm!VaaK(?7#M@r>N6#1T^erwL zg+N}f=B`9BX>!oe&;ZyvozsBu;Nah&;H_--SR&wR2bG$}-g{FR3%!`v*etnt4_-LZ zm_@FLFz#22u@vV?mH7jN`B02B6m&a}NyD;f1l$v-J|o@?w6g?8J&0G9F~ghnqrAjG z62^iZ^6^$Pk!s*_B}@V80SZ@XFd9O&V1IMmyz0$$;p+mVG2ji916jRfUMmD`-9s>K zv7R<43Im3%2;Clvtb;;?!_d4FxlE#e{hFn-0d{vn59^{bFzD*DReI#wEdY(-vqQOp zLc=#EmGkyqZsJ)1B8S}oAvwN+yd}Do^oQX_y38i3e@OK>cGS?uqNfgsS$V| z_{pidY~JrhP4FnM(CGvOFui+wKjr6}|H)^{E6TxlThhlQV+8f!q``tvl(F&3AsO|a zyrSZIVa2fi;r!I>VHG+FcPt=tz<<(i6yqv^Rh+9w&8B^utOoe8S~H~N%adcpR9LGD zf4N9S+M#hjc2ZwrVj?h3mx8qV=EL4pfzNQs*O!=NGSYz-ev+8t^V8Ga;6#kEtu5?! zX&KuRi9>1uBvEkTm`N=`h5w3!DM&3N1Y-$e4XvQc2+&}6&2l&YkAMJyQL^x4Ee=(c zYx9r3Vfr+GlSxg@dGx~|A*}a(0$hUB?XbW;3ka_DZVe>^$9I_hQNnxf2ojz>$>i0Z z5^M&-v4frx)Tgq|p3`<&{%W!uAvbFZB~162AteP{tG9pjy#fa~ZQ9Q+6bbTW3`G^$ z+yM`)Te8CYb<_~W46{TpE(*0~q((c9z`S|R@8&eHIrDLn2xOHGq~9frxyaBf^$fMj z!`3%{gPxm|v2pGiIjfNCB|$%Ievhe%Vio-;`+R3C>-K8F#;MPqb$nX>(fp5};NBdQ zB|dNdIb>ZwTROuOg4h4-*L;0MZJpSOZ?hbnn;M_c_;D`SlJ@ zQ|FP>zKy6%F$0>BBQ8C1^)}1RWV3pTZqi(+)wFy2$!0>-GXEtwJ9MqS;FC(lZG^`)(Cmd_k@ibm)pWw07c!&gW>fnPyL$d*q$`)rx^E|3I zFD(%97WghgI#z-0-XEyMAchZK3`IiDFC|t`2Wv1f#19$ExHppOV5uPi=y3pW?AY>v zgIMdGgmP{C6k}J|YhrT-Ht^`Qv~Zv#1G&u_k|&?o4qSC$V9nTt<+R&y!3go(9#av{ zp!+Si$DN~*dr-Bpp<$`hzG~O51O_X+vCqH07n{yrRgoyegJcC|4;llV{(4Ud!vFv5 zJV>6GyvhwWRvJBbzmk+JIPWVb156F7B!D&!D$_(o*?DMv!@&^+xKvJ5*&ypB4x-RU z2*~cw|0&OYr~UhST^(n}`0(<_4T6g}mtcd6l7@&4K{KwYdHEC`4#2o&Ay#ulx4tbG zW4&Dc`z$0&8*~nWMFz{w9y&4xMIxj3?n?*T_syY3Hr?s+2L)D>dlopZZ}|B&#!jrQ zt&Mj^f0OaAjql=1Rk$^)VIJ_g5A8Lr z7$^QFFXFa-TPPyp1#@3=H$JAc$%Y8E{TW{Ekj5k4o%hB-3!&xUNX*FiMop6i+&$Dn zLjFx|IwQm0-p2849wPGY z;k90rv9l{%d$g>WTSWLUkQ@rSuht_dtEjA>R8^MIg6T(o8Ud!up9|MXO8 zxJodRTIJt-oF0H3aT-!XfVJOx{hgp7Y4T7vSX`WXCfVDvZYRMRdd&Fdl(|z@cJ}79 zz}w66)~?a^b2zIs(}*H@hsq1W@?F^%nf&|4EJ}wbctZ^Q%^)^kELoBC5Qi!ZPa}%~ zpJ;d$tE&{yA(QsPHf9F^_8I8-K}v@nl-@zrnty8+@P|x!sEX(-E^LLWj4la?dNi-H z8vI?v#SxU1i<33zO}m!Oqi3~nZKD$S2UPkuCBJ1SHiM2*~^%{8P^ z_2m z%A%X2LfM_v{rie(k^In<#=b5$_uqgfUYq&BpCwBz#ygmOyZhbY$|AQE!-Iou#&Vfp ze!`b8laarE$(QIdP0sK!?`mmkJJ>on;9Xu;ar4cTS}mx8Ry9UXBcIjz*B*^*{Pdj` z;7<*Jc+l-PylATayYN?f5cStCp>jZ@8Q4ny?1c02@IdfOs09~t+R{@}221rjfGZfR zH_B11Ks5QX#fsBf3ZxK#94^_zv0`Rq{01s;A%Gt1_n`BAnVXXnm69TFZ(mM&S{OeY z*=J^(zCGp8n8-dmh+7E@&jW~iY+~X*kn|UdcL31T&tJdh2w}O039jvHXBUsCXaVxk z2Y2_zxoF#;n`Nb+fXGr3?Y74YFF4kE=#P){F0e+O}Ak((r=jz7oZP3$Zvd z=Wp#2Ue_;X>FvReB5`ie%zmSq^=Wk&bn%#fT)%J7xB!gH#dl zF<{UXKpxmPs8t2Mvh}E6nw^#T`ZaD1!ZP6Gy608oECkkiYcV)@zD$jX*opSCvyCqi z=dF?NaorsEWB^H#2{As+F@Ud=>qb!|IcncqQM_I$UF7GMJpi#GW06f_m@?uGrUmV# zfAstgtbDp2cB`!JbS_m}tYX|RvU9KKU%!qmEwvSw=m2d1kPb-;4|k4^wgi?C&-n!% zM1v0>h(YR;OrWwP1hWd3vc}p-l|DsVRPwlAkR2}2ly_GZ)CI~Hu-Lk(JOfC?5<-wM zfH4=>6}lY5fJonwXJQC$`h8? zzsRJLJK9hqcPzrotE%!wf_a(U$F#Vl_`KxJbVSz) zoQ4y*^5i^e4pn#>sk#8MH&F;uUS5}z!%+M~j=g0v(ouMPCz|E2&5pJq8s`j&)z_dE zB8$-E{{k3XCA3`vH{#EYjf|DQ>g4QF73EPbeOhka3QKk>iDKW#Vm}Eu85~LX?^yl$ zii|Y*y{RdYm>3lp_lmG$TM6Jl@^W%q1ag8^RnBji2TB(#P%&}_-tkWG>IK_7L2pIy z=eymmzSwTa2zPanf_Y0>IX~FaW?AxkB47`(tq zx0mzuF@p#|0d|yQj~S+}rF8tL+q+SMUMIXK5*d}2rU;&L@QXhKE2f>8Koja;BaZXq zmGjlb*Pmp6K2_@k2;~h(RuY8vIwrooLaa*x4y+Wwz(_w!;%6Hrk1*3nn8Pb>d4g_g ze*N<0WUrtEp*wlD1u+wHw$aBhk1pz&qYh%fd8y7MqE9#Aq2uW{ZUIk+FUT4J=>n`l z%H7joa|cr&PjB}{MIYd1NH~D(vkIV+kALT=wd5ZB#PY zY#IE%wG6PmnqIgY8U9keBxb#uM`(_g6?#YQ)Z2q(Wki- zdiw{8bDW8D4K6kyLL{asDlJF)|GWU2B%lcSm?1FAU@$cQI%b5^E+six?q4^;+7g%` zay=`jdH%Zub6;~-7;S-4$?_*<3;QASPyW`CnT~tdzIUf1KdmjRC~( ztJUbJsNXv&{n+XD1rcB#=gDEs@;_!o$q`+JVUEyno~$w2Mty3Ao*zD9f+ zTY1`b$?I$haq-yq-eNvtU%sj(>T>sGmonHG)BMF!8l6ZaaH6NDkDjCn-ikLKdhM+l zSrWo9VqznsNVDT%1PD}qOS*Cz8ccnCW)}x@$w4TDrw$u3F9I>^(wKo!B59Lki5(_H zQ@{R|2`_d#^;#=G-(N_a9|vd5KTsMNt`yD9MScAQZ!RXDU3CJZ4q@?GacbDv?e}VE zX{&A=DC2eB3+Zqvx}F;BoKgF*L; z*ql)_wWkli)~L9?E1=`4y!&AK^pm%sDRt^?eYm|m9Q>G~9ahM#PCPceOCB6gUtze< zx9<4=9YX(TTi7_Yc`S8ua%~w2n?*^LSb-KLoF%OB-?@$rAcwXHM8R3=nRB{WM-Hg{ zzy<@>t~JSIP$Ro&OT{s4LcigU33ft6?G5KT$+;RKBG_DlD?3kIGL0Fr$CS6CzI z1Z_?9M7Wqo6~OkGDGM5&&6xMzjoCxNRP|annQIw&!#t_?5~G;0 z>xT>-#^;GTE3TRk{ck0jgBoGDJW#}3d6Dgn4aU1_O{9(kTaEwYZw^A;c%6FxQo>@-pX8{g#x#RBVC3ky4>-tUle&+r-hqHhn0>kLJ zWQYoVewa{p6^fZnugP42rh${Tp3-cAPdK;hxx zDb`=12s>$zd^Gjh-rnA~mPEM;HWqzKD04mp6Wlb3_^cO$dAlO?aQ-a~rlySG!-4f5 zE2K+YI`DR7+4JVN6ex=n^J117T=0mAcNvl%-?6>DFbya+%xAFqe%n}sO9X`t!?3CB zg^jZX!+$te>S}Tw3T>x20G>gX$w=BqudbdRJZ$W5A4N%4dZTCnt?-t1X0@OuA<-R% z-6ORbY~QG%-e0|!L)d8yYGE+(!yQbNvEKE!{5cnNq*;x^`DI#Vn)-*oNfJ9nRQXed zJVNp=yAnmBlw^2PAv}5yaYp4=?7s3QP1@+*7dn2*{mE!&WhW;mY}LQWw>1xejVt#l zn^fB&eaKiv7tyFhplFEJmLVIAj-~J!bfW{J0S~G@WP%nvmI}$dryzk3cl3A!ZuN~`H^{%wwRnjVf_&Ql z9uxqx^Z3_605Jjn%Sjb88ynFv`rA|H_n$stF9XnB6ZG;7Z^)C3&=hy5XW+%0yl#cj zJ&EKfY02ghSP84LJPx_U;s+?k+uGUyj0+sjvx-#r4xM$x=Ve4SZGInwUE8}5el#B7 zSG_b9vsh&xFh+?cx7GS|FV0B}c@a_%pex(-4Vm=n!cpgNz@ekkSU<)4CxRIA86sh? z@ayewG`o@jU5JzqUe(=TkfgGOZNWr7;nK>S#C*)7CN_l==%c>k=eAw>7g}-L6aY61 z%*X(vK@vfQ1?;`tP3O{S0?|9OrgSZu1+&TDAX1UR7D}|$?EW>cvkkr*%!2Cy2Tr_z z5i)9#D#0_CGS3xPWue{HAAb2jEy3KIn+OfZU)>ne-e6_QQ;Udd0t*BHp>W#3grZ|6 zWRyl|0o1y?n}(Kt9tADr#U})^SCy6AbvVOt&Tjn7YV`=GiH~pEVm#8ux3{)9?Kfmp zXbW_S#cO7Q{(z=77Z+FDYu`2Ee-wi$^PIA>sLTDCWD2kH0L~28^;f;L+}|{lb>GXF z1EyD*`|TOq;e|iwneYkkg4Qz(vQ4gX>2{_|Xk-Ix)ZhwA|J8tuL6SXaX6|8nNyrK| z2*9cV)VnO1Pra}VHG>pI;Q zN0Y@rPIXmx3LzN)Mt(H(E1lPh1mJAJcpfl)3l5McfGPrCzbA=izy5v>K1nmFv}<9u z$%GFMq=guvT`T_|O=lSvWfyK?Ku`op=?*2Nq#LABkd$ueF6kC2>F(|rx>G=;OBh1B zVd!o+o9~?S!?>&q=bhQHp0(~pl?6Av>{i^Su zp`fD+1}zb*t7Tuld>Q`-`xgbijDn`7kj+iWl#~cef|-$KC(Gu^oqqnA;97Q=-Ym6N zMY^PMpV#s*CugcEA{I`y5HM>(-`2GeN;yz8f+W_H0gIc(G*`dK{j`b}&6HhFr1+z0 z)*y|q#)(GMFEBSd`^Y6L{mEA*ftryq3^W;J?Rui6i+h2{%;Uplhtr^nSZ%Lz^Ux4U zb@g*a#qnz)Zs)z?xHzkQwg;nNONf-Dr4GKJ8|MEWKoG|TtpC-%w*E=pK?Pb`f6H^+ z+7GQfZ4-+}bm{Pm(Z!P25dnBL2~2DTmg_rv^cA}43suvp4rh6i0<$GTrh&D1em-)% z8#u-W`jXYp_}ZL}FwEIe)di_$f?HL(V_jkhV_Nu|hZaC3dLbDgGR5Me>5b#Nzlmx{ znRl=ghHtXcAQO$G8;=Q%+7Mn}%VI&xF>aClGS~s#srwV>>4PfosE5pxdt5@3y76!_ zDJ8k4c^03{N>|vn5=iWNF>AUoGU!0cdCuI$#rG~HxG$Lb$ARB{`K{Ik4&GnfPLWQV zjE?V7BLf3U2Zx~6KuJdh;wtU&o%@G_OP?uqj8?*~!VCB_=Wa2K3?tL94~O32ZFvjqzdJj1P||{tSkwbx9$=WS*(m@cYo3x z!*DJ7QfXZr3YFTck)v51|Q7p)X3@gC(GfjUPsZbIioBhGCnKk@Is ze=xo}BZ4Z(Y07s>;Nj7^rOU$%7AupT`$cM@?M3SkY)RJM_RM!Rt z!yoYF4LLp04vG)D9Y+Nd0UrgdeK@PS;XqUu6%)f9_JPchm_(=YM;zHrYYW zUY-%RipmBKzU}s33;=kg1t5r@QVqKNXa6)56n+71U8CCQ<u2I7b8n7raf~LpqM;=U4MXpON%Q?ue#xt!99j=3yFlP37!g6CFMWK zM;6f|rJ*^OooV-DsJlg}Y!O|eqTj>QoqKifZNY8_$K2jssm9mo3)yj)$&oWwn%0K#& zlEQGGJ~>acxUgL8J6f}q>n=3CglvsNE{!7>lcMK1!6sI5v$+-c-?A=BlafBd?5zcq z4^CiWdiu4-Ur!Ic)nI$vN*uw1$~ZDUu$p`0ThP%|>5{U>qPtKkWq94+?emTXqiXKo z?a>P-OW(ufplvTLg-e%~mQw%v3Z{i}Zt52OPQHgR$PPk!_(77!?$x8j zR5MyJA4i{k#;gSj`DsyPSztmzb@J%nwtX$$Lm(z;G=D2D_M|e)N{NH+^2<*TyqYws zs00zGsT}Q@UGr?_SlCGu|3RaF!;-hwspf#!7<(OUCuOJamai+@`sx3<%lKLb2YCUp zMk?sp7)@R_d!=3^nIMjX=0ybFMr!=tQJ_M?M9T4Z-CDcolNNrmP6U&Fe8}knWoBE| zf?A}xZT56M*wjY^PGyzh=O>Q}(j`YdLwKb&IH{60slhg<=3jzrT z9$N&!I{OXo;M;R9aL31jvz47XpUg%xzKV+JY@iXcA&y;cbD`Rkhj@2fZ>F}WEFS;g z)5aVI^-X@6W7(!KX)alQktz%{+LJ&V!v zhgK(#XPJ5I5dm?54b8*uJAzo_?bwTwP8Ot>P@y)@g>!c}Tl5?22?oQ}-yu(< zmE(wdNvYQa1Vs$fl$T;4KLtY2DT@M&QK6cM0pNZ$Avzhh7esc32az-v6wxU-x>54r zAg+@LrHJh}Z^8%&3rs$NT0hY!G-}PFH=7PHO)`)z3MOo zblg>os)s&8H#Re32IW0;E;WJn=qoDl%;;<|%cx=S7I-Vm0@E6NBz<6ePN32$DlM(d z>eb68bV49X8M%bWFf_MkXMme6kb}Y5vm4LW(4*?svrt0PU&iBN+0Vb=4gXo+*0WoT z%GF(5NsTs?AMd(@i_QYY&*G8KRJs=vTNfu&!H5%}Ou^%B1uDGIf~jQvqjnOj;d5{_ zWmK>HQ1gJwoRn?0f)c41`WCKmLgZ@>S}A8>a4@hN(sFV-O-@fMDOF1xdryhFln;gx zvV)tckjd}%1gU0s^w$}`finlZtl%h?yR)IKs=9eGG}V&f4sJ1Rl6p+V*2u`n6oP^a z3<%nTx_WCWMW?uUcwcK~UC+j);tdyV=20A$Eb6{C%*9_cx3iVzSB=*l>*?vqYiUt~ zau?v+2Bj79fWuVLegk7QFHDqZE`Yp`x5>f6w!;zg#Wn=Ge{fXQPaU z1k35N&By1Nzr(`N!A#KB?0!#GuB|wRzuh~WP*9GdZSLl!&p;dQt=64N3fxf2R4Aekb1$ob^h4dt`1cMQj^lx9>BWdvIauGaJGwk`ge zZk4PiUX%`ZRqlwsys0`_=K7QhL@_Y$5fLeGAOI$ou_Dfd>rF)&ghYKHNoih#cao)4f9c815n%}bl*vYiV&4qVYgfoD0>J^cogWd~nP$wkIR;c95`Nzy1h|7I&1X(VER- zn#KYe`L&-zz?YMAq2qJ+l8M_-3T`ONE@gXysyCxqEUDSR^IA>5==x$8YWoAI^9o8z zT|lL5ag`jzCImMlcR&`DwYGlyRN>a*Lay-L89-O;uZ}1!EE$SR-u2p4aOU${CwQg- zMmNBPFGCs@5n3;U)$~GvT9ZO$Z2XlQFp8f<91%SL4guv}pp~x(0@+_(Dd$#g8@Iba zOt!mNm)K(%KP)C`yZv~Utcxime@+mOkBcj&t}akj#R}4-p$ob@H2r|YSseD+Y5wWB zGVDHSs5nR_Jnl)gl66*mY_zboe(>l$q$eNG**SOp@E92Nc){zbamQoW(=|E!tG-A6 zXr{*Ybha7$-CWnlk%6^62Ah?~2c8fiN-CdcwmLKZT?^Ay>!H28>>@cbBrR@tXI2OD zK8fA7Y4T>fK27zbvy5~uMSG~mpn&Y|vN?kmch-TCGI;Y8FyhptIrxh;T(Qi#11pz* zQ89-Ij9(;)?Q(NRJ3Tbul~Sehc2mrfD4Fj)K}rh{WC)#G7JaC9!F^ zcC+uV4rlF-jFHEgH%z7QbFNLTdRa2eRJ*lCrw?2QU?MahhNZP#bFItN>Itd-5s#X- z{R&v1boAQC=e%Cj3AbRk=28xvt$*1c0TNa{sfsLF*%TFg|K>nYW5AwC^hVtr$ipCgf&zPU%H3Q9Ud3k{nhz{9Jk0r zNa#?1S`EV7+Z|U|DfjOcP6O9NW-}}q zHB|g`bT&fo-8e~9e0+Yg0?ic|OUz3v%J0-YsESqS!lw>z(zIl&WEApAkZQUaJA4sh ziA{4?cwI^bv8wRB`^y|#=8#@JQinHLUu3OznXlVX)UUS^U=ycSuagcUlI>)3jNqT% zkgP@pZSD=<0Mt({qS%`L-MgIP;t(}mw}43Dha`wr!wG1fJNZLwdo*gAv9jZK>gv8I zpjxKgADPN!-O%~BrbMmKW#t161sIHe>z0M>{VZ0A9Q&PaC9l-gP z3+6C4jQ|;!`Atx(EAGxlHF&qgFMThI%PyBHXQ8AN8OP+N`o7^@YW;d^5+0|)dhSo7 z{o4Fr*m<(1yBM?74E>E2;4lds{d#6oKX6fe`&$3WY%-#vs`_sFqqe2UI@c8U_tzy1 zB|wNQD6fxz{j^vuvnS!R3-d-#K8p(Z>+c{|g z4Vsp<@xTmI1w0z66}q3t1E~P~vQ!oF6@&u5sHj$f8blZ|tk|}w7w<6T1+Wl@goGOa z^lum`f5Msf&eIQ|7^_T`0TfNXA`>96!wOU`klpz!b>b9tt9zFqs9skdEnrhuI|yZC zVw>bD8ZCXCDw*hWW^yf2t{~yfG%K8^g|TJ;7(!H>=9`+uyIj*!LbF-qgUjS8!9vb0 z6d=X`DR$pkb|f{PQ~H`o+Qb)ljTH6tWR#Q`ojs_54S|OQv@#qP*4M{8DI}@HRkJb3 zXyFoQZ9?$($7-6IpTN*~4j;~a6wgVw?UChVAqksQB;V7xZp{R1}bbfN3PTD?nclT$MxdSyUecZ?<#Gv>GCs9Jkm&A2awmi#=7IGgI+_ zuMh0Q?}0@MxTonE8Q<{pKl$nu6%>{)GS+)viq9a^plf%3PMq(4*CI4){&=WI=jo17 zC~(7B`go4XeRqH`!qONsEAP|Qa5zkLQOZy6X@Sa?k1OCxRk+s_DPyBKU?4^Y6%{`u z`LnqdTX9ExT1u1b^KyIUgmJ=g;^WWoKPgdv`cNMSf`pqEm&|S>I$niu#NBd#(>+ay zOoFl}(2tUSIF`44!03=irWFuK3(lyyDniOi_tzUS-XzpG3k!W~t}m1*eD~5r%juQ5 z=J0&z2t|Vr%1c&eEy>XbZ^u(}XDqf+$AGHAYbPW9>vsPw&88m-6H_^9^CF41u zPlG2kJkVXe)f)RR2fxYwL_ulIu=1R+6DhJRZ_&D}{$!#T!+!QE`%Er4*K~7d$kPEg z-r|L)u(p|Quj91t(E45UtKpG1mS$vI3p|k$wgN-s%p{}qV%3BxE@a&8l@XfbqjLOu zg5N0Dq|o0oIARutb^PG9wGx+=BAr`WPgqJHyi)8Yj7#ocR{rDIzh6;Pbzt`W0!@I+ z9Me>|3h6DC$Zq0%0)OxzKAA(f1cnnqm&UM~W5sG0d++9&`Pz5XU*;86Yj?bkn%1hN;E ztZ6RymR8F9s66|r>fc6X3nB)M`^Ls)+hGPm{}xskoUU;@711~F2xeY9TvL$5lxG`a z2pqBHVZg~C4S4;lB4j2&WHrFVMiLthc$=So?c9O%+A-Vo)el55S#l6TCc(aT5z!^k zzSJMy!)0(N65oVx~P*Yh=#t`mpL z>V|vN5wcf`+4{tAHNszJ$KjXmp8df}nfaHkyk;c~4E9Ej0j?>0B%khD?0- zPWNl0YNhn4B5%Q#a~NQR6LzUoq{C{#!p{BX@A*Hf*W+yP3?5pRB1|4D#d5X-To#21 z_>Hv0P~CxQ#^9SIUr#wQRLxX!K+exEDhdXlI-!RvLp&zU-x-1)uB-jDZlLiIhwUai zh}`7*CoTyi!`j$Nx45{(_|&+FtTu^;|MO^WlUEHR8N-koQ^)ZheD>WGOFBkIqu;?; zAlLOCOhtf^t$%RPQ45jCO%~>r@-9oFvG4i}FB9fa*N5MBvQe8MG|e?3x3ZsCE)#l} z@X}laxwPM`tsXhpy%t$Qq#hUjC$N?xUs`}c40=yORo=#>>ML7wH08vSw z+l7WNB;{FVVpw3oUsaf;1kmFi5X_zT?tA|C|Gfan=DyAU_>^Lm`$tDjfqfD1WP_em zr>C2Mx_TctI21P}=aDG`&0VKFx&g7+{Z#y3D|ALltPP7YO9BwY>@`!d9dw=e&-b7w zlL@`KU^Cw^SZ~OAJM|>Vm@m^ry0Ul*xneIKk z#|2J}sXVLYw6`A=mRDTt2O7??2nh?ec?O?6uUuN#hJR#DCX4J-oRGK87Y3b8jg08@ zV11XB$)6>i(t)=53s}B?tp9kq6_uR4##+&AJ6)#H4Hj-(mR+#!0sy=ixH2EMo}vS@ zZhlG0Pa&_H_fD`cVAJOTuCsVFR>JRg&!^R7z>LWEwl&|TFq$#oAM*+?#08^t%L~$^ zV%usV7-|H@y-$_~uu^{n94=6L`E9U}vwq{|X>i-umsMQ+aYCjgE9(g^3;s<1$;Ke3 zHBQuA6ENLwj%JR6%?6js9b^bS0otNWyD0`VO*0&tfO#!A;D9(f+Ti7ysp!~;at}vJ zHBRB-FyYog_+b@$(#+N~uG?6awQ^zfxAXgH0l(=l-`{fMO?8~`?dHc@e1P=`JRYRK zX?5i6$kdZfjRrv;U=@q^Aq7N2Sw%_bDHEfih6fD!J>Wvv#NFx>@E{#S=SFz zKK|uQwFRFh1#~XSZA3ENst8cwUUg9Vf&hOn&l@V3<}$uCBd{Df~4`sJYH;N2-bOc&n;LV;;kn9hxo9q`}IWkHEgle)z0lT zXwH-BQF{1xVa&+$jmV|_j?7lri?euXX%uNo`1hrh_J;GGSGva5LRU~kjob41rQ7AK za4bGlyi~b%P-G#|#ct78F@1t?g0x$>k7XEa+2kY)-Gp+$O&0{hI82$=-Um*QWhXcqTl!AUCez;Tvvb znfz+QWykMSmihi2w9sV7ZUHWs_0ZkGxZ+C{c)N+Us3TT^w(`??HJ>0T;roU$i7{0Y zuQ0^CUz`|SL3-Wzww=rAN4Lbw%j2gisrnlRNvAZPH!lU82+LYA9x9Kv<4m6Wz27lW zzhW)B!YTj!{g&B3-+6z%y|!Be-X{rpG`>>@)u7*V`6qcHEsSL?S^o9bUxmOm08lO!{(f zHWpOW{ELwEiF}E%^;mNW*o)B1heyZiXr!2aSy46(T106YL}~TkA3pq4!mWcgs_b?_ zKHIjbb>u_utV)5k#+t#pF7cvdFp&H%0)& z7(3c;DmTLS64yyL5}4#iuG2=Hh1g@=ycbX1M^l9}XJ(?!o`4gu-Q5re9?;KI(7=85 z+QMMk;JJIidS(I44;kJOa>uyH$eMAJv?vd$yP<;NO70TMt5~ZzxH#X92@l5hMC|jM0lt$o?zl5qq?B7lXh;a<+qXy! zbHhM{$5n_)NcaOx0)ERLhiSZyU|CdHv@C1aU0-uoP%oFUwH|nR1{^4_nDlE8vUMNV z9W{?M(xy+5@u&Ot^9l=3fx@6we=`QFmiPZwdSuuwkQW|D1a86f9O6PQumJbLfNMt zwIv3)hu`_Q^!@d)CiIdF8P&ON)E+HSDdo5&9v4UNoFUsttx=#kaE@tF`s zeKl3H<*)pEC`I0_RTU{VnST^@*K&3aZA-ezJ$7?xSQ*16dzB$`tG&tgsO?%)kU;

B@)O*uQJf_c!WJ8+CuxDd+R{I2&xpjTJwAtnt?@FS|kSs1||MG1Y zAGO{0r83`Wl{J^DRDIhllEaAa068xDv4%&O$N_wD73X^Ea;; z9{3^|Y;R=k!qaw_A;P-Dsl*rTjlZQ9Y{`~)E>N$omwf(wPDa-!lqtBZY;-`wXt(2+ z*A)!;NBa;v9ms6Bf9UfYda&$^_j&%0tuFC{E+)?(b_^kr!5)m$OItmOl4nV3vRhgc zP5bgb`R6yOA8Yt9GU+5@g$!A7Ph))@R$bbDh1(99^guIBoH^e2cJli?s4aTkQuw3( z453MxcVwY-xq{8+!!LTZr|i$A5~Rf93lMDNn5}$$=a92JkJN}^yWYI@7@2-AQ(XBC zgR#~ir*V%BFOxr0eUtt4%tZHU0BfY}&LLq#qO%KIuH47Z_RbLX;R9=|2iMVz&pyRk z!P4n+M?5=xR!&-8fxKfcb%*Kb+tQ?q17(4#iGFA#!~mMJd^z*e5y8s)LB8!edh=vDf%7l208vy*HMRU7;PT^7CiT*A-C; zWV{6%?%T_K<$;04am|mN>nzS}KiK>kPw)*CGpF!1>}8*K<}lT*x67vS*ndfff%0j5 zgSKty>%ki^5R?(JnT2K|1b6m_~C;?*6Klao;_6Pk{tffOg6 z=GW~hUdf4_O@I-s_jse$ejIMQ{r!297gMr?&+fT|mo5v6N+3%Plc4Xr8x37uIa^zn zr*K^q-s7PD)y%lzCsGJg=NiyZR?G~?9@+UBQa2MQ)KzKOzX;=>BQG0mqVAqQ7qo?c z>wvAVukQ=6vT1Ur((4)0MVx?tL`3XwZE9*dv9JJ{O~5OQnU2P-%s1uD<+Nd#CW0VQ zkL5E9gD!Ssp)g$*Sg+>3#rgEBA3G9Z79!??ZUSU)spbX(Q=5nP_VyHY`%Nl1+p2cz zSQ^}5lk{LMe8r6k8BtSF!9~SmTm~E?ge>`+w}o@*tapbz9+x)UI^3G62weptS1(bm z7n)VvAYf3m=G=mNgi7~OUBU|(1=hjP{%Ii{m%s<}OJG_2m3Kr+!7stw5sea78a*GuEEwMP9ID1S9c89w zncKgYQ8HaI+bVvxLgzh2dbepxT&!LfL(c3TA1XTX92paiWM<1^9OrIOlWd{VcURTh z|CGyHqDFRwsbj-Mk6EdGnGajwN{I5+Mp>{pRAIFJapmFg?mPY>WKCU-W8??f&8@)M zDIiikyNrY<;;oi&K8yCc({;y zo%aZx)uR=P3+`Ur2!)bsUot1&9}baToiwOtxxV2^QmfnR?o1O4q1GisEt2UUgwP z&Cq?bw>s?A3|RMA%NlPqKS@g~P<@lQb$EoHzKtl&E#0UNLJyZiDSUA>X)St0yAUbB zc48W=`YlaBb-a9h-oj6&G}@{fos=j9XZjzqqCcAbVQozR%gPGq^ABA=5Wz9a)wb8; zQ~Ihsh!XZjJb&$%FiOAW??wKe(i@@wV}C7IgXZ@FP2=B=$IXBJ{nd1wK+Ky=4c5E+AHo*PcR8$F1o&vOIRpTnC@J#R|}^j_ZMZ z-o|O6%+w@zjZX<$49ItY2KyDBDkl}mY6{i>UMQnwMy{!+D?D&CtnM>yDyLn#3gilH z87+H)^OHBgHKKK6MILXaxrv9s9 zrG2D}M(>C#CL8AeYYY=J>$=JIqyl5la3y_dH4*hx8s-(G_i%g3dh?u&^fjvAhe|mq zoN>kXMX6`+Te-qs;L0%izk2mkgcksgI$1e5_Fh`sG%XVxq>dAzAR=J0C#rOGL~gv^ z2+d83BgD5k6#fe{dq&gs=Ea*YT_q@2D-8yxl8xIUNu;RHV)e1d7UA=LU6%XSF}ohw zC&j)*lmBJvV?Hk@%lMuEu_B^~!gHVdJ*)RMdgJ-qt4)6q;cY)1yNTg7o(L>j@nN(j z-)|0mX2(br%f6#!ez&8jg1D(DrphLWpH<82zm4%13eh|hxlZF-No6ElO?G>?E206Z zwy5~(M&b-tov>A<8zXXV53yXZX)r$#Zd=Q-vDYmnb;_&0(!1cAN}+{ZV@0XUQ#oi? zbU5e*7zYY?JLyf1ufra;uO%!=r%!$++&6-O4`Af82OOTv{Jxp;??0J2Yps6f2j}B` zzzZ@oZ#R}ev0EqqVQcqv$8osgOSIgaTtWh(FL$}9g`ZK6Bk^9MNyOyGGpN1$=+4}< zj-9W=5Tzjx>YU+?HGRLlIaHRp_&OC@35`|#VhX}s!9nHCq+@d0G=BiKlNdXs^f_CO zZpC!z2QyyQ>^|*^2l^@jE~d)Di<3#>%j>O7@{{>(nfCc|EM(SaXeT5)=W5buvg;n% z8w{no)T>Deqa`H!X0_22{^{0Q4dY(bsq1-08?7@}G4~xCoRo~hlWSj=UNaFqI|9)o zx(+_fBdh&?b!9p&3D8nC$7vmxDo_gYl=b!U67=rK1eb1#tA|P;d%o?Q0v(uzuF|1z zw7R4;uR8qegBs(-echvGEd(vht+R0O@TzSV_>3W%=2972OfslVWVyFFP7vKyQ9)nE zR`+2m_DO7t#>&bl5WJwE5UoWHf2ehPmkH8-thnx^H_#pb zc#J%quHD_>?IHe&EN)2R(ScJVykqSasN&I+CikRUU8#g8%Kd?B&uu;Xyc6rg10%J=rdW#lBhHOI*{*q`-cxxTVEb}`8TA{ zysv2uCRj~YRDE^W_GdSo&wH6wV(48+w)vJ2UDC+e4)tTfM$47a*Y@KniXdmG!@I+; z?X@SKn^y&j95p}o#F^p>sDnZ|Tzn0kUZ{kSSl6!D!HKQaue?sz`)T|2g%(#wmfH;%VkxIDRv+jsF?O8jp=T}CF9@~C`kKG>{@0BLC z{y_DH$Cs}0SZ;ar$N|N3e}LkL(;HDGxPN>UV<=kazgD$Y3Qn`XJ!d@H`5;Rw(L^ao zBs7y7J8z3wZ{t6Sdo*mB)rzw@^sKNsIvWew%7p~3W)tDClbBYrWUnFsE&RQQ4Q9k> zI?@Y0|2DphHCE;9Z&Z7p}C@!q>!4Dcm8VZK62?`1pME8oWrfG1n zhlOdi;SE`R9y$osCDnB5C!3X2>~*-;tf$tzSBw12!lzsR5S4#W;Y+6}^!H?KV=!^z z@82$9)Y>K|`MoqHsi=rWUtFBWm(EyH1||$o96=8cerpH>Mcck*VeelZDnUr)I;lfZ8dd9Jq02R7Mki2$Z#zFZf#sY&ck(Uv*U||HQX=1#M#=|sD6m5bb;TW&OAco zwotYmHb0*(F%E+32Opd?J|`4{*;lU>(-~CD6k^)z8XCY>TiiN&HI*!LPY1TKc)Bs(2-{xeN~{u2-KU2qvVeqB0IX^y1C%H9|EWbT>?ZOo+=?*u^ClVUhqH9|vu-SpEHSpz}nigfzG5wXygk z;yj*WYs0()D$w)>3IdY!W|hRW9d{uOY)?o~FpvkK8haiRkkyFzv}txRi0$M9^}>$s zL1<4*WHFhmN6Xz*^%NRN_yltvV$>DaU|QM)Pi5`$Hhw)grz{~pa4KcmBXjyj;->(M z$*yot4bXQ`$gVa%w|dX|C|3Nw=8Us3%Q2n%z z;T!WctB<;h1wnLL?a`b-Gwf}`!?qyJkF=L#UaqLNcWvzJv@MGC%DjaFFPOBpBV$Jf zf;Z#7eiHD%JE$T*=^bLAbC8^H{xypE+F!9N!iu@k2>sIg^7d{HM)$Bmf?;2{xX}kE zjuuH7?|rE2V_oe$D!I<83pc`2H=q_t`>&^y9p; zcIwtxm|21~pJ>j9_%}ZsIGk`MY+C&p9xdN4-Q7(S7B%76E;)O9EQxt4crpmL{C)|a zgjFl%WtbKtt*Prd%?BZ zer6)HQRQDk^;Z?gO(Nj8;5l2QAa7#org6;s%E;Hv8P7FUT-6;q8NF{}gRcH`D|(g- z_|IgJa-bt8nJr3w`Sh+>jM(kI$wk9`&9nOTA7uO3k+slGB%px2DiQChNI{0fdviOBUL7|TtNLk2b$lNf%IN0@l{u=>Gg_BdsvOz z+b#U2to!%mXNe9IZ`{8ZPmI;{RBh@b}G-~|HJAVS_$&Q=gk$tGMjV(h*WD@sbSEkaPRGR~d=R@D0AbwJW z7t4_qzAgdx_HZ~p@a0|v2dya24+81ij%FJ4NoGg3y*XacXF$WG-_}Qw7c_UaY zF@epSR&;+s>1-()vx3e>q10SNTI*K4t>ZPdq{2i=a^ZsRXbD1k6Z4A!e@3Ia{ z8%?o-ok;KTF9D(@JmfVk3;`cfHDEoURKWtDQ@6*rKCKFTsvsu~{3)?XNytAC%z24g z+uG90$`}_t4%@&vZf^uq$dxepnzR$sFe%mx?oif{Av|?5&p};bl(_643pm>wRs!zy-Zmu`LJ@Qh74=I%4!jTo;$}e-IU=0;ikFsfa~& zwI%M{a5+kd8`h=rh4phB4=hSv`Yb*oz5B%yT`>oKSnsNPTew2q-W?THj!yweBXe_R zkd0?@>0%T{q2r1_@ywUw*WOo|KFf1@SCkJAh-?L!-91b9s4hzn<|nk^g}kH<0}L&+E0Qf_TDWwc~zYM5I?3p*YklQQ3Xe!j`SyJP9-zFmNp-NT&bJsg6s zCK*xiAz5^9`^uG>U46GQ2i6zKA0uq%ui(=C-mrxx*qd&IGY*qbhY37$;2CKbB4qd( zR&sbeadUV)maDgNLw>fB^gd*=f1-Hk(^xGs0mQ6e{!W?9>Xr;c$e#Q0=G6OZjJ9h* z#$eC&OCH8rEWs_wcK04tGS_wZ4B^K}&nCOFS|+@uMDHHM*WN?&-X0iGjB{3cAECti ztC#H;8uFOFQdNAJ{o?bXBLEBjw)k)qu|dRAMeEu`p23kWrkJPIoG+@w8PczhA*4c|V2 z^qNLQ5(@`ClST7oLmNV*CmQqhH-a@d62hZxOS{ALBZy@d=koy;KYUd&i6aKGewmfJ z#N`8zm59>pI`TA)$|KJ{60*bZhh2lrR~Hq_rx;xy5M=rBO}uvY5QZa+3MWozbEENV z(k;8=HNJog6H{MtVv=0BmS@Q2?S1aQ$xk(^g6>7EE&fGRd39lbp`PBCw56c ze%(HIPu3CA3Q@=Xcvf~XIMTW;vJ3Jf4vvmYZiuB7Dz{cab1!n;^y;k$D>@#UO>R|< zoaO6&)vNNarY+Q&L47n93Z{4@e$*aCMgWEpJ^jnViI2bySFM3VN*ca&h~akl_auS~ zCI;3ra2i|ITDnQFnYF`)*CZ{)P1d1ZF5rvKjK2skucM~MEQ9JHcgv~5v}?7=4O!~wkbeIBd7$DMIw_y{=g(-bX=Il{RE?bTMK$nI#3641*Pcba zVJ+A1rkotM5#GY@yp97i%})GIPA{ZCeadTp$ig1Ce#0=nqq+a{mV&AoxF(*ez1cRw zQbp%j3$B7%hm@N80a~gg{O)H(`}L2>?m&^pohuEdBC@px6a)}wV{X6t8W?ERGcAD= zU67NL;|juXPoeqjY`^Q%E%vNk9TG+HDcskuyTOH9Oim7cD?{tpz=bv^GMmeGQCv#u z1rWF40!3<~Ndxf8sPLHei&LVivCmWJoJydRH~g8P({E=oIYCD#E|E8lup7d(PZp) z;?%jSk9`&`mQF%KhMep-ySbqa2P|A%3E);ljyl-h{;8DmqtVCQJ>W-)f^%uGrRm2=@g!rc-p~O2}5OSIQuI5Z!Rv5H{Zs18Nuk_S-0Z0 z1%bgVE$STJSrn2a)S>;Cv^_% zklC3(RBm2g_q%#q{un})lX^85P-mPq_^6F7)hWMm!8ij8@S(`h&mYjlsb|y7QaNh? zW*A_=i69r2Q&Ynq?(TOvU+k^@L+_dFZ!MQy`|Wv)^L|130o)6WgZyIiZ%gN!5`FJ* z61dqww1JL^sb}Y#lA4+nfTjUrwh&AERgSr!q@n8IUR`bj9#s}^j(jzuS^IWQ=+n>b zK_vhV2>{SA+)H)`slb7Q505+EX>zonX+r;Ia;Mg%)^WWLivl?h0w<*5;6^A;EFx0lenycPT?^y( z?=p#6dN*133@dy}yK(%?dAX*!EWStuJ{M3eahB%51RK1vWC(ebX1&?o!_C^|n8-Aj z28;=KWVZeoS(qmDjY=N3tmDUTb(L3=ECbIMb zJTxikaHRJcb$*)adW|Y6NJ;aML_}?yFzn;w#w%)TW3Q^{sPhDTjK%&a7h!t3Ied42 z=tEp#5G3uYU_0L!4ciOI7-{J(1Lg{k^WIERwMD=6!9ojnUhCYx2|)0;3Xlyyl^~!NLeE=yAU-Ec$iJP7Eo597u9`?MZpcGOFg` z;UTTzO2<*{Iy zoLE|l0{ zb&NH4sBWqy4`9!&3pesj$l`YfD!4kh3g|XB|KnsbEL+5{o3tJn-QWWSBa$Gu z1%yGKbUEX0rK`b)y1FO+l!gW&I5Fg6ql+FnEly5~TUflq*YjjuSXcaY<=$6NHo8SEDCjk*sp!K@AlSZVY(@AH42b*aFj;I8{ zK7u`CeO=(->%rrUeRe zeG52yTnEcZf0o(pD-7M}t2j?(j(f3}_U`Fww8^jhvrsqh{&ZHEZswZnWI)q$smyY- z#K@;>E1*i9CqWfH5`q5qpOV~98mW+%0k2g+wov>wgifnsTE^6+@M~&zgp#Vvq30(D z6w-83$}Onz`ABhYL5+aMfFQ5e4M+al{5^Lce6KbyS2n@Dr3T?V>(Xd&Z#}>91Toy7 zGwoh2``1&Ucc<=cPcBb`?&qz#ETF5xYQ9m?kHtdRjGyhczg4l;sZsIQ8ZHt9NK&}q zRTsEkk1eo9=`cGM4qN|_1m31}M;1_S_cF!0>ZK|j=;Y+l(&PP-fs{$=xz4V4=(c4v z#i$Mc*Uu^{3m@FBNkBlMp;@SVwHX|l3glT z4Jr&S>K)4$0&^WNwBL`D=_^}Dcp8yLH_Hz}f@!@8-e`Ex` zihMkF+#^kZ<>YFeFF>s(_-lDl(Q=Aqxj}azTFMlyiS@t+bQ-)xKsf!QG_pzFM|qct z`MoVjgYGzl`)fMZIIRX%&hr|;RB2B!$KFcf+R zLuXNfEp2SL&WkwxgH3+fGcNv7rO2G+*{9hcX2Gzx|HIgqF-yr zbXWoil3N=a^dData6~!(r>=$qR?h6dUyX`+`m&b1?#J3z7w=b z0jP%p&^w2k6n(-+aB<`9JCX4J&dz?+S%6<%%XPg!Pvodzc=xV*e+2IPuR6%S^h^a) z+ieb~o_i&9z)g@J?L5VWhorgkx_YoYKRa6ye#pdfph(#LG%x87RPT3lF2ocf1xf#3!zfh~HagW}=Pj4<={bXv~_iJr&ut=CG?oHjK z=E4Qg8;1XfrmFy|s_WWxcT1;$v>@GGl1is^cS=ilNOz-@ba!`2mwyV*Z9K*%LAZUA=<3Rgr#;SHsn zWGyIH@c2wEEQGF~&NG$<&pA@pVd5y!LUP0(ty;qc4IstN#*9%@{=CjA^>?;~-F7C^LC$QB$s-x|;aCmi6}A)R~T+DjnEMyZQGYG6Sw(VM}1kNTvm zi<%>@zT~g1hE0oyi#xTr_@mY5cihzZ`T5n&%{x}D5iUYWDXCH_qcMY~q~9`EwH$M( z=q>_kd6iLfV}nJbUzi&Wc zl9qeKnwa$LZbnpszQgMG`IR%**PGT#qI+hX|30HSz&8YD4LCw~2-eZ&jNtjA#6Wm0 za9CJafGTP_{GA>sX5rxB#~4ECC`lxwq_7cSUc(^(GKD!wJoP5dWYU_JQX@$ZN{C@n zn#CdevlUYLrKC5RTwo!}U|FOSKi2OcWPd~JxQV>hRda1k*ZkO^BWfm&mN|J(1ECdZ zSBB#l{G5iFicD0L(y*7KtJ`ds^3_|i+}tjaB<};&SACX-hBTlMJlvkr^75vU@VP?d zszFr4JYuOx8UHN2LB4)?y2?7~OW5A%?1F|UC@4?@6+uPe#yZIa|LvisMM>_j)V~++ zA2|>6-!!UeyCTrg(xg9sT0ue}LPj8t2{mR=j@jtmWru7%7FBGqK|@8|aBZ=$w&n=j z(o%zj;!XzH4v%*Z5V{1YUGr-om)6`GrQ!ulCV-aULQyQ;U!*W-=3>3E&?ii{!kGr0 z-^|i_RwJK9T$>Ln8bX*xR5+pWR)1Wet>qwaI_!y~LcO}m$ZKfm`*rH6d?tyN^I74} z%!Eo@cn)~dlKMV6Y&ZIK*ftOq&sa3GksonD)Z4Bi1tvd!zA7#)jR2OP3$?8a!pdT% zOlM^u&^MdZKGkKGxWx>VE(8ruFX_b6EX9ENLvU!R)q@>W31=6VjmvwS!}?H4Bq@Jk zKOkOytB^4W^wGcvG^ef(7ZfpI!W**M7An{c%J3#|&2H3T2KU8(4=<(eq%|BAV8Sf| zx1kF!etzriOK^JwfBn^8S-`!DJOu^NrABbLqv6R>=li>zM^&an1%3+2_irj&!}mrt zz=o_^9ZMcZyVcgsxky^ktau>eSH~1SvBT~S%*ggwrc0WXTO;j7=~iZS`9ngfdg%X}|%M_6WvA4J%?l z5uHnR`rQ#Wxrd}4XV`l3Nc6swJOk-uxV+rdl@W!m`pU3jbBf`VM z&f}Fv4$Ocxo9D*4B??M^jjApp5jO!Pd?3-h6xOXy z`3NQu_0!Myq>OJh`I4gj(BoWB`Xva51>KJ*3r`_h+K~tzyhk4)sc7P^t@E?wj>n+K$46!5KFMFQsF9=Os*N{Tj@qu3 zvo%kXGx4qb3dDl)G7fCsr|=!t@<=d)SGZ1PYGg&=9wv3>RFw^jS^atg6|1Y$8{O75 zV9M%QHnqEDcx^BjjY2(k5;6Pnn|;2`z}E~li26i*lt3#h%nGLHxFhjrZ64dgtaHL* zPhAvgJXBFn{mIvn%G%l*!5MGLLhUfN&VBz&wNtfNbXcefE8K+Vb_^$sh_H^1jx==* zL?6iG03Q`Y)(nJ4lSkUzoAbNc?IAr&a!&3-69UY0wNoi~Dr~D$ep8KGWi>hu-u80^ImVd`Zf* z@?pz#@SsvaOqP`C6#wIeT!r_1oFJ2Y@$2W9&eovvos* z2n$R2E^ZHiDO8z&-E;TU4_2JC3bpaEvF1qWQPlmWaAIBDDk~*kz^Cy7Iq+k8{pRKU z_rQ>DeVqvfv8)LoDF+}fkKO2LvlNA{t>evtdDvtSv z9^_>`rvv}N5k2i zn!k}8*?m>;TUAE6(=BJ>Gqf*3)R?j4G&IDFkGrO&p;;sW{t-1T-_ZDt5(uABO>n?z z)#~2W>b$g{ub67a&AA?oQ#&~P7Pq9V>@9l_idrH-Ob7!sC^ptt=H@^tZQZw$UXU;GoR* z_2y*Co0;0rx$8TWrvj{qgq{znE^P~d7!bqG;_~x@V5BE6@Q9JGYN-S?bcqpS@%+9U zf|`(M@~ad!aCX2r6qK0|v5=~2Df;<*xGC3y=z76@``DyxDP8Zqi79PjRvw}3YZa{b z?Djv+B68pgT>1S5kWkBi8_lZpD&Vy1rrNac(PY<7OSL(f+Gqhdz!nb>>WNl+>;;O) z{JsLxOUwFKbk+vLNxzhRVu}2-vk$3 zuwn+pR82mxiSYJjdr~?WPpJuKg17`K?^BY z!=Gz)u8>(-6O|eED3SA3t0lG+8zYS0V`DqlpKrKEToycZk?yQ+n*q&@^y?AZc8aH} zCQ*byhp+063y5->V$JHCb$7e-xNTqr9~=P{q(CR$JBa*?(f2dEk29otxr ztQtAH_X0E;;0xdZRwKZ=pv^GT^Vob9pQn4-GEdk=;K0%I=FRJ1K&zR~Wmi;L8PgYm z@4KKIwr5m;O2o+uE(43}E{J4LtT=QCTzbv>eS$ z;$iuFkNZ$Ma{&yd+RaT|4iYO$cJ_qPNYM5P1&U9bi@ z2P^M)+ua{0ixFpnDI7PH&R#6~B+~wH>wHCK-~M{Z!#Hb&uX8BzF@4dEU}#WC3$<{| zyN}~&(P)V8pFA}g$G4968Yo;#YN)iwet)W{tx)Fqyco}xqx<^YZ4egg%BJ4gHL!SY zp};_)+}slBS0K zG=~$&%(?Elr|ggCR<`m1{W+Ke5M`!|m>GIFc#yOhmOhoD@pNla=OhTM!qS}_9&YvF z>!a*vH?siacnTSaAfZ+z0AIGXwGB7pxgdwt2hrA{qz+iwj#VV)d(NKvZb-7Gmm9?l z$N|C=L{N|_zzGRIejHe+Keky~Rt(%;1-&+SA3m>%%|4GwTCMF~ZaDM)C<8lhpJU4S z+qUz5qBN@!G;7W@>^LPA()_izmfWY9uY>UR1zGTagU1g5n$Ap4cH*k*fE^l5UQFEc zt?x@R@D>6?N{W!LAT%^InQJmQcj(@}4F<-LAsHDN|D7#^ta+MngW%?YAg&N9>omUi zT0D9WG&S5hzTAHsn@Q`ghLe($6VlVAd|w79=5%fGVJ5F*q8-KQ^)n(V3k+exap9px zncwA=y2j8vAWw#Ln6j!1R^kU`Af;iBnRfCJFNOuyL;u8{Ub(7`^y8tKx4n^Zq&iFhifG2JJX?#ajs0KJbDcDE}zPry`_53|Rh57#|R3_qohl=Ry!IYZx!v!u-bfZ;fa9>dP3|NK~G*)->O**TW}0v?4rp>?#ZY| z=Iefe?&t97T%$Fmt}~qU6>uD$AfS~`5!MIEgWX*0zpxbw@>08l+&u+*Ef3+#U9S$N zBE0a_FyGsc4-F|}BtBHuk4^qmFC|%Y6;+gc!p>RRc8vO23`DA+X)>`P5%fy& z_lKle`m7*m&Z$sdh2Yl=;HLP51phz$ikZA%sfnk1$2fu@NED^*?m5DVxlv)nr`34I zPfqH$vO)}oXC=~szP`9rp46KgNsvT9bg`J9m@^^Y-SHZP(fW8X;&)>ub)%1Wwz}{9 zu6@iXF|#Q#KYezq_HqQN$@+hN3&dEmzR!KgYGSCMq$hCWrFz}qs)N6CE-FM$Gnp(+ zS|aU16XyImFzPCHs#Si2iySEoG5<^dOC$_D#1~y=mH4;QB-rJh{{9<#dp^GA1uMd; z*l$uv3H96|e~}q7_UKaiWso7zsoh_8l}Ut!QDmBuVS>lvIq5PCls@(bew~xC8!i|4CyD?&lPxHf_9;#p*;dK< z3)ImTmX;tl`ddK(HJA-vYcM<-Nlt!^*!}bx5cKJ+FD?!ND3!-y6Nc$|>iMS@tCl-y zXGSF{P+H1@o)-uflgb6fr@1jI?Hi!7FM zOCUQI1z70ll-4Rij?#Bj**90G%MCGR+1{Kmrj^5#W{@d{f{#U7T|HHTC@Hwm`sCKte9rLQP1d2)S;=PU*Tcq&O zMsk+Wgy$@m<)PlO42~5Rwr9!sL!|cg5wrVy{J6ibl_7uUdZGhSJu=MA{M0Mx$}P$( z8NduB-2!Fb>H;G>aHqX5usYD2gr}{f;kWlF>^BZonTuaTc(epLWfbmudYvlW5zU;i$4pceS8F;ilxfT!~?5{ zXVYT|BEO7{4}W=K#W^`RQShKAV#s{lM~y(`SuK9d1U!gnjZ5S zgo7rh9Tne#EMPm$aBRF~f-Hd8MqXW3|7w441k>m*^7LU>sA3wx7SqbuD-o!VSr z9EpFbNeJWlrDw-_rLe~v>E)<^IflyJRfhP)A5{KzONd+!MgOz_cnQv@_X_#Vkp^jA z3J~oeHK0rFZ%e3Yl3}Ii*kTwI?iuElKRb*eZI1X@Lqh{LVCMkn%f?2$gbQKxBn%~c zwv&&CCv||#SI5oT@e3cHa+jw!`fh6@*TH+znB>34v|t(sP$@B~K3;07MgG5cl^*O$ z%yQyf$SCImGa;1QvgI(zsv^+l*J_-xrzTn)Rq4`g+3s0R5l(>clL8}1$P=kGOCRp z(XuScEuV`)WXSuKWI!#Ukrr*&eiI1mIkR0ro0$5e)KEN#B3O!zQf+n@LBiTr61w&E zN+8k1k5P#8+l1vAqg*@Z(+vLfiQQCWY_Jk}CLxJf%{mztg#hbgp{C7z91^u0=9tm> z7rc3`bG5k$uX?BQRpW2fF_#*T#RI$w0xf6+=P{%aBtfJ&Ns#r4R&~@;6tu+!=1}0! zpmlP;lQU3v<66|zq|j%6P{>yMXNbeZuO~RJ#kz(7LqxB`fJ60T*FYHRTGX{GGwW)Y zMXx#KD8pL8C0j+<26X@bL2=Hp$>{@0wl#E&BDN74~OH2xZLIYXpJk2_rki@~=iUi%(vlZm#em?(fT?<_^oW;`lXPbsq z5M$E~Tz<}D!4DxFXI-ig8<}qc&VK+)+^?X@XIlnu)b*h9gr&X(|b+X5j zPn+Tc_Rw2|HY^NwjUFG+4;rt8d^=5SpH7p>ieSv2kIaOKAjizYf(iAu@MElv4mwu5 z!plm~Tlng??YUoR50p8JMR2!|VW*F~hDqM1Xh}T43MZoL+vD{{u?6q$dgFeEOvcAk z9n497PLez9l^W9a7pIg9MIS2*4{TCTSldT5oXo!L{UoY1XdXyGe7obQv5jlT0rKA7c>D*sau8 z+ufNd3ykr5Ki6AY!1V>!a0D;bA7UGR$UaYDvv**`ui0eAc z$(wd7A5f4asH>NPzc7ZOn9z~h!nie(yO)Jw^<2;6&0F}JvJdIE9}5#J-#Br3jjMP- znrv-tSzI?bRv#8r(=V{KqNROcRDwZJa4L>VPM3O$^MsX$PQ#ojR>&lT%`X?1vXTj& zs}8A+U8?WdI-hi@ma97E2IUgfcin)&Qb)J{T}l-eo5x#Y4$ih+E!Jib5?-|vOY?9p ziXjR#_Lo5KMsQPFRMd}CA5EjezoL)25JsKURX*!d<8|){@K-?JQ9o(QoUfm)%Tpj+ z0E`Y0IaQ<^5?UXmv{wepVr6M5O4&HZiC<=$QIgw0a9A@TXhmRBSy*K)8<^g!v>LrM zE}FFTrMraGMR#+hOtS`fk^N=yy^nb7H{Yy=eiv+|X|(-;Ry%m12_H;_K#?}=m@SAB zMPyD|w*3sd&98F)-o+{ji|>YTA_vZWm#C1@ry@Lx@6>E<@nfIM?CsI6%*%=cDfihs z{qgEhE6=svFh0Aj_F^ulk{!&;602=Jeua9E{Vb)1xR`fH6sueSz^v{H(vac@qw*Am9>5Mh+O-zWBI+GjK(8Ui) zl9y|Zx^mSyKYL~nBd~`3AtSr58L?Pwk4n0~1d8MHSQu(ElbIEw$2T4g8A?nL&?F+{ zt1OEyjnMXw8rWcjsDgDf@neu8_{Nzt8^Mo;zoXUU%D?nU?odnM7t=&UA}0x~UNmt9 z?FS*ns>4{Sf^u;R5OVd)ZedrQx;3FK>bf;@wi-HN0ISU!UQiph%hk`ZQF+qz60Bzj z$HwPid|ccAE?40+n)gZI;Na0sl^hs*y2fAqaQVq+UhV*HVaHJf=^g|eaQCv+*;|IX zgy03@O-(XArUG}Kysru)%d^t1RB?3$4a`?d^AQG|+C)bCr6nW(jq|AG zynzw{yr~<&we59ZdKH^k=*CjJ)2ATXZ@+|t1)+#K619Zsr;Pp!WR5x=EwF(;A9!XU z5heXx4kYh9K0V#d4IxG1sjR~b9H>0HWoq^9Gji!T5+5d9rNS&^;AAyETb-XDh+t_i z`TfIe?8{s`iC@`CexmsI3x0&s2w;pp`#voIGvEnX>Vs7}o69Q-n&(y%`WbNUZC!?l+Xx_(%D;ZDz z502)i#+Q&wIp5*3UG&Sni$;gze2B5^`%yE&;2a*|U7Ve%bz-~cckz*UhXG+qy0?N!~IO1GC$QWt z?Wiw)8%?0~pgGUg{856oDSSM8c`u)pvAZqa#*yU3B6au;LM19f#sBEh%k{^S3~Y13 zo_VfD12Pnq8p%*X{67DpOfz3*QS%d0?D*i|pS$y|<|Gmd?_Y>c*Td;uI`>V=;?*Qk z>c8tXSJj^K5~`~qq({clp0m^C)a8(AgWJsEGwFdB)70{sNIG;g5s_GH{`F(-^%3_~ z0lfP0TVb5zG#We<0C&6Ea9sJ-;96mo^Zpftfr5m4ctEYJJH#xbg@g^X363+CLwv)3 zC}Li2?0Mj6Yyr7{hj>mbnJNrUtsO#URWHOb}}H z#U|&FJDq$h*LD(WoL1tQU%rVj$ov8BOC^<+^YY^*xc7{H4o*(&U@?nuZa0_EOm^{f z>)8gfj8mYT+Kkk`0}rcOi<$4n(SXfQK?G-6{vQ!~Trt{35{Bbt#)OCiKF$4VM)l70 zhMhyu2N63M9sT45G0}{GL*I4LgiLO7<@xVtce@x9n;x>pe^k(E>KhM7ra#xc5-NSg zMJ|D1I2q&^Cm`tT@M;TR{t?vRfPTh=U0;K_O$y1-osmgG8PoOOVMOV^em*vgN*vi zJ3`{*Ji_2hb@>72eF%av+7ym^w(u0jIE@EPs~Gs|eOUQ}=tnE8{a_dy5OB@NSsOhv z@OJ>}*|d4(J6tdwDvHBU*`hIg@E{rtb_j`!xWjMEzC)>l#qChSdv$$9qDektiKMjb z%HQe42=*%fL~}a9egCh)I@fmuZ*%=?OcuUg&TbIC^lDYY`1*6w+y^Uj-J0O&2j9-2 zhPAxw``tY|tHO>pTr-?nwCjYVoi8feqHjMl_tqV_nhKs#>F76Q{!QeH^Sb;a3M zn5-*%I-1%$o-TLP+LV-2t|NI`wZ?X?6Fjroko$cs#!+6BHhCy}Ng|(F3v$_9Y2N1|&3_J~r7lebjs(3yf_T@3opfzUh5oRGjN zZboZDH>oj$rV~<}k4M@4OZS=LUMt@d1|gQB27=pi$X?@yJ&9~2KH(^=3Q(+rJ1y^D zdJDv{60nAVwc2wb_bcwp8-d5voqAwAl_#O&bH8nDZ2U*w1q+u%;*&GZKs4DFVCA$v z4v%nr_%H>Ul%6R#kX&`<&i|TTI2DA?R^$8@pr7*eDcw!G8Krk}rCl|lp?EK5W>KRt zo`TyR^AV!>vU12zj9BqqQFwHWEM)hkBDRW^q@}m|NrXs09^Tz5v&3ta#+V*zFt=FD zyw&@9`~d(%BVemXK&TMf z(z2wYqNuq!4R``pH0=~X( zwFF!Mu>Q{l4g=b@O*DVCTu8oT4uNmLMn+f?gc*`V-CT#(g_Yz<$6Q)G&3Zn#Uf_6AQdai&-(e*>{q3X} z`fJJ=usXuU#g!#`omn-0`2nA}=z!5L(ZDN78hAwkP6wcJ?zKxw2mx}Z6aZs@C+YAL zpYvX95n0{cYyji+(UdBjA~bbSbtV3Tjlq4cRzZ1`IF9`Ir?a_Ab2`D0=!crT~ zzL0f7L{(OrZhQ0@7x50I=nbI?xu<#x+%{!3Xn1dXd{-Q!WTII}hMixZFhZZVAItl~ zUx72-irjc&W;gYYsj3}%!s)bbSA}~qjKK~|NukoPV9!H4&Kf!E$-h`FfPe3*J>mrxSBCa&dT)ge{VlcU4vwPTM^a@v*zb0VB zR=bBR>kd-C{R_R5ocCy1W8|{Wb;X5`NKV4b!!s^pCRf5{9@Y+XTW}h!EBV?mm@T6# z_1qBUCQ?7jC}XnkFmI>5oHiWoVc2mm-=D+M=sf#lyK;n{#^@)SZ>EGTuF;Bk}I zsJxte=;@f#8Rns7$!R1{&RA(;)NvKC($^a(PtFw4G!(oKLe_MBk~>P8r+0Iyd5Yn> z>`B;BjulFWEq+OvwfjtEw`u)?ZdLgt7!ht3$7Kd-rgP5Uf_n&6u~vC^X~V$nZHNh5 zvs-gF{ng{JQ`%sD+gEyA&HO{>D2n@qt$CcTm>KHIHQ!(sWH4vJ?Y=urMk2aH90n#F;9rgo>JEj6-z+Y|z^lyzQ8a^!3FPHtdViweof4_x!6K8i{NjG|jG(w*6;>CZV zV1$~M`?KcjHz(C+91U$yKxj)J^20Q=zPlUuOs3Rqy+uD@##BTeM#HSL&R2cZh*;2v z0B`#n57Kn_pPPn_<$7wGa;H+&g|y!zwR*rlE%e%W?^w3R1^< z|2OZQB1)F2yf)-g4sH3M5LK)9Y-76$MW7K?+4q_zs|{(yRyh==dReBT|4s^vS?>KglKB;W60XxoNdgH~>Q+=uOVqPHn^ z{c%G0HA6z(v~$( z(9n7f%dA_>CP?>PKA6=$HhIYx5-laCYu#5a`Lt(jvO-4GW+Z4a^MBBw@h!W?wvQMS z-BwQoEh&D-{(0g#O-8zCzzd*P_b zMT)bAFV-W5f{H#hwdg-&O!-#LUWe3@Ph3_u{I3@=F)=j<$EWb?*j*9dx-A9^#&fT5 z1%(fL1ujgWytrg$Xw9plk{`$%|2xEe!Ok9OD6RW^vWqPEfc-JojbAc94ls;keAc{g zb@yG$MXf32K`0u$fweVC%PO-3|Mx`1Y%Q={Znm`LK&Y^&vMV>jqY-KtzD-3yP8`>3 z+hS&6xeXOksvjE~Iwz_a+TA>C4#k2jpC0l8xx{jp(@te+@^6PU8F-Ddwl|g8Nh=@PVMDC7)T8rd`lMgThfx@2DWHh~7G|Rqs{%h3~o4C9^K-sPC`^D^U zgj}AsCchn^5|Mfgz1G3jR-N!^ZlHbu1uO32hn$>T>i_n^Krk_7lmV(HWNc<;RNt2_ z16GVTZ+`F&fK|b3UqD~~`r6q{=KA^O>{`+XCzfGk<)p;KDuXU4Q1NKnKm(HuefPwW z_ww;g6|R2g*o2O3^M}Y2k_o377T<1@eW~;PpZubdR*P2~czM1TP?cF0-^N+)XEM2J z96cDD_(%+Y{zl6uJyTX->-y?`Bg~ zWx@$f*Gt{(uUS~gtK9L?Sr7&mYg5rVqa6F~p1Xr?SpVI$cRiK*3{@-fwfMFKYUKEC zeaxu-Dz>8@awR(s0lknz9m>#bwTQxEr-O!M|K z9x$5Pr)EBZYg0eWSEPImA>bHCvUYm-+NB8KM43_pQGH|cjuM;rkM|+;kGF})k7?WH#>*WHVfPzG{9mgR&x>L_ z4zg$)y+@|X8vngz9*z7nDU|&;E2MH;-D!RI<{s04mF=m3%;7L>h*~mQ>EUE+#ru>+ zI^~*_3pZqg|I<*v4Vpshp~Ltvf=SK}be5JAixBG2pQi`>jbzQW0fJ^nRHd4GCrg#e zKXENF6s8494S;P6Z})^g@N%@fa-EM;@-o`!D0_pR?7OH(MZa?`z19O2 z(j)G;!xNo>j1t~CAxCsvp(ulc^$Met1{(a$m;C=;#QErU*mQ;L>y9z`g|&W_Z4a7 zQYwWL_$-qs@S#3m+i~+E@jk;9>p|7a{XvfrF=lw&7rB+H(bhf*njs4rAq|ATFnG{v zJmC*rM(G&kiHvXx#6?o#ZiqeRTM-g*!%yzsynyJCr7MGrOROwCrhON?fLc|)a$i(*$InCrDRo6Ls*6%@-I#T3l0a68<-1INTldav?Y=MZipS&rV$B>2W$jJNg zA|Ei}B3>*_1Q|A*Ms93+O-)6-Gk;4ms+ElTCJ80msS~LRDg=U?McgYGA;0ghz6Xr- z-lppQvH3t;ylCsgOM9-Zx<(n1xN5zhawq?bdA~p1n^?RpUX_6Xfs9T{{?8Fhlf%+U z&{`&Fbu4#faCvq8@|gnZSW_MljM+*9)>mM zpjL)=E&JfF9n%jF4&LG-Q-*8|3ktuCG!T|yZzPdEDt{Z*)YQB}yPBR^rZT|=y2Je) z;$>^jGCT&OE$qWYz#&t~@K^Di)L^*PY|>>a67$ggj=^VRNeF76czWLFN<(XFMsji2 zf}%plvp*t~`IJCKR@79OO0Qb<8V8YL6e$q)m4JYN{KJRO&CFlKL$ZGV`FZhg5YmqP zmzoVqIa?P|fW?>yPZ1tnyd0WV-AcOU(_MHT1{F+gw7yM?SGrbYFn5s_rda9hyDoDK z;o3#(qO~WFZD-!X2l*^WMxh2-sefl@tWQsbLSxh1@Lym8fUVwuR;;F-van!u7T>&W zLyg_K;JydoXW<*P0wLr=ofSUVSnDa114;o8$j!itOzII$p$n%QA5bSA8BSyfi-{?2 zX<25d)GBXN6H*ksFR0DtP6qk6^OZ+N`nTC?#$iieMNYHSMb$8W;p5|f^*aOG@qaXzyw}18E zacj#F$=aef`sFU+!etA*hk!AxUE8m4?0m@R&D3u%)Tdb;XG7R>+*GpOIuJVLt=0c5 zZt&N}qw(LR>|@4IJVqJRCfUz<$OY|1ZWYa3#AvQG`A|XQv(N@(6p{Fn&h+jlH!j?5 z?prVY_H*)YSty?B&%nla60OIK7K)~SSl?|-UfYbAqRGIR8)hiY&U8Fu2o$=7(W)0T+gO~C3(}#@8ezn-Vz^=5+-uEB4vc2Nq zn$gZ5)9Q#*YQjG%>JN>Ag`~vj1_TY4P_Nv4RwwQo%RA1%zunlHpYV`JX*~}a7(IMR zN0M2{&i3__E>BS(-UxBV9PE<)-9AaUo0W>Occ_Ns_BS#^tNL|>NUH0L>#IXL za)R&E6Ee=O@h}a|*nk9o)s|wz|FW@r(o}yooX;}pv!v?fynHLe3UTSU|K$8u{rTFP zm!&aK+;^hKO_pN8l&Ro~4qHjwc-xctpF6W$Qg-(WM$SSfzV8EKx=^K|mk%>VV5|?& z;H-X~V6v~eKV?{KZ+m0r5d3S(oWiV2RJNFKBjsM>kn`eO$4dkYNd(>XA>kccFnUli zZuMD8KEf8AX^iccr&&~Dr<=u$Si?Zr`z!D2ETWg1AT)Jm)nLwFCk=ek&381UPZn{1 zY#5oke|sU#3qE0eP15U$9AmlYPCjSUzlE9iQoQSA7Fg;l60%J~@r^F`H9p24(s@4c z*7=SPg`;Y({UJN!mecODUeC(r%d~ZVkCGh`HzoP8cnLS8ngBwF`ZPyD1wTgJN4K6O6~mYUMI{B-D#RAy_y=?=YVW ztZO6F`=Q9PL)EQnQ;gK47>Zis>6W`pZXpJEi)^$vYsHEPP2HD`=H7hHQL@Ph9F_lk zR~EQH`S##F0kA!RfOO}II8#hg&P+rukI3w1&o^i2lJ*%X(dsH)*_pk&zC!Vg&=5XXv8HYLD+csm}x%Py~i1D zm}#yGtoHWzzUOA$+mKAkhM#2Nr&~WMZPU{JAd#N8e{zykZK91{_l1M7i>@)(&3akH z&W!~GtO4{9z+c0F6h|{jOiHQ%tU`b-qTZP%Vq9I$uM0w}KCTjff)D0pUPlvofh-NV zq~xj*k&^+wmP%UXr$B!O1X2P9Rh72^c;xEe${Yu(=UO2@lQTiJgMGe*wwoK5T4`e2 zNx;udK}T~&A)oUMx(Q_u4<6GR&Dk*>K*k4VFaS&A;6QkZ0a1TRIt!kx`ov}+jt2!D z9gxbmubasGWe2zD{%W4dy3>mq-QQGHFz>g~cI@_X0^ilY+uMc>uSuHmPHG-6VL`_r z&*N2)Hz1nCV%B!CGE5V)PT5(jRX$w>NYv-QRTVul__ldI%koRLUnD0w;TFRFlo)UU zR|Kj?L3K5jaJV0Mw@m+C?E`axnU$5%cp5qW4Dh%J`O3e=2F@syAoopGQ6Le3nX^Zx z4((R+6@{&>8DM<}*fYBhF)&ccPeaXW+BmDtE~Un<-;{K$kSiK7SPX( zFTOvCFGZ7W_lDwY-?{u{h$_KMDjO4))C@&)CWaUh5m`qZU-koS;&mo>o)Mcf?+^i@ zi1)u-`H9rvs!NRHEeO8*i8;e+7A^U#cPy^c&E9+;^ZA-i*mQf7{x=Z+g5 z_fOMj8fK^XYfnF)v^>eo*;N!3f^5kW3SugH6dv8i$h-*66LY+0m!SrkiB&~Ow`!9C zx>S5pse0uVTk_)tiBV$T$T9t>OiF*ntGc?8 zEx`*_CbSg+%bMn5ybXpt1J$f1sHe7zQCknNM~{|dfAt5I&#`TEu%R~ySI6pyDLj{a zdpSmAEzriRlv8Gzi9~oa>TDfo5 zO)M<`{zf$&n7b@H`~` zx)Yax!ml~+q49QZSv(x_)v;jr9bY@VeqXP?@im9d(x2w&seP@YOp*Hq-nYzJBoB9E z)riht%URwhGk3l2JhcrfUiXK#!N7!X+hQ$a;qBG(94Z@axkDbf}lBb1H)US)tDtJ&vp~Ayl`O1Q2IxKKM71a=S@17T9F|7Jg4n zwzZ~?xrk{ume-Px2ZvhA(L#mfc)7Pg6`8*s5R8~ylT;gyYbjxG&QrD>A47ZEQn7|w z3J+J{LuvBF(YPGOyzd{6HO+|lTT&d$E>NQ;HFr`;x)#GGTOoZf-nC0ZG3L|cFZj?j z!OW^1Q?Dm(RYc9cJTJ$PY96*YJuYLmzSJMfG#PG~CNZ1anmfVus@n7THkmYms`d-ONabn zunfPDBBXbdv(6lS+eeFBi~fWCv7Oh3r1l^R$Fk^DHn1p_$cv z@q}>L;l4Rtj$xXT{PKnJe8+uSWqP5;3_VjfQ(Qu#%I2Zhtac%0%+%;~tqn+mKo0Z( zh{+3$3Zr2bL<=dS%Tt3Cr7@m!QW~LQQ7ic%xz#1PzwP*&l%@M)03GFE1}^ z`WP{{J%k_d#?iei_97kZ4p2$Z{XXd={s6V+`E=*_&N7P1R#95o02oT>ZS6tYl{@W? z+?R3MIkZ%62K+(Ir=p@_OO;v#`GTONqjRL(s|52)tB<^I5C!u+m{8Wh zim&oA&&Afs(UCP(K1Du&M!pF{1^i3MzHOrseC*#k!$8gi@-op{R>xnHH)aKU??dNh zV3sNW!a`Pr2mM(CE8)t^N|%?R!fQb#?Xy_1MNl=qeE9;lNI4xH`cUJZPjoRK@0;h0 z?pJ2>9RAwq13c>0%1u)<)iN-2&lZoOM$JLFZi2F@<$l2^W;;PqaEf06^J+YWP0SJR zftRz~iF#bbO8Ju=g?!-X@bS7t)Tws{a{CL!laPC8@jRn}r7`*;Ly}|2nu4KW;HI$` zac9sBVs1_4#uz>emFjcQv;ig0P;%cy*v$3?>(4tCa}B!4n5|xk5i)hh9aKJ^{q_O( zYiho#Z$yo|4}k6L_QGn<rM@&3SxUH>7p1yW5L{#=aglfOzQ%XZZ#;-_J~DD$)v1AY+B#A3Uxk!B%8c z1iT43BO}hYnf>v=e%emX#@!+}^d=o<1g4F&Ud*$M8_VC;oj6%Zy~aX~Aq>&%}Jad=Pc1v&n&?wLE+u(J_D4^I6Tb1w!e4=% zN%kGKL2Ep8UK@6hX?}!iPA&`g9L~p70vn9zze?c(wl8oCb76nhU1TR3g*z!9N;$rx zH5CYusH&Kn3Csr^hcZai-EKUNnv$GCPelX z&ADho3aNj4qL8DsVj!nu5GuJ#`0|Vyg&uCR*mT;_o~!qbbXJz!NRj}Gi?h41Aq~0O zx6$Wbw-OOkp4vI+DJ?Y1A9m+`OxhR%DPr=yE}>ZdwJQ`hinRd#mT|Uxmmh`)x4BvH zXzo;&IvxyXFVff}0?rZWo}NG#S4<+KFL%OG-*fpF)=%T|%W$V4526jWjrNI${z0zW z?)1=Cmn5-!bDwEj>EEC49n((4;*rd3Y1e!HmCmLj%AYXk%t(|G%RIw&x3rWQI8Lf4 zzrKqvfGd(1%Kh~oUuEpWq2l*o!pEEWDq6u?{9gLy@eIL)e!PvfPf*79Mjr$4Z-v6bFm7ANc?)3DOmV@K_)RZ!i+#n*OU;2$+JWIIMPSccsA2Wp}2kMl$IW@4@ z-aEynL@Zh?mU%Ok5VopR|9@niWl$E-8m(ziI;5maknZkokPZRqZlpVvmK2bdlo-Z>;sKcfV)-jKiE2G+fwMqB`R>1)%ktSnNR z7k6M<)0>st>$sZzRm%RMrdRt6d!TjdTFvuwF){xtz3Zo9VJde)>~Qe`qpJk&(w)<5 z7whwD%P4bSp)XEORr~b-tC$Iv)?lg-gvV+M0TmGy5fT3#cY9}tm4$_DOCqp5j8bH2 zeccdzKY%igiv(xQk-G2MGb5*6LuD!QwCZ(6?!?ACrWx)-?CB|W@bwcFr`Ck8! zNbF>ph>n}ZK#vr7qg@`7O-()Ik6NpO$s5R}{OlGKe=M|V|<7PJXLVCIWjVeBnt)0fdTe+&UZ_md4D{dKOLl!reEcIhp zd~(J6vT^&1a)Z#?cx+H(XX)GufFa--P>_OXGIa{_3>bjMu?5O);H2sOwRSBC>2JPO*vmBHk@Q zIdaa?se=1oUeWx3qJo;$#j=Vb4%*T4coaHABg(NL^vZBZbYcSzd`|mjKq-;EOGhGf z`Kf9BtyorcH6PS~2B&sAHk9X$-vwKOckh=24k=A2&R?{T8HRiqdm0Zv(lF7u#x@|5 zRiOTaM579;SC$V~yyswRU&4TlN*eOt5eO>c6+YTvbLPS7`n&x(<_t6J+V;Fe*&Hk2 z*Amnw^qMXzikquGoZw&^vdZS?n7pI?1Up2Sfg)j36YQ!Kj2^!pZI)i$E*`(Kud#b* zrME)K{;i4HWTsmxS|`usjb$ig%XU_R-%%~OlM~PhR`Kw%w`$di!k3;14mZu`JKolkEK(#V| z>r-PsG~}$K^aVO+A4@Ln@N_zZ{?^Ooa{aQc8BvKJvxNv2{$bFd76s(}g z|0*@lcM{qlBIeZ8BozEGOi4+7ld2J5bb-z2TF%%nTsDFJ2iuDDV+?_riO!u9Jz6P; zU=4Hk?1!o{uOXp@fYrpW(^D*J6(@W*t-+N?MCe2;HShhFo7xRddGX0(s3RL2d4T?z zfm)g8i};;mx@Du}k(QivI+T#UFEP+YCY_&kXS;pL`htO#*tx^lcK>4vtG$L%WP5kl ze6OP4IJ=@E7BKV9LB)G;5=X`{MG-n@8J%D+zmkMdaWr{&dHu$g(_L8_P9rFUK!Diuu)+_b(VF8uAp7K3RE+1xX$s_h@-UD+ z)F`RXV5H7>d7&Yu-N{zVRdheG>_(#gRb%-BT8@kI8B9SK5h+(AkmqoSRY-j3K7UN zX@EJLI%X~z#T5Fet^oiUeSKjtFF-t0yr}5u*%U9D78|?fAP;z1=C-z`_V!BbZ#!lm zx-+_Q98j{mj?T{*0P&L!8xcrqz`Z67ivjKM@UU^3(5d0>$!$zXOq}1?sQsM)WID%P zV?x>k1Rv1K=QU$M;oV#WTo$YrMzTe>47Kjll;>>k(r|Hb)QFsqP-%zIMD zc$|<9H6HSecH2DWpz;TNb13)i%B(wp^MMo zdqEq6z0oL2ryoyv`9r_$_tDzCZ?T_oU9nXfZ&=fO-`%7oy>dO9GX$e?6@~h6NGA;_XR29c;n3|BSq4K+ji+r z->ooJXAOVuFDH&c9|s!6c)`Eo8WQ#wsHR_*Za$(e-OMGc?vPA1%}$6{^G`0iPfBEpZ7{A6suo6FCLHoEolRw%AhaWI#3rS3&(W}X8Dz*h}s093mK-HIEaXbua zyJa|d*6irM`0)*Yv6pmM4!VZn6W4VvH{au!(b8>v>_zwwg!c==lgS7$-qBwoWJ%f^ zVtrd1ev0D|il^vZ#t5u0DP!+tR*pdCa6vNsOMU+-^Zra9f2s7yYa0%&ZaL z(r?3AMv-?Vnf4x=64hEcGM2XhD1tLwkr|Fy3o z?Vdnuu!%J>#@-pbohFq(;A*1LShFSvIn6CYhd@zF1@2_{P=H4T!!Lq!G`z zr4IrT%XC=Kx~{Z`{h|69^na4l>fRFZB992**y_Cbsa)=zf9N)R8lKT{W|hhJwv-ER zouJ%RkiZufl7Y{+<*hdrdEnu_hn!H+diQP2V&5^l$O$A|2U5`RP)?O8r)ehV)L;7m z2#qU(_Ev+^L|N@UB{)(=_wtHFf2OtX*MJPSs4c1SXT39b<-MWRmK5zyF7^{Cls%PJ}^GKQbwI{IIt6g~;gp z69vQ*C1n?ReU1*gdX5M^wo-kLgRqD>wapPB7Z0y=rKb7OVfdql76Xa-NM+bc7?~GMPgng{Zj3pE4=}-QVcjP#J2o}=y zA>v(jpU9)rat>)2zu%0E(>~;AG1J0xfMV zx$UtpvTL$=4LaOyGE9?%s?|Mzi{b~7Rp;d7AfX^lOiypYc8mSa%{AaiEi5Yf6wG0X zjxKYXmXVRT#NkGk?^0D3 zHMsL8`rXg_Kgc2yTK4XhA*wc;uD8jAmSB5b!fMwLY@a)k^@#M5rmbAjF)&aG2&AJ5 z-2Oel&&$n?NlTMcjgL8|V$`G-F)g0{zHEDAFA=_44>%R&OpvCyNF7NhqXG{@8(iI^ zBqiPO{HuC8I51)esP~xfF7Fto0s+vgBB!#dihC!`3BW;lf&E7BCg8UI&mXz(<1w<36f-(29|juwaLjvzI@Wt{ zPp^z^>ksO5)qLQevas_qym%>hZlQ)HCK%km;}n&x*TRpODIcJP6mVgvyyfEV+|1t? z5t=wRb1S~_D1Djs);;xtN1yLyBJV=zL4!mI-afyWeG$H-=e)RmN;*Hx`qEJ{Nv(B8 z%fRnis+24*`Q^8U<4t!)<^Ho;v-7ru`ehG>_y4p2Tlc$)RXMPKJg(KR^{yxc_0FwC z;!K^^Hu9Z%{%n%(Gd#}tZM1s(O@6{Uut2lUR`dIReGE_(NZVsX1r=&yAKF;ly7EOnlt`yG>{~1|cFY)@kna0_y zXdrHON$xiN>YN;>1yY4mzX~JTRbMCH%M|isgHcd<5YpSk<$+2{w3~ll8>0O@9$@mz z5X|2MBNAO&lS3}(kr3E=zG*BCE>090`#2tjQ?Ik-R zX4F{p!B`4^ZIwJQ47ffXK(LyFN1|Y=bk9ywFy-ZBwJp{OATZf>$%D6jm7*=Ly2sk z5bZ7fll4fJs!o)ZnLcukM#cW}ikXkC%fMGKke?sP9D+&4lSn^4kDzYT4c znetndXbDsd9HdnEr%lOld@EZj8t&jg+npN0a~y#K>Em>iYE*imKefvle=JM5ceyh@ zcrHEHcZ&Cu^8!55oCc$q>*4q{FceK+9<(IkM#nbl4zArW-=6g7gfz`O7*Je-_^3fnI*65hhf>Voz~D?af6?-Xj* z<6&UY>WFhpP{>RtKfWn7jqb7593*Q3r1seOxG*4@MOU$r(kGKaF*Y2`8?#8`O#r}4 zT*#>Q&pz#mM!WbZ1K$S()pY_;jcZn!$_qW*s~F31qnPtbKh0|}PQ>HE0%y2C1-6r2E`eYOtO^p_y2T@qcL3tUXvCw*&IRUy7nN0&m71+y4Or6T>AYJaD|PZ2zR%p@IE>GE`De>9#ozK3Yn_}H z2H6CB;bQ+?dOZu8Pv*%J@VUiI0;yC!D~a!CCE>yWbGGvl-V-L5eO2H9=u?&?>`pfQ z>YyZiS2i}L)Ox#)2msv!%)RkGVCuE+tCY&&EdeTmi=9z;tW5XKC3J~nT#QP#l~A1* zo>9d0B5o&4tPEcwA#KQ1BSI;XM$ReBd*^;1K_)E(ulgUNS|waa>@+*YusILLCX6bg znXFwxhMySV-+#sA#p3G1{tYwkKcaEr6^-CPxXjLSYu%rHU_f|zo3V$KZli)|IypHm zY^aSNtE|i=DuSC}@)4DdQ@%bP8e&Ptq9OlD*;Il`zE*4Xc(bucq;e>JsUw;2XuYgf21ulTLfmI>#_lD zf{?Ru`1X7+9T$*S*={LLN$n==G!Nfdd)FKraS8A##uKTJXs^i|b00u-Ga2uXJPPH8 zs!#j9IDUz;s1gU#Fe6|=Vmgv0J^YN{FZ^+|8&*nD(d^;+2n5FMHGZ$r^|rK`rU)JV z_D$p}1k3`nb8^7PCC)L++oJL&a)r5|-H{#^%Kr+&h9m`P4r5D^p|*?}oP0ilg4Swa z9QE{oEo0}$khZxP)6V=HFUS1t-IaTNp zK&l){-5#h1ND+}k|LB1OL zh{rt(O%czzr)%=1`g>Xhk1bjsSBVZ+vT#+HVE|;bL}P<@5i@4PcL$Q>z)bD}@=_9W zl>LK59P{+gT(fE#jDNG*zx(v~@W6>GoqHj4msyrcJ|KULF0cNMaL?MBSf$A*BYHQ7 zgP<@nV5DDs>Y0*|ksik~XciIE$%2pi5|8tc zY$0AMYy{^^p^%~9tk|2GtLqycL6%VGX7=#oC~e#{YIAcLX-Xc3sNG~-vYhPP0B;Fh z0!wSd%mx|*oXa&KV~2l2*DAHcbac71$Rnc5^WUFnXfPra`uZ}<+A{p>x%#`|m}Zs( zhb@0woCrYtpu@&@J%*tIS}ZH~N+ukrz{*h8C@+2YH8FkffkikL4fhA38_XRn76FC6 zTimnxdA6yUiLI{!#4NbCpE_X)3#{HvEf0}BB6m&G{TtQqf4Fh|*X}P&ryhO?AFrvDHptXT6|m-e3qYV$qReQVF9q(2>YSdmtTIe*B_9jsX*P4o~M;ap`hxHGZTos8w6u(rlL zHCrchWMx@Ip;5&p*MsnXe$aqVwt(J!vp)3#r5o978y})!7WeD z7;&02FUyA68f^A}sO>UI@&iWFts%j&--$hFJaGpvEpgM5zHxi$3Mu++Ax?H4k)M%m zE+bQ=Mn34d2O>W4oNV)gyY;gXHu&R`TXPkJzzzUhM8FZoNNJem%0e?_h?7 zy+6MV*v@RVwctr{a&r9E%KIZa>K-9vb;`3-`bD>#=;8fj=Fa{VtofBe>3IW2m}UEp zkZx-nRNiO9y6Au&nZJjKTxMFVg-2*4iiXt**X=0LNA5W*B=`n01w3r( zk>g|jhuS+cNpf!rDX0*I=vjEamrJphAWtLJUNVolj6foIa>GE=AI<7fv6hnUTt=V2x?ptreiX$L3@v*7)~~2J@kvsR=hVWjDWd$y9NchX*`GhY)b8dTLfgwQowXjd6Z^m4!XP317^T zYuNGgTJhkiKo5sV{V?79ac;xFexj07eY7aQ;pb6W!ORe+HUGvdJex|5GGH6P9pQzY zlqAK#NA)$|03juiXZ^n?c2C0W^10%@0u)L|VR46a*{^~=UM;_3Rg&^^sfOGS2VRNL zN3GOS)g~4Fq+(>ZPy=xZ1az-Y@xNx}HT~2-EX4>pMkdW4WBO1iy@&|k!AZ+0kW;O6 z%i|OdNdvKKC$HpM;!?rK9upcm!XgXYv!hh?Pn>Om9q;*mw1W{Rri|iXt z6B6wKjn^P{N+$!*fD+{6lX=QIDmi;zi3d}^^DCWZ722YZm0%~BAb;n`-~VGvfY5r@ zMP@hHY1q9IJN|PiuqXPqEWFmdPunD_J>hHybzUJx{#JS8_Hl%-n z5(xjRj#rlj6F)!=S7OAQwlU?n_5f`T?QiG^3)Or@5&BP?L^om>mxySFK$6dwO!EPx zM-;soyt>wqaYs!6@1h_4oi}3oju(s85-`XB!JN#r^q|%ZEhZum$l#n_)x(0MmQ^2;Ak(FfyrTXKJ;CsH2U%CUjCTBc}iHVK?qILn|zC9t0+510t zTSCnKyVyKnr56;`AFx&Tc@7JQkkLG}ItFQ(l*-D=DJOZNqk{LIX;V2X5VGviAO z9_2PsGIN2gc$I+HXPPW$yzk+pjTl^mgbuLanCaKC318G(r1`hq2n&=Wj_Bh_{~-+u znCMpZ;aEc$hpO@C(nsyRJ5QLI&f+tWHiAi&gNc-7*?qu}QdcjfPEk zk4&U;GPC*(a$6QIWLw+r##?nK9rxOog>p5Nm}1VnX}B4aMhJPss^@VNyM?LOD$^&z z!!70-)o}Q9tg+>osiJK>g0H5&Z_zAALc$_?2>Cza^9rD@+AewgCFNoE!x||1Yrm0V)`n(=ID?YCknv zYn)w&@6kz&`p0T>a`Mkmb~P7VTAIfv4Q&9TSD{Hq#3YCMHXKEn{dVUhxfL{almQQRJ9UnQa4x<>mOYyA`_aQ^l0a;MEk#7nH;fg-HUP-|bQ#CTsqL)j3IbNA zr+;fhpz{41$_@z$68{iK6R^Mk#K!4~O*zz0<2*{*ZzVWBO-G#n=a3?8K5TPH5;R|Hhb_Yh(%uax}COFL^{UD;jo= z1TGZ<=5gjBxeQ_bE4?+?o6)T%&s0_aYTbWgd3C+G?a6vVh zXU0xBs2ZQ1*$fiju^qa;G%wgzyy_tex<&rbgd{4h4K@HjLY1C<{J`>fCQ9xH#DE&z zZvVslcx^!sTQd_+&vrWeT3fXv9h9^LCT*JWJ-Xu$+x(zL3sM0lgi3(Y)Yw0`l9l867)|s6tokf$Xm` z{hxPblNf$iRZW&HnWJSoOG+|Q#o_sdgg}G-$dl{GRTQSd*?Lt$NlDyyC=NCP5MQG9 z5vd@aWpUm%11^Hu$uvarGLWErz=*!!)jx(-~V5E5&Y{c_MGfFLiBbP!ok zKn({6m&{><4;SbU=md5i9>PyJv=kIDNrT<~(C|PbCOk$kHA^NhdC}KEK2+a3qBMu* z1vQu+c?s1+)-^pSr5>lgT~^j?z>nidlKF{SK}-Vs$fo8n8YhkS92be7`T%iE0UL&P zs|-<#Mn7}mpF$UP#T#27ZIh1M(IP9;N7UDO~TXtz|WDPp0w2Zs(ip zx6%3Ydwa)Zs^q1e#!M4O&rrNGOLCta-$EbEvJwbA!ny_Oml%d+q834aTSmKKZ%hl~ znL?Z>kfxOoRm@VEH2;S1yYtAgloK~s#QjzK=i$*JI#5F}5*Iw`XmQ2t4btL%{Jsc`Pr$GukgFqdpSpbyvTiA`+S;%h3v=94F68eGVxA^V5ye=>7_kEh=-r59ac{E7z_!-&Cz0=RgX0_C2=p#pL5t!kkAS7;uM*%0bf+sIgC^ey51GH4diJrE%u$l zdFyQu+s6Bcx&4J2xgj1!xx`ayxL;RENk~Eh?&|6a1k`!dk3s)zawKRuG-)wXX$*v| zKfJ^HvmF7q7On^?Kte)7pp+g5`OtXN4jpguL0C}4bV^qQ-q&>BXHLCd(j)?|{Cvf3 z16)IA=VWlW@39X0uH{wER%SY9S^RLS_rE&J6Pv*HR}=r*+8SUZ zNPEZ=g=X<3X*-Zw_R=tx7p8TBip(9nlP;tEoF)J1L8m}8T3A$6URzrR@TVfd1)ls0 zcq=0cV(FHfTwghbtE(j7wFJoD9|;LtXI43x0dG|SLmjXkz|vV%RP_HI!ZAM0@zJ^8 zMsty0x0@|~uR?z)oaeTFnth-0i!e%74He~nF}m`XIt<(@Y{FLX6;uMYmwFub&@}Wy zC@+;caRz?9Lgc$_rU`2c3^Yq?D++qj1jc<%tK<9+zKgWvymBg)2qicq>507B@*d$B ztyuPl;dG^NRKltKOiBE)q0|87q-Q@$iX+-_1$ujZgh-JT#{5WX43uBn4fW2CnMNXacIms za`P3;HuKWHW~;Tq5vbb?zVMPBy*fk`dvH_*lFht4dDxikJa+irWKo`|D1|jvN!m)$ z!C}5R!M=Yhx2fA)p&NRMb*L2Nnk(1#tLBNk0+5%81RyyLBz1Q6^&tQvHZVz`5O4`8 zDn{#(D@u0x< zm6U|2RYHu;(A(SV*`h}+fl6~%{qR<61Hy)n3#(yU$EL`jQ2(h9DBK$`&)DnXRs zg|@l!K@+&NgMwh9J%v|p*k^TfxKHc?UvIxM6_9APo@^BLr8kNY94`<0O4xU*B$e7F znkDLBCQH7ovsh=BpOZtLiBBU8`&;#uP4Vs9&@bLuZ@br8Oj0i;v*G5aEf=f|0p%t? zyTrA|mk1=}@o8<^Ew&F7Cb1m!z2sHgX!0C09si!DGAkKZ3voU(&r3xJrF9R~l99~d z>$HAGiAzASY;icBaNOHFq8v_y6Z*7-rR|9_J~tzkHh*}t1kEq#-{E-YGlgJ-D2G?w z*n9bIHfzclM+BobO&Q4D0Nc~}#YT{5 z*NLxEQvStSj?UrCq51Ry=P}@~WHxm=5fdT|mqHKauOB}G=B=qXIW-zXfD^Ol>}Xgiyp9T>ElNBu?bkJ-VkO%K`z>5$W-f7JttE7!AmCr+PSzE_i>yEhnM{fTyVjhi>Ck2}3 z`Geg7C~$}AEGvU=yVey+#C}aRl!l!P}|4kX6 zAxZY5`L-gl;sh>Dd}R762s$FbLzI4opzGBUkA z^@!wBUeI0Lk|QE;@0{P?d1YesqE~r>1OYq(g508_{jksQW33>i?w#JL+JT;Ci$~37 zt=fTIWkZ99Q$lo^h9>f+((?E6qNvFpBzG^koHM&f< z0V9919}t=P`e{JMXHZB;;HQd?{r#in>jkULO)QZAi+E|J$Ekml#}$2eXl((B$k*OB zQ#0214Ek4)r^F8iD=faxUZ6PT`|HG%^IE})&F%ra(cb?4+eU>z9y<3Xh3K_G#S#xdxr*u$fc5O*k$@#Ao)P%zB-V31DRA>I*B*XUvC-@ik1Bi=rB$%n#$ z@Ng}LZyt{IHN#r5E~HAE0?vp5zbQqvD)9-=lZ7YE8=70v zG3*HOaM0gb#1Q-QQH>wOZ`Psbrk__Vz0k1?r!)Og3SqO1s=Le~3WpLT5L&1{#nJ*% zL>l^;hkV8~eIGbbN3H|ze#R}eapVvi`1BrS3t`L&(Kd><9KO%Vd zj*>8r&$Khc=o6GSe^SwT4Om!#K;T>`c2K;4kfq5n5-hA5O}an&ZF;U=`n`M6ud=xa z336a5yLxlKWoziJqpvih|DjAU>UL`|3B;4(M>B(DTunzuN50icK2N+L&tni*bVGZk zA$jpXEr6(2sgObGLMw2`0e=Tjjl9wyTkchPQDw>*8bfLfX{xu~xWci{4P6rwIs#Ig z!?FaZv-x?c=Yt41*HNcEdoX%zhYy3CMM&|&38d; zJP8EwniF+nbo*@X0O4N@IGi9HG3?tn0Ki6XT2=t1>&=o=^l|f+_jkni>vx|9ol#zA zwu2x!855L(AO`Zs&!2chiv4KbdX=Yhdr({!^CJ!E@9r)&c!8VmTuE6kZa1*Ur%x4!A7l3+8Wb{=>#@DZCOvI?rC=#M+gZo+O&I+x3oFUuQJ+7tEODgy`Nsvi9Vpu7_fS-u~A6;6iKIVW|fTv@w z@3f0~(4bnIc)+H0!E<<)@O6n*f=vsubwL^)6T8hv3zbRWHj0k_^)@sKXBiCH_`x_t z>&;u}J+sO&P1LZx2IPe3CkNs1qnaq$(W5^ct+#O=r)3D4T(%&!2@!{3bG1EC;0DM< z4UCPu?6|OZ@37RAmDeEkuY}4OIV*JiMHEUrMY&t~>NNKBN?(Y(qYefuaMOX!ACt`j z8|WvhPw`ci;*_PN5I|1>4Ub~L@)H*i@5@?8@W0FIfP3PJ5ajn^VPOcb2Nv7if4gdg zdokh1kAZMspIG8FR{_SStp) z80g<=`m}mM+O_z24U>*>VX<#Tiu|C&G*c<5mS+^?K?`mBC0Xo1qE=Ymjg#E^=8ZaP+yyv#&R4R3m8o+kd)T40ig|;3x;Ams|KR%*+sCbJosC z$ZKI?2Gv#J$Im_%5ih+f?!9%&E548P?gQsB^o;Xo@r2P7U0?GsV_~FlAw`&A%(YG5 zq(Z^s_K*_*z1y6-jNF5y$RonuV?? zMpw6^9Zfgphsh95r5(mg?oav}b`7^x`a_C``Y7pyDDXh`uz~%K4xpJ%EsDVnCk>I1KtlF_6wQw@vBbipY)0ys;=mBH!Yxs_7hDFIz;wb9EUg;C=xIe#-X9nFfl{hNxV=1s29G4X#e0n6K+uVC-L`@ ziHW8~#a2CqDG3{woMQF*T3P@viSS>nzGmh5*mv+K#Kpw;0r`1t?MyN11&n!m*vl4B zU@)3nTN}^((VEE4!(>L6!~~gAuf4Z+>egY^=yRS*O4x}~^ZkCYTnd{76q{n#EXIb= z#d=&)y*4T#RAy;w)MK+(c1||Jn>Sy!BYt|F&*xjee1c$ag{Z8HS+u`>TR}Wafdh+o zr~0+YuBk59Y1N*P0i+V}Jzn8qi`v$p706s`(po@6rqd|XY?{bz+xrrOiP7#DbuHjL zkbu;)+n~x`vM5v1zd{|U`Bi0U)tPl=OD*k=`bAE6PIt^#y}a5;qN;pRE98M{{!>?{ z-$!tovlAA@7g3ZnUHxG4;+)Pc<}q$7)S!&n(Fk`%LbYw~a#A?b9N!G)YKb;B`A;zh5tXDRzbw=z(El_UmnSud zcoTh``SQkX;;}wn)uIg{7xKqjL_CKZD;cTWru_GxlQW%BP!Wv`>|@5WNbh-I`aT3~ z2(?%7L8%EnsOVWNl5P@@ldGE*vLfcK^Y!C4f~cL`Z7(W3Jaao8ayk$PY3!>`}%tux}QF= zC^-B{EcUW((b@}h|91EB-K3+EEk~*vX?10DvJn7TGPd4kTV_~Zfrg)?-F&==oQ*A! z>qcBOhZzG`jToJUbtRF2o)gdtXnb5g}%#J6Y>UGQ=?EnM+8KONdQtWJn0y z8<-5&6Y0c@=WoTPi{D+hYH;Tk3{R#$a7CD z!`r=LMLR@g%Pj`2+CD#L5f4b4tAsA3dZ_{GT;EaK$4K%kDUA?>(kBbi{mGK#V;*NA zOaJh%i{`>s&R$KvnEBhb^0E<0beP`=j?J-oGB)w+AUGfTfII2gYEt6^TK z1g(}%MAL;*osRD%fWKNu5UP%ajs4mPP|2rsrP{ShgRJM+*jT`QI}3Y&9qmRI)?8Jp z#ym~PU_>kV{Sg4_b^s2S@A-B^-~eQP6?Z7x^~&EZ8CFERkHbAD0OUAk{77RH6X}l{ zpqP`C?ByCeIwA|NA0=kLh`mpwb-Gd07_7r)z#y$!A`?X#Z*m7O^VIaT^ae)nTP0;>|6x;=7PQ}d`v1=X zlNoFFx;wYy`Tgw{rQ52kg#$9>!@5+heMn(_E+z)f%s`&~Rk(N}anz3e&xO-E~my`QpuH{#YA1!-VGK~|8g zrnvcWHtX~qJu?+$?${g^#8!DG+Q;jXizZ@s0>t-`Wlf5{e3jl?xCP#!d{J12FZup; z2)V2|th>C<5PtpAu+=k1*Mp^^r3Tj~y;)nR^md&Z)DIf4Yb;mJrt1Bgi%&d;aV)zF z2mc-|{da}1$zYPbx)Z8HL)QxmyRiu6t3=$B*5F2!>!svIHgi%(Y=%~A(FVi@R)mP_6uhkwt`Zz1gcOQJd}m^>oLw+(q>8_CU0N}`JKq8nWErNRMR)W9 zGELQN5EYM!jxOxz$O3jIAbB066RBP#EOPYWTww~YdfzPff`Sd|`UCdCipN2T&lUqJ z{nh!nu2*bm0h+Cq)ke*%-bIs*dta7$rt90V^2VwvmC6961O2_o5|& z{VBuj9L&94^R4PhY-N4@6Nfbt#xjH|Zt2SL+x_CB=7(c^Y(_mfXJ@w8pm)&a8*-$A zejbQ!CMPGMBeY!n?4Q*%G(7*BZyk^Wfg%8kXMlAQ5*##DoOC7T*=*kL`ue#OSi!c! z|K5W=|Nqt4!!`DJN*-PRvH1EG?FBY5Hb*u{$SBNATtZ+vzg^D-Y>Ka$p%r6%ZQ z${*0F*#tgqIc0vdATbE8W{EFa5wgJtPpq`O)RhuF^al3Dq-Cc@#`A(K%%>ZvFXypc zz8y~5g;Lmqo+=+7_IJ#&6_6-;2tmK>EwdOEvkTLq)9ajytZDD%fx#yti7n;ty>0G++J~xius-L8h*i{B!~h9KQCdao7hc%1Lbe0g}vU zFu~6^BXB;hy;-&A;wxc~h)u@8#5+9dHm)#m?Sv9_!)@1^52}ZB@G>N`QBy-=drNc^ zG68Wh!Q-$ZVhTvc!NA1asL0G5+~P6(x1UoXdS=#yjids7 z1YWOCYM7n4s_EQLc`(b>BFDV+3*>SjZSC^X*}|WTU9F@5TkWG*4FlROe!k$x-7?-T zua-N!;;sB^-N6SfEe;!aoyd;!3f;p@$BLaVt8iuI`mB0OPAFOEG%rY9F+xnCuldm9?oU$y|-cc3H*UZ z#>PPwlX+iQewtfao}Y5xTze?@1ZBIEJtrBxR%{h0>|=+HciX6-zH1f9pOp98{&uS^ z`X(h%K)>xdictT^z}!Ae{ypdT#8O8#EaH4i6NXi7LUXg1#{-Irs;XFiOL$yT+R)`j zo>3Gh$b6KwwPg?&2PSSrGY}X@WI#&JFRG0z(<*Pxf{$>W^E*Zy4MK_YaMSbEkgJ|9&{ zY{L5-C4Z-BlQzH{e$+=C-YcV}*V;nDp7B&Ny|G_(mE%R1j;h`8aWI_pL{gyc{Al2; z8eZ7g5bhzgu@G@GOSXSg){N6LlILR};UUvrZks;|JiRiHglMKk`LE1sIyl0wAtDCU zFqhs&b!RNLsk~tm=?*1!{u%#l9WHNJ`S`@jS`a0D1wV&sgFkQVp5*7}!+UxYf*7LR z-F+~72`nW9lacp>f7b*^XWL1U*1q5(t>H?9&_qOT)n^+Tep30y*~rdeTo!3qIie zgMBx}g^^oN1H{F__4+mrO(3k-qNx(uMBv;fNask0?LosfPB7_)W<(3f+BXqj_nsmm z0l6Yc(QP1m@0B1d5*!)|dL|)2RiKKqAZS)SPt__?Vs10USa|C?OjMhetCbwZ0j^GGM)Xr~LWzFs34(Fp$%M zQJe{IlGYuH}@JM1n^i*msk;ov45u{sRy)f#}M9 zs%~Qz@EZvuqmBAAK$RITx;VA@76^|Dx_L~u?#_eTr+1teUzQxBMiF?fzYz}FyHuU+ z>0g{`d`nY`4|+}=*?Au|zQ9?3b3E&SHQH%8bysSS1y<9bYCr|bY_4A;Wi@5rP8rjN z-#uRS*X>m%#=N_`B6=w!zx3b-5%Lp+v|t{JnK>VgJAZ~#+P3#j7ZE46xCH0+-pHBw z<$f5t`6Q)(D5Bhs3H_>|sE7<0I0O|_F6HxC&ejm6er6^fm-2f5(JDhCP2v z2ff#uvp3Z>b#H_;;9K}xCQ4S;aZE~dbfbIfwDe|^^sDP?pO%3n+%eeMpE6@$n?ILA zGx>*L@JKAPTIO!upWk!S=LjfbclZT_!MM-V?oW~AH8}`fFL>4b1#JrN&MVHNu$?rl zM6DoYeb2A9S&wX@rd01kOzX(FmgLHj-uCvXPRbyn{x+OX3eY0*pL4z~`SDf9MXG4m zhp>XmrKTz|v`TcNb}jbqcZ8e_UfuE!>#PRxMFo<{G@;Ml{3D&A-y*+d6*s-l{|qso z6RQ2&k-7IBGbl)&*dNpu`%_pF7C!U--a+q?I+P#}v_-WD@9tRBgM2pCsrr4hwYh0* zS!4wf7V$mawk1(N&B_W>^>oIXcA6ckAgMSvJp4Q4T&;I%kqABs8%4b9KOa}?B}wxP z`#*;eQ~UQ$p57$faF#UoxlZe}psrMF(db4y66g{@L`0O9mp1`U^Z=bE*XWz@7oPZa zZPJehTN`7QG~=HHiihoh8>OM40c>@lq>9GCh#m~uJ3BisudXVbb`(-lQ(KChw}4+z zU}SV|w&6W7@n`@nB7`cAjY@4+VyIV}qmS2o<84l@`t^sRP)_SPl0qM7Zk)}1^Sk73 zC7o3TdVTbmlwng~l0T^X@qcJK%b+UTwhPmpf^DTGgre#@}q~NCD|za$5rwrP=w=a{k{^eH&Hi@kb}j`~*02pPz2dl$ zqW9Yh`ecJ7Qhzt%M^ut_e>szOvGvBrmX1wxv9s8LSeVni6e@Q(fibG!Wo` z9agat?qOdAhS^sgdXwQpNklwruaz2hlItPabbffpeA_of4wz<;G+Ph91OLl$LNoRa zRE`me(-+HJ>AlIQ{lKH6L#jFBT)jdzkk7f0sotGXYtO>Si1Jvus}x~K!VQrQLJe5Z zT8Jz1Q8UIJN-_q$B0>%au8hl`n71Bv(<>{Z`7@tB5>OG?p;eh2;uU*iOYzR|xRLs1 z$8b;dzxJKs7Z&e0=X-k)r&YQ{A?${qp~v7sp>nO6j3iY97Y~3bAfuxf0NMPlKZwmQ#+B-&0A=>^G5cJ&=H*vTyeY+J4nKq9v=c}K`-ULLyYd_^N zcbRP8m6i3y?s-mo9VA@Km*w)itMK0i-v9+aQ_*i{*K)s{3>j~a+|$0Sv6;X4Ocgi@ zHzhZ+yx#cl&KvkXccOBgHsP4ALhp6L`09NAiX(uOTqrhrd^Q=4bmWqSeYfD`#s}Tt z1Jyiy8%NpXNVfbIrIoSE1NZigck+izt&!wbOUv&m8rrfFMtN88>On)m6e=&P&`&`4 zqrEg@P9hX+BUHd1{FZOTn}1eFVAQlWKS8s`82R}4_)QEC0a}1)F0l-wBCRsz%EBar z_kxXu1?4Kq_~Pw6jK73oGkG0rumeT7gMsUYA z1YIVu$%d6C?L{8d0?h6m`6p)c;=5`SvaC9Z!ti<*=rk=Ohszj2bD4Q%aRF?%ptc&# zBT92XGnfql>jrRoQF#;M;p5}Br}rztSV;WxKbx=vEA=N?**HAx%eT@kRhbv=6vuEx z!#>f$sSEha@zD@`KDC}|u@9|6D5$8A>r-@rN20V!`{BbC_q~j`&hkbN6BCo5&`>!$ zm1Dl&%$tZXk+n<5d>NmC=@T4y+Rl1VQ;*GebkxD3MX8msRM3Adp}1nO@IA^ZDw5Q8I@*5qYl4#b%`luGGByR=uQ zv~v*B`{xT%!*wv$Tu)a=b!^+=?+_j?d~8~ed4RY9T8(a+2C2!+ns4iouI4KZ6s@hx z$Irbqgj0dU;;ohxxy|_mi?gs>nw4x%7Z-U(LlQ&@Go=dd%}q0S*JrZhnWEf z8r_DBYDXc>l&Q@3C;wVeQ?G%A4p$*-tmXR9!rZ)z1V6NQ^HjUj zdA;|T^X(uL_7GSS=tdsHrn9fMPZ(pSadlvs*L6hy?-yOB)4R3Tm)qux5=Q>xy6OB* za4!91!Hn2=A&IzyVp<;)XwuvsO7N{c!5CEzkF`5BUP9IqMFBBQ^YKMHRXf$f(n3A> zkK}YjKBU%cEN<~jQu&&iVs-PchkEpVmwyw-GqFmEem?D)A^60|4-~-N88D%7F!XOo ze66I&#})QLT^RffW)H|^o=)GGwE6Jwj(r4NJs3xZM~0wtNnVCOlvR58A%6S{q)z6W~oQE=d=s&!PI!ZL_VmD(qklv()qx+9d0+6z4KDZ@&4T-p%1-fJ(S^1SkFKi)UjLdiL1dY|yd zP4*W|v0sRcoTm)D$DxZ!0a${Hs#B9&qo6&6L@DACh=%r(t!z7{wH#9V|L+A@mvz}3 zcHA6x+WdQg5H+AJ{>OfQOj~LqK|H#F=>+xjuu@4{nocS(Ilp~y4K$Lgfv01UvfDI1 ziYU}&VD@DaH?1aZpOguom6cJ6yP79{Bd)n>ta3pcZ}rLa<>?+5|E;R7nml0mI+~7C z($R&cr<0f_{E0bY-4^qBez*qkACL>ZyW5Ih0N`RkYp`1C_z7%Mx)0y2t!a7)J~VLa zlzitR`lP4`F|CaSA_SPXfjlBPkY>KkmVD9mzMcgcM`d;O0h(l8aSIEE|A=X;y%&Rj z{*c^iB7ff=pQWh%ef6cGs9vG8t;PU*f3Q1Fn|L?|R+N8PrIe98da-H88}0QT>HEou+fhs9-Oz)=(qZf@1y zk1h;!{PgpwRMnBd-8hoOtm0np_`$lOT)h-7rG8h1@PZ#}4*==ER%_;;ih+IfKgn>R z*35{F0GMBI2Jz33Q|iZzs;$7y3sdL}3UsM0`#c^`_584`WUdEWV82bHoPio>kP#ls z(_sc*)&RhIY2EV|xiIye{upkt+_MBP1qwU}wyIa?G92IXe7^Szj|Q*!Ico`!BOmLZ zQn|nX*Y5^;)41e%a8BbpP@Z4=GSa?L8(dAI$*+N3zkY#)vi&Sm8ucz(%_MABGI8u{hoc8l$ z-(J;z_^j38Ibs~Yh1)S*I=>mm(Bwu?kYv2efYA|g#fEEx-5ZT|L7t?Jm8V)SLdoLE zpx_|vl$fC_9F{#>PiaUh@j^e9*=`&b;pd=#)dYs~dYnj;2NMV4DUJqjYZlj12v#0l zD}+qQB!k_z6&Xzqc5Z7MCeiz(8ywd*#XozR&;R`!DzcrlDeiM7AK@fV=#@-dguI6A z7-757OX;VqE$SOUp4A!_#}JImOur?K>HDYK@aIPap3Acc${pU$qZXbZ=)&54hpk)H;*a^lBsTr%_V`EDpa&{6!86d1-t{_QUAYcaxwZ?i+h;kwT8~2LIEYV%mOs)r>kOM1YLXjIy7fp%3yA zn>1@EJ@NKz4>H1U>m!oXM6k)ZchfMMDq&A;_G#!8Fl0q z9)UmpPLvs2RSmZ~3FforH9=Y*OfT{M0T&LZPd({@!|1xs6Wc;xu_6iXm?XKk8@h(z z>5~`XW%LLwKTGQ1{znJ=vdx^%C;!9oREf`V$f_zVsOrx@Dj&A51s3l5>eD%xK@LSo zt9E>+h*g8qpuN|9pOdV`it>J_x{unJbMFaqCu=`CWU@A#lpuovq-h=h_0>8 zm7;3vqLTpe1>?K;#=#ziBdU-#<bb)i&}yz}1Z+*h_H zcuUPnMJx=FbUqSl)kWF%eA6X{oN6G)g9hBuqMEl~S2@^^dh!e`I(_(6Mt< z{SdJvd?Y*-d|`NOFj;>Hg{_*jfrLy&N&hS4pYXoade_VIex9&!c)4nk!@3yr1Cru( zB?(a=U8Kuq&ks~bD-rN#McDz{ zA10<*vt-D~!8ZVSp6URn*h}SO>8)LLF9W>9Bq$(N0TE0yhazG7tix!IU20_CfSfKQZ5u|MyRH3K|+oXA+Qq&T#-oS-@5W;AL>d zE0Dw%6cEV2>?fzOG&Q9Kc9N}KNp~9tM^;8gDggoQe-ej6s$f@R5?l$XFY!U?LAOho{|pR z4=0X-1Nwi^)xF2)MLpok{g2B4^w%%rL)_ozWE>fiZg-c20GUIcHa-+Zo6NG3Q<<_I zNH}2H4D`s{+S>TCGNw-}N0l&7g7_`;C}S`MfE><4cYhzvf`Re zo6h;L_oYO)cVU)MUY&UVTwA^|8bfYSxi2dCxRLu9n8t6?PsHK#1jQ+UQc>-H&iBixDiN)XiZSHbx3f2&UtF!9OQDU-WYn_ zN)~O3=_}82aMZ_wGpV^7K%`fYr?t%YufJXEBVBt%p1yhcX)^g)z{Trhf6i9Z-U1y1 zJKt~5*W0HxQpTqD*7%kB#vdS9g1)Vh@jmL~PZy8w=lSwIEutI#Bd5DtdM>&ns&+h` zgP6&>1BLvZ+uie@DLQtnPg*v#LAhGZmZIE`a{&=LW@7!l_7Ja=yGNYAn^NZFqtto~ z`i^tw^NDm-mfmFZtM`~bY2?91OE|i>@wW?$o7>-%j|+K~y(Vp&ywqXxxGU{lo1ZkH z;9?zjMBVROU;-wvW7GS6vuz^~V6!6-Q|BOd2@lF$cIk9B<=N8WGN}?F4GQjT@W1V$M zeeu}2S4?9nl_s)r-bw~Y8@0{bAz2rJk!%>=cl55$H>NLa&%!oYI3cB%us-%1*IqGp z(4sFZ<@uN=n>(UHeJ07*XMZAiIfO~l6)NpU3S7^=j7ctEgyP8TQ4kw=r8Bck8uv?{ zws`>Vb-Es@miMaz7It#vMjaz)_1Fb zbCb}*D;g1e_d}c^jw`GuTj57`scSFjJBxW+R~XWO-@ zy2)71W|1ngX_#K8U^3^arO9M@=T`87GFQhVR-=K-duOV*PtQ-dS5%2YPCkU4HmT#I zm@n~L@rZwKUsRWGUo=-EPxgvWv$|O^GP)~Y&fasP&9+^YI}n$9&og{0WB zgls4(_RM@=--fqaIX{bltlz-jnar_9r@SI6R^s9gDaVWP!rf-UH#T;SllwO-pWVRP zZTw(sK~^ses3l$W=R6H4VO&4K-ZaLl@RQ*h#twjy}kh8BoAafj%F= z`SzvmieU8Amo@+$n2m35FS|p@Im~XX5D*c6goUl=MT;W9#W3Dl^Yr&Asp>E?q=N1) zuAJ&AeQ-n5S6rrToQ(-IQ~s2Xci{tC&5!M$fA<4DSQFe|!N`I=Z4?a?1ILI1+mosp)=4R(D zv|XX(vs_4SPHcc36)p+P#j2_4YKttR3%x^0XiJ5YZjGWiF6rd7L~0kfvf9Ko9f7}*6y&B)pOS?7pcd) zQoUT93mDSo!P9<@@U~otfD$Mfub+#ZK;J2wt-oe)XTu_mxso!S!%+t!JObHzfknlJY*cV z+ihT8&Vyk<(ez*Cz&N<;fg4?!IwKI(@(T+=sam(aHT{RW#lL-6tUhL@rr$VHs5>>! z8+O3%nwlDfO4{mrYFe~ZBWrChP{6T*ubG%d{_;oJ$*Ing&;XzIV|@w7wn@Lx#YH$0 z`dc*+_p#vOC6B?K0W&8RJ$_xhSJ*c}2+m>0*81BJg+n1c=!0_zIp#X_w;jqw6X4Rv z3;o!Hfaj5R=?9~9jW#+u#A zW?U3t+p9Q8ZkxH zab~|~61t`~MSzXCFn=_E-|15u&=H}Iwa}QfCQ{`e#JILq(28dWM-Vdq^OhogH1Ej$ z!ABpxC8+Vmo|sM&>d)rT0477zA-ssUF@xEIVS6^Gg2@me9ST1bpKvD-qo1g5+h7?p zJrhI6-r`*lb5~M*?wqWp^nTv}u27aqWS^_B4X$mYe8;?*oO-;1X*5$foc}3nnRzWq zn5FjoC<-4hjPHwN!awXUVCY}cSBA|6?`cNAH;q{DO4H^?V{I5jtv!@ z6hPea%%D4c4qV0*W}q)q;QrpA$I01w)T=oNO12 zFRu~mTDM)#j5uZ3v9hi>3DA<-r6=~LMemu}`UH62qiodkVTU8VYu=~ETgdg}|7hi% zQgAxDogR^dTshh-FxOrcFfO_@z8_Ewhy8J`$8pGEKJ&}bw-waADtjZUvE~z31#cl$ zd}dSSLNYuuMe%FI^ruZhD?))_Ngq;J(T6kaoP%0^i=3ZIRtac6!*ckfU%PMBYq)eU z>2M8wPiZQOH5JpozfbD8z3)BcHEMnke(^XY*${S}w0cJzakl~MYYO4-%>KG!nfdq4 zh-9TmFY9M6n5x0u?RdI*%GE&btNwVQEBE)J4_DE;+{^^OMz`&nv(w9 z>2c-vnC~%2ThEN3kilGQC9>&6$}9~$Qnpp0sw1?+HPu3A^GI&S!Vmn{F&P z1m7{!0K2Cy0Q+2I*I>cV!Lj=_Mo}=-RNeTLs*))>iP4?g6)$84y{ou5LK^sAJxw zjnY12z45*Cr=w8!;A7mVyl5st_#MpaSB6kg@0H)Ldv8zetviM zc2Co0p}NR&oG5L zk_IVJDL+69lyp*XiKL|mo2eRH(?}fmU>45wk)-}BF=>40GM7d~55Mi4TO@jyn|I*K znx2|!ZBpeS+I@b01sk$&?lCdxw2!4+T@Ba#m5s|O{k=9J2ISXdJqcbZv>5^HA4@#a zZ@>M&7svwaQ#WppL@%UR>G_&aJ+RmEzeZ+VT@pjXOcm(K-C`h~qVSG|X9FfRuC9(@S_ZwbHH?OA@NoIxl?VQ$LQz5#(oOSWe?z4gd4J|D~ z>Fn@wvm?+6jc-p@N{rNdMD5x6uo7-4NV48Cszdek2gSx>y8yP6u5Nn1IWsG3GFhpX zEIs+7qrVsi(yUl@jSX6N1p?ZiymxB`yvfIURPXien9hBcep zDkWt}6@Uc*K;l^yKkVS>XySTKlE5;){EUk8$Zfe+ZODHYDi@k}e-cV<4clZj;4Tm` zNY+~pE8;1vK#Rsqv;({FeK1aa1iki|mUY=`RQbg+zuh|2;e4eTP-p+6&)qRUqE=y& z@O6Rd3S_2O6+-$-BbOxOXk4xNA0`6WHC38{viMo#-Z(Wi6?Fa(G@2I>87GMX_|G>` zPBg`H?)Jm-0^HcZ=4TFu4dz@g(H~5^7Nq)nUm=w*50rw3f`n0F;`0a8E9_w{b8NrT z+pMlKLe0tH|BlX)VjNlH$9`*aD_e-A{52;Nf%B$K#!~vm+BiZu>7FjpP2BY7M8D?H zrvOatCHuJW3QtDG*G+t(^D!68MUtTYpb1XPF7|bCXXk=!C)&Lr&SfX0R-B$&Tk!f2 z_@cybBnCtTUm*=EXxu*i2lk55)-F+O`IuW@lTp#6<*w4}Y!>A8CP;ib{+1=xOTonp z^M60m^hzG8d52)Rx*NMDGWuvRXa8F?Z2t^e3L&0ghVRIye^B4$h|E+)i-B;8zZAmZ zO16;a3rfYXWv+K{E9i#ef+}h=Sm?0e;L<)t2A-Vg>!K+)8?jcjk#q9;FiplRtC-RW zk4YPR;q;IadAyksKjFvy8Lt%4d}1`e`oTlM#&9*k!J^jDiGa3oVmGMCwmIQhw8A{e zndYjLj(;|wqCD|N8NY&pf<80ft;*Gz{hvdQYeVfxwSmJpXI52f_w&o&9qLi`Fx8~j zznTGqW1}C}W~Cm(P&KN4e@kLa4SxMbnoRC36K=la^uu}>cRD9Y?ag2D?~n8qOr&2a z*x6Auj1cwmST;*}Ys(=Y4|3o2Mvy_Hvb;K< z`?sSKiOZc7{)h!Z>1de2Z1wJN$%nrC=tHM=-QP>Qo6*KTzu`$q>KUeXdpNZlW#uo? zQM$1WIML*@82HPR0fvOVhiTm>0rY}S&0V;#j<$Zmz5$49eu$nMw!&w9+*pgq>|&mD z>p{#q6y|tL3CPgz_C6E?l7Rmtjv)jC>AgSyzpQ*Vs3jMPEsg9uCP{MIZKs*6g4bpw z40Pm;E`L~%*93Kh{cTe!FZWNE#%3n5DJest9G4VIWIPuze!{k<)ZlQKI)R2V;XvyXv$>@=6nz)<*;F= z<%a_8^tV-~O4_br|69FbA+ob|jXc}$Ey_JCpJ9yuaTYJBg<@n(j4cYsk%kg@F3@SY zgt?HWOcKttV7Sre7x0*1P2wZnAmn;~F!jZqv80$I_NowS3cW+Bl_qw0TcIxK|5uY9 zlHPM#e6$p0%u?+4m=xd`B_v2a z6guL~CCSVjbEtPT>s)u5x0g{;!>FHE!VK!8eq;7Ix4=>u5%U#(2ZYP6)U3S*k*S7bcipoz7&B8%9M|9cL(cE{Zn)Q zH|2U(Xv1!{^I8_b1p>-if410j;gnIc^Wt`Zo>Q`Q#UpJA5f6IIrAgK{{~$Nn(WT>F#2Hyu<^+YzQB~v(2Tm=AC-HbNY9P-Ny*R(d|3;#23Jc#6_f)EC>G%zO(tNxx zxyRL{G|eH>xo!tYcmaC>VUaPYuwK;tzH>5Oea*uP)H&1tmhXgw$nVnM&lTK>K?vv_ zP~DbYmaLaOPurpXn==74Q8hrzaBy;Jb^5f2{sdB9H%LnuL89zYVILkv;!;!pos&_L zN8I_W%+5+`Yp0G!q^z~uOsWj2v%V#KXprB?k7;DM zX1nG9nb!T&HZ75rK<9rwID;40c?$QdqmZu zj7A=L1x2v<%zL6zcC!h*M=F$-BB1#d^R*mKmoEcL=veCIdfCKyu=C+ClA4Y*jeG#y zsk3ng@MPRbP+#fJI|ZdWwkJz%cj2co?-rgLIcX@vlIDH76JPC4=MRvldVlY}3t5C{ zzxDhV{^XMkBbK)d!+ZVM;5)%6){TUgoeg_ z45PMoGDre@^m#1!EOcaNo=o@|Gtv8}?EjpGrmuhRIq_5GCuBW88YT_dew;e^A&Z=$ zxv$Kej<~M)8j=JZcHg?!k=@zdqO)D0PjpmvssS(;u=Ui0^LHp=4gd;BKyZa@ zYM0N!(SeYFD7&aAG!fqm6S9s4$a{SQ1Il_J#i8(7cDHW&vyrjpop{yFb3K`o<|wZ= zPz0EgG#(TmONvZZa*i~ZS^1mBX3S*6_XYkzpbtRW@%`ib;v)Z^EtJ2iqBjy+S260^ zE_X1Kt6&|-&QF>R1YH&Z%d+I(Y>(+TekVx-IeyjyBQ7vb^(A@TVgVWk7uPT)HIxfUsU^i7OM95ZrAz?z}@MU)3;92vf35=`hX#eYapPxl-X>*H#OL6G4BPi3oS4^5y*(*UGs_uF9TdR1{M}P zmf_O{s&41%ipGd9n@0ESS39ERWsIlNUeP+>uY(_3xHG^DuK)HtH&s*Z`v_&N5N7Q{ z8^D)G+-QSU8yB3c1n$xlK;8v-q7uu3b3OEp+&@U3jaEhDEpb`P z>mANsP046^V~plEVe2sAMF^M4$DZ9DBKOd%%%tg@85RR9??sjex`rH|RJi5Xwa4eI zt@~Koe`IAg#wdN|62gyP6*NzhR&t?qHzf5sUtkGI#^n_8hE zxH93U=4>mD2Gh;gR&TwbZT2>ix~Vi%{Z0U{T8sQHp^bt6tglF|PX7-)UZNuleQ3{6 zcUxO49>-^h043Qo(YK)IrH)+DLm``%T_@S))93?i0ZXqr=TMQ%d^mgs&)dnZ)Z%Yu zo6_V0q!i*?d7<{*bMK-eYHDAmSqXK8BG{lb@UwhtNX_O<lfXuA`PX(Bc>(i(FdFm(E5|G?*x`k} zwcTgivsfr!am$#GR{Y3hWxrlY-jyMK#%DU-e}w68hK$lKh6juek zoK^5qA*6Dr_DU4Ln_r!gj#Wz>q{)DY2^?vhTtboEU%!G+uiu#@Co}WU(+ppc&X&v1 zyW?q)y~83a# zLv|l#GDG1M?ukvw4z6C**EQ-GmX=mDXL!DvZlEWUoa)nyyH zxbRTrQT6o?U>k)~0tY-HCw#E8gaoXk+4#n>Z>PjTn~Dk(gV$Acwzw<5UTU~8cGBQ6 zuhpfsnitCx(k#q`>>-8)2@wy8B@gArv33O2N%3N!`MmOMlZFSHOtfU>!Ijp*4EMbM zP%XMfLIkW^Xz`2Y*TIddr1y*X+Ze`_;>@;2J4VcyCI(RRX*(fcc3I*E>22K=6fW3^0Kl- z3JU0v7&q~mycr&FP}ZO2V`s*pSOQVeCQkUm#(wvbFhlJ|?H1Zs@pCV||D6sk;e>W| z!#1>&+wOqBg5>(8PZDKhHD4j~&y90dbXsNMzv`@^Yv6f@^!nXJC3Bm+Pjfx(iTx#` z^6d?*&D#E)dX5*c=5o(+li?Avt-jua%x?0{(1%FfAx+Sh&@E^HrNx}!8f+fS`l|$v zdsw#(+JHN;4oPcoETgpfx1oy48vy8k^Yx1=B|?o-nq~(WqPDKExUYua1DLF=cer7- z=0I_)WTysLF2PI}1RKa?js7Pf6WH>k*$ZUEp)4Ob$$Il}bALK(ud2er+EssIN@5fS z?jRu{<9gg7R6M3Gpbyt0$HIQ&zAJ<$NzAF6ifL2^SwjWhmF>w;0_`pxxb2IVeqH7y z`I?#w>OnM_7%er<|877zH*b`7DKz*aauBFy2Tm$On>hZ{tgFAlgXuDGL4j6;e}*_4 z$GTY{{(*=|W(;~f0Za}!F&A2#89@^ekg6UY;8@>H`f6hg&W^pUSJFY6NJi1m%+tkY zWjUeiScR>&0!y>$^}pGvcS(&P&e?R2&1?b=?pGcO^U!&ZP1S1Q0GIu7 zy2#;W6#sl(>(=4qR`=;@YHKLWZbElK1`uAg(l@st##aZ+PAh7kn_gkY&|hdYGJpNF z&rV4~BF1Mrn{-toQbjS^_u9iI)5Pg6UQkw2m9~XCIQ*7uztT^b{;-s&OX7{GkuWgP zv0))%<%j|mLQ$yef;vLh`DU?XmGp-bZdP=$6tOZob6GW4Xp2T&|r@#3x$Y#yRI$&L13`&$dtJ0{mKjkvPOl zxnJK)y9*z1IeZJKns?p69aX%-!($SOS`)eRd^xoj#>b_@-n@$|jAh5x+uvr`zF->{ zx_W0ZLdUMO7GZKwobIy&|8!p?-Tbm=xZEU!sW+}X;jQPi{2>R{ToV; zlitrV*x4xBb@);Y-@8wiirCk}afr5UJ=}1hqUGg*?E3VNrNUioyr7mj=*G6t5blcQ z^NXuCktv z3NL?rZ%&#n{59!3Tl4*QSm{_wp~K{fuW-mZ2#lEUr}N_6B1Q@p_VBx(4I1QZIsIxS ziF<*WUqgCz<@p%hQvuvPSoHiDnGdK!x^UCi6K`Pg(-A~7pXah8}XDlBF5l!)IAG&Q_l!8fvr9Zx; z*iYxuw7W-H)ma4o!yG_e6@Wq0uP8KLZ`KBncuMPTNZf@W+WBYu1%|Ou-v-e5^cpPzcyT_?fx0wY3Q>RoVVh0m}yDdhxn5 z(|)VeUd_KPS0Y$sr3)DX7jt06zRuyUQZ%F**cI|i%ntM^@L=; z5gc~9%DwQv9KL+Cx35Ng!h2i;C8%&!fFm|BWaGG6W!T$L@EO`w0!fNB} z?(Q^pYT|frf^8U}1p(bc6p&F+_`;2y&V3Ra-*&U!Iv zp#9yVhQ}2Q@J;Fl3U#q&@NwrZ8Y;@l5;_>cDEfXufxtQ$KUmUvba8jpDvOw*iN z6_!Yrb}iHLKauQJO)pmeB;8sffaM8=f__8c1TDUQ8~W>9Mux;?%BuCDO}{N>*Dcd5 zlkg|k>HVL*=GT|U{&7QZ@AhAEdIkpL03`^7prf_UEP!GGhJ0d}0RJ#v*<8}bjX=ea z+xb(UTfvTp*~;)eOOWOPIZ_5DrgY^wgP(Ccj%%>w8{4o38%veedx?so1FFYadueN} zKd+zljZ3&V(B%HAWoOcfCFZoBK-#V!NnQ^8>Fyvpoe@+q@=@+M20Fg@^SgiQJHi)j zkH00~WZexI8SFNk3R0B&E&AS(+vt^M8Lg-_Jf9JEJO@{vfokj|Ul({8naS8M`qI@d z9e2FJ=%Q|kMK~|9r_b9q6|Yi$={s^Vk;#uQ+VY9rl#5m7K?u*u5lZt(xcoe;Th%rAKSJi1t_c)>Tc{T2YoW4Yk>vZ%*+jd5s z7GM0n_l>@s91W)KB)5KAduM{4<$HG+DRPI};W*D~_mKE|%84Mk>;oO5lG4?I?_SQv z>Dh$pE4l9@xya_s0fDS~&FpV+guw`#Jsks^-9ynwmaJ!Ca}-{?wQvQd@<)_T52l}p zzxj*;&$xdgd1Mlp6 z!<5mdkxKG{_0Z@G(bp%}rwM+^Tv}qIBny*|49xs-%G4l?+v-9k!X?8Ie&KJAI1AMqq_0Q z)I-v=xcYJp%vdq17p|gv_K(STC%)d9OE3M>x;0VD7u;U?^vJu)(#zrF7e71s`$S*Q z(u6v%(O;_N9hPLKe3Qj$>t1A*ij9ZxvvwMPtgY*aKEpKnxTeqKegU@w(X-L$op-2k zNP|DU9)8R#iQZYiY;AbDm5c|>OyaC(5S=e390-K95*WThZ%V zukg@s2~Z3ruAM?^(L~Nq?ao;4=E~V(VZL{wkn6x2xD%=wgh;>Ob?{@*d|ywt?WMa2 z{L(B1JxenYi8l94RTkeMjWA@%C;A4iKm48BuEO2o^BE>@AS3cWqV=D?fs)hnM&Qp+ zNbhdu*B`U|^?9ie4Hu;7Q$(tFykTzW*Ry<}ZiQfN__sBBI(eS@{Y@8OF@>YClmJw6*i49EBiV6!ufGmMiudM(O-S~n601QQs zivn6M34v;CYzzn4r&m=~y?gcnIeU;$%8f7ub24=(^vRra@yo1W)NwoSt0Wzz_lb24 z2+)eQwyeN(0{ZNarcW?7Ag=iW1=Br;VF~vn<=(uuOHw2Emu~I)B}vR%1<3}xsn>_i zY|onCW@}99(nS@O4JpkESqI=lnNl)jYcPxbZPpH?7UNmmjal(&&fDY z!MY!$H4r6k4Dn8tEkO47VmD z?+Gt??}XukEraq0nIB)^SEkw|N6}uM-R-#-jrHkH5_=X>)GaL0c!LcWlpR~qdlndyD}mALrS3}thc^?%ER2cKdRHMCwno*RYV4(~_ z2z|%GNc!h{$C$(i6(z@JmJz$r*^v7_?T^|w4oeya2GQE(wA|cxTkpWZAG!H2nvv(IOqHt+(hn&N%*y!x2XHVavP{{_p!ymaNif)9=$(mv|5S5$dnH zkgJ>HB>-^1va+*_!8h(2$C(xEh#|(NZI}U z-}|N=Zs)mo#$CFK{D0~VdJM*k((UlCK%!Ctfhk?#zcU<|YiUg#W*8 zK)i_Ha-GKTt@nMn(}^-H$+h3-S-=MT+o1WP*XFalZ?J&dJ{F)uwzPbu{&8d``lz+O z5lX&$(t2tNX6GOF7(Yn&;&@SR&!!-5>)51Oyb2uU&`NQ)cxJ zC(F$-GBI|4N%i-*59cF5s8i5cfK)D-$?!dvSUJWbT`**I+PVAb7uQd&ZnC)9p{uKF zHe+(}#QdJa^Re$)!Hn7=m%1aN(w1*q@-URhFUcKwGn+x z%S^?RDAVGXUXvR#{y5yq&`Y}RXYD-EYsxRT{U=&ErMNtyI^+>P`S{^bHIK#eeI)dc-l3=gm&zzvQOYJ{+z%KY6W$BujITp-Ix+3s`BA+IH@RzEi%D57m#>nX4H6W zmcynG^4r@<+x5pcdP5};3eo0weDo{fCVY>K$f=l_tr3tgPGJqJBo5FKp%Em^3!R&Q zk>kgTP4qrmw964n7GbwPX-C;r6V_rQNLx=DlERL@YHaU4jfn0j;?N}Q9Lk*OZf8I` z#v0dHw&>{eH^~kA8+Mev zeGLV1bY9O@4~+|Q)d3!+%ZI~Ch?t{1`7cwy-6fk=W{R#IK-UH5@4q!BsM_UtV zhLpgdA#^cFW%akpAB-}=Oq5C-JyDiM#1!qry8Y2#cA!R5i3p&?`ksLh9SFJoglqx8 zud>&ZdYTA2ZxMOx*w9e-x9TvA13L<9HUhWf`gyp(*7dgy5@{8>ic9bASkHS?!gTN zp)w6Su~N17Dyk|U!EaY(jr+Y91*&Z>Ck7;igUQ&VH6qGF6LBFf6t$e66- zc4z!FJQ2BR4yE-=gg7P%W~aGMsfw9?bx#5tYTRz(*>Z3+uM*NT69#MTA<*DB>7Tmp z)i7dAA0gMbA1T95WSN-iXhwCLbLF`K#9$LIFE4~&;dMviUl*-Dj|Gbz1&bHn!X~j& z-%zMLgF)|rO=GB7sX5`)hB7ghlhmP;z*s0c^#Ta*1Ns^cPVz-SyME;zvG{La$|Vv| zP;P8|78~tF4VPW6+pGdN2DoKUFTQ|Qe>cF}L77B|q1e0R)Vyxj;7yF|B2CQ2wmd4d zMB%65&`U#9*YT#&m70wi9!yty|I1OM+B}YB2u_-Fy;Dl;nO}G?13SrYwfEr5Zikm_ z`Z%S_E6#$y8@i?x|9;Aa2o2%fwdO2AoElPd<;`b>p~3gD<8n+eujf!^iO@%t8XN0CIzQ}=*HHhgz@4CPx(TifKoO!8j#y*F#F8$nih_wLBK z{Jx1l9+u?(R$>eWmrXi+=2+HRb8>D=yOHBMh zoCsoA71p;y2Z)p7ZXbl{$Wwa^=)Syt@j^k?3!T7|pO?lGndIJ%DY46>KlSZb6VhyUYKO0B zMTHTGP3*k!$D?tl|Ne}p5Q|ZloX+qzvg$Dsm}qsKR-Z3>>f|p%QjJ3+bO&FE`G1~X z=hMWV1P9YIFpPt3o>F)Qu!{xqDcoOq&30lxJQ!OHP2aQ|#3l8)*jKV_z{J3C^gzKe zGsQ2~{{d~Q3#2G?Tm1Hl(%`)yVZRx>$qnSct&VQp%X>xdS3{y;{rXW%%*42O#pZMZ z#1R(?bXiJvMHEEcJrZs+(Q)e>&EeBh?Hc#gk$YqFWLLxAfM^DVcM1{C%2_xq(AC{_Q>LZ7G zdjo1rt7ldL9`={mo`B$$>{`D$BtofJShW9d3ocRi-qXK-Ju!H0`SdBZpuo{M^!dCJ zYxm#f+bDY{CnsNYSuJnxpkz4PHcv*fr|b;#uT{aC&){D{*-F=kh^M9H>h^YlVXn=G zIj-I1PpA9$ALz0wp6%`_zqR8r?6GaDl`P%B?Y1y_V&pFuB}uD}#M{xwk61&FALEf$ zzN(Vb`_6hw{gJAQq{H%yS-D{pf*o?}jL(b2P(LeS#{n*|MwfN{n&yu)wVcQ+S0VZA zn|@>-9%Or$8&B9jUfS1JMD#4RJU)X`N=L;_Y`x57%gAo&#}Di7o*oc}X+f_Ezii~|J)EmRXe9~WESH+b#hQvvGb|IY<@rX46# z=E)g%|0ES7nNKenzq#BLzgU`KXGv;;`(`Z*(J3vSRJCiGg}L#y7S!K&vFw^dt^aO) zL&L^+_tL`wCKpk%o!HoC8c#&_*(b&xxzAl1FV`r_)Nw9X@D4AT`TI!Y?Tnf&l2O@M zk!R8_@5w#2Scu~1;>%ROv;DLRU?(o;+c5F|L^KfZv46kdIg?ktD=vRrh@52-ILcpS zR2%Tl&4^SCEjxMeDc((p*gW!f{j;gf`Jz=%&St%f7poyU&*&K6y03YaXJ*H{S;wlh zQ_|OJdC94Y!!kHB;)hdWpOQeKaXzh}cZf=wHjf=O3tzxeF}?FaYNbvM8cDU zc+QG`cx>?Rs2_z{>EOA$t2p2@`=n@J4~&|Z4LX-3uoRZZ&lC=Oek<)v5Ogk2LZxb& zoS(|HT00uuT@|$Eq9kd-#K=hALUp8X+cj#&$=>SV-knO|gn zP@1U4jsJ$2fs>;Lk#ts1kR}&aLa?V4Hel1ZwC?e9-h`Sr>3D% zH|G?Y__Q`uVyJp~Sx7xYhcQAstt;YXPf)uh9*(6Y_k3Tjxs8pc|7Uc6xDP$U!(nw} z3Ta)VF6D0zA92!9-fP*BeACJ4DZ1F;E-Q)6~2n<2A5;}(> z46F+4#tz;)e0JZd?z!4|NDe*zgN-2p;|ethY&V6oWZ_w0ETWYp+mIcVCF!(*FMe;o ztsCEW8Uj0skc2V8li6y0bHKyV|N6qT`Ds*wGETz@aU0e%XP6#jCP$yvPrZ0b zh>o0HjC#=O;}_!_gS?+kD`k?2(9kv9Om9`aCg{1j{3kuX&c}H}L3Xq|a37MXz?KD_enPJRL8FbM{0tdypvrbGcsY++rjmWoDY81Q-N4V@!M=zCY+J=_ygB<)PcICe9 zMl(A{hUt&F!h(ZkXI2$+0Sx>DRaqW91E*<4RQeiI;h(IFUdqaTbUhh;^9?69lm@y= zLk4jUKY%VcZI533fJyLTtt zKCHOQLX9#iIywN0E9K<|Ay4L)mS{T)v5iguVZOjFH~XV?ZKKsHW27kqW|<6pC4d;}OU zQhcBn-iiKXRv;uTt!`(Boy*4mHOW1LgQthn1qB4SC?EfRqpT^+uPG8AvbN@i19DGR zaOwYGsP}_rH#|KPE9NFNK$FL{n42rC%>`D_(*p>N!e21S# zRQBFTvMZHZEX!7w<(DZ*}BHi6St+j zm~(ocfGz#%ZN#n*@$dL}vlPtIz;&OUpPxWGbNkL6<+QH1E^|7L^u!|idU`@qQbCCQ z$YSA&WYq={T3L1TfA%Q8U_5d+M8*7UGao;<=b1U#z&amXI_u&`wX?d4bc>9xzrH5e zJ5DZB4GBoZ*pZQz@A>fg2ytBE?=&rS_Ul;~9X`Xl&0Dhu(vp!1CchemsdwrS8GxEM z47G4#e08!p+2q(PWKMrNUH^B$idEY4IWmGz;~0^_mK=j8jj=v|PVG1QB;o6`_Z9rR zGS5pum!_C|%cGg+J# z%{IBz8ju{kq2pQfLEvJH-V>d?dU3nD#A`l16O(C;*W9z`Z~p3breBe+-wKc}Cgz_u zS|#@;Z}aXLYxVcDym2q9ujQ?MoZ|>x<^sExOA^SL5es@uQBiVn&pAbv16!puO|5;s zy%N2>7&{bXl+Vz{yBwy9dv0Mp6k0c|?K>21-yQC3MHjCVq@Hm!NkV6X?-UW0V)2!n zB;w~j^z#~H&NBg8(1J}>8dDo>wh=G9zix*k&|l`57FWu9UHqs5%~#tycdiLtjkXpa zm7sk=dZ5p_m;R8G%AL~X2RvV>vYBsuhb_c2^$a=*%G@?9BH5$$)FnMrs2CDMfIac> z9I7-9Z<@e67n_u2G0p-j-K>D4HIdD1&%Dg#w@1GzxqsKAC0i-)|f^2yCb2FCmBA!3z9q#|Ly~FMh_Qgcu z>|2&xuiBHEBWR7iwt7;4XRq$*!;Ry}(n?A#FTZCj!Oq@$TO|JM=&4-ilC|~{uR0Tr zR`>=U-yX)gE&vZ))cTv#duqm>6y+*CYaX=!c){G9<5r98blX?%$YUP5W`{j0eOk`T3-qZqA5L9%zT~hOzYQT>XoAl!EzPuWrx4t$(GL)& z)_}y&PmEh?Sf#X1)tVJVBqd#dgonFbh>O;WMsfo+k)GULIf7 zyST38loW0`$B2}arXXrnhjJzRitA+#J}~sk`?$Mhu)SD!g@A-8B7DBMc&gJ%ta<7e z9c9Selk|(H4wCG_V@1;yj{AZn9Ir_uQ)2d>{m=||U>#M3-2VzwA{3?u$bNvjbqoxG zj0Cd4_l0LuPJY!VL`4X_BPSHX5#ZtOY6?=q$=ZvUVDxCq^UK9tf$%X(Q?TOn^z~Qa z@h;7obr1dkn0a*d^)&&(fYR~!WJ?s{Fs3A`kPRg`{h93kiY0jEv`EsJJ}1g_c6P>2 zHk+UzRFEm4)sMxq6ZLOqmz(5D?MDQrF9dcVsL5=vFU{cCoXgO0{PBec50#FEWv0Kt zeB5dkGaJNpY;s5+vR z3MM^huT?XRI}-4nqceT~+XVy#C=8D;p1I%rxn*qhrSi~9w)RSI{)5BbCh|LCGIk#c zTsrYLCLL+=J3M`FOv3G*oXR(^~s-AXZs^^3~F0=`o5{7`;fe5Y^RMY^TEohFUAJM;RS+&@mzbF&eg z&NtPRXIXv8=sg`?Zg#K@-i!A;^@zeZ1Ar*4Kf27(}17679#X5@hzt&qWeEAx_tO>Df_ZZzszPr#WnYw)w`Sxx97-7 z*0Yr|N58(i=AJnv1sukXx6Eh6wW7KH%h@j;uP0lH-fk|iInp=WYbd(r+i6=R%+Lk7 zG}@Q?bGPpnz0`lL#=S3EI;pIlq`O;8lCg&DpG$FKRH(fQ|F!Ap8kp&rNq;xU}+@aXPVXa$?nnHwSQq( z)^+X*h6sB||6{nIwh2X4AZkDjjsz-K+~)mDoA`V6_Wh#Gu>$(B)<+bzB|uROVpI5i zZ|14REGKM`wY-Rl;a{AGOx)P|Hj0QKNz<8VawDEovT0206i>OWN{lAq?WBvB5FV7N zc+kCG_$RlO|NGLXAEdR2A}Jy&%CBjHsDa{{1oe*HG9Y zrvU|dukBK=*1YQ&RD_}6_wNWyMS`NZTRyd&&F@=9!XR+!7L=7` ze=pbJYL|?7iV9Z!K6}CX$5VJxyU;tiFDa?4k!RkAO<Np!h;z%5mhk<^Sy4+1-!m7bz0&3#c2m+H7~`G2C7Cj7iA}jnqTP3}KBNIxir= zbHm;J@#M2-l&t)cApxq_*$&QkBpzxMX#1~UM^Y@=mZ*Ne#f z?xjvh5IxI^iOkfTc)N2D$Wgl}Qw`a+Lo@%E=woVTcecJplz4c?GCufuUIL&IIr-s; zxTnqDl`IK@8=H~7vzuz(pZ$gv1qT%Q-QuRf9_RENK^Ey68IhlV@kqx(B4szp z{!xiu;bL6?qu=V8Fn{t}p(@Jv@5?xqC(;_bD<-nYJvMbek#3tfFUrfrDd@R-{qFa3 z9v;$2X<7OC_QQksI?k+PKfG;sXPf@SiEEwSfn!a1R}$p+HUgRoV;ZCt;s16)%&+FG z?IPx8J5V*ApiRX4pkVdL%!) zJHAppT;5xdd^xA&Mc+IfW5w?i+TLwl7UBu_V4*zSmB5m0_ChL?LWf`(F!d>#(Dr=z zE;rv#C)^+wi+qMC$ak$oQ?^7aQL?79^WvBJr8u+a;kYVT+xhfK9hdumLl{VT1&9=;IpY%#d80{_v;xrxc~P>+dBy>TT5UDi zeTqFb7(Dy-&1bxNrRJh{D9mb(Vwe9~NoRMr5=u+(9DBkKiwC>f4VHw0_w%!ShFNZV zpu-8OreI1U(h_V=u@R3!EGRqhj&_*sWXr4CvPOS@eDZ9QN6Q3o@-B;L;PffX8tGQ;rXcbu9!yOwNuBchNNd0-Z;q36T?jK5LOVdF9JpqUb|b2 z;TWkD{;qc6RWUDGwnAMCtF)J_hl;m5Oa5GKHpYjA=cG3 zAe?U-^=V=?A~IQVM&a!uYzSl8O}!ejxY``V^P5e4hE9JZNpO|w9MmYtjyXTbYA$f1 zs-R11{xkon%&eR<^<(6ZJEf@94wKNuwm4{NQ-p*^CMPOAw3!wmk}RXS^-H<-PdujVH=6y-c!R_?6y%MOVy85*hbWQ_G2n{;9DIr;w{UBiXO2 zu6}gy-o2NYLRWjE%U;YFN-**rqFnNG5$xDM5G!aRSGP}=Wv6_v> zu^&PAXeU5$Udrv@*sS5zd z!}UX2Myw>WhgNIXFO?-o8M0jec_CzTp~Gs_kTfn$DlX%FqWN{hb=0Ysa(dbJdOy-| z2npQVv%FQu=7HrOS69~xSV}reC#3NVweVdQqdU$2p`wB`Ng#N9oc+@$h$rW&xQwUB zJ@7EjTU=gKANy}*&Snnp)G}BuK2-E-QCTfK8+)@X1;p$ z7;FV>HCf%heFNQqCW0mI9}pF{4@?<41P>KJDTpzNSUm*VYXA{jI==#R`&Fw+OUv;c zo{zx#f`SxXFj~S6cqwl5H_54BCWCL}%h#`F1y_MuoXghh?&_+6L@wcyA%HTXiC~Xw z|G#lkM5Z0dXFPv8r|z zTwGjdV}EB}NQh{i8ZRMx(L1p+>QpZ2wm^qq1Q}%zm)h`VpvZd*3ZDRn!3&atnXMK& zSZ%ZhL{KnJ!*5Pc=hWjp4j7u2t>^`Gdb{=&du}>C3Ji4o@Es!E!m_dC_9>+&fdcKj7Iyt+m zy1!hi+{NI%qg2wXr%z|&+y4tNH40=KtiJQXSAm0()x>V0QHeuRfRt|Thf`h91_yGjyXbFHZKtce7y&Ap^;dRLn+Z|ww(zc>Q|!pdn=a>E{nVK;O=P+> zf3oyd+>JrjPhFRO6&~&%vU}5h2{W{=%=FO{C%A<#v@^J>GMtPB0I$Nv79* zR|A5#Xwu!Lx~8wC3SPt+`2Pi)O1#?OfcY!FNd_w z*=D0b8XmJ+yQQp*lfUd4kn7#tIuC&h1-~9rtt`+7kBv`o!#MWX*g6dJG+bT(Bp!K~ zot`&6U`KNB0qgJYh!88Ao_~Mne|%E*U~EuqP-;PtSgeT=quPr{jk374lP%ocCC9H4 zA*Y+n{qaEZ)`;Pw3eU~V@a7*@B7e5E)iXy<) z))r&iqu%rRACn2@K#G^Sul80{%h^kpsL&e!omG`LLj}($<3^s}r*Y*94PNKW{WU@f4}3W8`EyL;_&J#; zN(SvF;w_VJpgA!rb5JA^*<(e+*b6j8Q&aPC-Z(s_WSJ=d)q+|0Xi}1F^9u~12>Rg< zw%0B}5`?yDdEf3vlROakWp`hJteF(AWPmc0PEr8e2@2+DoZjMku8jYNj>sFsVs#gF z{mYkw!saoaUa3{_=7be7`&;pZ&j^^Xrm6<=@%dZv9o%ICc^G~B)3~@(N6Ma|sWa|$ zb9IF^VTa(u6|&K%=DhG%!f(OE55Vx`)Kp|_Y+$c7-fO^cl^kaO#B?cf)xsja;Dwgv zQ{X9hdREMC3GnkzA&gd;&Af{^{2d}9_Et<)4~q_l1x$(yioNIf_KWQHwi4@o$%rf2 zdKe%?P>n~dZSJ@m32^<5Dq~d4y6$e&q-4~rQ^_K9Pj24WZhKl+n^lli$*S3vha%pS9BK$s*ro+y!0vbc{DgGNf@BzyJ;3(qpOf^``e7vsjx#Q115NZ+fE z%1vN-BXxi6P5+Uo7Ea$;bhi=Q<^D@Xib`IgAt5h%<|Ms#DBf?0iX69!@Id8KV z-(M`o)V6)Fk}>zN^WwMnL#N5!$J1)=V^<#7eq9L*nw%WIFub@}lY#{>d1li2e%xq7FP7tQli*5)_bUfO<%qo!?;^H@W`0khlZ}k z2XZVYB<#|GAWSrcN5LB!y8Bt$DfmfzzE3hs70Mt(BEo?5a-(!`ZhqbzJF}ik_ebic zoC?qz5IT>wpWj>2F`PPmdSVJ}|JklItPyA>ODbj>Yg?)wz)+rm9}4HkBF3pdd2)(} z=f=dN!*8yAhyeik=`?S1M+fa7;c+5E?Dta)@xdtD%ubl(hAnze^^B)$Yikj=Bh%3p zmVUSxQzU!iAL*)$jEvZMrML`NJXMHAF8Ky?%Y0nh~xsBqBVp6 zDRANohD!v1p0;e=tmO+E{l#}^RgbXLNQ|ZBXT{d|C_246>^{VN(3|(t$!V|rSJxG9 zTw?1pDkMgnhr0oe1BZl!{*WbC6jkue%+oEmQhpA;)wI0fAr`bFRB5xZZT07DR6#Xe z0r`#RLMGq58uxHK7dxykXnbzaM;t?Rk!KzYO^cm-pB&o9Ysvmq;56y6{`-LnM@|X$ z-f7RRo-Ps|cQx&%CyZ3)>UKDu%|wgZd?X1gHspsV4BflKWkz}QgD-onlrujV37{zB zPj$v|g9y_|$(?-;RwD8BOM-KE z<|>x^m^(6zY_rqtjCkV25j%$hy$n-R&@;4mKZ9bn zzNsmA@0a$=Sw)pfNs%Q6?+@#2a1~v8pI0QG(G&11y(cxhs!ERY?f?diwnw+Dkf$Lf z-bP1$!LUR<<7JTxk4GgjDtTn>haXug<&;CJaTwv8{w$K}K$bR3R$(DE20>SH&gEVq zz@$!Z0@eeUD^J@7I#d|)(Evd^<0#aM3LJYhxS+CIvuTWy4n(DcaABk+4N$6xJpCmp zKK?w|82Tm;{v-Sw?uG=c;Q4a~F^15M6SqJwL2Bir3GV;b6?ToFor=3#jv@4=Y`sLe z2hXFpwcla9#YfXx5w`D!jOBLXxj{iF%ZjqD+PJElNI*Zyb^c0`p{<(OlcK+Bwv<~B zaYM}#uWh{Rk`wHHci%%AMn(rd~;67PH*!tw#t{MJY+f*)?O+`_H;-}=144Zf{YM+IM-Kbcd%DMW`(iVd@T zjE=FbAK7AoK#`f5Y35b%v2`n|)$dX=3JiRyQLz%+3bkm}q~2Zqd5bU=uaG4=#vDF# z&AON&zpoYLn$Kv!xPH~I*g3?BF*F1`-?XNNoiW8HeAqmvEv1ccpG`Y}atJxS>fjQBg#b-? zsnc+&{#BT=6GA9NVFwLQv_K5s=3JZrID<=H2Z*H{ykH!_3XsBpe9NuIcXT4wL2AKY zlWQWkbT~C9CzwDRKmm+B7K|40|3Vl+SVSNC6h@^u+$he0fFsiPZLECTe3*fZrj3t*}FxoLMxC#y7<9N7)Ivt3ZkfdaDjo$$&(3C+9;7;*;iv1<* zQxGhcfHzNSdu>sJllWARcR~Ebk95x8^z`X>icv7>!aNn&Fxr0%+X#3x3Ut`-SQQ)c zo<8kZZp0oDV_Y4u_bS$_l&%HV37EFc=s^U+A4~h+D0wadNrHbTGm2{Ham~p&+vH7_B8RH6O zK@#6cCKR-EPEOF72-qln{qXq7jFXd7`|a6hMgNRnAR&$kEV{nOH=qxpeUVnlp4ETv z)a#pD zdf9~GSF$5T#<`5E9=?sP;~89qqM!Lo5Y;`D*EMHuYmK>4=}wj3r0k(3@JsHrdTC%m zB$dkcmIK9+R31JH8w>xM5^;;l%31GAmC2%(S`I5_rv+kT(>eds)g=~tF81!7$lI&$ z>$xRKP#%V1_KR=v>{}69&FHGw+O7cwhawTSV;+xA>+J0J3mP(_X6~R9=sSq@MG8kB z($@1G=erocMrLZv9~({To4+o!eB?lX6pGKvp7-QKx-9M(L(W2)&2XG}?t z-={n(ld(gFKz1>wSCl!JnVxIM!oQh5{KG(vw$?u=>C%wpZ*LUyS{Aubn@?*Vf?4_{1=GnuBHYAVyf8 zYlSIOfBH-?1UQCmhyXHLJVXnCRI>m6t`gc_#|affLqoiW(I)v_VI)Vw(Chp63!s8M zc<_J_6pdVaFQWm-E1zaS#8d{Ne0Rw40Hz^~QcnITw4EoLsUQdt(PDv+{o}_Ef*2-1 zz4}UawYZO<3E}=BG+L@GeIZ$wuu0diWfcKa^mlYA0 z@uL+xYlHs-`kb7O78{0kSxtg|K*&>sB3eV^-k)B5gAyD1`)dnqF!T!d`a6O1^$WxT z$B9shr|_^xy+tcv^dc`W4Cw`L7)=O)L643>SXfvQAs1t0mj|@Rk4HvE)(}z%NUWHQ zraW{h1i_+la*`83I|26~EI?sr^Yg8V36_77IJq}nT#kJl>A?F&TgA!6g;R~eqwGpO zHE`EBR6_s?CMG5b%mvNOorRIo@arGkZipvHNgV#k{Xp)RlT^IN8LUk{!*L**dxuob zf9;WBZYD;i1hNduAu2oLG6&)^mm2EB$2z8O#k7|i=B~QQ1=fu$yVeelJ4l}8cH3x} zv+0z6I%r6mm{xftpW|pf8pK3|6%gl;c$O;HnGy9xO@F7`AJr%gKsrL0fA7Ndx}G%= zUN|@I{c)lZH0IkghoHn8d--W%qUPmZkq{N?T^{-Uer%ki%A}zgPnB-Hq^SMg((PIo zOOYbzD${3N>{}*z5|sgh`#}S4HaX^KopXuuVeMf8Hg4C{DlfObo|W%qaZ$W4LMJ2h z=x-`xV4F`HzxnxTvqmo8h%CwcxUnwQ$zH4C-yinRGXJ>MFQK_)C3q%}d4J;p$)3Ah zBx zmC|3hR%}c=r%OcksExhY%zq@rWt!P%GxbEIg?*HAZ|UUTl0C!J-E(Qyg){cqQK3m8 zk*TJ9Ei?7pTkLYow(s^ofJmWPyI}?0whN;-QDV;?;!nK1l6J*U6oe?39VeR=D~#n4 zjdym=%>MCs|K2xGp4eYZLZZ-SKm^EfJLEk$q?c05mv8xH$4;olXkGibYuMP71+w|2 zix;2Nn1Vcg6HEbfAq#32L2h|@+K(gHpt$?RDZN^iG;iAJ>WD+#VFHx^#YM-Vp}N-i z@K!qC&I;5Y3k&R!pq=|!Md>;a@P+z_6nKA)^e?2~0BT(6(O9D1(a^os`-4P}_vGg0 z{`TZE?JExB!5vM%s1T*gvi-NB z^CZJc6;B6j!VV6=5Y?TWY>?seWoCgIHhyob8nzt-mqcNFD^r7vd6XXxMnz43$xVTY$+OZs8^SGQP95;{S<>nTjzG z91BrhI={b_u^O;@Y}6B>DVT=8c4qaQYohXU9Mg$}`YFcVtV>9&nljy)KN%mw-hk5)=p-hNvR(q+m{Hp0@qFHgFqqyZ5rB{oUkq5yOijJv@2-_1_xZm* zqq@6Qt4xGl7RQx;9mDZ~#h0fS|53C0zZJZ3=#IA%gF5XjX+V`46VJB`jqi)DTzeo> zCH-^oRiRXvbed~+>nl;$r1zm@y4SAR=9=#F$?H_tDByd!5TWoQ;_b}3s$^DRM3L*m ze9OnU{$NwJtBKy`VG(u}qFTgS zECobGqcGNWJe0re1?63WiR9(W=U{h*tc7}$>iF>nWbXm2!eStZ9AC9LeFExbpKx6a zO6`~cPH`FL@~66=Jxh}RaTmVdin&(^vNwjgDxim(JLbv_Ho;J3E({-sQZW zzf-wPXlPb@>)t=x`*}lx!q~(({nx^djGLMB3~fi3vDhf8p1@O*>~%0EKCmc%fMj!G zZt+mE>E&7it&jzh!;k~ZaKe198luP*GR`nIjDu^ymuwntuskNL!prNFOOQYn~T*7?Z4^0MK} z-11nFuf820vUg=ADtWbgX;1cuK;pfxiP~=^$F_;9K8EL}xunn4#8*41XK*t!|8#dR zOS=---P;@b;R9nR7enQ+%Cqp$!`(wR9B~0R=SL*GEGhYp5rHP&u>HfRFX^z-{p?9%-nUENlH1uIK3I=4K}jHZl-H4LHrRn_GcE>P+}NI@~vKx-nK{}+Kq_?f+-Ds`i*^^MkZKjlsupN?p& z=KOeb?4bz5g{yqGUT8D^Tiev|ql0!xaxd+!Q3qbI0rM83Ys+m*)K^z*%zr8gRg-OK zs{nfe%jJzx`7e{}&&W0;YC#4K3JFO^d5*o>Cpj#FqkFJ?JU!irGW~H#NX2NEC$aoN zu6tq>(=jX$FKnt+X_Dbkr0quX|I``VM#Ra^pjQ`%C~nGPP6M zFY8}#Ncs2IlE7{=Hm-pA9#$*ff$i*gK2Imx!pcgGd>IlJ62Lz~OG_mP7#KbzHzKEo zKsgC&0Df>v#uit(i_RGaBX=k(Bg)uvKaje;6!pPcw zO!~IzIm;>V(Uo6bT*iTU%sYpiaf$7^kscp!dQMKxxz;0ZDCsC4gWSw18TabdDb%HH zA@rhL25xGX7uB_=IQMN2RHWYb@UXJG{W2>{mD4O>2ZKX2G?8MMota6m-G+y-B z_x;cIjVW4hNpD9OyvWa>7>FQmv}pDgC=7ipWm|BMNh7)gF>U-I&%%0d@mEvk*}5O> z=B6$YufLM|a`_s3xytzyHl89j{BQB{{*D;zO#_ zIUR>y_o9Na#ugg&feZQ5yz`u z22anwE9?5yv{@X&mx60LLyZKuB_$8S@s4kK?TXWnFZAaME7^zSSX9+7$GuU4);;x? zwyN7k**;RV0K^RaO=UB1zWi zeT=;W@zVNfT^BJdLCnDqdQu6*-q&895@#4hM->+l2)^t~>}G%Ela-a_I@NY#T;13C z-m&#R@m4l(2qFPaQ|idp=bo0sNdWMrW?5c-M?K24x}Kf`CL=^g7*Emk#Jn!qm+`AD zUNm0hCMi%cEq)~croc%FUl@3BYfB^Y*$cM{@71akk8NgmSusAHpOKjsIQ3j`RG!{9 zb<@|iao=D2ar|x1!-GZ_#Z0OxLeGDthjPgGIxuW!U8FU+sL_VL>a_-`Jt#OBk~f4l zT=f2$4O(r2QNX~!0QmaUbaan3xj1-uf&fi6Ha0G=tz}}lRbE~mFeZW%-Ziy^garKH z8xgJ0wb%6Z#S-F5fRayE7WbXLyo}=FWjintP9>!)I7(60#2l7?Y2skvJYDHzG z0erbJF1pq5TJ&rll_~Ih=9S*^Y6>USIdD9WB zbiB&RQO>=B?~lXK^z6BFV@pdN$Ru?1^f$i0cLibi9q=?hKEe_O!WOu62M->^qJ1L7 zULco?57Y=usk^%tzJCa4sz|gL*g+x`hF9;>xla^tR&qyy9?H-5>FZykC+o7>=Aow8V9)|bjBd|mf7WM8A2Tx3o!(8S=MHrVr?;z91>M?a^{p*=c2zD# zAwZGM2On}Y`**sz?8bHXxaU0&9te?BJ+$63+>VI180A$KKecxsdkeYcK^Xt>olMPW z+ONtNw*=tW}sD|8vZ);z8vK-Dm zT!>R`^XI87xY~AAHPF#9N?WZ*&T1@OwyDK(e)d$&%NwaFE=w=#$lZBYG}RQC8PrGa zj!;EES6?dob?I&UTh+4OC%vXGv~KCzXaq6&cv2m6(=h{=jFO(7$D^23a>Vpj*v}J| z>2C^MLK?-b@8mR$K00&emXVQ#e?WjH>-7Emwoe{L&1ovgWS@I9>c#t6!!W$?-iev1 zDJnWTNgknOBFp-`Vx{Ud$U)hBfg#Nw<< z+ec?w;xIG@6D~pAR{D;#>HS-WNUx7I*u&UKGBac9yqcPVK5RE&zMB zhwk(6WnVYMNAPAeJ=xg*IF@j$(ehobhOotSk#^FiQA+SL)R)wL^YF705fZA#bOB(L zHu^&>U$xv|Xg_GAx_NNqqfTqs)2BzVecFb3NfT}@=F5aAfO(G5_3I5w!5HBf85z}E zmR!lXiE@F@ut?45`pJl{-Q8Ww;)RGXrtEK0$oB(UVTB7p@j{$Ks>hU}-ETMby+<5D5PipZ&EMjz^F_GhR3fbA!eSf)? z)x|XQO^vJf{Y?WDN&9%3Y(vq($EwPkg(2!OmPn=p?aRjYLxKqFNVPWN6H80>x_iU4 ze`qI4Dr#vR8Sz{_3|DOCh>MG`C<-zKHb)ow3;dAh z2$*Qq&e}EMh>j)}ueQ-qR>-=we0--CJ6GV_+HIDtD<5i#;~%s#w9JyfX|Kwsv_^eH`0aP{%J*w)Yh%JkAZP*^8MpV^ zK7oz6aSUHGPznR>18_@FQVj|V;}Q~zKvCa~1qk2`gk9ZFr}HPlQl#UV)TnZp+aw$&3Th|rjrn82n-0Wc4t-Ukk?nIs*JSo;o|uOMoH>y1o= z%ojTr783FnvVEvAy5|4rUA`>!C+}Fq|MAdPmX}9=wF=Gz3sw=0VmvTCTH}YsS>!t| z%`XYqK18?$^D4h;>j~JFcwWd-1n75jCPnw*hET@Ilh`cPip4SkO! zW~-@z5z%A+qA$uGH$0?kYHHXE;=%Z;(xYNMOmZqfH2S$iuITu>4XK4{&4G;iV$tJ8 zX}0%k2kBq(EjZKgt=L$%7TTUZM%tzP9*;duHT)OIUB4E)?0E!AveRU~$p|roz@Pjm z!_g<@BeIHYXKsEv_IK~!b4t?xos9POCK?~NU6UdvCa$+OTUlK#-1id8z$6?llN|gf zvjQeo4y~MRs;8u+Qv()4MMYKCGKIH0iuNZb;lzrgu1$^ff$J;vQ3^To4=y|y<>io- zOziO!cQSZwTB0vAn3Lf5cMs$17a4tf=(a=1k5CBR{UrNnD{z+iC(U`A)wqDQWViQ$ zALf{UHum@U$G&8er_lF!{+jNm9XoG7g}DX?$Ajxvn^fpdELhsSWwCg7$iGP8i-D>t z3}9+|zcYm-Hcx|^+9QR`d%7JO6-e^w(cGt+80Gq zq(&rtSe-N5T{A;m&hFawza^%ipokQ@`&&mRt4B&tbTFzPT`7ADU$u>Rc+SObE=or% z4w$_KcbRARr-Pocj}17v97yu zLueNd`Rt%gb%)9%BG@uXhuQ6KI=){GKK9Qzm;5?p%ljfTQ$Y4^p1Vf>TRiD7khRB;4_;d2=bwPw zN&RsOrH4QZP_+R)KKpJUKI=nKz97lozXho&PfA%P=60$qvK~$R$`@!KFtwdoRkfd9 z`6MZjK)W^}FmJ$0`MFkfa?kD`x;x+M$h04ZIR4mk)YD?7YE<)MiJVzDQJu^*zCg@wgiG|cFcp#njmfb-~PE+f(au?t6pB#e}}xep|1f%3=5 zt(8b=dz?gszI{U+lXQgI`q7K1s602PVlksfN#6hAt{}G4&@y{?KE06+F9~lQnl(BO45HDUJk3oFKeUsNzQ#SpEbqaz&o5q{@^%rCm1*w3@W6Jf4o8^>i%*QX);)ol=HFA$^IWrUjbDG7Of44q>@t7AxKNe&?QnL2ug}{Nq4uTbcskwgCZ&2 z4N?Nq4bm;$|Gw}2Z`RCOjv^N>_nx!&m&ZwUdPUVrgjp?r3?(@d!&tfC*ody_-v9TH zj^;_UZ?m}P^_69|qd4k634x4%uX4?Emju`4eLawr7nQ@m$UKSCOo{D@JemIf_3q~` zHqu(5(4$DYZk}jDD?X>2pJ(qg=>&xzQ?xa|7Zf(Smwfpua=OWhT&NT$8U7`E>JsMT zO;wa){i8))lreVLu;EVl!`gkPL>^w=K3R1V^RPhLr0}9$>)K6oWsk?7`HZnvhm`*! zBNK+0EIKr`+l$jAU#q;PL~Ab(E}5cbV^etZK!7d`Rb@=)rFn69Utb@v0LK0oV>e_g z3i`~mHoTQXW6mE31~}Y3E@4CLFtY?B2PuGH@Pnqz-3gy5_lca;t#jNM#xytaDAShh zRd!2V0r33;44H<8>5XM+|keB;!U8Hj57q>qH=5=RF zKt)36+jm~2_tyX-z%X+UciOWZ_!cI-ev~9Q=0UU_<_fDXB{g-r1HpHAIRh8ObraBI zlnKHkz|{}#+Cg+9sB#cw^`}q7d1};ahJ>`yz5Y*us!h|2uv=(G4qmD72{o8cTf=I1 z5nXWzxKGZ9v=14nNu=i*|x+;JVa=*E_p_U* z2U;je3eJ9JH|S4PZXTXCz8Ng6NaUH_(v{td+%_EX5$g%vu+S8k-9j0E z0Jq1kcu`(n9@D$BJ!Oo&0NxQmuyO#i00uIR3AHs0df5OsfKLvmIcy7=9gy{s3AhuC z7l`u=Lc~EU4fza+Qyc&>gc+)M9FfmFH9ZZteXDte{l(9S8GIBXxOzb43*~PNG&D#y zHa4Z6NV~hc01#yX`ATRB8cncJCSIzkso8^)!(Y%H`5x#JEMi7cbi2DIl zM`{ZXhJ3gYKxochR8)jOR(}5$2TPc`j@u(3`QTLzKsaz_Qcy<%5oo*hhl=oQ1$G$V zUot>41fc(~)zqXx*j(qlBblQDsuQ}{5KwXhmNNNlDd)BB2niSqC~7Gc_yT+K zv&4NOPvoxScN($-o4rn)$s)JKQ_f$#I2FP!T+a_57*2U=@#$uYO+Jj3c%X>JKC?wNW)gt&?k3&-MW>_HY z4jjBnbkTuUi;X0an1j~(>3_B~T{$M++RLi8NeT}5hgMW>zPGxYb)c{>p+7U3$DU1} zz4aLH3$N1R6l4z%Wf+VqpJ$(AAn#=hljomZ1P5iecZ#$W1Hi1=YufQc?k=?TRpDd^3GdNs%z< zEd;A0g1GFJHULLVU8zU$h43|n@hm&LCf3LrfB0Q1!%c?0#;vyT@wEZKZHt$6v zJ4?&${^sMfIy@B+(7gB4rN}+aDkWX%cXN1n7$yb=a`XIr6v%D0-cCaeZA({IB^EP% z+X0JmiWP({2Opc{gh*=EbM_OA`!fGrS-|870GzD`N zB4oO_NmTsRt94fomej~m>@(B0`?vX0xs1|Fr}Sw?H_;`|HY>XpRLf_vd9J55lcbA3L{TTCk_PjhHEfu$PNzH}tKTfIT<6@4%bBXm}pFzIiX#X^e~|{_ zwdZu|^70s$%S%fDVB;mKV8Z-D%gr4Nb1*2@z|jgrEx-=H*sEqFLCFjX2w)4|GOWP4 z4P6sb5rpO-w?oK!SyMpvEKpVersI=E6?K-Wgy07ev7tvtHZ!!=j1@oz)uPc26q=zyB>Wu9DMfH`dZYa$ng0t#xy&Y*+v2V%roiiWZcz8 z9VEKU<>&td9y55N4BgXH)rz5gHa8JcrAzZtn%+JvP@tdvkJb;~ZlgDz*H6FgW2odQ z_-U5&(~@DM^sqfjf0p<1gJD-S>BKU(-Pn5g?>pp^o}fIBO-y8pbw3#wp#PR*E7gu+ zEA>l&&L<~2)_LHcqneD&#zdl=;0*=7>q&dAZ9{ysi=z(`V2rr`{g=$aK}+igbB6&p zSqMxPMrH5jCnp7HHP%o4bR=ED`HG^T(PN~`;TM9&n4mkwIV@;Vp#^${=g*_{S{S1H z054O#b1q;`ve=Q2r}4^{es~|)c5UZLV^Hh@{TI-pw*bEpH&DeC7^r6t0|1OH)@AyRwk28k+$<)EJg zSt;WE0OA~wW*W?=e2*BAE=%9K0z>M;))s4Q_rOJVSy?O$%Q3vC$Hzo_x8gS+4F0aGKR6xuJEl9^ zZj6aCE!th+^S;3H?3Cf@4?Uurx93eNB3l96x75r>ceR^+@T8}|I-x$C3oy0u4}Q%^ z#pzBVYKcCMvtBN_5G6;<(bDun#9Ou+aUR0x1u|_!w!VOX0L-9vV25iyS$2XrW+3z- zX;1^?uH~kK#91MGKw-hNHZwa5ie-t6R{#?}Vv!|(_z=v4@RtQ(AA%saKFB|dkj~Nv z`4#HjyI|dga}pVz7AYB-uy22$!MFLOO)YEa_r%0w#S#RA_$z@Gc+qd)F8 z7MKvrP5KeDF3_cLtbyt`J9|P}6+FZ44LS^--@ko>!(nwuhI$2xMsnffAkifqC<{0( z5lM!iNdOrhEKcC!lZJqR>FF16b3#BP*w9E|s6%Lnx622m3>3eQ62LkKbSCI-U~B{< z;>buGh%AU;_5Y^&9rPNeAP8DALWBfCnXoTFF>o_PhJ|5&Iml^4U>N}0!{yA)%Nr0C zg$v>ea7+Q(hKY-t2c#@0Kj4h)kTU|8B#2KIr!0y)W@l3oW+0(2cR1^`P0b21@S@dVXhEKSL5K_-_cpaYn~=YB7D9k;>#86a8kfeYI*f^@<1AZz zM{0Bd@e_i_f;|Qyr2zrUoaf=o#+mZqaUHLOR)3T{?gX7&@Jdb3>A3V@kW9=ELv@+UUOF!68FKZQ;53 zH3#YsJCEJ~uLV6&I8j1yA_s)U@0T;->kM;(t$S&FznSkmD7lb4LCXb(#5C&I|X$k(3W5J=|&oH11l3^yVuM~F75PvQbj26 zvxhB;L8ur5KjWw@N7NLHZGL$ft+~xjEMZ~G_SaTclob_SlTaR*?HEXUA6|P)^N_eP zQSZhBC$`aYXM}IRe;`b`!n<7*-Wwf`adB~=&rROX19PFlw6e&c zs;OyL;Jgkzor-c>faNJL#+`{Ep0{sjlr3$~I(|o!!-H1WPI;bXWzuyl4|}{>5B~X+ zcZg~QrISm$l|GCB<5-zS{S5!92T_#Q zvXCAy(tBFEJW$jAt==}#1CO*WdP{dEN^W6}t>a2x^WjM5hkdnfyVHBpb!Th!s?683 zyz&+;aoUOaO3``fIuZ|8=MTwd)qH7>gs4`39Z5;nC!m@Um#h}h3EmE=-em1;dtJDf z#kL-(UJ%6C3pCA6hP@nwfj@jZLrR`j$|LT>|{Ze)W;lJ(9EM zNYYUa?cd@xB(J^pRo{PhIOm+4dm@Sve0uoX(Z}SrNYc^}&BfO6v)Bur_tM*)eoEDf zIY0Y(+N_PbXqqwD?~-et>b}Or-e=7@z~Yne)*+V= ze_iI4BMa-ztG*4)YcZ)d)2K2=3qj>?NUcA^G^#ep?~%+rrZ8NfDZbjqvgclX@-EMK z^N9D;>;=l6ja&F_jd0jxk6>;d`|?;5h43L;>50nO`ifD1(!d)lg7WgBzm4oN>y%=m z?n{)rwX57^tNjde-;JlX*^26Kizzn9#PqZMnK%^bPA3h+u~tY~7Utp^ioELj`G^N& zx-|87GHsXLId0_y3wmA;DW=M;D(#sbq8A@*k$;NeVhzpKOu9O{In9sVWGrN4nY(#p z!IAdNe%Nt1@g|(f`463labHP#|Eacw+9t0f&#iT=Tyc!w9ujbrHu&J7yqXP*voi19Bg>J-@S#Gj8vxBe(Cs=K#jpK z9lhG4?WkAp`%Ryd(_ZV+1B}BvE&^xI+rD*ueOcXzHY~i5%Q>LUqmA-fc%e!rfO5Z^ z4&xZP1|`#^%~03BT&6=z1=qJl>r9nO>cZa?"_@ibHJyJM=qig#@8qCRRCncn%u zh2@bRRLHQeDk+6^<;*m3zrjaf2JoSCAYefk3Aj)2Y@G`sHT59K@g{1WzLUB#0hS0% z3JMBJ2=L8fV$?aqm4&-NVf+QVBtarAcJChtdwYa(2p1Qj13+ZhTUjAc7eJ6;>v_JX z4++Wup1lN`7(veoV21qC*^pWW(4=-4Jdw4 zp7S3rdxACV=ssX`pp6KEtp&k=Lz*{I`&WMidkwjKh}~`_MiFby=ho{0{ifLam=(4( z$VpiQ))q|QFr9X;lH(3Dlt67c|ss=j%?2Cn(@b@16N z=jt^nOo93blpz%Gz{3`FY8Y8y`@~~Phu?;Sxe_8;zpVw9()?_Ak}G=tm$39Uo53DH zL;r?wq|3q9iJ!XWo_s4&^sz4{svt!cEO7{?he?}0`}>d?gsj2PsVumgL4}9sJ2RR9 z%jOIb7C~1-5T|a9N}*C!Py5lv2$RA?b`u^E;OG()(^X3?i*>Bc%xul(5s+DX`&S#Y zWsa*6UEf(PY2+si|hGY5|zzQ&P?}ra(ey+ z6aXFA9sC(frPaN=CzEJLQnZ+%uOPyxOi4mbviE9|jfRFskKmk5*feKNuxznJtV>yR zczJbXmB*P9$ty(4G5(h{Db^>-tPfrRmv@Iojg9`yu0!S4A$HCH^a-IAST%Li? z3$Zr@VA7bFAcb-ln7Cn7hwR<2uX`~}&nHf+8ve~D)sBf$${4mx9;&-r>F7{_UXC!n zZ>@GrlZ>Ke(xt#rSE2<1j=2y1sf4KE!Hm16Fg@pQ3^c zOxI<^9V+!xZ<;oLK8Mq&ysWI9SAlUvAe|ls+|HUc_KyG@ii__bb^!W$qD22rV`HN! z8Gf%pQ5!cGUJDm0S)Rv&}R+ zhBK``EO>lo@Mv#tDRaisbM7LR^Sg|klJi|@{)-izT0^xGh8`k|HNG3ug9J87U&v`!w3)5}9-I&#{-iIeN-C+BCCJ`STYC7D`icKo&L!bTV z;b!f|knsyy(fjI&%S^*V)lIuJMVDX@e|X?5x{VNv>QLQ#C*!u}(qz=eLY+%>PJcL? zQG6!Bp?N`I$m-pJ-IOA;FH6oYPua-LDxy30Y~Y)x!R}o5d|Je!<52m`@%P?IJp1^o ztwx(Ctr9pQmGL=)y)}zHRcBe&;UD`??e!m|~T^<=s!w8?1PGc9lS1vqJS5BCvDVb;e z5%F4Hom)?(Z5BB-Dpv_JZG2MLm83^b`>|(k_Y-Cc1)DD|{@j}0QNGb5wa&dtmaiYT zT;deNH27)E$tiY$(j>wg<>VsVUcrSWh^6y)C~t4ECaLax$MbG?{b&0FpTn&V{d{4x zA!rY1^4aD<$=zAXcq3p)neZSHxBM(-O%s1d+UJ_2zW#vA+AhN6l)8+cQ~i^}UpqC8 z%L1|LsEhq%x7AbZeX2j@%aby0|HdzC*4L^IyM4Y(G)3f5`vhEOsZ6*}ztJYkbw7Mr z=us4Rln!a1rfx$Qqb6yMrtB}XeAa4KGOEMV{*J!ANj9Bcvl}VCZNFNO*!(!Rm}4L} zm*qa!U?rmTki=ncPscE*%ugxZE&kG48LwtX$K(e6f;s$Q^E!%>@SVXQ{%g3c%geOU zSn2+;uC6vuwGRm#BPB9fs{`76ZmD)dku=e-Hgu|YiTMwh1L}Ma-ag*-?V9&{^N4rb z51l&bHq^gK*Cp+)Ltxlmz)!q=GC$6=fZ*}wqdmQvy<0_*!qk1SF#WoRR9@suXbTbZ zlGYp#yzd;w>&>9OC<Ic9CmZDbSqKChNNrijCh`M_@ zl717Qm`4xf^F0g@eRctmigEwGF`%>A+1YpxAIbxt2P(MAbzHVbo3Nn)w_EBq+jc!QK21Qid|ew~|CW_yF}qcwt)Hvl$K{=0e`bM+`m=c)>%M z;L6>P%@L7l_Ha*!>5M>{9m4Ago+iaK;U36abcI;~pdG^AL{8K3qIY!oY)-%3b3#I*4iIM|FH3v}Z@t+h7ayOrk_{(VtiaN} zxVF}Hxz~g{Asj>AxfiqEEgKnu-aE44NFnA7$UuOHl9uR(y{iW~vIkvjV`}!!R)|K~ z;1&QX3!sin7S~Dz_f}(n_B8ON`4f+GAH7_jup_5^ScH?8Q}LW3U1(Ye2?M9XEs#n` zO<++>{MFZpl*0p&L#s#O?^^0KeMM+zr^WM!dI4sajg@$%ee$IMGf8u6SaZra2vHgLDeY5&*J-3`>+slHkY? zbyK4+u)Nz1UkyqdV7u{?zg;slw&n8&SDNh4N`C4T&Pk@f1u6xM(FrKbxiK0_DeS2Z zF%zu^0G!@K`;gz~>}U;`2DSGY2(l?gyKZuP%Wo=}utbD~fgS;da%p2j&du#S+teN2 zE+B;+6ub3QAl6-umN+Pu!3#k6-~od>`v-Q7$%5B;h*$jQG@jTA<#(y0{mSH% zr%mMtwnd`x-a1v*lz=P8$(n3b4E(Zf>7MF zbA3<+AOjBxCNko|Cdl8xymv3Wj+iqMdd1<;FSLWJ^BE9?wT6P56V1Hb|}#Nfph;lQ}L73<5+PRsAf<`!G+l_U$` zV1ViZ3@j`INH_rX$3IZlD#>4p5pyhNul=By*J!3_%JPgpp?$<8t?{WMr9+3hY`I*J zN?x(q=`X2}s0GbZ*-CbG#J}0CsKYeo;KUcYdJS4=+6te>`s!PCw%5Ch zEeG~94b7EDvEydbpm)o6mR!HwB~h|}w43=ogna&s*tGmX-3w+`3nMlW?-V_UM+Un& ze~m7YCXHO*?4K)%Eth|jNfK-8mQkvg>@S?RH|q6bkZ&?CWWU(GJ6T{){#k;u+~@qk-fUcdKaNmqLWyQr&#!&t)n&IcdX8C< z;B=j;6anjI6tYJ?Z#({b{xqCpSov}+&Qq`U^ID^O&{nIFIA0h6yOBwKb9wq)=k#~a z{HcEg9-W^`&l|+bSi03R0_RrhD@?CWn<^rr(q{c>PmLQd`iUw@@Emf7-^OUvyxXhD-`!a{aveqI*n?lpVfbMwz?u&hj~jMS(ULl zo@p%e@l5_|*&)x*H#25?I#oIH2+zu$@qG+OiJqv${SNK&hUly|&FoZl>J%BOHD8Z* zHg1x>=L6cgxCsXvlo4ziHL=@fB(h3NN8{=L7H*!A{&5kKS4h$g$>k zhr23rH!sweScbCl7+u1K=^iVM0oP38eOzHo7cV4J4qT-IZ#mSMa4geR3|2^O-Dxu6fFLS-;Wp=N+8$^&Uz@& zWdwH+(2)@I3yujIMn*IUUbnS1hvA2q~3waj7!f_&qnr5!(m1CnARvT1?Qw zl7YbFY`Wq`2ukus@WF5j$}4b(<1zX8r*o&!=A#lodJA@1yj`yUbuI}wU{>PSY z*@$D}|Cm{}EN{~%l1E4*jHz~SKQBOTJIHs#F$qolev?!Dyl&=(*3mMBeCi3=Y)EV& zprW#-@6F6yhg3qSE`wl7_oICN9{3=LdjaJTqK^#XUsj2B}Wo17Qs(hs& zWHf~^1ccTfLBm5kIBaN;$p)+i!q)#)! zo(Kf;#JvX(^hsR2c7kLruWqf;5o((_=1f-gfv^{`Vh`?0!9v4h{zA1<4P# zzU7k#Djg-|D?9%7cmv^f$ivR@H;Iawloi2V)1s#{4v2_YB*b^4nD{}6?tb7&ytT*q zg!ema1|IPjTdq$;ocJr8Dj;)HZ}-2E$vMAX(!O*d>Ig<+-!qNmvi=F<_6cJtFnOr1 z`s?TpmKr8d2&u_A7}BHTY_B!@U5DSh|62X+3osT_?P7sJ1-!;fAF-V#l1!5X6?R@V zSSrzA|K*vGwRr#V$~@fTq!X%nS&UrXBV335=`jHv4$R~U?j4~ZzU z;chynjBUwPM&duQuCf1jW_KZyV6>tw86wSt;I1vJsD(PiKa&ng-x;v7fMOvfKtcd- zB8+^o7%u*))mvE5|BaiCuBgmuk%$CG_D=W7f~Dbq?Cke_e0+4EVL8~?@r|=btg`Q) zvDTsT?i;NJ9VJi~1K|U%mz1hmRE5U9yD2Y|*fm~Zp#D2=)?v0zHw7LHB(pH=fsz-j zj0W2Q;GsFF8xS2VcN=6mkLWgy!$&kItWp2Cr@L_x%tcXY)wiH zbd?G|i~H_Rqg#4+0_g#n6iTvt+B?h?h;liI?}u>}aH;Oz-Zqe(67+Z$)gmKYKENg* zg0^}i!B}bFZ`=jm7%;o!R#$6K=z@X<*il5GEu?4xxPgfALqz#3VTVDH!ONdpvM*mg zVrP$lQIv~Q{AWM^v<4W;o6Rh{%y@6aP6mWIivG>r?vat|1v&X5qoF9!7?IL+#|AJ+ zhJQxQ;v&$F?aUc{=#f>CtNLxM;n?Nf@YK=RAFXkV(eLkg&3QBD%m^6T8GP|1Fk*z&~a3F zE>k|(tq*+4%w=}x4n|~6Xp>6>j~Q8O!pRt`n$pk0xbj>(Qh|X*!)JZE5V91h-QA5T z&%*Y3z9z;thXho(uFP#UZi7f!ohEiQ{}i~i-pacT(x7`+;w6krd2h11t!zK;G|B4C z>76IS*qq;+nr|*>I%qysiygROlBeS(zSL;nwLSW0w<$ShFCcb z8nq`l=?zv`h$Fo^hCb>uIoS!T+qcsF>=vBbph%WoCRQ+e^0}^#tX%7CQ{&NCwyM$l zfyCn9#SAZmy4AbBk(T1T(p0{K*{ezLq-H?lheq)C$0F7lYYlHhFyCaUeOE^B+_&*S zC$+N3u(G^xIJ3I)s-j_fL;kVwdz|&6v?DGZ1D?D4z~sQGD~XJ5W7M8*>Bp6g0yZ5d zTg0lpgDN7$aDe}rUQFrK{UM+rm4mknQkY=6v zlGD~b`@=~&kJZ&JyQ7QWDD~B>ey<4LKC-Ynri^n7GUZGhw$9DMQ)q6skf)-JC^{@9FI*6rIouSf5Fck+>w4hR;q@>L356Bv31|bT_OTc^p zf>VecC+DZez`-LbNAv-}?STv2KSD?WoAqlj#Q|3Uiy}-7*0mdqrBq-Oa^56uc`;?l z2dV&n$O(cE^*ot0MS%5?H4V%9^Fd3$ece)nyC6;jwMXbL+Yc=?Xp0s$Hm2ayfFB~F zTMz6{q?SX2gGyIamLE3|iilp$CT)uL8TYLpAa)7)LH-T26)em)TAk&4+FCZuoA_P7@ z#7YNlW%$Qn8nX8gEli+^1FfE9Mzh`%JbZjwtrSG>x9`gz_3%aJ^+x9SQA7SPV7;Yv zjOGg1qzC!$e~inU)|u-iHJVX~qdm}>YI36?NP+!}tkU8aTZHrb_l40VG3{RP4AF)o?;OyfrERa-s zlL(28?UGvHp}L_dkG~E}4{oZSpPnU$`%B3*s#@urBk_V++hTsmCo1$47PAc8f>CpK z3(Jo?>t}BUQsVPhgd#XmyldbqE^~=$irkgvbK{oSyOvj$6>U)KF$CEK6V81ue0~!FhN;ZE zfqMYd&o=CZOQpz7H{W=zDu@UYHD3Mmy!}MAwONZXuJCbULIVb~cWLwmcRMV1C@H3s zA)a2*wLe{Ko`dwO<6Cp=h5XG2Y(&|{nBMi0NMgwTDw9M4@1KxLy@&v-ZQWPD$o8D& z^W-AVfup3g!qlRR2&5KKiC2}izht^C7>OzL=1EdVXYF#59d+SOo^?ZnQ}=&)YT)~O zV<3;$2Hvd@SOt>H%!`SngrH?FzEP3?Qd>Q2ZEb(8#g^DWD+p+3KJxMTzeAtc%>lKH zGV{*bnv97_?&C^GfS?x^)(&q2J8Xyjx9`2(ecCTyzb-e6s4yRW)ZQ`4TM8ag1A*4P zQUMJ9E*Tdqz3Djy?}O?8s<~-HhL)SwI`^;*NPWgEYy5pJZhi?JSCy~s`K%djGwNt( zA_d_ScL)-m2vE!PMsp2R_u}UyRE}4cEvCt<-Cio*Gzt>W`+X30K6WIZF@F3<8N>8F zcO$v|pFIW%e*5^Y|7KfzH{ZJbtI>@k*p%+|neEA4LzPsEOui>ABfTwaN^beL#7j?P z@w=VW$bDuq_A~2nApw$B(*t2mWmgtG%kUvPS{s)cBJM)NZHT3w}Dv!AP0+-@qpV!XtT?=foKG%G8g5E6zk1TS z{`vP~GOR$MvV#LmB{TKGxx?s}f2_WV8dYeuh@|e^9}$>M%mCO_d^Pewj+yd%26 zddHa2QWqym47DTBcEe^7b9;*+XtRLXgslP*S|6R9`~s5Q!A9}s9e9Dfr7^PCu{rCJ zXgK^x9)Q0x1`g3^*d{sL8X$KPw8#cjC;=_)z@D~KpR3SmJyzO3wK6lq^AToZVuE=9 zq82mJ9lg97T(zHl=(phKPUY$g5@vj0&EY11@K_Se6R`gQ zkQx#iN(-Yb*rq`a1m<=GYz}zx$KELL!D^NnVXAA}1(N>c;^mEpyAVcZL=bG%ym#HY zA6x#b>#HkLQc{pBgY&2lo;-1QSb%8_kYx0KLozy42O`6a2XatH!PNZlat*f3!D@u( zVqB-qj2B@^hk~;nct*G5cU62$KWinNL2uyn{f8j@+9{+*HE`dXYXILpFn{e9%=t%w z*RA5Cs+z;sD*loaOf$hFh~^Mp-W1%-HQ7wLUgB<_E?@s)i5kOqfro5=MwG4iW*4Sa z-A%EiH)=is5D@wav(9<4$&W$~jke)P!_@ZB7CMhZkXb$4Jut?DrgK6gLMtw{!CDEP zDVfGA``A{28Htx{p4Lt@J~{1WCG6P|ugo^gpXzfv*-g2AxwvuPyxb~SFIZTPqjso1 zEID)exrkxn!bAB9=fFm<-DGkRE|7SmvFBTi_#=|;HmS(BL}Fjt*a=jZ(B6cSzcNew z`kRAR!L<1yACA`a^uKV0P5~nZ&B5=fy*LyLj;83C7lG}0+5C@^?!aZz8_$xQ`c5gM z3G4I^pgy4y5vdR2dy^;wk1mvmJb%YLh@%7Uw;mVFY}#lm4r6Pnv(qRk?0b-aTTx#2 zSxz+4SiUMXRY``QAbX&a64Qk_WmE>^AJb#ez_qyjUE)TUd#>x>8jI3+Bq`x10FIy~ z4=wpIq2!-&pK2gc{otBTLm#{a0p`1v(m)duw19{We~oj z=h*jcXV>11;#hc;!)|HVVy& z@doOog6H0?@slxGx%cRsz23h#iyA`yWHSsCcj410Gn^Nl(>4%RjUB2WG|1V}*Vg=h5(`ot+)}xWB{W$xt%l zPJWk6WUFh7EGOy}pT5q>qVpv^ZQ^$Ui3qEze4&Vm`zppWA&t6TW~*q2#WD1WGL{I` zXWTE2z8t2t|I?Fvs-~qhT755nHRE6F>{OWM7jb6k~65-ypyqh|<5FPXXB%O0yn3F$E8wm<90+qQ7xT3#w*5@?|`bi3cD+ua(t zcDs~$$MlcV+7rr7Gk%>8@jrsr*Da5-$(DX|%F{?b4Ks~ki(a5%wQ|a%L=hOsyq9#3 z^tO}Hb0#zH$=Q)@;aU5+9ESz242~){Rf2EJV8lXzlw?=ql6cJIU1oL}Lh2}!`bcv_ zJg(Bxb}S#RL(HUpfeW#KG;8s@@?`_lhs$3#OLGO3sn%3viWQqP9? z-EA=s(cTyq{s}CS?CI`deDCZ^kqRR9 zhI3vZ)Z{>_p`xOKRJt4SDsywI$sZs>scCT|sLaTac!M4l9xVz%Q$C zbCAddgUkxCfPq{Z2?G<8mVrTPI}FM)5d}U-&_mJ8O!ih+R|%wJ`GScA7qEjm^WhdP zD7;(2=(<*^BQb3$4zTz(GU=HJ&fw?%x+UQ;twg1CG_ZR@w8`-7tjO|$LMxJryr}$$ z&}$<>7Lq`@$RyVsL8?8=rk|dsEOHqf@JwV1zH7GhRLJSpN_Y;LBN-W$OjVA|r6qgX z^8(Gpq$PP>CyX2G>onTridH*rJJEc+@vmND>`=y5VV{_r_)0yaOHdv7u#EXW;Fdcs z!qa-=DFIbsj`3OjH*jvJsJ&)QrDqhJX5>6>vTX@OETFK*1gA5#HSn=giQ)PPvQ?UX zud4fx$y{l|Gx-r-h*{MxPAeU~*%wzoma99;XXs12TZ0&Q*;V*9S%hoPSBvzj8z|YI z2nzd8{*mi1HH7v9$;^Jf1tZNQS?)Vam3X{Qu&Q~vVxm&Cm1Ht=^(D_)U6Tg>giVqy z(yPkX{_2Wxjd7>M9{h|JT025ky0S@?V4atfgS@6%HgHiI9kuKwI@`cM>d?YP-4*&f zNmQ3&1nRUxFDd1mXfeK)SGH`Uh+sJpFgAyQGivJ?fxf}0^73WGXPtc|l3x!B>g>$bLVadE}iDe3%0t$?6<`s%=JK706BcgkS z=>kH0U^D&t^{X5)!N9*1oPl31EBc~DJ-Zq<8>TIT{5(7(k&m4eIO8A1H$mPGTy4*r z{(>0-BEGo_?(@{><_Qf(p7VENeEyaKDUWy*6x+P68Q^$&P6KODobd0v{O+>ocl}g0 z?z`&oegQMhl6uocf?3QmBxo)yENDLwXP%*xQ`pb5*xQ>tsQmcC&@rTVb!#SKyt9mF(97c-gFGm96ET0aD7o7mF8fV8-t@b>TY{bdB45pjV$Yv z>_^K7d5LaEVk*_wC<6UfH-)n)&)09i>K?kN3~f^@`8$V?>w2bCwen@++Gf?wweyP- zV*SHV(@pE7j}q;)68byy^G#S+v+@^d3DF^{sDKAc=PqfNE38spoL^dksOb1s?MIbt zmQLN2Y}=wlYHmG3yDe@82&0HICa=(vGmR99`c;x~goyILN>@VUYiQjfN0Iv?`qfgc z2U)*vly!c%x=%&i>w{_6i+@NZt*zvTH5WO14!5IXnWwuJa=5Q;i}I<$z6N}HU$Ysx zcTm@_g{IOElZl^IVw_3bUD)~y%E*g%r|?Q%3>PE^NoM3n16g`>4LMUef^pmGk8 z`zgj5#w(jf-iKSMGpB_q{RJ71*>r~lS)xNn5@}D>v#2oetl8rvR`NY40@?uPa29)*S~&HlEx#X>>4#3;AM zqVY7-VP)zw2i)#h8fKK6LjhNMihJhk-;#5l2T)sT-x2e~^3Di)Do84bF6f1!ulx4gqQt|Jv9`B&zt&lv>>!0Sk@1OOyXfA}I-T}MZakw&QSg0NQ+Xcy z^0alpDcXZw_$N_j!YeiA_r=s#M|{<;=zp2@ryuT9`@OEPJ>biA)x8;PgG8%T(CR{R z>@)E4AoMR#fdxqen|SK*BWuxD zNRUj__109NkM4tD6Nx+_o4S4Q-V8m-U=x8}P`DitfK%peX>c$)&<+Sp4W2$&IU2>@|# zD=jmi=>eij!1(G0Nal3;*f41mDel||=nNLnsGea>v)B;n>+3^%S?C4@=EgbK zA=!ErzM6dvMQ0c0Xu#L7kGUBK_txA!xSW!<|MU&WnlR(D&!UlUu-yq~q%Wf(Qxlth zTRLh)pK7?)p)#(`bVIWLe21jnwd<>D;A{PFB`cH<6dMY3go`q33{>9v6G`OP($w38 z_!SYp5n61&%X&X>jM!Tp-;Dmr6q6D1$FJfu*VhNewA$4ugtmAgkx5av|5n0fg>7ZD ztai*eg{eCQ>NEX~{`>Ej@tTipZEYk1pZK51w?Ux~tSV|)%t;&Jc=pd-vE1Y@)1Js} z_O%+;t{k_vL+H(HwkUfbkH2+p+|yx)rRtrJ;tqWylMO4D28t!Rwta6WB4G=Z+OJV5 z5oGNm(q!Hye2@WB7PrIIP(q{HP&pl7%|Ws4?d=WYC&EJvYZlW>ZH)0pe0*a$IX#XH zdCM-~v_;HDk+!0COYJ|$Ta&&aN=*TFfS(0Z!e01^H7+K-N?ON4oOu@Y5`jg%s@m030D1HbM>0PRu6byUAgYLI>%Je~-xWMO2jaN0!QH)m|_9I=)uhA}C(!QZx$L4u}C z>5YV)B2AutLjR~T21TOpT2L{18KMQfxc#6skGa;Ud(9+Px60*SC>lUMwjZV{X5@6{ zs2Oa3%(=Uk`a|fv=e2$tQDIOvWmc9_4fG-PqisF2=2oAh4^%XVGf*owj-p9z5yA-YexnrsepPPC+=Zs1F);%xVIJH^0 zrfynQ@~KU1N~09d#iE-j@lO~c+>@!&XuRD{R~Ee{zd4-ra2??dkfeM*tcq(tYP@jU zv}5mcXI;ef^~FbjYnO?C@m>#OzV6%=UdXuh->qAS?EPwbuYRo0c{^&&{$?RkVUo1`0f8r zU#OjL%_ms;B=PUZJbR|*r*-bwnwG^wEf zm6n$N=pBKMOT_?}2IOj%*2CVWb0i7DFvLBJ;2<3$)WFjJ%JB05?vWM9Q--Q0!v7J< z7P~4ywt?9=tq3)=dgFaqO@PogXGApEjN4i&xI+jb&GlPFi?kuFi=poz ztVo6+WU%|VLjKxwr^DDsFCftE!Gi}Ozg{uRC4(hbLE)aq=`LtZO)-Q`qow(z_ck+(cc1cbf$e>cLN?DC@U+|VcJ3@CltGZWf-D7KfvSgKD-Yp zJERfP2n+B+h@@>MYjJ(-{PnJjLF!%d`x3N>1s)R36<)juOZ_!L7SNKJwfR05t0L*! zE-L?_QK~t)_Ou+vyxiWJaqp)CuxA=PA>BVbT;5-7%ltQ4+W0y_fHK#@#r*#<^&a3@ z_U|8Xi4qNaG-Qi}QnHK4j6znjcQ(mZBBYW{W@ZwSJ))u{A!H@W3Lz`mdOz3md;iD# zKF9C(97pN7yYKtDuJe1IpYt&Yr!ybJy;xFN|sCPm0T=B}GtmyruEW{irdqA80!x&$1;=gKd@H zkZni(ymw>Mkw(c(((=43!mS{pI4ab(YP}I3SnfP5L7VQx{fH*6HN<>7q@63PtMjlV z-6p);?f&;wo-1eR6_A}^%p0nG*|L}!oeYL~xze1xCW;q&*8#b_0O3h*)j*=Vr^{Vd zHekhp$|w0S8y6F7tR{Z_qWNA8kLKT=qA@4G&2QKbRM9*A)|~F`?kn*XnPs$E?zSUn zF$xO7y{SoK9DkIo?#-b6ffZr)^p4hFzor+p*6SQ3vX%gUgSNT|aDn6nNYiM_uJN_U z2^tCPREv(BTwUGoG%S~UnE7}RRp#I7d-cKl!`v-gt5LY_Rh}p0C%=I z0AvbBVisXh4lx+M7k(&oI20a&ErwMZZrWf_Z3t;rccD=@wCect@P}zfUJANatVa0Z z{f}Oty}KKUi1BU+P8Q;~k z^YCfoQ-L=M{P7XVi07mi$v_lAEsf70BHm*v4COj#eL&V=$U=SiFcH-OYc8NxVdI6+ zJcBF%+CJVWKA9_|00>bJ#`NQc-7mK?b7 z2=C>958LMYaxuRC0|)G+eb9CQS%!K2-MYH7;Kd{F;t7a)&z}?N2y=5z5EsDv7QZ_* zHYShvW?7s7qTfkr=~h_qLa8(awH|RvK7YPMq&FwFAakmxtFa#5 zeq#TmJM6*1u}pIFuXq;jR_B&m{=(+Y@v%@l;_ia()5F_a7$Pr-Kv_~) zp6=KI{`Tv(@2RjU1v^7Ih62P55|S^vMZ?@TIs8l{?Pu)&B&?C^1b6oI?@Eb!rle3V z=WOG^`sG-3{3E8v-ig}}QXjv_@gr$0sbX`?Oe z1?2B>|JxzV$#H7%+>Zp|r0dr+zFV9B`NI2Nl{=mOw{Eyj$4jgI+2Lp3Yv_h#y?Aul z_-PUKw}IUY3vcb69(@QTMMkw=g%cZ25(AH+pkX6LMRFXl!;6Y}UF=a!2v*6gtn}30 zG|g927zn%)VCL0WOCHkZYm!>Lt}EJVCsJK=Gid85?$)?q0|7V#$fH+lh7(Hk=^#`Q)X5cS=hVbQv-w_Jv?5ORBT=)m9|{DhT26~ z{^RK<{0kxfL)1-Qg);{xY1~^U{I`5wXNx#qzdjP9WB3F%7qBx%uHz@X3=zN0Gn||} z4&x4Z-E!x`1e#K3=|<@Q>IJ-<;pBlV8JYxDT-9Kv7x3R0o|+0nU=yyWxcEJo4FdIr zC>B4S@oN^94tpcgBqk(eyv$Fh_)}eaRZdb{aXdbJPVcKoqjXm1B+QhYJdG6Djw`Ia zDz>T~@qSbE51G}dI@)xngJ-hg-uIlOlU5KA%WZZdh@XSKa+0EU> zeV?F-0OybmEfG=z2;W%rT6lFcoHRs{1(qNyg7q>E1+WwGzB7x8E^FC5eE1OEBm3HU z${iFYtaLDpsk$*mu%8u`%`Gel6%Rmjye2%SG_|xi_mSgPb-sBM&an9Ole4qqFec2z zVjmUWeRdE66G||&2-*^=uDbeu!fnFZIs_C?2$k^hU^_$@4Ep*?;RF1HH7!IdSX97% z5#5B--)TKK2vvgNPna!cX&{x+#@3b{YZffL2|YHn++aoFs748Dh3O_X18`6Z$JPQj zH0aMB9v(=7zKhii=%&cP+yy3)msb^2dkv~Iyk&^jKnvpmFCLm`6xgw&YU}y1E z$Po4$*whoo?nsFSp&I6j_$ZNyiOn0Ui>n_qe%t;Z7XZBoVO<7s4*}0WG7kqq!l6e= zMP(#PUHS>eZfN9?Yi6%-Qf1xv{Q3H5(x-H-JL?KQ@V?l4^xD{1d^pE#i7w~XT1IIJ zwQ2HAEky|t5pDS*{(Ac1D7=>CG|)|8X#RSH$|kz$fZ4LIYnMqTC1MURi`i;nPSIM(d4PmK{uz8(8@ zlD_rVrNaz*XI@@rejls$?Y4DZ%=U!)GOq>MNivEa#7`)`9bxF;uk0Rq@ZkO#k&_yF zN+50D*V68&@;~b@a2&BHG5gPMJVFx!HQCArqqZ7iyr7PT?p?gIqOjWtxkGVWHFKgP)OFh1)bLoZ-X$*%mHJ;uWaZ~KWqdThO?Hh|@&x;-zhf|4K25bE`F!&i@y z38cy%1-`|lTrJF8$TvfGH$?0Qf!{$U@jugh9RH-E>W{>`-!V6(fH94{U+|lUGsjc& zt`8}GQ0r3T6&DvrUW9B$JJ36@1z~wW?D$a84m^1O`@rtODyY7PNwcCiV!Cy_lFpq> zROL4G-@H+6RsE>7Yw1RJPG+0!q?mKJrOEf#uU|)xTR-#r-TMz6?+GS5nb0iS)5e9p z42sq^TWB!u%M_t=LM?+Ml3HPLp6kgjF&B6Li}D7PHkmzn$o$3%52mwlgP`v}8jZ72 z2^1Z4lW6+!(Ft!SoE+d(qCPk5-Zm7Eb`zz5=T&{s+9&E3*ZBL?`^FlD&yK6H`2D%e za${w^OZWkQpWoO`ThG~^cZb>~gB=gJ$}Jw+(u?Ont!}%^(azu8)Ks(&Mif{uf%S<7 z5ZBXXWo}5x&mkcFa*o6-FaMqZ!g2|CClM(N55@5Ws}vJR$fm#79YJr1VnxtTC$3FT zFiLc0#dc)9CkbS|@m9ke0ByC*%EDN)C%{;+#4X^|g)tBPIN#TksMKC9n*fEhN}!WdVYqm z36A5&X!LN}5z*c4*)kdJ+eEGgg4BfWiMWnSOCo2x;FC?Hmd_usfSq@Le>2YXCLAzt zuv#Wsc{%@I0CcevzO|V0`OJ48VbJl@8UMl^!UNXheP#9s!T2Xal%Xqus|?}lfarD; zd>Vp*`al0J-518U6|EKIm3?{_*-D)0T7?s-sSb6xUtAmY`3q-Qum~t z;WXZM4V=f_8(TB?b@(bVa<+H&3+L_`GKB3q$!HnX-TqbR_=Ql%V&RI9>Wuj#a{2bmesYSWIr{3`KTFtMuMSQf=d2sIJadpb zgYsVX8@HYHLYW70w%8733xDpuWKn*6D(1=G&!Hj*az`hRlYd=fCw<4q&))!l2Y2$f{^$N!LZ7bC(;MQbu**_i zT}@u0^O+V69bE&)fQCOvu7rhzv(0LcUWed0k3z(!R(xt~7pZ5iEr@x4cHw^f#RMnm zr%A%cb`E*JD1Sy+!J(PPC(r1zMNuRC&rrWkJUDkNL6uuVBBpS0kBc^=jyrAZFNrR( zgwWX+#XdZcuSB!8U3{73-KZ0f$)M)8RzaSm42 z9}yTVz>RK1kP~cUv!6e|kLLyc-}nVXR|AYR6!Nu+7++LbLMjDbH$s>x^0k}MLe|@t z54?vIOcS#jj(KsYPc6ZYMegn5Q1FosxGG<|^f}Wa8d?;AD+v!(PLav?plQHUfu;%( zQeav`YegLW`_La|!3G3#A7rPX4`NQ$G%(P%XD1U75Flrv2}@-d z#iFl5CMjw-VV{LTk_6)rK16>01Hf$}cD?7o&IPP;2r;tgkMPR8$Bv!|NAAQhFy+_~1KCN@#g zc(k{e%Lx`eVa!9s!W{9L+l~&7c*}(KH4fm2(Zc-vclGr zM3kd)mMKaRlDtBSEAV~7oe!sUZhk(BRuI4;>)O>_2xcr%HX> zS=Gr=_1>?W@_VLV~N^` zz=e5rfhbMQtLI@H3+NC0`=R`W?Ci3;?d_M5wudhRAmr#tF%Axnqmp*rVjA9iUCWup zPP(;==QI?Fs7f@wJg2qw-aIo%;rKJ?(|MaK)D!d} zb)Ql_pLu@LY}r96x31vYVX7(r__)+WKzi=s-%r@j-F4_y{v&y(g?mS$m)?sms=rF* zF>l`dNqF$*4|1*|l>>`ngikV?%+DuD`95~#$Y_vLNMD%Ga!vofq(YLvSIt1s|H00G zx3~YYIGNKB_W3M21^6hA2T%(9sNa7U18@Q+x(H)1OJzN$nTCw~LXB>mrnj)z$S;kl zU;KHwXW&6%;=%0QMiW35a4R6x6H`!#`(fN`2wK0#cMf-glyHl3&Q+Rb19&kWVJxMDFw3ZsJ$d3~ztCii(Jt0E22V`f*s{ z$|FJ$p}{!ehzL%BnmJk6IuTGxDPgUNc{=0Ot7Ld@4th-;S4$S>;)?=Ts$ptMS7)d= z&#K%kvD~hYUEiZZS6B&VdrAOfPAysz(ONghS?$8A2oJ3_*)2FAq+j*OVS zPE+aMZ{w+<*p_HKG-j7|3!ngBjBUs4!8hF(1>!ov%9WU{5uP;cnRJ71gT{sdh*${l z#+{9MlmRT}g1N_QA~B z*Om7ta;#J8&mN4TYr$kz^1h*g2>Avh3~HbB4(&^VcP^ghzvA@Ett`zCLoe#v4ySf` z#)$a%5Abh*i+xUddH`mz%Sw#2wDl0HV7ov^|D;vxR6(=>y5Mc;7SPwoJgrXisR0?x z6KjC&gy|rb_URp*m_A{p4-aDxLJ8x3>%k-NX0s|PfKDFSCP8KgBozG@WP@-wzKGB^ zNQQ~9z_53+_z9Fb=`NL3RgY0QPNV^-JC557g3w+vrB872f~yGR%9si!fBkw%$$j)n zg@u(>*!CsFssP(VTGrPHpa1kgNCU%B1mgEa4c{H6FF+)$RoZ?y=(V0~0^mL|1SJ9} zxP0we3uHO(+yY*TLy?K&26iIbrUMj|3yZY&*1%v3w@h!PYmP_l@5*r&WCYdcr1~i% z?dGXZEMF0+?8UsUd-q&yzSFH0I1S=_sku0Sfw+4!%hk{AyCl>T0*Z6~#Lj zxn{=l>2~ZCr}-#+MM5Gw`J%J~OG<@juWHIGdI!+gI>mcGvNf|^ZkY}_*7|VddeQfs zeO>JXgWGzKCBB>8bc+u^MPpw&92PTjvY#{oQ0s4Ds}H&_=~QOLzIu5HrAp7dti5yM zM9qnywz_SNuPwnT4C&0Ngt}r|9=-5fOyWVK4>R@55>uTWzC_qAP+~Ru4vnt-ZMT2G z(~eFl1LzcrDi7H-)Ys3A>ijf>UgrMp$xWedt&Q9H-c`=p`f0^idGR^t>GK6&N*>1l z@*$_SMnERR9W%^Ldb#;oD+*fuvQ8DCMO64Wh-(VB{nQs7o?T`&_ zp`$y+A-{+Lp>i}*MbvpXP=%{FZ_PKkN?gL>*}5v6Yq8`i5ZC03Ngtncd-V4XVW>+_ zFK=Trd7rMobubrMP6Ag}@c~0u8aO%m-p_&qyI#OOVw``2u=^%iG_Dx8IJFCW2ak1Zb&ua2c7zzCD&-vh(j z43udo?Uf+V1$2+evAt6a3qrhwrh)-bdT!Z2I*jgsrjcNN2CjfUI=8$$4%!cWKLlKF z5P9bb^#j}pOx^^L5m8CNs@u2DvHI@ac}MYUij=oD=ROD}2qF=HFv2eYsS)ls<*^Qz7&@(_%hesZS3_S8k(>n_M zCu-*{+3&=f4wL>0-o7*Xrux+N_VUEKPr>0(-d80~t#omnj&RpT0gtGPsnZHsu5lOtL>Wx9{;$hd#XSF)Z*J;Yr2oUV^#d##_YS6jPaT<7SI zLcVvG|0BJOX>>@lCO5zi8So~R=jHYi(&9fAjsd6W$OjT=I?&XzQy&jX^Ke!ju?@KJ zc#uBR1|^jFv2k;@<{&)Y!j4I0W|nNbeQp=bYe}f?L{jiwevzC(42U#O1b$3KzSoqZ z%=Qux<%l@ENdIffT1KefDxR+3*O^2S9!}1X#uQO!m=T5L49WCDjr7E(BV! zqH_W6y8kofH$T~Ts82H3pB$tmq{O1R26OB_Emu?%5`5Ro^3DYRdq;R2*_LV;8HJaZ zFB4dXKSdHvi@MYj9gZc$lt>IKu(DJX+!=Xdki1VYs7l<%)$u!|fLB^Jt*2T|4e&y$dX1CZ-RF@TnM!y$S>Jdia76 zlilwDM59q)IwmGY*nntgG4j$;+`qtq-4j5Ku&C{CPtz5|V5EdVY=rQu!j24>>phAg zJk0=@R#9nWF}A`8z@2taKw~L}g7uWVtz1x)yrRx+rP2DBjyHGcEej!?0`Tt|wB* zD3570@lW5}Fl0?su;BQzr#Ck4=F-<`PuuEa(~6cR{SkKV+2-!wawyeDK3Q4Fsq@Q7 zaj@Or-Vw)dG51Z(R(VE;R&-6o|7)+cf`~+YS95GpcMqfHW$KHT!bX*q?KHH)x!*rE z2yPyk{HIBsq9ObBGVipaqRMVlw3A?HA|DR(p~ZMMn)C#gWCt4{<1*8HGAB~l15g*wgskf{!(vSOKhXi=bB zBwIr93_KK`E2LLkaqAkv|0DXwM%f94Q*A@3gsK8C5)KAbX!FjE-|_W_vI8(UK6^%i zTNO5#a5M#S5AB}Zu}@;3hNg@`Ah`>j?~WbtJoyi1jZ>ruhg|kG zh!&YJnI{5UA$I@_jFW`0d%=nUOG!9GU;>^?{kNLBjmU;UbB!vCPRJazznZzXl!WvV zsIZO>CIbpVK|u+}A27ZHF&@q;2!^>0s&8uAxzpuoG-bN{qd$LQ^#WMojh%?5j!q-m1PJ59o^osO#Sk{R zP$^=gj`MqrNMr#$7~)NIX78j+Oy5!98o)((m`1%+AE{>fOm;!i1*}ICqn?i>oxf11rm&nK9QdxW(|sXR z<)z*|*OSZ&re@dFxW9>rE8pr;)&=17#dhoZzb)pj7G{H`ri7+udFpE6&w2W`Grd(P1DB z`*rmetY03$l5%{4o1coGffCD!43JE)z9toQJYVE6AWm?%C7Q`iE=eAI3-5>>ASFm} zm0YSVKJtyEl5>O6=W5V7G2?^r-2ZtRrac?(W!?9*1+}974Sp zJ_)zYZLQC0!q@?E8m|dA%-0wA$?v3NuNkqzuv5_ssTpUA$ z@kqCU{TvPXo{$04BE3UqrcQ?%Luvaj9#Ws;bVw|9$g%l)rcQu5#XLd5T z&B+@BoW6-AdcQ>T&L46tdf;rwU}kr_g}wOWg_cpQRlyS*%vEkP70N>yjeVu59R^f`L2Wp`Xv!#{Qju6ktHJjkOcTG+ z8jidU;n$h2 zb|(|CbER&&WJJC+<+AISOXifpoYDtF{~ijzuR;S`W+LQ0k6SGDI;KV*2^LfDDt>cB zW-Rd^28U^P36yJ2F0RX0uTJUcjeF-8%7?qjT8fySKm3GS@T}v3CWs?(7+_Jlkf@%l z)~MI4C$Pte6;7o{yo-3Gy_0u*dW8RqCJz%0)6EA_kK#WBwVUuWI2M}n4)JqE$r!Hk zOPysKJlEr~KSgnWJ7#|K)ylOwr&zwk zEW;L!m95|5b_`Af7Z1J=5oy=e3Fbb1<&S-=Uv1i@Ia}j2o#ahhWeTO1mfqX%$tayN zvo2%#jdE%9^4+qqfuTgjH$RzzhilJ#tPt@Wlk;{S8I?cW#9xVoEF$~;=f&QQOX403 z(;=1|nVXQ)KR?Ri`=`BGL%6Nfs3OTJunpA7gfg}iIud8XJf)TQp?dw_5tqVi$fCh% zk=XJca5ox3L(by5KZa^a!d;EwDy9eb>_lUgbNu4+xWvrC@WLB`bQ)oy;fdWK6QCum zNB2quVg?0`8Fn+*D*tRw_KA`0<&a&wziWlC5W!`gn4Em_{JAP;eAd0|PgFq;!^Mw| ziD`B)j-1Cze zi@&#Oaccz()}b4rJI+B$x#LYqRC{wWEcdi~Fco?`Ppa;9%E?O$~ zU3K)utx7)6jaO+ZyFQTgK?%b1?ADlw5$%_{x7;CFSy>qK{HZp5$s*NQy-hk;Owk1n zi|OZUf8z)LBO2D69Y{z-lrZ|KUOSO_{oAVabYCzMrr$Hj(!d-^uHRgO9VD=LXZ$Az)Gx(@v8m5v#U+&4Hu=YKK83lE|#`DI`5z+z}P5&sNivn6DRuLdv%Pw zCGDB`aC95vUBPXt99iDp-Z>H9G>$!Zopz3I|N3`w6=l)3E34C?Wa^p0fxVs3mc zIS~=jZ>DmLctk9>lQGMeq|TC3#k6dmAGcu9fn6iCH2Cz6Q!MSXq9)E_L>SU2M7(>#hAzCZ0MWbGKh=^3C&0PC`PL42HeH^;kd= zr=g~PgC!HlpaV(2mQ`nr%gVef12dwNHY?1t9RCUFH1FF^!j_zr#INs0-gXoT@w9Bm zGp{InwVX~(4b&jI6DKi4c=s z)gNVK?>dQI$jz4$8u0}Ig#gx%QDq(r`RQ_&Y$^)q7_qSWD!|Xr2|x$Uyq>Hl#xnL* zfd^Jikz7x;_^`J_P$$ji3-x4ic~#Z>6J0(NpPw*yF6o&Wwo8Vq(+2!1LE{MWrDxZq zq%?JQo?6^x$hls>zE$zkoMmxE6h;@A7m;VC0DLE_Io7vZ>2c#YRdC+3n$VvZJomFk z*58^?uq)D)n>B_l9kjs{F~|7DP9?U0eHMwv(KDigq{ssyyq7N@ebie_-RgR~F!FrW zr+>(77z6W?U4~c65xY7R2pmIVPCstNWd%ilCY9^ohp-1UyF{83kv)}{M_E143L?1& z8js4Q?yJN=_!e9zQE#OiI#;hAbMVmyZ&f)9o)VWeH8~uVk8(w1@qI#%eEA*k(>_}P zdq1v6|90=*4KnJED2gn6fzD=JPc}?!fA}E*6^nOW@PpC0gLy}dbuK1dfY3GgoA6bB zu`N~Pq#ROIy85P#iksdEN#b<7u0bk?xdaF>vH3fGyhSBcKucW4BpE0`h-AC2cL>EN61xr@ns8 zVWgH=Tn-Q4nk03FKQQ9v|MuEZkz0SC^4V<@pH%Yrb$#XFA}Jq94c#YK`2t>@k{^#` zSrf@d6~=@aPQ7O@qNV@JOLpe)cd|9@a*kHQw`G*S6*%L6 zBqVpXk?+ws>DLZk1gj!F2_wB+3NuIN*s$9<)?f0gNfN$0%da0YlVM{vF-dZ;&nPdZ zU0xAo2@htCxi_!kyORF-QZxrglGf3Qknr(~i4V{aLPiHITf?NATI^I1C4p*7u1#cM zIDs#b*v;RE)N-Ptqoc)^sfCw#;?6g$cDKVq#kf^veY0==L)N?R^OdUl^b8F5R3<1X zC>mnavC04m`ANHVw!O4v+y*WRY`V^%E})`f_W<0~LP|`OBFrw&X0TUD#b8y2uJ!nL{AokZ8e}fzYP|#(5}aS1ewLIZvIU%V__A`tB^A z4EX3J5~8866nsw>C5%N{7;dv9HJ)Aj4pDU_Vqhs#v3*6*2%ukY9%BbO4N@eSop66; zxS4b9h4FU%dH%RR9wl1ow;$CaKcxE85 z&yHJ2h)Ax%Y98{NA4ppTROa1hj}9yJ*%)D0ixd~cs~$T>iG5{@B|(h``v5#2BIRzh zDGDtB2z_!3^-$p65!$XnqqTC)%YY)PDX_(oHaz^{!`57uR8ePBeW|~U!A`0n*G0(f z2k(!?yCvjca^_b!I0wzO! zy{37olj_6{Up51d*JCahITCP*(cB%qq71qUzVpCf^#gpzE>RU|)6y^~W8;Yj1NQoG z>Qg$MovxMp**ab6qLPJ=k3o_g?dR)>T8f!D*}}%D_cVvLkZ(87=I{Z0?AjixAU zy`H~AKN@S$lK>m57Zwi8D20+53NcZy;PyhY;AyyHQSisD93^1Ns61ZKBM+BNsLJAG$%Ddh6 zxP1`h$j%;sSFKz9)5F+GI=LAg+YY%5oTpw7IjJ7w03873vOl+Oec1b7*8Hbv=}Iq- zpxM%`!Gz4o$iG9-v#?7^9Y*5|Oq{b;aCg*Pv6Q-{mu0KF(Zf~Y!c+h0t?3wZHJEC%)#|+KQ+HHWX-b5ZXjeAintUw@!@M+X>s)9 zD5JKiJVr->r4Z1&^rJE#mI*_dOP3yrCe)#%5Xv6eCq&K@xH{Aa4txZZ{?6&VtSl0w z(fGK$cUgPh-qj_4;lg{X?OJ?gygUxaKvh*0n4|{I@91&=e{(1oWqP!aG?38*m@#m8I7SbL71rGr z_t>wsvDYK$%}2mHV6o!$%!>PIM*Ht5&*FGzx9-#}*f3EZ2fpiv>P9!M-c+3L?TbxNSB6KfL8g5P`=TX3R2 zij5^!m%I1w@ei;q-0a{>-4fJ~0E zY4@!n0u^*GvP98$*k^GY@1`8n1i8oqH`X{#jVh9V7lrikRR_n>rm*t5iUtjZx&b^69bj{9JKaw!=_L;h@J8vd4(& zLav4v_4`^X#h*A$3k-wXb@=S=N% z;@0R>x`+MYQQ2pP=Skbox}|h)b!skuI3b@+$?0mMzrFi*(;9ue#c;&zzlU`jJ)2*A zS43iFH+CI(AR4()3!xp>)kD4hJyUZZ%q*ycuqw<#);wROpWFi=7XWFBM` zSief_3%-N>Is^xVd=2Y9P|olZoR*A*xJSA8`R{{sP6b2_Y=za1xLP?pnCQ)h&7U`! zzlC3YyET@vG)*N5ifaC}q!=>6p((~*vCq32X}fj}gGAU5J|39Q9@MQrF4|GF3EQk~gp&Alt}8WJ zeRmq=hR{KUm!F?5U&yjrP*xvwJG>$5Q;%(IE&QXhYL{U=KpWn8UPk6kR_HxIZInRp zaDoegGKjN=pI?=~5c@&=HF!*cGa3jmg7fz^GkO*|(Ir|XQ*$1Y8yn+imzASRe#23V zXr4?>(<@}v$gvM)gscPYbcNnH3NQ#iG(0?QNn#w*g@G@tem=gg`}bzSy~jkyYeQIe zfkawt{D!3cuO(*N3cN5_ff&YQQJNrPLObQx-GuR$9OVT7W-D#W;)<5g18Wv$W=}Mj z07unOdr*?lRpG{0)Y|>aq+otxTYBZk4v4xG6%~H~ zX-83pG7|1%Qiu(}vIzJW*m}ScoPmggE%6?o-NxGb2Lw2B`P$I;;8lmQqT_^I1`sUz zUGVd;JqrBK;R8E!6Jp_NQv)d#HaGANqy_sTyAov8gN`*3_(MdF3tkhX5+*@CeIyBB zh5{VNDJglVy#FGO56tA$U2i}>gQ3g*AXypM=@Yv~Rc_)ra=ipYY7;s~c7Azvo|7|uYA+~~v8>zcQB$6vJI|8iE0=F5>)&iqA}<^ZdEjv@ip zBC=*8FBMsTWZBGd+4v64#((BnQ7N8XP8g2RR99I~L171{FqAp;od2XE*2p>4!K@Zk zBW5EwL?R5-)Kv(a4>}tG!x}|&{Wx7f6M#C-Auf?X>)P9IcTQ#&7VeL04${y633(Ce zQ9`B5=zCix#UPe1DT{Q`AiC|Iin*)uJ?ize4XFe8I!A7xM~+dBxR1pT+M*}q}XtGM+Qle{IQV;b(t8 z)2vkZb)Wmafm-YtrJ%*SRQ+XrGIW{A^`7X~ki?#T`%FQ@_j5rq?i&l#1+~jE4(nru ziURz@b1H%^D_L^xm3p@U_$nzdc{u5Jtn2_S8UasAIZ3hs*8F_{{aZU(! zIAPaG#BPA~aq85mkYCo2J0o|25POJMAzB_a2N{*>#>Qz(7r+e*$nnw3TZ zp)+lN%`^gJSTU@F&{0%-r0* zgn9g)nxah&A}KmTLxcEn>f_=>@)vlKSexS}MBo4OjH7G?_Pgnwr(pGF*SzkmPUGu@LV^*}ati*nY2$?Ze5hKi>T?8T}mGm{hWfE-z|@e-zefv;@j ziJzN}bI|!Q8pe+8{8bwm_a~|EOA?75|FwPJySm1fh8<5PfHYzTK#(vH#^HH+li%3G z10Vf7HgQBi1wB0>oJSvpML&$+E@^16f7QVN<2>}14DC9u4%D^?o^njX%34Lm3?_qk z;P5uk4x@_Wk6`pj&&>@*1qM@Ajw}oVG*E*e+1o9a8JNci_fqJ~cTh1f-0iZZ_e}tg z-U9?QeDEK!R~_D178l_V0lf`VJ<1s*@Yrh-*a41mtU_@<4AUF}77CA3g0~8h4L}8G zRbNkb<|tvJf}S15_3*%;AxJUkq)`Lp6cjKK)MHcMf-M93N~Q-tn#TCD+rapZ7B$um2K-*iJ>#&H&QszE1M6~!+jUz*M z4>}O>F);Q`fZGQUrjIa(BqTssA~ziF#FeE2^toeL10L zh(UvsiRQ)9#TX?AwF1Srie0TFCWMStL17oso7aCyI;l?6&X;v>WT}yviHU0WBw#aK z52nM+00ItWDf8ZCJbd_gY}g^O<3S{3e`O?CQeCrpK3?OAZRZNmS2oQ%-!<)Lc7~!f z;Nz3}=OIS7rO&lZMsynXd===ec`j`HQThDZdgLdrq+i$HxvuTGTVfzvpFw^ln3g(! z#BD}~gk(qM*5BEMp(+1uKi2x|nhWCm?wFW}9NAc1KD9L-#k8wCfm+eVz41Xy(+)qE6k%I;nq>`!^f?=ZHvP=s6tf zHr-SF)@=M%>W?gZ(NuSCK3+aIkrDns{vs1dt|{8#J|{Xkqrd$+)=-xq{8O=xAd|AYM^rPEvObfI64-J@@98VVz7bZnxTl^?^#cA zO>Y_}u`w>L1R#G97SZN^9UcA?w?DDv0vZXRa`Ev@5EuT8w(>ugM%wkNj<9ebj4trz z(myhD>wHoSBJXg)^Zd=d-(ECX&2OzU)l?*r@Q%RK_tL(3c@2bCP{8G{xPrw8w`?+W z;fc#w`wuki}QCzUqIsHeVV4hp2`Uwaowe3QY@`^PU^WPpF@2 z8|e(>Z|7Gq?6VWW!3_hjTgxsUci!9rR*Fi<8EJK=?sm}G4!i6)ZxdF2gJVkxbUT|h zEZjly!BdT97qU+Da%rz#T}$Gc#yEI|3q3M^-)ZfS4cZnwufR`Tetu$Z55Q1LsGK4U z7(}EyCfx|O2k|M4whCsd@n54mBiXG}Qr&&X8VWfn)}M zZ%o6Nu;N6UMzESgceh`+b92+$n0Bco_@ZzW!97Z7tx%KU;$wki4;(bmxC1fb27H7O z8H6G*nh2c|IzfH?1NgvzWA9PaA<}}-heP&+!5Tv+#6N_Dy}X<;r<3>Di^Rl4A{*4U z^xi?z-_Tz>`Yk4IAY6+}QZfl*6G&=BoqnLVyTW-1kSkmq3~eok2AjLiR=!D?Gg_He zFB%K~z`(j>AA9Fpn$dw2w-EvV$t8vEkH>TW_WbnGpXWSW^ zzIBXFbJ$1CC(rr>LkI@7+>DJ)G>w;RD!0ysj_=Qd>13+p>B`U) z<3hHl$z}SEgnZeqYjz3^&|MA+qKl<$KFwGCxP|+*7PRhmOn1`z)HZ@+eY?6#qQvSYH4!jj{A26Jbj=Of(AgSYJOju4?nYKxyIK}^Q0ZJ^W zKTf%%+F+=|W>G8%k*W%4;~+VpI({1Utmf@8e*RHn_kuMQ(d!@*U`PC)bf}=?uJN+o z^ygq_$J6xQ`qWFymIE+D5QG0EU^c8{z4~nV4Qt{-O>F+DPVP;Vt$&uEh-vkz+5cC= zQn`IXE#=kJ9)ge@^p9lJ{pLT;6;6rz<~I;C z0JnB5+uswBU`jh#5WG;FV5CkAK2+z|&0mgI(>WAymI=dpvwxkuO~K^^i4Ln1s= zFuLNM?|{q*{0)F7SU&Y$zj-6LUIqmWq%%W_0?I~G3n|t?|FCz&>bYT^=UYE`mwJ?U ziO=+wQZU3~Q;F4HxZ~Q0)g8eE{v45%=28vC{<7%6NXqr7lBLSbWtWA~SpyqSWLyy6 z3wVZzL7J*EFbq1$hf!wgn?cd=Gy0O!@+KA)A z7afR}wixK;?Ns@FH+?6D|Lh4@qsa=;Z)L1yI8@u1(!X|yw~05&{w(D!tJ}e)W7nIM zTSr69>LOpYG9?CN%|8F`mPo^B`rFq0-J@W#9W1k=Blq_t6@M_aVp@LW`R3y1Tfwdw z6c-j4oy&5a7pkJ^NE)xvS(rOLn>;mcRZ;FwPO;E$hye>6)5HrOcRwnlt{iVvy`fwn zuvYB=q#lU-0@M%Qhf`G!E-{uFNUFpM;3T>O@S^bhc!$v^F10sj#ejvtY|>jl;X8(L zOtb%OK9l+enSVyMRo2{8Y$HOC1>&who*_}~+AH$_lw97mCt$;S+fQ&)Ig^-xmVb<< z-MxC?*u}WcS)<>+)RI024;-lZwKx`S55+B`pdsD*Ag1gVrkuJpugbPl{zEI$nq*wX zpDj0I+VO|b9bnoS8@TyBW@eWqMgN(kgte%Iw{*W{@DuD^w!s4Ax_*B^)4=Gsei=ws zY|!_@SO)Y)0f#a@ZSD8CZ6F=oh1qr+fRa^vb?zvoKdW2b?{H`97F)Lb5B|S=<%&G4 zyDF^O32>ia7XV+;!+sH{G048#!yARygNW(s(os4>W)JY~(%Q}1y0?;BC!8yu5#+UY z88#s?F};#jD#>UFU*dv-+$PHeH+a=Yg>+up7rf}70WU7}S0PAO*p^~8A>8&7o8a;g z%BRovig=!}v4PI_L=8cS*u1K%tB4WBAH7q}!h}oZ#Oy3FQURs{O1@7ul7yi71G*qc zOsMGFv8f^G^Ux1t4GBH>B?xBm5a9&&kYs@iX^3{-yOH_N0|PDC2cQKZu$ScI77RTA zchUiHfQ{Evw{-)WBGg2@OTu0rV+@pIU=+3+>0f$5e()gpSOofnAqZ3fAUy5sy+clE z8o9)*6&^m~UQKwyfb)$Fs7Y~O0~Zlp2s8_J8RX}@y@?epUJSz?d~+?`+@jG*Vvoh$ z_2}9)poxG-31b}ewS=k}TNj)bL{GUSkIo0CI;K(v*grsEfPoRsjBcqd{jCZEP(O&p zI2NWc(*eq@)~BF)AX8PNLOWwx-k-x8@gOdG_U+C+0mD~B6}$?JtAFedNH^3kv|O}^ zaaiHtkBi}Wfh%HOAGvnEIq3L!n849d1;T1egYtmQmerm4js+L7(jJ57(i`v2^uM&j z`uaSa6bW|-2(Lc^;A_|$1+w}pn<2vGpMc!JjJa{6G|u8yp}3k_QTC;yOf1Y7Zoh3l z$WW6n>{GYS;Y_A@=1_FXv75hncP2^vM&$3` z0s`X6a)Ao)YIdp|07v0sS>FT`_@1mZR@?HA=aZ6=hH?tux@#p;D`8y8myLeu3W;t=%k-jB4 zQMPpQ*`*((Nq6qtH>^1KoHv-sf@)x9##%$u*|6##oA}`Zl^ZrkBoP63Ele zm&GysOPV*6&s^-roa)Sboe17n`)aPFfzXytqI)3xbNQ#y)#<{PrmSOJTx8$}&CR{g z`I_at_E#Qdp}F2OTNK?F$U2$mgTH;gbfAr1$3Vu&C{@w0sgGjyZ;vovBWnHyZvIPwIX2<$|`^l9kYj$3A8$qV-t7PO|=k3!;{ zCWN#GTKgufeAoxCS7PTGKKdn(Wcxb!X7_BJhYTvEzZ&)7=5ALzubW?jan4iT@p4`S6 ztX*h`e7F$nmJ^IOs*F>K{CMe&x%0@0cwp1mgVkjJj3wgkI~PV0+pgqk7r`_XATXK- z(L?*3g9x-1syob0!0MrL!-Mf5TZz07wr7Uz8+vbjANL$tXRg-$s9{EauT5O)pWqMX z(TuZ_ZykRv8C;`Mcx{!G^GyPz^BpU`(;HwpP?qFoN{~`}R24OM==75NlWkUW{UR#@Q2y)uz!D z%u|g1lmSOYP%)OxA5eOLGT;Iei5EDbfuG3y=TiC!i|7BKmX;O^a7O_%I-kQcBMN4c zv$J!$S7Xn=ufT?|X8{FA1<`{*R`4_-rKy1^oXulz(aYh=V^qgaPRRIbM_7J9A zdVn0!PG{uj?}f!TKsaD`(|yIkf`0R1SP;sT=T@Apu1L^F%4Yausp% z6>OO$s+o7RY+eN^g=+wa*3JW8Ht5LagaTN$+MGIp;`mB2fsfu_62%+_CJ%Fy#rHDy zrBDXe@-IC`@h;7?zD=Z+W+au<)kATDtEV+t0!y0q%5CcTDxQcEEItJ9x&eoASR;{e zHw&CSn~HOYz&EzlF2odGf*J8mFCgAy6BEzUu72xETl%Q#)OC52nyW9%BV8QWcDo= zmKF^rGfh$H6N+xzp4w?H8?h#2k-8>pylIMOJ+vn(I^|A_4TmDx*Z+s6vjD1kZNIik zNQWpTASEFnN+T&D4FXE1C|wfLB_Ji8(nyJPH=FJd5b17_Ryw|WpZEKp8Rs~T%67AV zPpo^bYhhCjvgDu>=?)C|nR2~-_x6Wt1Jw-$^G9v*41rvEdCutQfoKdWs_(XD!7l`7 zeb_CF2bR_jC}LFa4f;>q+7&i{P!O!dy)2%ar*@YuI;?C4!4CJ1unB(GCwqkI=%YF- z1osfGsvxV8kw#z80$u!REN|6-dP{cs-9x5fl85siwH3mCzk3egf$%98{P$C}?0qpP z<}g7lR=DA@9DgP?{_9t;hXHtlK?H}Mm_5))7xtau{%LG!DX-(dY|957E=VG8Lc)gR zi}kfNyIIF^XvcwjJoxV5f&2Y#l4jc;?cpJS&G?ruW45j@8mlL_kvSz803($IDEfd{ zGVegrX48q=mF)cD3Ij{_UZJ)fefiz1K>J!Dtd%J_km2Fu)!xmw#+`__a^U%^&8D-4DH+} zPxL$+cAkf^*M=8A#=O2wpD2{<^)G*=-~x?geCE041%;`R5-r>~P%HaWiyu(Rmz{L?Hyv-jIt;b}VDyNSa)-#Rkk6(J$_ z#3p5b|B2_y_{^n#uBPj*I#bvQj$7OQrC`~jeja-hV0y1T{`Fz`FL{v-|M6M#eJOxt zRyXwQ>DALFl3zj?ayz~c7t%v!?%2h1uuZrhbe zx(pv5Qx0;I1E&LcTa>^P0e~nN9upB0BZ(H@AYukn3CP8Of7R5=3KlSbcu3)9OG-(( z3W*pg2!Lv9hp6ObK?e|$osqo+_*gj9H~r0KN8%Y_-T+$I*Ju6K)#b26zAqQc(6O+v z=xBg0bNj0c7eG=WlMBc*m)GT%J~HtQZA6{sl?P{A#UXm5NKG0vhKB2_b8r!seAw3V zygE#S$)zaV%|N6AgA%fa0f3QD$r*Xy!Zm;vUL#0Xu*zz{fCZLl_{4$W*aioypwUfw zNUZ?Y3YHmIJ4j^Q^2d7Ns49u(;BiT>O#dwc1{e^PhldsZ!Cj?|%`cN9A zmr>*Uz(x~H63Oz=1&zDmr4(3tAWH*dgT5#hI}|njehG~8Ut@@lM?RBF5!kBVwm#JB zR?X@U-f(4zGJ7m*JTH?sd0<_sb$O%=E^$HYYHh)FWU5jWs3+h61DO%IGgnpF!TaD! zxNoQ5lph?z<*}XAo{T6?eX5DG}Uy9AzR+G(I*t2vTp22(pyc>kXcY6I7 z4blJH8F@C>3_rUuqB`1P)Z#<4gdXVYt17V%S8W)N7W`p#h;+p}RttJtCdz?QHaB3G zI%sIdFw@3E%dROdhq=}%joU@1>=9v0`+BM zBR&0NQ6fs;0rPvW2fR=CdzUk8Y$NQkI=EV;ULJ4$bA>7q&e$~mDE6iZx~i-_DQ758 z?c=O^7csvw%FEW&{#}%#tF!Y~wD3%MrMek;_U^6LEI6yj%zm?lJrQ)$y)FG~*C~N^ zX!)wOUA%=v;l6L}=N+v5%XSs`!OL8m1}{RL6Z=?V0`;Z0L$r#QXNMgt|7Z1u+m=3RC{0hm;fZRqd~ zDBCr>I9>onq(o9rcJwCo8NJk**&cVkq{~ukF5)v;}Reja+kx@LP zp$d+3$~SjyK8iN~x72aU_xbp0jE(f=5{E%jG%oj&HF53}+qvM^Jw2JbS3-xm!&KXEp}SXnTC({1WJKLi zOP>QhJg(VssBNvDdW}fXXEt{MQPuYE*lQu(6GSTjRRbv_c8=b+9HlOY#z^T1c;Rq7(U9!*?Kl@k>YjFbE?e_V_a#v9ZxG>@! zn+U>xFg)&Rvnz`D#5_J{a#;BHIO%U)pJpL7uIl&J!+1P1ucxY7TL5lPq1&!TzBf0J zubDlqXL2b8XJS$s3Hn_3 zuElnb99!S{Fm=O8h)*E)6P=WZ7)f#NN={PyJRINj#*OvKNo9j1OXch8J8(5k%t!6_ zAE$2X(0Fdvw#5f}%{$1XSv-+Mm0e_S6cYrFJfVzn!k_WgrGrK_J_ak*k@asj6D#|ZJtWl(8uXB{@9pVoWcMd>sEY)<9YW654yJE-RD#lQ z<5{>YiiY$K*l3_&cHQST6#$p0kor0pB-xNA7^II9;(ld@ZRjBAQ^j+DAv4Oh> z&V3LUcK62B+~>nR=Iw97Iir0{*Y5PrMe_2p>d8hXI*hDk6jR;fx3*KP|G~wgp$Sf= ziXn#p$D{#GFjLCH_L=V!(wq^fZJ<7Sud*nir^x`>K&4OQCo?YN$B4g2Oy0#r0-J=mxMjzGOC~Z`}0ZO)gMxhSLA3haNZtlC%Cg1hJhsjOpJ%_olaNXDYvzTtM-uK;b&)^qPYRCQkHlunf?ei?Wz(OY$1d1U`hhHA-m%5BP{Gb8HIth% zZ;17eGpPQ1gLG2AY$nUly!Efo#`O?=u^~3eP49N(-kv7~LcP=$mzbJs3c~5teAPAN zhLF?`&}CsH{ZG~c#PuW|D-eal0VeA2EjODNV?ae-=9YqA0)1$Rp>l8{(l8j`G#NU2 z%0mpGFVfOd)y6E*uh{o-;bIu+9+#i?!0F)f5X-48dL|}X^i|-U*EK#Dj`(G59C$_M zSKR9UJ7Luct}M37m&LWHjPqS{A>O&+-*XXzW13p6Vy!Y7?sOu~wS@1jS|nJMV*JzR zRaz4EMr$txuf|kVGQ}~&q_g(c81tfcM0oXj=vX*{LNH#CQAn!n$2(gd^P{E|=3kNV z6l+L)7mgyxj{1?n6*qrMFO_xw!1av(pr2RMY9td6lkQnwM7_Rw8cv%>*d?ODHHh)N3$Bomr(+J zoWq~;UizC$cRx0~q;vZ+Wj@xnP=BmiLmm7h0t4rC%VqDMT4^%F^7Nq9BC`79X5zHV z)&X&>hxLN+rBqYtnk<%GnP!51?^N++vTjQJPC|ZITH)a0C;b$OESb)uy~|dLrUS-& z4VxN`mdjHzBxywR#N+7m%^H5E4b7(Wj@Y}aYcEUQ(9NF?2-kI9(zm;OHbGoT{)%Cv zndkZv$3AmR?{$g@-yh;F&f*)A@Z2P+*>&nFk^8=^asD{9=J-V%`yh=?&m$-$e!yoQ z{isU_hx_7-*ZF~Y+{%}3_S)3?v}e5~B+Oij>vQva+w6tLW}c5F)h~(WFE5qPL~L&T zMcku^6}(bXS5AoZ=6Uo{x-c?oK;+#tCw__9sTj^vWz*1yGe;5+FU9!X{`_$_;KwF1 z3i|xRK*O0^-_7{9UY+7an1GsoODnxlVj#v>T!x~#1MM&@#?M~u;-}=n*O}JeMQTs* zj@vD2t|p6m>iFa+I9rX3))BMa2a;y(T@rVw@)+$qh&}(!cpYvh$#w^hrU&)C?TDLK zWvA?QIXm5$v?*l}i6jk;`v0czIWuS^TiLG9ChvIjuFw&A zmB%_Z>%eD52A(gi_r01ea#P}+^sjhZ52PlFK8iG;cA7iO*6Dw`t#@+E?}|tjUyJvm z0QJsp$Cl6D;!1t7mV`Xy_@3=P}rMWj{VZ%}3$jTpUPie!40C z7M1Fn%(R@k8ND%T@a+le41#!REd5to<@`tU2Q8DemwRI>fq4Fb5;dnXIYQC{UOxBZ zMGMF)$oBpfKKYB!qkIFk8`oI`Plh}G=C|GT+E1%C5zKzv+9xn&IRKB-BlhT?cF2u@ zVGmp>Iv-wIb1Az1CJTK*ffw+NgOfb;jq}IE(p(eSdrUZ{PJbqzgYW|jAr63JX9U-! zM9v67frOzM99X;9s%Kh3d4=;2E#U`PDq#CN=~ZuP^+CB^12;a94!{Mis-e-HD&&SF zvcWVKDUZT>8z~C29tJ)>js8*C;$Q-747?oLp6TIXq$mo%51a)%P3P9in1y5Jzytzi z7btwt010+wm=1$Htd3-D0jb&$rd=kfF6b~_fuuf+CI!GZL&0b34aXe=JI$Rwc0@nC z9w1*ZFf(KR7jQCwlRa#@aH0VjIN8|?U|AQ6FF;xh#y+`~@qbfU-uc@hj#3IWt$aY8PNfO6PSCLg|rup5b zXpCEHQ%XJA)0RA=^V3R*!nFOTUN%#z8#|k+N7^50e0EZ;J9S5kNq$~jd19*uMAlG8 z!f6BaZ z*aiv|wB!G#64aS%UHmX`Wa z&<0=T_%5zhkmh-PJyhnwexl0mz>Tk`ZKxXzcW2DmDTCicowDxl|xbLi&r-D zO_T|=jw`>5VpyYp-CsPVel3a>K{uY|m+KI8X6fjd^MPJU$5^gcI(IZ^h`rYSvV&hW z74SqCQPoezNOE#>p)2C`(8>Xq`Wv|-n&+mu}410XmeQl(3IU4VBe3^2wDl)$0xmi*Mbsn~aoPn45nPZ_jsZJGiRy%hFwsT`$>f&^~oraL9h}(4}c;z5blavuwk& zX@uQmyFP8N$Bn&|^+fyXbXB>I{@uU8p0z=fdBf@3#kSh5hQD+?a4oV=Nz1*v5W?LM zy5ZN@lUloIzC(Up^y8D#a`5y6quH}+7o!1Oc`ih+4V81eDjkic(BQj&YlW7xb+Lul zHPH@E8#Cwh<8yng?@C41BT0Vkw`0*UUR4FB2_;MA-ys>%7GI3-IC<=vK%(yz9Z%JC z_gcupWnog~O;JsNNU>Y$JlhfdwGv`&NPilWQhU^7#%X}9K!iIsDNU>E5MQ@v!X^ze zpoqQg8&W1hr+A3kqvuyg^9Vddwf!OV7;1BIZklW@u22ksc$=**Js{2m!#Zy z*V02Di_=RIU6fz#P4qg>_m!GXZ(d(GaC-F)mpT3$I$c&5g2efm#qr_fxC!5G2Cwt6 zFI&Uax#gLN#z3r-O|HTlGmExi4(DdBiEJ(jBi(Ec&1t@3w3l36x(0VsLknk z-elqV`NO8%aEonmlf}+uua7!T=+vp|;*z;Y?r!I*PsMrI!P4uH+IrEUN-xj&@augH z?5VkhGnVV-@!3q`f!`bc@p|4dNehhSi}9KzSDL05c<&NCc`5h+o!n|)o6e7-q=SQ) zyeXoO{lLl_tmuD1o9MNp5MnHL{gd`cS( zQ1IB>U~pb%COsrfPQ!lJdTXAhTNlTrWpCZd;8082&Z#1y$m9N?KHg4zOC06i%e<6niK<& zEjX>FxZu_+@#a-C6edaZ8S_Un5g5xJpnU9zbid#D#0553@DBrw&}AbdK!RljJmgKM zYXBOmCqhQykYj2HcJq6jaUlzVz&8r#E&ya#-^>iF^<-E`$TC#!Tx{ET*_$#xsqvWU>y!Je{_VVa&K0{vz^X!n z)pEW`*IiMpQ6^grmBnt=)tGiAnhJ|Ut=)M^F{26v`wlUF{(5~#~5vEdmCM(Gpvy3}2A zwHUUXoP4*iM?1NV6Zw-*(=F=#*?Z@6oJ#apBVKW7s-uB%V&v7rtRFqkO(>%o6uv^R zq2|Q-2B;*&e!JvpE2H4- zv~PMMShLeE41<)RCT!$fE86#m(acEaEi>i59#h;kOs}2mPmm#VNZui}yQ;xI;f~?p zrU|-y7a&O%`XN8oC=UJ2*UrrSeZrtM;-DOlim~3ep`TF5>(MIzo~plk6%iG+BpUZU zvP{-PZbw6*a2E3z!fgV4Q_**0 zjxxLjQoLmA-k7?+V~sj>rQiGUdvD|lXNm~cN1U7?*hA}+_uudm88B-8@m`fGTu`C% z>`pqDaBtTGljSdymQ-TRp7HPXQq`c_??tAviHaU)oGq9^wCiYjR!v zcKP*FqfQ8fbRtvWz}!SeND2q26zc+M2_{-;8+9x+wTulHwL;&1ko<^AQFs|UM*KlD9;HS+z&6`~=m#7mb=<8X(evi~PWo8t%?8Lu5D#t73TTLYj0sVp z1mwxm`g#js8268k#3GKug2|PPjD+qaVU#Ln8O;>w)+Y#i)U{drE>7)V({i<_)^4aQ zj^n%uvoY)wKXspWqO@n%>YgyEJ{-Q%TkCh|(rOG155C~L9%OA0s5;DLL>SMo)oXa! zpr_tAG+t7Fw~{E*)Lb1e;wMw}e4~G7{d9}Bg?0Xn2cNCPOS?bG>fJhLJ>mSt)cgM4 z0kV^)(VI7KI|~>Qod%q1*o9eB%aca0n{cwLVcQSUHCzx4o}Wv(+Zz)ex^ABaH>_gw zTzWF#(Q0q+9{kkDd%E1xCfF!Q&h~_JptH$}-*QG}urQzKF6AMAYv_h1Nwi1myg_YN zyw$&p<K%qL%JhI7#O8@bwD`bsY(vC5IpT$z$w-1?zpU_CLD)1A`UgL= ziy&E9n$>wF+J9313{SqekYFHGf(lM!l*V^*E4-K&$<^uhB}LxfiS|>-cyKPnOVmgYVLtJ!o@S#vu(u~|yXPuW`-&98vg~vMgf#v#P zd--t*U$N%E784zC}A$I3jjo-{t>26lp!Zsj${ZMqdJte1Kt->(~O zjV!0!*WRAp+;rZ(z8xa`WiVSryVZg6iK_TjXSVwnb;avHcV}$rjvD$1e?aPc(AFbI5 zisyIU^dLPP-@j<0_B`52n&BN1p6KtXDBJRP_hV1t)NgDa)qio2&z`#2`HJ!hQS>$8 z75_Em9CJfB8RxZl`;eDqg%?(Fs-Ki6y0zBH<|F3?laedGnKz`GI&(%e{O?|NWh|pO zA6V49BbgDPCgHVVcty4t&fdI=KgpJQ-)HYtjRSwb*PY-ZRMiI;?{MX7$R4MldX+qH zM8ohE^77x_*&Af2F%_NSP{q%~HXK;ro4GY{Ddk{MOw5yG-=;t81Y(54HVuz!TG&`b&Xag zN&N*EC9VsiX0Y6+Ktx{I$r&urP!$uhk}s;b1NhFCM`Na3&=-d!ej?ihAmjD@l%!kk z)Ngux+$pd_4M;MsjZ`)^HgE?8B{xEv12##RRU&DmdMB;(_Vmi2L`}owao+j^}&wO(P&^};(}=t;2_8x zF_PTM&3zAkfqy-@Er^H_dFci7Cem#RW*ks0+Ye69&dNXmyg}u4@qW1HD^y?f^@XhV z#oNPF-H3}ERw*%Xhd@RWf@I8!2gvGq2p393K`urW(nEK8Kdx5(oy4}Hhe$K{NMVAe z0a!xm9B@_zIa2E~K~4@D5Fui&2$Cq0ga;<@yUSop!YiXNr!P-@SWKQZ^<7rNyP>gr zRN1$DyLH6KjK4|F%aK8qMnOtuSvhge)=U7K<*zRDm&XeFiR|2RJcfeGbeS>fch$5M zTk14%&Fcna;|8H{=5?qP*28?0)5e2&YttX;WMV4uu~dZNz{A_Drp{9aDWSC2i2fmC z2JnD4*WCT*B~Jeb9?)} z&4nHDGPo^0H>3TzSmw^2VOU(ukHTRBftOM$r#Lq;)$+fl9zdPXy~@N@EAcaJnM1Nq z)m3OvSWUu~H-_=PMv%d8 zR{`62uZ^Wq`)5Jb>Tz6L+}H8@Prj7x9piWP^(B>*wD7>0i&;w=+(CLjBlLiI7A|;z z!8_|fWYe&Zp5}SR3|Sp8`~*f(0(0Q&TPbMdQSAu>)|NL|AR(WPgtNZQg2w9(FZca&p^O9DrYj^VTXPd`Y7`Ve8V>?G5wKE+ZS^LW`Q*Ik5q% zTMQq;SZirR3iduQka0?guAs#O&vmxVW9x$bYyKarojNWQqgSLp&zBP}yTn}U>o=-= z)@#*mduo>5PxJ^qH27=(2{j!dB3OowbBizTA627A@_S8Df62!*9K1y|mFdPzQARQ& zJKN&>vtHpLi*5>kW#!KLs=jXb=b%VGRCJ=0L)xyh`pw^JNf?stmBfLUqblv{^+_P_mMM45`8I1uau3o&Q>n27N zH;=z!2AYVWYW!xqCM5nY!cfOjeb7D-ADP0BGWt{V;_vC5GuOJ!Q{hjc9#VW7BYh`d z$l3$*v9Ap<|Fxc^U8RXn;F~D^G_gk_+R?Pq}0`f*CY2g#fOIL z`lYV%{n*^Xca~XH3gSX>S3XayGbH@PDR?BhjCt$*p?bcMciACax%(%#(p z-SVhXgLu@I&id<3D|?hU;g&aFGJbWBxaml@4b!@s>PSQIn+`KG(pB!dnV-G2?Xskj zYh=bIv-%CYzm?D1ei@_Bq*4T$_PObW6H>}@4;(uJ_*UaOYdISNG;pWG&-1R2Zd97c zy10KJg>@A2yM#PmxKe{Z-b$50 zL4O*Lvm((gY zxAR_?N36qr1^N<@sT~;1!6gG%h7N8Pg6sp)4y|m|u#!U$K)-RhX=Q9g1lT)BU`b zCr~5+Tmn_9$e`$Yn%85k*U)}L1htA#d<|Ix$o1KR?*QBYAdJFA4ce;}0BW?cu?MDp zWY!Rg`-Z2yGyH)Ps7}ZZF!=9H9grJfxe7tvbE12Sn9sqJg<=Z@gduS&z(WJm!FzDv z0S^6B1>t77in&N@IYILBH%(@l!p5v;b7Ip3sfW^4myc4^%TrZC#I3mtW13XvUu_l3 zZeqtd$hz1XqcP4D=fwV&^@@vT8r-peQPbV?4KARs^HLUB5vz{t1r$XZ4k^|m3L4U+ zR=Ly3TD;hS;UT$S%RWMwK}&mE!U1lO@J8P_Ih`u>Zt(cyF?26v4YB~aX6R^W!#`)} zo62#YqJu@OV~eJRhKmQ++%HE#CUaw&wqvW3(E<|>(-<5;5MRS((<&fT`y3gBsvg79 zF{0E^m?T7w&YHlDp^9Skc8LIcgZ+YA=ciShQrUBQrdCl44{jrz=pX){h@N^r9di># zB`8d@_(;7dFVfY;sOseWWYA;YUE%Dry|ldCvaK?qodg+9Ol*wz3(hPdEVTg@xfiDz z>=$Zfx8lU}QlRn=hH?QK%)QI%<=-AW*1uKCh^)VY*x1WZxf=aY`PitwgQwdhh!Zrp zFIRkyjhj^T+on>%+tf%`lWNlpmP_+xaeM{48@To;R^qevWeUHnhJ~!|_if2t&BPq! zJ17=fuhu}*&5c)VmSamXvd=J^@K@deMpUAhm*9SqsD?)1w|g*pmwxrr8HDZ0rprc} z&F*P^P}3o7flQDtFN?!#0uK0VR(zbOZ(ybZ+aRF9_+3VtZp24NLsI|^H}~s5Cg4GV zCZUjD!>z~U)LJXw$AT!#cd-|1K|jSQy^5V@EJn$o^0SBDW`nc8n@evX4ga0=#oU^k ztHIHqQ`+Z(Cpv$ZZq@x2N`;dY1k>xCc8L#7INsrEWU$18H}}Jz1nDB|v&{p$-o@Vf zD+F<){^5^@<0X$zj8i=w*;KpglrK9&buRjw|2^eA-BdwgZ#c(465)$$Ov1wGb%}Rr z@(!i(^#AjccdJ~#)bMqRQPtsoaeRrnHrBCVV`@mW*anMU-;igM?l$@jhn*dR@;8;Y z)b6YO;fNDAC^sBMEqS~Bn2KNNyLd*65L05gQS`W!J_0>O(b4?-Ey|r|C0gh2)dH^V zH_qb_MQ7aiQHs~*x*kyT_lMT89hV-2`fQQ2S!-?Vs?vQL`#q8~zw@hH>{V@7Bu z1ED{XpMH4=Oi#GqZ~^qwK$0rLvtfiQD;Z0|^9QuTb1yUTvUeM8qW& z;T}IdG8r?u7idcP%n7&3lZ7WKwhl4hKXNXcaK2#Fz|D(?7-V<(^Ly;ovxsq?0KQp= z9fPf|DVw&O(WM-pra8UaBQDf*bkZmRMgbiB-L~EXvncpy8(ZbU|MKmfq>Q$!qu14> zay@-rh66Wo0xw5wDrL&IY}3Y!(T;I;E>GB5BhPHcP51Aw?>~^Zx(X~wT+9y7D7t@3 zVUhk6!9L!%>>Uutnwp${lzVr<$>{=Fqp|1rkv$+^LsDwkUJWhYPs)qr|CIR12WH)h4 z8dq>e_U!uZczJmZzY(8!qYuvka%n8NCF22&TenKUd8#ao>?A@qEFcME#Ylat0)_fF zj~tCDF?JUiv|;c9`AmtvHdxc4Xb#M@hR~dCIa%fphAx0UOM$Nt@=ajdM24l{5DYO* zJY;GFAmdPf2qYj(XnO+~2H!VF9T&@X4=j3}>=xmcelk zefWD#O^t@b4m@_^5a+tOx&kZ70TR^Nehs9y_84YW3AqD!pS98W^|Ur|De#xV-$Lu1r#+CMTweV(_5& zg>+9_=wIPVi&k3i++0TE@-m4aPH86tCQY-RE}ol3*7w2Iz{Sl~yTbJHQSIoD9|lfy z>Uxi_?h)Tp(RkGjH=&+@2cG}^AM$a0b}JaLX2XCES)B|P<3k6=lw5(Jp!Yvt#1Rca zmf!TpLe2q4TvWd|N)H7Q<+5!fEZDMmu>|)?`e6Pi*|%2f7A%RqCeW%SiEW%`T`tOT zU+fJd{|>mptwt3ui*-HHi3ADo^VtDsNaIA79w>E~li`SX*g>ARkYgNnL( zP9ECi_6jcLOij_gQlox~Z|s{ID8AEct999}US=ne8hd?|;~n_Y@!iFJhnzE{Uw;`D?m$X=e(#S zMA}smF9X@L4h>gMC3yFi`UVDG%d18VM~QnXUd?1J$5FKPly)N`!D{gwA|!Ac&ofVK z{pzPBC>vsj-j;6T(=5s!M#*AtD}DPz-voq#1KeV#DkF00>jl8Zm@Mp(2p2)v{VA5B z=UDgx3!s1#7^2`y0y9V#xH6!uyz(1OBTSc&DSQQm(1}z=g+#ybaC`{7LaZ+^ZWunx z??AFDfNqwV44#djPuggP2ImC8v;Rhb@NbvYQi0aQz4u^86u$hcicISP^|PnD+jfHc zp}Y9_uS9;k_NMx*{Crh+7))(`y&Lpo4uk#>zBWboVqM*%eGT)_$Lw1o*QZK=i|QU2 z0FCvP1J<{@zg}NsT@RFS-zzOvk^A+1e!u*5R7OUTZkF`%msc)NmPteyS5Kh$`p|Li z%v?}iSKzjdD6b)8=my+t%Og@-Fiziec^2$5J>cWKeeGtizN@9mo?^d6305&dDe zq&6Mip0Pi5Nl;Nqc;-RtLpM?VJ?V-6t2E;eyG#;0IkLQlSj)G{WIAX{E!#5-UR#Dj$ST zW|^62ASQ14^EE}LZuWP`bqP&qmB`C-AcQa%wSSwTz>nx8dgR{r+5BzqnZfPw?Pjy zW|L3Bx^$zl`QgZxi}+YvXAs<@_&G`b2jaG{>h!-qXl9r%l~FyTsh_^zW2eC);rf16 zm`)VPX!48S?wi@&K1^1c=7e zK!-!R7Ld3cAZWm11=yaxDy!)lNTLF5G##2KA!LJuJ%TwvT25{mth;ZXeYEBjRgG?> zff&t_^ZQt||MLQDZUUQK4mq`eX9JM#D&W=?7e@gl25BgUW_DtBJtU|KxTSDu0BZze zuZ;Wob~S~NYYeR7kfoOfWRN7vFCU0_!S5)Ad_9ELVaq`=`28~v%0cgdGXX|5(k0kY z_dgb8Lf;j*knxB-GlW50Xg4v5)A*c6ScdLv*d4bG+)2oP*H)Ib7%V)vJ_!(?zBBa# zrp8}=XQ;$>pWtlKgtDYn<(-yQw``u%=VH!+I_Ij-ZH{aAA}sA5hHeYi6^Inen4?3 z5#2VZ76`aqVm(df#lTPavEcWZtTMAI~{5}yBfuS&Kg`PnvwI7PoeR4F!XA4l9 z{_(fQKeuj|4Sc(Z_?d{rVoYQR`CyV-JW(;J8h07(c~pU-=BmYR(@DxOY=W6pyGDIO zC`e|aPA)L7{JqYbR7bvRIo4&`FV74=nvPMB-e>vEef(OjOf-KrO=~;C1OWjIs8ynL zkPEP2fs(vk`~{`}nuuqzez{zpX47$6Cv|mgqTkJ|DN87#KB-2blLuYZ-gthfK^30P z#u6&7FxT=$RpsW0D2sbz=Afc&X&$gUv(0t$EXl%yf|5Hp$V}*qE+~1$_`LzoSxxRj?P|PKAiUyxJ zY_%O+Xk7yUodLfm&hTX1xiUF1S|f5z z1mcs$M=HZrdHwIz!Y#TIi`Zj2Vh)<- z&^V$24YCvTvEN@B4LH19?Qoq$a#v+lQFnCb?aFL^U=0|la1fnh+X!FsDDy9G3J-^Q z4x{PR9LVbFU8!52BA(8~MSJHQ(51TkzAt8)BJGzy9~(NCfxLS9^o=i4+-wjZ7wVEU6DU6B zoRS6%X1!m|&dUs;6t_j6bH@J5Z+q%MO4k^7E1scwNF#j*V79ZRp=I{hv61c$t12`({R!8k2!Q68-l6G zY1EUpwh}WOR-$CC@SFOSKk*4B$q;^MHqD{x&6!T35<~@!_Y*l5s%nq4IjnsS=Re*j z79X%NSkM(d8FcbpMfj|H;*sdzMl{~~yJP#6ltBlZ>DetQp76!lOglN|XFA;4-rYr3FGIx@IDA21mV%{P`qf7d4yFiIs0Let@^ee* zI^|!X6J%${_icH66M)&P5$ebYxvqMdDT)-MFYIAixw-a0p1LhV=u`0zs#Y_@g=yjP zqFHW?tqGZqQBqQZ`N9_-D{|10zFyf#_~}k}wzc^}CJ@Og z9~{hq$S^=3f{Ev$Hsj=U6446i+FF>$cl1a?Mh~_-po|ebco1G(%nn}wmLk|hKeZT) z%M&xKtS8&!6*nG{gS8MgQ_w&te^dTJUG&2wBIUKFfUKHs{fD44Z-a5Hg8$rx$%%>N zti&OFo2pvP5!E!=J=M^sT21*fH3EA`Rl!vpQYi9tjk@7HrY!V zW_%Ut!oyf;;)mbHaz`o`N8*L`^HyyD<_!0)yXX1kCou~S%MH8KseT4_&u8fA3K=2se$;~lpKGq<1=5$_hK>&gCRAo_=F`^x z={KVmjTip(+nN(6qTdMjg(7aZiF5`w?roLLLVoF#+88Q*+~|*m72Ng1IH(=%Kin_) z;-a~^UcBHqACcoP@k02jijq3uICHS}XUs!?CCtjjtgVYsdgubk&DINau_a=DDko}P zM^$YvN*kIO#a7_sNU1&gr|WW+R}sZh5WI@i9bfxs=@n#W9BRS9)J8(Om9Za{FIhd zSy|!0{$v=Jf{!g8P`jC#WiG6qkp9^E2fUYH`f@I>w#ElBtxSX?vO{9B(%1wTn;<2^ ziG}GIwmI_Ny+J(xY^v;)ZR6!;Na>N zLPX)PIBhLXQfYW<*GK6kA5qRbIy?2LeVx)r0k?(S((KhPKg!UOZMDRV?Us*iRnIhj zco?#~OJg8LEOI$*BIy1)=0Hugnoq6alHU_iAJFwce~^VyDRUo}&b8OQjM4e#6|0LK z3gUdsTu-CP`}Q--&->Ukv@|KsUl1sc&hH0(rzeOVc#nmSwTs*v?%n#zzkXD$@ytYU z6LFpp?z_8oMY6m4JvV9NFxX(JU!UXjQ@I3JCe52oZ1+Meg@QW{5EbVhGXIEEFl zwRq!GuxcO9v~z~vD?KQk);#zWx*$WcA5b8duyg#t80*MmQ8-ll*Tn-XFL(cdA~*jd zPp5`kVu3O}v=Z10FJ^|W+eZiR_y68ME;|@%+;IOmtd!8xO3KdV&9h@pbz#MPeZ15* zv-cRab8vZ_bC8kSgS%Lmr1`;k!SeVxj{$aKcdhz$EI03vVc_#CCqD+RqyT-dM8w5D zS!&a&f|dgz{lMkJEj9h{9yyFdqARdAeNA(ZtEQ@nWSlN^Mh|E4WE_=<9rg74*_#%eM|B84dI>sUv z@s%!<{d4PvozI9kes$06&-og5>|tdUDfIc>*I!!goZs8SuC`r$;5vNziQr2_$HVt? z3u5GTWW2WXN{A&N#$A)qR;3!Fs4RrsZ<`3yxSZlwicTul)7=88$NLM1h&P*ULML62 zf?F3}xay-Dp0J##czSVBS$J}>?{wiZ@M!Maw!|_~?@7#|2EmqD__!4s z>&dioSL#H}xOzjl5wDo?S9%%e5U!u|4njv531_yVqkB z!BvvAKz!TA3lC9$n@S&#QOVbaRQ?M-5juL+zIqEDZ_PQTM&(UK3mS6{!Km{GQd|}d zjg5%$jfd{t&*-i_nJ~<LH^O$Oy^@NKFa(s}R>KY6k3&3_v;I<$} zieI4q^rr~K!?tk%bW1x(80Fnbg50%tN`KSU*%mUN1eFOusYrEMBLjRngwivrs)%7P zN=!hE!hZz zs7IuE&Hlic|6>|UXyJq_i}*p7LorL%AL*y>WS`B>3dO|Yj`2Of%yI#e+MW3}U?_jR zcj{zCcT2}5H@{`FJi*v@y%$I(C zTyW?4RM7|gqeP(U#{cen+xrG!=k9wxvzp~9+IKtoT57XwSsxB%AOHIK6DMg0aR&_i zGy($W`YEBx?&=eY2N$RNGxtws3GuqQS>qoBt@YYK@$+L z`XI0jX6|m_6hM3dnv{Rc&4uX|o3#320^1x~2IYb81UmB~#0*x!TCtKHuSW~b7y#J> zD~7~UZGC-GxX6`8vNI&Wz*mVJEWtrcK212K(d~E%MuAZB2LC}5axxN44xK(wHv&z- z*zgR(j{VenhA&6{ix}wN@SQ~p63C)e(AtaYcb>tK4WKk4_G|q#K=cCtIfuz01(HJz ziZy5%Ur}1%)g!6!z#oCP7p8XbIM+gzp$iD}fk8n?M)AVokO(8FmEduCCLqAf&dvzB z0(3-1#Ku1CG%3|+f2MB1X*a7(YMDQ>{?ISFi_R~yN^aAmwe(_Aj@vey_`Il-(T2U% zWlZ`RcGEccOe*L*DRBW;e&O=crclN zi8f-`^zK9YPx<=%F`d-vTjJghICh_ahd-q?^(X2cmLJ16qBdk*xl;u`CW{E86CSWr zc5D?rhq5rEC;pv2E@=U^9Z0tnY$A{J!h^yHQ|=;Xj76R$h1l!<7BIbH0Bkt8ZAz6k zX1j(b#sUY_U98Hp^BucOpK=iPc}FAYgvoJCEI*Sa^!c}wZf@?bI|S%rvpiw)3;VrX zq2^B4Ia-Luj(^{0mR#$c+W~*YUf%WzgwZ8FeHz(Zd*KAJZ#FhmNHoljw34RlXJ+VC zo$ao#O97}22EGuX5zvXQ_Nc6)^B|G=_Zk-+r5JH_R0CmJjV7qwHJd~Tjn%bFNhB5xnRS5F)ARa*%J$-7t)@v*Q>l*>Pm^9WI zxV@v0{6SiwmNUHpHVsG?7hrd^UlnkDz`oQi^4PItjZTdYLx@oTDQ`Gv{b4+COOfU$ zya!ZuECx029q5-Ez0c0b$?tEynjW@|_!VLc)5zv5ndo+1MX;s>zkB7X?(OP<%Nr-q zSFPeMb^?5D7<@zHfF!|3JA7s3Eo6;4W}OetkPO>G zjezUN-}3Sd;fcNeZTY!XGWqn#>gsHta7tjxj9;@g%+cwv`RoI+@Cj2q!$hIwb;?U! zT?MGHfx&C$+XbdUET9F$KdF6wJ`DfI+xV&_6xj0$0A?;v# z5xA9~4|guZ3(@nDTVD^k+q`49@fSD5i#k~4@AzN0X?i|dRY+Ab96|TxAW>oD2EsE5 zn;AX@A9c)g0JT>q5Stf4wzjROx}8bR4z)w1@e-*i}Jedn=U3d}K8DDnSu9H&0}Y;KtuA+et&N4)QnW|Bt4x z46AbOx)ntbK}rSb25Cj4K{^CMLOPW0MmiKwx)EtTl>i%Eo(mltS_ zmID}wmQzCd_1ci}6QXBpDC!Jp&+Bv!Z5Q9aL{xAf*8Q@iktfF$^=2?>=}IB&y~1X} zzJ1gW_IeD?%%6~|Jyl<7A>HQi!A8;ReHoJ+!XMm?RkDD4Q_t|=M+mrvMyWI1S;!|h zxsK{2pQbC_1nW9^?blud#t_2g10yL^HZ4puqSOa7VML4sbiE}Ivj`c=@*sDn=6N{{iBNDn zXQrkK4+mkQp;3Uv4@_mD$_eE^e)7WbJFIBvUzO|)zk@|SxNAUv%2Ib=X4aExCs=mQ z%we8@#vUsC`I?GPVCYV;c-rY|*^+~%MnLhPYE`@^-$!&6?J%*{ zX~xRcJDe=8HjJKX#D`WAY@xc3(hwW>`F#gBRv2dUc)#LUdWdTDHli$SgHF1sgDw~L z8O(e!W1odmW4)fwuRB%;+oX=Jt|omp9Eh9+Sv9bK5QAZuRKvU%QesxY?Fh=Ec&MVD zlL^Pds1h-Z2IpIF!2@eAu?S6aWEdZa_2_3Oh=RdBIF^D`fB@`m!43zGkCfV4Vt|2w zqza|?2Z%d_?eY9S5y*Eg8%prknTO;w#DoE!t2R^G+k!zh>9X_;1p;A`ww4xoH8n6n zpar%QXeg_ztBIGmJTQXN-(0C$JD}HworIgm#(a%Fu`+S5ROg(db605uGGGvt6-&86 zB1VhOo@38{$3_a$N986+{MyNVBxkF@M&@}~B=Q~3gH%1eQ?^&hnXR<%2p(iBmuLzv zX2x5kk~h4+=WHll^dY!VH$XbAa8Oo;vBTirYIpa>J(QkdrOD@ z)L*0*6%A1ILN5Y{8S$W_Lw9(mp=1|Df}*O#1a}acb5D)3_#~xDdvz50NMwzM)W^- zh2Mal)y>`A#LUdDe>rlMf{6(OZtHj4$Y<1Ag^~z9Gq`)fU2KyI<|)8kwi}1cLSSMd z?hd?Gmpbj~*L+Z@|Cbx2|8Kg=$;AcYArZtoShD}$EfuU`;Z-1B6y9|3*RQDXX3_wz z1PD(aE?7V(>+9>`eL#I5%j3WR1r>1PK=FYAt?Io84>F32alu*;%$7j?)1AQm5FDbx zh`Mq{EsQ99R0Sqjh~`2-KtLvmFBbeHlY! Vo~+;7$e&7QFW9#f2h#BRDunNl6z* zWlg5eDdx>{@(xw29md{2^D~G}Qi)Kq&d_NedbA-(PfC$n8l0^*{_6;xe(8)P`;jku zLsRq!0UCLpqBAin7HK-9Spn9IiYhgCx2YrM-rK2Pd3awLBZ$8|xdTx$(Ad1AfAHRq z4+SH--TLmnQ+Hdpy#uDYJ(O7>-+GcoCSeb68pylak*|$!sS=`g(ejglg%_|02A&TP z^F5P925r!w>ZD(*gouSzo|861B2q|m33>7dphRn!F{We@J{dwC{U>lv6oLynpo>zM zc=K&@is}2aUdmS3H0(_8-XVXH_(8@Q@@wC=T0`AWQg+2&ss$Z=rl`d~f>$ zu+QN@EB3tc81bOD;C&szbK9^l31KOYiiJ5E&giaWqWP96Eq#7u|0z6!*E`%MWMSG3 zyN&2D@LYr>bh~ylm`lN|Q`tf4=rr-q^6`Gd5cmm zT}b9h&A-0DpY`r-y@I?1P#J>*7-BlSHP!ljGdI@gd9rqD5F$tE_owMkId(*kiLIhhQma=6PpkiV)4 zraTCM9>rTL6}%5|A+HFG{J_r&z|#KVVNtLZwY0Ph2&qGCRV2$(pCE%R)#V01a@H7< zv#YERN<4axjEHR4!RP%{emzJ&;V~dDpu`vd-_90dNt|E#_wV|LU`QvO@f@lxi7x?1;+chG_S{uUgyAT!_syBnAe zAkuoFnTFeqd#CmQLXj~pPIeI9gitNw;^Lk{w#?q)A=v$T1HQmgwS+r4H3d)ck8V++ z+nFuo^T1jG^BbFuVR|T+!N7bG%yIMqD1q^5EDRO$D;Ms=SrQ8X6--nh-7_45;5V2- zLJwDMOEpd@|J}wyxD>tr2MY`vb65`$ z$YxxXxNkxf!LlTzOZ|Ub0K9f70vcN>6M1o|oOjn6{=dUc@VVtF$FQQ?cyVnt^7Al7 z{2k~`DER4mcC5eY_a?<_ZYpK#l$Dn=jP6PL>vAKwqCO5s+DQ4>#L$qEyE{^g{na4 zlMwMM0YO46?4dYC!YAmJQ)v3!1G(u#ObK>&V?TBZKWr9h?4eN~Kp7c=w|u<)Qs7%r z-W&FpsuBp+=lkNrVL(d)Q+ za*A6BuUI|3G|61KBt8NtOi<_0UN7S=;Lesc+9AAb($kR>WmmC10JTW1w^vdc#unBR z$p6K!XCzw4m&?}+@#qLp!oVOyk`3J;yyEV9U6aXt&T`+xlZ->HpQTS>qIvF?aTfi} zX13NDMi7iVad$5M<#&H>5vH7hjOdyWfYB z{tz=mD$pL6!8hU5)|Z_yBv(;d`hLn5+#r}f-t1Tu6cn&k=+#|1y69v?p^ApS=?64s z;Ai!5dr}PCFySkqkd%M>_BSYsAT=A2y3pJ#3a~&k5Xz8!<)j)cpLw>}Zt)PHe=t0`>>kodHe6yP|><)^{|c zN-=OVK={-&cXRCs0Y7kL0Q3doBScZ5*BS&CrX)Ed0WmT7aNR?PtgeodNPoXiz3@K1 z-z3ys@{~>QpIQI?jRb8uIK}>GXh?>>IsE&_jF|_k-LKE5zn0Y6q8Pc0dc3h{WW>rD zC0qKCF&emE`1xH#p&%8Vc62+M^Ys#SHSVVr{q41G+x?n|%Y1CJeYa}dkJO@jl8qk8 z9MtZZB-SHZ669V&E@O9dmEb*kc@*G`^pt@?7fzm_Kw{2j z206=_Tv1^OF>#!f(7%5_c~jF;^Qa1%{o2;IlTN-p&n@^&IxqHa>cj$ykoxXU`Paux zalGnGBDwK*_p8cE?k1uLw~cej&(Lb`m|ID#E_y%bi8IWJ{`bk~;Y$Ywi?XsHq{*6U zV&Xd>!?wOYTU`WQwdof|wE?IxpkP!t(uNZ^7pAO|XVG|(>DHsO>F9#5LlzRkI~3UL zxG2?=Ag&spR}~Fiwbto5q&+vfpWTB%nSC33js~F@5-Y2zsgV@GQsFqO z1acrB06-I!HfbURtPPj8vPpdOD>?;Ziok2)NqfA{uq1bi7sis$O~pOp_ntx)LX`l6 zld`5kyX!oWeuBw)&2^FaIh;F(BtJnRRXwQz?988k+)|Zi5n)D*nc;qdwGYO@3zVfL zR*dUKgs}z6vd(;sFV_!Z#{R&rL_(Oq0{l=}RRzrmy$4Yz^S@|v_XbA?hj0jm2GpVH zvn42;D*X_Vz1kjU1}%wfuXpS-P7XnTo1LGZ2@4*i8Zi4XF*VhN-3S+P2?Q^}T?@&+ zhz0I@; znHS`T7FqtQJpixxlFG7TfLlP27zXSE;AF`FQvi+#gn|$r5Fa1k&tJcAhoX2@9`>T& zoNP@{@w`W_p@}6{AnDja&yEg@u%j?Ksfs|&;7a!i#FjHQ{wbpRa+4{;X=D-tMw|Km za!J#Z*-H5Cdo1N*43?(1y$;b7T;6^E3NHiF@Hx=Z)-0dLvM!OV33HjN64yVx22OZ`eF zqNrZ2?ahDOhKWB~V>}(R62LM0;r{;AIG^*y==(>ZNPCVjo&Nz!(uSmu#au4pQBUOF z%3uIeVhlNd&)FjUmh^A^Lb<2!<%1+mV={FH9{=|+FuLCQ2Sqlc8o1 zmO>McjKO6gBPnU^WX08$TziS)EkumY$iVRBum>V7zFx$~$HSseWkt?#tl&$WPvGY9 zhKwV)P675PBF#8?J*49DmA>q5h8_&cbCodlDlejDEe2gjW{co$A&L^}l1l++H*hJ1 z96}q%sEUe{Fg_{IDUyAH{!NlL{q+L{20E@|`Sqf|n(6`YF(PAQrC@==6@~H_Sn1GV zJP#T?$u2R{hm?c`en{P6>VqR6sfJ23ULAYW zN{BOxv0s*W9&q#V-rONa{DVYU&U4Q5lf)Zv#y9jYnF28h7## z3S zIZB|`1b2dW$=lXPjLgZ0ZU8#MfJ)wiwW%y^K3{rMjhQtc`n+{#mB|aqbDx}L-0PZ! zZpm!|v@qTe=lKq-GD*?c#Ke3{3CYRHx~f)II~1!4Cauzd*k_n8 zCR+=TRY?3(nb79MgIOy6=jjQBt6%9hO+d-fA&tD1b98BQ&<5$xDBIOu|WNn+OG2naBCJ* zu%TWYv6dZ3XnCorqe9s9CGg=EG9?CXk1#2e@3KGuSFNy2ls15wfok3;1z8iK+yM+1 z)N`Ocy0x~sxd`|YUQ^{{0pb)wjp&AMSwAV_aS^d;?}9iROJ{P*->o;V*=lZQ>=3IY z-AFbx)#p$NnD9Vq^)2g3yx|Q=uH>jF>QQGYDgUNAm%2|ydTDE0=D?6`nXhSi_mlfy z6e&6;#s!R0v9Pe4P{IXK`=fIfDj-BB_&Zky+y}woJ1{8Z^1$U+`ynSie7i>99j~%I>6r03;;ef zWcq60%O8MiMKI4D;ufsiRWAg?jjxN^b?BGKsuUEIW&0C@FCTEq6Iu#Wa%B>*kTr#O zz7C7&(`UPS-id#I4u1uWr>{;Kcn2yD>IL{2K~aMMcGEv~ri*FC8|NptMVOV(SV+)9`{~4a7CA zM#=6dzk&RTz-1uW2jWvD2C@=B-2%yg@Ah$BSI#C6v7va$xJgPd1+=&{7gk$+r7pE*VR5&43V zQd~UfjSW7l3(z9OH5ZV792y*a6s&_Jv=LDJBz#=GpR&A8sGt^%QK58oj#7(yr^O-9 zB9B5v`AUF335QDjRP^bIuakh%$M)4is0;LU>?zK43bKk)D zH73fIFBP2l4VkhP31=iSxBr3amXHPSR|;+9aG!t-@I3A8ChcYyPi?TUa9GWBM+R0&|Y&xf+oUr zXZR-?;O~s{oaU!8FB0oniv1j)u5AxBQfbuQf$48mFzW37VYwjrNgKj4^i4cRcx>#t z1BLL8dkemC%gBCl%$^o`T+0|X5;C^nt^a;W;5NqX5ntQ%*_08)Hp>cpbd%Xh+wi+D zkynMnd1P!PQg_0;61W;fmX)6#5OKV(n2KJMPZLLaYSQ_T>=WzG!iRV+4aI znh^4Qv3h{)0g!fyF1_Xm}CxudxnYy?W?Dj<298Y z9x+Bvf;j^`qTi80V^o<_lT&^n{+XGh858SRDNJAAwMmnG>#Z&rrEdt9yg!f(X2{Qs z(hsgt$(~Xd%RJq5=FrGfZpl&ek^kxt;=snl_>Ll)m9)%DL;}<1M@NR;F9|Lkm-P7W zi=D;bYL^+d<1~RjQ*{l4LQMWB&H^vLDeq}Nm2Fbiw{7M%Lq%I)Tc(7V1%Q?;BgPR6l{~`HQ(tPz8vi1x`7wEp-8CC@iRO^x7F04!^PLfr_dp1(}VwG_n#1w zBwKd%w{u3~4rsgWRG}bJMs$RjUqwnnKn$@!fleu+72~oTb>U0?{VSXkFZ%fOp7i0L z5~;XF7eXXaD4QqvO1Kx##|!^XpwL9*QKun3jL$V*`Wu_5rqYj_EyM=GPdzOhH#rhbX;U#Qm^>g zZA)qdd*bEG5epTY36|L0a#g0FC(l1)37p=7PO(LI9+6}TEhWsh#VLZ_k3t?hkh?z1 z>3Zsc9)EXz%S;FNO7tJAI`ZZE?^tTQi-_ZO%H-fiV`qxC=H{@7h}(yjlX!%LzldSz zR4pZP%5Y~uB_Urdsh)-D^s`k&6pDo|AxJ8{7wJMCCja%g9)BLQ1R0i$^5OEtW_DM2 zkt9Mgn}5ix3<;nxv*)RC-aZ<`Xv#)gqaVtA;_~v2y^-VMmf8*RlkfoNzmi`b5O-ED zyd>t%w(JznY9GSsMvJoOVT=j0T2V0GrBWDK15mvY;iShbwj8ye!)uVB>fNwq?t zlu*2gaNi15fjDOx8k?zYe@m4ty&sBePUKWvRD5nBfuZ ztUJ$6K_PTDiNF~k?*p*3Xlqz+h!l=$gOTE^2x%4yM#e4?jgO#efdh9B+{X#)U!A`A zc)CwYxrHzhE-ZXo;eK_bFj6wq?(v~OJDvz9UEBb)eV~_o9Z7x^Bgz@ylfZ@KjgrA; zyCezsOLuz+oL@*tz{>rR;4M-B zD>A_j4D6lYL-_{V(@)12I#(E5PWW$f156af<@X5JXj>Zdx6gm z4LN=}g2_v?idIYg;8oNX%icy0Qx-Rj?2_D%)qZEp)f(-PhFZ@|%mk4>zpt@O+KSal z%hx?pK%^1!bhgJ-#>|GTv_oprm~q+FW&0a{>`+8^snV3m#zcXcc}`^Ky@w&^h?^lmmI|jGv(waD>hr`XHa`JJ4=8ode*}=$5HF z1GYai$VRDrH6k{Oo<_rIOZ%hu#6H+T9N7XAh+)#=FmyZ;xVc#(K-1EFwyGnkrB$G8 zprCNu!QlZ0Nu02T#zR!Be<%Hxcx!?9F7QtvY?TTU5eJ49R5l%S0QvAL!YrG_<97v8 zeH%FDM9rzk@0<!xcQl9r%Yh0Fy=XcJXY z8Jpms_u6>|aEA>~B7(61sxycW`vXl;U%496B|ZhjUKJJ=-WnkOP4Fqs7!xSeS3T>! zqG6htUz@foYCnWD&HvUddWvkXpb#M}8|d`c1;^6NO!4~SKKBEM`i;dBBpAyA4F-h4 zEz@bOy;=-1xEWz9WX_~B_axhSD3ecX15|!f4;#81giVgqr}%>Mr94KXGvT;GWNAbk8b zh>vU!qY&YOg8vDZH97D%5C<^0I{``b4stnf%Ll;P|Vh zl@~QLZw&}(O*4Jsxg16W=P_K`1@{UJL$Eo-Zu&7Sxx0Ti2Ng2GOfhO#aWyR3Q2n47g10@QBm@5qF4hlA4jNCol z@GhaaB8NU2J~|C+nu{YB@n3t}UhdVmDmqy{k7xHxWw?xPzbtzRw327*(^3F{DJUw6 zxO*GTWIm8i18Ak%Bfk&%;YHgJ>$q6HgpXJ__Vas2G5&rYDWwjF8wSl9xjtjccA5r` z7tc{`62sgErOrAGCtbM~D)nFFwZ#+IPD}NVGlfiOm17X{6Dr!Xqs@O9em90qh%Zqy zj7L>ctXeP`g?MC8FhYkpGudU%!KlEtP~mhe2KA1r>e@hq=qsg%0_u8Sx$thv&I@N% z)9ymL5f~>&=?&zIpPayK%s(`A6}U_vOU$4}xsOJ(;N;5EbrL^ejzGI$Oo~Vr2Z^&^ zP>_9OeE3o9(Lcwk5X6KDTFxjJ2Ut(BY`y?o7h6nmRIo2OKKcY;D^{agj=4*@pB>0G zq*?2tV7>X)vJ>VUPU=`BYjZiM4PP}ICn!#3%BpAyluYDGcKYo*2Qsqe`dx_q^K7h7 zlOO?h2QGfh&t?lVURl__fHnYJg+P>Bg9y^vc{-d;>lD{UvYO`KgQzWt@MQoH9WsbF z*wBfJ`uJl2YgDMPT(%KfDj2zjFm#oAOSp@URHwssRMI>sCUp{xG&JHR zbl$c-+{pq97f8>6l4*K!^J4C%{_D&ft&*}bo7?GbiG}#Bn+$|i7R=T^to5fLML=ot z<-hnSpedf8>>zwnAa_q-%JA;4jt|gA2O2y*wMlsn&Es)@ds6)4azjY^pOt2Lu6r!% z{o7M`v^2Nwv-=a9wFjCjZe>@)pHgj#MbfewPL9SI08j#R>cTv5moR*B(wqaPZ_~Xw zbU4Lzx>SS&H`gZ(h)E6DvE1)qGDj3Slxa3V44}6W4<=m3;ec>>n6M}+MlSf80n0SL z=WufjOK{H?CF&B2q8UE#Jms7Z{7;02{V~#9M)oW3*jv2K%CK~;JE%W?QDzkJjd|lb z=0ATfpu_6JQ%CS+ftHDA$YFqq5ct8Z3DXG$ZEab=2?2uz(0Fva03665MuZ`*{kHh_ zhox+W8x@g%UG>v+Mug%?nl599lS(;!;;Hu9NFsct{iaMKC9UcYw#F`Wt*rq6D~22B~5CncnW= zw+|}D_pel2hXXU8o~1vKRt%8{-Eilgtxr?gsVqtf&wZ|D`C*xB`SJ31?{4IgYErqH zoR8JM1hG802fxFczf^S^$y#S9+FSFY>dugvP<>U43cd-Ura@x)OzO4XFDItLv&dM3Scgsex=B^5IH{lk;4Dm_Zwv~v*4lWP| zAA~(f&3t3#RJK0W#Jk(7p2bxQ=-X;OaNtolkiYph^;TBV?0{=RAZ_n$zDCteN4bj1 zl!@_A(C`RVX{(I=o~@e#1_mO;dwlyNn4^kACYD5!_{q-%Ik2Vx4z4~7rbw6jKNnWO ztQ8owFs9!Q&s0uQzf$g{1I~tZaG#5FfW0VR9^X;xL!`RZ2;z@`43l2H^15~V9{KKZ47Vr$jwZj{E1fB2i};^J6W@T+ z3WGWb7}Q5h|5{rkqNBx>l%f} ze9hA|S=GzC4Bo=x&vGfaSYS3E{&(%MOb$PJWdU{f@j2U^y2!HHsbP~}o8lx{zkUUT z^<$qOZAuu5XRe^I=SgTdc+$1f!S2crA^~zXbi-R8d11s2p>uG@qkMKf^wZPTjq>1i zIWz{#9Vto4A8_lys3I~cyf=SAmowCGK97kn>W>(8!Idd9qIW*83xZk%@K6}3w%RxQ z(0BU0n3NK3CWquPBx8Zmh1ZVn31{fMxyCCCIQ!l|OSZ=yMYBolA64q}AGVJR;a%ff z-(cKsbJkzHc*Yat6)}|_tBH;X8pv`N z!3T*3k1Gfe$AOgH<_t z!60LPrEqxUGeZ1f?RFQvno8PMhCHKu^AaAiI=slZ66$lb$cX+n5^?2#G5~{s&Bt=&w*4)n z!@FRU2K5^K1@&FTS0n;7E%(2^8Kq33q;HTw9XaRR?$wcxO8bjb5w7FA`_e_1*%@J} zTw2Ku$+Eaw{C~naT)D|8K2eO#TU5-n0%Hrnk`L3BHVE@ITwFwD=@$^7(5WsjKQCnK ze|T4ZW^^w>uhr>!7?C|rHpq1^@N!37mrO0d-YM=A!HC7kVpi!gj+lU-S@MH#YfY?7udU}6&x{ZyE&})5_ z#`}?v35gOAJ~N}wJiKmlqyY*EC#On^jsg~MQlTFXH%aR)lt?=GDu?~}5feI2R2FWZ zDhk!dg4@YIEn2jpp*@&~lFxD#H4EdIJa%LinhNgO(M_CRV%JdeihUGoFNE4M8PrC) zY_XtPf}qg2{9ajF(BA{JNMq1Xj*^ugX3znmiMS{sZ{t_9A!%QY@s8|&BcVl@w0Zl_@?>YCyHgQ<8V2EFxMGI z|1-U;nw4Qa@mfg-F3#t+SZ5+mUFiC@NefQ%jlR&GSK;izt$tWIGj&A*bW!jmXshvM z^{J3y>)I8+CJ>_CIeI^w6|^-LQQFUF2M!v-Yz3NC3Xzq=yrU6`5y@H`j_q*J5)zui zR-q8^xTR6CQqxkQo(CgQMQ!a~gj$!!{wbWe0jqU{w%1sEySIQugJ9f3JJ-W;RIZ9> zMB#*mB&x%ouKc>H*F4?x)?whXp%f*}W(;k2dS<3eSnUS;Ve4JysjGE6#7woh8KHD( z(Urev1+6X6E?;ggOnpW)Qn8|5#+ZNYsRY?kt!Z({5j$t?#lRM;zPmbqv3S^zeQIIi z3+WZ(<${;~15`MDj}B=KHqa`PBm(*?qc*MKf} zN|kRgk;HB|A>3pD3*grP+LESuat;o>tRaYKuGKv${Lln+erPC4K!64y9TJ!IU$6Ki zW1SASmpJ$9okhAVn6|<$q7&*bb%yiEWrxRt{hrupInm2~e})8{cV%Tfd`)X4+DL!E zAt2amA%%%O(zhb*X#pNLlb>DMehz<(m?krp>d``I1?!`F`iKdY!!n(-n#zor(9tu+ zJgU087*y?X8@5hD9O(W;yNCLu32fhgZ7@{Wl|`3TpXGGr(muIMuK?UbNLYq)nwE_+ z0-^>ECW#948b$S$s6kBtSj!irqC4Q@p=c3>W&n z1!td^i6I}kKBmSHTfG`+{U^f9WqTQ>k#PRrZ}Ur`?AT7Feu*$gSDSY?UI@>I$*Ywg zRO8Lx|DdE)+AK#x~o=B3Q)frCYOz0N9RZ?mO@C}yK(%(Pc z#((Cmtw9pBKW*1nHIk*y`;IZ`e7t>1so<6K=AtRTE`d5aFQjz`*WSfHgGUCz*;N{G z#lbE*@9wozrxlz8&feB?cjt$M_<)eorw64bL(_a+BkOC-Z#$85XFsQXb8om@X3hTj z(>n6QGfI}=dcN>&HbUN@Ryl_WSo#;$!aiWiWU$m8-uWd=+=8O>hnVKY#vkUvr_3`V zY7-uzX0}d6*%2eA896zDV0zNSS5i_E`^r-QRyu;b42ubhgQy}Et0IjY4@myIg9-}6 zqJgxT!}F-xcB;XU(9kUCvVht0!uqdZD7(QEX4=!@?ODh&Z)>DrZR#KiAFyRYE`6qIcR&F8JLC2KZEGF&d!!#$wpo7A85_;7k|lsey_fMHZT9~2kI%O!!-mM zUKB(#ZJ{+Bq>B^U4u2br__Er*AYj_wvGy70uP!obAws>L(*Q+DAf+t>2uMgI}u(FFq;X_+_96 zfb2q0DD#`+Ua`>8wTW2G{j?a-`#J4d_Rom_fkT>rX?ox01GsE#hC<3znP3j{bTKB0 zC6CE9CBrE99bKb&kD@app(EVuqD{Ak(ce7Wxyz@ zV0W)-s9S$U)H337{P@wMzt&t}`5-`bQGsmDGtlzqv2^A9^%(bf-Vv|Yt!v%^t-2&n zzB61i(;Hr%>Y;Uv%d_3FqJzi(s^(+dl;+$&TC7jExi;Jo^m#7-xX^gZy3uf}-gj*h zwc&!^ZDfmo%MpWAv;?n+;RauSwE}4)=AwR_M)FaeRG^E3QK`)bogXi8z?BA2Ej4b| z_HCF%`aV&TyDf0B_2SKxSTz(GuU*t1zJnlYus^yy-LouzgpXeWNBgZz*~Ct8-y?Ww z`UskcHgk>_9~zNE-R}C6yJ95XFTM9zXHp~3ZQ%3IMJVg@t2Y?np;v+wxudgFfn&uC z0)k<61Ahi#gAELs0_;v`fnTeYalByb)G=ers+j*qx=!C1$Z?2*BOVxaUOqi#ZF&-; zty%X5`)Fe{=KNXl5PqsUWBqwTI0?v~*+*ZxV7K2k-RE|Gza#!xJ>9ziIfQu3vO-az zHXbLo35clQG%EK4Y*oGo*annaWf@<5gyrqDI^#H#BzUmeqjz2FtXaORko%DKeZ=6i z$MNGzg`bWeTKFJ4*!?hx$#NIbOvayNIC;N`dLcp>W%j1*V?kRq4(%6WN8u;U>RQx} ziq70e@1mnd#;PnZzVp~nh7_}X$>#fxI1Ge8n?-`3O7fi%rYUov6diBGanQQ<+=_Oes)s+R3@oMa-Ob8&p)|Bm899?vSR zC5~Y#iDfSJqj3ms_TRBD3%mT;?Uhgn zcbNw&wwI$lH)i37BRoupL+9E~@sHBJ|M z4Z8!g$0g>HxBmLvIooZixOC63qvJa^8n>Hv9p8Dv2M%Yt@2*+>WSNb_-x)TI^8A_hdTNp(&_cX4Ad;Yz+qkh~menG;#4d)H-Zv zm@-4QZNa}_x22}CAn=iky96u0Cx4=QPv6u_oe#q-sWQP1!ItsbXzipuBy_xm+oKI+ zR}?)XixwbRJN7mRD$=K4rAv76XOYW7l@LG}=;Q|mC-2if3=V$dw!fZ*_>Y)pYhNLW z@9eg(TeIB|9C1&8%8TDAjlvOaK}hdEI#$?*!U1)QrA|F%o{_wrDz^Lf_MY^n!0|_`bK(9@ z{a>Wq%jop9y$JXqLr?VYFDZGXx;-hz{KA=d{BrfqG`JGCXP;Hi8OZ78wJ78rN3^}K zB8EjAM9dulfvC<=Zwf4rK=s;p%R#HN!Ch@_M1viF=Yb2h!4OsK(JWG#76A2|og&f%TP>EWeZI=0tUQGgg z2=phu{48mmcRww#ZOZTj4jWA;SiU}7C$2}sy=$w-r&pgu=q`0J zn!CNO)EO=4<{ejs$9>9tZ|7OmC%R{~dkl?(SYf zWZRQdQl|D943@O1u#)JoyN%$2zS^{Y}vUIPjfC(rwc~VUx+v7u|8CNc}T5# z_z%m<$9o{PpRv4{8JxktfTxUH$$J*#r#BQt*PpdmG@>vWp2@W~SH7gR&cTkZ2y z?y@RYwWH_mhd<3k8Ub7zoSyCmB?Z!Wy%!e7-v@^ zwaJE-a{}Yjarx|nN50J{ zlG;6j4kG@x_4U6ZA_t!9OU41qkhEnAo+{y~GjG8b*`#x7H z-7>tArMddU1_VSXt%_|2{36RiidjEfXNq2xMvbnIR*S~q=@bE=TgXD)uY3)DDYP@v z7ld-lhdy)%;LsnA3daeayPGhgeQyhi#ijYR)m^G^6cj?+R2L2 zuFl@@JLRMe$IgK?iAeAm2bVz|&#N+xYA7yAk4=`d$Flw$z5Kp4k{goapk1nFXh;i) z!|R!VO%PdkqI|N|d3Qo|)c94tVSuW4NY%;PMCu0!jZ;W8V$dgI4G-ouVIP7Kae zH8bHHiT?9Nlb^Kn!)@y63F?EwNtegI{Y4YzU#ctiJtr`&mMUlUWnk2o#yT6buiw1Y za)-c$Mi^YY;cEgoOU9860lxs73xwxA*1pDHdy`X>k)n#yk>=vC-`H`TpH=Z-aSfA> zY?LeCoKyraqZP~|EBl1+NKw`4=xnr4@f$^ruD8Zgmjs`Gnf>giO$<-d%&N|1h)6Ez z{V1z^*b4R4CCQ?C?Yr1n2x`3ivz50V zEJMj@sO1?M&r)*gSz9(XyO?)msorzT1kD5+>UOBX(#v;s*(S7wM0l-Y-lsI`LYhvi%wwilT8zW zfEyQ8E>_VBwIF_(PD8V|O3(X+?@Y8ZUGrZ(wWSTdhEQy4IIs8SeCJ)(Y*o`N*L0b) zt38_BsoD%6kRdetpn04zeNvIfMJ>Fl-@=eoy~@VILl;=I+PhSpT;KT3Wx};zN_wy1 zbUC<$+cDSICUVv0;y{CIL;Svj^=a2DyPJ^`ZqMl_w6YBms5kY#tzHjPIYO-7uSX9R zVUo!#cs)6%i;Hz@(yP5(z|F5RW~bk~Bgrnea-PM}|C4Kn=TyH#EQmBh@aDU!g1AmM z3F~pW!D@bkP1n}JlSH1d@$XL-6qqyr}^7Eq=i!iw;>h*f)cYpdB=Aq@u^mno*Z}gEaFTN0??087?T#b7~Zgxbwb;CcC)Amy7M-qFE zloj*#3`{#Y`31S_IiGYSJ4wT)xmPnI3y20xRYA9|#}V(qFS>kLN^bRQt#2h@qqJv5 z+kF|_gxEl@3QhQ5aV9c;m*E}_Za%(g>jB|y`E4@|vp27o%O9=|2R^l(3Yen|a+4!` zLtEB4Z*~gcnw6U#na;+rhG%~b%;wg+RyXQ@6ZvQLX0hsJ;Ftj65GVts<)toR-SRl{ zPyYPOb#eGrJ_o?f+qZ&Zv598~EA*=)L{~zgC${o9LYd^DHkxn5(Nn8yQ;8Le{4004 z?qfaP>uq)Hm^wyto)Sn&t^T~RVyc^}r~1sKKG2QyMewmy_oh&orOm z9%Yw3Wf&_+Vw3=>xM9pwLSv>#9c(jydu$4^HpFABTv;~DC6nrOjafBmfpX_ z$R;~iUbNR&qzA1Zi{b88cTMFY8ru_-f2xSr{ljz2L%Y_61So^W6}4GIpp%mUDVSy~)s^^kr1X~`Nme|%FJzw;_C zG?U#{f<{aS|6$!<`RnpahwJOL=)<`~;?UanRNIru2V2E4r`wIz9GB~Kd^HndYg|MP ze^of=`r;*MZFdyAoYrsh_4-4ys;-V-m85-5+sud2pXJ4aoEp}Z6eFFLf>35d1tngR zfCsYboP4boCk|vn_X%ycK5~PW_tSOUM<{=9U39cRgP^+@y3rn!f{{LQQea# z-4SqnQMBpN7fL!O*18>fFj;f6vYtbAx*tAuI#a#KKifPIRK0|h_0Y}E%j<)ASEid8&1wO+@0-_iMx~NT<+7YrXg+3za?VeC ztJMuQEI-VBaUhn|>SknoMQhcv*uCSHtaG_b^Q*Te)ad4jY}U;l&tm7=XWHoFz`Xr} zebSH9?3~KOn>?E1)+{I2Wm^w-n->Lh0-@6t4C}T$HXoyQ56ieOS2npUo%VHVPYSYB z`FNr@CjRwaU2eDfUN(GwWa)bR%I&;YuiMf&m^c4|KYr>CY0vqZSHsQY*4aCA@hB&6 zd^vTzz6eCkPv4;OI{wMm+SSGUF55WRHJ|d*y31~NPvcn)fn^e!m2&lh{g?>9^?KT~ z99)l^9qodZVwDeP@~1ro6xYbaChPusUpI~Z1jwE)-gi2ozjyIuW$Cwe(eDZ(TRdS8 zKE4ZO;TitSoSO%BmS6jG{?@(RT?pPCsN4NZ=l-js1dTIwf@nUA6Gx#zG>4yD z)WuY8pdLHuwr;WRQidA?*v>>3Q_N)x=ii}nH+(q(nuwgT^@KR%!Ol6N+BY8hFl7SQ zoKG{BJ0<#GYO_ZCcA2^_16cz>UQknuB`T_Q*i^1yUq0XJ`us`R{r+b;mSi5* zx)uV5smXV<7uTld=R~01*XG`NvvVHrQ&GNWz^5QmV0lU49n@%wbAP`Gk6=N17K~hq z1^=pUKF3|0p4yk3!D(^=P6?pzZT5Kw{ZkFV)5#XlgmCDYwUtCBGW30C&~xhtcL<|X z)=myNU#Rd(2FX~XYpfJ1I{ox3FyDMy6cbjl{ZL&)y+}gPcH>!ZY_%88!>kuh&7vrw z-|qC(d$wJZxlul>8)nohlN0gU zMWi++!}vj+*&$}7^At`Iji2?kAqB3D_8a6AfX4#NssMKUB%!{*FPl?f>if9gHFTJ2 z!k5~AfGZjJw8pIYPbN}FSj3b1C^bRqOZ11i(Vvy`HrK;@hHGc&v7Baj2l;0>tV?x` zZ*a_SokHC@*TxU|JWrXTh;-Ed=vA=1AFYi)-PT~WYx8nTax!Gz{zFx%KW{ua z>egMYcS|;|;ndG7SYus^j8q+vU!8(l+&-bD45w`jR)v(;8P|*4_Uk=WuQ6eMGAa%|-3OciXc& zmreukKkN2>_%kx6_xjl0mb5y#sz_qIIy;D^`l-g=ZL)HiMI%YZn)AJ(iEB+zTM}d+|xepsBmdi!ST8&5@qdTQbH8ol5khiH{e zZ*+O-dIgi^-geKyQftHh;h4zje3$2Z{u#dYY!H$2mRwajnPx|gm`n04WWh}ar?UJ1 z&IOQB{~S4r^tbIAR-IIuiei3#uJ>U}RWi^wE%{GmJOJ5$@yD8SeRr2?3V+_Y-c^Zl zv~j${e(O%#pFXRveMvssB)@G=4_-XG)ULFpZstxYZ==u~I@ncvT3dSCQtQ@%<>w0R zFGy#*-Rdgek68bFb2`0fn7=^Rq(0o)xt-Bx|A$dda5ryvvhV$de&soiDjUId^n04l z|KkE2aJaP{quW!(l}SFeqW0qyeoLD)l9cK~G|+x_+_L%3V?w#@1SR}Bf!i+X!I>MH z6>=43@1g9BI`x+V{cnD(B8;>DB_jtLI@NJq3(Ioy^Cv>=fnoReKcG9xb7IG+LI(r^o@X%f7 zhs3#YnVAkA9daq3x4V=ard}z1a!_g`<^N;qyrZ%H|NpNLqL3mZJ7n)YBSJ{XCbD<- zUdaeq8JVH%k-fJvu8hnsdvDo${T|+*^F8PH2c4tCbzQI5^Ywf_#{F@-KP!e3Ow6xZ z={DC!GZWIqY&vG>h{}d3P>NDb(G=9n&VU2RL-sem12V>(5F6^KIJY_em3pfgqn*gP zV`Xdifk{|ZYBrs^ky%^jXX8B!+!|Uw!+Wpp&j~Pa`~Sw`ni#O)NqSIdVyeUU&YU%A zEuYa`*jwk1h4b@hoHqAhlQLulharIO;&tq?e3Qcbb13j%V@tOu*ItDGd+Z}ZcJK?G zXBL#I6LX3XmGvZPrete&jE@oRYTBM3NZXr$Pa0^rUTD2Ylm{9p*y z(9DvY*mB2?;#^?UGkV%bfknzQbYLl^wT^%0n>5r8thwwjO|R2N+~fBv*gE?WGQ!3C zjaD%o@*Fg2qyCM1p>kU~I6ves%nX8Xd`X$Np*EHOU53n;VXfb# zuS=_zD|ANPHw_omio9Ju&xg3<%q00ev7y6e-H_?2v?ddsw@H{BvKp6uw(a&iRTL$L z|B)9}Ss6_Z(}c8}I_6tIW^#P$a}{g4V>TOlG}6yAuf;0=?p2+akQ%+q-rof?5ZVG5 zir&3DWy?BpP)xeq#5udq_+#{}LnqFFABI>$P)@B3Q~ z+{fLge8pNF8OBN~baYBRc~8n-jx+0*d!m%jU6{WY=H{!KTcEAfJ+u4Nz2q#M*ZlJ z!r2aiBZ3?uN8Vx-#!fJ#D&v*Ct?_G+RP)okB)MYdonswBhNiRcI8-6GEY|DXd!Mn} zy}?nGK~>OI6qKuaHFQt@Fbpf;iFrH6!JGpo+fw-)AL2?6E;s2H9n9^jlQj=WTxB;Ga~2_Tr#zBL)&@<8NFqMg;3G@-Fz+DrCH4#%eU*zk*O%KQvSDeLT2n;cr(Z&2%7q=IJSZ(KhDx3TM`FUUH_C7xd z7w5AYztytb;wbCFar(6LlW(ha|M2E+-rZEpn1e=6o1lz){O2ygxIx=?m=OU%*fSd6 z5m{S!!n~;5iN}8QP1PpzY$08hb@M688}YK)Qew~#+Uz)oMc_&rjmmaWO9jaxkrno@oz!(FU^C07i zul(gxyq|_|#U-fu`1rWY`YD@LcqQelh?`ZdT8B(tVJ@9k-ZCZ--_a+7{y;{?PemhD zezh}fWZlkN=Y{1z-a`j}Y+pvkIApQDtWQCB1g}*qQsN{kjy))?DKCuu>G(?az?nkX7P}h z(;@YPEi3%fU8M*bct6%L&DWD`xJF35%y$(qUn4NG=0iZY&pJeWfX>5FbT_}MGsCH1 zYC%Oe3#FI)1sxpcjwQ?3Nq`{Fdv_(o@7#1 zrEF9_*cqDeo!;g1?|mffbEM>2H`T4HRNp#o+tj*M)G0L^ zs33ucA)%hFM?XMi8*4pU?l1JGaV4bRJH3DSS=Bw!fJi(7#l>~@i-2Si;#wQ5OdMS) zbGhD_`lHz(&%b*|@20XB8eF-Er*GuOf#r_#$FSJxbc3SGwGF}mOH8VCx@6r+{*=j~ z^L4$VOEuAwQL$dqG|v|LVip5;&&bcWs!yeD6I-ZY3OJ(<5fVe`uh5VDlP>X5@S;<) zsd2)HKUpz3{bEIiJ|$&R?mV*p<%>yO*4=t-TNSaGXr+k1Y`T-XPDiejy*8LVOGIge zFJDq#@|INCq533DvWatBrjOtCxw>x=*M<@!uZ_HaqmMj5_bT8HJxUB>@XOtPC!A5@ zHphI4+ddOF=wILw+>yxru^{bwg>}5D!hU>L<1?lN2Oes$KxN;7CAXqrI_bkBl>0V8 zn<73!p#~jdl$y3Wm(H#4%?^26@CnqN_*pm=BMSJ{a_Aqp>s7e7Ckf9+(ere5b$Rap zkvZQm6?+TfLk(s^K%B1g=BjyA>^~?SEl3O)+VhSo&UZ@kdhD03?xJlQU5sJdUMPsG zPZhif1JtSL*o5prNdpNt^cPx8%4*!0unmzEN)}E&QADyvhDai_Rr&6IYWvWSABF3W zhAZ>vQ`f+^>$X$V(7L>IKeb?QIYuM?`N4?LgO%@#mM0gv^amH2RmWd3^gAf3 zvTnI-=~tLm2r95d@X_QDJ&`)UZoiC8v_kuZ2kY&-A|n^99jqO4qtdZD%{zls1P9i4 zGyf#ss8=rov;x294W`alf1|C6tvw#W_p8Fr1EQLOUoW-Zf z7b)DabpyG@dEeIhsic(>zCJhgm6xW;T7KLHMJXMf-`AqKcddJprapvmXr58GUIq=j zzqSmYcc+c;o1Hs3Jo$>B*TTCZaBh;T>>oWte=KJ?&B|mMdJUR!^>;m6; zGObsoPJ8H?g%2K)}0GgD97a(1e z0~`uil}2V}C+yA~KY9H~9*t}2U7l6{aa=0(0*%A$-1U~z_+KZ65amo6F0J!$lCGJR ztr4k{y4%@p(mUyty$!QBimL6%Xk;|_>ABKf=4?OGbF|1Rm=hNYdS&QKJ#6WHow$fX zMe~qPFrY1o@7?nq=8Y`pLFv1IK84FH- zx$)v`{W3D9nyjz<{shg&sukIx#-v+{ZSX}>hJ^W=1PPT0dEVQ%^=EtR-HF7syiGND zyM)fn{HCc`@EY-B6JZnr=T=hV?aaD#iZ>tqpSuSyQ6})?*H-$k)pY%uxBE2wEKIww zzXGe#?y9?*2%p{H{%4z@geZ1*$F1oc)#JO&pSrdw6TST6Owsn;Uw2Q%aOTp#k;22W z)wZ4WEKv@1jfns(+?sUtl=HatwYjAqDuzAyL_KjPwPszq;~pc8w0y1bG>`tSR?=Xu zQ_{ubaN}cnItvA(3u~s?5@Dzv8_zew1V{A$bS-^j6_!t!ncG(#Pm?RjL-L7wiGs@& zod#v~tzh*JSuga^=;pJTn{acowYW%yYkTLh7>V2Xo z_bJIw^?MVYq-9`k`8y2f128xTKlJ0a*{kC~d zpnmu8AD+Kh!@8c1SQEL zTm-Lsf}Vj|br0Roe4_$OrW{^Id{*f|o%d)@ySO7Ics(l(^X=rLq@)LW3FRV6i=sKE z#c@($sY5}vp90WYx?`ChXhJ!ZXZJHGSW>Qlp>yBf4n`tuM(bB;^L;F%HZIGfQdvt+ ztCV$+gqp09ahBV3Er$DgUn?b87SpTn(uafgt?)q@MaRb%4>gp<%b59(`{9Qb3{Re1 zb0wsnJ;Ns^&OO0V8)q4R+zPnqk-|R9Rq9Z5(gU}Z#{ph$ys)=}Rt4ZEz?oE$MG&!= zyi+K~?W%;L4P)x`jbtpxALhtn*F$}ZveQAIoikF~Av zoSzRz92;)N7mV5YW_BA11_yj|O~z2)J2X8rbI$W2T_#WTq7X~+@*mx*jni)``RJ5C zz4V8au&jV1=`pU(MyVg=E&W(T>sMTj-B2~0`q{fC&+6umlI+=V6$M&8dJyfjEl)4* z6*n3V`{>Q)R=KPQrJ>tt8IZ6i<9F#=d9AyN{;iI=r;Sy|lt|k%aX+hvJYp~3^w@{Z zyICDQ>F*D347KR@4oy*SAGW;K^EsU^7~khfD?a|LYmHj7fHBJ9c(gZhg%~|H95fj@ z2ZxrcA;Nn^7rxIVPo-FL@Lv22Lh4_##tXC< zw*wJovX{*i4nEzb5qrq`@4n}Siwy&m5?wl_$G2~7oiQDWY?ED`*wZBO6)k4+P0d+0 zIZFw9@RO4FC`Ncbc*|WM{+>O8_*qlw)%J3eSNE@sN1)LNT63l^#dxP=hP$N>9EE z-;GApy?qpmso!n)kYi4sCqG}`b^0jWux#*Ap0aTqaP&S3CnYwxXBG7^9*BNzoA14u zOWSQ{^e<259!=~F`5bdzIp|#t_XzJxubF_{p8GP%qDK6r5mA{SL}G z*`A?2-s{;u7TO-p-Y&CzW6XZO!HRi9OS_pE%aDV{mH+%wxq2DbuB|_Hzl~B5P0Kxa zW8>`2Ay)Oemh0OG1>U4K8aUy|?dG3F49KIlWY%g2D&eMkBVOokNh^;M-p?KeQM%vJ zX?!?!dcX1Xrk)4kZQ7e>LjIy+cgpElw9@u1KMYbg89mifD6nXlIFtX?$#(2qr;Ggh zb7KA^IVwuR!GQ}OAOG620GLEfNpFpfjE-aD*$BRIq1%!m8b^|vq|&D5-s4n|NrT{d zadFXx9HHfQEJtaHbjrgs&+T$5L#otiiiakToT_TFvFUfo6>c|1_I+*8oXw5QzHE-a zL#t#;+TBk>2MOMJsbs`P6vDZ7fm>1LB7aMb*rJ%XVJDxBJxTW-Ng+!iIq78=t-a)1 z)bKmuat|v^%L)dW_1TIU==1-G=pvIeT?JA9G9L9O&hCmAm5c|=^Va>0@!=aDGtXtp ztj-Abwrnzz@h0zOAH^O!cH8^%!wg?JH&yh)Xe;&72BOCz2W92tfHm5}a)*l8z$k{qeWA>kug~;`8>*UPe3`OI!F zs70F^MOY>dGC2@{WrEwPgFYrt`C6NL^rM;cy=+d4A+#ReSJ{~|WOZM*``=w9y*y!ZKDt#UCge<(pbu`|M` zS6?6VK&&xYAbt|D8;2CWIPnmU9A3w;_*fUXfnSCdiP9@nMq&M>e_D<<}eX}*Ok&{JVjCWL8U zwhxBNyxJLKJ8mhgvRjs9$|3c>K`=re-g$?)ZQy?MHS|XigXI z-dds-K8H%(W&hqH z5n{hcs9HTErkhS~h6ath%}3Q$pJa`n>{u@1i2880VI-gspk`epF0xI@zV4Cp_PHvY zs6VC`-Z{L*Sgvc@6nkva_588=uz(Wh*t3bm=QWq+ag%)hB1)63=c|L&t}SdDL?%?0 zX5W}z*h-Yk>YC!UZJi3SO`E1~6dyTEF2*}3{Ij=^Rxq}grag|7>2!11&0kk};=Mas zz(2I8%-UBwl&4*joF3*iV?E`yaMMEXgi2lCo1p2E`!kdNd8F~^ot6d1IUKq9IG?4R zs-)<@yT2!Oyt=;YIE;>Sho|(Sug(@Z`pejjCQm$bl0rI|4|_AN#Yq8nU=BB@Pu z)jLXd^0&{IEUFh?A1~9b{KLTYL5a{s^EtcWxy5*#LvcQjT`e#iJN$=`G9%vX7uq02 z!15OQGd(2QA7$2vRU1kM)G00Wc$d})wjjj64{^xt6A#MNq!!}stqQwwao0KL1OZYT z57gc-=xrXiD%1H|6GsjHDpsG}PH-STUt-Czi*Gq+ZN5)T>?ZAz>Yh<>>BVS%;@-oM z{L?VKsOS?oSS+3^@J+UZKodl+-$0M3z`CHiamD*o-c%zn2i2#Wr8O(N?s*ERIst?W zgPS0^pLnT`)CW^N$(#Crsk@)FrfoX!I}u1YHLc4FxmwQKlJ+`|Cx1HK9@#pV&>!1Z zrTk}pP$G76@+!za0rpa^!{m3uSMg0NfoWVGcWI=Ym-J@qzB0O5WDYjGP}xGZq$OOFMQU1v=ow0K&pC^ZTx>aozacW`*Z z%Ia)MQKJL)6W}nSTN9U<*qtsJbS>uGnraAiUPo2~+zEWVp#^zujX%t@VDHY z0Kiuw<0i*JOQSWOFIlsiC}tZ--}YAW+<5o~HfS>F8H43gpTYp0FUsjhpy5?oAzS;? zC1GZeeQ&u>o$xj)=8P)d{rm0oX`a{r(bYKPUuLa{0wzU&tD}I^@-zL&(R11mQ=|{( zZ0R|wJ*-!}vev9`W*#Q*9Af?O1pp> z(COd!d^87P`8jaAUg$w*dq`rt%5vc-p*wl9`(~;8fd#ZeuV-vfuy#^UQ}bUJUsEhW zNlUgpf%a0~UXo1RDz|xPWL-M*`yU+EffMn9^%8myc5Hji!r2K`%WTe8sbA04YZAwF zjGX0bQhK%u7mQSBWSqCM3M*oNC6e5_OZw}tJgY(0a5tDIDZmH^NHB&An1~z0(B<6f zg)z=*XOjhs#@dvpbd;vrRV_0mMYf(7zV+d|IYg6hoKX(XX!s9;(9kualQT%GcoUL?9eu5ZgRr zg_rcpPlEV%mqrbsrS3 zC-sWFE46qf@4$@Ds#~#omBsE6tP7Z>tBv~YzV${rl*YL(1=PoKQK-8nF8>p8W(V48 zX;Ez-O@hz0dWpFCEekZ2j@h88CG~!A4A&$vndobom+ZS18Fj*KkUOcaESrUrNKbdUsxM)2IZ`PaQxO;%KUOjxR{;16@$&!)j) zxp`rJBA&t?=5?O@eu`TS9Tu|pdgWGaqV0uO?}UZfOTH%5#lRhK+NSI&Zj`%_XEWDV z)2+7i1KX5;4M%#g=Xf3B(!6@z{QOnx^Iy%FjsMbiOPR%>=$y3)C~Q+Rv*)XRtCqrX zRc8d4F9VAOKZb=3b=oHN5Zr%Bk@HeiUCI8m^k{O+yK2cTFJ8P~KTX=G0w1hBWRRmH3gzaz7&l6R<{z*RONz8d26_r;aKVn2^Pwalog`Y7n61O*$mK}}Du{JK< zo;SGqt+X_HIA48md>rvMLL}>vEnP=?nicyRw!Ie*FR#Tb5&+61eh##l1E_3+dxg2c z4M|%QFHK!mA`lsKr4mV{eqeeXnUMSpsTsrcSPUcmB}#7 z3zv=Vw_!`h@dvuAJ3_3wmZa}7se>u~;ae3acZTNG!0_lO-+bBAvakH=q|zVM@L7`_7jICBl%C`i3H5_DZj<>zg8-O8Js7Xzpz(Cg1jUS zUvWu-$LdlI^EwM3FK?;Gkqu1tvucw|PJcSZ!lOZxBU}@4RU?_*Ej^A8(K~T{AhGT! zXew2GG|XzB$a!LY%PZ~hLHVjyb6Rs^ypSeJ8IvjHSRM)tv3gT5%_v>%kLDlS&o~P5 z+;P9bbyMJF&hwAgwrGE*TF$19L=_xrjNC$;b=Fs3M;CU1j_jeFQSiLlLK!B`ierU4 zK4Q1YciZAtgp$QyAYG+OVR)I*N{p0{u?i z%GTEPv>_-sMhdmTFZc=MMC5h%17b8OIH`Ni4}uBDJs%b0>M(7@VhPXAS~*|wByy|a z8|9TCg6%%{4K71DR2KXYX8w@GRU{sm=LO5FH3+0A0^tV=qBl+M`MdjTis_xz+9IuZ zZ5mH_$v*K+I1cuJ3k{m@&rlI5Ju9oQXxiATaJsxjCuQ8Hcjd)9jbV`8+=+fXOOENK zzux1P#{@0XdfU=>F?PB9C`ABnd+n?8xg*rUXw&Ru`bB1Saj~s5DK9s--Q~I4>q4z( z2D9ag^%kWty{NZ`r#_thLl-wwbQ-*l555Nov*Ns%d`mQD)&7_+y1@+JTvHQAx1OKI z$8C}!;hP4GUyfQm5Zq);dY^zw>zOPT_DN3y8D)33gBuEeD- zW!n~U2VY_rzhLaeD@CZZLOzVwm-tyaD?EXtYH2umW&7LsC{jYkgLE(Zd757?2m5KN z2fx=T_u1j*wSUF_;oJ&*8fgcw=deq~ZPssC3#!I2y?lmyx4hl`ns6Oq>H zBHFO5egJs__&@cXCSHQRhdjQGcL5#1b5Gs2SUF8yB2EA5e#s+{vG>hT)|{N^&HKM# zND9ZlDJdxl@OcmXUTN~b5;|AGy+6w8zXja;Y3ufm_g$Q&wE><4+6{>ef#alceLM*r zg#ceZ^Ti0Gz(4Zg!ZbF{69<9dd$Bp|4%{sODkP4Hs;3nrXfs{Yu|D(f6P=>40ikTi zO%eP}K#uA;N03Hox~6hH!O!rR!w4-y-||qlQ7lqcJ2T!QmfnrhXv(VSgLsI3S-ceu zuF#1vjeWbmkSg1`eFK(eIO4H{S5)WaJ>+F{hF`KNw}hc%uhnV(#-Ggymm{k^EN)#d za%uhh3CMZG`^L)3*LxNtqZLzTW|(6or=CsK7Fp#i4$SclluGS#uswi zwWeeNVHy@1;_ypy`sFs3_6QI1fm0bR?vt>kPj~IJo(NSbZlR* z-`HSAdHOU*;Av!R3PSa9Nn}jilt{7cw$Ibl*!rKF9Xt4st3~h5RRD z=RI!sE|TF=(dU^HR|ovwYxhx#Qpt_CpM5dntHp=|YtH|<&Or-35LOBrz7#Bs|GwQ& zkt%yZ7ed6UZxsGwjkuw6mBOpY`!YoUHWD(|P%9 zB%Rx~Alcof^;cJ|<)(eVR}P-ulN`~uf!Wl&JUN>9qpfMN^+T@RTEa+#FzJ>ijqPI} zswM`+L7|U8{CM-qqT&|MH^EV&{e|i#34(CFL^U=f<5|(;qAb%Ia%lqE%TKm5b>U%S zzi=F69TCfUo#Hn#*=`#}@awO>uNBeOPQFj{fHZa7uD}l*71#_MFb%&emwrU`t?zb1 zVP4*DC?(GT1FxVu^XSMwDk`eiGzsHlWAAF*>$?-8qvv9SlrOMK^~8!0C*6Km0d!?i z_v4WliW@2^>!C*Rf)2Vr?6$<0`}C<-afj&zu(eY4$t-->=T><0%*X;L@i8s86f)=@!M&~qDx!GAGq6uWKSAHG$=d7DOlX^#p?v@T{a9m5iv-H% z^u4#~-~?3J=)g7Jm#W!}#Adx$cc%HKj7yl^>-UGf!DYJd$Z9)p-yBEMJ;fACMyB`{ z{624l?+1qb*x4xM-BM0stUHevM79j-o6>+(8;oKh`Scny0~5P{{wTLKLeBOKLMdn* z^zW-bx{DFdste_t_b|QQwyqM`AHzekx8Tj1on9(GF?e=%76Re>*!m}-e=|EB6zWS) zK5>*v@LYB-{?QMTzEEw_1J@Hdx!Y=LYOq%rmLa)`nTPrBGFZnJbIk6HgJUXFaeYPs z8&a>#IjUH|4JQ`izH3CYxAgNK`9J*Uh52Xs29sUJ%EJ{oTqo|o!Al$Lfx&rd&W`^W zp?}HQCN#o8QKPqDzlO-S)z^2*5L8mDvTw8;EjqZZlOw3EC4&j2KoWs_R`8k$=#LO3+$5)F6ctScprG3#TjwsAU`fl!tZr;@*B`AZ1NH;B>1MXJ zqm|)dVR-Qg&tE(9hRDj6JGpQPaz5?({MJuw^b7f1BO4~}wiy@1IooRfj`vmI0#2FoRwIY{!N+}6E=K`*#tm7JU-@!pN)-5=QXFa z=x;A?^={{8#h(2)A=+qc50u}+0SeUwvy$BrICL~MGrmU%uOdW`27*|5^%885AG zr5%4+&C|Ohe6c?WaI_xMZhalgy6~@gZ>iF#%IQ9k-4eI7T*rBWqi;;W_Qbt!yylnH zz^F$s_QQiF%Nv<}MIIg=ru7=#*6F+5{;Q>{#WhIrMP-Jovw_ed$;!tON|j` z*478R=V2is951*81;;GCjEn-Fg%X;7`-mUlf;@R*%SOyttm0Nj$%zi(5I0sB5Es*& z$R9jdtVsR*`P;dBOHM@Ma9wfZ#h(c8AxqCekGlLKF0aJh+D7J^rL@7`VR&XaV!sl# zUwg!68@XXQ1+DW>IVKOpey7zInR0vDCjjYdVYYUIaMDjv5#|Fz=68g*370L&f1`XN zmCF%nw?)P7Qj)F3x_zX; zu&bG>{#-ri)fCRu+3=~;@~;?W^y8%$xohLj&c=PMq@{b!%^%a#Gtn3BA0mv^CS^{~ z&Uh4-i1b|jAY?QsLjwG2S5qcW{Im37=eARUsFIuR;-ky$He4=tc5!gVhQ~G`s`B<+ zV@@)M%EC67HMbrN)e7(^mxK81(Q58Z#iTMN$GA3+#j8 z=e?H~XPRJFAB0PhRaB&i-AW>bR|bJM4E>jaM(l8F+NZDwYwpoaFfrceQNA@AW4Oy( z_SWcl?-d@ywbzn_L<^3>d`$pD{N?ltKQazMC5MfT4dzU+_L5)~J+3Ke)fxUE`bdBM z(vUTHSe&wo^v#$|F`9|C5@$N4?cOlaPu?$-itvQRh3kDikow^pmHqwW@i0Lh=h)a- z{RjYXx;i_*mX)cv)i+w%6aS6`gyeP3m~`CR-8~@uTT0+y@t*O(xR1bSWwFDx@dMm# z&n&j=OgR;D2d_u#Og&20r`#-sih95VCte0x*X_{TZcD4C^_4^mM6OYYk(1XtrXsl0 z{=tNZURnB>6LMVPBp%a1y|QNdN$eU|E$h15RWdB!{!N&lw!M*XrxK|XIs9ByA99So zO4f&HJDA+M8TneZy({pRHvvhvdgJZ`mYKx7#s!Y{;B6*2C&14b+F5`9KHS{gtUnyH z)LVTxTvaTZQF~PcrkGIe1e{HQwa@WvP(vr(MUBakqdq%{jM{vR=LVP{TzeuV@!4Jz zrJ)+)0nm}qKZjdhTOMG!eWuncj#yjwp4~dQj|oHalCWt*Z5bqf+XM1!=*fX%M*?Mn zyXgA!2mmjln3x%pF0xH$s-0c11hGAgEd$04ECfhT0ML|ZP<5%byBJ9|51#APH1oIg ze7taBu-nne?NcAy6DlsDBq`1C9!)bt)xY>Pl)W&-yCI{tc5KVT z>;K|U2tvy`;1GnOH;TqJP1fJ@9`1>BfGs6kp=tf8{e?KXg)@p|rNV;+&n%6XX3?NlZ!vxX_$z^d zfhbB1-R&PgCMYT?Eg!$bjmo9ZVk45CuWz1ZMNo&Keaj2EvN7fxr2o;7ZII2BK*4%=-%^lS$Nfnx%+!l zN0+Ay>xFG)H27VCwsCo=UqCw5XKFoJKk&n~iS4k(0d>;N)jj(&&+YdVw1AfcLNK%j z%+1VZz~v{9AV_*4t+;Cp>=I_}Yq$+%S59rF>XF%-et1(RXBRcB#*fSeUd~z-o7PN} zQLS8bjZQmnLnbrcGk|aHGS`l!=Q@ktTz7>oczNsT>t5$w3DH9){gd0Q@$z-vp7>+C zm*NPMAquZpNhd4NqJe=g%s1_%Y9H<`5p5k)wWpJ-=g_ z-ta+^`0h?__FShU6y#>d2AX=#}rGWA7U!oSb z3d}h~ZW1!pgJ(|_e~?|_lufhLD3F}qm0(bMYQTM^gKqdZcY3MM=qs`$&pOR#dvBv~ zs(3?;;_SGCf6yyX-MMk@8ReP3XMqr+(2Xbmhn0i?4N*`D-y=GkCG`WjRsnOeI2?sn zB4X_{h402feiA=@rFb`;;+%4xr7%qRN;ssZ2Iob14Thv-NX?1K_iPrlCF`WLv|_LB zDI_w)p?gsCc`Nur&e+$OB%3-%a8olKkjG!&vyP6vb^@j2@<}2S4FU$VRrl}QT2ka+%`!RQhj3&SzWfHAF=ukYk(2%%qYSwzwrNS# zWvrSoz_Xd191E2&({i0teYo&zymKy41)GqzP0a_GbKBiTu%X(4?^jH8bOssj{vq+~ zY*3Sgtu2LZqW}w0Y&9iut3gL`+Rm3xANk`Wns$EK6SBS-y@|5cWaLZvhpb(Q^cp=1 zn8cD24rpb)yFO^FeIcIX0B5(}G_gL=NIfJWp#}pJJlR`Mf+=tQTv(t5t~SWB>;XD> z{Wl)?rJAKWv5P-2YL!DHDM1#!uw(P0OoSu9ZN{k4ih+rV1|muDP)+sRmG!>dOB78&5~6Pq zVm^n{kcA~2-UY}$fsT&V0*s!p$ zhqqD*FiQenYN)nH(a4x=XhU4UQNlqcV*eR(7`eFk{>k~tQ7LwDd`i4}dReOw-dh>B zC_PQQ#tQ_b0)9osmjw6zaiBf&=#4=|y^FhV-hzUjF<>oq_bvz>(|sIKTAMj-T1xHj z7|4bgk?}Vp|JktO;9MV^CsTTJzFFIL;Phu#HwnrOkKy>@H|BGH;XYnl3KJ6>KoNA$ znMeYyqoV_=fuPur2MG$acr&b&*zewE_~bF;hmpW%OCBM1Ssix;#E1$M4|h_v)$Ypm z^ff-|Ba*V(Xw)lkr?BuFR_$1?2s?0v-_QU?S%m0m&gg}{(opU%f-?L3o4sB0DV_z4 zIcdJ$X~i>NLA(!xHqefg2cKtaYiq4Y9pvj1Zw9fmm9sP?zs3Fg{W)HX=ZhY}m-Vng zzk_Wh{CE_D?!l2Xv3;tSmsj`K7(X=U&s7NPH)Y83cYjtU;KYUK6!x8=(b2b6| z@2>_Ep2XX?Tu5Xnpf=h7e2{teuda{%V*N(T8(#?>S-6f|!omd&su=j~i_|cs1)NNf z|6M;)AcFzie|tMxOiT=9EqwWDGdO}mLSNtlYHCKD{R@K{66M&q*yaNqJH-$a;!`4x zlkeTr44Z!9O3o+L{Al2&2L1%#G?)Y@Dd@%X-7eQC>U)CcnV#jG`BTP240!#qpg~8I zxzwG?q>zxm!JV&k5qf0R?Zz_Jt>1aU0s*3YJS$k>7T|Y6p&%?g93O!GVD@zFik+Pu z1j$~wr!e%T6|=9A`J2l?wuL$|q+ziAnVocvhUDq($4L86M26V;oCX(LO7R%rVS0WS z8~2jleinAdMRzROo%<{8WN+Eh`bo@yy|z$_B4CNRsmB0mh2NjAUi=F*-5MI5a3SEY zl03<+lC;hIsH2Q;Xs8b(yh|r^N10H4cnJ=w&&`5)1F;AAnYqJ058V&E75I>hY@hlI zdJ7o=!T+WDZj1xS6yd$L6u&th%EI3|dK9+I!nWH-0GNuwA0Vnn$9 zHl2`DW->YChimYP18RWj0@svSGYh)&sfUMv7<=%Fz(Mears7$*RU_qwaHnOUWz#_E;m9zDWvr-t=6UFkDowX=2}ns_xmRxq4}Dmmcj zxAXNcLKGd@kEJLq2!gGPf(a~}HHy8Pq4pRDELF1I# zLSCan7#WpnJJSn-oyKlDTO#v_u&~IK6a|O{!CUUFr>D+dVlm`*jjy8CTQ-O_dremd zNWrN)v#CixNy5PQ{~5d|w?66@qM7#9*oRUk!`~tQYVoDEgpwa7`>VG@R2)y5Fu%W>b~a-~SRQ z*Whh{d#^`A2Y)4GDgW?M;JIDF$ALSkLE0z!O}d@*!9L&&PWTg(XlLEj0c-Q# zQv%GQK+gbi_#EJo4B*#mA}yHoT$>gG8NGPM+ZJ6X_p}~l87C9VqNaa47L0@1{Mu$w zvd)q(g}FK}kU6&4My94QDJg~cs1Qz10JPl5$S4w;aIm(ayDV?u$JoY)Y zqiktk*uQ8Hg`+8_xHubh9PsA~udW?_8a$5f5fRCN^E5FrvFA>x{sLIfWy2i@x-86M zf@0-xVEb16f`;nLVNEBegD}pI-a}i0^6!*6&`(l{c&I#}Jt7ZWzP-Xd({EtRo%blI zj9q5DXw>Z1kB+}3VH)LcH@=|%El72cX1!}U-oYiZ_(HDCZIuU``G>-&&&TqK>G}3Y zvvg~LI?`3P%lm&a@3ZKxIoW6_<0B@>OV32M+#)I`pMR9HBAUm2Ay19f$;rt1NJ`Y*>PTsXa4tHtxXmMp0L6h4`%gHm?om zL!EgER25?-_DzwCA^~?UD?=hDwq3~XsM0+Xl_^LQ^SQRSmXX1LEdFMHk-R~Sh30U? zvqaYTD)Iuvu%uML7`fUQ{PG??0&=#n2oHJOgTq?rR$#AaGW@Tf{a;htg%FzB_5FH? zAekMze4ihL>vP8P-W>Rcx8!gT8f7MTU|m*E+N8R#JrUpBaTIX-jSk`fK-xCjRDt1& zjHPA1G;5PC<`Pr*V78KFnm1{~HbN>PRrSuo2bF()hHi$2{vhUrcAaLKNw_ovK%S$4 zE(mONDN|E=IB&p)!z{qw%d0`@Ch~=lijt%L=DH5uQ`PMba(%RAD+B56#Nk|WzqOvV zLCkNqU1$qdWA=TiB2b+!1%r1mfgvU#nZpn}z5#5)?`36!>(^0&P1A*QcmTNGKw6Oi z-NL{i5vjr^+Uk#yW3^69djvoq|FlaT4%W=~6NzTNk21$;D^HROR#D-37Tc4+?cd+`k8(ESD-x%zj+p7gJw`IsJ$?HPB3?T?$Y8XgPDyCHgFBCp zeKb@!3cbUhzj&}iXBoB@;zP_hH(*j$;&tW>z5SK7wSmK8=rDj|#v%|^Ukz2U7nTBUeyUGSkt?=RzJoBy>MxR7ez|anM_ng%}k^|$5 zgTiRbNQ2Lx)=1cEQ`MHc)_1u=>h;m=2#jA}pP5ePFpR8C>&cfF*1-S*wPOXfJJ>O)#h{_6TnzM~@t-fzPFzK=cKQw zX-3#&rVQW~Ljg3^ZHbuNeTAxx=yn;UFy~TqB;mp?%yx5cErJhLePMn4GKnyjJX6opGER@@x=0J6IsIBbl>_L>J*CNFjO4BdFi zr!Mg#O{$YYLy=S^wu~lsOcGup&Auy@!~$q;6x@&}ogj)7Wn)_b*s}A#iCnj*2)xw( zs%dW_Y(nO*1qHtm*joA&(gF9yT{Rwlc=my-KI%-zYhh|;vy18Q23N4ToA&zZh&kIT zO{(MO7j%BzLVn%Ug9&u(8~j{n93Ejq5w=+TBfEs-z9X6M=lgwo z)*!YAIS8jP-~Ydjv7Qf@5w@uAOXwKQ9avyAa{2d|kXI{x;ISNesiM+G6CvE1Eqd@I z&9800pMuR&9w5bLr{0VT+Oa85U63YwXx?@AY7x?rJZDpR+cGL1MG$KgqAviR`!N$! z=wtafGl}D0zkYFVE&xp1lBCwOH+e_sZ|cNSUbE8VifEy1n#b`31GPa z;V9_y<|k?#KwZm1X$<;1$kQN-BRM<@3Bh{xN`;tgdxhnwM)=@9Aqh0OZplQD4VT9+ z&iFiik7RiG^*KFM*5A*+-&Z^|>|_4Am2B$KDMgFei<>1`qvxUe^5as1dcH91s2uM> z(#rQfW(+K};O-yzF3!GO_=MCORh+69Ow6niQZis7`{dnDxst2`?b4FH!5iO^Pj{n3 zKSGPC{~MdCU%wH^5eBEG6yfXyXH%_5aBbXWHCNKN^ml7D2#rR;O|7%D6CA>><0p^l zGd+cT4ZQfL#hTKTM{=>f1*vxX-vtVaGXZbx041r6%uJrMu$#TPH|wx6UYMb*N2tXr z#3ih3Y$U%6TXQ{mNOLhMUJ`!D9Ap`7s6%b=^yBA$94Mr$dDINh>G zw)2~*jyCRp^s318PBQcH63n9vg4h%;I^abECT&bF&ri-zN1JYag%%{J2|yA6+4>-z ztE!h|n)j>d*!_Lx+B%P%{Im72i^kI?%}2rB>^|Pq9!KP8l#hSP>F6*31DYN>RIrag zu_cxGz)^%M2Wl3vQjkePz5(7sXd=q*69}Nle_cxV^c04l8kv|t7k2fmozj2%x=H|P z*?SU*I5~7G-uSws$-PNzc=)Bk6J3t85h}^o2800AhVp97(UgZ9yv|KJ8`XtMSNwr- zqkU>hOq1E2k+Cs3kiW%Mo|p0vwWr*+b%LT@e~jf#&Mr{gYScPD0T~v&>?^Qtgrou{ zM&H004oNCBxgg=ixqJ7zEv&1nD;}_`BXQT=@%yRl*KOnX#m(+BXNkNtIz78bd^umj zkS{tPqRZ}8D4>@$>)yP?Ta-qN^d9)lEb=Z4lg@SNH!)y-1ng!|pfR2}nvNN445@Ee z7%kLiK;{fR*=z4Y?yjDm z;WdYzM4mC)P*>6DO};XT-ccg_d|bsG3m-Mnyhe5?t6igWO-1*J*Vfj|tgQCsuE3y_ z7Cgpb4Y_-G#P-pi9&A{Vh7vw_sqPXvG(;}U7v-t1OMC>(-T@sEIJr*0g+2(Qb$CTV~^!!di7goc_QiCy7 z@Y4DDIprVElsBbb^by`yF4ebRm+<%67xsL409_k@DF@#K{!7xv%O0_(ZUQw?qdz9; zwT}0cu96tz%7nT6*K;v$g)AZ3a;KZ8FL21VK77lc_~GUAVe9-Rr|pM@d_n^@JBIf+ z^stcFBKv9XNnQgOsePyWBt5W4HR^o%*yjx(ZFpp4$lU^9i{HN3@=1fXGzocesoEP} z2=KpgK;k4KNs?JoqMZAOexrt*yR!JP$#{@)O84xnLE$Bo<)QvGV8jMNagF2ZJ%DXx zmX*aom0%m}Nq5)vul~!x+!h}kZXhMKwMiAT2UUsg*Nf%G#vd%B-9u49AEsZHE+s0Z z4YasgY>vNZ#8md_wms}Ru`1FoD|sfCn!C0u_f*L+CvN#(9*W_q@Z#nifc!KR{3SbW zhekaxuj@w&&Y2MCo`lF2Ffz@%4!&b~q}+FEPuykNiReiB5sc*km&)7#I|U zS~@yfaw@ver$N(A6<=6Y6%Q_bJ=m{(3jR20!1DipM4fe1lwH*J6_F66RJv2TB&87$ zDHTb90ci>8hLP?Nq*Fl}>5d^K1{fqHhVJfWfcNk|>;1leTuat+G2V0TbN1Q$x_+0A z4jB*>@E;~Hk$*r&0$pvTPsC7O9$RJ8fQ2$|;o4pM?DE(WKtVohXUfMC6*deYxEEGa z_c}kTWY><%y$RDmx-Rz^apG6f26=dDAb5b@6exHGKWuhvIC=DjgJDTGJ5BR+sKjIM z^yCvchERG9s@}C!eaBA~CE&#z98@hy^RSEn2QME#zfQfwFS8=t>q~$T@WoC^*~Ind z=!2VGE5Y>Lt{@FgzOk_@U=U(IFZCF-LKjZPAzB#}ohRX;>WyxI9X(|Kw{n--5(sZA z(>t2AqFYn!1ojgpw--jwHQ;<9@XmmuZ(6k)e-DX2S01d|p!Qi{D|XPBb0~|^Pa7Jf z3-yny;cCI0P@8D+-ruV@Ezyq`IRgiq%c>s@Li~RK#5-zUaos0;KqT<%LHJmFz&pby z*~Z6PpDr9$2u;vjLHiB7xaANH^Kf##zRwZ_FM!6}e_e*8O)hvqRw;=>{GXbP zVy~ASiNA9nRU{%nuM1@8fVQx^C9A88%V*I(hqn?C-wTuc%Lo)&(J*psi)Ay^>Kb11 z7hZ}h!WnO#`WMVU93Yx2;uPnfUlLB()T|+b0-_=#1yn{jyssx#!ap3E&tO%k7KD)| z<0PHn@DJ;2;LAMlINO~um_mRwUJj5P6ozE0vs_VmI*G$tLBhu?p?c}(Bui9(;#B0I zQw%Sw(kV0dc)j@t5C2Cqk3cvMiGp2*dz_H&tqcSy!HkJ)^1F3@NwKkK|JkGx=#vwk z@(^XV_LP%|W6Iyd&gcRXnXoqi*t$+I{|yo1*a-X_EvI9TNT1jjUR8J%Q%j?pXI$t9gzEGQSDDI64Mp)47+ zK$8UgP^KapPkg|rR}$^j~rOVmawcv0y(@^7C^aGA^|HNFy;& zaxpS|d@7;7yBd$$)zl{rclVq{;`~6teW|^=hH2l>V|*$IUM(3yJ6j`+NfQ<{jcCvM z+1Tj0ki8Lu60$2w2JP!9;Mp~Z;_-Tr(^DZ z52DfabI?ryb`W#)jV;jW0`VGP>7{ptfU}V3jdU9e*%iA)m`kTi4htF2TCC7RCWYM3EL~HPUpst-yUY`U_ zf^Ldve&H9dL5pRc&VrelS;u|k4M3W_I3#OQG|4s<=hz`0bV)n=-jULg{8!MRbgpYi zo5fsSeEdR0e_xvHTAcdoA-4DFd&Y1Cz6HqHO;I`eY`eQ|c&?0Zo;OI9M81Zs`GPs$ zL36`1k3_z0;ihnpzmmP_iL)=f0pzfJ&}KC>{0j2J(5N?v2&KvZjl*gQY>DoKgM1&B ze5YqycC|d#u_02G>L|(631fqmQCYkppa3;r7q@yf^wJqpkTkgq_eauHAfDS?kQ%80 zDWPVO2E*rv%Ug&<^WvtG^73yXSb))jM*H%m(#za}4Mr6eXMQwo^6FB;WFX618;R37 zkxRYN;o##V5?}T*p}2nhhV>>8J)AIN>Vv=qeTxKvH{!XPFW5lIDJXORCX<+vz)Y3V z#aYBR+~9;ZaikxqCjgN1ca#XAYq%FhE#5bnUTV>X5ee2E)?#{um5Q_ z>~h~Z;;vEJHLkR0Z4mar(i|E>2|QJZgPqVt>#Q{O;;7n9PKgx+Q=?h>@Ja5%ErRqv2?+r^qJJi_hqV_qLO`s zSimt@QZ{6UXZy-Obrb&H>tWp=wfvyTWqvg%6Z|BJ{wG6j-`u3MiSi5ghD%6%Tn89J zYPq*gr)t28H}TC5na$8Er2vBq*cHJr)h5*dFDo}U2>kBI5CgEefsJj7vG9>!v0#OM zW^|wJgCh4u)>~nNyR$|F&)LKljz2#1K$g$pc=twKmrTXV4zs>Gyys;rWa+=8}Ewk zi=h0&r*Lqv-|7Cl!bu)br>{z0Z>R;CK3e>27@M#r(M=Ua@j5b^(aQjrRmpaxWv^ML zF@~QMiAYR%^&V9%Yw-w^q}CqtiP7q|D82q-*d;A0eQw2grJhkvE;h#T$(cljzve>j zO6g;gn!|6}IK<(BF`ZWvr-H|}Eg3xa+j-Vb%drWh3SJeF6q3gXYpe8z?&#(=NlulV z<8Pt`0|txgI7IGy2+c~eBmkukEkS+icPySkyugX`B4(1zDoVyxMh7;eiGD~aeF4@L!VR=_ai z7c-w^cF0S?>wrRjhiDi6w^ukfH-o=S2Gv>{>>kpfY@e+)y-ruEx;gmhRs4x{vR9F# z2Nr(?J=VIM{gjyn5zrIvK}Z}K?do|mDD7N4<=|YqhTcBEJsPdO*bZiU&RJ7gg}O#v zLupK;Mk_r-v|uN6Y_@uDq=7N7<3<37hC!-DheLu&`CUrzR6`pp?y`y$IBRXr; zY1L?Fr{eSI0GPMwWm-94G7`1eYg>Q)GW*EVo`CxPF2N2hb~<+I zpCx6hK5qJJYg6ZxO{G|$7+M=hsi$%)jnNFQT=Sm?oImezY87&6J;`-=%16Q1l}Qp> zv}5YZNf+18hu+2kHwFcW9`8$(B?&(|n|6H8wKzmwT7 zTzQLp7Ob$2g&~9CV|VPA9}XG$j;Fc>dn;$=Jer3MWIR+}UnkxI6qu|>T!GNIPm+i z^zXinqO6oELeUXW!1FT2X?RO77r@rw6-NKt>A^`c=a*7frvfR^mFD2$93)sodpK2Q z^Z=Bslqs?CgdmYRozC$`tO{Qtd-Ha3GFQ!w2agpC#Kr<+Qq!GC!CGk35$FTJa2iMp zoo(wDFe0u0ojoK(C(JEnVEE#qar?bA+Ij0AP;HTtlG1{HXKE+dIEkoicvVG3u~4`B z9Ky~=B_&kWI;+--Dbj`Zzbllj>Qj^_eAyG}0hx^==bJ)0Pj*+QA+W)#y&H*>@Y|?v zpQD#GUPfejJ`UVlE$5G};~stF5-FI~P}-ik?fO!)H}4wlnA#3{M-?d03`^;z(F z`A}PVXW6=b=Bib+L|f_Y8j08SAc4X4DakoP7a{)TP+44~+PL^~QOyn23prfk*5oNa zLVE4a87wuyTrPS#p6(u1Q5NSiEis_xNz@KT5wO0g(8Pmhue}~v3t~SmSz>G*OG5<9@XM~Sy@1c_bs^QXSBbfsgs#M zy1m~E4alTSn?2jaH~d0vJ-bY2AxG*PgL{4qYpAH(lqgo+3Rt)d)^8i&*H+S@YK8?yytdL%w9#7-87b=!uQwo_XRLfSIzrz z%)i+KdNbb2bGszs0Kou){UT89q=3PVI_>K6@^?~X;)81?2jCdBw6p}$qoJuOQFg=% z`~7Uu;}sqLRMFZ=YrwN2^J&;n^C(pNqp|V*`*)yt1080NtE(H1F*iAh&C?;Pb4vNd zCCL(bS@eKQDZS_Rla9vir%BsdAaXBs-`=R*fa8ulp#(4c?Ck8<pRxWnA9E`~Xbs9r z{wsQs-gNvNWu5ht-3vlw z=AAgPGjxDR>xlM*h5-JO+1Y+oE%wuXG*tu9C}XEsTXP1*r6HQtNf@nY^6oc@%MMy{ zQkySEjJOsyKcFpZ4}Jjin;tq29d1ytar3f!tTH>>&$S8O#cA7yC~79}jrXuUDBp+i zjKB2`mxag6qR;rA@^zZu6yCEuGzkH42vJe;um7px!3-R*0W7ZMMvs60=92y53RwzM zkQ7b_NC(iE6}bA~{Vr!5s6T*C7=S@cj#dZwql6yan0<%6Yg~u%5naIHY*?jw+4cqx zfAC)elUsk;SfB#ZsREmzTuFcUJytRvN%X4nK zN>=WMzK9WS{9Wpd+g;-{jtg>Um{$zy?fi@t>jI-3~F9Syg_oVXXebib)-~FXX0ur z66K6gWVWpyK`o!T`^@X3+|HnOb7(ka2_F+9D$Gu@QFd37`^SHT$ulomU$V?064q`a zBQ@20Z9_{|dehY*ERBs9JNTJD_q?OaueNBId(oz~TZd+uP}g5>`X{4rzQkUa1iLsy´&+b#rcR7e_lJ z^X6tll3w{xC9jFZg;41aF?Mv#cq5yVMFyn7N{{x#6`yKf8u#^dHn zl1Rz9KZQW0-pGS)%e6ecg}i`$8J%|^i4koG?uObYRb6E)1!p?CNoaDo5{#TsQ(sOx zQo^>RiD|qN@}d|k4nVhIpBPd3?n1@(RMMNEO(lxTBZU)_c)wuIJ6LT3eB`Il=H&6c znKq>p{0c9*BuEV`oo5usm@vj2Q>=-&<Ys_nSAYSlAzd_-sGxN^K1iM{V7vMr8B zQ)g-0cd*L6P=DXen#OB*$x~KNV!Db*@b-QN3^U^v`*;?u^qSIIUDi^QAGMpPPL}C^ zdyZX5T<&{U5_X0@S?1J5cl)!RsyX{=qhf_I(z9pX6sND+@kAQU zk;`p0>S1r%ce8BIPW9huXqfMG>PMvSIXWnkn@<(FFMJRePVaoBpl*k>Ii`GxA$1z| z>}&A+yO~=PqJFHx8^$J5jWaEVX2WE$J~;d+_6Hb`9(nS;N*Dv+Rm^*k%i+YjgFh5^ zItHMl07KJKRAh(@{|mr_m?{V3ZE~H0&2ai=(0B%t+yY?9eAC@ST$$BlmQw3+PCsx* zh=4FU{@01#M%E%m<;S$%95(#bW`-20<|)Vnx$q#nN^_(irQo3|IEBa;ZZEe=*=?Q) zZd{f8<~}rPad#1)pcVs@#*>Q;x--dmr-xF&LiyFGOx`k(hT^%mGUmK^HOfu}0xgoUu_Ejneh?jDBp zc{mU8%msBq#F+j3y2klim*R{E)rmdL-kk1JNGq(#+BxaAS5%l$=L_%71-q+HzY1JN zHeGydx%~F%4Y7G8?KQ@1bA42Kcy`32Qsd}@*|px4ckz3}yr1zP^lSf+J&y^IoF=on zZLy&plwux=M&T{LWwbM}zFGgD79b`$>Q`-W3+vuzR|`JNUY?;jM1be_4uNhv60I_3 zQ_|cR&4*{M23;tE4)wPew-^#v z-GqM{U#@5D>j&=%M*|Hr9jEwX_@u;TSM8ON=KD3EpcGN_R?AqKzrBK?_Rh548f?!0 z3FAJ>^HtO8xvzc>X^-2A`2_KAmehNI^{%1j6&PTIa^@`>z9yP;@|Rz8&hz3t;6zWdoEtG_9o zF4W>(uxw%Gtlv2X9z#g-}&>N zW*m(_Y+v)>EdhRumO74ZycY2LNnOGZmA)xcW)L2YyZc@nw|NFj?eL zmPGI3uK^CU`)J2OX8b<3Zy6F0uA;qFFRP3%J=0?5|5{R0Qmt5TRi)bm;}M>W!_cTz zK8P=i@}+$L@XgrFAflybt#P*jM~cCgot^#8oJ~|`Hq5eE2Sz)Q6Ts@ZeCJ&P>Tod7 zT)9SAqeuu`LM5Izm3qgQ0IedZb(mP$GZ>ap8q(hetVfWxg1ySE)1t@BPQ$bo;85bC`m<0v@4H@XL$=;^% zfqJvI^qd?9=BnV*XgdB|KV>w`4tITPi$PG(B`A`u@nHnoR-xG9$&&^!|Hj3|C5=U0 zT8*z$j{q|*7#PwB% zbTpk~!Ay(+1n{T6=GaUx(EoJ*e!8)(`9y>mA%Ut`*x3>EC<#?u*&Dv!;<=Z10TmZI z=*qm!NPh`ML`$ZqCCT>$5q$PNDCd3HyRq@n*3__B@x|ZA+4xL~buhFW zee$!9JjP?-nD+DhH0;>qS@>lGYs-?}t58ctm9L;jsd9|!%|C_OGV?i!Q;8KI4TnP;_ zYQ2Z`7zeW!8JEixFhr0u)n;bNd-20tiAy`zn%|1A z7Wvrdm)QBVV2#ZaSmOB-ocj<_+oDqCkJf1@Nq}Qd9HRReKcNHBf_HnVqMI0gaC?TGU+9-PgW2NM*3s^ZjeqbN`@roYWrq3om_Tg*W!)CCtn$&# zzIcz|#;5yj^HZDb5l?b)5UY3O|0^Ub-HWHeG6935lG1?l^w*%;5Pry9wIP z8*t5^+%nCot=0Mn-0UlHnW&sx*!0kll#0qg+QWzuSj5$%J~t6}^hZYF$!p^)^uVNh zr0pV1`NrE+yuf<-Oo&lU^MroT`GMy93K$2vMdLFAEM znpp6bu!!xwrW`#vp|+W~2J-6_`}*mQJ?%}ivAvZqeQHX;xoK|NG?C(n{@@r;SlfU zW_jvAe7-vXv9!)plvUgOd+-UKUd+m!Ii@0N`6|W-HIDgD0In|iBQ+^01itb<7G*YG z^azj?rUb~Ts3PGj?VqdJO5g2M8_Si!z#R*`r4tpV;j7iwm6Q3!$6owwVksJey%&1D z=B>2-Jc{G9Y^vIibZqhcW1bS{G;9dZc4qyB7j&VyVTqJ}XTIL|e#E`_XJw(PsV0?p z;Qp7`sF~8?rxg*yzZQHZ2?(j=l00L4WEt+JcURGGw{RB{R3Iza&)A<=aT}ZZ^c{yo zU-MbA+KSGJ8IiuVF>qou+NHx-e$c)noDek9V2)q%9=bk#B+4QaX8&~H;Q*mxc?Vv% zL3W|5=w5m5_yqD<+j|8GqgU@gyuYX5T2VBTMH9SISdi}SBZ%_NunZrQJ~XqepJj40x3ON1q=)ybSni*?diqUS$FTBl zy!Vx``zmiH#e00cyOZ>^L&PP%FSpYVGvggy&fb6UUNqplAKH87RLji@2U!DZ_eED( zt^(iDzep_qYpEBnbiNXtcar#$EU01cLw8SO$`UL>>}79h>ku*ntlCHSrd=_gl1L}d zV1^dRhCF*OvoNrPK@EFimroq~uT661LDVO0dxribcv2d(?*mTE){6J@&zoG#M0?BS zCq}U0O5)3I8+;a%*eVz_IDwpgi`v4&_i%8sq%K!}6(H(0c^+frL&=7os4o7P?)O|Q zLBEE3Kp>gpICpm2|Hkcii5fsUQsT}X?s52x$Chh8+$(1M0iEmvn?|V@zTVP!^DIpX z56e-D;oO5UZ9J7@i6p-s6}I|cihl3q5ussF`?*EN_WoySDWZrb++m~nN0+_Xt6wT- z)xPIW6Idi%q+W@9f$)PCK`SWax`&2HC%&b$7ccv392@$ZS3QEs-w=LHLMd4y4$D{o zatXKkn|aWgY5allCo0)X_L?^=T&(R-SFQH*cv^;`pe_kP#z3KWd4h%NnX_F(slR%9 zIxb!Y3j>{h|ERJp#N*{!SVHV)_J2JllZ_$(MiC-`|BmX}nq^~BIcve=g$v62*Ci!Y zE>1jOe25;XL+ZgBPqgOp1jit!s8IF8+iz)XXi5YgpL8hm4&_N4o&q`z`Q-70arFIJ z?~xGN_+IlL@U+-i89+$@IeI{CH8MQ>lh7N)PXL1O_dB?`w#l(FotQcamtIdLLc+?U z_<8r8DylSfQtu-gn>%TxQ@@|UrD*AYrs$FB>0;cQH6^0nxlk-Jv(D;)Rn9%&pNf10 z)a)sv3hL@{2??L|hz@X$cz$o z$jH$4wm_{{d0r+vx(H#TZ%bqXWs~0OVX6qfR#AG3N+@ic{GSN!1(5)iu@QbL(`y`Ocz;0#M8sz1G|{Z_MaTep&7?gs68 zLo9y#pyd=khFgDtInC3aTU($cP8Oeckc+pJ_HlP@s*VYDzDjdg+r@ryo}PDpYNJ+R z)1U6O2S1p{HXbc;tmj%V_Hmf0bvuk?D%Pt`!`Ir&l5>+m#@3zArji<*q6E4A_yoN)RWHml9fv-QNF}}^QaAI$ zMs%wkX2Y5~x~;;rn?FAp3py*f6>G;}iWxc(QJTB?UYKBz-!Tz>u}U?$eT%%FzTL(w zHmLQxh@OMXhIb_2?1-2I%9;$8ObZmGpZUD+;Wp6eXW1G*=sk?wj!WwAIfDJ!S)(yu zK)?oMOTAhPowu}4GRNH)t{qhU_y3ZG<}%EO-fyey9ti06xhLuIlxzFgv9e2s!$8gO zBbrHGYoGbTnCaUJLctFhtb~M^?o+dubuK8r;m zw8Vd4M1z(=wLkSqcpJNg@}9A6Fva4$@7DZXAIX>{%?7jkYS^R51dG;Ak9lEI6(z z1+*EEb4> zQ(nYps;$d#SZ|aeaoVxMTb=ZgZ*rUHeq5OpKoJV(hEaY6AQZ0mq-Lew`N%qD&{@F=&);$C z0}10NbzDjEm5G}*>q2LUtp~yFwAz{kCvZ$9g{&GETYeYHO0VyWo2V(VeXFU zqS`PzKK6HNYE%8U6aXKoAeCrinG0Ed#q3QCZG3yoLUKPK4m~R^YBK3xDMV5>`~q}j za4FZvPM#UN!+frBsm!HS9}VjS?Iz0*xNN%XPk`D4lvBVRYmj&d$Ex~L(AlE5D#a`~ z(4#+dGCa1EqZpT8P{2EOKDObRs`BWZLGXcP_-F61P(=YM_rLAW*fr0q7-p7(Kib>I z962=3NL(J?0@o#q+%$B%PJr7o`*-Npjid=gmGY&yozFT1N z7l<5yUC`Z5kKE@?bhzyp=b6vOyjW@P@R1~>5k7fG3_H1(T_ZNgnF#4i3m%U>Odr=d z9Oc-)KSdyMX?t_LKK6?9QbJ4r^4YG(;$y)b$&T4D&#x`aER87oBe(soIUe{C9=@I@ zHi=sEcM_l6O zPnQ6JTOZ3Z=N|QuNMd#2BTS}EA8OQHkAJu)1nmp3AT$$%YMW8C%V8jNG#U5 zw@cc4Y7Xm8v-+JoZxvmUJNI0kMFI19%9FvK(%Y!HIo`0DQdGbf@1?Eji`K1C6IBy0 z-4`|Y4ns(xICC)Oz!HSmpGGt4U1>U^@pS0Q#g${h#kd+P>eAKC+LE!7#yfCMKYjTm z_p#baP@chx>-Z$=#TGs*YKn9EV*Vwii~eg{U6v8jjJEOH!$Z%fmC!F;m!0m*d7uF=&c z=jG+46t?>cd{pYT-39Wl+j|3idAYd&Z>9`d3wP6JagXl+B#=3_<%tvobN~R~VU5=j z8Oh>``Nfce27E#5j-^b{ap4KRhjFI`ekpqe6%0vM+=GpJT(T@0)r#hMIt}8MFM)Gf z$!yTjaf8_Zb<>5Fkou_(8Rr0J?l39a0*7(`Ic}1#$Y|a>%R1o_hhm7cYa6gF2 z)ZXwyGgse(Ec45hvYswEQu2oMtM5qeUokUWFiRTwXQZkcg&#_8L4jRkQ;-20hd{*v z8syVli}(FnML;x?mG!4f26>HL-xv(Es`K-o``6u3eFbg7BLN}-@W8UdJHNJS!7ep` z5FJbcvjAEloH8h1R@yd&Gl7M6lPTts$g*f{)GDWa+l%MA8NhAs?8pFwbMl-@pcr-_ zRii(iICj2SIdgunbVn5e7tXv)A9B#l1mb|^dzoV9w%N{?}hrXjbO9k=`aLtVz)C#a*|YPfr~vB9eNZ%N`P%20i^fI!sT1!ymSFW>c#qv zLBOR%p-QX2dSA6#sA#j7e$8^_ngeFHK6n%~hsZEu~#;at+$}Ka#Y0-LWqTFJC!8B0U&Poht?D&;lrQk~G zP6#(e|2AHS{J#l~%%zT?$HrD&nl$*P_oex^27OCykIGlgT(owWYMNSOoGIDTH7+J@rNU%o(qX0f`X|}R~(zKclqv- z18=B^SDiH91Im~7e&^@sT+Yw4Mh*nyLSt&jtdz7NBw}P)9z;z6P=0oDi z)0?*j27_fr9TDEre1PEbR!a+WXypl1#Ma)P*VJ^j0d)Qr!5R`64Cl-H^^0tFSaev~ zU_zDS#+>Pi(Q0}@<6Hrx9&7!$a7An&L{5ato^wg2(Ey&yLC+mm5p}q^Gk07j&gerD=W*AK;a~FPekK`U z4FXx<4e`&WwG7XQ9mCgV`X7g=61%rSo+MZlUy(b4RY}eU{bn{A$0fk|2E12a)^&>( zJT7r5Ww0Qxj;l$m*U!2x0|{iX=)4Gr0xcxsGwX1Ynv0X0`wQ&V#{7Q|L5R^ShakHu zSl%C<-*GyB9BbQEanNTrc%a`er=Xc6ozMwz0;6v}trH)PG*@AU0YB*1#q==6u-z@y(cY8lUZ~pkt{ok7t8;4A40ZuMD%cK0#$<7;IjVe`K$@3F9fO8aukWF#_K1(c+X;^k&g}m z5=ySba6dmZ&Fw}JA$Qc>^h#n38YTG7hfIsYp*iunK;!==JHUi=<5&FnFaZU{tVa2saQG*J*tnSPUb}S83QU z9Ook_o2_^R4aiHjG0TaMug!e6e10?Kt3gWTv1#PpaG9?M*_25Xb%00oA8YN27vQs( zid80>+=ot$i#9rEG<0){J-s}*}& z@ahIkTKA{%J^_;H2Gz?+OixAS1%T7V>A3>yrediQfm>pRq^3}9TVk1io+;zZC#dlg4$G;VBvW*FbeD76i=ZfKc$C`sh@@apXSs2taKTdd$iE>e zA0G+OzR-VdQazBQj}O&dH@jBveCY(7226r&TbvwL3%XqzwE(x-2Vm6~01KO6Sa=7# z(w8VnY&O>TqW(@*S{S+GVm6Q>2l^dAh5;&G9_Wo%X6XBG2H<-(f_-kp9djw_C3yA# z1NYwX&IB7({cb?B=IlmAgfFhXcXH&jo84?p<5;os;#8A=)pFpx0`o-H=g(=u2x7lI z0nWOqmY65{mt(i!u(R&Bn8Qc!gD#SKFemkPN-gOtsj&p1M+}v;O(~{V%ln5lyGkVG zZogFhWD;S?C7MsL01NsDuoMFy{h;`n9#Df!);s1!uU5ehE&(C*UXwQqD{HSd*4xgp zlTgEdw^%<|LJZr#)HoDxkM^3qQgKgu#>Dh}-6ykUzs) zfsvcN84#b!%@Nc<3=H5u5*tasCWnR$n_h?T zaOdwM z`eF+$2kM5Vl1+KnW~T+YnUEK9bMHC?g@h<9!^*%uQblNaOhYgb`tQjrd3ipQb&$0p zQIO3cwlX50V}HJH1as!uZL;5%oG+0ioc(8!?W5f+g!s-oO1;sPH!)&iArf&^7hJW# zCHkI=k&nwaH}XitrOMYxl|>ihSj)U4Yy%t$si;#vf<)#slHke#2^I{0w^G0#nCWxL>Up*+V2!^_CM}+elU<{7zeu8JwN!?>c3G4l zqdyaRBSPbI{zL7??4oDMZ_KU0vxb*K-K5dkTb~mNf=TN4+i@a$?}15Yn%N1x+HQgI zci3TwfB+jC8xSaUE*)5Oix#a_gP9%xswa!N^EJBeonFbMqByb=%rB2OaH+Si(PZ;f zes4v$OH_Y3ZxqsV`YRVf%IjBH$OfpIy}-XiD&Zvz0u%tG_%oa%FBz2QK)Mg0bo79b znUFxdBb@b52jDc$=AbZBsuKaw;s=M}wiW-N#l+>~PwQnyxFa`|xDne{I0(J%nZ`u0 z0>M>V2Hgm&84d6{K*V@oT3S|1vzS#lD6kbv69yfB4xDyC>J^s$#7Z}n#Pwf3B_d$RVv6)!1n@^?0{ z_Vt=2&tJ2n&3M!1#(&b8UC(k|$U?29N!@T0Rq&qf^99NfT~p@&v;g{;l@dR%^b7)F ze3-hKW;-7eYm>kGPHC33WDSk|1;8hC@GA zYK{MF+RR}L=J-`Uw^PkoXb(v=Mmxcrj@e}VJ<#FfS`RwQRf!L-lvp7x5h1=06qQ~Z z9v^QUM~55t)UOeJ)Vae^1Nsg?S1Fasm)*Q+&BQF)6ldi|!vZ(~qcnVz2+d}X66@0Z ze4ZSv<#V&sUa&cM-CV3uO8QXl&vrP1V3S3_>n3aH=W{|}eZH!U9VRf+C}1sm(SN8l zGAbR@4-8!#+GVY;k(s0Ms_(n{*m%(OVKktXb(Jjiarr&CA|7k|}d6bSgH&!nx??Toefh!p)aTa8LjmD3zw6rv9 z3*N-UL|`|$TM|GroRmar)4&&C5+zJSLSmk#-tCyq`TtH_aO~1Da1hvhm@)rp#@M~# zbB_D{^?PhH9cXi03GLJ{23dbpBX~|X{Ur7;+W;`N zp5_mP)cIO4UMY3ZI9>KO$O(1T6#ih9EkPJ=JHHvGZxEb729$l3q$oLj98fpjmDqgP zzjy&>kCC8Xvtf=l)R2G*_U??XI5>ZM&dU(>YVNya^Y|~Thu=;?E}!B$3Z=)~Y4S;j zDc$+4K)Oa~I<;HelOwz1K8DBs8xI(E`RJtt=i2N z(5eDl(?8^-j;sB5v8wvRv3s%(ll^~&K_ry2Ck$`-=6RFF*5;<4OITS7EfH95$|)~G z8yZAG&Ddzc+uhYw{;BH`Fk~kS+yAsQXuxK1KTzaH9NpGDOpwKD!v$(oAQ-n6{Ftf4 z72sojhA^xA`}ePr*cr%V0l5LvZf zZyf^s9Z*2ww#BI4P)|K<+jgiIc3AFV)tTQ@4o3Z)|ME`I7rZh4dKjg%4#4eM+iS{x z-1)Meh0(Yy32c94(Qjk-=5%A`sn1{|He^280=~4dxBJc8!VgG(gfc@710(nkY5UJ zqF_-j$#Q*k=f{+h$%}k#yi}p$(fGb8V~E$dbn$Jx&or|7gz>%s&HZu~F$wZP>`>K^ zgSQ{`<*b!)Wz$tZ*I55BgA==OYD?+qQ3BwjG6<;WhF-vx(?!Qh2Q+6pWd2D>DNu^0 zt9JNLZa94casc`{YZ;x|`7{lQh8HGD)i3L{d36EJnsmspP zin^cx4HSnQLxvLLGJ+9;`ONIPd&h;}ayW;J(UCU%S)WM(Z0jeI*jq^p(@b>uvnZ(J z0knv;29AeoR?}BD>`(l*^heX4lPDSJN!afK@YYz3=YjfBVn<*26E1_M31Kd$%m

mdDgk0NpX`~Cb zAJ=zv{dHpDW?aJw<(kq54=^5VJ$RJDQs4w4p#T&P zwMMNVU9R#uij~J04OZzXDR02x4gM`Cp6-e(P#Hu#OjLEgvP*IMaKbdo2M<^CerMl+ zq}Lv|0v#QfZEgG$-`AW$@z5=4{3MT*CaCf zI?{e~5t0AbY|4+08LVwLR1?h(Vt!xkiQjD_NG{4Err@*Zi8@w;9{w2^#PC8&Sy~pT zUEXXeOMG#GJ_{cZzd2t5ZD;TuGg3oQ_9LElJl?-pcGLzG+&+c{9++50fF3!hd+$`o z-O)5Gyu9x`OV1M3cviL}J+nX>Z(bZg!oAnhT9f6ws(gluj&#ryDTcXe3KlJmfM!BD zatAQd@b^`F9&LmgcJmQ3PuSA~&oG!{+?0I)xj;4dXsVa1wVa#QxF#Ix zJ68+%&>j%QSccpI5fm=poOp{!peIb1g-J04Mxf~gUy7Er4H&830LY2q+1Wv`SiELaCTUiIvrR+?FqB)wv5ON&|0x%rwJ@QQ^M z=}P{p68EDVY5fzf`BzJXHMYl}n4ldtL;j_W#dj5^ zeUfDDRfPG>WTJ3QyZ|U=eKDO}S^O-AQ=2f=H;0{>#qg8I`oe#_~{-FbJ4|Njeyh0%p#`jmkzhRaSRGZ16k z=(02X#w4vICn+K$flff+*;g%X=RO(-K06pjE}s;TFQHi`-dG>3 z?G#!S0X)^RzVJ7YVi|J$ZR6hdboofER08&@RIfS04xcL9TkF(iYNQ8GGSO&YsMMv> zwM|m;^~+VG{T_}th0Uf+aC)rPI-k%AdEk@9P^o`8yN_X74>vIRaysu$l zkv==sg%66{`2ObklSxzHCR4sXm)g-d7|Fc(4))L;=Y6elU!vJIshl{FOb=LR9xLP* z{$ge#lz6$y$)7mFlH%h{J!~E*s!zPv*2Xe)Qz#My74P_W3(f933vI^&EgM@{U7c_T zg}$;I7Q(5TtG@<;@l#~^FJ*gy-@fP!Fq4615nbsBfk(h^gS;n`P44{Q2f+S!T1_9mpWs7m~Ik{1WhST?M4$h!X*h>gck(e^ki-@~7 zZl^7M;?3-RRS)hWBpS9&%<$q5r>udsrjoxw9fE1t$;n<-=aQXyc_U?xER$OLU0a|v zrkG(W#c3cw2}DdDl!X3Lh3T&y0?5Q=>8Zz=290o#*UHtF>}_T1Uc z+8L(Ihrlh;*y9bb{z158GJxU?s;T3>IT#YXB3Un3GXG+EdHF2_G8f1g&m`ewzp{h0 zZHy#=c=2YT?kKe(A@hJR1QZs%-61tP!0mIT?uycU<4(Q%{+q}mz=LOiRiE1kn zP>N8#bcp~buWFjGkyjwG43>BsAp3(L{K^sLf0RlDZ#C7! zPno~BeY0w6{;_2ADBWlseX+IuH&q1!%rcz-7)dq=mzS6x+2Y+O2(9$$pXZ(i#7fQ% z?P`8#XEC{26%+LIqEYZ>s%2Ugki{b!Y8rOwo6>41wf={wvyQ5=i@Lpp2$F)*jdX+3 z98%(?L=+H^kdp2$X_N-(IMUq>2axXWZVug@cXPk{jq4u{$50#t&VKf@)?9P_W}J@G zjZe(JsT=M^;{FTMKv0zP(&yUO%2Nq@Vz(xHdwP~ z^4%aYdh^0@XWkOGD~#6hNVhkPOdn*6@}($d9Bv(OKXF&5%aCg36aa<`unQTWV1&fdk<2eG=wOVWdffHIn4zgcnrWrTVg6X?rETZNz4ibNterMq!dE8jDO?^5; zzAvz|v$H!X$5Iq?#9(MATI5U5CA|O~>S>?!E&UVkQUcVlz$Uc&NmWncdwTTx`a7vG zdE>Rt?>jpenzO}Wz9-kfo(Y98%sDT*z@JJ5fR1!NY`k<|-3OXfrKkNZ6Jn!C?zVc2 zib4r^XK?Cw9>GN(XHZEfD3lx=sz$m1GNkI9X6jdBxOqcz4k={X_US8)_wXNqB(e!E z%TA*Tlesc?;f)?ry^cOqLH`Y)v7_LT09qgLq}8$qdZy_(d4i_{gZNz#Aj<-a#Sc?cF4QC(@hwIm zk$^WOB~X;$f!K#;cAx}VO#)v(JKK9Sc#)Oj>fq=~n)=IHAVtf0#s8_21wj1o_$_)F6}!Jpppew5GZrO#{leQtw8N#WMV4+)Ag}2TanfvJo!Kr zUPL35+Rk4yx4=A=U!(ft&0BLN8#*!FwG9dk&X1GVuu>s;JpmS!GIz-eKBo4JH{}xLaQCv@wV)ASTT0o+%SHuCKVU=oX2YJo8lhYK%n?N zCBhK~S?^CpF8DuVDChDp75Mptl>e>=tZ$V5T{w0CejS(L7Cc8ha_RD1ORg~3d^yb*M^oYftE3{PV)518OWijHsm z468W{8=Dcp>ObpGd>;&u=g=crS@0aw>DSOBmKqO%9oRv~D$5NIepoSfuR)#GrRwuW!xt@69Kxhv9Uw}ZG}Y|Jkj8E1t342Q1Wp4GxU4c zeS#=mv=w`Cxpz=T$^4s$q|{Up|MM1HmiI@rB9fCP_qNBd{lIF zUU6}DZf?*(67P$mX3&;3;OI6!KhK)q>7X07SEQ}qttw{jOOV99MBeGEz-k-`NBsJ3 z?=xjY^_w5JDt&)v3!6%l6wHyuKVBuV;Cg6C6QXF47YGo*`^`V4(U{pAf>@ZWx}Hn3 zXScfSku>bc41asS2idh|e9f6-xma+Z56{6?H1?{9`*VNy^U$GCWch*$y0IT-UE(Jt zo@C{+`=TZ7TSJhoz%M1G7k|_8eud;R(1hfoyR^y|3j#H+DlMC-u8BcQn zY8j@2=TWaRcrlb44G?ekC+P1q=7#lAQ}BCDkPnB)c!wR97e3_)gxEjNV?kAP7!gl_ z1%A~5TxWpw#yG+q1ZB!dMptAiBynqtFaYDYIxjZXh>3|Ov0AQ5X_s!QzgGYpEVf|6 zUcHT5OUkvRz74Lu@mKdoZ<|R~2ggkNK@{B+I0+1&empPW>5dLlHQDKCEB9S(GUE+Zo$*^SQrI`;|=vSXe-1wiod;D>kVCsx<9kK)^s{QsgE zsBCSY5Q5(p-4^(Ocf$K5pwmO~)tV z^>C<_w<2+_OP*sM+%W0`{A?#B=Q^S|V}qs97lY&iBtMmse%oY)hy_mWYv1C|>Nel5 zuX?fS@mT$QouhQ6m!SVcXjby>C&D|KOOB)g67Bu5de@IVT2;kza&ji7rr*K0^bAlR zflF4w(UAwJES;;aV1W+g$R)Uj=kJ5Xj@+^BcbT01e`$*QgT!qhAWaUusM=I*0ON4f zUWC;IasI`G3epFerP#GAIuAk01b+5Y75aa#Dw7Z%8APFp)w zjO_(==tv4|KI*Q0`-D#U?Z1mDy0;Wg z)M!~iH1<6%-$~Pt;2m^#C5vMx#YdcKIBiT(V)qa^=mS;1GGzlAgawR@%7T3;u&tF*OKK^qO@3!Q{0eS@A^ zHPNjgwoA|QNq!OOffbD)WZ>wt;t$^&RI6IggvIi=Zv|!!+2As7+pAnc{GW|=I`2B_ zd?Px?3^Y0Hr-lfpNMK@O?EDG*xT{DTTu7(0Ug{%{r#*zszy_CDJCBcm*}tnfdUTvEB&b+ zMBCdm&vJ98b3={kUf{{3u62de)6ldT+tiBQMmC!n7-j^~L(!4*ovg*g5CEn0n^5n9 zWlgxTrL63)y!G&6*baC4j<@-SEP20&d=X7qGk_6;(o?>~pL7u8NV9IO<9>2?A?4GkNb9@qZLwGsG3!UIO-#hL76|d`E85{>4cv((gPL4rsLdt?HZ~QMJuj@R$!qM2S z-=gbWg)(&Sh2JOV+boiSMhL1j?68Hk{e0NE79sF{{cXyTIF_H}q>Er*m*MDabypuE zc)R3OdIa0RvYSIk1HO$*>)tKDt-~N}x7GIx)pKNgETaEaGrPm|UH`ibso-Q+!HhYs zOjFazdK|G5Ci9dPAUA-nEFBDuE#|6$g@)44?RdZo1j7(Ip4-Z6TfRxR9hk zxbOub=!Oc4>wkkS9%;9tFGG9VV>w9l=VOL~e&zvN8Nj45>l)WbmC5y_&+}TPhLipx z=7|7lM@tF9*x;ZNrgj5Q3g`xRc3`P@;7EW}B@%;*-{9h-2t8=h(&B$Q2`kOdJ@%iI z+<0($Qu$fezrq=D&!==#Zso z$bCb-p90|uc*?w`Z^k{;n?1kLd5?37FM^J`xokh&`t=+r1i*O(Kzq#a6@XfQ;uL}U zqQS3*n*ZMAYWJpkuf@`c`6?{#Nr5*A5E)erxOwl##7-vmT1a1C zif_H#-LqxFt3<5#e>UN4gh#Bp79SJWph2IWEFDIg23A5q*>)@6nmD5goLyj0r%>|b z*8{J(XFyxK-eNAeMuL1IQi5C?5V&pJRNcJn-n&WK4k$QbeHxEDG=T2s30wzoqM`cf zkmo&GfQ+2@-fS@5_y9*yWR^!{sK)Y&^KjB38g@i#v~Vi2*%DVhyeVQ240<799tFhZBxxMXVNc>PH0>Cud!l_Q?q6=?~(3NFz;{ z0gEB3y@D+{n0@IhQ)xn&^MCjcR<^=)6(1!L2x1HdX}q7EFsPF zT!lbjD6RrQAWFicWl9z)*)qs|BJRt1)+E$p!6N~Wx%UN9!3E78$nE96M(4gJ{N`y? zTHcngaJx(6y~QnYITw@I^fgg6>KT|PQ6LuK>G_s&#~+Ku+AHr$OF!hD5E(JBv*#2S zhqYX^05v$?)8*wa>HaMs3?N^EjswJ|NW2J2Wte)M-;T!D*a?bC_PhrR4Z2<=7n*&K*Aggp5 zNEpum>;p)*bCi$$2iUe=M^oVgbUquEhMN8sprPxBia;|nGuhDLJ*Y;A-G!c@3N5!Y zel8I(omU_TCL5f6aqRR!^#sS?(z1BNxhN`&2^>)m1Ch_j1;&LmP={N@^1)J()lX{G zK=^O-v8OHNUxA%%Q?crH$3G{Td^YjBWqbvz2n&60+Jc4@WzwmoPJa0`tf2s!_Ef8tIVc7fn)2B}um?oSnN8rDNPQnk^@e^knEniWX7iQFGU(Y!< z4*2Q}(wXSKUeR00oIiinbv%5v4Xv{nl|hk~#=(zl!G@R^4#`bLaP8SXe41Iz5Snvh z*??M=WaL-bHJ=a_6UO#`8LC4IT09*u+v%WpK8`j$J?gqFI~F-q{(Rp-i7_Nq$!l(W z9=JO*R)i(LVg7AsZKkL_-6 zy6yroS6;Uv&8f9Y8()DHccZIw3cUh;5$kH|!V=j|&`lck$G3n~F;I`A$Lq%02n0zU ze=KtQaX4`IyoH5*PfbH(M~yh6!IsW;zDZO`NA;%uUL%dy9NjNsf8frof>ra|oano7 zw@+RzuE!cF*q@zX&J2;smP>vk!Fmg|kL~HS$~BN1H)hNEBXl z$Qsu#7JL*^Zr6~>wi$}+!T<$|4B7|cD`5UVzrA7D9mg17P zyyc59Y1qV~ZYA1yzMEPzO7k)D4EV?LUElDDXxE zyqXsO|D->G}jyDz4|pX$W_23dLHB`kOHEI z2wmip`9}EI;miiyVBQ0sC9q0?^k#}{p-^0IArv0H;g*w!$*4702h_ zuK}U^Dl_Nhfp2Fooud&ShpWxUB^ zci+PeNnBxrw;9sL5rh`Iq4Sv2-*I~gg%cxxah|F6?l(NPd{cXK(rQcvg*SNzW@m*T z4;(hOXE)IuJ_L_|V%~UYD7O?+lQk9rscD<9u0Yi!5Aa;E-bM6*rU+v-*AtU#i0g9y z<(gfl*VkMAe5K`71Hrf22c@a-K$z; z(J%IU$122y4KAjRd&d;jqp>ec=k4m$*Lt75sj>u}fC2&Z^FHTk>mR+1Jcd0pVCDM2 zB{Qj}O3P6Qi<{^`?(hW8Y5iBCZ=?mXz7Aw^`>9q?CU2CoN}I~c*ssbSK_VoXu-$=3 zmpvsz+iHNQgyR6@AP9V8A6Qr=0^ft0`l?W8Fb4*kH$MIc24a?V8~7AoF%cHT^YZtN zJbFyMhp(=j!M8aL@CV1gnux)vb|fMwGN7=(E@&?f6loufb|nY5_BRth1nnZ1@LtSBwigAiYvF?Y0;+ zH|Hc#>c23QrEsu7^1fU=RfJSkR$h^Y1I-ld0)T-z7pMU!Nc{K9KX-z*UOo%*`5sOq z9rmO%0tNftl_$w#hOTwdZbAa^Z_(4iIqe?c2+QW#dV_zf^ z=MdW!h%JH)t~YqLOtCjc!0vjqIBcJh396QUKeR5sh2GX}t_rbr4^gqwVRXfLb&ZBU zN{ZPYdJYrE+G8qt!9wUuNN3F??VilA)QLzB4&@OZmVr6Z*!y;ZXU!EaQ&Fz=xjFb= zExOP99SMK=5t#2WT#4&>Bc&GQHYIn|fH|y<^xk-co+5`x&)QWO&riM+3>+BQ*^RGH zHo!*|hvFrWX^i`7fvo$cFDFVD>mutPg|ao%vNc~lOn3V)v)o^S6yc|pk65SUZC9!a z*Sy%3p7XY$_v=pY(67Dzl`8nfq9$DHv!ez74KGgia90)GXA_VG1al?5@|}0 z4{E&mfkmdx|LJNfu+-5WYP|<76dHKWspjz&RaEeRC!c!|&Gsv8Sj(*2SK6!^RdYkI z9+DX@A2`V-yHc66LbzJ>HK&gydgyjxgEX`!^2wP()FAr~Yxs%nueGT%A z4oBcOi97wdf?226hSJvN2z2mRTRE^K{rb%tqDy0{g2=?gSwmdWxE#KmY>W4*=yOj| zWx(YH)@(Jt_Z5cO`#EvozGC`3mz0$B6c+(@KLGdZN84}vC)EnL?gMnIdL7{XbekI% zWc);^j3ql(|7TrLj?dIz`7jW4B06}j`EdfMe87qUQ0`?w`Z_s1 zMX0aT6r1$|Cb3TbluggU^`3S?(zEbTTHvPTqW}gyFsIMMG!-zqP*qbS(cuQ;0DVnS zvJ&I|crkF+zzQ2!xQGRWk-jqt)Ylg77cy*-JS04tuU*1bhY$GMM|Hk+Wfs0(&BzEM z<_Nh9oEnpQ(eU`-Fepa`IA*UoC8X?noU}J9HU~4qYKBK0LoTf<@Qf<-Dn8hqi-Zl2 zxc`Z*CKKXhdV zC~U3{-Dzi&YW~?=y4|e?pj*?O(Q`4yw&dy8ZPkl>H0NV*mNm<22%!n zt@i(Qxm4?mcr{i+YcO6V%s1aiIx*cf#i*v3E}63eqC}8p>-2v7oC$L zPl@b!)BL!X>2!abB@_|eG4;^&n2Dsj`~5(WHyTK%gFP-kv$_yw`HyZ2LLJT8*Kd}ZjF{?X*aiohqud^D7%@N1 z2{yT*Db0JlAxMe)aB)3WckHFD>ru2Pyp>jV2E9AmBua+vug=5z>h8DC-(6QO;q869 zkUnViL?K8Pj6EjM>BCOd97>D8ODAV7aJice?&*>5IzkOR5 zuX<%X8T^cX@_5Z|t>=EDGdgj<=+LgK)S1mIyLS%%eq9eui8a{M^$mfC$=f!RE>22I z2Dm)q`X&2=w_9_Rw9$8=<6m%&tRsFNikLOB?+e^ZE9G`7grtX*_ddH<$0Tpw$%zSI z6|Y~`==8_ypz`!RZrp`Jp<10IcUu%Vr5$r#m#&Ih6vG4~w z#TB7tPoUoq!g$0fp$~B#FMA)KtEFIHs9PJfrkwsgW=UfB8~p=9=9f+x4`wf52C5e4 z|B$ShQJ@4qJolDu|t8RS6sit1o9Ywl0UY?eo5D_&2}%A19#5Z_g#f@MZd}l>dU9?CxMh$KPaUI=%dBRTV+>=cOF1tLQcUB2hWIv zDoq3$(|d~;>pvw{KifKiAE zsL`SUGvUjZm~h3Cq4R!{A;PwQs2ZaE5 zd4mz5Uc>;^8S;vO=kAjEe7QfX=6_dkvTZ*%;_2G0Z#>v_G4RFvh;aP77#(fl-`1^! zT%K4WE{+h2B8|?Z=K6REuUq_@$1<&`#jUQhM@=yM)|@WSiWeCSJ9m8(C|GwtfqQry zdU)(>M^mppTDc>wC2&jiTLs-^XTYDud3$Q!!#}u|yq?z0baA72d+G%EzHFE54o_BA zd9U_2cqZA|zSpeZy@_!ovU|Lv3tsf_zLm1t=qXufReAI2C&!DaM+e^;j3j(cUixz5 zfcrQq^B-)y?vKiwjW<@>E+>kEHqGrwB3{A1EfIyv1joyF{!cZ#zg0giJ8q)LJ!{Rv zwK3CZ^I!=yrEATf&9T{;paxQoTlDVa7t?p{Fz=gl+{qU!BS5dKLqGu|`e@VU7M zspj4XTQK|hA4MvBMrTRPa*tDyDb9tj{AOz2@vxaM>hasd)n%N^UF_TcQfq@LnmstK zO15vGiCx*nKS1qQ_ZTb`ql`ZcY)VP@F*0iw3&71!*N zM+AviWxQ0+*yI`wueUWO76W$MS2eZlFsbSy?UsviL1(>(TNd|w<>DW1Nl^DoqI~*! zkd1JSUjng38?ahbT8Y-=TRC1nuKaYq?mGGG27~j0)$?yM|pT4lx zVwWDWwDj>GJ49A@(CV?r#|zRzrcZ4WyKi}$+`K51L{TKWS}g+Wcwu#yNEBLfG(h6j zQLj%GZe*AI6Q1h7*RV3mXgy@$d_FXs^8Clp<16z;M9u1dIxqh@l9E5Z6e@k)^za(? z$R2M)XqkXjqUy3{KQ7K{y+LCw`{r(EiM}z>sR@~#w}t(I0Hvn2rE`$avUVHSxe@c> z(82i>ZR--!&+_vnXUiqg>;8Zk-xX}D*1H@^=FusA*QI8?&3zmfG8XlhUUfu^w^(<& z$~C6t?5_}Vv@>`C#jL$u5_mOr^IP^*At0ullPvpR)ZRI<2Q4$E<7w{Zx)8m#!oc$tp*)vNLakF z+@&27;^||Qu^Sdd($rMN0}{>sEEf%ZN~Qwg)~&!!=6!W$4~(B$g72mzcvDer*#!h< z?N?=rFG0ft{1X^faw+s#$vHFcElo|+!7Mal6i~yB|NTS&HcO2#blX|mRFKTXkW>mn zF-C?P-fKSlSfw`Ac_((zCLY^fs6B2+eGjhQrmq*>vZwn>Gb_Qpds%q&arkey;?QFOMkZ)4O{8EDu+IOs{e z7ePmWTF%pI1Tx-0{LC}xFVeb4G6DN;K6fjJ_Zg#OvO(cFO=;fVz%#_}`e$UV zQ@PA0LmA731=G*m(Fu3a`lNm^RXFJ>p>S?Igoqm>%B2G^G^a9jA_kUYZqU*iN=K|@ zQ1mM*ICGb<4v!x)vTY|q7-h_ca8n$JbOv_jdv0+937UH?3Pd(g*;WO|Nce<;_x7Ue z9~aeT8Ayp{42+>~<2@jg$E3@l(ontIT4=>~OkK!MuY?oczPZ=-)Ln+r%Vr%&c!QK5 z0=blxn@_1%&x*NZc%u)$+5qLtTE3iwFD6T?_u&_(_aooMX?&33>g5#~_3OAkUel{x zT=%wRPHc={vkIinFJK zdQ-bzn+u(cLT5Kab(Xo9wL!2m{nuKj)Ta<(KQw4nU203b-xg?lGR!6O|@!^dO{Jd{0z7 zaq67S=M6wbf+9%=_b*L$GO-|@j_)y3T*!59S(+c;`X3fw;VnUU5#wbP=XoHob%jNi zYa%?l0J@<{zH(&k`~aP$mn(YKW8aQWHCHCSS(k9vR(=m?nch>p)cCvo?P_13_EP`q z*X6zMHlAKMy5}j2JFq);*^zOaY1Ljh)~?r-9!qtb_=-T#5|+Hpq+3datpDN@B7RV6 zTa|G>b*LTPech4ymhbYVvn~IfAxfbu$|QDx|6>4AicYb@_D>PCKp#iv6;9Mg6xfMG z5JLPjx42fCk`|SUf6dSS5h1BW0}x>Gsv*I0B7`IlP)(0FgE-t>8s*^9LZ@lv+sge$~x_n{0+oM|Y4l_#RX; zaH~OB3hj{Ly#nIQG8oTdGoe~grf%$JV^g+b;W}qg^R#|obGD_-V?Mpi zs}va^5O&j$4Xi*EN%qG+6C(uIAh$9Cqz?U&)jm^<3y+a5m5$ zBxNBqt%V-k^aayeE;TLC7wDB((8%twTve!uwen(|e_xXELq}1jQc7pHHcbLTm~y!#cPjh0!K^l4(q_|JW8TIs0R0sf&0?_5f2|ea98x|I zQ#sZP*K}&-hjUv-psCDU@Ix)kvW`WttyiX50K1}_*o_LCO;BpCS4&qwyN6woV^(2Si!<28~&(sc)n**vJ#zhu-fPHHIp7&-+8h|{o_(gS*)snLAW7J zxV2R3+S|gWfLWfEGI=#C1AfJ4F3yGc%cmN;d(yO79DV{=D-m%vFMejGp}Sv3+3MnoMD8H4jc#q z8@WB#0s?`!=R0$TfD5b=HHRzb?%*#)JMEkdjJ}OSEz1wX%_3*v-Y=&9jWGF4RqbfT zLlANo=}*vQDO254xri3Tl)As@-R51)$Brc3^a-&4t&oMzhHPP@c;ooxzc|RdXsx4M=CyWi>5MPex`L&Dl2KWHxC*LCY8rXb5^oQ2uR2VK1+_?0|x! z3FIYJ01zRN_Mg1EGR9u(`50wC$ejtk;9caC|KsYXBXU@A&?!P@7JGZ);CBhk>`w+S zug3?V>6Qb*ZvTq?@{5aRO=%ia9M#D{PlCLb7Hm=~Ma}MSxiobOD6Rm@#N9rjXh$2) zS%_QCl~z0!#zWKRn@~C)s<{)d&r?P{#{e%`#I|>^0FkZ*1t6J`IJ2CO-9Ev;rh-%{ zz0$7aN;xqBei3GsH5ZF)Y+LU3irW-kEcglL)UO zk-K!HaflGe$h7fWCa=-cl77s!k2x(2nN{(---K2A#; z3xi9y=pwo+I+n+-`p^}=d&vrE1M@xUi&O1_YAmr@DV$d(ZDWhxU1Kc|UY>!wUe!@o zN#q+8!I1AG%yxCo*71K(oaZ`w-nG$Cw~Q%DH@v{s^PBs--;RdKxPwNGeR^{expL%u zBq{ak1BrzNnbciSw~RU2zV->M&0JX|DN-qCnth+_#AV5uEEOxLA5KqEs5d}-%)B~= zS#UiNl8ZA^C=p1Kdi(668N=6n(d`c_@k1$6^&O^a4I)oT4mbV3&-F_N7~DlD*Bylj z8WtSZ&-}7l=aW|UyOzCDf391#PGF&updxt(C}M8@+?_H_K67ri7Py2=m%ie0eBg;| z%_g8a-m7OuY1}JK$Vr;Uhena}+h%qlSInR;xMJcoE>baemv{>w@nRlQcV~A^7d_&&5ygR_s_v78?ojI-hSC@|!PMgQd zUz{GjjFpVahcLLKaS}MZaZvky;`&eqYcNgZE6+hDC;dlF3q1D3}MViax`Wp)8Q?Zi?8qr@@sXOWL*GD@tUFal5n*Tt~KmI40`|0tLBzRHS&hhO8i#$v7$ zKrr8!5he|E0@riQeHzBIJP&UqOq}Q399g{9G)v4A8$TEyCOov(RX%@~1h|Rj$NNK& z<*NNKfXG$GGQSM4yupTdW4)IGttONsYT6uEI0 zQ9>Bocd{()OvDSxbc6VUSObaKHo;cJmX8!-$At>YfM?cY3cQRvZjm*6%xrT%epXA@ zkeejOCjKYqCK&4AAT|^Ftd}xs^6&UJr-kPj-yW$g9j?n81DeGM63nq^KEKtK`8k;# z`}cDLJe+*}$c4bkW4FS+Ru}8qj(|&$+sFWQdP`_?;P>WPbx|_b7b^T$-r}EcDZS?t zRBR|*lD@&&eoo79M2Nl^U|m6b7Kr3zhbBEJWed_VY)@Bbfa)(DA?5(VK&`8D1hKRu-cxm^5XZaD6hqmJufIv1}#ddiCrLU0!Xi z%$4|+Y3@=dT%jt8-@$>gzFxjWF-L(@!rOFT(;hvXmxj1oBc8DiEVf$?BFb3$6h%?? zdtg<=kQ50rr9{o}YV}+Aoa59VDEr+AQiU-eT`1ZSUrB{meXv6ZVQFxQM}%p}*#;|_ zo30W;zk^GVO&t0Sj!;|B|9Sx~Ta)1Sh>Aa5>OMN6MrF5w^+q{Md@W>OeJ*jj#0eY` z`-+MRaPpo)YC&cTMN-H|w1Jf za%nt$F-s*$;MxzD6*Oan`3MhE`21R+;HT7{pLl7-8uM4=N+thRkmq$d^B(X?I|sRiX<8ahKpF zG?sG5u1;%0$(#VV7|hkgU}p8Z^=mn<0Z zD8K?Pq-hj@C`MVNNee!hn#N>6uA$xbrL&^@==qRqpc^8g3hAd}$HLaTZx!Dge`IbHz)Dw;U zQ`UBI6nsOr(>~JQ07qvbxq5-Uc=JBh-QvX@uW(O>m#{cPq_kpUAFSsa?525XHDRje zcow~R4JzH1X;&H~)1#MI1x505N%lH$iPNX;;&aV5`SFuxbnwemf6M*k(Df$X<9gA8 z+f3CO$Hb`Y?-WR|3F&fz^keUwo72fGddZ14{4M09PKo1sYfb2=D96R_5K?`2-R!b# ze9O6X#&0=#W{mYlS-$aH8xnQJBU1mUr|oP;;ii2{qw_fGs;JQ5TQ!x9EB1PD4l;Dk z*l-Q4($T+fuCB0pw5+DcB`inzRe2Kmo;TX&M zp3v(7OQ>y(?z{2MNIs(tT(=u5p^G`S85Q^Vw!m#PI&E z`&kM1he-GgY~P}~$>nDS{6m6wUyuxUB;;djHr(mc2g>ETtB$)a z`4=VkfT6oREAxd1;vx52758(fvinuvB?o=4LjRk~lbD!$*x5f;_if%s-M+AW^BEYl z*E`K!AKxSP7TxV?E)FuN=5^|{INg-O`*{62yzz>yan0J29^$&PZQSCC=e}nPfTBMV zyoBeY&>x*gxfz$!lm2PE#1=w*bVjOfLXb8@v}-b)b@r~`yLBiogg~z zsT{2ltQ4uOkWlzyDj$Wq33E?ZRr$<4`_4hb^uqHB$NfRt`gXnLZjF+YSmVX7z1G{6 zMDp6pwWGb=qs~+7TVg&nRP5p-(oa{xcQcHNE_$x!eh| zxYbsQcvrS{{#pL|*CfM%tAw=ip%EhN%MTDV^{pj(QK@d!!Tr7`S!D_sR(`Ljn5+g=%%N}0bn>rXMaZ!$uq4tl26&^;9S#yOW%8~noangRX8m*7uOZRP<)5`TFugC{-p8s-VV0S zZd~f}1YT&10Jq<(ik~k$A6SbWtu}AXEY~)ZLTg_fea*t)jgX>OcZoG@guGb^278>i*s(`Jws6ReLD!Nm-SWa#F(|pF9-Q^pGuPNMFq(O)!nfJr;ZN{$*aA zm8NM`k=795359!VTvJ2PtcZK$oF&Zn5Jud_ss!u5Q8K_?aa;>aZcXu;?Y25BEq#Pv z+RRB?F6&=HlvEzL@D01%PJShJHV!qm4q5V)-g_Nx=<~Y&nWJ$36B@YtgW|}E{DDl? z=&#$0yN%cLAN>v`*oc4s{(Jw$IgdE1#5a!Ie@o%$7`rXd%D)CrH_PnfH3P(COa7E|N)Ti>&1 zq{}wtCj_46$fzivj_+v|714lKXhRzZ7G{cj$CfY-@SeM}U#$6qXq$~wyM%5$=xsra z<--Y@p?G@a&qQ|&`-6!ogTF!(bKn;exmTKcy?x#);PMiTcD9fU&f5b!{lS6d!s*H( zaqQ{KO?MNroUksPCDcEva#X~*3g!ts-@og3ml}Wkrc#tZXJ(6^qnMIjQxn%8BA=gM zu(f^RUdkhETt5oYdDu~NZZ7--0?iq_2D?*MHab}7uE(e|s)FE3i^sBq?^D;NNAy1@ z=jlovV5F<4@Fi~@GrlL0e`n7V6~~V>Rjd!`%K1vBO+N6wae4lk+gPA>fj$d=e8p+* z%mddL=JhmQ2x&=vYityvtgO4mFo_!WN!_p}fqIQ)N}R|kO}J3{-su$YT?|pLjVX{9 zaKZAdhlemQj3azRW&05|r zkj!rvJ2=Rrm`wO7c8(0oG_(E*q2hXO+H}8fWj6UmOP_iY6wWRS=fnRK12?u;c_nxMAMfg zki@3*gXo%sy^_q#w+vB4N5`-v)Xa2|+!*fi$MTUMr0*X$KCTS?r(65B;^RR`OzT&c zj4#<56U?_(ri_{E&h0$cC8Px!`&n82WIas>Lr%OAh)SWl+CJys+1c4C@Llkjkb6jF zl-;N-gtVf*7CXZm8^Spv^RVYWIWY?))q;iVH;+bj{a_hm&+!G@)F*!f{Qr!AlfM4%!MXRQ zRm7=!gJTgvPvP^%CY&Ep9Und2ez?$?#gtU(KzKekP{j4U8J*Iirf66wmcM%;foFmL z=8er}KT(!&)xnf&?`=Q;O1+!gw#i|3UA6bkjT9~}M!dW#KD)NR$MA1@{`WB*1*(yP zTTr0$@!M^ND23Sae_w`yZ_>4AttmGb6*x0N&fXK0&xHQCIaSAjP;aYc0T!I&bd#G3Pp@baM-z@u15C?pG%a#xNaGx%)5!_; z_hJ5G<$CG1;~Dz3w((&z8f>9{MqiCu(8 zI3&+{aM~;6`TBM>cHo_Mp^{P`aNpo{fcTG|?tV(I1M@;693}b zB#Lv%QX+p_p$UkFG2I{E|JpkAOqb?+$;AqyqNCl%X<~dBRl?mTPX}U7abt;}@h&>k z04Ck<=iUNRjf9mbM&l+(nDx17ABIi#UxfdD$IU$^H?UpOCS|NEKal1kX^6@tT@ z>5N@2luE;cDgFdhbwfYvLgqwD zIUb+ls+^s&tidB7;LSdD@#9q766sOG@4y9QtGc)DXN-wR2AoGNHrif0Zte%MX0^7* zfmh>g4W*t3L$JI1j`na_+E!GW5RRwcjwOdB?ZAt&K&^xhP#gj22rF1OHtj)+^Yxc` z8DN}ESWak63(2f1?Qo#a)l+8;SXH<4)KB;o`f4}ppk zVcXMOT-{B3T!q^b zzdxm!22kOCrHjUk>et3Y?hPtifA&$$BfvY=a;USV#$vbdYhu^W#}co*l(sCnI7Eh* za$=-?{|$-`@0z*#Wu!t2RJFlp3fAP9@ri+T7u-M!57!Nj66fEs0$3(owR7opG|LTs z#j#fu9%0#gAi*wX%|HPX`R7kN$YuYdKVZa7uSl9+RyHU-prxWhUYhEP_cC7@sE>g9 z045^C3cDrAqW8+|6b^H}&2o}^u0uFg?`0_sU0q!G@q;^<14MQFx_7yhS>3n^@bRB; z4}gq<@@2~raJT<70~kJJpGFCJtHiQnu0}=Yux?15MdGq9l^nas*oiOKinJb^mJlOz z&b%E9>r-A|Bt7!;aH|G&0uN{4Y4(KjBl09+M)ybpDob5m9g8+hy#}JEwH{<^eK~du zW*?JU7Z0l_QHX||_vERww~z^il(P%RVQW)%c8EPUzg{eV2#0v9GqY}6Usjdht4?)l z%8|nAo@v1BdQOlJ|HVt3nJ7`t^HCEkXlQ0)BOh(ENVA5Cy}iwUGAFIK&wr=F6~O^U z@cY-nMBxjsiazvicBvD1>Du!mLSVY=2tIYjK=vC|{LV$?MX0C~qqFyam^urfth;WD zqojb+DUCdUbcb{|NOyOLfOJWNba!`mNtXx+NOwqgcizMI-8*yNd0u98421u4&faUU z{abxG0soL;Zpim8&ZcPeLenO=`?J074kP1`3V5O4Dw;2eU-03mtP+xJ+ zbMNe5{=sHISg%o9c6!&fro9dZjds;`DHe3tNV2lBgU{f@Hz%hUgIegQ!`}skjX_5J zkp>yYq~t7qtr{%J+`K_eBG41#g|+i`(9^GIz{}!@^^Saki{F*0nrjG8Vqnvw&P+A9 zg54IKW_T})9P(P)?cEqPWDTQLW$A6W$_2Eec;sC#9SXXC&It~NyNa4xEtn>Wy1rSC z6&c)?xY*b4U_=z*+@p?}^79rNZUIOcU6+5bm6Fh#Mwb;jys(a0+x~7)kfi&HvWE7( zl2VWpca_rgmw2E;H7N8FU{-2u7T8TtUshxWkNq(y-`VX%^~cCS2uxtO#Vuc}WmQ%E z?WY$k*G(WriMhWw6fJ$bak1wzWpcOg4IBct-U=vA7JZlp$MDs<^cung9V=iV>?J>P zkTqEbNZBB01?!AUL0j|QN_oc3(~}%KH00MW?&0rj z+`m$jkQoxE(Zz6$-gJo6Rt=b2S-o$N4aEKx14Elw_I5G>TJ!hlDDh|CTcNB?c%B$s z8$*YtX(~5{+ODfqeXKvZZ@A#-Op2!qw{hHb!oEE#kSnwxcJttxQ!k^Vqf;f8$<*By z>Js{0ZXv_D0a@cNe!9Ab(v+lVpEB0Z4JHFy5Q!0*9Y=X)nvup9`wP!@fAXR7WaQ_M<9B`q5W_{L z-X3&(8*@$ul>@TP>06d7O$y5T460 zQn#i8N*y?w)-HB2CTBR@WZ??q3srC3Mq`0zwU1s9VtYAKd@%YxOs$efefIC)thz$} zfI4nn$0bl^3ahFQotW*D^}oH_Xi^{j^Cz#m`ZF~P8(Tc6ion6-@sL}!!_YNSJ*1DX2 z93MZJoN*Zp)G9C`r6M!Ut@N3~fs1<&TGl zhl9^<8$l0mYVeuI^5s~xyIB;x|0>ND+mUYn)$>->!+83Q!<(Z;V@iiE$Ge*C9AR8k z&Qv!JS6XImWpiFL6xEhg|Ab>rEI}3O8&;7_&3emt$XwCX^TV9T&LwQ~1NbHZp4vWErbpVrzcfGs^73lO zq288nD^rnob!QwjYkRW@BUs2*ouhlZ_Y;f-7y6FNKpHa!9$rY#zpR3SG@TZ9t6#g7 z9&N9DLCeOVXL_3k|FaQ}%xTkOa$Ad`{O(!cTG;z`C;9=^WmW7*&%Sk!8(d!>W39WR z*a8&btvrXbb#Ywx>I#E<|#I{Q;KXUAFdYIMU_ zEH_91ATP*Ft8{uhB|WrX4*&w;x(uE=dh0ptj@9k=h`c_Z(kf z{(9gcTs0T72~>dvBv1l_vgl+%%(7@7Hw>p%wYBSpKPYEeZ97-=?EaIk6_h|^6ZWCW zf4iy~_D*TSvZ?3G3X02yzR)1Jl&gceO{~nNf1S*;lq0IDyN9Z902mFVm7FcICCdP4oeXJekF*Qk5i=v>i^aEF!~xgn2ZCSMD%>b#s%mLG z0BCIHEB!+8I)Q$XCL&$G=LVFO(TZNGfYb@rW?H^3Om9NcS=cZvh@p%d?tnT2E5qd} zm_q?;b7i7}V4gPZAyS5$cCZwW`i^TQeCWT1{jWnR#5hv7F?*J1$1T0j zq;Xl=rU!e5&1&xQo`0k%LqqZoeOO4<3kQ>v)A}jg;q6ECnp&FXhvq&a980`9X%$?9 z%InIsZ?GxoT$IQ2KRp-38KlGsuES6DrW6{ongQ0msPabCcyVrZ%GF-(S0YoBk?d1z zit=3xqRsgoRuqXu_F0l3dPo?pw;tTku^?1y9m@Kevv+BC9vq?p`@mG$I zkNY-sozCzFxi2lb?Uw_5m%FS;!A!@7C!iWhB?E2h%`H9xh3>67_=h_+6juI*Nypx} zLcIJLJ+ZyHX~2kErCI*%+qaWxEnC?1$a#oRS*2FvNRV;s)7`%7X1tp34>iI}H+#PF zZ< zP3FLp(I&A4NTq1S_vQuwyjKQ}=hhyCb@V)GFeU2 zUcVq*0XeRTgm~+eEJdj6>zl1mwEqZ~M^U2#5*=;Afc~HA+?)D6*?A8dlJrYq3*~`Za#*E4g%L0!=%h-RQ1ph04{)-kT zA_assphjnU*^zb_fbTmKQ^>5f1}4tEuD7rGm$K6JUed_?Umy?*FtIO4e{S+=flmk6 zz(A|^%d-Bg7eoH0xAY6KAgdNFBqmm=Y7S7g($)c~1CY%CYVbGUB!3U}GnbQ;#5?|v z9Pr-{^se9{1d4!DButmKo*qA0i6p>Y3JG-wW3c0t=o8VX?1%_f4K_y8W4y*_%x-;n zr`E?#5XOF52D#pNHn66gL&nNR7clbqmwc<{#6Ty-RQ;D0(jN3oz*Co@++fS2D z66IbRF*dV=xZQ`cgCh?J$K^RrtohoR-Sg(q( zhP%0q%9vF5I*=%m7+}NTLvRr5){sx$j`@34zw~aaK~~gxdwi7_?f85g$i>^8`t{Sgq5Sw(2W{}HOM@G zk3l$Gu|&jnT&8gg&S(;A78pZ}*bp{+Njb)v%}X^4E50C`iuAo{%RYAD@Q4~--Dfl1 zt-SULS((8Pm1hRQad14-coDFyna8xCe;ZAXW?YJU?V#VDCiKmco~&xHAa9?l??YIu6*MC%Wws+3G?_$IV<9@ zTrtOo#`a4(BDWpVOdi-*OG`_`Y%|)>S-ll%@}DybN44MfDr#v7+no|c5Kx<*uJ!3k znfinZjuAjodT{B$8ynuQO8|szGruy!HPA)?h*UzrZra`1LAWkw6vMP%LBtp~2!opx zaWMXVksCM$X#&=2faf3qxH>Qli=w=3QAcRfXN;CK?UatEu|?YAjFyul9&CP36QeOH zk6LgB6Q;?K1?~#~*vyhJJ!K|9{9}6Vzq|efaYw%gyU@O2|I&~RfQq0umfoZwMLA%R1EyXt*Dkw~<2LMRb8?n@^;pxZ)x%JcDuDu1 z$;^g|5Z8EywZmg;LT*m{L3yG=O7>~Wm6x;$tCIK-3|N?f(h9A)VrFD9XmBZBTwT2; zBAYj@rQU}EEBCq^^_+4UxQcl*ilcv$n1nTmzoO`mR=Iolw{SB;@S6?)VdbSxBzJt} z3r(P1!*KTS-M4Mcc=xA#%*)})xN-D+xy2s7U&Et&r$k_!05rBwvA-$Zkqf%Iq5&N*?s5~lz3v_6*{!Jw%F|O zuN_NQ%p>~#<-mXiUN*`*lp%0dh(n*19p*d&qMzQGX&x!UaLA7kA-4!@kw+L(>Zim3 zd%SGa)gC+v1W^h?>khQtNw8)pQ!%u&xA*#FjzQwPK;FsMyZQt-Z6wWYL7H-paI4MA zMp@fTY&+;X$9PFZ@55}!)Wu%;a-}oTn3vjp7Urhd^Fo2OTk4n{X7g z6efwSL9e0L_VcqhE}PHo=boLYXardArLE({-x6f%ulflxbM(Yz7n^1nUZW0%6D!jg zJH&Mz2rvE!fxiFbS=q9Tdpv*!*0RklPK(+C>S42@4t;sBsp#k~$=2SAK?6t{D;pbi zFBmFfq!Xs=_Fn!lp@EW+l2NP>^Z|8R^e4K+xD8U<32+WG488MdyTAIlPo_JE!M0yR ziyn(Ukd_wW8k1a+K@SFQ7cKV#gCmB0^)yNADLt1Qx}!DmL+U?0s6(hjh*IM}kehuR zgs=o@*?9C=*p60AjH0^G$^MX1etE%2Z^)GMiy2` zFkD(wIKC`O7#Wd+4Phn7M`dBEte4T61OI2eQ8$~?Wj$TpBNdKIPx;btV`e>w(^S8u zV1y`xXV$D=GqLY=n{LA&C=j~<_Jdw!w7;wff#>GSlYN<(NLL7E!UqlToW=fO!H|kMU+!HYzx}j zmMB*kyKkI@Jv|?rFeLtMj%)VXPJUfMWFT+zr&9;REf`tWdnFSY7zAG~02&08@;8Ev zNWb$k%sas1;ZmYDuh5ZDmbiHY+ygZMv;pnFb#!+hZY@zA+y`F@$EgnmDcaEkj$Fio zg9G=MXQyfv_+2H@n>9hH?5K9cWv`hre?Q7WBz;xRUh!FSJ8HZ6H>zslJsEO(Jv2os zszF#wtxB+bHHvHlVrIhICzKp*-gdidATgt*$8+I9`E{*J(*~~=CE*73Eu)2`MJH*f0p;DoPvy*p4Yk4Vop+E!aSn>2+kh*tDT=WkLWygVcGM2RJl2?bcubits!Jpj$!%jnT`8E^?AFo-s=N*f(1sOsL_@(%^n&$C2=KM7`UM5DCT?`a~-snrM^X zAH{qG1|``bmi!aG*i4K>oA7=L2q@m$GLPeYi|u$}B_~2>@SZA73CsW~ps(!Q)AbeJ z^L2fy4CXEQ{M2SpPS&;fM_6vXHFeQjZVATHa#myaAn?8?#gB2o-lk}NBraXK=r|kI zWs2CF(7hu4Q5gwx9v-bRK~t8OQb>QNmkUt;m=q2IGYZuY`%A9UlCra6EkKl2EFhWd zO6^P-TUwGeR3y7X{*)Zc5)vM&g0Kr*_#30cX5esYYF)J_kb|G&n$vcjieEh4{R9+& zzNC%hV8wFvfb91DZ`?0T!lMmu%|||5UsVBl!h_=s5}uH$+n1C)Fk}QY*kRzw$8xMC z!OiqIlg#wkz?~Awc8lS^yezwPOd#?pdD4?FE@%6`d5jbdQg+=o|3!vPEfhEt$IpQD zNJN+5Sr7teV%P>8y5FNHUroNRI}umDf4|6*9C#$1LyU!m1+<6!vLQQ5v?E{^FakVV z0J8T3B{W2(yqs6sbn63LP7b3+xrfIvzWw$vIe3uX5pu(H0`j?EnJcKC?r?464Z&aS1AQahH$vQ#t(U(Y>97)Xx%TQbO^S!!B-}Ki?x3wQ z8_-S*e|EYLRU%UVJfjhZR+ItoIX{9JSJ_CjQq%)T_rpk;$8)9lT+i~%o>!ku3VD0$ zty4)Q4C+gi2&`D$B>F*+)dBk_uml|!pJ{rgpYghYHPtYcG;S2?ZGF7%@*gNJ2ShMg zjf>MQc-*kfN_{4Z}3NO}ou#3oG^-h4a6=0Ivl*gyorT`KoDj{JjzZDJzk6z32 zdt+aq1j9pd*8;Z*h$AT?ox$R%VqKnZ_RK(KZPjW;!ob?2*^{vm$)r!*S&;e-F$wT zWPqS+^%~(N*?@4*PH~Gqlmp@8|+_yDeVL zyrmkG&@XsyQTtiWx|7$ef_aFch+Na{?R-l&z@;wVc5&2|&4;sb0ffxSNtYw>9AYkD z9e>)gZ^m>-aU=rg(hJ`RnxT^lw6C z)}H)JHnsnEFpAqG7}j=Yu(S5oi?&!%B9mrb?T_rG`C{05X8Q z>+a>XZ`mdxEt~;lk1Yq*Rj6AbWKI9Q`qiNntigNUYV)gOTy?a-u$Bv@DJr}(fM z9a@LwLRiW?exJLB{>TAW-CM6KJ{H>o`S#rbYUOto&d!eGOH(1#+)I?iCsc7J6fB*| zd)%4dR!Q@_+{ZhAibaZw!wCC-1-V#^dG8XkRV9#O*tj7n;LZZPJg@)?gbBBNEN}~c zirGuC)YQ^yJ7BbCfA5rKJ#n<$rWMi%!q$PgNz|2Y!5sl0 zh)udXDk|tfQhB9y;(6jaKX_>RjJpk)feD>4d3SfPJ%pA7m^G?@xzJ#N(R#K2y{Zdd zIYk)bFZ|B{BY&H5Cn}VoZ%jr?LlX-0BGB>`7ZoY+oc}@s+VRMU9P#F~xiIgmFogw~ z$#V$F8WKd+F%#2?8lnjs+jLJep? z-@etYG!Qdn{t`F@sj?-_dZi5JoB56hUq_lj76EDCCeMZ^@LK9_B)7`*K^PcD3-tzX z??QDBV$Y+lL!U?s)re{OKU@uDlxo@qdl;=7N-}-`F*EXkynf)pkTo3VnhF^(CSziX z1~@uYJUmG?XPhsqon4R17PaY3c1EoDK!Zkb**qN>g0)h%8<|>hMl}nF2O^@+hC%}4m9D^a~oI8z~U*cy$pNz@B2L2=p z8)s(@@En_t=SfO^0(v@6$x5#Xm?+0x*p%DUHP+KCPZ6dQ)-^QLxSSg1r-Nr3luBt< z+}mvKj#}>Tfs125)+@T9Ha8Z`o`CWTwX?f>irN+uBIPNv2>xJILrfb+vk`)qu@vj- zXN#fh8t_>GZcvpvZ5qG#GR@)XdcTF0?Yi~^mx&@rZJ!L#pvrB8{k3Ie!h~wLfOY0d z)Adry?cR+S`W0HnE1$4G$a3+SWE6A(t;wz;V&aC3_&2lO9$~$CA_bfUjD1Y7xnmOG zEAH90{81gP#e>jNX9jhVclzJgDggI=N5u2{{Jjut0y}t~c4Tf>4x6#~eZvq0?+n0e%G_AGvLk zKR*>$5aC~p{lppA*L3}D!VU6DF2JIZ7_h?Fw%t}^E`?2fn_4V$cqM;L$LQ3=Ta!2DW|7L3_c~WC&m5g)9vH2cjbm1*tmO%14D*` z2CKjNAVOKHbuF2EA*-pP$v0zJmllF?86N)4$+6md2wN`mN*%jdoBk!)uGUnx^Ddkc ze0MzBe}i{kv=B&A0E-P^@i#Ce?TxR`Aji$7yl#%&FR}s((J*Juo^GI}N&v#lbvf$S zr#Akx&P3hrHfyd4^w)*NY!@A){9YG;BhRpXMs2r_8_X`UlEUM9<`RVdiy|0YqM$R6 zd%`N-F6W3Q@kjz$3`G?c8H^Z@;oBlqmQ&4T0&g~zZcjOnH7yO;9;jn{1IpS7Bt^@A z9&Xy?!q)Fe>trOPNIzV1oaSLqeyoY!+0Gr~)7+lSd_A(_bgN`n-U`+&uBY^Q(jPCq zy|*Qg&)vPNEnGWGR0iDohY(G@Z3rbSs0v}Lk^&Ftj2TSXjHLs?Ih>M`^3`uEY`~;& z2t0dv;5^tfZW%s`Z2+l?$e=vUGocB)yK|dQ;qA2u9IlwPlgZ@MktD}hQ!#7hm$v5 z>-$6%4bj1{S8bev0y4HR5!$7Hq8P0O(E!7^OGQ3#E?Ja>OiknZ%COc&xh>`_A>Lp3Tx)@Xxl5{1-wvZ- zt7i1{a0{~4s)28(uLVyZz$pQBLGSZag=W3ffOvXllT!c+v&#|2OZ^tE2FzQa8f-lq zqAg{bcAJS@4g$S5c-~LW zh#9DGtK>!C1|=`4fvE~sPX5SfRA{CDLrkjF+>f8 z?JgP7nM{CkS|_IL{QW{=swyw7d^yHHDI6JnO|D8;V8AaT&&tRdq^0tiFo#T)y^H9ThL?` z4eIZh*fnL=M~JnAvr<``#5NQ(z*%Y5m};_7FOB`}?99sdC*cC-=?@f;SIZyF z#KqxPEiyrOPJDt|lGA4VdgjY@{Ua30?fuB7W2#$r4mJ!7Lcb|Xm9xP=f0W0E96teR zK~2}!9BZ?5AA&J~=<~@aa7N_&Ys(>2IyOUj`AD2Gy1~r7v=VC!SH$`z0U%qxu;WTg z*VRL|ON%Jf=({ZI0ZVyL>FM?U;exLO3x=XXj*#8qKs64Azg0JbeTaDJ z{GT$LE1GGw>lCUFs!Zm=tEi}qWGN=X%11i+FC)1Fl~{ikq3^`*Ml;yA{&){|nd<86 zUq*)5wCYfuz@8-uoCgSo<=dNpT#RW&{W;LXCUo0@@mlt>_Vehd&P{10c=quK_(1BA zeHb>=zHO9rWLaYNHZ0vy;(v{>KvH;tAD5N=k?yM$M<2RWsVp^`D)kGN4Q&F*WnE~( zfB+)f8_?JVe6OgeP;E_;gUN-rww@is`}lWN;&0Ka3y2thcvq^j%Yd=l zc+wZh8SA%*H!*;qYB6_BAGu=3qUTxc`!x3UusaLKOawi7!Xf!cg7Rn$GZ8M}^y!1w zw}e-k>`(k(TGtZ~_KA+wg&GlXk8$Z)pQKxC!++(l&NlTkvhLA8U~u6{}y^r z>$6v4sJX|N$yI0O&T3z5E>h(`V!6>^md$i+fXy_3@gVz+|L4Dwl&Q?4NGuTzx5JV` z?QuoOE_LEB{5_Y4w%|c2qc--JIWQwD(`R8}zc2HrM6@vj2)w?pTjOi&HOn82iw4F8 zs?A9!1(O62F5TX+HfQPbt77~$%*+@q)os??6S}

)Ua@8F@42mr?|S@`_5L1(e=P zqv>G2@BYXjVIcTr&}(pWvk;5yXM1}_E`|7Kcdj9e^f}?Y>{j~R%1vluThs575!xm? z5!pv4?=tHWH%C;0wa}cs-CGj**<9uYqY9bF7M7PI0PG$FqXBG~VZG+S=&0J&Py+he zGATw8$Qm2;_X6I^-o9UGgjlj7BL3*YK=lGc7ru;9x4bG&J&<}vGd&U^x9JgjQ6r@l z(O6ffth8AHsVMze>M{PCZ^S-hK(bw=Bh3u_zE4g^S=re>eF33Z3#hJD!W9m{On~D` zi-Ks5b{GqhRh%{%wfO9PYlS#>%?)7>Oq#_F3lRe^{1G;==MV#=u#fCgpCz2H9UU~T zObF<>q`;2hH|d`0bPk{AvSK@}|C&<ODmpWqh! zc}1FAo^;mo05#0z@1DQQ?jF{)q^lTG2)hDS+0UN*~C zKfL!Mvg;XUPF1%pYSEm_)nR16QhD&%6bIj~W}t59oD2bpv}Eb|?cH=RgG}5jIJ>zp zXM%ZY-1e^=#~UpiOI^fLo|JCWVwfYJy!+p4HP$%pt1i1d7#WLbHE-fn)`A~4eDU;K zS=!xL*`PkgF_K~(l0w6?v^V6jVHWYw%oNd;K?qQY%`W^v^foRo&R-;0FYKhS2@%fy z>R`+xn%LGH4fc%WyG+x)()S^Y$9$i^2TJsD-%ze7xc@#1dX7A#3w!&ayTQ~=JJKg+ zH=rprhHB~*;pl;bd?wFuZ`M~u!s;+_K&o8w1cr3)*Wso^Drs~xcBm-ncYj5VSyN!h z)Mv#{HcrmVizn5xMrc7cNH?ffZw(fp3&jGBfZ?!GTd)zDUtg3!;~w>U6Gr#q;yyc1 zO8L9GkQ5#)7*hbM2mgV2NF>nlKxG);rJlUOv%jgG_qaz^wiX@=D-eNYRtiD5Z}X*!Sbg&qF*B9S)R|}1jRjWzo&oMshS+_ zHdB-9Fd4!|L`3|`Nq|Ut_?7eKe&x9$@3XfB)N<_ZK(A%ieFr|MzLgKSMVjsTfIzQ0 zi00krMYmb68n)+Hes2ZTOrWrU`Wp=gr;sX`156TB+BHjH3-Jq!IG_U7CmFa z$E8+Py$qY%h49~B$?-Z9tF_oy<$pkZk0C#3lIXC2vXbW{z_-UEPOQmTl<^~fwV!ea zesLK7=Fqb=$z9_kTyA_a@e}hXO{Nvf*Q;Z_^+4a<*_ic^5NXK%o!+^ZH%@;>duFKv z9j@WJM8jsy*}t}6%F<_^SJzxue0Ib$8?xQFwj^{zeY~UT1_BHtK1vVPl031~U&K7d zj=p$D77}aAwhv3R+M&D7c=@alT7Pa=<9K%b-A_Dtt3~P` z_LSSP#jeIaJ^3MK_#J)6ZHG&<;feM2;rjEioJp5AF}~vRc=?x*+&#U z8#xkE(pP>qZ=d&GamrsNh&NfyAzND%s~0l-iy&?v#N%D?t1*^YoEZN_iOVV zdE$vUkD$?Hh$$QCzew7_(NQzNh+MafWy)wD!hkiBtUyUbeRdXP^rsDLn{lEN`BGI~ zJoVRimVnwI&xI?rq^(!^$*Q70$K3>VLpxF4rPcrv};WSFo=P+ z4U~yJTvNq$kyDoWIXObNdh~kgT)*?o!DN&a+&@;kyNB7irGAH>8fY*|9G&0Fa#Hnx zIk=^6GA7+8m4adqY($;w&c7&)piZbf+q4(Sz`H{3TN4T_^Wfv=9LObU1v=cg*eYI@ z!h&gM)S2d08aC6>a&4+ki?c!PoVs>X61XiZuQ2ytW}?-5q?nryImByns`ovpr`E~F z20#n`5iTz74nH7f1M3X>Bd~*|jClm2XbOvq2ljtrLl3)OAHnj>lqqoHU}9430-@0H zn68VjR^(}|T|q(N`<%5Ym}L&~F?CYJO`mz1j-+vc?)>APRhvhb`|977a|yY`j0`!@ z3V}R&qyC6n)YdMl=1T-K@9Lt)V$ZA10rpo%KlkZP+FDxPgS~k$a;ofj`kCYA)T}K< zYg#*Jwv5O$R*1huNZ9Idk~MmjcjICSDOy_Y3wVXUvM?BdvQ>37r#Abr7y7UkTYPY{ zY_oVT6K;%&B|5VGG?;z8yxw;GJ7huibV>)W?D0~pq5T1&R5Np9Bcgp^TT7(mIrt-R`ATdjE3>cn#-gTv5I*}CHMR1z@s$XP}=VA!ZQ zen`OK=ot7#*&(F6Td98DXI6AX459F)Jsg5fb<+*VqD-}!h8-q!h_Qwv^^cL03F{fB)J3LVbh+It?kB)s+Xy!9)R zulGq#zWvcG!*KYm-rA_t;_j-VycXW3zz1vcbE_9vsEjNe98A=`PGegGm4TG1n zE#$uan(4^BBIW7L*NE4}a{a9j25B@LAsb#Bf?jujhFVYW;GV7vB-p(k<-F<&`yDbY zm;ViWw$a`{O*|ZKcAQV5sE$3K&D{2Ka7=uhnzPkIRtOxo)^x---`uEZq#oAnA!dIF z4QF^r+8=rLd%jz3)L(;s@XJi_|rc{lU+KGXYG3Lew9LAy-v%oVRQxAx|R zk)@8C_m%B8j5Bq7!)AP^J$BW3Z-k-8CT8!dVrBPj>KXNw_^H`MV}6*ObLYPrzBof&0A7!rFwFkTt1EPj z_qlmWrE(7T_N@}aCsFq9*X{^a(+#SbH6nMQPX+DIY=<{76jCMCs-N3vuWH+N8-FPJ zhg$3YXoFgskLLZD@SA?Ims|y$K&Iq}Tb&%p)xGV_lQ|2)A!+}KjJ#|#e+XR-2#bHg z!3c~OVIv*?w0{vPvAe1pbb?4K{_GSQGW1*YA$Xmx-x4~`Upm(R#^U;DeyI7*f$y3jxejY)4QvIzOxb}o;zg!saJ{?)3m7FE z6H`;0EMGsIC7}Ir(1}W`uCD$7ff$0q_2~0j3ih*^iOH*zQST?E>RF%_S+BI~TwfP> zL|!;YV(In)uEvBdz8rlq+Ku$a@2#?SDoMRsd?$K3-H@ z45Enbj~2NqJ&Y^8%C`gN`O5S1V3aIBwk<8yy(LObjqM2;SH$1nn`N6-qa0UL#bF^+ zG_5-5QFCx*t>Q_%E5G%4jwk%)an~T&5`wTsD`&d7O~YW*w&2}IzCd}t*|y*8{e`tE z2{w|@>^!F9Y{qY;P``S+86!Gnw0@@YV&m<_VaY$gCrnlPXH@B}LUbP_CjZG68i5Q4 zj`I%wCGjn2+w*P|Y&3?cF7lA8aEvJ=_m$=T+p#TNzT0sm9uHwew9YB%1J*z75t$Dj z?=wBu@KG!XEeuAcO4XAI-_Rs56<@F=Jl^UZ9P11Z&PH3^OB145oU41r-q^lMOm|IA zBwikJ-#+dpDqEx{3mITBWuD-?>9~h}y7=uTH+&1{?&ZKgk^8+gktIlp_NFrPY`d~- zqkX9EoAu|}EuG;r3Q2)ifzGg?Llkpv=!@uYzKXBSbC(Zv z2McNgojG02EM&tQ3>|@+5fbVRn9_5p9y^t(oU<)IHU-oDNCpwU&kkYRU)E6c*7)D@ zf-iC5Q1c%D7qiPr33aB(tr^|b^G{An$0PmAr*IuNx33Pa+kVCBF`O(OCop`dwkNV8 zy5&7yIw^!apWM5g`bs5fA8;}g3Y?T@h#_ONOZ|6NV5v&3Wjos#>e^V2!&yS2L0ce^p2MN}#E%J^>l zNBt8JBi8KAddgC3`YGa_y@5mDaMmzIIqvBp!>NZ56i#SBBs%oZTet88~N|b z#O`H>g(BQ%IQbQo>&mBbMP|4V6+tR&S^~wWL2L~7YggT@y(fNmJ)-Gp$HK=N33F&t z0fZ{1*T!1Rvv3R5>zs0Fti|ssEyj&g`s07*c@x5AqH zbwg5tC~rJm)QB-zwg$?zU6;7FX?5yP-UF76^5pM@jAZgho-?}J8orz>B|gLZ+qy|T z!`oP;*s@4*F)@Y1vV^^!H$pC<81;N7Zf#{AUTL9HcDlEJwxw0cEibj&t-0>*?r;U= zML46<%yQV?@r$LVqyV-eVo*<)NAYg0Q;Uu%xzqFGbuNJ3*&CP;t+E;{*PQ6A^u z8z}j9(zrGo9Jb{SRyv5;*w|VTh1fjLGw34M#JFgk^h)*wmq_`!`i(X;a z*w{1yDm~^Q8h@%}*(FHmuyDx1;U z^PK~!jNc?NT&W8l8UQCwH{cYw$mV~w12szo7LqD+$vC&ff$-| zIlfY_#p1yHxF06+IwV9jjg$AsUlw8^+32@mO}rropXW>nS?NjoM1FKRDD+f)v6^kh zDqg^l`@7%DGty$4$=ec|!77j8%=KM;0;AmZUK&IXd&yRvF|(yL2nmqwIUB1Ai&Y? z`}_^*&H=yb5H5D@PI9zxY~}&ZjZ*V;SnC4~&=KM8Q`iNh%9LjE4;8jDwfIA;Gfc6F;xZ9KsI?P3~KkCiks6 zIXse*5xMG^2lw)O(}^Gj?ZaB~>rZ7cuqwv0EnMoEyT51aRxht0t7g<%3E5?-A6xC$ zD>0h4Ou)%miwe%2yHi6RPyQi*-4!cnd7fb_UfGd|W^3#NRa7b*A|OlBC86K_P3Vqd z1Vj44p{2TY zG6{4)zem1}q>To+O_R+Sn_sh>9L~D8fOR?KzP`RDpiIqz>4|vqPaLQh z)fL815Ev+O>g%zNJ&)Zry!>U3ZsVT7IF}!!%>FoBXzW=(%_=T_L;ScSp6t5p4&ZZ%OYWzJf9a{O*zpGmlQec0NNAq3E0Z>jAHvswz~_-El*O{FXJ7X4NY5QC^9j zI(olWjP=BjIRlNt0|f;#D~tq@T;C(-jurikFhlnv!A0(l%Zz-_>3H27OUY(``;kN~ z5lKc~+HjTDu~?5R8tNOzI?cV@+J>ZCt53o-#?948>tyo&(#?qy9p`;ZrD6Z<#LeX4 z7uKg++kcT}QD!_oE+rrHiwdRsSfnXQ)C!@|?Rpb;qPO}W5EWvK{?kim4+Q?*g|N|w zd)pHr%E3LKomg%#kJG;A(&(Jr$U{V|)* z#L~Obv40@s^T4cZ^Fq+;5bh{4lJ*NGQ0_QhIjy|DI|)a5;C)xx^1~tt+LR(?N4`@ zflR|1)$OtEue?m>zi&bn-U(W?CnWhSm6)nXs^U+-1!A)5G|LfVSg^yHV!-3(;3#EA z_woGKFh|V{RTTjVWk64Km9OKfU0$^iX zhT?`Ju;=icbV5^6Q+K_r&tAEe-2337#>4AyNO^k%njdpI%U!vDZ>?pcWesD*^NH3E zcF6uMHuuw!DztG;xskAR2?PyQyJ3B#t&M8eFy*v;glfOqhY;LvLB2g5+`If_u$ty^ z(Alq^Cg}CyrOZM$%2$;~o1_Na1!a7BP8dU_|OOf8enrcICD#ql+V z<^2NRgD6j{5%jdn^uNHVs|}Rr19Z-VH#Z}C0wp(UZn3YLL(q`V-+Uutt(eNTdiIj@ zAquj6E^Ug^iTw5Rw(2!wR{I!q-9e9!K+VB`!~NGH4iu~RYUDU@lWa{sN*(<~dOtoV zw&3qiZ{%EuBMDr7EYpnlC@cHuyVcE1oaB4m`#xBO|GT``#h1mVX}_Ou_p7>Dhq!x< zrmK?#@ia7`*3QKWwx-$jb)FdCb<86>MNp#kc6m~wRq968PZPvd=tch6U3YP{Wem7u zdmnM<#<{lr*S;8rrunqdG9PKvbhy!EfV71G#p^i8#q8$(W_*3g;>Zl2S+JphU9xy~ zBNA;SXs^1xoe21-1#OrWJ?%OYIx&R)ho`TMin5K?9=au@k?!u4R63*^0Vzpoq#LBW z8|g0T?vid$I;2|~&h2}?^SN058dx*)+_CqyuUI(1b2~>E--#el_Tt7n8*%1#IB__j z8u#m0`TMh8aW>@H%K1xvs~PsTIZJl)FNc1&ePAncAa?%ZB_mQ!ki!w82P-eF zjPz@IYc^2Lq|(a0@4Z;}Y`f6BGR3vw^zSBfaEQ>_*NL1Qf{dnP_Xzrp##ejZ0a@rS ziUJ1A@s!p^;)Hi6X|58YpD5(pD^h5Ppxq11PYp4uR*4CVcbb~XOcl}t-z49aX6IS` z0K3sFRasfz&zvgE39t;0-bx4<)fE)LeIC!~1_VQ%FTaYDELFw>UUATorf)_J|R9UIs zkCvK3PeKHrN9RY&H7mX)Pb}JH1nNzySWyZqf|Di>7%bK&7~%U0gN=So{r**vw%`+b zHts@i1(;ua5k4;mis#d19%nzdI>l7`{18O$yw$j04B8&1NH^~^Z?=L+eUMM@N5~gn zu2fwI!tji5S^`_|Kdtq<-AJ7Qq8@ap zb-DY*=X2TyuiKvNNB)k7!{nNmF2>uZT$hMAEP*nxS&uTcymwb_>u$V=MP7ajAFbWI z6}-!P=_6UY!nr=3Q^{nJCEj(d$Z#&pJ-tQixXD}F7z#Dx;?0&g)q<|giNgqZvacEw z!2QfhIjRxy-IY=Qc23MmVk_*vtRz0(M!F&Wy7}&d=c6%N(^UZa#{0Erw7(}lNH0$X zU$;0Xw%3`n?;-O$R5`61n4b54Egnw?N&0AgZgr3NtAR(fU{sbXhr#bi((XLn!Si&* z4w&q_jhWl0=cn6V&gdEtGb_5&8WuK?-*2z*<0n_tsG5TzR^`q;0 z?3YLxDdEcrRm{hd%CDv8dxzKb32mmPrqYm~oBr!g8fB$YjLFQOPtzmfq}XiJq3oy_ zlRw)yGe2YyF6SLXy2?3Sd$ij=Nc79vZoE;2LQ#_r(|?Lk_x-b!VLPlDlhI}aA43(X zN}r7+uC#pYGXEtjVJC4ykpA%Ifndq=`Oz&X`l6-&5K_#T{SBU)2%&a6XF~bo-NoF& zhzE%(@x_%!L?jIxUrO6wY6A)E*~*VlWhjw`8@X5D_(!gM*5bc|Iv4rRtsWiXBX4{ z_fKB5k)h$g!-Oe?2a?+8!jQ;??tQ#5Llh|~Zp@DQ_j==({Fz9HNLA5kp&Zd&(*vn@ zV04AW;LYka?yu{!we=b=V*D}Zt*y>GnCIhTv$l)to2}KiCw(wJ=L&+3J<-x>1_P>I zMQ1Cg!u}p#Rs+Z0uKHEg&u?A6JTbRbV04wc5!T$D>UW_SbfRt03V##v8qI9FX*cLI z{>Ji2KwYRG*<@k;eWxdZNRutHqW6XHueu*_wA{EP<8v=}&dH73Q|1_*u z`CK?3$qEKc2;S2CYS|idy%q6Lp84}mCP{p?ndDBXvBB~GxB%#nx60@O&rim;GY==d z?@7JiJkPDv6b!&pVGX%>A-+7$dF1%qRh>sYtokW>zF1^jD0X{ZYM!MVc)qDjI^BG4 z+lqerGGMRfxot0aS;5;|co0A8F5{{oV~0h6_|SfP!ujI&b>;8I>6#-c$!$1kj@Pll zR_MzU#TPb}G>y_X+jbX1|_d(wCBUWL*>yGTL z%hL|h8{u1W&;8F;IbK>+l*t3e=Y#WlRqD7SYj?zgfB(p4JpJ{sU#MtYZ}@1?Rpv%g zuFVojnQF`P;x^x~G_ZMOy1jaa>A9bo$oHgZFcANHL;=>+p!Aw~?E~?F$T{QV>Dnsd zi;wpk+s@OEw-={Qu4f1nn>8XIgUbODam3Je^SSjr@9UENW2=u}_|=h=g5KJ!a(8h$CzuJleaGtdq&1mU zo~>1c!X#C`5RS+Vv>Qh#)f0QIU!b3ud0cVEcF5wT&*YFiy=Lm4WFJgBx=8z}RZ?a@ zipJ5A5ECotuE|%%7Z>XwA1i*lE6+pOw#9}p#s$R0xEyoI%ICtBEe zb+t+cn&?)ariI0>9;sJg?+?NJ&0glo8IYkM7rtIbYtUH3o}1f963ZSZ%?N<(fA;XC z1tM@M(_Wtk%0GdCd$m#80`8p(4dIUn^(`RFjM#oWf>Y79zt0sK>}GtTaB@Gy<>eLd zNvpk|+=E0ocZLH-iUgp2mrMraSUdBjTY+nxwg*JU?aiO$5VMX-;9>UO>!Z--IiG5J zwup~@VN#W@>bLVydmx!`5t^A(M+0?U<1YskeXnbEaKNc0Xs-Xs&7+?QzjR=+vIUv# zfWWv=(=Gnp3sA^+r+5+-a+X-1aZogYoT0Q(d23fp)tlsA+{q0w>ofFtg;nfa1 zvME1lTp~eiBnrSfcz-|B09ODqY~*eY^Y;KM{Z+2_#^V_O`zIL%VO`?cduh+i3+ZdG zy}IltCNK;21ydfF80>LS1OdakUXaHNp1Ln>wx@&si3LeCLT_GPv2*j})^+KsL2(w4 zvbAhp;9^Ndlk|glDZExf!b;UQ{0^{y@7r`(*=lmbght4M2PkN+8$o!WdUUX{wn))D zGd>(3O6-*3GH+7(_v&1wkjy4sw(nWi9F;EBog(ld27mX$tU^uTr^`6qm~i3}HLaiy zT!>TYDmj}!)X|sX5|KpH7C>89GB`&M!ZfZ#f@!n)^?xXaP~9D{=_leF+Vg{g>9%?vgUBGwKjTVk}gKY8KZVaaOK8fUE*c{K9?lLG>qtjRbb*u7(zskP2@6HKAGVBcBvK-ZIf=ILSo9z<%QT-GRPj7@>?_EfIp=H_DnHiVs8;NQRp})qQ~w+;y9~lk zYsW;>ssu7W{1uAZ)h{e!nO&CI(Wof)uUh!FGg>f%AP7YUn+}_Vd-l=W z5EJ+~D@$PG1tcbu0R0a6TBEqnzvk_&fGbo~@(RKG#iPHlS<3*8kc&x-yY6pOA?fns zGzrS}WX^`=JGb3yWKet|C65MaF$K4K+>C$yO9*T7{VEepQx)m0fhn_u%5^jj0PRa& zqro@#lKh_i^@SH$L*Qh8tTRJHHuL`x84;0_lLMioqy!BL$IcpXuz`ZaN*`cU=a1tk zt5U{#0?B5&%LG+Ttc@Nq&oUuG47Y+6u$DA6qRvx||9+3Vl0PJX z$ZYDA8cg%_YVVkcJrAH7`-b6En!B+Rx$|E;`RwuYL9i1R{ZjMp>bdKY=h$Q3sD5cA z`aF>(L5AVGaA-QBTjSNXiR;_rm@@6&u0LB*Vk}N~8mkb^^%Se>w6|c9XjUN2S?ovAg2Coba6)L5ggaTG}%z})Iz`xwEMji22GoN-g%>4=MoLDijtxIS@bXKqPJN$hztL78$F()E>z z*Q<|?EqgeGkvVf=L%Vmk9VH-a46HMAu(a+6+c3x46oMBHGu69)EiM+ry-taPl5hqQA?>J|e*f$af3!2nUB4Dd!++ zo)NL_l(S$*EL*Pcb!|?NV5k){odgBTT~uJNjI$FLLrGX&ZC%Q8`YB$0+bxHi2Rb{k z;?<=M@TIFY-Was9QDCO*zY_qM95j;QQmrYZi|G@Ddidnp-PC#guxBFN6?A2CLQFPX zSn3}U5bH4gAKxfA8%h7-V*q|qKxV}zC>Q}~4fOMx?4%3bVMka{bcwhVqA?NG0{O;BzG-4hu66^HJIn(ZvY)HzH{$} z{hhmm5teBb2jJ0?y+P_V!46 z9`Zt|(UuN{CSFVBf~*J=97e9}cFA0tT1;F^Q)_Gb(;w8Jcfcbu1rO)c^PNI-BK<7( zlu_$$3k$dxcMIgabk)=X_xCM;z#c5Vp@jL8kbOY$#z%$E5c1Hd_k4ETKS+*xgEjo^ zHSLF?kUviA!?{aQN0%>`;%H=;HiGB7*Y2@)eyM`$35mUXr>1_#t}3(`h&c@{xHiN# zY^m~mPPZ5kI?oJ`r*?YvByo-+e+$|BxQ6@Sw`wwGt^CnQ+20<#d|6OT%f5)Z>bOTr zpXmFr(m)^66*oh56L5r~Ck^I-y{KP>r^{m->&6+Mrg4S2EA}*sP?k4?upzA_mSJZ4 zxrXDetzEy0$p&0{vT{4y{A8F;cS)Y9Ht?jd(Ne%UC_-!Jm<_a)RGR{T#h=q@kQU$H z&x8639+Qwj)Z9e0Foq^3?MFqsLgDPLSB4w3HdS896D*+tK#I;sigsY2;x4p{W`LR0 zMqvf-C$}AkT~kJVM*E-PcFlTmB2Hw!qGY}R!OHEzP~|F8r3!b9&d%FE>D=Ef@7?Gc zh$Ld?<121q!DudPn9sks+nEX3nX;n&3_V>^&#C_QHj;xoZfW1ih>8K7V;NXnshw?_ zC5@RGLm}N+N&3CMyL!}GpNWc$?nW+SYX6Xo>Mv=55D;KjWuI57gPhT94Tg-?Jo40q zIlTK*M1T5CJh6b0W7Dh$(#luqZk90`&X$%IB`u}m7R>IOMAyzOBomcHRl<6Ywfb9P z?SSAQUrBh&6jpQby5Jyxo+vIo8$HaapJgd~M)CH{;8Hli`(u@Bi=?Ttu!PvT)}E4<_Ku6Ne|1#WQ5U^e98x`deBufDC6yB#&1QU#_%w)DC1XMJ%+8=7@7xp9ssAOyU$X8cg z3x~ZzH@_&YRDlyQuwa9NG`HwUvRpP0w5cTD&=x*phq_S2NTbR0X#lM&ArT>t3w8pn zV(q=V*J8DOfPWw*MFu)FA3t@b`+5M|vNg}{)6WGls+;?QFFj{xY!E|hCUDduC(+iY z-y6O>KOH$!q`K{JXY*hxdT-z+UK=fol64JG7N}EB$lU$BNnWxJ)-U?jyW!hyXh$-fTvhq^E=5HRh2-68IMDW;=3 z_wo2i9_edMCqo&dX*#*vy&&XbjNly`zKIoz&)B4JFIlI6t8r)u z5m;v~wfl8`0QaTGh;W-m5dMD`-+wn?5C36XKoAbh9BFKHie`qr z=~yIy#t)>LuYTh|_wflRd4SJ)lFO6Hk zBUK9MqJcuq4v3}on(Ux})W_VyLJUY^9UKe1dO*ha(Q-Ws0G&Y22D3)FmLD)-1rxHA zF*6OCNGs@iJ3RF0x03>4Xvy!32NSL)fYD4;w`gOPvGD#W9yd! z`hkK%6%+)>asJhy8ylba-k65a#!aH zt@B5Wmc3@o#1teN(PW$ks}Ht)5DJnv#fD7dhxrj#?y%g!h>z+zU@rfC`9idjF}eQ} z6l!D?McEH*vpVgh&s135w~KtpHbLO)!bg5ZP8j(eBzRTz`b1fRIOznq%uA}}aD$BsTVi%+m7e>Lsd5-F?_VBFS{s8)ZYr$a3PhhpEPq<}I z6s3FyWhErzlBK98Ab3>DF{Q2xOl?Ax7)wm`!cci za(k_K+#CW{*F1bZ*N39l0Ou12pP;m?jGdc12)s`FBbXcF+~w=O-FI&N%~I!`yP#T8 z=jm;9=jk;!@>L*nXxllkErKxjaOltq{rnr0x7 zrc+@d1->Ky<0SB}FXs(04)-Uunq8uOenqFF zqr(Osj3Had&S7{raAqel> zxOq_h+d5?}4({0oP~za2tN;P1{ogh&9;-4dWus(-E@v|_lx%vY4WQ1VH0wLio;U_>W9-e{|8({bP!8Ck!1p2DC1(yA?%12cX8Qi`Jv zc3$^}9XPls*5c4J^}m6A0EcA8T+N~K<9i$QC}TmokYbwi*RRIr=7`Q#2l&nPAW~Iw z2-?sKP~Mm*-+8qQgPIOJ#o-~V+RH!JH$5?*MZLX+m)|af2W1lI3a&QbC4>KIFyO|s z;Oc$1cLtvuc5}0vU9;t+v+_th?OeW-gHiMVrW^Go;NLPu!Pc+sI1CTj^~`Q3Fx~3% zVVP~Whr~{Xe18OQcXHo(^6=XFi5MT>aKua&v_RlZ{je#zWZqXOS*L{exO%vACNA zKUf%s!;LxKAB7GU=JLu~2%Q z01SkNFD^(h^AZKwWJF(fZE42ub~}RA@e@Br+yTulzkmR8dIg3TOqXFNI(+W$HXGO_ zGl-~IDDhK!9Jd4)u6jQ8sfO^MU!YO}r8lJi{CQG(dL^BSrcc!O$K5CbG%DIRLymNg z3(xV9I1hr?0P6_`5!g{rtRyc8RP{D=*ebVJuL=5+(W#h)J=<;0t{dpfMT>2|M|0gB zm2OPtzAtqlpfH-kKcuwsODxzE$}aJ|_)9(MD4g@Ao|%>wf!C%TNg(spgZ^&>QE%n} z+JRJ4`0nN&q!;RvpH7G4*4KUU3fs3f-ZbZ1`0@RuRFIwnlp?5f9S4)EV(czz&AZf3?NwmUaA3a1l$qg|C&KGu($wLMK)@} zG3JgNaAWlM&Ql&KUks^e1}SeU1ry4RTDT{5zTd2l*_B`u{oP&!!?7$<&nUUWUU*8I z4s4M$UAz%HR%lLXDY9+bIXpZ9!iF7Rwe4C*#63^E^u+>UF`C@4h)2V@TQd>nWsRTM zQ$bSlva4O|Z+QZ|NXbw2IyC@D26d31Hqu#sa!PblQUQgJD*%`c8-^0QDef9gFL7am z5mJk4XS6HG2%*-0E!E*8MXv`F@oe3m8y8np_B&BjN)v_mPfmaTMb*9$Ja)v7$qtwT znNP$aZ}WBYoe7I0s0=IHV+(eW_RMuJ!qfj3+%Npa%W#p2dTnf!L#&;rZHJ?oJF^nJ z87vvG%ZO9EH<1lI;1V%E0kgP>KRYs%=l4o4I|mM?7NPlA4{5Yje)%FlQj#X(5$-rI zuNRx_DN*5LT{Nr8Mt9;cn@UD#*NjMN%uxY!hg`Ka5G?6B?`qO9H0uq0xA|qI0S(l5 zOw5>86rVmfuGCm2PMcA4z3JIct&zCKS)poJQ$KtM4%b(21j#&nzy_>!SAmF<@n`S0 zR2EUDbAEK3ou0A+835woGzOj6JzXw8vNE!;VF{>ot%|IJHn&A>1w z7r4sUJWd)+vFcZ#GmJ2v&BiOzk7&z+E3=rXspkK|QDUIo6QjfK0SG?CM3hTYL!)QM z0nn7#xOc2aQi2AIuwwQv5OBZgeH>|u`LcFjV*=qpYK%;vXA}>2f82 z6$)ktHNOw!aYhm}1ytNhB8u)RlLxoN$S}IVzwa>_bKe+c5y z;o*CVEJL>z%a6ctRl>(dq|HXZum>>P;)j~cJy!MR^P6KPN_PJO;GpJTS_Ho%Jm@>> z=E>*UIpSUNSN@FT{}$&uU95r0-N5*eAxKWN2J8LnkArjAYrF&=UfN`B^P{C!DP@xE zq>Bg%MVZ`RS*W5gI_{ur+&mEu?MK5&A!&*kGQ%s2*Ok$H&= zmj=N-V;i@#ZUkz@sZ@J3U$~^vv9bORuLl+Hq*Da_sf>{U!^4L3b(>2H#j0hbkZGf4FZXaNs2$#6L+s>F%-T<`7A(VwcM zpvDeCKE3`1y`u4@p}aY`9MJk0eyz7SgB+Zz;LZs+q4Tkab-kh zN8^3n+-2z9Y98AB+cXauML!-RLv(F_g^7|uq*C>8K3MKL znzFnNfi7TV`l?+&+MEj+{0|Ns(CU!Ced|$ER=7bZDM%uvsfmY-g2K+jQ;0c6hzmZ9DZs?mk)&d}r9PG_JhH ztE#^h@rm5OH*?R#W1ypi+t&qiUzEw@^z>2x%X7cGS$_=u!)}VX5aVtxixg5>?`%jftC@;cuxq#&j1{%O+m+xP%A|!+s zFGE3pd3gyiiy>(AO061bKw^vN+Ir|V=XqDP0OQMKjvEa);9IUU_JNd`Ou7wkz&!@q z?|8U60ncrKA6@P;n_IdAR*u)UUFK?*-<%ozv=Y+`a<9(M=_vfd zA-)GAb0JsgpDgbjn9`BX`g`{-$wfp+m$aA4(YHeRm~g}Wt2duawOcZ3L*wHEz>?0i`{%6xnKB!<=!vqN*zK*MCBU7mRbi#0-bN4hG8vhpqQZUC zV&j&Tv&@sG@)vB!adSs0ETXlmY5mA8{bnu^eR?3?`LXGAe_!lr*}eR{99(Zk-K+O3 zGQvxi-A9Ptod%d%(FUBe^GJX|go;#qMmpBSgqpQX122->xkQzt;rez?h7bFUNT40#d%CR3nD3~RPoZLHL7v>4J z(~|wnMW}4aD&bczn#Afi&*B|mqVSurZ_8es0uyxkNej~EuhiLNM|KKOpuv=wIdhyTuvkEX6!L-Y&1KoP%5rLr_cext+xLoPcysewEfht0toE^Tg(QcL4Y` zGT<{BNt@;BU-B1fSmY}A8%Yls&r}2Ygf%#)l+7gEg1%d~{*FqT=bU~p-2u}Dy z+tbIp%OmH!VMI|1Rm3TCY%rRK_{LWMa2r9mfR2MzN#W7FG_&RmV^mVo%3GGgn~oT3zCK!$R$0|rPhM3E}`MqR=Oa2e613MXb{XA!vnnRE7Mg$n|yOsTu&thhu38 z`E#tmFi=wYouaO^R8}(P9O%ygc3RtEa~d;X`a4Y^X&f}!14xljRSTob@@}eZ+!U!O z6>#|3h{M>+2|R0YtfMnvbyOy5f#{`xENC*;xreB;-%aHBHYkJdsZzI zP$dEIrCvP0?|Z87K*50ct+(lJH@(JwOHzZDoz$LLx_!a>+ z4AxUS)Q;AA6}SQ3sjK5Wtm$jK${dDmUxE&wLw<^AN4CK~a~w6RBga+vf*)t#0OoBp zw6seZ8;VSmZ-8NA{0H>FcUqm^?M#X!kDdjuiHufeKQMtRRvF-h(-%+q5)}(MV)rC* z(o{db{Y_~^@G1iE|G(XTb#+A%?SQr*P*_wH3$nDdtIeBA4aFUSDPe>45;TBd@}#0! zTGR(r2In-gFGOHjzexjiZ+of9r3x8|n;v~EVDr>~@|ziqqOb^9zZ@4! zmi0!*%k{2@?Y8}ujYsc#@8N+d`;hcMkQ~g&#J|U3saIhsMbW-bVwJ-pG0BCZ3MB+b z-T3&cTiDKR?kw(7w^y%*^E@8ly}~%|_PER9`lvC-At~*_V`jZ3#iYl3x=MNs^)p=W zx071pM?OR(!h4?09Km+NR ze)O0OOMS9OVxo2tr=`hkO2)>w>3M@5Ysh^FJ}+fMhcSk{j~!%g4H z_QewkbFoxtFnVNPP=8OKo?HV29i#GTc+5_*_xVl#zu$pJqo{?F=?6@%^~*cEt3Oly zmGQw`ImRW)Fv=TF?HjToPUi?$#9x2qk|kAWltrk~7-YQ;X=3}@ZkFUr=BX-n>* zc}GKpAeWm(F+E3*W1k@7Ucca~s8L_rFDx%bS2jnhT2JLS^jSqn64l=F$Uy47QF5|SBn%%E4$KuN$n*iN+ zXlhT)wgCvrde7`a3c@3zyT33dj4@NVTl_jZ&U1V3ye={rZE*e;ffPHQG~ALFs@TQ} zD+dg5&3<wCM2 z-#6>PI8pqA1`pwU(_OIxg!I7w<4s0H*60y1iFi{s?8tJJpP3n{Ji9!ODp7AaC;lEWX*dkxLX@M zc@OA=F|`q(JjBMs12#6qN8DK^IK#H~W4WHH+BW(322_LltFMN58HP%OvRS=5vm@cM zOm-^t%{_MxoJ2Knf5O4BrHl>LX|Zu}eik?N0#nL9?nrxsDs*6$8%dD%7Wju2mnba% z1z!nZdk=?vsaX}gjmLQ8+v63wg`|0UxgBEsFGJ_QK_!QT3m4&BIma|vBB34qy6nLZ ztz&I@R-pgTHnAX z|G?n+TAs&jb~YkGs?bJFm9vN5WtanxdFTt@^gZxNYXEsVX9-&%3T%35m zxoyvisge(9SV2qJeR$1qK`!|6c)8g6l@&r)&L#e{P#-teGC-QyMqtOWCW~5WJP&0-h*CGCE=0*JEBFv5Z#Z{kOk!>PE z&Pohw6O2VADd`w~l#UZw<*G~SEzHl>vVSlR&P=J^uH)YT?&V;j+YgWVRN&SdP1(3I zHa*F=w}+OkG3MxI=^*Q@SEz%|WqxbiZ&YSjKX`o(PKkivL%5{{qpr@fP%A&{R;>PA zBaEU;g|o4F`2U!tXaU`1bvl-n$*O#Q^7EE#m@=R+ z2r;)gJ?gq^KylsJStEagl-Cs(J;$hNe7H*#TQsvVzH*vTQnuZxr>DkrDFILA%%VuB zDk{o7VNmM>09FazwTQI(CTN$uge2PJx2*!~?33e6oDh19oN=AB+Oa@C7E*`LZTS)^ zi-*@B_9(CF-=2YKZ*Q-qy!I7uP+4x_b`HyNrU((Fj;pI^2W;ezg?9OSxk}PWileEx z1T}DUPYHL1uH19n<;+g`21PUMJ2ct6w%^F-)nOC=4G93P6ijP@;sY^!aO;TQphJiB ze8g7t3vV3Nj%HrD{JnfG_x^7^b7s-QC0-K?#t}wrFF5IiaA{Hf0<tCRXzc3Z3V3k!IKALF(s~ljH1p`iQkijuN z?5I=m%F-0$kGDeU355qHfI=4~yPlsOps0A^#i?z<7;7u|W(F5#7e@z$4eJ#pEiGPb zjlDc2g4@y(e){Zq@jG7V3lL-2Lz{Sy88d{d%-(3!j||i*5rI-EHj`uNCF72}~p zKf82U-R1;?Ucu6==XTLm7RLc>Xu!FPl%|4i{ViP9l8Qi@C#L5!*R}TcLk1stdYxr@ zzh#)&l*+eNpg(*EUJd+Hdm2*@M)v51_i`m&izwE{a5-C_+c?r_?NlS-(%u3t8x&dN zIl-$)Lr=X6kLbNWz7~dpgi;;-pc+@_aY;{4$04#7b?Eg|)KyaIlD0$ckUE62`3@Ow z9*rKHln${e488nycs&y0C@SPjlS3k!z{3v~A$I5@!Q)BtL@qzuC5qQ~7zBgGXvg>A zXW<{;52TP-_pg3N&oQ>Fv5Mm_T+ZtM+HqsWg}|M58jUpb``h`^>6)*PQ4OQRtBL3J z&x=FNr^BwWCZ=uvEEA2xmBmslNPUQ-vOs5 zGc(hA%a^tQ>KZMmUn9i8M(?CBSch!#u3An8=S{=~)-dh4R!4movO!h!M_me@_qiAp zQ;1)d8Q^lZ68rM<@(`mV*0)Q{oUZlywnTj191|Z`ugKMu8}T=M>A*ZRv*v*e`NL`y zFIqynhEQ|W%$ZH9<|?J{zeD@7v&yW(2Z+fJCQy|S-oKrw*-K`T4K%mV=I`P3ZuK;5 zx1;(Q(g=7MKzRzM-NzU$L7^q+t%y-UR}ObU`Q+Kvw&Wjr9wv2u+qNA0tV9P}wZM33 z*MO^~y8P*lfK!Oj&GkJ{gUJ5HXepLCM_7gjr=VZG}o6=;~9C75#2=;{>w- z{7}7~TX9$jM&y8rIJuZwYvIK>cd7y?s5m(4fW^er*%5LlNS8MTNxDN56N5?2Sm&uM z)g)pW-!>hEy-LSKMZJ1I=)E;t`6Ww*^)H_nbi#`%ibdmDW7AT{j-D%oyi~*XvBjAg z^2>iFwbs?o9tG1=q@TkI*oCnO;UV&$_qvKF-n+7e3>hMtM#-wNe5FuijcpMO9Yes& zZ|>?eP*;cZsZzrO(h*=J|L;=YabSOO^tOh(hY343uh#)c2ca#OX0gpCJkruF#%!XP!$tCD#qz{G40rMtstlJ5cVTQ}(%iI)@=$YSas*TdW z5q5#4E% zov4r!Mb9fNzJi*yU80>xl?30Mr`YBX=o1v!$e*mOQEBRAR7k+=13E0^Ux`kL7^BD- zCjsk~rT1N8$B9~ph48&1)Zby5jMD83?~_rYrjdi*Vq zc-%^ypa3~!16h|;wdPXLkba5&Fd!TWkBtN5vaQ$T5sKn5pOw75R8)iF`jOV8)V^jd z!uzU@6{+cD2R2ob3VY%M1g-J6OZrhuIBbRMi^>X_?A{m?rS*)K!TF*8@-8kq!`?7$ zHY~*YSCewXMi;`7`hy-re(lNrK~m+00d6v80-nT+X1E3{^^xdyTI%Y60#sZ*1=Ym^*Cz~!_R$343i2%Y8>tXq z*lO5=xVtT#^18`WFt!>@`3uvoD!QQPcbcKr(fMN474IdQPa49sv2WM@!UOk2Z^Y)? zz@rPN=y4Gyy0N@go?Ds=os>qbBKZ~l_f;s{2dd4cy~bD%;^s8%BWUSidl)KWctor~HB z9CN^OS^^HhaCAu8!cC;vNzyd23Dj}wR0|&(sf>AU-Mwlj&Mitj+3m;_t(D0{SJ9IW zHV>~qSu(icCSSY?N(eJqmC`o*)^kVk;O+&25NiddwUkByRmk<er)) z6a`S-6CQ<`ufP|R^Ml`vOE#ScT;PSmg{Rb;B~bPOeP(qvcLq8-BRp&%_$+}3kyK5pdzCiL*astza)uqh0!0T%Fv}tU5X}hbh3Pgl8^Z?Bij`_f0)r z?b)3ssnapCi6(3Mj(9wy;T1wr!P{@Yc)>PSF!&7{iuK<&ZaQ`fptxul)xPe0dKA*q z{o*G)0qt=dd3zK--SXyiCA>=L2U6m^;2(wl;^i~)#|xD=xwItjKCRMtRwTMe(AuA= zaQT18x@|>$hEr(*3s63-SH06arfxT%VgLB4u5jkndpv zZTr1zy?)-_zEo_Un<8g_#_P2-OeD_3(3(yU5ipV>TaldF&(Lq{h^>^hjovRE=$>_) zlJxoVjL)+FCG@_H73m&N=lxXinfsSjWcD(54KlR&> zA0iA-McUBb@>B$QToYRVI>!)xFc`y6b@RDDnm8Z+x*AEGzF<6dFju_N1cUB%V$T(i z>U2QWVLwRt>pBycjd-As#Iw*IZS{K1+k$CaMN)?v;$NTHG8!-KCTT&BX|3*_q@RFYthEA`p_=OA}^n1^SA#Ts}zHt118 zzs}!iOx($NZh)SlvZ+I6i|3!PQvrh;e$}G0Gd@>n%rf|K?gE#YeaQB1vBvmzht-Gw zw9kPiCAy;ncQ=f1I`&mK9QVa#G*Vq;f&2sQ$F8cS3-!0Puc-E%3W;8K8)AS+_M~=6 z%T3T8Se976A_>>F$v35~LfXyF0hEba!{dx1RSq?-}R(VGP*(*lgCl=A75OVs{;Mc}HK)K*036 zThi+67+1HJftb075;YSElqF$jl)`DZ zrkQDkJt;!U)|aAk+?Yx8qJb3Orss-1vN7F;OEKLrBSPj56Jw>fHs1{QN#y(k+Cziv$Iu_q;Si4F-(N?uIe`Q{m!mT36D(s7?5c|<;BY- zs4bDo)eR*?`O05wzBne=Owc4XdE9;nn9zT#4X~XI{~WIPWh`!Zc-Igj2BrK8u6FSL zanZ39-!^O=%ev+yTC=;(@JFU=P)4v9YO`X*m$^GQI=#;dHSi=41n4sGt)6i%f}7pk zrP3S%#NL_OVryf`U$&n<#1=w~+=_sWVr6q`-=fFge{ywFx!=6edCuHg?=vfNiZ6QZ zUS3c7rv#oq@Vh6&!)e;zMe_$FH!t6n4!9UWMmqX$`Mu!Pwq)0)8%}!0AxD14ZL0&e znXgps?h*(BAk)rum4%rs3icshfG+WWxd7hh_N}`f{7X+hS$)|Q9_NR)uQ(@KHZbUY z$XPx#?G6qc{I9*mkU_aqfD>*O0YJG+QwGrok+nYP*% zE=I4J>(e>6785sV-k&Yq;y;aGv3z?ig=~7DnQk^I@I`b8@ILyj_nvus?!Vk_x-fKv zt-hQ=Gq$|Vg=eaVxp}Q|S+Tb#ynXZ`QC)%_m`I0(Ve|_O`jciNR=@G#3v;*?AQi}z zbl8Uz4ai6T(hvW|Z7;QSjP24#Rc|s>ZB3y`gh*yg`L&21o5+sP&e#0*aWkcDzHRvp zC1s2!mSvejX%Ln`OH3i>K3>ka4{}Sm^0rV=%lp;khNguGN#YNcmsj=;`xmrT>EfbIF}fKO-l z;CJ`sjpn!Z-kxacp4V;}GTvRt3@e-Srv*w+i--3sBiHX_eLX&{V~=@-&@C&T8Cl?Rh-c^nYBtB6cuUC#&WsO-`{4HjoM<+(7?5pcL0^hsc zuWem7<|XbXc!*lv=H#BPeo>?CbN$IOvwfxZS;p;|)PD}xC3!{BA4gQhn0PmRaY58@ zHgGJpWVhOK`~`-fW*xG6fnM7^ zD?p3We*eYQ1;z7(No632Qqzq`l|Ud6A&KL-agjeJVjGZiXga9tjj4Jd>J6568&uWHAc6yK@DU(`PLV zS<3fyL75wsfBu{W#{A$+KhCS2F%Lk9Dv&2X1#&=;5*P{?{xvo62bR%nc6oUhVJBQK z3k!QM!{MbW&^ah#ZG9;jdvkX5ye$1Nsi~>|tn0DF??#LyzhsK)qsKhf*ZYWyi%){A z3}yA(t7}@zubRIW=2j(K)bZXls)n0pQ=_6G8+GzY>Q|lv9H&_;s21D#J)j&-b8-Hi zU8n3eG*vk_9UuH9q^^MGcmbizYd|ym`HLvay`X-1eT^T9wTczkt2rnCz#doOn++LkMivm?3$yg zm6g;2lT8mB%%SG3h_)-DIN&n;} zAjv4Gs+x%The_OY;RI+s#ly)`noYj~JJ`F@(XG8t>nmV*xA_=n=MZRiUQ6; zfZ;=4;!FiOdjMP&M&2AP=hns+{YPccY+IlxwX6T4YH8}0fx@*<5zS-IDPdV>-bImFyJTy*;*toeR0Tv2OEI=Mxm0@4_x6Ald z1@{4DWaQ#6Tli@Hlul^w?G?y%&9euhMQ7WO3|Xgk+zI?||1K`eRSt=^wEdKdAMNe! zrKPOdW0x;fA^TH4q1MMNiRw)kty|Mq<~b)NEp0fK#?c%v1?+Opi)maF7rffMQYc0P zLxQIMO&6teGVzT`OdS9CtcoSDa1Pb~vI$K{u_V{}(i#7C`~}5?Wohiw49llz`629h zh*)wKM904DQkVEahPBwGYV|4n<9k$8b>sv=7EIy1>#^x>F9cp-? z_15f*W^>CQm(jfL zniCW7d7Ei{wCln&RT|6Ce+p7R`J8nsH<8YSK<#z|$9S)U{RisuX0GWdph@TQnt|{6 z-WrQQza4 zUKe}iQ`q4KFJ3Keb%Ku%ckSn)<-tQA55FCmEQ7Ji%05$=ot?>c`wy$Hr|`8acPJYY z3#eIiu<;)qS&?@&eTAtLS#}HR;B=gq`>eILxRqUl ze6eipajSjwZ=!QeQ$)>4s7hAAj1_q*VC@L5ccy%o;S{&3#ugD-;s=_zV*f`3fO2ir z>|zY_jvp1GpP2qZ zgUU7t4`Qe|--%U%e{CTdejsxiMEPqRblL8^>sAeWBxd*OVCO}2C6Z@_4!f&!{OnSJ zlf)Dl>9IC^Z{$eym>HtJuofm~Hxg4}G4vxv0PW?8ld*+3i4W;U?9UC|AfbCgfqEAK z1Px~i+Q$of=Nb3Kxm1F~^TwK16S49c&D#|XHu~;+h6b$POPm$O>Uiv3e-zHvZ-apx zMP5z*x}F)i?+k4uF&~|s`0$Zbj;~SGZzpup1!N-lJZ>U@0ZHq#BlmTFM?L3fY8Ii) zqQA(*RQ=E9H1GQfu-eL_@qjtYz^9$l#CwSF-&WWibRy(bj*l0g;9hrRi0=n6lE%iy zv~yH*sxnB(8#;n3$x^2FuXWpp^QM4*Q*`vcHVNj1Q3L?%6$>03R5&fmCsVJCra!A$ z4$?tRGLTAuEtN&Gnnx)l@JjOcEkA4ZEQR5d>!aHq*BO&%d`P-9a~urH$0N z2z0?G{vtL>pvx>hX$^R)Zb{WX6Fa#(Tuk^9j9US(usz8#{@d}`vi?T+k*0K>^V#F+ z>Zg!rwL3%GcN!~oTe73eLZcQXg3Nza?YY8{h5+Wd~N$+|h17Fz_ykcIgM)m#(2c@@s^1M%2sHmLA# zPQDLIJFk!HcW=Pj-e*riOzfr6OsH_Knp*x{?|Y|I#kjGyJM|y;FKY`~xN(iUv`eX# z4RjCUruVt1J5Q{-ru6%*FP^a%n%@YaOVLTCXr@1~E9)k6|_cDHiNB-r}?7);3eTMC${KSJHKd03!k4lT`#f7&4(!)dWNScGiO zWei2&v!}2cy)|1oW90C1PK%1T+E8HO*6Ol>vqD&MMeA*aR{-w+uf7Uw>zVln5;@56!PLM4ZwTK9LhT8cBZO{7Agl_ts zpi8v(gHclyk#?6CHDheMckr0+rE>NUhO1kVdFB*%)I5T+ll{uTU-EZb@*frarQ!|Z zP+pv1KcM1kdqu$e3qBid8`CC6!wo2hV3jvt;qjW~p*s^`>5|baYG~{^w&k4Uo+l<` zqwLTOn#^O0Z1JTbhHUB%d*nzyhIv=gbi3mHrTECk&MqO=I|!VoA7vLT?*e8k1O+2_ zQjI6IE0{$VUAC?k&T&5MsJ0;Gh@uOQ%da{~r{bsnsBOT)Bam=b@Ig_Rm6@ti0rIHzW&^a5dDcVf06nud6N4 zrhom7UQUhEpqhxAcXVHbgvr_ zn*vw05~^oFkZ$&SZr0JIXHyqMy`x!>u}UYyirq+q8(N;2UynBfm!EVbvto14B`U^# zkW+wXrXu^H*Y1ZQ(bOCKLbLpJmNr@mTbv{vc%K7HzMykE6Qn&kz1it$MI|MnuU`|w zt&_57+}o!vw*GJvr=yp`uCQy5hHGh-qT+5UWlBQXuF5GW+*UQVIc5${x-w& zZC$UM5&T&kRo}Mm8KWgI%BH?IVBz5ByYu^Mv9ipm>l6y6=cfNvL|*@P{th(|(;|$5 zVZ_R%#^qIy>a1iCu<14N(Yj~FYW?;$p>21tf`r~KfBzWiZ|6k7gnYAu@#$VGlVN#) z2F(ZYlIGT4>_xWXQ61+^N@&ZO5a;n~|7C-G!BcFdVu}YV+VLK=f2#NWc82}dn-vE8 z>Tlcbn9N$kHtHENj|YiI=Gr43R_m<{ES;7PQ+FE;jTf19|GvAYaD{U!Uajiec`w-! zzbD($yT{o{UD?H3^+*a=`B(j;HB4%`+=aoXbv^y5#)4nK?SP5@>5PfE$^J7L5*dN$ zAH;{phaZyiXgo)=C}mushRxaJMIoMCS7q#??US$B>)9Va3U&y)hoECxcJqDQlR70n zSo+YtAQOmoeIW#CoJh)_o*|Nbh=lz4K1I!mVxwK3r1&)4FoZZ+dFX13g_8X((}Sbv zD^p+$I@U>-P-o=xan|K8_@7~V4-7Bo8*F+HkH?G==K?PQBEntAH(M4+VJK> zK2(WjJA#gh^v*R@T_r|hdvSN5_wKo6&BL}6&j*d9BBX)DcgVZ>Us0uq|BChs6A|In z-2KuTXIEl$R}|68@szIOmCRp#na})+X$mb*4ml!EjqeruHZ;(KL92n4>6)+}?MW25 zFcYeSJ8Y8M8gx7;`B6uI_9lB`3Et;fK00uULSleCW<@eoh2nbN9AOa)E|>Ff`Wa@7 zIzoi=6L7%-CG?AB^!XG%2wrT4sJQW34LsW!$tcXwhKl;^78K+?xUw_2P0wHwl*)e}tc8{6jsOgUX#HLT(|GnHY7$uRv=-mxL4c@TO5v8a zjDUbZRa$S}QKJP`kJ@*5csTgrgsL8wS*M6zLXaR2+W^FCm%P?l>ZXb&CBGsgR7 zP;Xi+Cvr4D(6?AF?U$3r3lQwrl-AcLje`$w<1*`&7uct%5zR43@T+HWs?37_D2^~>bTf)>Ig72tE}X3`IZkLQ@#UZ5*YNJC zX6^f}&Et2bc*^MPSN(_zCS8#o8v^OhXG|LT&ioo(m6Jm#va$THZG3$eN>O~=QB6a=<5-QS?-5B@M6 zL&*NN>z(pB(qgK05g)(GlhdNTsvoLu8|Q~yQ-bZPC$!o2udXY0vlvt2zQ9zvq&se| zNL7wB!Khr?9%God0}(}N(_s9O@<y;*_KQ*@r^wateA(WT%{m@p;FnR= z7jnJjRG-RMGW|kmNq`E%A^)3Jj7wy#5#v;D2$RC{0Z6uN^_HV5-|UnWemj1BTDAi~ z^nI6_F$ORf7d}kJug5p2s|Ie%%gabrV9L?yNcuOa6&(7=!jJ_no8q#vulXFxdLx-5 z3!lvs({(GDaqyWdsbrGg^XER#dp9=o*%0F3i#a8R7$?&38vEmU z2B`agHpp5c5sTqFy9!bpz*xvw(MNO8k0EEa026f2lUyXj;-t6j_yvM@0<0zB|JEI@zD)1YU(&v zVH-awUGhOwDcQ) z@N0%luoRYGS@`d^j8^U;+6h0X?Z={R$#Rbrmad*@+)m@2$~;fx+nra%G21<9xMW%P z=Y|S@CG<}zsleO!%emOgU0Hg+%y``2mN=Dp?XtFejPx9hJaY;>8NO=_NV&OgX_~E1 z(${$;BKG#;IGn9q?}?oGflO6P7i4vEhqT}FI;?K{Lc!A3k>q5xy4#^302#P`v*{fz zk0Vy&1IudS&iM^~Ww#0M=fCz+|8U($9>YD0-^pS~yL#Nnw+kWn^H`^UoTqR(D_C;% zl(JCu#baiIZR`X{I@%(8mW}=fCtcp{*xY}5d1O9uKk(wj_32LcX%Bc*hjV;!u{9R| z7>Mir>(uMJ?{>!>Zim-59D;h>nr~yMA1JBWf1J!UI(=th@V?YN@mcqp#lx$433$DD z^1!*nn9H2qJA!J!hlLP(Veq=rJRL!En+?7hHiib+$Dg6M_ZELn=v&s{V}2`35#xowNvl0D(&1Ses+S| zT0!Cx?NO)*+Eo*t(6$?i{A2cZsco8F-=U{1=9!MMjaW|uIt#liO?UEIyeHZ=}vJfE3AiKX0_<0>$g^%--R%>#)+BkZh#T=pPKb6?B%&IHMhjY8_j5h zn?h;=8HdTxKzg^RGWk_%$g@mt<{3~v1o z+HAI09cnyTsi|R9!-u-1*Qao+YdTOw$H!aS?hihv=<9Ux128C&C?Ha#=qc3%!H|ag zlWf%(l({o^Xn0tDMMcs|doE#>2V!mkg&g<7f?XX~&B^BW*94F0?w^p341a%~VNA#L zF>xDRCa-Y{`j&T9B$jeln#@!zKPyX1RXjE8uHou-{~XQ18FX+ZfdAPN6xVaBh9 zE-Y27-cH&odJk?mP1Q20BX9%b{6rQ~6BBjyJiY>+wRMBNY9=Q6!)&m;YJ>}6i1x?T z(KVzo+njM>UQD&aR%c5LOcPl#F~60AhDEb=+7NJCDZQBlE(O2RK2$RoVp)9t7!4siBa^HPX3)H!d= z2%16Jw{GX59?!d31)iE6&6CClFyTBfy_{V*N4mvik@S!9kw{q1D^CSN#5Jcs>b zTg)HFtM|LV%ut!6P)!%qZMTlJHk1(ckCByBm%1z{Xj%OI2w_c9oInJH7i*8BW+N~lLia+CtUQ9~3z1(oCtv>5! zR-_qpBuIpwQ`30W|Akw+ga|mKJ`#C5jKO6zY#Dy{Z1*ecCftxCX5-pzfm|%zUKY6> zptgI?sOr3yzy9U+VnwbVU311txRfJqes$uDF#0|SXn-)5RQm3ouly^j~zV7MdP~HCeHuLwx zsE5W)KT9ee*`&@m1%uv3)RJ`O{keMM#zkqQj||e+ zMN3{mQmy%RFRj6S#lhf?=-G&g`(>@-aP3KE?ZuFL7eMx%nY4F2$_KjnfGo~EVORaoX9vmr7pTD) zi<<>WX4Di`&_9it%le?*fE%C6li2u=Te{x%jlp?N-_=z~B+;?+m+lVD{#Lh4UxTi1 z>$27T=%)35r4-%}IZpx^bSyijLLuF*CcwTj& zl;h&|e>Cmw9T`A&(D3(^Z)g78F=Db8PMw(d1WJ*m0?nf!uw?@h@sd}QZfSXBVnZqF zw7NWV6_xn#z><<1+71ZctqzG;&Y()L4vAkx#5=W0y)h7cV{UDJrR}Y#7-Kj<7Ruo( z_7nGB1Lx}Yx+dTCX9-viZfzOow>xCA;WBA$UCx_N4%<*2SkcLC}NN-8QPC8cav#YYiqVa6KMv2JW*ayq)Ow1W>pTQljB z=9ZS--n|tX;-N2%<`d*IZ8#Q@4|3w-Z;y|UrO_eVBgu~m`RXD6ccYqbxbo-Qo1hwG zR_)P}mm(&8gNYomynMOrp8fke3`{~{2?>TVrV!u}fNjh0mej|TfA&2ZbY^U9b{WFI z2HPyQ^IW26ch^0?kRJkBwErcgCF?j0xvEq6PGP5W+3o-%C>{6x{14hOP%zw_uyAny zxe`rIP4WELLkCVGxvPI$xP76-qheyv>%T8cySslj%WAW`!-7FDNch+4h6Q9gaLBym zdA>Prf$v%3?p?8`Y0{0y$Hr7OjlQa@lf-lMYh>TNf3AEk?g#b7iJHhV50!+E(P53|ObMoY*% z#zqaDF=A!;m{BOAfcT>F(){|0B)Puy{k$D9Tzno5X?-_vIO1ddW#pcgc!}l;PtxspoH0Me2)$!%~zzYEns4p7Pje2T;SK<$N27HEl|EDUPjO zN)Wh}^vk8SG;#;^W`(|=&avFj@1NdR$dx|(a32x~R!t5L4FUTIeI@kA8U~na`t%9e zTFY!aG|`p0ih`Keq=baOtE&ondYRF-HJORQRFlH0PB==jO5tKCd!;j7Q+TjL?`SC* ziXL+$OXqAmYuJRYh|ZTK9$Vv&zXw+9XGQ=%!q@&otUfk&N)dhv-R z2L#`?#~b>rTf*yLrDPkkT1xgi`m9JsAsB?Un(%YAuDA75R>-8j;OG#clcqhBva>rb zA(oyiQ%1k_*U99tN*exP1Z>$ig+G$8h+j}>K`;$IeY{{M9(yLX4SE)>kHtT&PaTYT zOzGH7SNhDP$%K6+zH2oQCRti1h@KZl%KG6$oAI`U7)dO+kSdrfn_XXcS%zrgVG?FW zRXK=rj2+Tw{$%v5lUmaXu4X^?&y* z4;!2IG3P0292LicNwU5b|KQQ0X8vnEKFo!KdujsC_Q*BP4K&bXi@72j%Aj`RVPIri zQmi+ZN4GnxjD~nFIq6ZzQ*hI+7SB`CbmE zrsn_Lw7^2E@w4tHF0RLaqJx{plzCMG@7?&#Oih*b^eQwg25kzHJ7V#w|K09JuP!h1 zZ9E`>-z~kE>}R-J3qUI>Dk24U%}*4AGUW*>sxfiI?N=7^RRE_4$MQVYR^t>_oPy`Z}x0xQkoVQCT)ld4Kp_L2LR z=0`+CG#X0YjONdf-SQ~4jAMCK-M&lVPQ&`W9kcorr^DaJyU?)cf>8g@7bxf)O~0Fg z2#pdRC4|y*>ejlym%4iO)~V6%ZaFg^j7ndyWg&YXBB|+t1C3XL7Kr`{_L5_XHab5c zw0c+AifphUqE}G~KaZyk@z73>Chp~qoeB$Bf4WK_B!SH9Xxirp-Fc zCi*vuxPDOZ@U1fHxw)-@xdPjcH9bP^4oExMSHPZCjL_M|h23si-7Gm%@wfjmR))T6Y8JYHk9O=a7vVqa3i9XWp>#6@tAy+HEKh}RGQnn9YvLdo;C}$7Q^;U6%P7) zCnstc_Mm6x=bsd&dS?ma1{(j8!`Ltm8?WnxId|{IjpjN_^;F*E%h|UoKf@!GpZvsl z0RM+yNGimm;6P6F14ftl%l^e~&NCjPMkk1c|8Y5|qCN7cxJQ9h8e{%mu;koIbZ~^E9h>t+MCI#1zrVZ(%h*e_mLKyapv9c#&pdZh8 zw}B*rY`EeAB^ens5ay&I05^_=6WZ(I+)Vw}CCD2DQeWR3ofG>L(Q{SVt%xkk-z=pw0hrR*EiBFVsk`h%#p54Vlsi*wwX^1>T5$6LXEC=+9haWJ30)Ni(BP@CPZW zT=4+Y7Awz4%g8CE#z9i|y+K7=|I*U=CG0&0Mwj5JlDjT5>Q~i?*(F&87rc-U1S!U> z4E6X6R0jckze<`5 zLVgOm*Q6(KuDk{|oavaOj2u)m5^m+!_DP2{lSnYK+7*iK;a6<)MRh&s7Lf~*f*NTE zp`XohR;v5Lbo6WbWI-8m&?{}5i9vV^VRxd$4Fn8<`a zceijezdy-r(hTtDQ?p`~-Y++EWtwjUb#yWuWYJf<-|*A3N$0EK-YTnI4*Ok$TA}BG z2>zE>?6GPwtsDG5huHm^n?Gl@limcqHu(0eE6$q&vk}@-lq)rq-ahwA^-R*Zu*;hp z`3D~9mYQF`LlJ<6p63)f89H+YPRoigq$k@`KlYFSY|MDIdwH}NvY=q@%8XjWhB}?y zZT{z`D10N&J;CU0Ec=N~TJ2yc#T>Qf*yvZnrbl2SKvC^H?~CS%GS;Q`}s!Su$gZaLFVJy0pAPHM!CTSv~3`V}!V3&_~wReo|IZ#!=R2 z$s=h^f?_L%{kyUfg&W^ZLzh=l2B;)bR>@a|1$p$t`aCvHs&#Q$q{rZK7BMoS_^;Z) z4wopFhpS{_|8}=^@L$#nF?#S`a+8urVbYx>|{rIMy%X&`|Wu7u7sS?XraEh&&D zOW!8_0n=TBZ=fEOjD2!&qhUOl2^otFN%We}o!?h}g#1@z{?5oRU~}A)CqR5RCR%M@ z`B(I>`8h;-U4=biehM_CWLWDjzFnWE|4kJPP4Y8rtJj#SeD+dP@D2_c&_IIgG2|q8 zMT=$03-eqT^<%nwGxpoBcjA}qqB{2>q1g0xzYCC*<5k2L>Q zPDFAD7>jhbYpiq0u>Jui50^%cU}>A`bw{RGByatb+=E3Tq(_tfUfcfce1N3JpHj?>sLYHe@)Vle>KKvXoagoW^!ujI=uCapnVYy828u~iq5D^(M_r(rSH;;gMJ}uIINg6#Hd*Ok1u~tLZ<{UlNTsP;N z)=bFn`Z09kv8i3%B2VgFfxk1O>u*%)g+H4sQv#tH7Bxxq4AA`_92{sgc!LLosJFkb z8dRD-2~G+Mk@K4wVd{@?_gF@e-=rU~NgPy4L#MSTPr)>iG=vOnI?B{a(YiRe_pW2QF~G7pE7+~MKs$7!B#W|~$-<#VX|HS>{3ZP%)(_7H5l zz+nW4(8;f03A;BAZ z_&Oy0D;C!Ok!kCjDwh7)eCFbp~u~idv1H?<0P0);DUrUDCU7 zfUNKt%MOw9@T3CNV5W(H)0)yq`fXo&INi$E2;3TE)0$js_$X6&x$DT@evjloF3!%A zbBhw@8noAOc(tTC%5f@Ri6_7!-nTiJ0ye}$l2m9`G$;lAQ!e4BkK9WUU}QpwkDIkr zEe#2>5eEz$kS|BY%bNjriTC&4v}7KYvZ}MCbcwJa6%9=(b_kgeS<0ARDbyMIq?RhV zD*~IQ+aibsoHtaPL=xBpkGYDX;_s!(qcZEn3-x~BwVL<@2AwK#Z7?7sVGvgedGx|I%GxDcFqbUh@# z4ABv9$f0I50)uu{trE#vwci$1loaIFh*TMA)|f`F{!V})KMm}K z-PS}W-XRk3Z6dTSrtmRTr5+511^2&7Oc99Fm>687j{ zRRADRt}B2az3J`i!@$EEDATL~PzpO79Nd4e0&^S^{bwkc_bAq!1mLh>V`KjTaQ1nH zJX97&1pWlCnlWTw@SXfueM>$BfBfG70t}2BVcU9fU^L#9d>ksaLzBlACAha*#NxT% zjOOKBAYp=`ybSA+wAQLE*=};&z3_Rx^(lc|4YITi!IjPogFtZA`#GYb%^mIUJHK33 zl=w$}WsYRFc@%w748d?ta6{+_Y!s!xRquMC2OSXYE;yQs7=flTu-hhCm;@veUJ88o z=N7f|U*7MXTn&A(k><3?CWaBGt~i3fWf%}6?Tla-kZ@G*aHx>fS5_8Yw~iK8RYL*- zgP^}WAcf$~^P9ZF!uZV0ae(*yQ>yRzi@IqJQOcpn4GRlX3Y}RWq!*$O<2BjP(jx~W zZ+V7_s_u3?Cm>dxH^Eh2%*~%rzK(isgJ_Z#V09%;DyoRpxIm)(->?~~d z%P-=pQmT|^xhr#;gDrbEkadYl%sU9CFJK-}*xITiW%j9}&h7m%flzvXsA%$(d6o)1 z8WANUZv;a{qd%t^K_p5hKfMBZ=p(fPrEdcZk_Td}_#r+suu74bL4)1;oxnC<_KOg+ zeU#`I5%=P+VX!fw#{HARRPwt0`?q_%6zjyq^c+b+Q#Q1Fvnur0?T6tc4sr!IHad!) z$5!lXI4_2nu+Yxv11Nb)(bw?MP{s02L{eWPArKBeS=g%&GDG?d&t0^jpx^xj0TIQv zHXn8uV9zvthpahCR9vU9iUSia1!lr_V~b#-;RoDFq7n^e85BG!uLkp~y2DOfun^t7 ze7NB%&9f$Ir}n1{3a9F1VehOI_^PF7(XYoRcJldN$Fr9Da(#T>oy83$>$%gZ)D&FY z2@tDqQ$+;~u-E0!l#<6Gn(*DBk1K1rw5NCF360yh#Gfd3e6W#9{in^FXL1w)nOZnF zUx*C*vw`3r_25vOlE5#c#1C)O9T@ieH|fpMd=G$m!FXvsUk%r?Tv0@B0;UkKT<<>e zpNGm&b;VtjX)p@=`no15Et><1GZ=k4jfU2b>?UWH^I>7IMZcPx(^}1zozuxM>!T|P z2?>4r^a&lT@%N*YgFa4`T7fOpiBN+uKjL;xroTf^FiOd5O-(gU&_~yyM&PZLwdN0e zXoKB`1BqSzku6nk9q!q}yw1h&HV>4w_4g9d?8Z3e?r1y2w8Tu(VmiT_O{muS#jJH) z9!ziCw%aywM<6d}9T;0Mg*gx#8wW=M;Cp67ydn6p|HSW6Q{F;pR2w4>No69& zw7>8#^S^2L!Y}}H487I+vzT(wdsHiEwY`{6+g|lY3L1$}4ABi8EjB>T+(@G=Mv|qj z@~(!if&w=VPO?jD0st<1!Ib`E3JFHj_J~olIuLXdS)a`-Z7v_e%4$r&Of~H1PYNcc$no)U zBjt~W+m&tV)&3m({F$KmE4-mdUoO4JJfd%2`n9##$p9Y#&02%;#8T3nA?IIEn zM_g%TxG^1gcQqc9nR6$W1DF9sdS{xo6V0W0a6MnKtPbs&L>M!`uZdwpW?(-oyvC#YO%p~ zcS=D34#tbYw<>6<0pQ8TqzJ8QXdB2agg;Dkgi1r-*!rd|ENDr~$k2Rpb0z=w<5kqR z1Jqs+oG=e+SPJYN0pfoPg|E>Y?O`PG{_n5w?#viZifJXD_;4P>GR^WES1DNU@aDY9 zSqUfXat=QdW@C2lt=l>%CXlgS?xYf*$^v{8tkRKPXdv^v1@nG^S-ryp|Y04ZyBVjO;N($EW9f`nzz}T$j z@l^JK!V}-gaR4w&-{X{h!YHU z^%;!+;T{tJJD$dY+_}5VoLpSq@U96JAhjikCdW>LuU0f!b-UnO=#{Xa04-MYX-uQT zSCN#HyGA6Xqt-Q!)8u8Z)myG^3*6Ip+!;OJ*Z+OO1w%)-(wR%{1&|EDnAH5v(jWY1 z4E-MTnhdLRrsFBaTda=#vSM;f6?Bx05vCFZy1$72dL)z+@HvYbvPmJYH!zBzFKc~? zNiwZ_ElbKk1&55B5EUN0kH+PbPTYS{9t@0(U)4t89@Gp7M&wSk0s6>>4%;4>o&=Rq z6q8s(6R*J*Uf^B*amfqgRsnq!=)xOym_d?50s1Hq{S7$zgnXIXYt*wNr?`GN7uF70 zpKccy=o~O2e4kjX?qc5|k&{VMYVW{nlT&E=B{pRbQl$dteys7uI5oGeP^()in6MSu z^RZl!QXg#BKr&m<-Gs1}9~o&O9&Gh2xriFuh@C{!kP31DG+K6Bg2{vrbMM`Wrp{QBlmNTuNzezeEnT%0lkYG z#l;m}GyC0`-?BR@v&N(37Z!M5YT!``Ny*9mLF-6ISp+igtZy`&2lb{M48B0mUuvj% zBqb)sg5kV66TmGfObCH->Vl{u5W4(L#rr6h*`u- z4Be>wR@{2{HY3|lEg&=A5?~z6ZEYn4(kUGsLYX8+)=`&6m-39+EO*V|8;{J)54@j7 za}}ci3QjEmQo8o`_Bsu#V$u$pR;vy52>w?1{MMg&1qvY)V5folj(%k<#|QtKpd2S; zDH@=gB7k$phL`~8w$h6rBo=+yu=~xL`KglX2R{nANaB%*$>U)&aE^kV{Y7hoR^B(v zTbD?Yr=IZ-b7vnCy$l(eE2$<^uU zJo3R_H}LoaDmOKmii)x-y<=)^ylVEwLLk!{LD5F8m<;07vO?k60yra%nw2loc^pWF zG=&o?m{uJWq0LFj$y2~}e#n>{EGH6IC8@6?)IQ#;uv-aCdEE9>_rhepFotT``v6Ml ze1}g*xb-aZCqzq}_9GnTTY^|lW`22>#8_N5x=P(|z%@ryUOq}#ktL<0GX(uD0?PRf z4HFM@Zd=>0l}zG96LByKM_=H#BH8(Y2jjxb{j@kk%__Ra>Xy03Aou^X^75=-Pc}#G z#52loCW?BRe6gFR_p1|_1#OUKtvLor`e+L`m|ZZ6NLZT*m}qjhiAzl_E^WPViF(KP zf0+6Tpe(y+>zD5C?)d0V=?+1VP+GdXyFqD?ZcssKknZl1?v(Cs?(zO}XZ{%+W)OJ+ z&$G|oYpuPO%vVI7;?YY}tj~+ivESJV{}W@#SP8K-lwbqee#V~1pO%8qTkY5z8oiFs z7s=WN8x8@FnQNEee*7FAeWgJ2kT_$l`H)H(S!Dk9Z!dwN#vkNYGb}VM6h~9cF`RhrOKS$kZsMiAO|ds+u#Qu3VlkOk|1wsmRAuQJ|6Q$HCcWynI~eh1E1fZNYYV2*#l` zz`Pa7vM^a@(Ho86O!aheyAJbNp3y_5{jH*+`iYf`OAR0?EDu9`0Mupw3!p0`vbkP$|r#{FA(3Eh(g!gu&aXQq*+$q`tL!ACXuw345F#~$& zkwtb^R;jx6BTdskI5YBG>%adc%&*Ei+zaXeX`YUVIf_FnEB4T{YhRx^%+?%zIVS8N z{W45L=PBo7Z*Kl0|KPzBNkar~UYgoWRSx?7?}~P#81J+JK0F<O-47q+|K;ouuxa=ic;v-q+BYd6K_gmIf5012G|A4tHl7U; zU@J+#Jz5D7UU_Sv!?uq;PQba~^096#UM%ha#z!^kOJqtMjC3Z0M7zaWcJg=Mmz_)p z=stWzVA^&~zcgE6I4(!w*R$fWHY)aduL>D^bEypUHQ&B@xHZT}D&@_rDweb+t5`4$ zuNjP8)Tc6s{%)OAX<^N&T<7?cIOXWp1VSMCjO!RvNb|Jb41F;H8rTFa)q7j6pHoBI z`ar~BWkv4x>z%6gF^6;xmldPDxyZN`lv)I+H2ULKMAeI$^alWE_Ip!AFmfxcgKtLH zd#D?;w_;eho0wo0+I|UGWjWJV+T4=VxJf3`GuRX;FtpzaYCo3GK5&uzt?*O1D`{TF zr%p2g7l!jIKDz;`=ZO{A?FICT8Xp5a?Zb8|FRzjZHjNOI&H@2#$(dRTmBt@vV`qBM zG|kD8y<_40x2@LOqWAL6u>#=h63{v4)I}oiwB`I_JXj!#XKF;72t@;`CtHE4VyRR( zEB{}ufX$N$w9KI-WIg|0+wXbsvq(iJP)r1fPY)j0<1|5}hsJp7VM$>w( zTXLr0K)jVo`+w=HYHHqiZd?qrYv0H$;o;$_0gtXQ0)v5v>q9}{9lzcvC)v4QAr{$D z2K1ajsfx=b2+%{dNds&K4{tV~n-ePV&Z)|&scl4-kJy>~B^JhXTRDHT^7L|w5tB0S z-@N?0)E)mZCDKtySFcAoTk&zC>K79`7VV<^O*#2zvkCd>LZ90cvwtDsBe`O^066&8H`=DK6I246y`J$PRI65#eah(Ovj#PY|HLJwToEt+qUCw0+ z^b{Fj!{DoTqmVv`+=#wwHTmA+{(CDwwN$G~$W>QHp?n#IQRrx=AKRiAT4qxBgPk+@&&iH^iW?!$% z`HC!R@V9MjTF}_}e_BSptD<8gKdj;R9S3 zZOt+R3NrG<=0F0?ucvKM`)_Bd{VE-NG=Y$5LWl3hM#3U>;%msZ4Aww8lN1A)WRXy^ z%~qb-l8>w?sc6f%zubMiV~-pAAo8uCHL z$icKULQM#FtA$Q)IkIAXD$~Ipr3dCxoqeIL57EDxAeMX2P|OA+r;DvhWr?$lxn?NP>4>lxNX44*$bXBowBpU27Xj_6{|HmY z^t-Am0jT9b_xWo*n7TNVwCCMvBQI$XOD?mIz$49<+P{OM!;3SrG*p!_FLOT(Ys}Gr zkK=g2%O%JrCj6BbqcJY)#*yJTiM^X5kFwqhHgKdF?alC7(w-Psb(A$UaJ?G605ZsQ zgRS%G)G8j!HOPbz_SH_qv;?h;dVa%^(NC0?M|z)G2heUG^RLC`YUV+&1Rlk! z@9FgR_TskI4pk-4ebWBl#DhhdaSm@hg{_ODaGjQ!sr2CkAyAZnX@ny9Ub^^wKQ=>@ zC!Sd8HKNJ!Guk{uG^wne5ca?g60|IB_>qi|p5JdTc*o5u>lr4t#%*lyV12AKg1X!t zXJBB6C@7#N_gsha_VM}H+c;KUxtzGTm$(xN^D;Y22KysTw*^a9@}+ z!e(K81QI=Q)Cn2Y1Bk$%T_|GpjE^`9u{A%-#&09lgN)*+H9w(Oi5BT+o-hlMOa7jt--?n^E{c!MqT zw)D8(IJjp`5fa2}GYhd6b6bGX|N0-!=05@1fA$*M2`U}Lc4+hF(Nyp^EuFa({!#kb zva}tP*Cd9!qt`PH%Mdov2Q@Y)?$e#5oGr$N0EUXE4Yk!3ZeQ_X91Q-kA-9%CHMq77 z8yG@%)ZZHKu1>tIANrf=Y2*TCnxBp*=l*knm9HJghPR$QTWr=9ETth7{JHn~b&mWF zVfdDOyjw63qJoiySs*AXYVdc?hbuY0KX?%dKk{wVzqSV8HckLK2lI6w2=nm$6D^x< z9h#(|r5Y-lU%xC6h=ULyTG)Tk%F6r%eS5lXH1kXI3z@jD?;CJjpKj{gzk}k&s#{kH zSfCuwO{9m12i&kr0K%hQ4v!6L4J1eZN2ENOp=e@K7#G1+jKmpWFd{tUewW28h0e%0 zU{Sv?x*=tNf?76LeWxcYSLjcSg~+k^X1i?hK*T^()67zv1Dm(OS2^ctl7=Sc$%7w+ zue?_kf%9bL-9E=5ASkN7ji*ZePnQyLVEhK;T>VhZeXFO3?d}uBL?NdYUT!F8;yB z;e6H@@HdXDjk`Y|f^A0&iqcXw|Hw-G2U=X*086_?fOBKx;3NZK1%0QK5K6@<;79Nl zY&EpsmHd25pQI`r8W#570#-cZ7B02x`Y<^z9Ag0~cE4mj&i%__C!U|fbIs1l zNg>NATnFm_AOFr727q8w3N&6b7zCjK3x<48N`h1Jt7ci2>z*aDXJdN*f-vcFqAs)U4J$zC z0d#SBfAZ-{pO%~ZeL5qy8=`_%Dt%N^5?sh{5>T zjPTPB!G;j>ZRuk?vqB6TmiW#xzZ-7d54BypFFX_wzdKoHB@0ZlEJMOHoowt9>q`mcgwmo0&zaUtBcNT{@|_nJ;X9cB@~q zsrQ+EzMi+QIKHtjtFX zu@cFVx=x!=AVz$dUddU$vrwjDXn)!zZ&QUYsr+IFc>l$1A?^|w`hunvi; z6|EM{ve>Sp&Eb~Qovg9hSxxtSR1$*^vIwTJm(Ucf?U?b$4}9CNF;EUrZ&047-OFyI3Xi z0%(@XkcI}~v(8U~%-)ic3X=u%_!fXxeS~F)I(AYSV%R%8HIdiTd5bzvAhzu+2m!q_lXx5*@`A2aB9GqFy6BZ{Eh~F!weuh&Xt* z59ULFw$LV?^Bt_TME#~FZZm6R_4<`uoRNe&qi?GpCSgwKQ9Euv0fgoLZmHVUvQTRM zkTr~jk@%+)d3VHjGM3ZboC`ZoCJXoi7_&1?73m!j_RVJ58xiOIW<$!csdD5bR(}He z1Og(g2i4YCUAJ>Y6m;=C#TXmyCvrngwB`2Ji1Y1fBfZOrO^Lty;{i^Fo*eexHTWaR z`!CoYCEM}Cf6vg`FBx*4a9H;IdL#aF(ERc_?Hx(WODM*9(@H- zTv=V_UFAh7)FwL6T~g2+6arA6T_`$~PFsWJQonyP{=gC3jm>!*^qTiONwfkkV$GKj zrAU^F_Cwg+N3qVN%;5TG=pvW3T2X6j(q5(#;7_kjNj>wjRw$=arNfs+<)=$}98({poMBkA1T zzv@dUg?ngR1->miMs9EH{6+PxfS`2Fz_3!3)5h6*I5y($^OW=8aX$ZQh};NKqIHS` zamq1jMt^$f?o~qQqX3a;#6x^uB=(FHm>p@wo0U|Nn1f-D?_B_3s8`UdINF@31 z@X^tm3`crobNJ2Uk zH9oQIB5P0MqapEG_xJbzQZkvCna|r_AKN3pd~qI-DlUgLRbfaW;^Yj08oHC0_IUGa z-xImh-`wg21xDP>jCa-NQRM5M(z^ooPl)@8 zo7l=30!Xc?M;OOIz{0YG`X{B;=k}s*kVrnW&Tc9Eu)G;PFk6E*3e^|I`uCsIudR+7 zk~{SVd#rHzkICWj<2>36%0mnSUKg|)On8Nn^!E)lj7&T`drfx(zVEaR`|n8Rrl%oB z2)!`yesKzVC~t$||Kk0PjE)SYm*~dq+IBECrQK>&M%0qLd3dAWaFO9y@KLsQl@X6f z92ydmWqTMqXTx6h@H|gKj^|&-Owx4DnY7lf1a9h@U8?a$8E!V#!>l}?lE?<0y}1n< zX$TQ=oAEIG^&A*{9#u9d1nbv-wqPz_58)pzJ}~+7ef+}4|9SbPrefpebs?|~uY#(+ z5_8S}!s5+WJPU1G{a@0Z{Qc|o7reGB*SvMD&jNqmQf#!{GoSY@`1@RD)NOUbm7JMB zyLldLkHLWa>d3anQ+zLnP$wVmE7~F z_FVC<#rCa2*37d%WzI)FHwJHBv*CcabM^XB(F&ldm&44aXjhmPLz4t}IQAA^Uu7d>@ybZYDeg2wW&uR~`(H zo}NxWOyAP^zh3gI@n2%K0C)fSvm&^?#S5D^XBS9Ui?)>u-i{Z&xkiJhH#B##1m_F0 z80RBTe7-F=^lvJwW<}k-Rkyy+2zs&^2Jyb$;Vy{+?v*ad%PsGy?ezRq*uL`=ncDG` z*>L@EG@$ePm}28)>E#Vu3J#Q#;m9Fw2 zT{H!fd{J)BKd@`)y?ysnV@uLHs^JYK$~&Nkujs-Tr<6QWNo8*Kg&%dgLjEtPtI}XGV=6Vwjy=Mx!?*BNxN_T<=|J<-lJknM^6t;sBtay zei=KFC{Sub98z3TA_a<+h9cfrws1dYsok+1>ORK2UjmYql8>95tTbrOVw3SJnRAi; z(|`Xyq_UD@FY4HiDutKlj)fW0p(J$YApDkiO3}Q{{XbmfzRi&7geSU}iDmIfUnq2D zCT2nqY9VTZyTJ?R@#dOjnd}s5U6v(n8Lc~-;OyYWg7bAuyuLafmd<4LEsA3qL0~B@ z&#_V`g$Jqh?n-^v<9g=ZTmok4N+VK0%PIyWUS#fzUjhuKNI~vk zsvz{E0hFA`95)nu9ZZN36#i;_;K@(s^IPpp$F-7ljxGLk~2elySgfG1#QJiy>H&5Dk2kbHelO7n<%XH^- zP?0J*(S!alYjy-@oe%YDoX7QyzL!|a7qFF-C{yo(Z2Vs_d>;;NOSf7Ba}ZVa14{*= zAb-||?%y=k}$;MDzOLK!x9pJC5oEXJo7z$+&U_%^`LF2Fe9ywQ*! zY$E??jbUU!FFAa>-uJfI@#v4FX`>t3GGjMfi;2aj&KAM5KGKoBd-U8jyPoBxIU}cF z1P(F09S6~VDFl=WQzZ%MU3*~Mqb6PY2!AS;08a!l9Ssh6%XFgqimp=XOS~xMur+Fe zy!_nT?#C1a+^( zny@K>n1O&#G-|W)@N6pJZEtxlL##)#Kj!-Le;z;hs4y5!(Av1dO{O?9)^DN)O^LBK zQnIq5K>|AsScC(7%zUFu5#=CibQTLmd2qVX@4*1JWldqUUbb#Ld7pu9X0NxIs;qr} zaQDuE6)orJ-#lyMM^Ybko+pe*D_^LdRJ5iO9%Cs_lXN34wBXV3*Te9-m!_RL_ z`cNUZxi;EC*S~ej@>oNK740%ecZ4xOCWx1pV6-fakTCpO^S9&wvVJy(tqQ3#B`ZIG zWrNNKR5)p`!xL(R|13aiH2U?_zAFnHFWQ5S{C9P*WBmza1~hDhlYH23aFCAogS~o% zxtg~-{jDTILqkoKAWx`S5nl`2fo?4~Jwi+N7QD6=a54XMlGQlUm;sB%qK{86Lgn@7 zy>L2!ZLCFIB_@coguV%Cl8byt4iFsT! z&K|??kuAHcDp4siQyAl%+_W85&83FpXFIH%s@~>Ll=_M{nB;g+3h!x@VGgV_i;zDt zbu2G_@y~>#>sRSaNemmA=)Cx@;F3Tz8Ix!Nf3?`;c+hj(vF$p7>R!ri%Qw$PlqY5- zv2^p8fLRbInIA|^3x#oVAZaMYO8lUIyWwfOC0rNoU1nQ(%}@0@g(9p?gmC}k&$CY#?d|`L&;q>_zT0)K6wZ4p9_u zE=6$T=6%saz;D6DFAzJ33mUs;I>SwB9Gnbv5w zgHt$+_Wf~rcz7!HNsUTTA~$0=0d49h!15;?Bm{-eXILGB~|FpOr-;N@@{LtMgZe)q*>}eU6r`H(Tdy$vqAj z=0}+F+qRB%pUvg5JauQQ8XS!n3&Gsv>FlS=+6A7jKIH}#a_Z_#^lvkIjta}TEhi*k z_W6>W8{O!x=|b7+vt8Ga6YhQauw2C)cTw6z3lz3G10xjs`T|8$zZDMuZJxclrs~%O zqlozr30uZxHEA3Wd$J>ZpF6nn3MVgk+V)s3wYp7wF%vdsSTVP?J(#q2cqj!FpX%!B zu>BNJf+{Cu`Bh6x{KW?4B^55j(`;PSiB-wPB^6R$GJ+=T5+zc;^cfE zA|AJovZE2|a=OwhUL#9S>^xb7iJD&T6aPYuhMO8ynZ>U|y~p4Sjnfk$bTCfzXm*7S z(DxHtwaE%wYq^GVKYf9&C{+k1kjn7tcn=L$OfN9i+`A_GNIr}oh%aI#VpKx;&JxiY z9yCwOAz$4V#!M>9cU`@AaF3c zlL;mQPy6E>lOgTpTdgs-^Tdm_)dd?<5l)9wUWjear+21vN#5NgetU;CT)RFB-{U_#9&a~lG8X5C{%2vtQ;^HMv#|To zPD?x^b}c|e-~}1^i{sTD)zh{2sS}wlb;FtTlZeBHq0+(GZS8pB`ljdH?mBDP#oSZ_<*OK(#TQnnj5__wJWmSCykR)~oQM%<1 z!Srr-h_@w3zQ2^Py53=UwgdekCkmS$g;u(9cwe9F2NrzLJyOWX$V4wDUey>>^t0A4 zLyONFCW}|hnE=xhOY0Vh(YxN|)zxr-N0vSemc=W6A7B>RhIlOj_lVxazkg)` zFR^~8e$gKUCwE}bSB{Yl0U7KOmxww#I+a#a^mAIGC+*l)v8=bGvd9innWLr3p>JZ&HM zVXOCTJ48Tb%fh)3rl*I8EIn$M%y0$Whn9=ggCE!#<;q)R>sINYgN%V^@a>5gXx@_* zd!wlU!b0R64AQDrfL~=3g)7zDO5#FM68^-$C9JTkIXy5{`6m zaQF`>VDx8D$%;HXa|BZUsz2B>RU6Sz1_lOcye{|^an7Ee0)_NH26ee!C(Ncy?Lo)k zV&Gi8)iS*zQjGWg^6!JxWssKJl-VD*@5da$!NG*i>E-Ot;)-)Yn47Mv)Up&QTaEJp zoftpol!?y-zM^7UcMp!jd=ernc!)Z?&PmxQ`AzHpZd^C2-BvWbn_UlO3!%bTw@}Mqi|;&cd=PuvFK&`MhiB2bv&Daf+5f`T^zte` zU=S`V9)3h$^Z6#uZ^ly!F_oXR3VM&=SoxWl+YG_6copHjo5EQz>U;I1Ae`o^dKIJI zZf2w@dY}BZD<4XKZ2Gsv%h+3z>mta!c#{z>59+SHyX)E*E71$@Yty()h>iUsDm}NI zS(?dtMm;;XZ@oN+>Rzj z==X1wBRb*lYnf=(w;a?rrKRumS5R!lFWck7@1oNgEx8F4*BrrkwN_9ZD1k16LMElAQG-_VoFSl$?RVf5?Nq?>Xh zj_W12s1R}?urJ@~Wegscn0Up+#K#W@M4v1a0%T@p26Dt?(V>D0Oj<}}3$Y$=j=RBj zUfOS0vD5h~n7}hXNn2tFr6?7-8w@N%=b=OEXB$`UN~_D=e-9pThzbwhC7;h?=24vF7Yt5Mkw+b3cpK z#8H#_|E$k%Z6yOH$Sr;yVG~QpzC#}}^1dUf<@e&{ABqpP{KNO>?YKh`brL=N{Y9sK z0L=<8zk-ov!u;gdie+ZjTU^2{WoAYsCFF96Ro$A0q*yJVmXm{?G}v>e=dv`K8W#@- zUzVs3o}H7{TZ5uY!MEsBuQZSwC%ti^=CO;s5*c^* zx+(sEy@%{KUWqg2iK)HDpIE6svf%%Sr7fGZ1eU&x+_C^6d!HMILcm4qX>ZRar8uSN zoiAj+(uC*l?=P>Q@M&f+`6A~C0}1UD3rAO1SK4dQ-GGr~^q(8-Z9U0qg9gVS!P%LG zUTR|uynjYc2w=N^E8aul^UC`iPcob{FG7AEp1hJ86u^WC_}+0qD9sd+E5^@(Kq!5j zb`7|If$dskoN+UIZ*_VjhAlBg8JM(=G+&8=JprdfHo7> z)zaK>x5H}65QfCL7xWUC_C5#y3&Pa}H^^g~C(>>C$2jgJioUI3Das(+MWU&7zXOq{ zjohUwhf{Rl-&7be+Jo<3JeiHWlA|OB(?}=do;+T@jH8pvI4N*m;f=a)_Lzsf#SS}k z$bnko59pFQ6q7o6IjwXUSJSu+QZw;ZRgvLBKAWXj>*rrP?!Cci@2HCU^x?k52TS{c zfBAYK^X}BcYyNu7q~Q`H0@HiRJ z<+J7+&(mRn%qQ-r%^jnTogf7dvDjQj^z~b@dy1Bpd);la<+zmyCL=0EO9fahQE%Y_ z)%Hl?lY3^-`v=Gcx^K+*>oeQU>~&mm0DJ0ztKI=ekIna-MA*|I_OtPTfEYuc%v_I(>n{x}#^A~%HPY0vyRkuduH#_7KF>V}& z`$xGO30LI4=Or_DqnS&U!t5A6bpeq9_H4c1oyc{m@2J$+`cNuX&@_u=evcDUNf!{s zG7;x%XKI(}@P6~{|6;Tw8To+{qYxxcmp*TQaunDmxy{=6rN8o7NR=ZI5?Kf(nrOjj zHi0oACFoE}`R(L|3Ui2BHXLY%^jt=HS=3p;oNQg2f%jo#csPn^&bQ)r%CXM!-0xm6 z+;*wfh5%A`;d#5-X=Ee4pJnKX_=tWa2f(#1dgYGIO#FQRz$;93)+y1ktCEvYU#(*J zLsjOqduS+Vi19Qk)>|p^JW27qYzPxOtI-Yc2N#+iOm7`{w6}{p%?h*EwZ9h~>^p~Fot*5u53qx6Z?)VhgJHWJ z2@*7Q?LTblq6!rF_&Y`s5{qsJSO1y6hW(J>N=GSIUrN8NjZEmIxzJgT-w6{@-Chqr z3TrqXWS{hzdfmvZ$nC4;f}BbJ5gFf1AgcAetg3f(76|XlLGm=3^7nN;g~e^F#IH9s zjHA2t4^G)fiRV;1xwvZU!@0Zoi{LbzWy8sA!~0?^-+3x(5Qo=E8wTq?TXT1IzT|XS zjc~4YUF*3se0&Ei93LkuNn2_kaZ1q^qKdRvB4un|KVM82Rhi6P%HP)JQaJU$ZWxNi zbR_KB_r~zAh3twk5>wiiqet@#?pG>Io%Q$x^cpX@Kbil99vN=JvRN&Y3$~}$z!vu6 zKks~9&zAdL?0cxTTxUz9C2~eZoXC}svW_xudzR)Y_Hr6m-|@J_Q0cv3{d6&7ConmI z&@LFzK|tak`?<)V@0mGeW3`<^VtZV)=jNJUvhy%$_zK%1m!?x;Ks=PKb9m`Bq!}0C z>}h2savoz8n*sL+h*~-Ev1|OY}NX)ed zR`5MxPaTSOo}TE$(lMX*Pf;Ang{3RW8W1hr#g*k7Fe6dh2Ov3!B}Q_yzu-pgjP^eD zw)cC8>L|z7#nGfV@cD^O@oAe(x)B+02ZR?n#B~k^ya^dEAtS&deN3!y*mqY3O@`;I@$MxnuL6R@*t=Y8xvub|xBMoWRpnNcP=rcD}&Hh0wD1C3dOz8TaoW zBi%=y=^_;4(r+3*AsFawM76y7V3wq?^kx{gg=W*mG%y-*y9oBDAd1RkI!_s%UFc6z zs|iWU`}+CyCh)_5Xz}EHdVW^Z)s1?3dKxxp(<$o%=`I`qMDo2DWB{Oi3)ZGwVmo)& z^o)}SG*%3*E7_jqwUo#lUg%d{DOQ(KC&35bQt|TsndR^jq~-J12`P+?>p8;+ow9H} zHjDDk#af#xkJD8u_NI94GatK~Tec8j80fSm+j*&8RK#WKq-UEY6)$EMiOtE$i5>)% zOr>amp(#XR(}Y*ge=SV93lB$2>!KKeMy8&p*!Mc5J5=f=u7ox;mL=eEc5&8F1R#$VSe$n+6o zW6@u>V#pnZfk;aiPcHdPT9GxHWRL7FEG(c-X6EF?3cBoY%%!UIKdZW)uXMJlFG({NE^pCg^O zST!Qs+TS}lITio<<$Nc`13uj5-&XpYmXi8sNQpZyAK&KIt=Nv;VRA6I3yM(4sb!(; zC`>-y!Nfo9Lf5Teaje!hmIC>d^xL;+V3`26OuJ%Sqx3y;uFyzb}NEeC8&TIJJ(V#goO=kL-$BT!OUC>)bKf z*Ed6m$@wPUKY93Xsi;3tIHy13N5KhYqXPw)=k1CIQ8EqM1x$ArF$}A4)z7kN~Gdg$Ii|^=6bS)-^%-_Ei6cT1V zQ))%)Fme~LMl^~&d~@ZTIUK3k@j?DdSJ}b(cd3ImA-$q?6QAKpY-{@ z&1@K--pB}CU*OV%)m-vbG#6s^SY|P7BMn?}4pKeN0NOTnA^cV5>oCu~($MU_ zE9ytt)7@Z)5mO6`ZX=FLjWJ0h+-@ZIUJjxn=`v;CLL_ir$E=G$OAV~Lq_}{8olyM9 zHxb}O3b%K3x&)G3IA)w>nDFo-aZ8IwJ-qrDq7LSp zN^gBsU}A&bmHhfeIBrF}-0?ZkMHtmyXR`2PXrx4RJ+jua|A$P0x*oeyJ}hcB27e9d znv9G8NbUZ_%$tI55{Ro@^$^XW*%Yj~(m#m)O3j3j*{M&ECHk;@md~$p`Ht224WsO@f$xa0w_Ey0#5RWwzFU(s+NC;4*bb&d_bDyJ!2dQyX; zS#WiYS(*?XTyxuC??#~<<}c*l^5u$+!$Xutx+DFA&Pqqwa)#eY> zQ$T7V3H)Z>dz5Jn>*;2z>|$D0H8l|f{~2KP&YUL13ikVT%J6~xK=gM!HA0+;&JD0$ zY8+CWZWV?0=LD#4i#3=c_ypd+1$%KuAV70OvJ1%2kRZVhGLz>d^2D_|F(9FNRrK4S zMaKyZ83{=gn3w)p5LB^mvwvt}IXl0R7}~~_mX)SvY2)`tD`lN9$xb1M zu27`2>&w4%enAq6^*?_O=C?t;#4@QFcjFUb4N^}6%n{w{Z(HmvqHhq6LaP;T4G?OO z=vC(DcS>BdY+B2(Ba^F!rbM#r42>*7N=>#TXUC&n>mIWF zH~CKecpCypCvJ+J1Y>}Uc^*~uf9MR5MJX?5eybcUt#ERnXR#g8?1jqD%290;REQ)h zbL;taTyxCj@x8p6;8*V?uJA*vN0VS-2WZ5E?7-|w;II`xX!@^|K|uhe?KTi%K)KH5 z9?uyMt|4$NAUE1GVP8jhoIL_UfQiV}%}v+ZI0gihoDV7nCTQo2(wBThEwF$Bzap~Y zc^YyH1wlH$(H<)-EKEpCi|m$*%R3wRw5RS?DYK+~+h{P-LD{M7!-;USFtN`332W;2 zMPp5`3Vv;RCM6oGte{!?I`T4{IMoStK+MU>ac)H z$?&sCk1Ybcfm`-6`vm7f$nntyc!WTXLT@@l5I*{KXp*>S&bpF9gaWD6%u8mhQ;^9Z zqOVUb;0dSV`c!5jptuxab)M*wDzB z=tyZ(Xs(A3MB@SzBd&B$7*ucyH;xu+{sDP5Vs=yA zbS><94S}HSg{SSj7fpf_$`F7LgnbKrD7+$CZU;|*90nbMP6pj^<4f;9wfuYgRXZ`I z9ED6Tep<5!14>=_b;g~PB(0`l>HIlBoW4D~nM}fCQz`1NoJFRD3DC}L-gGbaRMFX+ z)PBZv65RMNSuvL+DtgA6cf_3gk^pjf>)f4=u_Yf5XwXcDI_5o4)MJ4_Vb#@@V&Y5D z@Mre6J80k~aR+wR8gU_k1sYze=Shi8_>j3Ub6Mp;HUDRD?`{AnTbG=)}TWRBi3WFTH7_meJ2VVzG zBehF5$ks!86g~?~eG<>D#lY%Jh>VH}*%%?x6W$`GrBey!`;SN@)%%@QX(*pUl*`{; zOl)lE@6@osorgnrG!2IgL8-8Hrsd442&&?%bY^cy|4fIe}f_Uq3s8nAeH+05Jx9Rj~C33++M zRj*yLPM7_MKe_u)mUQfbC;R)KLBH11*GDZPLI$d&fX_|oRAb_p9DNcMGc(G|%S+33 z;cNf84Mpp?eY%AFf=ZU4%b$E-5C4+Eb5O7IYiseq-HL8yi5Uejve5SDV~0C%XP@_x zI6x|KE`VaKQm0H_SveF~zr3fv4+y@Z^K+1umZs$4!3AF(m9to@1dEh3n%iOw_zOVq zj%9;t6b#-{Qwab_Yy`&R^mL@}>Yu^s1rB{R53#;QkDNR_U(=_+c>(%95LAW&iZp<) zaPjfGOu0CB_g#gu1e}5u)>c>13nvl5I4w_${qHY_hfyrXvOXQO822IryS9Jdf_V+m zRFSHjtu0GaQxk{HEX&vAr&59UJyIe*91li>t?24LJ3?y1g-( z3-HKqZ>LaK{qL&Rd!*4GeJn>L3JHh4!;*)~kAR#!_GDEQD3tS8mf_`T&rnc9>y`P| z@9hm4-!bB{XnFysihutA)I!=GhCJXOPQ)F!LXbXULhA>Xs)U4vC;$8j{*1%WH8qta zsB&?0aV6>JCsJdWlozBvSl30VxSyDaJ^L~cDKFppUAdXfpal_PX=VSZ5B;q_P6?Kf z9q>ncFDG;ihM$Q!e!`#=uvnnn^fMN^X{qpZ<6c;0|`Ci6MUHK|=jVT|jhoF2Md??J>4!sT-PG&zZx9NL4}Z^_HPOb|GHz}s%Irq zVSiMhf=a{04=1U%7oWLj8rW99`_E3m^^OvqLL``Vsjf?x36#$8n^<(vPE*kf5sQk7 z-tg6F=YKbSr=YBBbVj8|6yeVPh{IoI3J+0=KvJB6g#_{psG!fFGPXmxuL+^V!Z%bH z?7Y85&Q@YpZgist=FE9BvwBM~Cl*4i|8a|nQGf|TQb`HL|2)d@3|?ZZF2wT%`y$Dn zq^y9>uVXIG)X@FLm@zqoyvCPFQ%IzvqHag$lOxsi?Nv(yz>>FjcDVd!fujhxb$}$x zJXztQ049AB*|b2C{@(=zf9-XGZW5U1z)0aSje z&dy{8r4lD!@`km?IAlZ$e9XC#6oB7i)-oRo@1|D7u=z%cy zjdY8gPHP4y%2&H=`b>eKPpKe!I z1bnX;+g55w`hGD@PtO`_rCo{#{+0=+Rz}kxnLL2&p}QRKU#%n8tLzmgB12K~5_I>O z4=}c3hHCSPfNwSGsmDY*Tauih{U%(8xvdvtKCzaPnFCnElWpOjF#2q34qAW&i6s~L zQe4c4zi?!Wj*f;VF zPd>3-^KRw#WM%lm_6Nbty+2K3sF%7rwo1;M&wxi#&Jw`-`SWMXwUvWI|7@8q@RWh+ zIM@BSztJqPJcA` zyqKZ$6*o2S(wG6XIq!6IzQo3&|6@31q^JD*{9653N{}QGaU^x}-*HGlH-2-}aQ!Nk zi-oxqo!3DLzKaA+QL2804sl|DN-Hjuv)OW3j$O>c}!xb@Oe zjkhksxHwudyuV@g<>*EHrac!=Ta|@Bi;)pV&LG5@7$)&ud`Tl zeSh)$^W@Ol+L~&WDdsC|u!FJg_XzACm>zalVCjivy(nCOO;qje*d!}wb;@_xA5KDk zFH*mqu9TMK~`xmg74&(O*^zlj* z^)I)R>zfH}I)bLA)QVV539S7?m%ue$jA?_UL zy+pFd%I>u#e~ofD@1`4Fv>c7 z!utbTwy$*#LAPYb*37KXFM8h4phbLX+OlTvqa6ovK%Ea7e28?grE3Xr*)f>&K)b!a zgVcFoQTe6}0o1R;=p>$D;5c%6+_Q?n{Y7aHhsH?k*!QA5`08yQm+YuY@<7tOp^o?~%_Gm)Z zXOxn6eIIHM77nSK8`a00Q2}THW;TAo(8A7bW&1Mn~x(hgxy`;OmVoEMmkaU*HO-`ss^17l@p12 z5|KoH@$v70&{-glUj-RRe4bq7`5Xuj_BX zP9qEK4*xb16@?x&to+L0c|1$D5)-YkwzYK-#m^+~S5fgJh&Oc(jKJjJN=T3*H)h2n z;B}7Tnwb;cl=DKp-7WzP@A_=H9*R}*=$G%uR|Ti-INb0fJK97zDv7LJXFE6mv{;C-e~ zZftID4~GRed&GGA*tqx4;mSeg>1T3M62vUL2{+yMAkegvf6(R=4Zbbc1>qHxR8&GX zHcS`S;c)03J_-f?3I&~@6oLeE%2yl~=6LoU@w%JCRz;rE?tlH$RvM2NRh5uBctX>-e{@P#0)m6$&z@Oh3SprOE^W7$W|UI?&;dvy_Nb z*1b)4e}u0T;G#+_@5_KUs!0DT3?*1Ug%D~91JH@Ye?ZdzIX;2;ZFh_-rAYQDqhLhT zqd66O5#mq7!no9rIURxObN-GFSQ5$`AbY^;LH@fUa;s%BIydoq zU0q$2Kdet)G}43^Vs=1FB=W@#d>q~@;1(Z~I=3`8?*u-L8J|Zp8nXxjU`r2Srvc_K zB|D1YI*~~<8(|gaUK{t_7M{J zPRTdk?-yn(5{D6TaZP{PG2UVLV@^oD3v2yL6|3#7v~l>`TS+`&PV^H4ZEfxCDaU#( z;ZQp0%f%*81^jzvG2MK8d?=~t-#{GBR}Ey!6ig`MzDo>b77f{sGkl!>p+cD!@9eQPKW}&BM3n3U?LR9cUInP5Fqu+#1`F#LfgY;gmj8KlnJ9joOw698aW_v!vhgoLYZB}hSA!pp+74gw3b=uPR*jLF5usR2+ z=s!VMm%{5ZULe4NJ$%p0LjfBzY3l6!s&4lAi(vq9=(!w(N+j&jG-g0}c~)gM1Ki6Y z6$;*i8bwRuPHA1WE84-(iVFCS-9x-nEfnR9;wEI^W*z1FRn0`DL~{=f0uADIKz=>9 zQCMHTj-zWLi?SS<&XW;rC48Pg%olXq- z&uuB~UW4ZBSxSXs`krO&zUjX=JurO(0r)P6**`4Azwgk1ls*xv)Jpd7sDrCu3E8wV z9^25+NDuUbG9UPS`|U8{kdY1EPXMQ#p)t8wrFx~ES~)gIYHAy1!S;%&k8qJ;f$cM} z79lifhZ{b2Cy($aQw#8EYk#9mkhaq7#RT7>MIYauZ4BDn-$&>#6ZJQCtE_;QzDTp~ z9dP@126nt}M{+_GoZzg8(sdxbzfrgK#XMfwiH!{Zz{QJnw{EIgkJoUsXoosc zdeZX3pXT-K@|q>Rre3R%H}T+kf7%iCaN9b5@}{yp;_Pf&vB|D&Ca{Odi=eHo4Gs}e z1Q2t;2qvhBat-15@9F37$w|p*`1k{qfAWm;G9DB-eEs~&4GyrBUDfZTvMaKpiL-z} zzx?W=++@L6=u?td7#XnTS_1;<>uX1#N^I-U>&=W54c5`AQkPd!3Rqp$v3GLnn3=(D zYHA8Ih=oHZZ374A^%I7NWquiBF_Evn8(L>rhX5@oqs2VytI8i>P%3Z1zD1ZdGhX;@ z7lS9$I`eHrOwjBZBvtx#5&^sm^(3JsBej#zzC+HhLDQ>Qn5p+nyx@uI;baN8uZmMl|do^V(uZdP&=rx7QRRR&>00Q>)5yJMl%Efwbo(?wE*smH_)7Lc)pW zJ&Tk3s6H{Hb1EBNxQJ`Bp#O24$V{Y_mK{e~A)wB{Ovug6y}GvMGgYWk88NXlzVF&x zmq0&Z%$ikHgabr!jh|RPz(w(-$DDxM0k|{+1MD{k&g$w(9mz1DnxM?YLvLaDrko>g zQ*VGr#;&AIr}cbm0NlF202PRq=D$eR1|L$>ESGr6#oA{MxUQK1WmN!{QX*yFgQ*^K_6Z!#LURz}Z zL0QrZi+H`~Cm_bb(Gw#1l~GzMyVz+l3x+`(r<NPSJVCZMzgXe&W0 z5BjComK^{ozy(fi3z5!$REYDg-^MY_YH(sBp%h5MJ80RbW@cDS^s@EF=Eg$8@!3hh zCb(2MdE@yw&FtA0h!XpjSznPPCK-x$rYB)$M#Ia?o8b1{KX@$*AkTz^goDC%ii#7p zF)^=fiYOu$dOU`}mnk2$1)gs**>8WQY>#+DlwF`c1=cMZNxPHRtQ?XKkYB26H$S)aiKgsKQ}R zddR!0`O$p?iuApUUAqOytTESP)=w7iG;uyA-Ngn$vzBj%&2Ey0?z(wL>Swh{Fry2H zo$w|JVyfR_kPO`Q|7o#Xpwi!q0`O7gTo~v;H+OcjtE*p$;NIR|G}?)|guHQhATs{_dk-Gic>3?Yd3h8xvOsjxG1u-tX6!#{*s<5)_hh%Hz*Fc|>#)8pHuF2G z26UQWg#Mq3rJ|yOU>w6YJ!OCoW!CSb?SL)&a6mWHcPGEL)=LAh5(n5S@FOOUN4XAB z^iLRY*R^-FN0=4^{qcV(;Lb>F0fekX-UQH7vEzzVG2p<5)EbQt0%9w$%8K=Ujce0$ z#XMsatgF#aQm0j!)ViMx$DT&|Z-@~CA|kQqv3>ZaSFcBY8*(rcqT#Xle_JDEgwS30 zCw~|0t5&R>4Zb@tJ%DL~5icD0YS0RY5647itmZ0GbZ%VDXi2nXLTVbDi@ur!NU&8# zMxq|LfdMmyTrD{)Iesxrg3tvz6pId0haxeg-$hpjr4iQsogb8+wIsb!5t|etq1^Sg zZfYHDW}b|$X&xWWM|p;eUn4*HSEFsC;CAj=9-Ob+Xe8r35HM3fb%n>BI_#5@*QcU>)~Mh2 zZqaeUg41q0tOJt6f=&2&{I5CWJLu6LygtvIMn5aJsxbAYTUi_VGqLE)^(3xaWc7CAAw$^zj>jlNwyCb2`zY{azotRrh6FyV3cV63oh# z5}4WmlmQAD=$l~y$~lx=vufq_gilRFo%qq)Uk9+3Zy*AL$>ETY^ds(IZ%M&M!3h5Y zExBxB*lQnU=*TV{`=wJAnwu|Cf%9-54wZ}l0uQ@2I*AtkA;7J!_)lD z|D;y%jk!4lA}T5ACvbqo68eIrzq|5AA-C`@VMN_OaLjnq<7@CGDwj;W^t_-KJHU&~ z&Gq}&o8NZcD5F^v3q=?h8nzp=a??`UVSfdj#er8SVADTQPypZn7bw~E`u{9QzmTP~ z;UVj3FuR=V$HvE#GBBWmMpy)FCVZWvos`go9@wJ9mvg(ha>y(yN=VeZ>xOqa^J#Vh zhU$PR9KMVJy!rM}@*9XAu!brq=nXYT>)$GfxxNvTp)4zAZO!TK?wj$Ay4>~36s-G! zRBQO|^i_?{?dpK)p$sU@^HduB7}D1<{=a3)AFV_^OD#u1ccVMpQsP1e@QQzx3cEGC zqza+xP*)b8h8YPz0g$BW&>(^=FiR@;h*pzN3ON88Z=Z{_OEvmHlfh|~MZ)4uYBrC+QMN=cy)jYm-*viJ=kA za72qzxJMefi|23qq4P~-#fEynlSG{2=fc-!l8CCz!HE}a<$`to^rE;M` zY7dx`vR#K8{%D`ky9F)+A} zy&}vp7atSTku(Fm;S$W&_V)UshBOP|>p}7Cd0gvoDXKpYH&8)D2L%hz)!<@$t=AD| zRqBT;E!t7$xd%N*4c^{p(9r%L$qkv4k_LS}Z#CiOY@!|xK*0fO+g;Dq%0Be}07mhs z8^ykuHALM2LfGm~z!=Id_WpQ>+%>=fbWxyF(98O<9o_p6GU(w{`ea8DJ)8ryJ_m8a z?)j_yr;*bMI40?1)GQ_IeTk^2a>ZW1BuaP+c)vF7PSXXFP$n@{ILGg0h;tZTu;QT={%v@;Nk#FM{;s<-oTjyiwpRr zGZ_sN(5n9%NYH5ee=PtU;6ND)KODm#W>1V;&)o1)QU;4z+f9tGfR^mZDxg=B-dG`4 z)s$d`a|*V!hP)!W=*eK}7<*J~1h2N5K>vkq!Ny>TL~5wHnJ0iWCro>!EEr zI&dmRb__RZpN_H~UbO|~<>iA;=i6`2G_@KWi$$94R{*0E2o1_#@6eFL$NkUVoa#%o z@BJgKgff6?79xQis6i`$6ifYhQMmUEjJ6whJLx^JMDDHUbRb6>_x$|)6bQb{`^mO| zGbL~d)O}U?ZvK+M@r`{9R8djME-VZsPOh7Yiu`E60CB}>(K6a3=7oZSV%RMSG9#CP zmE5+bLi&r*$>7G{qIVq6P4QwS6`Jhm=uN%|Dnebz98!HGLxYr+vNd^8#sEMD{h2Dt@d)W`Tg2OLDu!~})tgDc<`SBT;-Y>x*XAd?O{FYZp)mT&k@ z=9VwgZqjymcep^@ml(7LEmnN}#pNY5pq1(p^~Ab91AoC-r4O!A6!um9VB!v`so?-) zIsHhEw<~1++Z|s;^W-a9SDwSci(p;4C1Y^@-xqbE)(Rd;k85oo~P(?b6zjADgOH25%Dv_rq#}~y0O&MZQ zK!;{Hl2%Nh5;R5fYicjQ^!EcVpFs z^N02RS;_66HcAUy3C`ra+QS^p;O!O~a!t#WuU|Bj$>V8gcttK02ZpN+Hz)fG3in&o z?X4p^R%gUZc|C#F`E(AOT9@$K3c;bwEq7)+rs`-cg`*q)q$140CtZv>rFc%#DV~If zemB~A4Vw^_aY*Y{AJ*HgbF{U+EN&<*SJ-RT#rVxHJ#UGVl1U=)@WWVPihW9PZu9$) z%hy(bOp_rP`=Tx`lW7;(mL6-*yj&F!acfOC%MGh01yk%5=YOeK#h5$hsFvS~-iK2` zZ8;l^3zHwyf3l%|km&b&`TCa5w&*Q3);_zMrsiSAyEfA*>aQD9X!?J^t74@amLF&7?}jpb&h!n6j5;SNT!4xJKc6@A85ft+`Xh)7TFne199Nn(oifw&kKDzcw8>Wj zVxm6exXZ$h{yTZuSvDim*4)W9^*an3xKMu}3S&#m)g;pPda4SoSM&I;cY<~Gsr3Fe zrgPS?*K{f8YkYK4(qG)0y6Yek`oyTXK5Z*2s{l?JX=ySLy#-D_&aUMqP^@bhqlqafSZ!6_j3fmW~6LvnBWVoZ*0sp zI5Ft;L~KoKSUH5qTIiDOlhe}=i_N{-&~x+#Y4*5|l3GvoY#Gh0tY{M_ifRA3!DphO z0n0}2MancVewl4|AYJg$&zDP0OCGx>F@{1`r)H-Tbi8CKt|Y>RLj~zpXKBF8-HEtk z>TU`nRFj@2_nAY!YahFZ=~;V#%Vya>;ohbi;U602QusAL@`4Vc`l`QQ#pH|aNjksL zLk{_gXHV@U!Ys{>Y(d%AwD|fk&2#tNog;+y2rm&Dj@knr&Vxghw$P1L?SZwTmBOi0 zDb!P3l!q$A`M;|xPZ?7>y^kxZd^W_^pLvreCMFy(^TLrKlkkE?ntslWj6{NXr&JZp z%9NVi$FpIIf08?hnY8G8ASH1t>(>H_bY>&u6MKeMbSY+afqST{A}XZ8+xR%wg7W+6 zq}?bR{?Dp&0_O^-_mh8XurzUu3zj#pjhPc)p9_%HCjY2_Z-(#dj}^m%724G`qNJG| z6(tDhU{DyqI8b-#0ycg6&yR8?JB9pU)>_*D{udna6DCC&*R<47h%t0Sc+Z`3CkpY7 z_S^8mbV>H(Hy0?H@VAI98{JHLF1ydLb=Ui5RFs^#DHm5)Iqj=5*JF@`E-w_%Ojcm+ z)@5>f5)EzKXJ^N9t&~LtZ8`^*Ow7gpa6aajz{$tG0R!kIu7H#dw=yCw;dGywisvqh zvg#0W28Kw*>kWVV<2L*ofkBXt(mNvXA_bVq58U>v^Jb+MavZ39muOxu4=a5`Ll)7S z?~TJw(Vu(?Gs)XwVPF80o1HR4QeGANtHM+%e7lh*sp39Lpirr0-)yQg>9!e^a(2r_ zIL@YIC`iayGdxAPft{*xU^t|2Xjt#eB%8u1?-G=sF5!@Pxv!Q=gdShS9(MtjL*BQ~ z7*+y3yd)5e0*@#lZ>6rrI=7>iT}7aYVAAV;U3!bhL;|fleN6oRV*!Oz05@=yQ7W~q zvtUmab{{DG`0xFsVPztSS?i7@8fgze#Jp-5G9(3#>l50G;DF29f_@3Crvl_@@*6wH z)v!W3HU|Cq8FmDsfx9 zA^K?wTbuAeF(V7pYRTX)WeXvRoiR0bVH%jxg0m4rq{l?MC2MZ2_%~8V(_Xx{N@pyD zNRLa;#^loVI8`1M&r1}+&3_raBl2+a)3*Z!7$ChNK0PYr_CE;_M&8^OQp0RV-&m5TPyfm7kuOe$LQay)&igPt2I+xMF@nSD@Dpemqn`F1ZK;G%+twcZ;3< zdD|qE^U>Ff2A&?(_Mc>AZV6^T63b=J@#d7{H^0gcQto^5!tPIg*$bT)=}DWJmz5_-lj#P&Uz9$naVT-;ulVV`F1C zL`gDF9`UlWek&iEt(@UHqrm84Zleu0wpQXU{A^;)-_bt8b)bXQT|c8{U_b_pyr@sS zF5i^4Ji!Er1(<(c>7Tzkcu!(H1#FyNjA2f^?%@xd4oMmJWN9^i57WH3roBiJ4qsqw z*i24GpUvCx+L>8tCA)s`YAApW;`T4+Xib$6SL1AUVH*n|+kDjJwG$WB>7DJ0J6hPA zEWjX@h|nKS;j%xR{beu^hmM02JY|}rn0IfBO30f4Y9iYgThl8#=>ogA|9YqBzt>Zm z%JID|lyWppRmm>!%%D2gcqYKc-uaQ7nTMr}VNr1;0j@0oq~G4%v6YQ;E_@ahB;JA+ zQU^!@*rEJ>o`2e&-nOq34;Zc%TJ1DT+g4aYp$r1~VwKlbt zPbEs6o&Kr)L54mX>rLr%Q$|krQndv>aIAkk(0*zEQ4TyPfJg`=oreRyuYRUjPEPhQ z^!aaDS=1yrx#qKiKy|B0%L#)@I0#Hp+J`t+ic}Z;gMwIe+o8b&`WwCmom8CBWc<_X zg8*n$OvLI}VI3d}Cvv`GgWrq+9=q zN;Bme$j;7kYimMMALa_Dmi0+gBUK~A!agxGM}tcthsd~ODWu2~yH?fLp9azhrF=J? zV+|w@L2sp$#EM*hG$Jo+Z4sQC<-zvJ#cpTKpD!-0Lev#gmbh`*~E* zZe*v*adJPDVjeEMYCYtP9;LNz9q?NHcd+dwDb+so+@0+m>=I!Hdg06Rs^6jE@dV~! z5&UuaF{5s4D4nI^3{lL-Yx04hYYNq?uVlg@kA|J)=^Fj=5J%EXR#qKWEwOr$i_3AI zJ&29t26)MvlFCBC1#vqE9bH!ZXR3NyBUYtH(6 zkHcK;RGON;DpAXJI_yNK-CaSp_UA~29ti_@d>8KqxleaX4Fk>t1B1w391WEKn z>I<5q-fKFrM0!>1@s<$W5{cZYYc<_buh;*h=pBJw`G|Oip}jtVD{FfYWh@N!2v^a0 z5yUZVD~x_JuXetPmem1ycEyB&$LH&2G`TXc|AC0fMBgi`W8ug3S)0IQfAGVyQ4E~5 zA*oj=+r-VC#nqGgR-}}P(RMwmZK_3i2rFJdb`+Tx(Lhuh`ai_eu7w&Ps9NetPH!5@ z=IEXv>kQ-iL(_5m;2)-V?m#hn+t%@^D-c}=CF{al<930=?N>wmyq-xT*By1%!rcZo zfzYG>O`jasJFY{GyUR!p#tbtaNJyS{9M=r)m8D(k*`M{j;HlCW?bubTTN?^+aj)N?PR=1Fwy4y8Br|eVuJlgKg zV`4Q!ByTk_$+Q)g3d(UXVzt{8uuv_$nGhFgU?0t;)4X6bmv>>nF7oGr^=W~3Z(q&b zW1SsrV~6d&_G@KFn|yoxg7c-cECh1c*SHzS6o!wvw7{pR=tpxD{_}VGDEL`KvFoG7 zy2>%39B+Ng}XYRtDva(Sz20YoD2A(eBg2X7Pk&6JOLzjcWUGjTO+=~abpcCO=3aw$|3|BAaD7k`KCmeJ5(Av zAc#d!^?`A#(iKVwLNRDKf!m%O6zhM-OmU;f98oLtbw#SP=I^m5Ao=MQR-Y?E(OG`1;Z!!2`-0bjQ&Qq1*d=>OU!u%b1-S zU=s6lH=**Y+W(s7jMj5?++$I*1hXnUihx_9UE|o~WYaB4X z1CWb)D<)I9XJ=~*9l(&_PXRaNelf)1{_=E#gwKuyQsbvov_WDX0!SG9rmPIYrtZMn z{oQ&fLxO-8|3Dm_V*lFl@i17-`7NL;qQ{>6n{^6yO>L5K9kp>MRxBkPX_&Kl zyo(8Vygdqf+;~P8b=~cnD}y#DeCc-JXzYxz^jePz2)$kJTh?!O!640}%b9({DO2He zg>daq8$Z&l(La8|zy6E9!Q~)=C$YJP%aoq9&4c`WFo^20;$EfMzrJU>Y za6jK;N(Iaf{<2})x%TZ@s7hUv5sm4^Hq%y8pZkstVyQ=bzbuPokKI_u;_dCbFG(0D zCj{Nq9*L*3H151^gxXCG0^chIcEH_YeP}MJJVMO-yCMP5^Od*B6d^a>6Uo{eX%8z# zRy&^?FV}h+UDJQ3jO5zRAetDflcx8Pc?`)kO0={}Xb-Q)U|V)Ob=aqQtcd5qdu<#= z3as8SX%%@qjWjlm-3fBaJhlrQyT{J;+@GG}6J4~mSY|I>b0qTKeW;$Xv9FS7*$Qz> z+t`^$=RLd5bH5#be_vg&8Ws%;OEJ^j$rm}iwwWPtK3v4$ay2YBzLL4(-8iI=MZEP9OgTA|g>*|sxA3%?ucif`vI({R$BYPMi{N9>AM#-?U0VO400=)7W1O@zg`|)zC_I%16~yJ7afX=*E2b> zU%qGrg)Tu0<1H4kzArCPPBi^GSL28Y+n&eBvL%5v;uRo2wQ?~?B(Q4yBH{e-g2ng{ zP{{RklwNmI{2|4L)0&fd?yj3|@pJ|=!OF|8j!OG{1f6U!$^FC4P+v~>TC0sAhn0-v zb{*TZl>5=k?eWX9&X<3%d0Xx(Cp*~-J*P7cnTr?Kke>J3Wa4q2T}?Gjz1=^t#47oR zTPcWy2Su!p7@a@8F>FB<+mQ?O^a=?3P^JevCd z?$;!iFtK$9qO}8kBWJ1BRLT{XyBf^M69y#pn(9(Q1v~z;HQQimVEj%;jg?>_(OQ!J zEDiasqtH2yB%*gsOF-=2=u(FgQz{2)Ng@(qO{-G@for$7UN=2@FE ze*;VrM*EWmMXKeH$wSkvD%AxC44>%5JyKBfFDM1_;@y^C;xjx;#9ltpFm>^vC%Xcx zXdosY0DDoV*Vo+2r0M)k&lZ5b6_6 zm0j!h+u-J+q!vK_ZO=*UumXyH$d0!d5koihyW$4;!0uTY;_zaf`Z-@e-=my(VVGa>g<(R$ykAl>A6X zSKPKwT1WIwtAGEWXj5lTPlJ>xe3k$gm)f3PR#sL5n;DjJ;cw6b*Z*@-`;eZNHVoXo zgCiq%fGQoR05PmBk9Vy(%jO(0@F$=oq{%`;NI}>-1(^2}h75BC0kgLOqLUy}pzBIY z8Pd|yV&mczl$68(_zF~I;I9B%m+y~VRr}JhijxQ6UfEr!DLrqhibTC0kEwNYL0g?k zTEsA7gnj!S} zGdt={s%9(x$zj%uotv|rtwdOB>oQ6;EpE@^3Cd|+UVYTvomawlcRH47&tASv=1|Ro z4-~c0Wf73uPew4Xt}lKTEP3c#Fq$!vRw$$3AhR44m^rg9;{H?W)DhQaft1w|Z9$k; z%RS#G(J{=W_Qopy=lXt$zO7^ImjTF{ zhP$)Eyt;ZeK`(yZ=$}^sbwx@1N%&GjAvZUOes!=RGa**x{#*1$cbCPprri_DdhJ3y z@2rFy9J7;myFUaBzO0&|s1dCN#h(zjBja$x(FEaK^~1V*y`UWv>N=_Y=Ep!{4PAR>5`mo3o3lm2-=Gfn5PPx0I`fp1!TqJ9+0ldTW+;qTKdMr?x|p)BLT& zb<-sj*UrfSvjI=<8TR&UnzclsVZ9KjwKB}-3*yClhP?GUIAeT74%xs$Z9j_|Ax*Z% z3oLsV9Lr-E2JVauG`K+IlXeBvTSxxI)txXWW6I75-x}rCuwP~OP_yqLLU-CEjgoa$ z=^7~}=h+x9T2>u7+^<+Cn{GIx5f}yo_OgZCjJ?#>qt%SO?V`>!B*!m`e@v_Yb*&R@ zs*A-j9-z)z5k@it6d9Ar_#eA^Wy0HCx^#pRu)tSA26{uKOFM_6om?? zA|7wg=+EFB^mKJILrLV8KMn(fHx(_Hw}MCuYX^5Xx5jF!z5= zuI$X&ljrIk%>2%UMKnmN3?%eSd%An6tu1)MEy!_jard%dl!D@w8r7@uUGLa%kbeG- zlj9iJ>vt$@R=%$I9SLkQHC(RsgKxs8^}PjMT|!|r4*TB>{1g)9YE)?n_*`QFQqooFGMO)5q)`*mcILr^V|sR; zzjj*=$?bS3dBA>kqr2Mb1CU>_J4;3!0D9%v?F@rqgT?t&2Pn3gl81n?4BOYJ%qjM2 z^SSoE7>d1x8io(^HLw};@k#wr0GP3G8r;t#&B)Sg=W!Q66##}^6e*HA4{B?@1 zg7LjFTpD-Y6As2sr9MzlS4fv7Hq)qA?HsZOHMDJfn#gVe=lRi$ETZ3*+TpD!=Aq<@ z^wcleTKUU8UhDTr+o(i`x%Cz6HB-`8 z{EmnGB0)ZWyPvA!M}7Q4^2>jft2DuAB8m$Oi!i28{!wKmyb+v-5&Ycunc$o5LOH6$ zG?l99hb3L3-3K%tXMDQI<;|rh!H*q{Be(NbP18QE7Pptt9e9X6O27 zcl7B^GfhcOR%5ifT6xi*HE~fD#P0Qt_sWP}%*a!{=WIig9b>aF?!yF>D|{jyaJj+0 z?Md}|Use zm0j2&4-aO-|GyUC?E*`0Va3^sZrkm{!^X*p?CF$Mc`0>zw#yXVPeW#d%cL_UUv`8_4K9ebgoS#6R{7vN<7xdj zyoE9#j|fs$`xFX67NV-m0I~KesPJ)r$V{^F7HuXmj4uU&q z$i~(I#76ZF#e>yvB`mTkXi3G!%_+bFOd33fBWhjlb<`|)13~WeR8;T{OC^+w!{T&K z>}b#%6S4wB0}L(h$}^?~9g{z85(m+sei-LJ{)U%pItPkJ&IZnDy6 zxoY3%X-+Wq>_?SAas7m%q!zU%ic2j4SUNbW2#FH}zKr0Z1iR-{I~(ikpf4o{-iZt? zkKT=ohz)! z9cy=~u*SC0{)XhsU$Zl~BUu+gO3;Af`v9Q$$HmO+6CU ze3dddWfgH+9X`>=1Oh0=oKc95yr{jSgKdCbgfep~nWcYgd?57x77!NY>czmh#I#z4 zPAZjK>F$-LYv?qqoQr)7nNndf9F%k4+=6$m3;W*SxK+JisRt|$kN}(=exN*-XC*)Y zEZ}%><2b`uV#`l@J-H?9a{x68BKIh-1e}gF$>_5^GW{p{+m(*dnE5)nTE zho4XXye+k93XC7ckt6lb(7A@8xk$E~)Z(khf#Q zqnrM{3f679wktX6!X!*1lv5Nbez*L=$q5Q&OK3c@S3W+Y4TAMc8du2p=;qAr?XvM^ zF#~cjBzz0xb$jD3bf)Cj&oe#}G&@ayOE5+M@f;Jv5U^Eo5>#!ztaOCE^jM1X-XLg4 z2Dk29;%U`wP@&XE&7j0{E-mu4%8OWpLj^UUb3lDd=h_hFo-x>@9dF&L{FQ?O&rETfw&|gbJYJ&cDS5QW zx{c5TKQ;yD4+YA4`aU9@K8#@*C##3?`d{ z*M(>CR+}+S6Afp?8&#+DLdWvD$-F4tUXTur2iZ{8@i#R7d~2Nyr8bGCg4ji! z4wzjdqRsO&RbLIVQ*?j;sMmFoBfD{HgeK5!X>0BbaMbbdV znJ}d+2-HnlWc)0f`YCI@nOeppdbj8u6uhtgFc4`3BhDSK zX|m6ll_;no7lR0@4p)2~EjZSy_sbwM&?r>2JcT5dKsYyW|jc1Z<==<%2Q^f};vBhKOf&P7T_26W5e$o<(8%m*%< zg(D|(4HEJUPW!W;?H6QWO=1jtha%v$ zF7-rKx3&F4iTopdvOtOWldMC>nwVXzsfY=0ZY&#?!Nu9SbtpV*T;bVq8>wb`+BUC0 zyGA4k<)7))7nQrBn-t?;Bc@flYN;cI+%ipl0>x#nCVxL4=YGUk$XZGTlWZRV`&{>( za_`mIgj#@99T29y<$66he6IG{ro%woACREfL&}~qQ70d;C-6uE2SK~rQ{4)-_XSz$XeVY4-1|=P^@q%p4xoZ0 za99yS0ExE~JVnbuS2++MwSK;=F`atde3Zt={6%CPy_)ssJJ-$>}ffd z$4}RH6x7uH23uVxACAA@j}G(<|IInz%E4`yY)IoXQ8Cl&S<}hN$_~Nul3y}DIU?Xp zQct#yo&C;hxzun;(%ldiw$x=GTN)Zc!rTd+5F8%r`=OwSciMXMFQyTc^JRuM18RkG z$;Yp2VP<{b&uHAj`S$Q17UCUMPUhRM_c@QBAD%R^S7H*hpn{PvjC~O}&?k5hm}`D* zO-NI_v5v{FB`giIEw8{5IO6l5;_q?T;Bg>F(im&Mm1ZO=GSffBWpM)a42Rsp`^^|13sDT^gh(V?6*+_ zGbw0G=XX=th_lM&^@2umJ;jJi4RwlTJc!(4)HFQ6+Ad^QXIjl?)VETE4R)M`bBQal zhp;})r(D_fa_@7`w9(mnJU=*iM{D~P&(x>kq+fw;5R+*f>(hJ{9DE*!MH*Efwk&oi z4Tt(ICLNE(iqi2d+^(`bhREYy)QdXs@!&&3i2pb;G}!v>&KKh^b!yMh`&XOn6|k1O zVVN5vYFqkVUf#FRA%47v8`L~Tnqh}Fz3%Y*o{OuVoY8sw<|8XyxoFs?OPZ*Wp}tX`mSrwt`Ql zaxOx&qVy;7PoL0;h$5#3&mrTpQ~o7P9_j{eaOHF6!0RjURd$n_ zIy9d1mF;%~^KgL9?=zr}VZ#+ix=qH@HvsHF=lNuTV&CvEIdDY;NLz*Dkvh9SC6a1+XJM04hmIeF91y02l#)e{ZRw=3V-fsS?Z)2+vT0nUO9i#q;~fj+ab3 z$~}Wqu#mugCY(`+@ge@*P8Qrtlb~`W0*PE&Ef5!cn;!$N0bsN3BQ^C;BCkjEe2RDo zuqpaGd;kndTp-hKYisLEBcI!~K4_f5dcn6drnukcf>5Z+4lm^E2uMhOy5$$Vp{Es@ zLpPY$XtimyDd6qb6T+4{!K|~ zFPfJ`nlDQ}@UbK`EKDB=j}VA+n)8@1$$wnkU+0qJPDOQumI1R_de3{Km|QJSF=vM- zeIp(YL|Q5;VER|>^E(iZ2n>}!@PDPI7E3kf(@Aae!jZ_5bK@sVDz>ytwaDv7y31>y z`{=T{678^ zdz3|8ae3mztRA)eXfx0PoH-t)>sR$-yD7ygzXdG-Sf0{f$DakS?(c`rT6e-;nd8Q5 zc&s!_7WlvIQpq)3GXrueYii3QvQ|ah&)iZUE!@=7grCgZUYtaB>2NYq?_whn^tc6r zyooGVT(?H)ve45T-1CbowxniG3!glxFq@4p3B&f(s-$Qh7}P2vGxaQ!3ik22mxbwD zUGwpKJNECX#5ciULdNH^*9Sj_bMSU=f&ClJ%}nUkDK*<33t9OKr$-FldIMYmSBJzG zFG8^j4R6|(&z9@w%Pd!AVpzU+6FF2*1e6MtoNNZH7Y(}JB>7&&*ZCJ4XTMqS5)2i@ zZyUneqd4DGJiCdFE;!pH5^{GTzqGhBvmtcOGGnUM`ks4cQ2Qvh%%H=b!1G4%$ts^+ z9xtyLEnae6%7FH5f8l9!Z|frl&3}u}gKj;ZlDi1?lf=vmsW^syqnZjEh-LBqRfe%? zIb9X))fr!=VVlvpLi2b#sb_>+VX=}|xYS^kzmvD~^73O#F`BNJ`5%FG zU4o*)x7AkM_4ePktrUXN(1|ATI(w?mwu5{NbgDm9=2ttY<2r7Tz*>Cf@Y#e%@se<8 zL;F=Uk!JG_d$Rk^drarXFPBBE?|%k&{l#MaWkbR;e@ZBH!x|i%FdklY{<@LVpVenO zdq(`yi|nwgVw3UANswrw`0dbygNB0|KZPEjj^{Rdw2^NCw)NYV1(hIeck#uz%8xEW z7Xinc)00hJSZ=KvX!D!u)kUu{rg|Vpfu!O{E|8M`BpF$y^TGMY)SS zJlONd%Cw1Cg?N7_vgL$X7FtncpmWH303&A@9n4W z?WfE3Y5T61du!3)LXvM--2>xnk%Tt~uKKR)3a+a}8s~TdUJRKvEhAWb*Q5$DpEEf9 zyV0we50=mletW+)_*!?S{i&KiY8+?s3+bou=!1oOXYRaL0)*5GpYXoCoqDiN^@Y^e z!hGR|^}zaJffi~Y_v?Aq`j!=%pZt%k6aRDg@Hx8qr@BoWU%<~MQQKG8{bGLTX(ofo z;5BmqF6b$W8yH+f;Gg?dlp2sPTwL6A+8|3VA}oP}JHW_-kd)o~#uNUt&gf7}%W)4M z>xM;;TvVgZpepavr%z=J4AOtFQ1PI!vGKlueV|vBQDI>pyA756-@AW za8?izH>NE~jrB~;o5|nV;81>jd8+*S^-s7r?qq+HLLY@(VAyo%5kx4Wysx+Q2Xh

MK?@jQsx5hhB>qcM%i!uDBSsCP+0imHT=?>U}!_x37NBf(xN!aYA{?hFgqtuJZXB?^WkD}OvUpQy*iY%+o@Xq{YCmL{#dSb z@H_8?qfyP7=@0D1^B&J9C}&$UY?#`eThs7N+HlX%y?wLLl2fNc)N7CGEaJ}gk9`CM zQdUPK@mxv8U94ws+t_!yDY!x=9plRTCk4EjxE1_=D^ZT$dd;4 zW9p(>W5&pogtodwT;gW(x%vA77l#|#-s|R_N;jNF0^GA4pT6GgKTa~>!!x~S``lo7 zyMZ^0h*w{*4ar4u>4s*_p`rKXg(KU$J2Mn}3$@KUUpjjTYrKcQTsf@ao)8zO$zLgZ z3N7pL?O%Tvo@Wo}oRgwQpiozmi`-giG3L;Rmjb$1=pXMkzq?)OeR4V?DC|o})|kMb zeHC{*peq|v<#*T*kWb*`mEsH(34eBgpz#7nNC*rQ8-aSUCJ@zY=OFW?ttR{S|HZ97= z{j$USy92hh)Q@*GdzjtbuTStiJ@7pxTdHk7U*dkZCDCy~D_|2b&`CO+xKrJX87aD0 z``7k*_Mihf=h!EkpjB3EAp>P$O8ad%jpqs4jAr$bl_uTWJeqjcpQ@p4^;lmFiY@Q# zb18HB+s1P5cd682-qYCYNecE?VD|~Mi{My592Pb}Sn{Oyh zlseUrD4B?KqJMYC(_tq_PC(+NBFq_PAx1CMu5Pl_PHxa{_|vzpV_PNM=Z$vn-TPc+ znqJC}&)ok*LW&j%Xh1p-=AP>U!$i(UJ;2F=pA>9?Pj59`z>dBy@<%ow!uR6hKDcWL z7z{jwzAdd;j?FGT1#LaLM*AH;LBS+#o5pC^j)8Sf@Z17DHV9Z-K!JHD`(bWg&nEvL zjj41@Uqa*e->mFx+S=M46-&I4gg*(UZ`hlnWnmHCKW*l9aupIR*FI#p((*17_H{vjAYx@d%m3R6k6(fc7I_{*`{c`XCv*5iyH;zXnb@j}+eS$e_j@n=tdTvHp}&nU9n@J3 z0r&NPTOwBzTk0#@k&%%BK|w2^d|Cy{DPRn9zCLUO;G$)4O@J9kV&scfI|*o} zu!OH)!d~Eu+60~9I!MTb#mA3F=i@!|wF3M&UKb1N`-*!v*Z15!-j`2y_4Jq@@-;fs zOqIR%=N`x6$QJsFPUM?Xje>)d1bh`9tfbpm|7Au6X>4kNwS@@U05=4W42D0K+?a0` z9;?&q1QGTTLU09MM;pJ>kR(Hh-vL!L%4K|K{xbmw9(+wyvN6BY#88kih+T8bM?T+* z6lgcYo;t44>Y`D;DFOW&Sa3K{$E~*fIj4SdjIUiLDkZpq+Y|symFj3CNOdiWYLOvS z?R4IIKfUYzgi-lNQMNA*)n_0t2i!~=tb4a&et{38QEkJsIEY4bSnDIFplCIcbbb=N z`;6IHh47n1>CCV}scnt5*?NQ9(Tg}a*jt9ZM8p~gxP7TCG1JoioSseq1DL(qbyCI{ z_d$&`V*)1{WK*_o#)(?fpKuAbx3|+S0=zs~WtD(?0vBe_@XRk2=k@<8Wn|IhnJk3n zP2Z5}3YqRTYSh@K9rD6H0Bo!3MraBw!|w(-`Hycq?yVIU5%eGkeO;s+7+FDb>rm-? zNocs5nwo;1az3;@p@Sh8mYRIFw#<8adJxWPubT_>Nk125?KPhv@)=$DiZ0(-7(fK!TsuGg;<_7Ie;^?>OEA(>2cCtmqI=W@cuEH;KK+ zjB4`!x9R%fh5Uy5Zzs9L!fM@*?@Tr8jt=^}>W30>hrsvbyf-5a8|M)I@v*9-2bKv~ zRfuSLlu|9FXn!|)xb%B=n{CYs3;G{M;S-kIjnRW`)y70|ioM=`t@3SC^mM$2(cOUn zyu$g`LmML}(p3&ICW0wRjS|PerIp-=brKz0F@~r2(a}jsR{@{*p-(0;*aRipz z?<7bjkBm{;QfHDEcCb#b&IG>fR;eU4+zWw?09`>+ezY5 z!&u#fZ7N5edH-0@G-$=@!{%=zRtlA%b;;{VlV)gtUjaxZ{k#^vkK-vT_bR)(3!h1E#nDRE7$3DSb8Sw?g z9H!Wq#C`Fcvb;srwJ9`4lShd_9>*5V9eyq4AylddUDV z(C)!O_0}ynR?xQow?vA{xeS$;qmAoT&z9GC*|up&b^e9c8*0r`x>)58G~IeDOCAnV z{KqCttWCqBK=WFRkp{hTllY-R9*e5q(Oyrc#9Tut$X*{b|AK|x*3RmypW(sZfD zGAZibjz*}`_0dNLq2HpSqL34?dj6VTI}g?08jQUC2(%si1#u{0#@7D#-r{|8g^UwDk^tMz*rQMR3JyLox4&q`-+#JU)$|w*O?zK zr~WO)(fKj6i~DCoQ`s0zEq5#a9>KBw$X?)4#;}Ksgd8kfo!ZS4-UI;|Ni0l>zCxOk)O_(bpKNe+}PPxBqpSH10oAJ*NCoV65hE)LqT{YbM}|PnfyXES0zl8imnh z#;mO_dIhTlvE#hk_tS&Ikzl7TO55wzI4%)OVF@?z#z;2S{|VUO73LJEoK!n+mRCwq zHwx)ANs2z1`tGh78Z{EH@j6oTKYKE2GQ!2<;l94U(V0HEMv=I2hs=qu8&>yd#R3h5 z?UwGrr)6klWOun+UGIa3oqx}8SRLcMrh&c_b{H9~N5w1uynU_1u%+jNvn$nDmz#^q zRO@{gUr94;kSn1-Yxi3>Q@G9XF@?>-)_o?iK{Op58nw5mT@!)P|Fx3wv9l|i-7aWV zYgyHmIu{AW#>D&r(locQkcy5@dJ+riwOV4pm3aqw&(t5i2U|Bs0ZQ*P)v(#+J}P1IzSZ_-GHvPbNq|@thgf<$w>v^_ zf8Oy!f6@y3HY^|vGW@gaOxO{}gN*Rwi(%1MfYlzvT-p;wCzm3WG&7@fcyz>TyYTYM z8DPFd*f?tWi2Y5fhWH$CFYhqrpm&3F2R{T_Ul5WEQ*w=-Gcht!3Ja&eWsiL0ovoOH zT!D)FvO5rVoB%Vasjr7tOw7|$0KVT=>uNkAB3T865Ltn_xjFbTt2HHOrkFnN{npiy z2?_b01QUb=1OQ+M1P4=rPsGPYk5dEqoDTi}v2Zef6{uKP5}C27ZM3NL${&*f1r9XH zNGO=tka1C8&ku3QJx7!ScYD}hgVGTavw(@}VFypm9(eb3^z=&rr9;dG!-sy%uU~d{ zETJ9u4-Pi^`SC88`UFAqfR2m=aj@VS_h(hJOoP$Y)wO1YmzlXpME}7H0lRzkR`q79 zli&Kj#P!&viHC%I`%xlwSv$yL`dEKouW_>8rWjXJI>3S52U;~MW;?l;iTu`l3i?mo zrz^`f=*szzp4}jQ-`b02Ent6?y@Szu;YcJS-;Fx3!q4=HK6Em!x>I`L3fxA&?fO1z zgB~I3M$(UGJWrJY;olDL53p`{Nnjl);^@c$AE#1lAXnxdKj0NFt+id|y|@#&ZPvQN zpEI8-_{0{gR!iF{B>kARw&9RJ=5?A|bq3b{agam?8xDoofb544P3b=$Ib~1WtXNde zvACb(Ep`SyX}jPHEgi~`MC@k$2V00;U9WrSZnhhnSL!xqYT1EUGy>G0*@<3QKOM8T zw-;()8dN$|6Rw2P>0NN@1GDC_g%AD>IlWna7rHE41Ll>(FiwG?8LUGBX+TT4zB!UD zEhD4UrB_&$T4chTcr|Is#n5adK9vTZs)FC_0jlu>DiD+!kJ*jUp#fkvY@DMEQPUee zkKUFRicLt6g}w{?PJtsv>?bIs2=&9ygmZ~dRM8DWJwyCP=ni4qK}kmk&}Llu#{E@3 zHdnWBU7C`xUPNxE1|t|3+OKrs+=;C!j{OC4is(;9!1Jy-kk2#3wG;g9JwIYi*fb7q zX)}FYM8;?PGGn!V6x=U>vtf?qBf330I6(aYZQqo))wQXSDPIT!4z%(RG8R=*QbIsB zOOQwi7UxQ7VN@XTMfsJT_mG^Xma1=RBO-!kW=y3<8Ev11k2T5>b~Hh~{BvR= z7WQBa*xzlo67& z5VQ67{xxJgBdzN`@U}T%bNhSUy3g6I|1#DvM%pmek@8S8k?@|wyEkdfcDfoWU9VYC znhJHiQ!l@2(DqsJY_5|Tq$%sM)_Vp$>_$HpukiN2Kd4|ARdjL3q5c7V&o^GB9fe%Q z644J+mRvw~X#x(nJ5~9dn>+U7$2-1J=3{w}I5|0GW)4lgF-Zd_KM7@_b356pR3-DR~&M@7}!&Rd$w&xzQx2q~y16 z#e}(cFwPuo5WfS510e98J^Kho%=SQ?H#9UH{Qa8-i~FE3T;=8ca8Xj&%$b|;tlnBWtT08t;pOdt3oH`PXEkRprJ1~ zy76*8e!^Aa9ck1MWlA2eZA(5R%2B=Gnc-_{-Qp{XHZ=1Y4TE#YbEuGg)F*$Zv%n{q>@)zhsCfOMh0q=OfT3@Nlv(Vh=OSAQHnCM3+RU*=8KQ1QQ8@~TomDXhO0 zSqz;zL78+CO^wAnnCbpCWGh7E_E;5&m|Ga2|O0o5_w`BU0(Jg$8QW(S7N z+}>v_^(@THYL@Kx3@_0uqy5k;sU+UMOg+@BYJKg&Z=q>RyXlxWc5Gn%amG?0U6=bT zqPP%!OL|v&z3hX>jmVvu=~GaR7=iu@k?E3O+#~~b?9dD|S3PE1aq&Y`U_8*ZT2g#Z zOx%f3c)y!lQ31QuVJRX^MC6UG6^wX>^_Yzq=PMTX-xNJkTTxWd*BfTBVa#4<$zQc& z&Yn-iz*;@9Plh;{7C;NS1_xbAhkrlEex=70(GlaWEO7S?7q24B^q`F4@K>*@gIUY~ zj$C||mb=kdnZ!^Y*}K{2ApzHqD-K6Ayp78z@ux`|T^i-Se`~mh%$MS}NXI-k&$d`} z-%g>4Wl3w2S`^D*5WO@){LfdA%7(|rN&>55z)2Az=A|9J{Kh+Gd&Bb7Ags3$8e90Y z9t(Na$UZ)HpneX0TWSCA&uU3M=VSFQoq^wSTDo%Cr>-?&YW4UG+8&5-s;RBj-72V9 zc=$CTfe8M+$L0tM5!iFHK1Pq7u}@pw@3~=rj1GYX^v&gn0r!)vaS{#*N&m;YNKlX| zIXREZl;XImDAiMc{E+xNfG6DNdkCD7gMQs((nd;Ik2|)4$v^+`tF1Tc5iog+Q zG`e%b#mZ?hp6C!C`;^IihXKv}xU?kZle=o}3;`H3M`x`BchKQ~0n-qKC>&HW&{^c< z=BB9^>%pi+YkmV}O%A)269(mz2(xM!3Se)D)%5o>qd3upRH+1Z}MqwiUpf;43j3ToBiSlOWeup<{>1qT$%fEKutm4Yk#=(-$ia}?Z zw&E*a9s^=@=KQgWp9ff_w4L%oA}Z=h)R{dZX42$Td&d@@3<{IcC3n4wv$xLPOxebN zD>Fc+LT>8jOY^ZRxP27qA-V~9OVD*HwW@+Gj+JQGkoj~lRAy*YVERRYQr%|BRqn8^ z5bL-y2o6SRH8mQMh9gQWV#{hz|2yQ*;N>Eq5UTu7V+HH==%M*)uH`c2G%1IXewy0D z!1rvmd07G^?8ZUquPdi_dt~z3zG5xIMGZgNY`TgGniC9ajnyl7t~=I52l6$>!otE* z$>hU7X4lPku$;V;9PCzE7kSe+iqJ)pS#HKRNmfsB=P1+33fDF8C8Fu zX@8OR>1@?Wb*0g6mG-pJw7FG%fwpy=E*JYWSF?3oQK8u?hSJ@?pQ9FBk?_L;ds1KY z?T0Qp@Hp_87{8D&cM~KP;BgpOKfLiAShp7{9=tsIkl+8Q#|A5FJkS0naw7EiO9FfP z0F^Wxrn%U0GurUjKacUUn^xwD&G&b=@{5hZd=QpYZNab-HhTKtW}jKhV0>P4LZayK zLtqbfNOSV@--8Md3I@V085dl`0j>BlAx(h@Nz%_6=H~1dBA=%AGX#ovzRhWE#B5{-j z)&dY$1SZ^+*}8iiR^stU_W;8$PHA92rH-c6z{#^ zBA^gE0qb{PH7bSpImaCFKYP>Fp@89+0k(2yule=^VwD0uPrzwR00@S+QewXC@nfENjLWKF{NE1370q|2hmijZCd3xx3w_?3eD~Q2atlYd2qtKXRl$9P`3U1Fu z#iXU)>X`a@)P8z-c_bva%El*(;%R@+e=7Vz;0rQ_{pBu2%I)YyY1oiKsT8Jn+B#*3 z6p~Ie(#rguo-(?1okFf0F7EuXB(3Y!_4WFoyMXdW@FL@=MM;k)y#%-eOemn!t!t1y zM@2*sb~pPDnMO@X>Nh>VI84ftll;K){P~wZe>9x;=j35ji!z4Ki6HRR)|Z}>ZL7;8 zm0PWS^@WS=;`IcZrtrS_E<}?BbTL>G*@j@r#xTB#Zc6}<^;KP{*h`kOL9n*n5ui?KFgqB4pL?}+ zlK75iN_#by&_}MJ=TlA394e&fH^?(r+DC!d0Ky2iebQo?6vBv^>3M`WD}_M*j2 z7c#?!r)vpqBiBvXEkMZq+nyNAx)PO0>j%%^2qCK)*DVus`y8vcR5UcQ&AwkG-Tr{y z)xf|2Jjg-zQ3lh%ej?4wai72^?0Xa;9HeXWXnIIzBG~;f)|hCclX)J%VS&GWJt8#; zHce(TdUyvg?%SraQ6K(((!v91nTequOr&??wH)XMD6cL(NJJY0S$+-G4@H!VGJo8% zPkaHFUglVY`1rqPX5_%99Pav}B4!{tD1-CB94OZJgMQEXd!OPD1H>~ps(?TjKq`eT zRh>A0$hU6>U`r5zdLNJyKt@>j%S11KL!Sp_y2D@*XpDD&O+z?V1VC5Nv$<|&#p>*^ zflG|E*DLv6r8#C&??cp^f9u(w=A5IV!y-G9Tj`g5{rqGWE0_4#h;=6Ba&sFCC{rS* zNGg!ehVXw!N;GuKC5`d!VK$!FZMj&lx=tGW`%71$vbR_`^|F{ltkH}5nbaQ$@~!_q zbP(f7@Gc=CAx_x4Nm5A-&0e!JnBnbUvW&UK*z!sA%LIVe^L}Ja={#(_rp#Ha4|xN* zBx++NF&2BGiq}2d{bFKb9{pDKlY(Zy>C+@$_g<#t>^DW#LU9Ldt%j3|+=jucyKQ!+ zIPrAVr>0?60KzzM-S|CDEP(+$hf6Ti)oW5?f15j&HiK;r#($7x4!exQ5R+vhW3@fv z)YCcb2nIHB9A>z{>FpoO(Ph_rUJU!$(>!{SoB9!pu(`8{NgIf<_0e2$&NGg9FP=zj zt!%(6AQ$G1zP@+WtHVWZA_cj?r zT6)tc6DuE>zB5q|tMeLbNPh7SS6BCDXHr?((=%$~ebqR!445D(|BzdRB($-h{HP)A zLc>)D8)@gXyYy20Us_&@ihl0>6_OZ*cPkh-9JWqZU0lG)<$nMM;_$YieA6f#%_xwl{0v%LJ=5|7{tw zH}y(r>}CFU^#w`ebTeD&57}pl@=(*0MLFJXSSrNKxl%w5rVJ3 z&C~k+g7&ep5-wlTMF2m1%*eXBx*Df@MqctLkxCbr{>Eej52D16p12^>?yycwOr)?= zmQPy7B+j}5eu6|0c)w9k5q2O0#VGEce{}}i5f&PKuUD`w1q!ktQo(r0`ap;irguS+ z+sx# zCz=oc7?EuH^Apl05QpN8+yYL~R}Is18~K*N<58buMCrPzC<=gNEmp_{u0SkLHYMP0m2wklqdn;WpPVR}b;T5|!a31E{_ zryZ5H6g(fUT!G1fsVQ$IR);yNE$zC#_fJ>#{K*_`SZAbuem_5TWWc*Nzc=dY zl3reovX9+#I8iF>JL3;adUzE`)rC59czN+R<-Wi81i|6C%u`cSlqMhC8lB)jseT!lAK8EMKQQkRXW;EF&PqhAP_!N*=WRAcscy2*GJ$UbRzK zPfip;ah#-^ujr=Q0jx5W?zHw!3j0g40ZL3_o}bW9XTGY$67p0B(3PHn0Tw@g&dvSW z_(u*dY4571H@CJ9VOUVuRD__I(4fq$MQqk9i}3h{i6lSHVkAW zFm~ObN(j>~p1{M#w$+k$b-~`H<>DIO{d^?Xv-~`?S-1-o4e}?zSL5T{zE1EnTx=gH zXzHNgL!1&wki9`tO3A-$Ag2W`%hmHA__rsDW4Zo8a#LVea!VcYybry#D;~1g%PuBfE)w)LnZnunB#7?-_}C=J;*B-nI)$=&ycuz zn1j=^X|}2KnD?AY`ZRD2Xze zWJY=MGrq_1`P@j@Wc;7K_iU7?a#n0l^#n!Yk~<9E^~ZDKZVCWl4rT8F*fNpFuCA2V zfaUWqYZr4DD6!a&AJc{pKu9dE2o+6vJM}vqorows6%`)1l6F<8-FR2y+dn^0@k`=! zqL-JKZzPU08;gw~RvAxw%wBous9sIc2ZKu-ze^Fmdhvv;5ssVWt5-NgM1fEmFUnm{ zr>kvfSXsm2WFA7`k<2CmK0YuCwX;A6|n%li)R9L81vC7_o;ian$qQL{jsvp#!p23Nv| zJ~-8P;E{zHIK}FXCr>DX7l$KIQpv#vtLB?T11Mw)k1)R?!3O*m)*cl|fFu#)^Fbp{ zKU}Tkpe+No!yGqa{oxFJ2*5XN9WNG2yoIXm@yf^j3lP~bSJN`t`#O&TAkX8x^S$DC z1YWH9VLlUOgD)V{{QL=ddGv6#@VFkNR&?=M|t10KE-VE95?w_);IOb2QRDEPqYpv{y6%(SS3QDF3ejyHW`d$ROB3P9rM zPuT9kCMpc;pw!JMEe!{t_Glv`G<{?ffrTOXod3CXc|!~Lr_2ZqC=}>=Aho6o^jT)s z*3=vvQFoD$rP`nV8@~cx^T& zIj*KgcPV?iP3)59w%(S{Zl=C2Iw!VabD-de`+Y`fetQ{#U!1=8z$4^@_#M7anp(Zu z_O#YwWtYL-|@ zbz~Dj)4w?VLW!)2cImtz>O^B{0PQ3Jp+}mQ?P-g5-B4@;Na+CBcak0L83_bt8JLvp zLPjm;eK7Zb%xg~x+X1kQ`nG&>CSrR2l~`3;+THru5WV8;{QPZxoIZP3wzx%UYED21 zVqn6BU%FC0D1;Q&hXuTY(B%$0oy{r*!2mJpg;&*I2NGfG2+fzoEhq$IRS(3HlfyARO8-xDReF_d(D8gwq@!B9oxp02&VMFd9HK!+ybGs=4Pb zyG|2twAAvZitpnPJVqnLC>VC$`TAH9jGs8SV*l0y?&_8}q z6XH>{Hu!(nUNtNiAbCeBnpq78jk#`v0=jBcEUZ{Lvo6k0t2Ab#6_s$8gGv1GK1lz7 zbb{Kj29MA8IxC4@?w>8Z1GLML}Hk>1bq ztbBSES8}|bpa1W+z!oo8%$WQ-f=V{D(-!yfe}jpbG)IbB?;+Gh1UBhqf8jz+5(498 z?5$UKK9EG54RDtZM=m?^#YJWp_vJ&bGLR9kRaAT+vc|j;_vzETcm;ha!NOVB{IPFi z=7R4P{(+Ln+>3sZE{HaN%-o4w1th7^fiUVoEGLHBY*H@UMdH@AD>)7N{gvibD}_P? zR$UXOy5tQfmpT$PvU_Do0}`T3VHc8sSw{-!YVifc&Ls#vppwT4xUqo{mI~4_0Oq~Z zZRyu<{C=j!4tS!!kU;VG&-+km`<&xY0CPe}t)hvGva*jEt0Hhc`j`Plbqt_!nWOQp za+%kIXnXh7=gHk8>JG%NL%yiPN3P0)-_=ZZnLJbyQ9ovUEo6STYIjM4o;Eu!)($X7 z8Yk~0Re|SDlz#7gb|Qz`mzKA-=Y<4>w&Y^>qs-J)RY4WaCx3Yj5Ln)+g}FHZNid8SSJ%d?EA2uxLVKmr=qv44yf$cG zz5kQ>+MaF=OY+e5751{HO)_#_zY+qA>-gp1vVu2n-h7w)p%=0{x~17=P^rc1yo0d6 z2LFdg(9;53Rm`*G4JUWyOsN6Qs9vdx&Zu7fL@cXK_U=$ql$q(IG76xdcBJpCCK3BC zQ0-vdaI7YIDn-d!ah@dk7yc(ufIxU+cg~xPJK5L9M#+b##Xf979~%U3uoLMn7rp>f z@V~#=p4d(K8!w_G6rquZYTAY#VrJxxNuMQJd_63L;{pHTN;Fq9(7c!3T6xW z_Sf#I{J&6DP0P)7WIB%jeXbp13NDeydfb1 zvtW}S+~H9{+ntt|*W>GGZDkcb74gx&;l6(;_rkh~$<^7L%paJrHT*+egV&7aYZ)oT zf`P&%dIibqP+mbOu&P+XI8P+-pxl}Nv$7xLnL__6{myqri-_T{1_U_FPULF_9|1c+ z}bae?_-^hTaMwTjMaYdlQN z?~z$Wb@l0#O1iSNQ%*9aT8C3b}sd+j*$Hd)TKApW&g6sdb|TqvZ_#Xd|Znr zwgH;T%FBBQV-cagXA3L~=yVy^TFRWaS6-3SKTm0KLK4}IyW#`g22{NNY=KPI+tsIw zRMQ+=Ig-#L^E@kUTeLm9@${ZQA4EX3i=HiJ3 z(<`|L< zj*H!n$J8}}4u&2V?tIYp?b%yiLjL)Ws;U_HiG*%&LxsO_S1ZsM3dA25og8P|JTL0e zjW{WL7Pu;2k@#{>wKkv7j%iT&t*uXE>`B?KX{dzW2sy(7Wg=j_qrT_0VS^qn$3b|V zB%cy_O1_Fa5cE4KC?ls#oLR)kqa{~_txlNVi{qD9sI7XZtc(W~60>;Xq@^)z3^GD~ z2A1&EYl@`RY$0(z8F>@lCrRPq3g+hY04J@b2Qo)Uy|1)Wm2I0g<*2J*;G|FpG(D{t zq7BWKpk)}retq(WX)^j$oV1lLyYg}+^d-&wjU+D$b^$rfk?$Jpb@2<^w(mv<}SYuH~8;uc89y&98?L$1J>WeK^JI_SW_M z)O&H{%SkzNZ|=?cZy`&B83LL?;=kM$038;41!)^%L4(@ zfqQ`wBrOl)xPJt@11URDfcAUrH%h|92Vp@#r1``46t#T34^R-GRD=$N9nu2ezC!Gk zAWT0T4fV_%ZV~5Uhk`-+-OG`CemV@ArYvZOwU!o7ev47iP*I!VPRJ~|0o^J6d=f7n zQ*(2E$bpF_p~Z|Z!~63{(R$Ov>?)(z-}5I??iQZrOY{WTX#^V%f8MA*tTBIY4@V9( z9r2k3W9EomR_HCH;sTO#KtUW_8EZ z)R%p8$J-qsTKXL+jZ*0n1zJQgu`ikLml$$R_lIdD-V50a#fC`S#CWX6AEbk*87$$j`31Mg2BE>T$^$ zHK@{HWPazfI|H2xP@J<2x}5d1_BnAEuPwailAjG-jAMI=C7%HDl~Y`70)}#V_sR~d zv#Zdyh`7zoa>+S4qk*W8Pe?ci4z#8&hS3Dko{CHPoi-bk;ji-%n{K)jiG|AKTN9`mtcrS+^Ce-iV9 z$<_E_=tV$bDs4#On$61Sf6`=5m>;))fV?z&6*j$Bn-_2`=2zd3!y8V0%k+D04$7Za z?S}Ww`8q%hptUN8b`hR&aK}a{s{s8(sD|Lwi~slEjN^zrc&bLi+VJ6KcFN(P_e~`9 z@$jMdgVQ%ahmg!21kEHO?f`gc=<^Ho8m9`4XBYk41Mt;wd(Ej|tc1<0$G2ls9?p4r zWSMAbjSM>}#b$;x(u7nNT{`jf8@~+wQU21RIqlB9aWAIX{Jd?{=kqlq6kKC_`Bu!d z+;=N2yXwlLwSb3($W|h5>zzkfqX7%B3U;tlK3E2wV+b*Cx)xV0b@sFA_9HlAaPvUz zGzJzA0!qwrD@3Q26t>*UtO~0{ei&1W%08dLi%W@#Su;=)FG6LWSWz8OQnlWQuTyM( zjP9qW^%EMptLuI5b(m9hJa#K}yswX~Nd~{2*}L6?4H+J{!%RsBrb8aB;|z3~ug?Su zAIe*~+^c81{`T!5U@bZdM$s`bGVcIrga`la&DA*!sZWWBJjN=k4$2&z#$zg}p?2A_)bs8Jo?p0-<%@7H;l87c*2(dYg6!V96^!0K z`PT8h6T2qbF-;ctQmmddX0CJH-99EUfaw0N)+_A24mo)>63OM%PP+o z9;$TBu)e(=))Z!cEL|q;FkzK0!tFy}C&+0>5a;LgH14Z`0?_{g#|2(Q6buZqBPaU$ zc3cG5GM(b-)&QaEwB|CMMPs*rxBr`CDcsW$OCwLg6ntCtY+) zn{aCPA6{xz#Yf^s&cqL6zjIODYi0e@^1UnBaizVqCWJdK%ifF9R`s*jiZvgQ7!;t*=bjHjXtO>#ao{`cTFmO=jbtit*Wpt}QL@u_noD_nAJk0K!e><+4e8 znPV?DVO}XigBEr8?cxef`U5nyHdqrNAt|IQ&OsXL?3fYqx^P5BfBY=`#C+=4p@&TR zl=kI(a%v?`x|+*UX3VpJRlBcPWD0<}SCCgh-z(3KyT?Vi0`Op14^?$X0WxQyp6zb^ zXLJENAMi4KA0LOJ;2yxx4Vu;U&TT?FWB0 zhOJo?vVr%1wo|L{PMR=SVvavFoeUl9zHbuqISX zSc^@QkpLRb3*uWxkuLHby&lfQZ21Ia9zy=?vdvV=i0D9JMXN0p&KU0;=Wy??r&A_) zds6o+owozNE6B<&111qf%o_pc3-muiz$O5tLBY-*2^Te#0no|A;Yyp>20uXH#!6lKPT zRf9~u4dZy&D@&qmn9}c13zHM&v%T_DnM2Jd1aDiVC0VBX7V=scy-DZSQaOKyx<+c& zv0x=wZn8SuDQOLAz1RxhRVx{*83#$8haLln zX$N45;j>4}pLE*X;8q;2ylUz&2;bpFV_Jvv+dXHiFa7SE+Wf-}{+O#*Qn`5C>eF$G zB-kLx@7V}Bi|T#m&m)4|qd19>sld`}WO#TBgj!@dt{7*mVBT*r^MJj$*J^6N;A#MD zIr4#~k#^X;@<6l}=HckCXGZ){vFg2YK2!X!tF+x_0K}7OqHFi6Ek;#bqxF#kzLnW| zcdR0Hwvx9n_?b~MRQl1Y6TlW*EV*O{?g~~)+HmQNay3^jW&QXuJT*l>`I7Lwy0Y?a z7#I`P(!t$!Q}1z`Ja>NX%bZ6z+n*If-Y)5fi~m^EaOttJz;*5RUscKHuZm|nsM^qd ze0|t$|8bCByd|{KTU|^w8ey1W6Y|{%dnS7PrMt$M^ieD3dv%iHTgt}(lV1JjckmNA zyPu}B)T+T_9-nRL5@*=v&RXx@VlWd^g#7P;L$?{*A*l%T#d|2oc%;IKy&wKQBqH)z z(A{ynjny%Seog$rCy{G^5@($9ONlzk z?s{<~_8@n+{-%4-JK|N($D4a7eyNI0aUI8)3zXxEWb0FQZI7`@WunX&xrLfzE|~X+ z1@+&}|D|VV>~7z@#C!LGb!}_@sC&-3{vC<_QJ0k9q+%3#V?17py+=cG@2y=)w)NC) z8zY!urlt9G%nxMK+~LdB6#S~qtUx0qqc~H7I`i+J_hfcfmC5waL<{C$Y=+PLq_P=# zxv%2x9~nFBo;d~$g+G?#)wyj&4(WOjhc}jTaMo9viTN8((Dq*J+&T9+iSwo>M{H9| ztS2!<{G5#d%N9Z0;W#} zyTk&_U3XQ5&C`R%RJLR zUSKSNv=25zI&@2JsnWQ*FPdjt&u&#Z{JqB!9A!K)Snaks@MJ-}ioDMB0!!4yaQIqR zR*S>p#n2R<9ktnjAld(yK=58wU2+fq%rNn74;$ zMoO5bLfYvb2;DObZo)!5TKL(VpZ;Eo;?brqN36i_b^8V2GK`V5T>oWbcQxNp)O$ zAa`>!jq7B49y+m?4{r(ad%>`#3G~je(i<+&>4dKehlLxgGr{B!iyHJO0QNJPMMbe_ zjKuEl*BujB(8G2d$_GBMM?yQ!1|9U$T46l{px(;LctY3F-%UluJ+OWN6k$T1VgxqU zD2ALbG6%_}@Aa4S-SedMU~!etmBr2{F)8?N;us+oED}2J@56PqBDR;-`rmsCE*>t& z8tY&3nw#&R^UuQUWNfWcsNhT!j%?ciX{KIuH?ukMIB4e!Ro*kcC%@pvhSd$d;t~>R zN-Ed`n!dlK6@`QE(9x41)dbxENCqJ7EQP#GQ#0}N^p~$Df2VA>?yBh`rn+=!3;sHM z{ywfS1Pr~`OIQzgzMGspX9@Xf!%{v=4FlmMJ)h7<{pd98AN>Ck>~4T?&$0bsl8pPf zH4g|{v=>wY81r>wqHcetdZKJ#Zc$eikit0znuc^>c!Qxs%F^A&bl#K2n5asWS<~h(b0*Cm*2Ar7WstJKnZGCJqfGHiQ}f7jCtDf8 zqQhj9ss8HKHk2NOq@*DT1VVl^ex+`XWD(|{tBC$Yqz2d4?H{H98df1 zq9Qzog+&7Np5|>ZxF{Fd^t`?!RFU!x(Y<&nqSF-@r|GtY^s?1(?&FLZJ?2)PKB7>2 zHvLD?Domr^5YzW#Li2-P0s~|pcRa2G4$o+O_-rxaj&qhneWYK$Pyx z*o<=JQjr8wO&}>*hdcFHuV0qM{RB%y=lJ@Th{M&V)rd}p%TVTxo+9pe;1|vIcj+Eo zztpMw$UoBhb0_q>LY42`9~UK*(%-cYuTJCF1(YWi7%%=EsdQ~q(ydxCMZWcX2snk1- z)3!!^*^CvIV~Br)NQIHQEyRS+;&V zb6f7N$2m1SAH==Rk4h(Mzu}znZ%6j*n2q3vRFET5^!FTX?GOJ-6kt)_Lo9+S1G z!HjpcnB*?oYorZ7uUwQ>E{&!v8Av|qsvMB*3+tAc6swqje6)af)@|J(+Y``aJnXQ@lK zLxO%f-^XVOZjYN?+YBB!V%NUl{6>v?sg1LBL4=d$%-ouoW3bA}b|QXc%`IfId^%x>qaFkFW+?*=mgfkqbDz%zip0f7R|P^)94D)A|4m1QuoJMBYV^Gf;~9O#BIkjoc#i0j3}l19AYYIl=P; zMgRcLTxkH!N)LF)ZZyDFx)ZKCX&6qEk&$(!@+yyEP;gtuFIW#+mZCcKE?$P=3fu65 zGywM&%$vnMG^?IGPK*DzU}&ZxHW3vX`DsUnuKJ1VzMSNlTFOLUM{EDD;*ms)S81|C zUN{Z?0!-Ld!7)}m1osFPcm41GrzaIxw7V(4D5z$MbEB=*-NEM9n^%RUnF(faK!0(6 zT3`4~t(})?GC~=(1Vjjy-(`OcR~Cf`wW)4|IgIPG_4W0M!Qc;8QXpGHYkYnvK1JPe z46DFMP99yK_RUo1Uo`$Pu@HV%hob8K$Q}SQi=-N<3($zvdSSsQ0YCzeW1<%w;7xys zz;oo{;*wc`%f#^4nJ_OZu2T-3LekCZF#*;HImFHiu z5yzYQCvz~E9aw|f0U6paP?n;nC$_exTe>d00vQW8Ze9PRnnO2iPXC05#JhGk{!fL& zJP1*g3*8)#2bHe34fJ+*n?O%9I5@axnTz81a0xOYs2y}ST6Kgw$7@I^b61Q1rv(Vj zH_g?C%(W%TGZ2GlFT6^8ZNa2jcT7W&%gyrM6Xhm4NUY@@q-QKZs^|0A=!##c#b9Ck zOuNY%pNJLCY^xe-WU1bCrm)Vqf6M7QW*fEq<+-V?50bk~_mrN*m5KS(V0D%1o~gpz zUu`@Cu|zj)F$|S#B4gvdkFjh2j$AV|$l4;Pz1t9l;lBwgoZrO+$HX0X%In#W)X4Tc zR^j#QLMWKNEV_mAZCcDaYpXkYi1b2Pk@PN)fDtN5p|VS(Og4^ee2ey}vQXzK0mwSu zRkbxfp8x1L`Vbp4Dcr&=YsFUNye9H=VD7ueX>X0XFA=K`JEEG{#V?@5PFJk_jc~qh z-%VrfPyd9-IzP5KUL>5-P`q{F*l5}e8~np=+Hr?Pb~EFMio50_soeZym0yH%H~knv zMW4c2mDHx@nI5@aUBnwO-4M)@CbZwNV11JM+Z(anj`%P-?2h+b)Q)(icV=%Ee{1A? z+~K1uvMa}9(C+a`Yc2jRE=zjbqaW=T=esqRVm^n}>P?8FF8O4>PomM1Z`$jVQKRb&Pjunen?*ucjf-P4ofcL-1%@Dq9k1(s@`A=ZWgh zW^UeURqXMWXlM96Gyj&5Bvj9jP4<5(t@V0dNx|*AM{~arw-<54WpiAb**4F&IU^^w zIq|24o1<=A{Elp+JACKk7ZknGS#jLiuaLY${QMM4!^isMXvvyoDnOW#$`=ACJg*wI z-AkX<-(_@#BS&6c?elInOG=4@`@*f^#($KC2L2!P{u@^KDCHn137VsZvhU?{3k;kK8O1x&@X>&)|wZX!^@&V8w{Po^k)2c6P3FB_sEf&rP99{K(#SFYK@f8Y}KkDz!*8)jJwA zvwVCzyYje|*RJWbo6U}HVs-Gkks-OZ8)nxr!P%PT(a3bBkC4|f`Nyh|zm2cA`%@>$ zsDnr^a7cx2u}&eiuS9hRGBeEteBE9Pnbmg4oq4?`qC>yC5||dvpOmTns8ejeJdqrD~IaJ{EXYQMfx!&<7=*>h%gvVX? zDlH+VHN~g;L8C+_ni+jbiZ|?5U*MtGrk-y4cHM*X7|AK#);8M{YNV>Fir5teiOA|X zjCH#CHc60%#FB(9j@LN4sIFu7@X*OH@W(K=kQqFugCP#=I&{7FUqj{E17$UO$n(Yd zzW1I=LG`A^o07wFQu9y^SBs9EGpVu$q6GnHn+mETprLN7LlCRjs0SHCr5Wu z)_#mmuNIDm2*+@4w%|TI&cn~;R%>g%#;A|7-$cEl%Po=7VE+8_aL9D2%N|&7Fm!U{pT5wn(aiNzz!{I$g(e7)oTd_6;mKs1WOtN@Mmae7K^^^ zyHu{DtX!33eeY~58~=+Y6tKKCFmaWpnpfrT?LUF?#p(2%etP)Cj2eC3HOYTXaY*`zYOy-+;C^D@ryA=L3fe;h_@zM3>i)~jPo3({a?A{RF^F2v2a$E$pWhS2R zSG}b9d;9dFWL}naNGj%sHOI?YXGYJ+hW2^h(P3GXh8SA8X2lKvii@@3Nm(;vXWKLT zyHU^+$A-di(b4C7dt>F`*`|{?@$0K)cA|5=zGs4+JnAa0UDV#+A|i>OTkG7S6p$`Q zIhHfzS3J-DG?^axWdq;d5m&1$gMKCZgY0nVsSkdYIc@Vg>o50lS<35;1@GE^v}h;` z%;A#l`0>wV^(?CHfT}dPDfjbHw1iA8Y69{ zo3>Lc#HNW``s0Wq%ID#zjMk`YLR`@LB3J-_^R^1;tbNRGIVD*yq^6JvNSw@$O#Ep$h$A2SazX!QimQr8=mN zcl(vD9qEMS3z5@bPrDWZe?54=_{AR9_^;=wV8G9*$URq4^ztg%&;k?SEk>Xj7ft5H=YZ+HU0uOo$VM7AyDkpTQs>SB&OVVM#zbQJ z7|t%E{wxB5)ejzQ-}xSwb#~})F;Pn!Ag!zY`*pL?@`Ol|hUkErm_w6)^Q>}Ho^O%$ zfq7ERxrCwYf#{HPZ7aVlm#Z~0IoWkvZBR$(aBSDO<=AQaT#s{?Tby=n`!Jv<@)qgm z(d%Xu_7!}?#8Fkz;kIq<=2aWE&ff=vj+lqy0vcw-evYrK-?qRdBwP+@o?678U*6Pa zai^nesy>xgC)FupyFI&ZpVDK`cSh#b>~-NiEi+O^Wc@&PB&qCT{+WLCu8xbW%Uv-s zKkCQ=mIm>2-}|#mzQ>6U1R@O$2wkBK*Xo*d(1ziXaV7*GzWzqOvONn)zZ zOmG-C4P5p&z%j>y3 zG2yNA^9RmXCX(=ag>as&&7epPoF6zJgj|R@;SpX}*1fr#HT$QWhUxyT8a(ydIT3`P zSi>g0?zyuPs0NvO_UW}}{QQp@1JKLi*sjd{ji-!> zS3_$+{rb8{Lx|c}Hpywu79-_>$gslXeKX(J0w=_QsQwgT!nw4$AudEf)BzvAfMZKnj%INnQdQl6_ zuV*?}bX=EaN-qpU;4dbVEe8DaZ@E_SGRS}bKI%#pzf@baD|I#g_2x^26Mtj&bCDmoTraR4+O!zGBryQy0vUk9K&J+>l6?+6+9c`Us&o?1MkSh?Lzkx!^ESfS za*<_a{f?P24)Ztu{rq(Jm?M8c*D{q2iq2SMwctBl4Kp~+X(WRI2GVeGeyY=C`8A9F zSHg(p*0XbqA>pjD8;p0Uq z@krI(Zim1^wWPiT57MmtDZ(BB+5wiO3{uvmVG1AR&7;aLt$kcnOE6J~LyDGw--E~2 zUTP!(8<&RrV`{cFpS9c<-H38OSpQZiivIGcWAM0JfM@V3r{N&sO`9AROWwSBt@_!s zE=s>LJbLE9SRSFPt)g{?%`tj0gX*c+2j21V!^GT+KKCmR4BugRw!PRBAPBVgBa?rQ zVVB^I^_^2zy`X4AP>FexnvYU(F<#Rp+;^E^f{mTho{f#Uto8559x?5_fE2sBuS4uD z7LHQ>nLi1yP%3hj3uNlK`iXHS#`xEizh(B^(D-tK<*ZVCz*IM6V&D9JK-?)X+JL;S|FM!wh6hyr5TuV344%v74ZYQ@zPIZuWy!nq4m|{t18P_p6lB`tsZh z=l4x@Ruzn*EA1kY&g_J11k>y93fiAIY`l1RLq&Ba#%d*lQLGUE-;m^$!%|9&tRnxV zna*bYFxRQIZ+@lRYy#u5k!Dfv%GJdei8Fc9aPa-Z?f=yf-}b#_;QcLRi{i(Bz2TER z8A`nEXGX!iZ~2BYpXY@U_=3BnQz?VoVqNz1%jeH?@r#10geW)7KJ%g86+hTqRU=&r zhWIOPf1iqOTf*~SXBJ9Ok+tqh!SVVu#;o1gv9o zfE@S)3NLi&12S(vprb(KAti&t#|B^#_pj~0QWxAHwkkbuz9}q~7mGbi8#B}tHZAAb zqxlwbRhui@g|9s96zlmnL0xh4Fib5QNmgm!9R|*whk|LQoc0fs{#;&Mmo(>}5z@>s z?=ke=QEQl<|Bi#nZR5oKP9ZR%RW*1&KIg$X>C-neJXEeJv776B)#Ecx(k1P@ueWM; zmExgH+jz!y0Qn6MLXBNp8W9Kn@m zT!(*1iW!^uVU-5$E;yejQ;g%{+B^?8p(L%ge$fs_`vm%Wf*X5?u7LV>hOO_ZmHex{ zXI|EPxQV^9bxJO#5ARexk=)mf^mxfM zc+(JxRqS^0!|Zrv|JMCV?x-(p6s31@*%aynWU-XlCq-t`2F)WC%qseOJn=GS1CDZK z2TliGP0EnYDlr?>iz`&oerQD;5!a_>%@5;6V3*pM`Z6w8brN$4#W`PeSt-{k&h5*V zXldPZ-ghpjyi`Myh;()z;_RNTNoSrO&}DcVV*MInHZ=VlHe55oC0+j9DJrqZUgFV6 z_AvV%61M^wq2;#FGX0m|^GP#H)73O)TP>>Rddy60u^OI6f0zUY zSMlIYWXS02vE!d0E#?xSBUL2-qlfSfo$elRNPie9Hm+tVaFu46pFqd>j*8COn{!0B zLe23NoFE@*x$@~h6Aqp@Bj@Ls_usokuQ3}8db1<=nadT=5}`X1_M&ev{-Tw$q(6--8|@ksqs@ms@$p zMXba{VzIJU=&@)R#IDPKCj6=L>dPl{oz-`r_rGr#m6~f&=WFdR)eUK`X?}hGIlju^ z&O4qW>>&L&!5Ff^fzcS(HQMCLrm34N`JJ4$6q*bPk-HwPbzR(hTv7CWEUNr5Ago^M?67S=e z1OiugxT32>2Cnr2AzMdBQkpM)LvDd}-7$VdtmYH$%cUIo5seQoZe6?fGcK5KL}q~) zxE~DAa_vZfv{>7Fe+c5+?)ZUzi{NKzdR3JGY6YVm0=UbTf3hPbu1m?ebf2lofY1z94>!%;(>svj2O zPhY#7XzKopv`%dPQ3wW9$7%0FOrF0QPxsY5x$xdq0{v>bv`vN%J_h(FH+ShPwS#<5 zr{^8tuM5Flt86G1T?D0QW4d~d~e?@q00Z9B7>O-+cQOtHM=?Es-<4%cFpV6Qd05)~}pP zzkGKZ@a^nVTc|G_sH=T<)oqh^Z)XtAR~`h(S6XXd;blF&9VN<)Y@gQYneVRqZL)w` zCym<8{S|u}mrA{Ps=mFnwz(vx{-}Mlym);S_v1ru8(xILV7|}0XHkg*WxSr?Q!Z4KY;rg-i7E+poc~A)9d=wg?&}HIQ;>+YZL=Fcr@&cmToZ5FSKhTgmlQhfshv3S zV$AUQBo&d;^v3~b0w+48HBb*#jj)*wtru-l z&@R`d*YW+tA(xrEx8*y|PCts`zVopzKfRN=@~wM7oh;V9X-N5Bh|0Awh6ajFU((gB zchg<|EwVyihC|P zIK-^5!lYaYoH75%gGU>c#5*s3By?x<5?6cosWX}W-W{3R#V*>ENiT2jgiSqsd$frK zeB)VeEcloU{)K0Zq5wYt716Wtmu|A@>tgzk7_kOBBd$s%FJPXx>p$vvgcE~RDVk%* z#!D!n(I#5awm=-RuK38V=V5`4%g}2W9hTWn{vcEVGENxp1h{36QJt(CbK&>cuK?ai zK>;5aAn0?Lm>5lU0h((Vwix^iw6pM~Xs#gatnVnBv9hwBot^P{9kHqFxK?WULG>hNlwbYl5uka9JAtz_jPq&g5 zQ)vl2^^dTlCXO|^-8X*i1(UCEppXp|xI7_mh8&AW2zu@iW^@zs>Xiz;dZI0pio&zn_=65naBw_-$=% z3+9el*9VzW)dW+~Q;w+nCcDV)Te}X!wm*KHtQjC=0ighRBC~JZM~x2ayQ%ls?RXD0 z>yVLd`7v&!(--VPd6x?)#hok#0UKMFNo!xX+i@5CA4(H*K6)g|l3Ihf9zC$x`9n(J z*3^2Hl(G>r`CjL$u{$ov9BfVZD*K>_tDH+e=-3;~Z13$YfN0HRp)E!snZxBr>N??S- ze5HjQrvHF)1%nQFLRD2%#C3G25WW}u5I1BDz*2~Sh7z}N;Io4_i}(ck&4Lsh2=N22 zRxtQQ;q^l=>OgP_qa@7YQ3wR6Mui^(KY1#iAO5n zbh<$$1H*kY2*Uzy8ya5)FuaPRxew?p2N)p%_!j)da`1GbNneJ)2*Jo3e3Rl|y{{;^ zH$m-*mX;_hN9lOpu~D>jf|Wp4ez)`ewJ*Q=%WxjC@F?-W4IHZ)^J#6DZGXFTbzyh4 zgo1)1VQpo_WyWIH)OPFV=)Z}-NxDw*%oUPt_QX_^)z{?Lzp@Bq9JJurhg7Jna19SX znw4bKmGB%@s!BcRcgYKqY@K*4I>sx;o2)>|rypk*jj%g@bKdpAQ%6e+3~5*peE|}Y z<=`O!lIYz^U>-u1Q5@IZhqv}^ny{?R{f8{4gKn96dd9HlLulfm^fNJh@q4<`i4l5Q zn0}(2r{3Pe|AkWZ4-WnY_V4m$nfnh{XXi&Nq4U6v0A|nj!2uGEBt{XDsUBjD&K7tM z06h=Jts6Vc)_*P6P}P~hi2{4@GdqnlJ)+q^(mK+PlK_u7T?x?~kO{l`jgFj{R^ybA$h5VQ!gyJVUg)y85rqTeaSK&_;Z%hOei)`yrUR|Neam z=q#?SeEc0z30ne34>&C0g}Dl6BsAKCX4S8x9lble1J(GYM3Qtp9%BGZ-3$JRTb&Gl zRWDi5Pg`zo?zAs8KXty3lt>*oow;m;RY6en2Q2NuW8u`4lb)h;$tEsozNZli{d;2@ zvkfWrJEoz@LFL`FCwCrS+vCYIYhSzk`nfVWyXr=msAr_8P*s?L`laaoibu#iErvQk zOu#-J_V2{%(MelIQES`J8vpdY z>~?l`W`pBlred!fa+Ar}4Sz?waUiaV9~r&dek*X7&v`jIHe>tcU95FLq9$i#-2aiA z%gs9!!<|ZH!FB`xVSAps89X~-iP_ONz%lqaKOd53xR$F(cEmi%cE#*J%gf=WCXwtQ zAc6)aI~qUrG4V)Q=+TiU(FMS(gW!uPxA~i3KJJ0VIa-1Y6xH*ZMCG!Gj1C?j9w6oE zmuh}5EM#P4l>nuWh%mcTsU#9`S>)f2-1-R69 z0so2qm=PCyjNs6bfV0H&V4ViIh4L(wfp{zxegGb}?_@3qW>nkR@$TtL)tbeZ4&#K! zG#PMc-h2~BW-V26e^9sE;FCd^bFe@GAIS(O<6*qdIE^2vGZZijNkOw z|GqE|W&}D4<$pau?L$A*Ewr$`YJ};cvEPJ)i+ebb{yND81lVZFA4DBRLCXg7=Z$M7 z{y>ded~;w~0Ot)L^5K{wVbxWD`$ggr-urog0xEtFfZV=nj&^SwHMK;Y(S=JU%`KIf zq>t^SOA80If8!XREC@9)RR6S}l>i#8G|2kkn1z7qOrPhU3VqRI)YO(%rch6wbe)Va;gGjGi{k|LYiFYhhyzuh<7E$8TkoVO z>XcyRL)(mxbNM=?wzl_>b=@=C!rJzYR{<~C7{qzkmQ>fx!0yG1=pyXXke1{MvazVE z+4J&y=jZ2lnUQF1pRTTwr{}33mq@SF@@Vdm8nCBeGRglPHR;ewB?O&4*3=t0f}T|k zyYf^22XMf{$8RDjLgP(i%&HwrDk?O1s8XW*3GoymudLiUJ*`J`$IHu028>cbPFWu* zfY}}Zx6a3^0Lu%UU+_Bt)oy)nI!MVGo=K>xCg9HjduR%n9nm?!(0!r#z_3(SNt~w= za7JSu(b<3{)TOvtH44=sx+2Hxst=W`6_4q!S>Tth2l-983!BT@C?JNKj|T7M&=-q6 ze?xF8)bhB9{DuGxN1uY~qwiBREhhZuUdb}OS3E2+=FAjTc|6zorS?I0AeW!o1pL+iG;1^GVm{LB0?S~7 zHIEZeU@hhF%||oUSv7Znk|`o0lG2;2StXWxvn?+D3QG74YPHCa5L_sDsQNCsgpaYM zt0q>3l#!wVx@0h06|=B-40RkM^D*t;G`EZ68Ke-g4X zm&VYUL&Xf0xRZ0Im9M5%;`N8Jr9#gal=E|vd;tp&(Cg{3h z(DA9dnj)Z)&AiuP0Aqn$iF7Y9!fw3mCJ?{?YX~I|+B%VvLf(xEefW8G3l_+>RVxfo z+PKe0@K!8kc)qFgLKiUWNiF&hb@o=}7xK#o-{48$%tOwPIz1ZH-fhU{OF0JAm;`J6PoKpNJiFc40J13h%5!sbdlW0+wA5n)H8X@SqW$pT+ps9d_UU<;^uqH?j}lK7QeRPY zCA{JvpIoOkHX`FoaN>G!MmWx%EG%_%y4PPWa2T(Ix6PUg9^?DPxA8@maJ?MT_Z6XU zlkzmf>eeX@#L;Q`*+8!8>FUqO#a*pBrLQIblvOb4x={YZZA)|J?xguust-bc_%+@_ z3JWQC)J)=JYby-->#A5sI#sR6>UG~#3ZeL6#sXP^&;q%6c%UX-r}uM-UFx6EKZY3V zgs&$O)rY|LIyyR<+1!kbii*qH~CVfm=8P6}3!-;nPCn-dt)p;Lz- zUD5gN+XH#&HIa^mO1I1RJYV*2{f*7;>y(^C{^1s;ecKXF28|CaP2_-61@6c+Q-M_{ zkJhG^zGZVS0pV|XB`;qV4JqB~RMF=C?V`aWY4z9SL97vNxaO5CV2r|50PgE}pXyJa z8drSvM{OOR8gqgv7p;&PxO`$+y=W$t7Y|{5UxDGO=e94bE}vBaFHy728^UHfy3oP1 zd)N6oxjs-eW7V_OR=uaE{mtfg6RY>>wUuzVdy<@k@p7=C;s9}T)fY}}zD0XkvkLpF zPl-L-uzV)K&zA**?*is)cXxiY`y9A#kh1gy%MVH`!H8P_1`x@lrglP6t^8q<@rFt; zXf6&mC*@zgx&x&p6z%X`ova{k2wRpa8AB=<9?8=g7&*3fcH#kq5Z#r49%lWT1v_D9 zPfvDD%~{|EbcU@!yI9eG$&hHGVc*?D_+r5{rcXQU8#A=XBTbc2-^8eMl98 z#&HK#6!G9su&-fs#>bE7*j`xx#)3;8qR5=Oxkr8i`x0(m5HF%>jHQ|YlPRSmYKf#m zCq1B%M}W&flV}G9njshg7*eKVB^K~j5khhqydLmE8AFasoF_U*A04bO-W&9 zQaR;RSX%QW=bcxe{~GODOm7kHC%PgID4F0q3VIOhVz5{d$>luc-ci=Mp~#S2BJ;+D z|Jj5_vFQ$+J%aR=CNC>WOJ5h)f#nzOY)XE|Ky)A>P(VS1dNX&)e`5pKMpX8fI|Zsj+w>9uU=p^BNOrBgEG?V z^8E0v1t2$9EPbq2p6A+-%Zw+iNhuR(MZLc-_!ix$fwb|b)d&j^!8jg&3RX-17IpOr zY^Fwd-}IZ@SJ2KE0uVJEfCkY2txwla8&G1_E^!0d3p$qSpOA-!?)c%208+yS8*{A{ z@X|p29|Zn7cpc-r&-OMyadw;iB%*-d1L{>Xv6EfYuMg&LXSIXT|9sW_jH}wdYKAsN zhi`IOn(IS1MlXHZGSYVG26kmkMn;eK;iNP)jCQsAB%7O?*x1 z2cT33nrsZ|r&2(0ETY$m?qZbV!@HuaQwQ^YlK~O#Ur+4@c|R(il;BjeoUs8hRE_7r z($20G3TU3xWHy5<|Hb^kO|!DGVFC}N-$qb9U`Aln1C72hZ~+#O$SXYOBOh3*-oqsU zgdBib8N;KDEHlcL14VgM1Es=#@cuk`AbPv_1}ACNv5Vx?wa!17NDLkcTQ`evPJ8o#^QJ#Bq7s zAY}j3Gg_=0?N5n2P!6DhKxx@!iA^^&S9nsbx+*dxnV|Uje2(I;KehdIHx^~F&2%SMtvK5AO6Q(4pdjUNV*wY;^=R59)D1H*WLZQ@Yaq!Q+j^`U zMst84gw(VH^C@cK<)Ivbx-p~IH-(i=^V>;(PJV!T06raUmdNS6+l|23Ke^hkcNGUGHa_0C{DwHdXj*Gw)$D8|Lj0e{I~_f+ zfEWO8yV5TFAQ?I5>Z&Z>ZzV-3I&)?z|@qk90AX55`BB3 zZk9BXZ=t5VdU|^5z58@PN1%QDI27(Y2Bow%-f6F97_Oly0LpyA%=ynX=H0(#nxyhE zu8Nz_S_V-)HIC>*@A`qM{0q|hU;&inQx%5gpEtzBW0wX3?gqd81l*#XST!;n&+Z^q zES1)G`cU_%?j^F;?!5%{Wh9V#rfS^LSbdn+Kz;xkaSGHDU~IF2A_0B9!0iuMV+IJ0 z0Usxb8u2pKEhcH0n%`m+XEvF9TWto#77<*a`YpBkvfHf zU|e+O#F*sUw`J+b;&AE9X(Q`L6Ecf+Hvr)cj}F5Fwii3kyY$9MmGg6+uCcFKa56GJ z#5zdDvRvW7)2{qkJY5Opj^!+Qw?Q_RT&;D(3T1MR`eU4`meJF}T3}|T2V|}r zLqoXy9(&g?hK3e_nhTyZ2{`HDGBbqH9$fkd@~tuX5|Wy>0|DO8OHn}CfhOL5Z&~G! zyvGB33piO>j3DX^YDb`1f;YLPTk*6$7>@-X8)B(oL=ALbxO*2ni%hen-3jeDW;ZX4 zh!Y)V6(nHTwy4H*6}PHQ7XLrLk!I$w`CFoH(c2#t$|4%zeRP8}suEOjXa+A_2j~E` z94=Ov`hlP|Gjk@MumY=5A4duUMzTf#g0!821Fop zTU&*MvZ$75XbE8~{R>J9pkiRAN;_FwKLuP7L`>d>{z6O)16_v$a22RR&{P3v5q<@d zT-+c#y<$F65cGJ)$Ed{{nBJ2vBRgYOg^(Z7>oTI#3VMz2KYl>|OBf95EpA)uTlu2L zknx1Q^@%KBH)W<)@DxEhj}?qeD5Hrj9+A-v92RxJdxk^LPRDJko9Tdk)t;dJF1ryO3Akf;g)e#5#bf5Il!tieh}0O99FHRQN>e-|*3Xbr@S zhC~v$J{TE8;MI7RHJu!hJ)c{}!O6KXRzjk*Hwp#6*}?iKx+8~u2xiPa%jeM`Co))5 z8-o%Veb+(d^97+D2@fU?R1{E~$G~(82IiGEI;^`{DWUr-zst?GbK`aF#WRN{lYsZ8 zHhi>;a^@w4>6}GlRG7I4sSq2kz%|1AN`Uu(=U@jcl`--0QnIq`vN17{IL<{OLj?Yf zZu2)j)4)p#j4Qz{1BcC5ViSn)aD4dG+#xbiR#|yzr2c{%I_^7n?>=^MgG@F^FI4~< z(rpm{A;UZY5Nau^hP`6eRO{TNO02(sM()!G=UxNT41ytZ>sAM59D5rP;d3^$?vrxT2>Gr#| zbR@BzJP}wbDlfkODebK;IZQpUXj6T6 zido(%I^6h__l%`;iL=S$QQq3tRazm$c`Zxpz$6vxv?3Q*qKd`7em7&}VGVV7YvzRA z_xAoqg@WX6Q=l253lw+@7!}+EI#qqB)7p&Fw<|7S!mRv0Pc+#_u1sAa)-S?YEiQz? z;t%Fb-*98W?S7_au}+4zXdn;{{^HSS_ZE zllsuCC0jPBpTm`a*nOfq@_FMH@;KgC`J)G>#(-(xFg&N8f*2e5`9S`GVpz*Sy$r~S zaLvZwRqa7_!3-I4%V~b&4v@ARlrY@KhWk$j^w5*^mAaMCp&T#7DN`c(2hoe4M~}?E zb^rg|3WisFYdcvqDZQp$>4Ky%yM<#1M=={O!caPcE$0e{yJvRvg}1zFF=qVYMH6us zS)*6cVl=J>YyBAqI#UJa5K_|85Dyualfx+Zc73LFM3)XgR6Dm&hljY7tc@2m4%rjE zPMA%pKfpEsqk?ROG0%8d5fB3WGX}mpr2DX zpE5EsVCyo!xv6At&jw-zP`?3~_7Qqx0#8Kwlm`=>k5vo7Kj(X>t=8R@l;jQ2Ni}zrIt7+HWSsj%2hWB9?8yum%W{T$%y#gc$%R3 zZ1BAo8~(Wg++PmGuu=e9mIDq&x{LfU6T$|ykO@Pk3Q+qC#|LcYno{%*2+yHJ?xbe>*_c0WS-@eQU_aK346f-`M}v$pl{$HEO{}uYRxNOS{aV{?k%y zn*%!*ovYKVbWjLCduf=JGCqB(pmBZ0Qi~<+iFqkAJPAYpDjc#tnBTvVcEfNBolXV- z4jd4ft(d=fvS$)P-h`#Nu4Y%iqa*;YRT}W?0)~Al@w-epF`!=p6*vec#bELPCyf_i zmLPRopNqT_O7-JzJ0D5FR7!N=t63etGW?mL!ICEMzUr>-0f$ObTwGRkufAvYAO7TM zd0E*{rKNX^N4w-%YoQr67$Rj2C|dLtrdZkrf`GXL#TGl4Kw zHvc`=X=0taf)Q#~-5R$B&1S~bCH)g7B3IY|f#*C5n7h)vzWe;*dBK5!_?CKp{;|E9 zzg;0RX@7rTNmvFqwiQ-+Zz>(XIx4aX??0gsKeDXVW34+fRLj?V2CGh3?sOOzW;t5M zbVqj3O0MZ59v$O7%5}#ms5`L)^Cf2HW7$uK;e4m{UwDr{eRXH~`}avsMVZ@a=+Q{?i522+@=gdv@R&{)aMjSn)Bn1i!kH4>eW z@HJXe67ssxXilgO(PKQwn2m$i{q^g+aLKrNdKQCvcOcOhMW0&0LWuqEj0qOV5I~RwRWHC0L2?Un2qQrJ z*SK@$=XjZ@AtH+_Jzk|?{u|~-~3JoY&mQrQ%t^264~^t@c*&f_eOvAFk-5? zs5=S~F#3t1%7nt+^KfiT5t^6JdTWb|(2!pR_b9-CABNxb zMC|@g3xFTjJ{TotZEpUeBR?1l2%w=tOVl?xsR(%3mm=b(c&E?Kp}vRWwiiZXE1R2T zbXw1JJ@y|TVtVZ7vP5OQMZ%!x9}^CTM5+dr`Wl%EV&omA8cWoK?Xy#2i_)?(P>pYN zfH*)Nia9v7&~pK}l&Vi+5uDO4v~*KxO&j3r`$1>f2O+zvm2AwR&KJPA z4pYf`ezTN}CG9J^*#$;kN9Nd7QY8}jh#={92Fe=rG5oU4#tL*2k~WceW;7tAP?nYs z`CF&0_3=Us!rb6S>>nO(k*4-`mYC{p!drC~!@n|wj&B2c^$wCs?ph)JPxt>L>aBya z+T#7;hmvk3q(e|zx?4g?r5i=MrCYi?r9r|&Bi-HI-HmkT^IOlobKloFb7s!@gTcMm zUTb|n=?&Ty)cAyzgDG5V!*b4G=tSKr`71wC*TbF1Mh`9nhZj z+ljEcIPmJgg$x$zOxSvh1Sob;vBF=yuQF4ux4f6`+;4_KuC?-+XT^mE>`#Kw#|t2Q zfPk zzoNMUS0QgJ;X8|qy9Y*ZWJ+4zWc}rP#!3@ojtgI6C%s|n(V=?T0Wk4;js|52{{Wnk zw7`Q`n615wNSUM-e-fOMa&^Eow7MDVd)Y@gpiuZ{>S{Q!zU`$N$%tRUUUk0?Qq~1V z)lEkKWHf8J9*_xy79}XSxixgUxLxg|RPGieM%Y7{cg-p^K)`+FMNRxs+$1 zCxIIfmNwkeu&4O?46Ev?Bpp-Jq4t%}R_>@rtkcRO?95 zlhr6zHLzS+ms|Rr=0NZ}X=(NT@B@;|ef2y0|D;<0GPx3I^lwUG)C+?R)bf3 z(-cXFVdx^XBYZiUduNzP#cD$N65whYEUm5c zK{%L2S##p|!9+8x%IZ^z=w>YhJ;PZgVHy!BQ`ZL&I~bFaVm7M=_=Q598_?m-!lIx_ zV8cdqdUFFX`8cq`U@4FQ#R6sZRLsmE@jZ0hvo3DOlyMP&Z=2LJ+4}2IESl8VntIX?AWo0A=OCmc#&u4+j-0956um**P-XLTNE^N2T@!d+*@Z`t@o{*E;W z-(K-6-e)pBPlcvKa2kP!URxPc_?Uq^My)ejqTLI+0RRv<{U(*HTDznlqd5eRYwC(B z*toKi+yVMav_GG;-EO)uOuB{T@~Q1JO}V&3HhoqjzYXew(A<6DXY1-Nat(I z^mVuZE(X#&!#0}fX4S!!-9T~S5cfFp9;L!fJ}~#8()Gd^XsO~=-y#eH?b!dvp#LB- zc{BcR54*hk>z!CL_w-6IecX+bOKPZCB@FpUPEMXoEF*XaEP~0vlnY#Lmdg#Qd}X_N zTNw5(Vr=wp<^}0Lef$VxHG#6j>57GwCO~+i^M6q3qZb+A9Ya9Wd)J7cLt(HHF<4AM z4UKVq6--HZFHy=Uw(&odz*aPfuv_r!H|hY?8F0{m?+^xm^_2o6HOS7(!hr_>6)i1o zbX;5~*jgc}J4SYP@1un8-$FpVry)R}z;<5#zwljrKdfX31}wr{yFh06kFEjC`2f68 z^D3fOypBJvrimaEql*uawqI~H8{m_cyey5?rKNup*UFt)`+P^x80D@U1whD{4RVErvI^zXF&sA9 zC0_lwfBut3M7I)lo#=?!{X>wQFD-m1v{<=Q;zM)J#|ALNs;L8Q(km)+cd{7GjoQTB zKORdk2-ZjmY8$0oIie@k1pM;s&A7j1%PlSXxcAz7(vTn!ZX?hgo(^2mo8BRT# zaN-PU^n7rF6$*a*7`ptoi0()%v)GxtBF~!V;326NNw3wHIoZM@H2leI6XYz7D48f)hkWB=j!ip%AB~kST3GNd?Svw`v{Vk6RzNP z&=qxT*dD(6-h0WT!&iD<)}*k)rnTfb>LUqcU>!-BdC<77y1v3K=t%W#1|~Bq2JtyZ z_J8MBi*R}BMnuXtsILBl&uzrec6WCd8b2t2D6F?9WQKps=>-H9OEcALk>*=q^392R zy04N8FhQ|{LpkX8gei}I7dR^-PB{%2U4RW_jJ1hWO)ntV%lQDe>g$_89qtrJCcoo< z6UhHv`Ez}DQ;DM(5llrEcR3L9JNFNZmK(o#=>)2*uF~#aKkgq}6&%Q5<_S0{mE1!M zRJrR{Ks5pEAg4PoQDX$Cn@C zeJ0*tHcf&q`3fzoR7n=y1{FZM)-J$1Ryv1@Tv_O z`~0ZKAdU<+dl=kg-X%z?5@y2|>Dv=wre@XU_Fy7}!I| z=6@DP7fJ-5NenJ5udjZ6GLXrnv-zS;A$t)1=vehnhinx0^8SP4vszI#MF`{WA88i> znoKfW$H+dN5{G<+bhIoNE&j>7gp2q$F;jPYX2KS(M*kgtkuOBWQ_)MOkINg!pi1G1r<+KKz{-8S7Tf!fp zDvNPTOG-wkr4LWwyE@W9T^$pLIjA+qeV>a*>f#)8o_tz(SWbBiKm0x1B zfp=N;LcE@*^-5C;*d72jSI7%NS=0qU3`yX^m+>n;0pZe`?fbOSD0G&`G2X-A9gY~H zhwL}33esd6QSQd*pShTsBY=Okpm80m=TK8`hJu8o2tx;)cR>C{Lq!F*r!BrRGm~$b zNXMx>t;hG(hyK$y@P=WE6SLUC19l5Czvf6g(7B_oV+Xt01Nsk~Mc@rPN#6eP{p&7} z{8Jym6ZxBi^<{M%Xv1tKuVuaHI_H~V10(z9`nnikVSqpboXiQ}_J4k;5B&wiu;9u84h4UI|1rQP0;_F5s4#=cm|cPC z6qG@g)9_y=7KOo-yWmVz9XZ79b-N$b+U*qYbm;tVlCU*E`VtTXJs5}UrdNaxWJMiE zi|YN^L4SmrAK5phq`HTDmX~*8lJSV84CL*4AQFpF#d z>8u%X*H2PsBJH!v=)@GzoNGrZCCVyDyZ*NsBG{h6^y&^ATl2EzrmotDxP6falPNrZ z$Tj&L52n0+HE!rq(=r+Ps?!B;JEy4$=Nyy8q_{n>0V;su%)dFOsiPAVy2Jv{Ft`&} zhU^*e z=hVA%1Fi3q{|VSx15+HJ9oKedctUm;1aE`H)Xxr=+_p1s>qb7jO#4G*4&Q&Z|KOnR z)qim#++Lu%EMYwu;-zC{ahf@@!E>8g1dUQOcMqINEL|>s9Hh8CoW;CMgS*Ok1_J?h z$lpj);mP2N?9*G`bVtg>AusUqz>w3p-9N$>Eq@9$DKOcJiV8q?VC|Yfe+c%mK(N{y zPk|B>3{!bc2NBso6p+IABR~CrPS3kFKWtLGp-4)6jE+u5Dk@k77v$}h56X}KvZZnQ zTn8kB$>n;JFtwvtLAS2i^8{*Ec41rBcelO=SBu;EYZyM*P!w67c zL<+HA1xq)d!fUMr+G_x5kU*Id94Jveiup5(+-H=N=RTd6JgLz|2 zfWX$?Ix8-B#ONbpN`66o(Ms_mLv44YVt@FN4G6=6~^=f|k&4IY=NHF8|h`FsRVb$L@u6qA|wB;0Tb+%Ef zv)=#syv*ff)8-F9cUPc;)n;?A{zhD^)2^Ye?K)F0xZY)&dHam2MPXk-bcJ~F5vblP zjbB)Q$ptMxAiWO!YH#1ZZR_nt2I_iI_erjlIV6($wAk3M(k!iKJtPXvN!3~33lgPM zC{ez{Z#XEj6&@*JbEjjjO&fx%9Mfv2y|FLP6uvbuyPleDoEhC&JXMiVAh0bBo<*XaA`?LB8hb!oDUF$ z&&PC_YoeD7L$gNFHKT%OCQK5y(eAB;P4~Wsdtb zBwuL6#DVK@@dy3=>V-vq(vj;$t z$D>dtY_S z>^~o4TUdY|R3?zG_iq0et&Ls^8^K96z&QmTst*o<_TeeR6=*s?f5roe;s7y|kNxs{ z-_kKWWB2d4DU9?0g*R~-87qoX5{m5NCuDT9AsAHMaj~%zirflYN4ZG7 zG2od>PFh_6Lc$>cwlYxH&ynZ-WoyTo{aIBluuMC1wv40MiI3Sa{bac@2_S4hrnOpf z6F%UoknANa`)v}1f_yj_w*qaS$w+JJ1}sD{^aD*1!rOCsmi=%FswH@$_jDoe^OXYY z`LLgJMNQs&H(vuYd#9%Zb_}Y-QJ#yNun?!$H9bq~^#|^1>}qDen*~yH5`~%Pzl~Pu zkx`!w!5(TS5x9iqxj3SFY2f+n5lFoAw>a;lR#Aq)`>sawRZW-;Gd2#sF+TX2ltYfFJGonhm8pB#gMyY_`m}?`(rY21i)wo7)1_>y31Oh z`2pMkC|WRTn*yc)J!2gH8H zU3#PBw){mMFvnXy(=X;%he~g;w%$z9HmHH#RyDwUzSK3YhdN%e#Pr+4H495Mr8*xi zbc6e{6@4z1jZ5JNQVTH_?77+0?yt(1{_4dV*^Cmo)!EtLbNZ$k`IQo1@SrKX)iTiM z@gM&$+wq1Z_&3_M=EAw`ml=ePbD57@^x%5{N-wVF&hMr|x$JcE>7liTM9Gz|B>f-0aSCZ~hY|uMaO^}cY@|Jh15An}^OowL4_SN*V~VC{=B^q1 zzg*x_=^Kmhig%9=hMf3D!3F2_>-)>vfP(x)>3WPa1$?uC(detX+P`Y^k}g!A5NdWc z!cYiyjVjMU@`_sN8(P{q*R%gF;@1nyxKreu7(*oaAl-lO0ANAM$2Y&fV;gzdx?S}_ zr-C{sJ6r6=+jqv3sF1!<&9g6Kc!bWQt5$14Lgz<5`f+i~i-x<3nWxE0^-DNV(WI^x zVlsLd`}cK2cSJX4ah8#`~zROrPiK} zko}Mex$Nw<;oU*^9=1p&Ioc-uReMp^$ga{)bvU}#&{}f-=dd=5LHT`(f4L_IN9$j^YYv%NNz~hlqq@3y{kvNt4 zywe(BGewRfkaa+!%gNYT{cKRj(~IG(6XERayaVS~+a-zKZ(E-UL?Pta^SxJb z!KkkTYi)?^@U4wCRk6n;?i!(;#g~YI$oFg8N7A>+7xl+ytn;jmzE?99XL;Jmd_BQs zQ6l5J!`sI3PKLrjo-pPsIM7CB?3S|VZLEt0k=$`)R39mS( z$?Y$7W%eL*oVAyDW;l~&+J7-(BYbKOCATYm645c?GyvFgL{o^O0HlF88cNHf6D?;X z!-o5fz5bdt^Gi0p_E=2@{jR>~eW7W%7`HZisaO20zTVKQ$+!?S%ns9mwf{_Jen^_D zfd_cemheS}lw8jAlGm8o?WYaal?>|5gwo~f+TCyyNmCrd3jDgq3L9SYStXOtP~H^nIww)C#J%gxUmVx|3YiE!jp&gHDV?gU;(>YprJW0z(= z;m3Xp#3#iOm5EPD3489TrEU{l$cYmq&8baPh4Lir|3Q@ue6c~nn>N17x-rj_xyzGe z!p1rjtMqdh}h6oJ`hKgK7WA$&TMLi&+H63t{|ZE@K3!d-qeZ#cLTq`_56$ z5Om`q1K>6QvT{7XMr@i17TA9cCELNp$$6zQhXpFUV9B|Ax!HTLp3NgV@mi+u*MC}m z%zGk~@j}T{gHA{lOR!=0cM=G_babp{Un87=qdo!lrDG751UA@r%*@+>R?4fZyN#cM z8cf>aRr)1z5swFxbBZezWl4fB=~&0=>haj;1Gj(1A($rR#vthAiqEp4U-Rl z|0eDFjl;HSNpIOYAZhhK)uQ+x?8L>=Zw086t1r{HT}Jx$-}jIQh+13BXX6aO4!7l< zK08i|1^A3L5>f^CsH29~ekoy!l4svv!)5p`rWE6Po41;7yg$COB4%ZG4*!uZ=NRq$ ziN|aY-3{JL0FIv_&;!ibX)#|ANUBz%kA3agk}EhxTOuRjf^FfNF(6q)V`EX`rtIFx ze^D8KAtxvI8`z(zR=O@IQFKx$XNuf~Hk9Od2Jv23K7Im{i}Q?F^^M@it&lJv{01sW zS}=iuDisq@zKON1^kQNK46HjJsp01Tf?em@@}OU!@Pe?2MUwaIm;h|_@LAxe*QQ&{ zZw~o?naB2?jKQ zcs)ZPWNWCInVG@T(7w0TO<%SH=+vsm*`Ll9lz)fMAhI9+o|aPw;#S<`I?ZIQwbK0^ zYQvZ5b&H{n@er@CpF9}$rdKm4!?Vftipg4Mp`%!&wUa)xsW+?@`sT}5p*^8T+}dHS zHvN+QrK<&LkNb7TCFemoyk>>A#8Uak?Oy_#WNzqC9qqmb)v^ok+3#%P7F|4$Mt3Za z-XxN!_ZQXN~n@PmR@wCigFo*a!05Q+lCp6t#tamTaLSx0E)Rnaz%bJI$eMBB6wTH{ke~Qd?ho^aAFl*V%%C8eH{rK`Ke*onpD?Wtpq%T~O0~ zqso9@T`XTKH1?hxQ#(@g-4JVs_wy$v=oW{t$5|30^oI5EWOGqQ{`qqd~Rp^7Vyb86y8cX)ZPSU-25y5f1ojxkOU9BHsFo~dUyEuX1kO_CwmomGL zodHE%D$;wDZP>!f&^mu#)T+}yd9if&FXPbF@>|f6u&RyWaQ-(PmSio8|I-4TjtM+I zY$h~4*o3T13Kgygdo+Ud2qlvb3NaPRqK0WxKAH7% zw|<~xY!4EqOXT{DH}iVWHDTSo`rsdXdGU017p!VH3ApC=k$Q}3!n~D0sf}NSo#El( zVpb?`o6;mbvJXuwH0mxVJ|zeq9vlDy`SU-GimymuMx=f7=Dp*A3Wzf@->vsxafxlT z-4UM=nb9T?PIf>H$)%G4_kJ+Et^t=coF)0w*KZ1Yhl^GBJa+P4E$z>)A}a24ERk}E zVc)2nvlE-g!srJL`+5O#{Ohc{KGOu;8F$D}uS0edZPHbrSc%7$i`I5L_)Qxg1sE96 z%5Ofu!jUZJr(pK{$_GMp@va9?geqi98-~u^ryZ6o>htnGgjler0ADx`s0@ZVS7B1p zC(ER4^=p8$b-$2yq&-+39*zK)Wx%b?Ra?wv(e+F@Qui4j+F?5b7bHL$|M<^7h-5#r z!f}7qTY34VW>C4lO$u?45gu{s$qooWq;kiP$xW+89Mk*axXc@;*U9o|k|xKYV<6fH zNMr!tvjqTDm~RJ&VS%tBf1ag!Mc{xR0}W+uPkGTu)Ib!HH)DS;tdnn6ORC<&nv>BA z{F%Unl4}924;<-eJ=e$}ob{+nlV(Nlz)Vgc{%~{~=DGne*6rxH8mb6A-3x3nSJ$#-*LbXhw? zZfrlBfY8_zEDlzK+ZEP2V7$7!o+GVnCYzgB9BBU~wUp~Eu5fLH*G%b|0#{q{LDs9fH& z{ymdmjNQ9;yE|=a$ktS5L&}eoba>il?$5-FRi;Zd>bgWLLYOHf*jt$Ue)QKt0eGFNrKmrc5q{ znm|M<=@1>1vP!X8pXR=kCg7)Ko_=%4#R?+UGLHFnSJqobA6i8G93khn^GMcPdiQu4 z52t!fLPa9~Y@QI_WLTWtdq0P3qPF1w!ui%Y5sTkCy5i?@QeV5)wDZd2c~7qE5E4%E zv!;xtO^8vrC%Z%2Ai7cl>z-XL7dKStw|pAvxx&^50@fC{T{oaSt33_BX-)~pL6A}$ z=%xLJ!uFmpq&josKj+!6pG@HBkhormP2oat{}675h9ptLCs7~X5^C7}MMxTE>Ds!) zSv#*VeR4tay4#lGbeE>tH$~NRX@Qq@_73MEAGlt2r_&8jw&~rdF(F(}J%plMsF!U{ zGoRJn`PH8F3a%ot?|;UgX}x~c*XWp@s@M60B-U<~(7RWcFc6Li`_n(`c%3uhmD(p< z!U&O+X~~dDOx=zI7vsBcg-!pgm(I@vG~8EDIhKD@AbG`x8q2awQ` z-WR^+M2U$D2Tro9fQkuz4+{wgwW`+giVXdVjAq~Ip9tEQy+vCJov`2psHBEA39v{2 zfnapz$%P$(?gJ;TlwXqG@6$IZ`9Qk1MJOl#$#pQ&UEde`ypLVkeZO9&$>oF9*nc8K zU-b`pPXrDL<+T}tQ3k-YICta(z<>l1?lJdL&Uf;W6;C96>_6jGfsz`K*Lm_Fk6cJ2nv+*DFb?B|4a<8mbEFb5GPVjl=5Y>Z9Qk#(^(5e-mv;A5oU zM|sSgbI-hX7nQ4;aD*3rRXVw^f>cgx=IYtY5bz=F)In=SFu(na@Z{C$KYpOqz=8}w zg)A3QC1>Y-{1HioCyGQI$@oI=e=YyV9UT0lp&5AQKML(0ka!eOkdrP|B0Y$+ia$$+ zibmEW-toC{+ARAv3z3r+&xJQ<6Rw92n#K}C_zf7#d~Z4!+04ew44SDgY)2nI*`3bI z5_xu$xwyF^{i>UZYp+U8V#VlWpTM=>6W~R-`?80TeBIVe)NDoG6OrQUPWVi?sH>II z!B)J+pfjc#GQ8@L+i1*DLmt_ir~Wu3eF^blfr~q5Mw$Ntr>%4{><#6eMAI1Gojblc z4VsT*b8Y8A7>2=_1wmwKzgU;SrLxt5KmW#Baxb;_?r*+~aDxNH^0kxA@i%vXPWi4d;2%7-FiMjIe+_jE%O_bIQ&BT8NNt|+@UV2QzHF~4OzAfg|%dG5%I_| ztv!k0_asQq)>wTmSef6r(Oi4zX=4&~=3L9H!OUW(b1PWWVA5iN}pv z8tkR~?S#&t-Dqd~faO8RPk_%7dQBp->V*BPMs;1ZfNWGJaSu2n&SaW4T>l*l20tM; zjP5PPD$y`ph%xE%!Yx8=83`=;dP)aBrXhO8O8)KoLqk-VA>WCP0SvW>1(P68&=+{C z=PbEBfSnCs*?mJplHlSG+Q5B5KGe7MjsQTtz^%EXC2E&ZM`d%yD%M3Rks-c!xY1RDC&sZ!bn#|Y zqz9f6sihYto$fdkCjnk-Z@XD?rDuzAMsX1)US=9Asta{=_#8*$cb$iD-nZwDxi*ob zAY)x;Miigk>qYI#7)&O;fhmMQK_vvX^AK@cYP3CL5KvdfGlN>Z!X8sFus|LY>a`eD z$z8hA5(!KD&{L$Jhtv4Jn0?bfFgg6~r*eKiv9CG!hM-EHQ&~5bfB!kJBok!72ttI< z!x4vb3617Xa#mktMAeR)sw~VeEfrH6qk`O-NFaCypF9Y*R53g0FI+P#|1r95`}PKn ze-)%Q*#dF#lE=j`#BH^3ZJ7qrl7K8kpiqDhOs#7*epUkROvygKnmn~;8EwR9SXi(C zZ6yw$f<#sBccyRLZ@uFBV&GHHsuBA;y$M9?S`zThhU#-HIxW!oA9WT6n{GEE^8>ar z$K%PZ)v0_o(G-i96zgv6BTaD2shc3gVeHPXU(ZEQPc$e?kj#;a3grV~gFn^L!}>cNexFA}e*@1ld_!5f8C{EV#seBO)NjauGU3^ytuq< zZ1?I}?cFu~bbvplq_gko`F%)vg1tM>XcO&~9DdxA;;u1M-I)`USp!k4=Mh4DyoV1V z8V62(v@sRRG~BYTE-CfEEL6|hKq!jBOj<^`4gIv3L#BS}=Csc?s{nZ!ZJ#W#+?K3K zh+N<8B&6L$W=!w=tc&T?#VtfiBxe+%jOXPpVM}CX1WCnNSAoX`fyYy(z*l@NTW7sOt8IomyM9us5I6StAJW07!LswN zNMu_%MUl)RSzac8ySZC;d+dVbT#?zDlIu;PkGqYQ8;QA!GCw{=Fn|-wI^b` zaPIyU!IpH|c>SAp>X&AgHnKTIP3e%1=*)33g=7>XfZo6Uo0%Qw< zFRhm9l&KIwYD;udQV_UufU^uhAf9Ekh@BRMb5WqS3-$y!r7<101B&4NRr%>=E z?lE`$%w=qDu8@HP2Ul)Z_JB%^0d>DuJAA7;y(F&C43%#b&x<=16J(XL-mX=A>s8sF zKXL+8h3z4&fl%oFkNm|$Ti$pcD;M)c&`J0s#3|-=qMF9!T1@G0j6}KZgl5Ce7hrY6 zq7(++uL$|h5(IVr+%e8vR&a8HnXVI7?d^5KEb|x1-e%F+tOr_Ku-TyDeEJ2>;pyby zU<+kR(G@!%ig?y!sPddUnwbembv17X_C~by^mHPScnyL6$R7!Ldo&WCQdpeyomrD}zeuvE;^MSahr=fhE zL%S>>_y(ut?J`a!-(hG{r1EEe1~y;QJo**0^%y!CelK}*zw#c z9wjh{;`h3rm)$8ty^*Gf39RLr#Iqc%2fz@CHhiI zd#Ek)>bA1J_PF%m>h?gCmZi#w5<{7Y%L(yR9`)l5x|A>zLJCc%ZI(H9v=balUDgeU z$DXKZeTxiYnDx}$f3{4+p{tMfXg&I-J%z<`zol*r;oh$4VB|#N-}Fy@$PY~Eq5kX5 z$n8}T(Qs2&Zs_?&(CnM-x{p#Ck1anrHX7Wr z(OwB$gc;#sh{xJKg_V81j!8Q0>X+aR;&$*ku*OtN`(+0chm`O3*8J)2YKNk^Z3c%niOw3*Px|>;={u zpub0bmLyO?u@jXE29gIz%OL}p89$9|ZEwGOs8aEfr4L5;p;(Gir^Lo$QLiB0@q}IIrjrbWs$M z?Uu5fzUrnR>KJCH4zL~R?^kBxGQDDp@|gMz_kwzO&MIeUnmS{ZDvdF(qjQDEww;fcMXToA>Ru2rCXHs|L+7 zA@z6eDE}Q-|H=IjPpn2Z$nA=U!Dx!8#WUH-S=Q~-wx<^5*X-{U=U+a!j0h!XdXw6$ zI?|9o-O%6WY>^3Sx{&CJ#QVA4=tsVV;3lp3A^(Wl7+x$`=PC2@iM`7Fwj9b+ZjH@W zx#ygmuOGIm<4&KUuN*!q0!5@~I@4FF{~7)B1+9zITBmoC;fXRUjys>R4zb_4$#EBr zjYqJe2oxjJL)Fiz!{KtS;=G&Z)KC-2QoE(2Aa6Ab$&L-<(wP-2f4SfV55x15;Ir=I ztC~3mCAH6i%hC=+rbLCNvF_JTgx_L}f;6K%0_TWtHu9@*vY=eIM+hRF zwX7rUX{}8`inC>%6L&moEeYAl{7@E+4v2pqm4zG=R#PoRvGwMiu=WG^o$Z9+>)p~6 z(#(*U)a!W-5T)p@3_5d=TueNX7;05J)Mhtm6q@v09Q*q+W06jJ6*rPbTl_XgTiZ-B z)v~flLSJ)y-O>nelWMvy;5j`b%+q+2^Kgzd}rsw zgGjg}h|RG%yLrRm{d0Hq0r9)OS7dD2!5ZC1Q(e5$R%h;!)p{JL^CA4B`?6bniGI*4 zs80CAlTg7_t4RF8Wq4I~)VJ@X2|t7Hu}?QdW)0)4NI;HT00Nm_q3=gu%xmc*bY4P) z+3YaIHqj_Di`99bW@#a>quoDo?xWc^O$ov$&Tozzota+i*OS$=1*esQ$xxpL?oI99>{q z3(_l7_jp^N01y?CM;s6;DI+J>1(dttpb78m*+w@2`~vW{My+cfV&JqMs&V$#p*lXn z!FTV|7VAR|^!{KWCK@rau=K>f`2@L)wKWP?FVzVFryrwam0lT)9!;VJ=-M_O*JaJL zc>tl_)a*3+qI6M;EM=R)M64CR?b_H>cBodW`iNs9IfbU21hS-L!JSIKVT&S|eRDcI zR)&th318Vu>b%B5rF=O?A_ZsYQ$&xNly;&rHS~m;`+gXA~m)u>BD(%B8 z#V6hhL=1P&^By1qpk!nmEXxoL9W#)n(@U?SR{1?;{1BvyeX-CsICz*VdSJU!f4cAq zMUp#0CgqciZjL?JU|zl~^t#xqpuCf5M5$j^A4IHOi~v|bRrQ^U|NQ*?zzJ~~tLt;S zgUBfXn`!V4MRQg;$lwgH++oHE?nzc?1Yrk0XkOeJblTWq2Epd!cY|MVZS@V3K!k_g zBE41{eCA zk9(-D;3wSkg8507h8C<9C}Nr1VNd9)TxY`U6PiuU_GW#Q`ucMW{mTqP;<}qBye4~3 zT4C2mW4Zp;7XcT~KVuudp~z-L@O)hDIg(&Ftp!`pfNx6O&E0f4#W|(mF1euHg^~($ zauk%)1)_`R^}K*4n6Vh@4ZU}Jsl!M77utXzVNd^6#RH{Dy5&RngW~#(FKPH-3w-VK zWXK@lBMH<7Pr8*@u2B&wgJ8#nb!k ze(#Ny7)O`0UG>dh9nz=w_ikw|ea!9aa&d89nWvV5RYq`h?&_Phv-&?n;!4HWHxOiM zG5o}KX-)!{uUMHHdc*H$kGth3^Vb6fR=V25b&Lw65%gHa1D7LPpUfDjgCN&t0=S?(%{1nx_cq3x3xCvJHmikAq2fos zZ`*BoPYES{w3&Y*`U_okaT#&Yaeq3x-JBRzo*jsdG3nhM8ZBvwOu&-;o7s7IgV9?W zP`makBx(J;zqOYz#yDJXl_yH2W!}MSdkKEHyUo#G*Ma_-R{&`ddjD39^OlwR_U28Q z&He>O@7}{|`$JSjZ+rKR;Y?NL=D6c}-E#tT{VFv!`@(Gj6v9w*pJ0o~_bTvZr zOKCTzb2Gy1UIW@P?oq5Y_c+W>s9d>6D}tn!!XCwxl*0UA7N(CG}4cs@u=BLn+zz|fE!FwkXr zL!S!^3q`?AHrmvdm$Ywi5V$JdLA<5_HjdH^Tuq^GM$E>3{CXN$q??65xi=cbYd5dX z8C=Z0<(T|^8XS(RGl&6y&zr6opY(hDSE(4Y$@AxGv!kHI*DV?WW~ukr5FwKhQa}=Z1IknY1nf^fMZfu>IcoLVzs~R} zW&W}~l9|;;e?p6i;FYFv?P7q{%XIoM(H~q&+VhWUMX%`MP(freE`tj~f@~&z`idoY zZhbv57;G7QV{}n)66Bk5T!Dc3)J4$L%&Us14nv%{Y3Nq zCQ%=1q}Dyb500Vd=l5@-zXHpyS{{Gi1$esec1HzlK#DivP!vuTK$LCy(?dH_ zG>oD>XiEx3G|!V2YC*~kDX%RAq*DCnaOo&FF?k16?sc>r?xU2yscbM@pI5hN{FK7#6@q4`W2^*!r4wl=eke7(fOB+xNl7-OzWf= z8nG$E^!Lyxb?lO+oje;;(>7pv8lRrdTfjbjFoo8-D>r|S)7NyMs6aRL;Xh@cS7en0 zox^DX=Eiq?1tRv={i8QmG10eFR3SSQMBt4TloT6Kc-^C&p8^e3!YkCQo1cD&P~2+i zmpJsmG6ifoeuLY-!^RTw@|cj!4Wpst_aDhF5!k6>sz+4uhVTkPLD<}zx)cJ1S#jJ? zq;PF-l62sMIshS!FK~Vgnpf#x{?=#Xxo%j~rLSFfB568h zFgK3bWsg!KaDA_CU9^=b_8f~X&yT;9?A%f*zi3jo=nPSc8?C@KYoYWxMS_!j`_dxf znnv5RhFDj&?_;U@W9mZy{G{-!q7($&-+(6r0TMJ2igh_AE(n)q7kV&5Lr{zd%>E0> z{LHKInL9eDI9Sve^&N9%eBiYC6}nQsDt+1VKQ3A~c@Z2t&?=H57pl(AN>LF7TDQD* z_icGqxQUti6-q@aGj+aQcH}3PAYnGF0D5lk$_+RX4JYZi?t1TK{&q2II(&a90vp5& zKRA{obRhExJ$hyH-gii`#u9)5x{Xfl>$V0Hzh#MleLGZ+)(jA@j{{8a-r;5l{E1@@ zO3K)U4*qq{nncu^1Iq_4>-vlig;U?vYHEO<0bvb!$!IdJJ3n2(8GejzuNEYKfzq*e z1g{aBgcqv6qbH3KAkEW4gT}YVE&`U&X}vb~<|9mcq(uuR?L_VmS0oQptaE__0{rR1 z#**cPw&4i*r!&C|{Y%3jmRI2eO??jrbZ*^AUPJ{knVGN%W)MdJ%cug8jX%L6nB12H zUoc1u06=1CVIDdfnu-{L?EDKqs<*ACs39#K0K6nnmE0RVJoSn-98VnGs=3+=-mw%1m z@twUfv%q5~&#`fNPPG{wa42_o9N6+?p+BDvJ;Wf6%@1bwDRh|v0tayET1UlE#CeD~ zl0-_LwskfSh~tlr5l*6CR=A^3EG#WmUXH-xk&%|(R4K%M@~ z{QgC@O#Z7h%lS*;3`~?0K~k)s&+6jh@JrS_z$M}TB)4*mdxbu)XbG35Ko9;Q#nN9> zsx)QP3Vw5BxQGeS_kQA1E7OYrr)Ax;b!#`=FMqK3Os%d8V)uk!y1tLI@@uF3hp@u^ zAT;*%2Vk2Zpmh!b4gvQCnj6zV@6Ib%RSVrXBVmy3#DK2#6XhO;cmq|9m*Y9X2U(#e z?lISXsOCSYwx#e&v*-qWpc2haOEocfYQ)1k?{%$9LSwAX59m(W-*)TGQpGmqie7H- z_Fl#O_~g}676ldwsw`(_rvb&w4`wYk(Lq?(?SVK$z$^;~kn2<6WazZ6l_;BKEL$N5 z+nsf-_B-%Da_j0et{6C6U1+e!@$d>r!02w%a<_y1nb19*H(fylskn1pi9mbr17YfL ze&vX%z8e|LiewqJa1~!RgzwLh_4FS{#W0Fd5>@4hf!G5VJ`N*h1G(0?obB{?$KVsi zCwvEA+v9(QyILlaR}iuWy=smuHDL3Xtor= z&PBka0fD%z{X~A*!AF!ps~ZVcW_-9H(z|rEDJf>(aA~Cw89HY6VIy`bVd0ih$Jm-l zy+71BX;u{OR^^_b;&dI-w;FN?qfzdFLZ4dY3XhAv*+8^avy(hmEU7yZTmHO6s~Qa} z2mx$$?^2stPkT~*gbP4I@w7G$Z5fd2K6zCh8HmO8LST8GoZQ^hAbP{%lQ{kpOzK=K zIAN^Z##hOFZ?(IfyBo0Qp%LH>%+wHy@u5L_Estzmxv>xYtVdz;=ScXr_z;liS#m$3 zjY4H=YAX8U2M4gms?Lx#eNbNcinplegoR&j1*#8F&;@$u#X=^1P-w9z`~ae9FOp(* zh9Wd6{|INB-%oRQXXm-K6q|W+NJDid0RyGP#4ZhxZW&W{fp*|+^5Nkjta|`NJ{aC# z?n68dsB>nh?p%L9_8~-7^+eycfWE`ulP$qi)a&rgxT4Ro$lghVdFN8BjEo>?hsvHp z2idRP2h=5eJ6@`1OC1I=T0!Hc{)SJUUfUDj;ag_=n@@9EA{ATCUk-}0YRbj+Gu_F> z^$9X!if2r^%1a0ZhYWtcX8dSOwkF&lk!K%y4hi0T;6@O(UzpDDFRpT{TdaZbXKl~1 z3AXgy#1(wd!7IP`8BP+#!~o1T9RcWYw@h5Y9c&uW>|ku|$D|_&Cwnp4$*n=1TpA}G z3ZU!&6&>JY(ofH+sXSt4VYx1nmP`x_=5c`7jdl*b=MLPCP&kNzu^S=0y)mbXtw5N5>WXPpPPgt{Bf%BVLr z5u}dS|HrO?sHTs4_j)f$NWy@fZJo#*_jl99E8V1=Zo>2QS{G>?LPF%WT1u+dQKE?K zStZZ24I`2@6o?M#;3f)E1H>uJV$fif_A&|zJs^EV_4^ABmZqwvlglTt<*#_&=(b*f zkk$YDBl%ZSY3*ID28e{oDJ(=GBO{w@bY@j6*7yl7ml$BV0xKN|A>Re@r!cSac6LD1 zuYPxkfNodjOlPit*DCbcxlX5al3*@a&>xxll_d7HKMqj-_{>`d>Xij89t8r_5*8cS zCQa?=b(fqI{QF7J?9KYzgD_qV2WaYbH@B$cCZI;*XqJ!bx1EsCwHzV$c=DR zq78Q|WBfHP`!mO(n+Tb-Tfz`0ikR*)FRARVdyqxH)xY*GA!dBuUtzjt-jwNf1yX^>`kN@kUlq$(GaW@B=QZ{G4YQt zDlJuuAmR07P%~n(vXiv!qI#39}5o&Q9gHcaJa3G!Wp`B{p)WGbesdvfylpx zcAf}g4Kk&2altbm@NyFVyD284X@6pHQ32v(B|(LVb<3S`p5SLXWweW)=ve|~vZl?Z zfN0S$=SwcJ8ek-WKwts4`ohcstUn7C+$=wYt$S*YQ43E1e?mt$HFKpq$X*Q9$}Er} zh(IUdOdQh2y;B$%M^k%Cb@l}WnZgT_V>|FK6RR^0jMhJm?>m4ILq*y3mi@P*+=A>=*--HsROb^X_*LpJZ({nw`Yy|7s$M4{glE+P<(&E>bI+s5Qgdk>&AH z*UlaqRSAeV`@t=KE)xy0FXwMAd1O8@#Ak2p28Y0`V-3q-;m5NW#Py?|n*a_U?SS@| zFS#zfFhgCa62X?2DL{R1gFT+fos=Yj4$;f=If^C zi2=f3N*Y(-2vU_~lP?cBegHYgsx`8DV8#R+5J)>Vd;%Y7Xg7lV#>C2~Lo=tQ^sEWz z>zLSBU)Tj)=Iz8ci71Yeg?!bSgoJ~`NK7ReD8a>J(}$G~@RI^M*J0cjnA^fY9rD|4 z+#GKZnYl(qgqP}^mX7Xu_BH<@)Dj=tOihfenDDP@d$jaUrNIfhR+wOybOVr(O|ttZ z&6;uo2|XOR{D9WcGmD@-9kMBsZ%q#rLQ#9JhU_V8_VruTE&hleMr)w$^_94i*Ve9) z2zeAT2*+2!9fn=o_ixL8d=lRX@?il9DzE<^S8p9uW%s=gA3CK&=|+)Mq(mAi>5@h% z3s3~48!4r`MUav%=}=1Pl#r6{?s(UEzMtp$&Aj(G{=ukoJp0~zuXU{}D$lV^=S7DO zS;LlNo^Zkb<{*>&(EguaYclXbCAc8>hr5{-ep@sU%Q2sd4d z(1|HU4d?FE^$XtyT};>MuHIfbOG`FzmsQiy$avuk&>@&zl=X_;?y@a;ti_^lGCm!5 zR<}Iq^Zc_;idQ19S&%H3osJ*4xO}Rtq`0kH=(po{CyLEP;cVq}#muH^V(UoO{<7}Q ziU+`A@tKr*{0(;-m zQa1s?^%km$ScyH=AxD=Uti49xoK*HyCsctXgI7ctSc1)h zRvF*|;X&m{p#V6oy}-#HBvPFN$~mopAkU^tlgza{T(4*$?B5t7c-0V@giXyDzF9o~(24e9A% z28aO*Bznt-BfdO4F;1uG(BF-8cp~m{p+Y<4crmN$G3V=QL-5j;l$Q22Ny5Q-)WjT# zBg2xHL%VPCR8yi*uWF+EqpAdRe8bbVnQk-35~km~ojcHNfzi{G-T6)-aM|Xro+ohw z9WAtaf1jUOi~VWb*%u`?`s`laVgdAKDo8vAV$B zzPDJ2DwAbvyGEuXpSRx6=y*+=5^TUF@1N&K7+vJESfS@crH~IT6=iBkuV1dE;&sgU zSZXfY2X+c@#yHH?q3nW+9;~X6i@NYD?(H6N3+}e_aw#4^e}}`-jIC$Lp9OlVSW@3f`Un54$F=wKqYY0J zw6E7$EQ=Y3G~3MV$~{bt&ZAtWzCrsTFM>6BsXHkc}!LkTz$c=6IY>F zldd^#>l6SuypjQ<;VSxyeohCHGoK>9Iu50DI6!?xkTEvH#X2 z+Yp2Om@zR+Zcmj+)U#27!TSs_jb8`PzMx$YPg~4Y)#baym3A{{t+>~fKEJYX zNn%a-EUH$Q;LLJYQb+$mP1q3c=*|_fr-bsM#cDI-k9!YC?d=}(-Uj?9R94( z>lrVN?2)Y?_{2s^{3k1R)rfr;lfj=V2oILKf9U63z_U}cF3x$BPC@l@SKiX`!*9od zboUAGDX$v+=0_Wj_rYdz4z1^qXTrv1Gjez35>Qqlm;IaIf|>pztz$2Fl&-+N*|3P^ zqs}f=Qp>oD9M z-}qxm1-7@faj=yAZ+E~^MHu<)5+{SF=*uqZManBZ$Jz%sc@({_c+rnZQQW;*a#^2& zdv-d=UR(=&S)<`FvO%atu<%RDW>gZr5l?~bwl)Vr`Es!t-z02{Tm%jf< z#S@gtUskAyyl&6!`(ea4n8_L!k-z)Ivwd8#7NM_K#$NUFu5Z5Skvig^DSaR>x_PED zVMVlT_VCukER9B@ifj6Ym3-hqN}8^13zz4Po@FsQu2OiZ`)ynucBXLW=M}pRpnrxz zvW$`v9=HYjgTo_^!mNaO;m8~#;J}?rP?R^i_!QVgl$Nram}>n>wmdOaRz-yXSBBM<} zyfk@mZUxUBo8KAZM~icU+a1z-F`TfqKBqW{(Mz~O59Ia8(DX2&Unw};) zilpQnBAG)I+^5}tbHi6oI}J$6sggL!U{HdJfXI~q=!%)|-qqBmeBhYTN^5MOr-Y+^ zwo<}2Gxidky>9OLJ+O)(#}aPq`73cWX{yzcA)5-iDQLwR!N)vFb;!71>iS3E570n4 zsXhQWB>7k`w_P8@*^0}TQSnQe)<>`I$j{`J z%{DW|3nX9Lh!%2X(D;pXf)RgqA341NGfHt1e^!j32j8KMep2$-v}&RxcQanGzavru zln{n??+XR2O(QRi`{5Z{q|`uPQM*-=WKSY= z+Yk-5`T<%KyN~zGCbhRboBEA95s320CwlTj1r6~J1v;%L6Yf=$nF;dFKbhy? zN`QM=z-BT>guC?lObYvR`dl6`L7i|UCT_P$dc-DP8getz*_y#jc9k7HDX?ouVI>Eb6ds0fBzu@+1fL&@~(&%v! z?OY3R4j8^73zJEais(9t89@xEnG=@1^?Q$%5+z23-IH1MoI@Dv&Nypl+6}g!P&&gl zt0uReJF~F&CM94pDuO3Pafw@$;z#_P zi#Qy0kfdrdMlmxn^^J|;G))soqbL5Li0F;`xQl^;AGFCDf;0Q*@Y=J206u%Nfl$<) z6p2QzGih6TUqvL&5FF@)d_f$Assbhbd7I)rS#%`rpNG-B9)z2ogpOph=s>? zvRu9!(w1UqTe0Zf5C~-2#nB~O4NpJE+kOXy%ICKUxej=5g;jPFbzhklQjXX7zvFK1 zGKzJxT>B6bqFJx^eMudOOk)f*S(uy(%Oxog$q zH?h$M<;0s==TG3N>h;G)&eiok<~6F!`C+C)6i+5Lt_QSUjcIlZm5PNQ+mb@25eR>C zOt0f_De+ge1m`~5HmZ^(D;wJ!fYVY>gDz?DWoABt18hZ@TzY?c zr`+k}vw5ABUQU6suek_Te=F4m1m*vV2Ax7+J6eHt~89F20 z)#+#>rY!EuS$k3QL6%rpE$~=Dq-SKH0*cb;bV*9{c;_}ajeH0F2^$+GOb-(e_Q(>v zRJ+&xDGwYj4@tcmKemxxZN0TJ>@k_fMSHj|H^a-~a3MA1Dx*kD-FYv6LZCGxs^ z*p+v1{A2Q~FcV?Uokv=I#IweY0`~Odt5vEpVua5Mbl306Gc@mE(rARPJy^Aqk$KG! zsUV}XOF`{>%@VY)@1d|^oVDhsQinAJE@3)2oWo>C8cbPr{lDHLl*Lto3(*c*;fn?+ zbQ;A5aDP0^X3bN83IJ$+jeqq`aa??xn<}~)EJSDsWS=}5|54kfM{g1Pn&sqinptJh zGJgi*x!*c?ytie=8L!HHgPHo~b<9=f0%4^~ODn7V(80Vh2|O)yn4Ww5MTSMc8uT-R z5aYLA{!|;qA!jK&P71)j$xjIY3gvTEDfpB|qcytdl;NMmJp^64|E8QEm z^?N=S?P*p~jM`l!;uwHvwSGR<`h}wM@wFvRJXEU$0F6NAAK$v;{ng|YsHYW+iyDYB zU)3T{$Lz{B)o%P}2Bv*4EXPs**2g^gZTO@mEiDL!V`sOjciOy>8?me0ky)H4#(*x@ z^Bm*PPqA?kUw*~xKVRCSu)C;`+uEcvv>VhGwEJU~BogD^>js}TxrN+vcc%Dh+>|mP^ zC-iDMp*2~=8DS!VP5AGFs!+Wo1mV`$D5_CkULIYWCYL(!Tn6`X#63LWhp%WH*MEOv z%Jw#nRONr)yieTu>ynkOl^>;`g10$o$=(xIxK+THRuwcpFth~k=%2P8r8Buj&d9aV zmjSYuEO0vJobi+O86?yn*n94rhQ42}V!C%vTkkc=@L-&TSB5_;{B1DOIK%jeZ&^aJ zJ!a`7nyP7>9P@7@c>G*~qLX(=i6MC_Sv>H-XQk*4@R zHUZt1zTamh=Pc!aIzKi^GD}7YGXCksqem+6M*(k;n^8c1)Y!IqR92 zahb{<6@%a1le4LxymeJ~@Q=j%Ac~S#MmEcA^4lNeG8yt0QV5UH;VaYT5sfQtuIt3K zpWZ2(5TTvfSUn)iis_vyv|Qh;BTcw~S#uC=)1__O&30K138^OZd?^BRWn!3D4D^dt zG4;I|05{s^1v{kFT(P*xbQmfb5g|4G2p6Hpc0Xrdqgx*k%R4JqI(zhIoc{XxbLO=W znFY^-k@DRH9qvJNI%RO=z)5FI{}_D_FJ%jmFl5A%-J_RXfgA#yT-mf?Fu&cPwr=IXA`!!MZ}uXD;! z@cI#D<4l@fVd0QrhmVec1Ozl5g5a879w`H z0?s(rBB3u~6IueS|Lek$hh_AI>(RzRSw*@v54iS4Z@_7HO=7+Ek!>Tak1fwcfVeoR zzw4H;*N-22d~cqzTTW|z?EhTJ%s%1k@!lAtg1b&Pmxd$-+r5nkC8yJhXQ8xNQ~Vu` z^+T6N;|YA#H5J78i$RIi4qX#>?J;(yDw$PNRAS*)P286Y%m-kKYYN7x2rr2EV-%e< zsVI;|kFa}&N06$GqCOj$?&{s6$uGCks-y4!D4S3xMS*mB-vQ}&{SS=X#MKC(A{-6X z)zyj<;LRBAvQiH7l%MZnljkD>Vfwl7uIo?%sQ&Oj>nk!5ANGmF)(=6eyYTkN{{0rG z{Iyh5ULDGGi!`_rhi|h@Pz$_5Ai$ei@~*^FhA{K~>i)Aa*V{9ic2UkPJ}T3?O^nTPR*fBOo1!ctqJc-tbQg(Su-V61RSrB2f)n7hx|yByUw;8L=*VNR41O1 z{~meBPF+mtO^xqY$SGhJ7r%X{o5q7iDaK#*sDp@a{8G~-eSdio_4>$YkoS$g zP)k(ZvegOKQ*IAT^)JF=_wkFcj8)mCG6spLqTa_RkEYX~C^7t4BBg!16SD0{D|Iz# z5!iE%hG5`#Boli}Ag9wZp_r8YfHD;NqVrYV#uhxDIDwH3{H3TCCJ)*V;FW=D0G0@m9{vL2)c}shJz27=*4khS){5nYUeR!YvvbX{ zmVDYuqzKMA$l3z_00?TxW%-^{KF4!UMXx&{`>?8O-%HFTvn}tzY$l0%?9+S$l$*F| zJ-!*MBaaQK{X#nq`OkThc;hrFE&`3-JMB&4n}4gAimOp?F1>>v1I5@I6B zTRJhR+We$M_sV`Pv|xM>_`DoCK}1gOpA{0v078eujr)98M}%f8NlGOPYq-nyBI{!n z)Py}}T$iU+jkDAf0$E?-&3ZcSFt`neIj7$Ehs?hIIt|12^Tq&2qc6nD|oxCtyK6N(xp*dA{L_$~6l`81o zQ+^LmK{`(95*fvSBc(`mbJ@tkf>lt6q4t#jCkx!XUP(H=ym&b{}%K;0W<3}jJc;(IL@*R zOyZEmgvwL*7~H==Igl5+@ux~xR?JiXJZRNvF`mz9;a-~mkGDLcVK1|d@%FIqLU^|{ zjkpI*?a_L34j&~X$D-e_v~33q?`@;Kcf1z(SO`DA{mUQWE*UNL%Wqcts%@F=Pitp{ zQ$PMaOZBaCy~PyZLX?4((SA-p-q=9+C!n%raG0Q|3X73g40ZnTun7XOxvEPCPUy&;7GHatpS zU*vi?w=ch8GiSUu!jmZY4yakt)+4C0LliD5#Epx{Dd!kvhvm)RFGDU>Ztp6yMbSGe zjpoXR4suv=^-*wTxHws7UDT11kdWOEHgz9CyHzyik9$frk0DG0s9C9U)GvEsxb0y0 zO*Z0MGhG+;UlI2Pia2r9VnU*?ly8xNZZWPRbWEtXeyfo0O3KZh`7JvfMxkstceMaF z2>M2)3HNywXp;a+9F>dha-Msj#Grxl@ZrOjW*||fyCJmZ-$FHyNDJ5i1c{G9fC2{% z3l#y|%*Dk8EHOTW{-w<;wHKjHW{>vch$&ZD((Tn5Q&*`-KlM?+()$T-`6 zWlw*YMF@i=r%2LS1!F&U=h+Q0TtAu9@!yr-biPU>-IPuARiPL-GQ zBO{}n)=S#S$W7ow0MqT205zno5K~aV)phn4=5~toHGgbc&*B-vd7c-0BffwCj->Pt zixF2pjLK!gBS6*pLqkn{TZ`^xx0#0O+qZAiupuZwp0sLx5`QSoetg2FR=GqPk^Wn2 zd$+Qx>b9RF?Bi9TqO^)Y9T9q^R|A!Jq9naQGcGSDgGMPH%+kkT3y*sV;EfmmqP@nI~#ncIOlys ze;nZu=QjD=WU63D%!d?k88ABWI4nzh(m{;0FFt3JPy7s>wl0psMOkhjc%RR)0BdSa{)~8DxrPRy9=NuD1mx>}ZXfjJ zGizhuo z(<6P?k!*Ki;TsVVVi}3Ya=r0`4hJ zFsRA^e;(DwxAx+LXMyB6gakiDyagN9lSv|yWSW)3)a~udGg_9qWe>aYsX*Ngm8gWK zX4Ks1qor%*9WD1&x%!TTQ-|f#Uq&mdQe+_<=wJLu^J#%$hO99m#dx7R|Z*QhQvzO&;QX36aR!B z$mET%<*p&$^Sr_iUhHY5Omh#N7C*->y!nj;P-&+Z&4b0(Q$E%PufF}IZ1fua+j=fX z_ptR#k-A<9dGF;x(eGMY9ym!5Goys(m=jg*zB_Nl{ao9p)1|Rp#$OP-p4k0R{S%Dh zeD$4gf*u7?vyHO+LO-k!&4h{LuXy02idp%SYsvT1}+ z`wS2}{4O!Wf`tx_Gj>s6{Kx}SYOvp>3lrVNrgPhtgiHhykjx{w^$nM&FM&yohA6gQ z(fDdmMF1lp4*F@+VSmn&#PD#2N4*@DD{fx#GnnT%8Bm1EO5O*Oy&?Fkv;*U+s#!w?Yy~(E5J*HYHY^RFb%YT|Hywe}1qM&H&R+TO%LK4G( z1Bic}7olt95L4{YG(p5AOA0ahwb5Q3)FuD4yN?#Lb7=D#VOn#M=V8Ldkx37Jv6 z*bGTwh3tK{2v-vly}x~CK=1Kolzxw0@CwA)7uYT*6bb)UnKBH^FmSH7sv#!He*b^c zk){Q^lyc>^Ba{di6{$Hx%!``4gzI%nMp%I2AqgOmmkWv8B`yaqeoU590h!nrd`aBg z>RwB-t6l8BfuJ33TSAykguno?INya5kyD8>^Y`AGmc`^z(pk)3Y0ZGAJQnrMixzy2 zU5~-$;m2=2v;Mxmbf)r`CTh1Or85R+gmt#6y3bUI#-~HVuQQ1D`zmvhzIN_#nf7L5 zu(T;(bkDA-p#t~XJa=~2w2VCr4kUO8OMffX{ZOyb%)3o9dc>3$U276jCYXUs541ha z3xU9Kx|{MhCPpNzVWcgqr`&`nuQ<;uw0e334E8S0BUkQJv;}21 zu>CMh7nVAmi#4#31jq~m=S+bq6a08U_my)d-6;r!kg=()Q*-v-)^Y#vY36z+8jyjX zNIwja%R6q6OpB{v!nX%in-e6>X`h`9q%~*o9N|ql2-r@Ef^^-kKJ(1Zy5EA-#IDk) zx%?imCXm=H@H99sOfGjRq20vW!ax@#Tq?ss3QZdSs{n(xu)xkc_*jl3vG)zK*<@x$ zgKNm@S|_JQDMpeikdGcRlro8l(Y28pXV+o5f9}sYPJx>gs%flIu|u3MbS7UiM_rUt zmqs}>X0K6;8IFDFd{U~6g^GXe;6&rqRGnT-EL#F8CY!150e1!AU9`DY!|DPJ#soR@ z4^5HxYmvKEhLua1r7W{_bVKzHnnW)#Z4JS4vGZOp-@GZmJ>`}+w-sTi>Xh#T*Szgc z_WYebX+oTf3TH*52&!ad9$ZTb`I1D4V%iPMBEH$7%Zsao>S$a%)t!)#&{CPyZ7KVJ zvxc(F+M?cQ>=0bdZ=Ikz_m?_EIzsfNs)M0cC;(Lx8;g-$`?e%XBK-@+Kdm$<|H!dC z=&comFA@UH{DD6Yr8CL1zGwWW7%x9du0ByvpArgp_m;O5D0-$6u>mJ}meGE7i2x(J zLAFY^v>8OfTY8T;P;{h*jPm?2mbI@(-&G?xydpHF#~{V-d(#pMQ{|iU1vv!>tq_tr zfzrL`1M@{Lr`_>Y$J&@CuYI2=pt8TZ>lFUe^1o`Gn5Ew>)Q8~sU7m55=zeQJLThJU zeAcPn+$#j*dld@sKyaxyPUtn)4wEPv1=HJ`KgS`nZK$fI1W+Ce`mnC_2^pdMBsS%8moCJH5g`<*2Ve(}z1T@dQ zs3re=S*e{sLy>eEqcA{I<%R8%om8u;s`8@;GV#mCzB2iZy*0EpT{ z3e^*})b^Im{7L%#(r-wTr*Ovy1%RDKuK)-;+;*u)f^-}YO1fue?Q_5XH_!D*26#?5 z5VAOsvMbnVpyO>l(r91Ve-axm6xT!|t>4EqjlClqh@l@b*5Ch$$oP}9YWnn-YzRZW zkmsc%j*N?2stUt`V-f@x2$!HIu|giJJM0L=zf*_;4c@)oe)BsoKQ(JgMeYCPS=Pzg zcs}vz73saV&(?1a3!sEW+u%|Mb6z~PxGIqHTyI_JE ztZjE=*-YAx4LPQ=2a}L@!g23zZdK_(cKkb$l*AAOXUPjPC+spH_i^0gzQ z4$jcV^93H1ePi8MCv}G;PkABe$dwx%L{1(SrK{R>D378}5GKTs&lX(@V`Ah18|a}y z?@GY5ARYo4q4d6(*ED?4UPQEb*X09C3jPezN2JKwg?sxv#@Xx@|E})|MvdIFu^)XQ zp-e6J<6V{;7(!5yj_8_+YKvTI0}G(%a|1#(=&ZG-oParg{Z1yB$dEnK$V>ch`HjJHI=#di=LM2jW3A>4)!P##cQIH_B z*}*~MGi^d>izLc;yxpPxwww`yIF61N)%egO*I}8ufvGGL24XqY?(;?8`b>-hW6MU; zUA=5g(th)#V*%Z2O9md7B)jv$yw~Cx2T8UMXX&r7zkesBZ*^YEYBJqUFMdskT($`t z>K_k!CFbuIh-S9SWzO?o$A^M@pSi{9`SVgWEyA-0V4@OdRy6@(f&Tv+C&45a;eyi+ z+b4$pC9k42U4ksuz#vD!J28G>7?I5-RUMnbrG?I4L^mFGpGdtoR&rpw@D1G?1uPE3 zGRtegodhQAx1}~_3k6}gUnDC+rg}pk*wU3L>KLEED(3Avqvtf6Zm*GY@t8ZhA%#es zdOq{><{z%}wS;|LJP@Qk590=^4HJaXKtVNmQsnS)_v<4WTj9Q?KFWhTA6r_aK!gHy zmR^|;gRGl=#qnUJ zv-!vhP{}+{B<+wWVoG4k^)}|QJpB#&*5&1835ZrD!DPGH?i#wTS*gckY1|~9(h%oH zKpnpj=eYOg-t*E5?jcpZM@JXGcm(H=3pS`4fQDdVrrzmbHgYhBo<3^?PE6Z=47WYkdk$hw30K zhRukwtzhHg{V9Pd>-E#k6Qdj`q73IYD#(H_e zE~__%iD(3e#z}&l$p=8}fF_)LMkS*3s;_9B)Gm;V6lPRI!^5|xondSeVgI(j0N!VF z{pPO7UZ&E-oRl#Muegt^s53>DY^F!9p~JTwZvc9fH^BeygWOq!qd99`L8j+gu$;ru)bs&V&ksrJ^L8aS`u418OtOO*Ys!;}=VrH!hEYmH-86`RmP`}dO zEvaF!fO4eSvMhI?)PY!*pU{3=s;0of!GSl`$qatXC@82KV+$em*M(j)(7Erclb5hF zd5m3>8XYl}s%L5}jy>I8{jA*qBMcn=#Ms5!k;fS(`RAsTtk?jvfYd8IHI+MgPydBO z`n%NaT}*0h-oAql-)ExB9#0f(qB{K~eUEK55KnuprVgaA$}=fbWnw8ZPTEJRJ+C~> zEe^QX`$zBQ2Z|+l{6EkLIr*~^Zs`4IS+WUXSjqS!FpqSb7zHi@50-MM&bdWnUk4;r1A z+hfK`*@eKLO7ij&FhUAW9|c|5k_Cf_dBNJfKBr={;ta@f1wld9a4*sh^VDd7ZZ&c+jdHZ|91^;!+%3x2{>Gv>}^B0v~<=3OI z9ow~chwJV=9gNNK^{MS)z3rD`XI;-mj9o7*^M~TzNiK`swgt!(?1$5fih9-A>5J?s zTJZmU#D4S2?8ycL&j6XH`Pkz6_3MU{=^MMr3@kCM)_Yi%mFMlYr*cSltyiz`B?f9T zpz#7B&8=WXi6RfJC$kx%5W$Y;r5|xVx0%_yH$Ttfb>m*yt1y(zQyx++Z^SLGE6;_} z=ZGFJk4bJ{?1gG)UExq|A;GDS4|dGc#aSZJH=7HqZ<*hal>3>7efqb(h-}oJB`PUW zQ}!7J1x2tKdC9^T)ZvOatUS#H2Tkcbt?k*@*CEZ;@$vJHjTrJXFOLs5<5PQVN3RVb z9fq`K4C@sfvHPF#w+i@7-0m0nlWz=tRegmG(Kc1@ih=;~ zw1J|S_5}^-H~^Qmzed$@*1Ci(DSMtREt8*aa2=)>O%veNhE(_4@m3(>R%k+RdE^Xal&b&odQ!nQ^y&j6v6P=~6P4D8$jTcc3u%h=D~l&z^9Mt)b%6}f7TAuT&tW5UbPhG_Ln0);F^N+V9_Ux9= zqfct{nL-Co4ErJ``=60Dn-X1ITsT28Sn;c|I~y7ADQ9gUSNWf3yZJq=#GTjTi$_t~ z?|VoGW_*1KTLkp0nvBdno2%~Sx6O|fiTOU`4+eV0_e$%>vHnPD`O+Rv#+R%tR{vM2 z*Cbs|yE1(l*uLI0^1km;l*vKP!0tGy)j@-XhSnnRU8y2RlP=FEp?Wx%=}Jhi zfGG|1$(Ji>mpDxyVjg;WHu{!3FvmK%3QIn6aB>!VYZuu!I?6tE4OMp#T&|-_Q37Y; zM2kk93iM;NR<NB}2_<$b%l9OJTG11ZH9uBx#D6BR*^|=Y9lYA#d@scae|7)p=>BH@qG(Kk zfw>MB1JO5aoZ+%}TgGJMqN*Gx+~65-M_$4pxV+ zLvZf&KNm+=Q>8W1vQjKf_57G1;JZS|hY~)BZG|7#>76*peC{XHI0T~N^46BF&0owR zMJ;WHO60U$A`)NiR%9Hv5iWzaGp-PM=bcZY_HNj>6?L(h^bg$@kDR8`r*l7`C$roU zuZbsJ{g(@nO67iSaPV$B4b-fBqE@tCdzClvia_|bet!jHXE1`N5eGu0bfDH{1W^mo z6Uq$v!_w67!7m13qB@}dt|?9ZQ~U07b~aX4R#r=uo_6Th7n!9_5|4~rg*y)YqwF}8 zyyRKt)MnbAmXJLaOp!<|c?`CW*C4~0!mPW#zw?E3g;&cO6)i2fMdR+z+xl5wlW?_l ztn$ga?Ecg^cP&-_Buo@j(z5=X?gpKW9j-dh=--2eg(5qBxNL+B8X7xpj-=tL(55&+at%*snZa7 z7=vF&PJTXV-V$J6h+LG^z}IsIJ2-}KQM zdXIiXm;>8VakTggne53DLTH0eC+0$MD#Rh-I$~bUB7$5Ns2!KD_jlX<-@uBr8 zOwkT#=x;>Gqa!umzkZQsGOG6aqUJ>>YrR{qYn5dnY67)W3HW|mxO+=9&0am)SUC8W zYiG7(EeKZPPxL58icAO_rwJt*CnU0Z7TlRSa4nrDbJETYW8RNSE|nup^(dr1so{2V zO;~PU=A`D1&SBC^i(T2{k-^Lv8y&SU^9>a8isB1qB5{;lS{9h7D00*06%~_?NZ(dic^^^RoYLdEEEU zJP0K{y1)`+o7FbviAVT#!{8b7Ev~9bRD={pr)P2zEKL2VJ6;3Y6`|wiBo4x9qhgeZ zAOM5-^TZw7iAuGt9T9EGHf}SzY`?=$$Md!C;w?O>?gR*4Vc{SMMtC#bP2iipYZCjW zd?`nIrS8@ctNh=$fB)#CCWOD467cP?Qc>wOF!YBruGmd7P3{rZg?{TwvHj$2b7r>2adTqK7;ImOcC zrI*j2tLsNNMf4(Nt^HvhECU*+zxw#STx#CTvq34 z%6(CvCZHAZYioP>;p4|AAmw=Kw(u@t{EMa?TIW(W^IhSH_)x`B>&*dYP72Zu)?on* zUl6R5=WpgNX1%yXS;fFbJhQcJhvEmhixw`z+~%1B+y8>0lfzr}VK!%*-OA;~d~OMP z$!z=0^>wWt<|3>1&Lw+Cj-1u(qwg=hIqu%QYvJv^D(bi%KQL-yQ}y3Ep)?b9Z=slr zFA}155t8^S5%U*;6bl(Y4IdR}AS#Ly#KAuT;<{vke(uFWJUTv}n87xzXO*+6MT|EX z|M1=DqwNPwft`1JB{ET~>Ry-i%)GD~c4vwwtap*0ylo=3kZau2!I}L0tUStaQ4*cd zk?j}f?gokq9VX(uKkBYG!XfYB$y>Q>KUOE}BGrIx9QgieX_eKn>~g-U<+$&@shKZ} z!_}D@FabCHPoF-K9ejBdtZvY$Xa+}ei=r9WQtI0Amp%9dmsEYIxS2zHb@2)UiP_j&?JvU{t&6in`{Hd=-j7*-Ic==x5CTO zAxrK1T34Ec{m7*f>ag>>r4W(*u+8=gG*#L`Xw}n4$Z@ zuzps<|67It#zfC{UXLzJ%s2whUq03o#n#ktY++;i`oz!4v=o@QWAb>OseEF=h!o## z+|S|(Dt%V_EjT=VzeWI|kO4sfza(*^67?#lj=M&<5JSyZLML6#ofaozRRcofZ^>Tj zs+j4mJaQHG?&5Q|?0d8M#f_r!1_F*REfOydAFcNj6b^-v2S4+f%HUfAy1;;kS5N+}X*w(vRBN4V*9^hs0v?Ts7Rrm{S>7T}>aSWwNySpB+5J4`;fjuKhP#}LE z1|IpXY>m>qac0uv7;^j z5sDB-B5Vd2VWwP*RylCC19An-+iN%`uKn9A;$y#mc1hcE%;)<3raAtUZQ#StAf|4H zo(~ffljaBEMWc{a;qmPBpFdn$@t#*lo;-z=6l}xw=d|IzVx33Mw7SO5tY5xFrFJBf z8Q0j~Vq<4-tzPfu%+`(QIUTHR4PWdMkny@j_iOVOxGGWyaU_S_65mGU!N{LwaH|Unu6dqS zdEzxr^Z2Od!M=Rq_G&?vJSI2mxVQBzp{yQ)cr#O7?C60KQ>`_98vl0+jWFrJ?>V%!2`Gc z-jK2YB@Q%7)P=^5r;HlJADss9J2Y|J+zrHL9)99^|_dgzmU8zM#f(wH}lfdrRP=EaVKn^aKo46E|45RN<^a!iI&$MeUg=xQ7teg#FrVC@YzDr?z zjYVXqWJ?GQrN+8-$uDGePc}|BdsS=U^L{45P_E#g)re1fL?iCKc^y{90`xqEbdJnx zoy^I;KPQ372%IF1SNt8^5^QiEvv>^(_{vL)ZHfxf5c-XbkApLuo!q#?+DOnY%rd2K zbmO!`WXA7GE+0EUvjT=uct5kmrp*GD2{I?tU!{G6gTCO(3^2v72;IUYt%2RgdDw=- z$>}@ue;+nuIG;8*H%He+Q^YfVxkbc)fPv=?M7hU^mN-v9_8@WEdG)gVlN8-D3q9l# zB4&UIj~dRBsNjzG?M(XDLC4XbO_V;5hS#rooKD6te4C?P?C&#a^%~iv71rk&T{o_! zIR@~!aq?5mmr|{*+g$JSHlZ^6-$OK|oiWxOuMYAA(h3vlGXEcbssWsc`*?aQ)GR6`de% zPxG{?fc^LkOn~|)Cpp_bRa9sT3p%+1xH70Jjw~$@3a)r`Up1>9bC@jQz7V6Z(-)MA z9+w-H{uJ)}ZDF1}E9)vCAV78uj0Ok}3PeZpM4Uzbv;=QHzW4Bsp5k*j0%!J4)WEp= zc2OM(AVn&jNrmqCywVJ=Trcv)OziOlch4Rj%FE2S)c4ldO?FrkBz%2WhBbEt_yvSl z%zdK|Yo`q%vag372jHR9@cKOuIN<*8p*Os~_FX?1b z>BS3N#5SepL8CuYbw-`kbCC79y}yZ(Y;Nx==ZY)b{R;(P7_UK8Ust|g0>FECo%|N8 z8Aab^nzjj`H6>m26mbdWW1Ph2D_eBE|2jf!kgb~b5JuRaX#`P){~Xq2#Y_}3Wt=!` zYsWB<3!k_#`U!^Pll&eY_UCb5QOf!Hm26{A!){k3=$K6^!PW9tu!lz2Lnh*Wk4=j% z_ef{qI^|dk;h$MX7@}OZwl~S7z^sSiRepXxD4I~ydINy-gs1WD%i6nqjZdqo5p_2g z9tzn-8dSQf$M7Xdc-aVWg$G5YPt7>q1uFBBthtf7XzAzNbyPAZ?l+y)j*j7jWN#fV-UTado(h5 z1aju)=f91n#zxn`7A5CTOF)!R7@xrWToEql943l6*G zFyw6fJ+dXsu=h6MwZ;k4-d{W%^o}*ggV!P#kK%rd*v(_ZsIC}THEySaX)3oN1gr7} zdZFdwPXp~~rz@v)QCzZ{OIcQO!R9JD`mwAOL7bK^iGyTl@D!o(V?tu!zU8dTfj{gO zo+o1ENyNBu8+M?g=sM-E8{41ctlJNgXl)TR_K;Vf|H=3Z7EVle@4{P1I*x%~O*8C+ zX&dm9aKf6ABL#!`Cnc_bUw?muM%bw6$OFNYaq8EREq?Zt7y$0kOcUE!ms?ZU*Vo6# z$IIiiJ^K&4X?ha4IE@-;E+Bb@kI(&Jc_>pRLmdHRrT1u_o^kR=$A81V15jqN6cmIr z>AF=9ODMrYB6*Xn1!UP6C?k`T>p21PWC@S+a&sk(jZ>wc9EDh=kvbrn*u@XdLQ94C zIB&<|B&&T{gL5g>apUK6tr%f6lz|d%B8K*{zqxroYkviJm!Zv_uZgRASg#CuAkfD; zBDhcHER-3uSvigCgjnPCMZ}8i#OwspTt*i4`8ows z0BG9U^0dqrGxMg~bj`1=gm(`SR7u3xRN`@Lmt^si;fGGYW7f8k4!>mkshhBF^zAhx z@Yk6G`|SfwB*ZE5-pR%2RD737)jUUHy35NsYR0{m*?uodS}Lu7{C%@B4b^eP z+@{CEooA172q2(s0R{+BNGrgf0iB%+{Zsa7>^wY1th@d<|39X_JD$t^jr*GsMTD%7 zS@te_hKyv-tTLl)vUg>MubB`cG9n`@Gkcej>`f?p&*!?&?>Xmr{B>T96W{xDU!UuG zuS;iPCnbUzGGs1)B_Dd@j{aGF+YsG7kTYQHq5N%z=hdrM4$}=6h#a(s?in>Sj+Cbc z?FX=jYk$3tYFOXTEG->y<@z{UXk!mgngOkl6r@#dBW)|tcQf@RkG6PFP>^1!e3{Zyw$@_fNH6@Faq#)&-eL0~&9>a0yItBEAW8kMq8XG&LjDwX}y?XMrXWy{LFf%h>K%KAlohut^VsA5E4OKqZRFh(h?Y;15=nlW@ z7N3t*?B6*u3Xz-JRhxE?lckraZJTJ@Tt7VH+?jv;I5`6k3pXq8%EYxKHqvx1sdolE zrI4hvv%4!?xE#Wz!jaou0sW^BAxsY-U+Q2T*v=imAD z6x*?Hy{`%%sHli=+|ioP9G=p%Q_?pQ88URq5ALIqScgv?wB^*+9>Q#{-qq%Xy%J6L zhq?wf<^a@3oJAO@aZoyT?s;NUD+^vt$A8QIEw8<$F6gXz9v57#}&Cd67JxHNozn_Ty(^Ne=+D=_KT%d&Y4dJ$_|>WPQ;zzCtcm$ z*H*OSZ^~3(miOR#bvGmKuo^LgG_<~^ia!Lr5E8{S#7wK09ifMZCXXk(M&#yK3w>zm z?^bb;;9^pxTTqJboh6TBU>=T+k1rr8*&Jk? z4`0CUO_9;2rL@T3`jj`0Q7(K@`4_zmBD}ST;`j5;$sFfbz-CV3)_%hob1{)m3+n{|;L0D_ zFFZOqw4XkhN}xA8yPM)|ipSTR`tr+K7X>x7?Ap2yEw%}j)bpVnwJ%4W^QUJ~Gu(!O zB(&96gjdf9>I$u>E!s?Z)dkR0DN<;~6hJc|CscaR$==c~m0rdoxOnBQwi3fbayqp- zvN|?JhORsd((HRCB;}NG_ilaIZ!VJ3ZZvDCVL)9ir=&KN&SS`TQ8Kz)tz;_r4H9M% z$y#8;t_^Kp@|tNNc}JF}wX?(S=g4#o)|LVFC1|KVRJ+3^1BiJmv*e*70O;A{eUJk) z7bUq?dF!0!ZaFp9O4_sF#*P`iXSaT*h55g}muc!I%|xt7zZx+3$Q$*-Qy8r<4XF|+ ze;8?kYjJ{CJeIG0tgf#guk+I0{`N_kp_#MmE)p1>URK@dt=K^trpKI zbr4dD@adMXC|iS@MFXQh7vr+iZu#28%>KkPE0^drc65cm;0)|fd1@wtr!`K%XcXgf zxV3h*4Gv!W4-UZB;c5RK_hFpx8p%evFs$~Z zG3L(_L`0;ZrkSv)Et(Y5+s$pHr7v7gty}?Ea8wXT9~y ztOWX5Rh>DVSdw9ac4wC5B6MwaFpbVNRV`@`EMZ=#6L_PfMJ%M>bSi88$EDMhG+jM{15|n}57?W)oHXsG|D7v;*xYUyvi1M8~MV)DGW|4V&WP(Wx&&JKRrTs#qtXhipdn zPFKc_kQ2R17Q(2L-$bZ}@UO|R?7e_v{CV47lm_O3<4}or)G<%jw6))teci~dpM@!{ zEBW{156x#iY<9j}+Y)9hRihrLeY6(B*rR*n{!QTpNBS7OvlDfF>)*IMq?-&u6#*ob zd^4QGb8?+kU$|-d(JOJGk2H#Ih`FmJMfFaE+>E~*N9(N7ZECP-R!o6F)G!agBNJ(< z(6@`S(En^ZCe5KKp2C7n7kD8r@Vz4-TOwP)r@M*wEf+N8?o`2*|w z>;qYtMc8*V<}r_q`13Yr_W=kOU48!F(=$8*fd+PZNlAY+z@Y1ldI>i}aJAEGT^c*C zGw?^A_gv;UQNJ@;a3XRq@=xQp;G&n167$MnwRnfyORc1q?38xYpWp5DYEGXDWB{#!79Ix91$Sm*S0i^T$|0I=NCdyi{#maaSgxp%#7&he955k5C@--FZ+ zOq&Z*Zf+HPsfL7-I=NR|l@vvW(LcAUl(ERk$;})b)Z%hW$rXdshjT5374Oe;AVcBa z`cxD+ZJv#mT>>WIo1N^9BG_;j^7zn4ll9r9xO?Tbbb-pZRKvrkuUhq~gin zzTN`HQ8o$RORc`6*J_8_9U0**Ga*goHeP#|GkhS-{6HlIX6Hk75)8j&bm-+T{kKHEQ z0DmuI=dSC8T5bj*bK$hrFR%W4ZD9t5M?R^$y3o2#45Wx&t>+i|q$~K7@*ypzv+`ad zVcLZplV#SLO8Qxocvu)fyCthXlsNW751&N0JNFyfnxERe)|}mQ&N(?) z^P8vF#e+GH36yEl)Gzh5PF_&3WA$Tx$MnSSL@(wx9bQ1+vk8m_>tOo)#0$(B-BA`r zmcrab{VqO@)OS22?;Kr6<@mJLv}k`5kkJvqR2+-we97z|8{G2c6h~B}f4Nn`N|T-> zfz91kRF{YycHO;OQLk9Pqdn%Dr#)dfy%eXbV-yt`8Ro3g=`j-Ct~L_q5c89>Qs2OU z3VBwrdONr+f1F%94F?B@M)u9+vJhFH{#^51zp{aVYrQE?79{?F5gJ)c0s6tmV*;>K z8(u_#=HC2t+p&8r*PNnTZ%Y_Eguf;Nz$L3T(IV8wTj)?_ABfN&kb4BkYg(`|oA*S@ zK(3QE8H3Y9Zb^$Z59RcwGOv9*=wLGn3Y7Kh4Akxk|9uwpxXVlyk2%jRZl9CJE7e`B zP+KCubMq)-*2CH{V%n1Sy_e2b@qa_og*G|)+a}$YFEJ$TuTR-4Si%#$y8iPnsckq; zjFPgxwnCcbraLu6)U?;SF(dMut^U)Se&1hwLHC(X_4mE!KA=Q3XsU|6=+9Ye{+;>w zQLmVKcA}@&+SIJnh2D3fJ>o1kCr}KP?&ye3e%#@@=F?NyZnh4;Vw=R8%)SH_vbcQ&L!s zT^b&nskXe+*Z8I}18wbvjj!3|`Tco;gq?pidvFeg+XLygC~gjCoBU`WI}VN$5f@k>5Rd_UrS7o*u=%IT-CS*d(OpBmUI_ z#9gwwVg9+WkRZV#^c=86(JA|eKDRrW(;teaTVr1fd2&RaNP5u7+k4{b4|@|+jvTh1 zYg}{AxrIJXN@c0tBbYz$DB`vH;bhLC7m@iv(aH0$?VNCt)8MAUwb7%qleMMIB0?}; z_9s&MZ&)r)hnZ{BNfE>cmnusP90IUfdA^v%r@hd^VPMs*??B1Nr?EOezg?Jl_>s*W zf8%DyXYx@#BkdCZBg%YSPC>bM%4#0ysw{kOP&jG!cLn^?a?O^R?)V!U<(frNZ)|87 zF>K;Dfga|(N)_Cj{bCYFir(2Ey$>7gM(R@RJqm+IeEW&YG@%t!;9 zJ-U=G20~#9Y;fHc(CLx)Jlpb_aHXkS2(ejv)%190XGaKE-DnCSmw;-W87@#_Pn?4| zgPdK4v_n&p58CK<5xz9PA_s2A3XuhYmBp9is+aZJ+oUTF7RzzX|9!lV(u3&V4oJc3 z8UWvr0?B3iJ<60Ji442{*$cA$S%dyhGvBK zQj^}E|AlzpMtm`{$>HF&jV70$ZmeETpyG z#livj4H>5MwrYnh*_rUpyDsk-=m_=m=IVM#XwwN)^}1+9&a?I^$`tvMk&`nLho%EZ z1#((B3yTkG0^3%WsTHNDm=#mDsKK`J$$L6c8WM$Ni@(>_$kwZ=9KFCfh7ea7!8h&# z1Z!){33T79;NW79ZA;bn#)21@xqQ_{;%Ssb7NU(_)qHLU%FJ72lfEM$qM_qf@HF3M zZEMxHo>oRirZ5~8_uSO6WZo?Km^VzQw;}8&9s{ z(q}Skzg6?ohs@oFt9`d4E%;v?{NhD_`nTfJOxvJoztRCHI8jpt`s`RGox zFN8>$U@?I1ti;wJ+7xQ(ZetazVB7ni0PpGrgs z<0WFCRO+{Hp&qHM5i@n#wIpS7H&JaW}%)eFpo_ zWUT>9@`CTfgarjv0j;Ag?_+2y%p7PKF1llco=eI(-BGALgm{H-W=F_0>> z3PO3MC-dm~j7q-0k+4Vgk+apL<6$k|iyWwR5aL*jwHxohS$tTfWWli?JV{h_V*&#& zdZ#8~d-G@k_`{b8tw&A&QiKf+S9`diq{>5VFD!gNGZt)t-@-Q6&5(ii=xXx|PzHfY z4#ygN(JyvaV|}~gCd+MM5_t@1>)&GIeO+ih4+v+r4`tJN=yG=o3JdSu+hZtr=mYdM z1>d6O`<$KFhTG9qrdP6;jz0U%7`2xb%5-3!zpOeVm1-64K6jv?Y|Gp@kMj8~W;HYZ z+dxn4JW;4>!T-sA=ns-#U!EprMnUX-WcfMUmIq*3=3jtZs#eY7KRsWFdf?&7yM4S( zCj9C4ytmh^Zo1Q?Wauh)nML+ht}SOB?3_7=(x&O=*NK;7Y5nFI!8;6Qb(_CbF0P%{ z3uY<@AM(ZGI@pfV0_&CsGfTC@oEhG5fBYEYtepxMA4n=(e+fXg=ggO3DwVO^Yy7n^GV z;^y`{>>`LU_;R(e$dONQLMo1J!vh_82QNU9q{Pb_83{~1=o(xwYFkWs<^837jS3TE zyG4#Ee3d&5NL_T0qmrM0pW|L7Yxu(6repfjhZU;6`}+qfl&Kc-B462DT&qU>+Yhxw z`R3(rq;9>H6y#2Gt=RjI2ce*NuaEgpFLVCC$BSuhkP#HAR`yHhWOmjRl!A~9jO3-F z{MidDF~Bf{koQ0fgCHa?KOdU2yBSv{_I8&5I#ql4kPRXrA5Q_-YG7AM78*bRV9{gG z6?}|yM|LG&o$yefsOcTF3H{~~H_zU@pZt17QPcM+Z(I@@ZidaRecpp}*a3`LVHTx0kA}4}40K^(OgPgv9bx*wZ4&^0Qy4N3Tw> z{eS#Wmp^5D|93ej?H*)Cggw9_WKqaUPr0{d0E5NTqS{;iaAof7?Ewletzyuvn|Ku$ z%aEMEpWeZ>FNCC#O+zTv3a|TD?eBJnB5d;1Z#urT+Ijj$8`9ci;E2quDWYnE^Rc)0 z91G(D5rx{Tw7b@5StOb%A8(59YHctBP;g_YgB|?r%-1o^_jAL5D5-AMfRaBwVP0XJz;c!uQRjPX?&0(Z^+OWq7-My38b6I@d`TNFT1^ zi|nUHX5?{D;;JpTbhlf6J2d+HMuMNE5WVH`NQIS;uh;J;XU%ogM)A72$kwV>2$sHU zVlSD4_Csz4AqxD<+;)Q4UkX)dW>QtuB)DTjJL7^#HENfSPO4ecEbiW!@Vyu$eQ?T8 z#xwX_BgzhNXfOstJ=4v51oBwyDz^NJ(2&fsEIT_J8)8us=zhP1J(x_BqVwO}bSzGn zwOND$2MBIPxlRw`L}22|NFJ^v>5p}RpJH!lqrGvonm=3UcWyFUl#Zq75+(A@D6D6y zbZ`vkK8&Ep3X(qgEib8bcrt(aaV>umy& z^(TU}$p(JESLiJyc)l84@qhS*+eDD(-!D3NMFaoodc++{{JnKx0~rVu7!>&J;Poq4 ziLg)_B!c&t3Uya5m#1$t*p zh116pd-ki2HhpR7?z$8?CMTYkGu~?$av8=2OCHkty+HKx?Cf|_{mGOYI^0DpM(Fp( zI)}IO3j_`h!}>`Nw%THtO2gDHM$ZnVpwVv=((2E8y|qZi62yc(D7ec$#B`VB=}9E~ zB{Ju>6y)op|e&X4Duk&*R&oWEeDre^1w z=~>R!UkNJ>K$`|MB~&W{CvoCXT!yiyn?Y;&VnwwW#T`Cz9j-Qb@=V0)#7)}T9sAL( zCR}6T)WCK#Qfn_%dfe|?22Q`VwKZ;E$ng_H9zdgz>I%~J&tZqZ@>@r28(-3{Uh9xr z`4&p9uj-oj%q1{a(h|Ei0^K^CAnC_R@7da((sR&E+5I=`W5Rt(KoK+2Fx`)X zrhpOg_us#AFjiGoz#<=f0s?dNEvdR{}qb0!Pvbt8OdA0k0ZE2c<3|6rUx?9nV zw6WVKd71S-Or3TQ!{*W164(`T0F$QzPwQ-G6Y$mrpvM;rquFxG^@@ z)M?_1mn0R~Y*iB{bvJW&v=_Q{UUv6^3rvGU^P`H**UKP@lacsO zLgNksfThRC{C*!ZOM(Ckqw@Uh_@(weVE7RoeOy#R{Eiif7z0sb#b&{D?kupHafh`V;-StGOD+QoZ{x!V$VUWt{x!0w1j$?jxNGCJy|+wsXjUs! z#kn@)7X{t?wp zv0Ih3nS52M0T;AgR~D&N=LC8;-3_Z87!uJ0hu!24wC4W&w9=l^I-48MF^V7VQnC~{ z{D15L{*MSkf{v8P%N-5Vr;z}Hp`;+I2x+usGu7cedJiv==<`2U1<1_I%*NVf*X6vX-=3soVV zXEv1i9V+^UK9*302#Nb7xcD8#ppuTQRZa{!Cr!;=wp5XIHn>8n^^-En`-}tig}k&= ziIGu82B;@5b8p@}iJg+lvv1t7X-#|q>?9>Fg;c7f9kG#~s=A9H!s6xQn|-S*$5+LA z?lLxM(elASnC%;^$Q%$St-P!+=iZg4#1IF|p{!B-Sp4X(dEQxPOc>}%^@o4xwVBtg zI1+ZAC3IL;SgEY@FEA%lKU9cT{AusAYB0K_;@c~Ex~z&V{Z4@i`j2P@Ch9{jt&tAx z4_n(ATLbjlTFnCBRQq_Hii+lM!m5_O-){~o7aIqo5o2jQ>wv7%QqBBw9dY(*Zf>$K z70i-zEIjFv=^*18Czt5;o{9DdJW0LVT&MWU)|A?^2UhUMo+N1>Gl?6@Y49f6`U|!gj23A;AFbK(D|`u*v8NzOiqufjAAbZ1Vre`l%P> z8HkW)5*)tPvVMNH&IlC}To*{J8LZKR`Uu}Q;>^s=Wla(DAV$R1ugs@zN)L zZ)r!99RK+?+2(2@Ib*gOmx}$R`T0jro+x;kGP*{64F zVO~VY-0%6}w*TlACQe23n2~V&y@$B!0fARLPqn|KHnhbjic3gDLW#H*jz4ra!jLTO ztFbhz>-rNB*H%;BjGBdQLkrE!ZHvU!KPxNWUJFi!z$UQ;{so6)!|0_eJr7d1u76)| zRzvrV%Z&fsZnM3yyoj@3^D{mpxydPMOOzb{;^Y6CM7lZ52e)-~bbKHEQxqv>pF>`6 zW^V2!P@=gr0SLsQ_ZbDj6$g|1bxQ{sfA^1DqAVE%VJ$AAZ`Vs$_%$mD#vr|LJ|w0k z1O6iDG2r?=*!MekL*@YRGwXe^Aw`(qmw4o}qfd)kATN$ay7}V`slWWImZ|D$YIJ}2 za8pi(Jb1UK{i+*$^St8{kNKeW2ngG{Y*^2i`()9$o0{)Xtfk#*>sfER^20YZcWyL{ zXfj(7GmC7>s~XR=bLSfghlHd)xGF)p%tp9id+L%F!o*$D%Gr=S-s(a|@17Jl$*Gq? zp0tp?mt7@4&$F;F_o1unQZ8h-U3;IPpnVs_MQ;1u)QGeS)&Q%Sm~aPXt6vpJ?c+e( z^9e6*A8JhUGaSLZ{(@NSD()ljw}SSXg^i6^dT+5WEiGpFHTC@W*J!0&5jYE!&1!{d zIB|2p4}yOwO&cXSA*T5yKt^6ATXP8szMtf-IGU(wICO*#1hQ;kSgSN0N8s^)CGX+6%$%w@(uM%4$szN@6Hq zmkQ}Lh*3lw;^N})um4X14;G}0Jf+&mJ~UtxWT3=>53adcwlm7IlV3pK6;#vBBtgT| zD`NY8b~w=|CsaT>!``i6=+ThzAi?4>7zLg@ecA+s*XyT+RTmL2tF<*z)-dR2WX0i= zU_DhMVgZ{VUK9wn98b$d?Nl$VF^@fQ_!xM;xoY>567gq2rm`Rn*?v1g5J|6L4=@m0 z9!JW2JR`|-zR*HmIwCbtrXZ`uUs2fsuc((GNDkC9P);nIoN`RW zjo`M~=uq_~2FC;d9dZyhoWNxiw(hg;1!9S7wpnxrP=IGgllZOrS4^P6>Hlz_#%7WG ztb>+)z-gCHTAmKGSIVD_;cdt&AfhckcFEGyXIjv{bCDa&*x5|1QlJtxy8Uw()E+>tjKP3J#g3Xl#Y^?d#zC zl7c8z(1#f9 zcjmBt`{ApxuUz%=)thWAENVwX|23WzhM!$8>iX5B{jbjAWvJnL?fq%oTIfPHHiD}O zUb9x|Z!Nv{`%~4f?4T|KO=W-rQ(!QyF9nb*C%>|7w;`n?&xM9d=BO$&&)XVOR#7U+vPul<4=}>2=Uv4&h0M5WFmogFiZio6C(8jv2D|A z;s_0Ov)$DvKTypvzi5eZfsBLe>afruhnE;R{1>Q*MK)-swYXJPMf;ZBL7Mda&YPqf zcc*(deTJuY!pxGC=ki3j7m%`=kbo11sSz~tLB=U3e|~=9YQQ4tH4WXIFf8YMUAe+# zjJg(6{u^yh>C(cSMX@APPLcuhqHWtcy1MMgifynhMh5UkF0ehKP4+^wH<|g8I+w6G zcIEE@A26M|}AdO!9}v1PqmS0DGJsj^&CqVy|r z(sK30#+aYpp0X_tSp!AdBT%V<4v-*Fhnz+8&fXUFQaG*{&-6>rvTbj`gG#p+bZAy< zzFhFB*T%blVic3c>|vb0@?%%iw?Z55Iy@^tyWN3%`Ty_Dz|chnCcb>y8|0WF=4;E# zyohA)m_qgpIQO_Z5cna_=~Kldf+fI3NDoa6be{VYZnPX-$Ylf3dofxw^SDGENanPE z7x_(25{v*8a>3NLcE+=By7}$9AvuL0^u_Y1ab8j}bRE*Jge^~yuoLh<9vEE&3-3p` zNjHZ<4y(rRw?=rDETrSX>+BHohNRs;HtU9n1j%${yH)3X^KE2$uXiI9>Wu!&iq(lzdamn`_N8~DUm}#Vco7ly>Df;nVDnUc|`Mc3;AhCOLV;~hDwzgvNf5R z8-x^1h$gFrnMo?QQvCKt ztdR6Gm=Uwe#Eqh!)49$xfBIy%KR(Jeocoj=^n2>U0Oi6wvagksKS@q{u-nD;6(|Mo zbeWoewU`u@Qpbt!4b<2Ihoe4)UrI5DpJ)FcaxrKMC41x0TSEFq>zreo&OV?jFhD@P zpGM2ykmexMBz|3X^Ib@&9>=X`g0RclKTOj5a`4%v3QCcb?@$~E zjDnMs`mgZH=brEA_VIgWB50=fON&MebRYQn@P4GRsEk^sq|z7ly><&Vix2*2<0U@* z;7!MZ!^aSAVOl~<=B3zAv^DL5MqU$xf2zH=0wHGWnsK|6C+SRLq$GPhk!X?Zt(a6Y zJ5l;FcMpfIFr6FtY9JrX5qkx`Gt-mW z0{Zd69uZUhwV<^+f;eN+X0=-j_^*-7Zetbu6LYLmc%Qo;-FxXBazb+GIQ37hAbdLYe`*iLpBTb|vHu`JdjBBmF9iF8?d!ts z?ymb{lGSH;BgMAb8IjyZ@O9SheJN@L;cr0!KFE6DPIZmbhngitH?4Nhi7#L{J~oyy zvMMi0=7V`c<4_kHX<6?;Qa>?$k1fB}bBdC;9!Fx_Jsnnbl(-w(hLX-R-gFI7KFs_J zqOzpT4=jx6XfY?l9?`hhot&J+J^vlTDO`kKaa8+^qvl#9fIo0Eux=Z016i+8@B`Il72fRFj&sj|c5Ncmue6LM7a z5UP3r{Qz9|E`NB^j}TX322kYCYMQEFdQ)7D9?DEH9293%;x<7`_T(dX z3a}{TPYq_HKZ&J}eMqu6B2>TAwZ9;;;7D`* zx{|uF^FnD&xx8&8n`H`-otnlzau1byfc==~0!)k6Cys=hJvjp1I)}goJZAeKMp?E-qfk+jXF?#LjgNViA3brc;|1vlcC5$U zfB9>~QiW$y6qq*JmtvXtnPV;5r7yTH<1iPtZ5~|ByL{umu@Hi!TG$ME@wv!`sGyZM zG$tNcu&uLlul=5@cCw_g~*^af*4cIo<43Mbtp1a!E zCkZ9E;aBeVJb1}LGT-n(pTMk7uQ|cazOTuEIjp}zx(Px zT~0uR+v_KbXa3|QE32!#Vq(t}7WL_9#;#!o?Oz6t40;79SYSznQ;nSRAfAi<5MGS9 zvi;1ZR7J|m%NayPsetE}NF#*47oKpD_6ase*Ei(e&M&HacvTQa9|wo45Cj7Q0Sh;G z8@Nw^{;J!GFQTKsH-$YVz_>q;hH?4Yru(=v-W?Q&QT3qX8A5&tk#@UuUouy@im5`J zG-ma2ushEiI~* z>NL_h41u*F&ULkuuTK`kuhsNE;t2tSS|3|1E|goO!glP(bB#0NV!3xMSVoetKDWia z|0Iex{JO9YK+NuzgMxNZO=Bv4&fe$8Q*EN_H9_DU4D;5?NhzwT5^i}FaD1l%J_ML| ziuIJSFvda8bHnds^O}?HEgXx=kS>FM(a%pMPhcix*MR#qhVR*Ud|Vl=KCt z7Mj1lJUa43{Zqc>A|WvcrEpW%f)6YgAmgV1XU#XLc}~vG;6Ho;mlTBl({XbXPE7Qo zT%jx@lgv4ZN{SG=KN51~7=hI1TmM@zbuk+MwjQYKK;H>A$~k!Y-*oGbwErm~Yisww zdJSSUH7Mu6nIS?#ss88m5Fw1Tluj?xt08i!?s#Gy0|jprBr9B^Tkh)~>R@YMu~6ao zy1=eyIE{<@QEBRs@RG%(Fdi4l$^uBZ9QNEbHWShMAncw5Hk0riyxDLCH3tz& zd@LBqPqX{G7_ir`sA}Q2ojlcy?CQq2u(F~}loR*!)2A9+fN}t{_;zqmc~G~s&ier; zdTU(aRM|rRAG;gySO3U;o`1h1QN9z=pPE+fkrB8iu`7M6PS9@r4WIpjlS`Up&5d`K z(9*^U|M`L1ju%TgE5R<6A0Y6lEeiKZ*&EgC`uy-sH);!HX^Ng|# zF^)`0p$4tOberTEueSs(-1bPYgtQ(Js~8|PM?s!FZ|@-E@}%#vEo=%!nDsKpAtS%Y zxuP@C!s-<^aBGIy?nuRmN%$Py2BjPkklt`D2u`|V!kMasdu9_P91u`EJ*J z7Lvr?9sH<(eb!{W7hencS~N>QeOi0)W2*G)xfNg(&7u3!S~%~}whlgtkzIUIa+#9y z>RGq*cA?Y9x50~pbH$Nt-g9~OVNc;6m^GW~P-e9fcu_({FF+L-F7{r-@~^@KkSzfPTU)d7Pw{X?F%#Vktv6~c}f85tqp z)sO!EK;%roszdpE_kc3mc3iLBXSj+x-FNn<&tXVgcLrhvkhmP3LPORg71ypX>1r$e z1iBU|8>o*Rd(hY0q9hLu7wQewjWc#^7Y|28M;#|tl3rpkBwd*Pvl;a6Cnf)3%1=rk z89Ya~!wnEMfDxrUGg{K#MTdpYgJJ0dFOG&SmU}9Ulnl6x%sb;N#T;E3-HYFSrt-v0 zJ&aR*aK6Mp4I?~@2J(5V%`@d`ntz20qHAtohm6PdnV07!y4h?1-zsZkA%qL z)R^Q!BOxdQTI{mbSYDi+oyGZf`ebarZkq#j%RO~<^qd&Lb7%#CM3q-Fyfda=F2{6h z)rp;d6c@9F6pW44MS+{uQc-ylSx=7{hUqINIJvRIvkqx5zcf@-$4HYm7Ld(z>n*oE z*-EU(LJ?6wz^=`b3%D8^8l*aXQnB$Rf7Xue6il?Xb%pESA&2Nu8c{c`znRY3r(13} z>uK>X(pdaIY0Jm|-54YLe@`PIs1RiR*O74a|0@p-+9yS9f`P-i4V+w+d`avvp%fDp z_EYwsQUO-DXK!Cbm*$`4R18G`_7yQOQ6gI333U;nKL5+iX~Qy%WoO z&=dTCED~@unS%HM8492-EUGEljg(-Y0}&buOGK_floKC@E8D0y%O_FP(vK& z+li3vI8rfE32h;<-R4P~Rgwqx1oh^2jx!gzTS}-Z--5XtqtBaO(a9khpQbWUUxy#l zW-Ma-n5-t>ppE;scp4tqgeA$ijsH}CI={Q(s(HsaB>q)_@q?V+5th4$r;w`CCdwQ% zSVbtdf%1j7bf!meN{egS>8`%q!%a^uB^3|HiweZ8adwcNCIqz&B7|~#nl1@}NgF&Y z;35TB6aYj-I}PiH@{a~tzqu~gUdt_gX?XtY*BgpeDCTsZJdTb1TZ6UMRV7bdMz{NH z3ys^CNXh)Q0)w!^`l4862R1P zL=G3|2Z8j445kExYC!gdfgCO4^XIG3{Xx}&TfZ4L(ucyfIntuKBeqHRxhpWeD(jil zB;&rki)jOITc50uAOPb8{>(`Oi+) zcx-<*?;s}n&7Jw^W+D4KSx}t9Jdf2O25|b#`w5Sb0|BW{jw2R{kUvN}Y~)4*`}KI- z)(jCw_#zff!l$tq$fHP~iNtodnP@^`Qp=MJ-;J61;FS6=!hDu3Rvsrl?jp<2VIdq`uhpTLM> zq*K6j5)cp?QU(-wfD{Tok9Vi(B``VwqZtU| z88sHBI{S&0h_<=ey1dslSG*&Br_TAzwZR|64Q@gN{=QqWX+lTPM}vD>P78Z#wC|GVhkgGu z03a`wJgt^8@TiV@h;g{Zugvn^U(6 zWOnVk+F((Lsc-%yQ1jHzDs}679ux$@XgE%3C-cmZ3^wbfw_lZI!|2z#Rmuq&$^a$N z9G>r}o)5YzPdU=XfZQtp-w5O=(D&gd14hVsoQjr~++1_5Ruuhf69+}-`v=(1blAEJlJPbw z`ihG*zBtm|p^r#AK)mu! zmB8N}qDrK-2E;{7)T=RC?uQru^u%FLNFg!jMM?8H6MNWAYQK>X4~f9HGH|c!jeYvr zX>yFk*ul4=V_x+4jW^-ClLTy+u92!UlH8PyXm1W*`}G=kZduTNGGc9Q?V3eKq_T5< zFnhvsb!7L#JV|`VB{|B9Nl$iP*dc`BAEc}`v@GYoEdWw@_$KkT?hgr8r49ZBsK^BN zWSXv?$K1T{0HUhb)VvoQ3}DQH`j(o$f4>Tp4R|4uV7-bd zUxTuBcna_9U_;!WiLd0yU;>Tf_wUh}v`+O4hs+fZ3%MS&H+cXCGP3CXq;VPfi9GpVL%?z+YZ3gzW@%{TF93r``YA{Uo z6@aK1+BpanVzm}>T+g1z87IHu63%i`XQx6kUza}_4h=Z+MqGa_@{XqO{?yYvIn0K` zLq^FWprGUWWMppt$6}!BW!_Wz%kb`w$-EepiCf)+p{oWmhS|Q z#wR6(0)#@6c09hsBP0|O5O4u;Zcb+eJ+ZNCy&^d7Z*c!U`YDB;(dX-%j+@FO-7@#M ziXK*7rb(qyAM+qBQ_v#m@Xp)4c6WmQWHo4s*J_iQSHgifq%@{WEYy3(TehRyo;<#9 zOm!-tUQaJ7Yvh(e;`x54Mv2acZ`anDW%;^7w25ZjudZf!Do`q56d&!BYFMc`D8l8U!d4P0Is0=(xBSuxFMKAXyd; zj^^pr8^wXF?NBQkPwUV%d{qIxsI@C@y}bkU*gsz= z_8-)KH>tkihP2KGh~7{`tNhk;F%m?0eYjJ~4@+pNtPj@6|SBX?U1c-XuQY<`OY6q~^HMYbLIF0c+KB9Sdci z{ebmoQYeY}6YZN(Zdr!5>$qxUFCqxvSdy2$<_-=V*<4Ny%nh~pINH_3%91uwYYszj zLXGJ|ZDZ|J`21fzMo8+17uVz26EJ0Qb0N%@f0gZW`z6^Lcy}}*>8>^Km->jQsNB~W zXgSN*9}Ji;Xo$+07*^i`{s$3vSzB9od%fch-nZjqWqsT@aj=z5#WS*eASzDP9(eY{ zcQNQk)x_Gz@=p)HguOOUlJPh!^A;A{T#ieym!x4F(F5!3m?YSDARl-RYwR5($purP16oV4n3P;!>YYZy_tu~{8(3zRq?@-e z3B?}KClFE#A+}zm7jK3K>+t(K{oc2B5*b}a=r!ROA!MhaVfSbcNyu!K6~#ryG+B(M z+YbOUok^ZLxg}BKzy+t6)BGXqmV-b0`0XvgT!f*8G;MlyML|i)bQvL%>W{zH%fNCH zWA9Bl?~^&&w*9(&aRdYmwtfq9FnaH$y%lmu&u~zHrO0bKm)<;`{(cp*;YrUAzZGo; zF$08oe#B_fM6<9E;Z7EWz3A=~cdU6&2r5$8LXvB0KqwFS2{+f4Ad%hUu0MngFYz=L z=av@k4OLjH-%so0bmbpUOVb5D+ zBze$*t)I$gie3-qC{hRvHJb`eCtoed%?+@A3oW1J(v|os=z6S=n+4Dp56A^YE&)nWQL%I9M3_#K zAitNqWNCV!;})&Ck48W*_lVHa82SBln_}*gj_bbSkR9v2HLr*uzx}~DwBFG~`zOVu zV@+vRC7uU+?S=F^2IU1xjFIly&Rs)Ayk0>qzkZCJ^>92%G0%G605rxBDcQC6gu!|XW->2YCA$7Y|62?A+X8Z#| z><;N74RH9CSAR6;yB<4l`@&oGYHiI9*k|6ScqLua$Fgahk_Xd42NUbQI56a`7S-PX z=IHn8s@aV)z!7Dv_IwV8&QC7^;>GvDh=&3ewV87j!i^>$N!>X5<>`;9sVL+M6P$1% zfxHd`1)DlQ+dr5kuMdHV5gBOfPygDFShYc%NWbrQk4j*H0d6mbOL$kxo7&UUi$gl2 zeKwGTCo)Ye;NS&TP4&KZMAYlXH(FNqER+5g9vvWrJ+i6#2bl4uR{)9jIzJ z_0of67u{@D+kSrBtZ=$+HjYj!=sv!tX0ooehqBRgrLhl)ttmx$* z_PWo$zDc|mAuH5kbB6&Bt37BxXmM4{_rzUm#B@r)ZoK`^J&C>IC}08uUi)3f8XhL! zyr1KoSkZ$1(((5>GOO6v?k0S4tEf~yRaR7NoM{S1=qKoUsl`37ff!iGc@ZDEwE$lN zqX+{pFM4F`*K2aeplBrn4`Z zTQ$WS?SVT`d2zb7vq7EJy$HDMtOe3G0Ibm6~3780`cB%2%y&PY~P7Rz~4 zlE2Y3l_%Xhf{~Q8G(z}gw@D8ifN}Xpb(obCucmQv-61MaTqGoLFS2-Ncq__++0Wwo z)AxyULlLmw=i{_SM@I+f#fq=;gQ=*=wqoKH?5RscF-X5bGGXK5u8q44JWzm73+C!* z*xi9yNy#XGMwlNInD8Mh3w8|Bv$9^wwl+02#Rw!yVsU9X1>4jMw}9oRRYmX`8BwM>KH&gG?kd&eYf1OTtMcsO*!(3$hB98a&Rc zbF=<hu$x|Z{4jf+*f%cvs@{DYK3kt<=gc9i(6hFpU#wIJ}j-xBmT9R{p+N< zaES=gnDSfoPJ?9ga{=x3>m{{&U4h4xty&wLq%%2}(_2aI=RJp5iO;#zn1(4Q@!d>fDO6)gC ziqm9mkf3qB3OgEP0TaX@Al)e}LPSVRkas)m{8k_Hx0^k?wy#?-Il)H!W-9H(-WOl} zIK*&qyU6Hk0(PM0179`a=Y13d9_67gH^_(4B1ZT>m3$m8M?a~kZ!S~mvoTEthRxyY zgplJb7JgI1%1}OXVnr@8N8FLh3X>{dB}`MjBkeNfvtOK^XevCgSxzQx77_TqvzPF} z?Wg}I$*@S7+@g94Y>als6wulb_Cq$A;*wr0cLQQ&KSZJ61mXhCelh#}E zdm5w7FKLTVX^F0ZO}*^m1T@+)^r2{J`fA{Bw^1=`etO^MD(2*AR?Gb#6jYJb=XZga zAS>i(YbY0eLkc?p0bfLE;>Jqu4A-Bz!UTjgPEhlKnxH!aB^4$pSrI%5?&LZsYMEfa zh3f;Zr1FE>urwM>q7t=NO<#gDe}{~teQq~c^N(IK)qgb>Qi%qFvAB`bv@naRxF zvt$#InO!zf_9$d#Wo2dkU!Uv#UDx;Taovymestg0b)Vy$&-?v)J!jsKR>HO3z|ywB zCr++(8TPHSOB=`T%)A+{^OcTwn>lLQvVnd}U)fqxymVNuCwH9NIG!Ex%D+2AZ@z@Qe)8d(Lhq0Ks^`cX=iFA7Zash4Nh(_S*`Tjmfg9|CO?JWXqAL!9t zkpR6#yfPfDr(UM9x3<{s6HC-{=05(_sGSlHyv!RoBB2u|?y+~VmWu2h zvH%PM3<>-qrLR)qWG@h16o)ksgr=37*1N31V;}f&tB4aqJ zDxNBCO|kdq7J@J9ob;^GN4HgmMae0@{f&nH{=QM{T6uTQ$u?O-t5^NHt;A8kHN_={ zPaj>D*H1impK&KJ&xsGZ2lLPtC!JAiM|V>GjN`y}JHJu%{c0b50&5EURs;GYo^n(V zYO9v}$K(mG>6m)szR4R*zqag|*E^4{+>z!n$!eFG`?e%IHe!6i(jvA~CQ-q`q3Fu5 zWW}km!Ge4(`K$R{i8X`P`^r@&vnz{xK@9yuKR2F^e1sJ^ zA%$IV(nPGm4Voq1!i)}wvphUywlg5ek9m>b*`F*ml>Z#Vr7lM`KKJwTg&DAtA^;$8 zFik~IVultEQH7>)`$wLOFTxYz2a2W>XbEUHw?QWr!WdC_0?`n{`?!U!-?F%^sqvBT z-@DmZ@Rk#zQYR(QUxqp0c0Q@tQgq#nS%5JZ#!B&>{QB$0EX|~6nIF|cTq5PQ4dEXh z=VAH#=jW9aAAiPmSh=XA^_Fh-1p%hVBL^{z;F}YivD^xb71g;>HO|q*d!>l*o~Wp3 zuBiksTCvUuh+pU&m*)jt+d)Q$<)?C?>y4DRGw)_T4rSU>zp+jA-9hA8P)?)8{yti> zABF&cT;Qm%>()J9DL|mxe}otXT)0yR4hM@Jc!(j5u!?8rN0aDzFS6MsR@#2k9qnoUbRRrkD|D4!kB{V?dX7SJB+lfRO1h-1i_a z0_LN%y5i}@bV)yGn!yVsq%^9rIxFnCsnxzQ`x;KDUMZ~AUTYJ+TNz{3vcs2lcNhCu!*ZZymmZy@ zuFI}I(4qYm+fJ2;>A20Bz-V)waWhfTsD9P;Cc(ZKir+Vlyt9KcUc2%h-Bm6wWG9Aq z%2LI}#l^E7@hIMt63vqx%MpR6k52)pc4G0bAX8FzqDwn7 zCsbB@ZpKS%(qd^)|94Jpus9c2i1G5un9`ldMQNd%58{W5CS|{FE`$ATbpOhQ5Qoa~ zNPQQ~lG~^8u-S$5!9C$9)sWr=bHW0}(_4!{4;RMYLKa1RUJ-jfDfwW@6nh(q$1_Vx zWr_X5k2L4^oUUY7$E98V7YY#KWt!e+%E14nlxx0EtAhqLC<>Dq%)n_4f5>RRX@=Qgds2)MPTVd(C`r?vv3;wynBsm^tf_C@L4UX5^* zD6I#dkw&1oM*>;c$j-@k06VSHauI-!)9acuWt(`r@7ofYa0a z#XeW|>Dh```KPK$E>xNj@7C zl2!@=j2FoA6|xm|w_gp3M@p1Fg7Z{KDcJvF*dT*6Yx?T%4Yd~{ldi?XwwHf>xqao` z_^MTAN!OgOO%ff9M*82^pDU;Qp~Gu{q3=Ivb^4JI>XVivGb8NBOuUaw1oWuh|RJh|iSDWnwoBxz{ob}w4 zap7&j(xfi^ytxc}44s>@`HKLR8{Ba-LQX8nvv2;C+GjL~pdbWx=GpDZ#tIV3ZawNSqVvCOJuHMnm- zK)5L{fW8qv3?Q1fApZlP4*~n1JP|>_ez=)ucE%msU~}34K?NE{zrA(^NgOFo{@^1F zmq>-Wp%mDc07g7KXgCocdUta57I1Kk^ewQ!m2f-KlkJ^CF{WzyBwW49oc_{uek-V9 zzf|VO<%?2o_zMd1U&n@CilV$+l%?i9e?Eag{pd2b37owF}T$1!J%tYQ^HC>E{fwl=y##bBx zA3y$+BlQzjl2$mf0X1eU_Va+(aOZ86Y3?zsgX4|99(U^<2~R)08kL2kXoS}Qw@mHv z-{m;hpyqOJ=F}1Ezqn>z??UckE#_uuynsxA=C(GtXJb=oOTItbtIx;R=p<1$nA9HM zvlWE)sofs{Fd#{4ElYlmlv4Yca3D&TtxfrI()A}gKDF&%+b~7PRpu? z)UT&J#viGGx-D}Szj=ya;OqbUL9sTW5;T{$Jl~akTG)a@rL`lMDMY6A z_T$H-{i|EAdlzogFYX>7eZr_vW_Z~sREqeMu+_@UQ?5Vj4}O~~DPw-ai2*3G5if1% zZJjO9WT0eCiguwD6@0c5J0s>OZ$wRmkl-NCS_iH4>wmaSOD`>rpptAbV@v(4u&7f-qZvsDf-0Wx~4vDrsS5m)kC9Ie&g}88aJf|8 zr_@;Slc*@}wwn@Zf3Bd8!sPBLE18$9PCsI%FgyN=*dpLR3{y`O+?7>TeYHwQdGLuV zRwuBJDr9 zos{$MiS`EXYM_-n#Wht*P>|7BeuJ_;UhyF4P7`}K<#p)yoICx~10#v3=xFOQi5k>( zCaS<8x_;6n1=(|6VKh`!Mg!OB&kz@r4&JB>4fuSotg?~-MOLQZN}5s0wcq&B2+3?` z0ioVPZ@L0M9l|39zhs(v(r~~CAO2Pj9|woe_^SMa2b{2sN$ytnmK+^@arC6*(v`Ji zAwG4g1iUT?8#8(I`-#(hH@(Nqg-MvpZ|UmNpq8xPe zD|!&RgtgN@7EHZf~&I({j90pJ4BLT zMl#*8^(axNDOHkWir`=yf;7QTD-hYGM#1t){Ss13q_E=444e6{QNu%IREemIj^!RBa%g5Ii4u?;h_>O}OpLp6iJaw^Wm><7nOfxcy8uamB?zTLv<|%N9W_yg zmp?`G)sMxCUSA_SAr zxv}p-gXdX^$vaQ|Y#=`oO( zv;PKF{ad#F{pZq@7M!B1;A;-lZtG7tJT3DlMlW)Ex;{2?1$oLq#{pJu==A${duL$4 zHp>caRi%(8&vr>LM$rczcR$HShZqBScHCI-*j(d*jsB_tLa%`Z9|r-*YsqG597gt( zScgjSr7fe+{C9vJA+hr9n)^h?SKAoVfdnvsu=6}6rNKvdw!sz&&+p8yZ*TX$`i_Pc zX2h?;-T74FQk4-eFlrdOGZ`Qa%C?!#%SpQh@(2_&(34LlpNk-g0Puxhnfyl&4wDV{ zSyTmg)CGx-GmVgT((vF4EMDBRCAkuD9Equg0=c1D?{e(6t_cZGJ$oX2SyCXL2%nYg z4D)ou8I`CWV=ok{`|ecJ_Y{(!DvN9{4I}uyh?YLCHLG^ip|5PQ=7)bNJqk@`W|2sZ z$#xyaPxtjFmw!`MyZ6)$*qhn`;ACjdi0drEhqbAEpQ z`r%gZXZ|yA781j9Vu!nsz@SxP#MIJ3{@?>;^M<;q(fZu_xCLuXr&yDXN6?Z*W15Hd z>Xv?5Kwm$LsbMq2VV}*WjIPuq(QZnoOjv32EK?3dxrq42;<5sbA0z8x&D$9EBj9Mzh z^Ws}9KNVh=Z?<+j-;K}W(CI~wYIP@9u)C%v@oLK&lP@wHz-0MiYcJFBvB|tBg#*sB zN8#@IjCNXTrvl7_Y?-~l(+URH0Sp0mxV0&-;?U3hsVdtrxGi7Z`pf*gbMJQhvW8@a^-#s+?0d^R{4gpro@qjl?DCF+ZlCr#!7)( z4dy!RMR@!!KL5PB^GfUJ(A9}s)Thtd(o!zV5z-Z*A!=rr7&pEzz?rr@ zop7f-b*Sct!=h8-HQTtk$_GqnZPSRrHp{ur*gZtGTdq1J|1bV>_AI)eEs2j7LC5|F z=km@=#EUEbRJmbiTe{;%5PMR}mS9ehs%2?u$?vbe;iHJEgM%8_AyKe*?`*0qoPZ~X zn{NlGS{f$(e3pynJ}~>CkeFEAY&Z|TS3mwXG7^~V@R1ahxGZT;r%65byG-SQ2%T_W z<^f@cywVK_GYMM|a4fhv(cL((@0GF0%Hl6qE^stI93tzq8hJNPzU(u_)@D}>TU)fB zOFgCT0olzjXBtZ{IW;y<-Bd}D3i>&tj)y9$Sv-}ndaPXg&5dAl;lzWJ$2)i_&+r`D zNA_!eAcNC&8o9ItUG4zAZQR)F=+imtmE3v2S)6oZZ*LcG=o>% z1ww3ECSi@VCakkb(onJyyK`QU#r9&zCj|-+fQyYK* z-zGC{{sG`(0*DxO%8jq_F8*bS3UnQ!#_eMC5ibCy3V9ngwr0%RR9u4@`dDMJJhXm$9T7lDz=*A(Cekk z%7AJjEQ*bnHenSf1#>tY?koynik0JTlK+AD_bG~$GOB^9Bqb&7#UVETTy<-7PEj?y%WL2bn01-BG@I0UdK1G1Ry+}+;p z4Iz7QvVltQ|LJsSK}rBt6GeA3TH=ZyP56a4?y|b5Vj4VvHyW8NFpIp z`Ur)YzL0Bm4_v^ed!J|@E)8&8l=PrOl;s8xagpxKt*5PR1}NZ)h?`)4`4{~p+uM9m z?U`nAdGT_5R+5e~<}xvxZUz&jxk9M*x?Ul?nMfCvI*EPYzDo!X2)qf0spwTtTWvZ? zIt>N%dOkWkb?nUQbn)T(Q~V{hHVz#Zwb_V0LwV6n*%U^D&V_CFIvVlQk?op;i(Bi*FbHC^zDM% z(oUsg>?(_R(3#K{204jSdqE@uH}XE%h|fXyhP;+mbQDSa4Ur((YR(%CCUaZ1v?LLg zY?$#-7`1Y5`{}2z?zuO2oEdauo1ZHtD?Pdh2{Ul~AGX>&gOMAokZ@&Tc*Nrt8uiDn zikr3^eKs6g_bFOs6WrUlQX%Jh*0A2=`hn6-t5saQ-hY<>LDlIXt4+%ZD0K7Aqb2k^ zsNL0Mj_Z};bE$K6G3u;0Jp6~q(Kr=CguX!wphrT~Y?5Dxn3OdG;``<9i zQw^X2x*+|6u<9Sb8UVUPuXQhP&GHwU%)b+`@ce?Y`I2)Alj-7qSB#%w{{~l9<6V@3 z@YaL*jW;y5U!~PZe@spUM!rRtGZvj(XgspHD2Cqe9>2|Kr_h;@^2nH&8l9mT5XBi& z`IchP52L~2>lj|xqhE+;aWvb-wx(||)w@WHKij{N)+mJc_H;8_)XL)GA|2zaGf4oN zS>AwnaT?9>xkqwYJU|6Kcd0fi zoUX1qx6i7@!47VWEA6cWeUBql*x$)dvZP?YnA5L*XTrLn zZ@Js~dG&vat78wRLG%}72mp-bKvhXF5ua-Tc)LZB=BhRJZyU;`DO0oVZ`?nvkxYHH%ynj9Q?@Q;a%jrE7(=NT5JeG>IhEdNNmVjzUs&a5{7Q5CaO`YS!frMi~@FZ#u z1~tbps(wyeE zokazG>CE)jenS3eUhnjax2M%+zW1~xN)+#JA65%8ViNQ+;qQd%i11kJVG~v1|E`$a zhb@6tX=Pa_(1T42jX$J8=%e%HkwedDa?eTl@P!tKO{x&6hJ`WKa z4wn<2tW7-6O8(}Vx?{19Ov2hK?N#@v|St_8&lB>!H3V;3Qk zwTyyKYhOYDd5Vn}#25=Zk@bymLcJ6EZq$Hvs`Z`)@`c-#?kn(Xt;6k9YZ1Q#}- zFv%oh@ZJD;dAme0jywWz>9h0<& z+U4p-x~hA@%h_+Ojv?Z)ko%OkoPlKO2D@*stw>t4`~AegXC@t8;csEbhh9|xvMWu)ql%H$05u)D*3%;tBNn>%Uhy&BQv~ zQbBCKaXf}7Y0B<+QgD`QpTAf8qx09VtAIs8Zd(8duK4|(z~O?-mn-hf9h>LV;^PBg z^$hnqoB;r#3DPPBta~nkn-GCAKZkq%VL>7KCD_SH{~=E!;C~Mo#&_3odj!VE;WAn# z{3J&gf}AFj4PO2~xKbmI#yeJsCdm2{w%1aeNbug|iTny7zi;4;*8MZ@Rm}lNWy*8jR~a53&3dfbSdpe4*_dQXGspWb`ZS68*auij}85XQ>aT z-8d@Lg`Ju|3$dgP=jG+~NscqhI2i?wi`b1c#`NV2T&a=&S9x;(eqa?wR`8?|ZofZ& z9$Wvb1wi~gnLtfWd12Q%Qw!)1KR<(XfB`Yz?q@@4JUN|GsXOacBhT|R73-Kl+V!Ut z4qGC0Hz<-sA5M9*CGfET2lQD|E-tU%o1;Phuexk3;F>PO#sN?lc@G|0L{b26%m*S} z$mizf6jfB3!E+uAM1%);cV&S`2MZNqC4uBY3o9$cW48DENka(uy5?8^g0_ina<5ec zB^wxJ#^0`JeG5+2`i5E&L2}I;RilImcP@f&o}J!0b=?KgcwE&gr>%5M(wZk8Ze2CJ z#8g-r(HcmgB}RbaRpIH3>2)ld^!AnGL(QZ{9`f>WPLxeNK)yl$kjQ)F@$vBrXz6_B zC*HA#8bn;tb8kyYWqI@Z@{4-0;%6k^MLP@q=>{k{GJfh?oloKO_hhUNdE{K5-(sT*kJL32dL`sMsdQ}fy;3_N7FsV(6E*0(< zYnWupI;2fsL`^lFVzOAE^-{5jKA&GPj-H!#q8V>;d{UatEPll^J-6>1Ik`DVgZhLu zC*39=4_=cUR3EI$#%gJ5u7i9@scW`N_nqF{FFtOm_on2 zo=|j~5Pz1MEdZRs7T+ZOrl_bQHeGg|x%@~qP3|hN?i8O~zCb7Q;?8_+V&chWW?y35 z%rvT*rL&D5we<0~tY_zF9<@_r6ARm4Yq^|js{OY_9Y;%Ba5sYb z=kWNgxrVW^Jx4Lfhn|y~E$F>VB8PD@2|$_b}PJ3uFbJU zHApdetlva71SG{#_B|-Ue*dUJj18bpy4{ceexxe!Kv8~gd^?(4TM-78dNG5;^#%VG zhM(K+2S1d9pTK}bYAfJ2CE z4Tr;siHk>q@DKK4L?|ih{EGrUaWc?h!uo=E-~jDGd5=3bFoMlzubExa2h7q$5c}nO zkFE-0Ue*CAMO24o6$AjH21^rXlgtA$>+I~T-$yaer-;au4t{(cVcs^4Lw~DvPt=p_ z-z=@Q?DNQI+tN??&^Se6iO)pB4?Y1hTFi;T-E&(s+`%JODx8UUX3Q6hB^+eAA@e&q z@|9tQT@zC69M{S#nh+{Ge_87;{*d~hSYp)fxg#jEkiX zMB-98T{s-KGD|;Ck-FD-_Pf?R)-4pgc+T*5qO8YObR<}FEB^HJXG?qs^DocQ$xvlI z5!|DXszLJjKancyPC4EQHGcVR`J%e59&sA7v%bOivksmY_Hs!q_Qvy!KQSq$1zE+N zv9@+aJ!-VANYJO^_*c&i+#hIx>EydZrJNgAc4WE2(4_v@FWDF^M(49r{kyxn3eQIy zrIy!SG><{K$*=Q4v^6!XdMT}y$;;E=&zn=#jX}El7gR`WovoGH03r@8BLCu@P@Pb}y1H_t&EeN)(F|?skE1aJQROg3a{b zBX5%Vxvuybh%ZPotM`4cC4Bzrv@0m}(7Mnx@j}2x8R>KR2}al^FqR<$2`J{kk7;&% zxUZ6lC5ifaV6NVFBwHf@;H6j9fB+@xWTM0qb+|2&~)UYaI;CAOq(_ z!B`yIf}MdumdLEm>IV!bD9npX>I`jwXp0(}=eApOM&si-tcNSzHpis2ono2jCcVvt z(WR&L4nl`T%paSO_JogE89ia4aKNATPTjWEkDPX*4jKV;offoK3D<0CAb!DVA@xb= zs_P5wt5ll#0Xj_Q_T`D;rw4dCscN#X^>b{JX!vIJ zpTAt}cb^y@>#3KqdmAiGIZiCwN}zsA>pEfqecOs3E4OL7E64uT5a>#9*$#={(lMeuMt0k(O=*e15~yjlPD)z_geH_`Z<8Mpeh4t zAcu17_%0&&3wE%a#{7UauKhcbjF@2#dv1&Ea-_x{%BbIfL7B2!4^NwrqKW?ud|qb#s zLhg`_*=Tj#kB=^>LX%>`zd}ilYXAsv+t0ld+_Oal*$)9CeI#)`EVJYc?!8p(X5y(6 zqNe(j9{~#|p4`*bDy)L)7q>usIK#{Qw@4tde&difGTmKx^V#}U)RdVFe%i^Z_WDf& zvm2M@Ge5e40uzNfNLmp}IgGbly61UA-ELIXVm&iDbT-)EgQh=Nwv2>&U!{Vc^HG1; zY*e}4oIm&0gE;g75Hg{AY;p}N3Hdw4#$TnAYRkF&D!P8>;V5oys-@p}CX7OY)PX(J z#2+X!8aoDKE&NJiW35k(Ca?g)Bm0Voz9jD>Q+Sx#ex9ivvvf@mg~1^Sdxj>rx|Oo| zuywuNXjQqNQqx))lMjhgdP+*D)ZtI^FqdFT5da-&`~@7l?ul?*DNxuZ@_%Zi7`tX+ zbNLd>;0p$y%I-*_TUoBxi9`nf`@m5}%->cvo^nS{^3fbB=kNL6YJQ&(cZx_DKU;Ee zZtI)%20YFdnVKMHGE6%c`K*L|PVZK={qA`|tttk|1}b~3^Xmq#fW=UOK{vpxdlC4O zH=YdeJLJ-bzw3A1u8G7kWEew+IRa22(KR2Ji)4WH29q>D7}0_E0z38Fk`lDk@kaQ@ zfEM7^uB&7I|1 zai(t9u#>0K2#GN?v>4K^1(7oZP)*fmog=_Pj3&fHzXk6x3bX6JBz_Xg%w_mJy{ryA zp5O%dU@!hOH_+C=wAq$W-BU~a$Wsc5JTMq@s8pd~m)QF&w`L;XN!So(I=?*K#l^{q zPoYuQ)kBRgor?EJ zlC!44-SvYpweQlFTB-0jBUIG*8A(PSan;uU+bAf`TlJmtmJA&_!bXjFaP-rl|nBuD~q zT!7IWIY2-Xk0dC-tpNc&{LgmmzIz_5BH@;>mw~hpIz4UacZFQtlKs<e35)7MSVLT1k?rBJn8zMJ;JuK#VL&^$ZO6I@yvNq2pnc#xtX+GCrYT>fE3ZdM;gJh32j(~OQ ztLPU?TyrorO~3L^-x~04P&8g?*9W8!dT|gHFX-Ol0;F~i{{BT!WOx9T(?OjM06F)M zc))~IHaaTVuUsLzAZ*tN_Ny?sWMB{#)Kqg(u{iMA`35M1L(Qu2&S1#ONbrGAgGj+n zJWLkPlOrR2026`Rs`cH7>tN{!lhgIMTGw&QMUa(;z{&_1m2&TG{B7fFt|W(|@jouy z|1NqXdfh(j5qOpY&D+9${#opgo56{s`LqkzL5@23pUaG z!ua#mRd6GtfQOkpoEPD~;l)%YUVkVVWp7&kKxe?^WuM0AANGo2A=Se#lZUF>&-Ew~ z{0ZL8v69HYJJJk6IDDZze#tQ5KP001QgYX-)|6<~Ii^*u>U{dCV3*bmOd@HYZg$kx zz6Ve=*5g*VNs|tB-g4E}!Bc-zzIR{=0#nE`3t7w4!3LP0U%D3;6(CqV1^`s^n%Bv* zn3x!5kl+IdEcfUU7Ww}NMJ$Z8$ejjiM&uK(-%4GBCL8-bXk>X{Jf|0TO?oBIyKH{ zI$D2cZf>~iH+@O&5rGeCz9+Q{-@cRTaQgbKsgC0;<@md;iG`Dg9}?{jAy30bQmM;u zD3C@vU!ZySb5CjO^7dViu6_IbW6BPXE9o=;>7|QIj9fFW>vn}EvIbA`70DVFX`fi8 zM|OJLx5ke@pj5GscG~t;q)qQ-FHdCt8p5;o0YcO5E`MzgsH(0`%(~p5dpEm`nwt9Q zY@`Cx-#~zZEY-$BJ~)8jNeUep(3SujBYZ7BrQLX@Pd{);OdTpldzX||R4lr%n~p87 zL`q%YSIilB>5D|*!}%_@n$VZ6FBK<5QIzi~x+s6%o=zO-UdRdjMHanGIbUox9+co9 z9v@b<9`l6zWf*SCK_+KAH#zms_R7?iwC0_@>oN~K=-Z>|QJ~8;FfmB2#l$Qv*o$bd zMnh(j_IMs6_(}?UU}gLc12PKJbO^yv9XoID&t0}9V5F_*O%i^d+2^ zE(okb;2HPo`S^VhKW89>73#g+D7LFvqFm!*PQKF@DZ{+LUpqTHxvQntSWircgG8j# zr9i@w*~_*E&K}MGN6^$d83fHkX$D|;J%N_3>10L3E$u4LI0{UTd9Pf0I)#Tw-a)k3 z&pBUk=1^H;l%6g+Ey816tnu$=Hy3q~Gzexx84RH}1u^40RQ)7YzW(CzLQj*BDm>88 zL5>D;E-*aYh(YEJ1%v?7?MpaLNWhr;CL`mMrW!!5TQNl5@T3FCI9DwwDinyMt3TYq z>7u{Qe&f!EcUU`Cz0;z3?`_lV9`OkZQbNK|g_};ZJNE%40j-XH8y61 z!7MU9o^~*P(bIr+OOA$g5NLNeSjmETSn}PPm8LpdgMu5&w-kvn`ODy=NMJv+XBnHX ze~sg2gBxy;_r|-Ntxd23Eiqb8|nv$#T(7p8ek}N_HxWazC$MEvr zsHsH96|K<*h zWqLbc31JGXss<1a0rKkMhQ5YB z;p-g})Hp!rQuCvNbr!_H>(KsTu(_TIDOKf`5*J!y*qwnWhW^MfB)}e=lwgBu0!&MJ zXYmFq1n5T#Lc}!zU-TN24cR}|QU?Y$7xH+h-WTsE+Q;Awpc;3}5|Yfj8l#6OXN&{Y z+vo6)4eF9?j`UCNF+21Lo1a%%l}Ma-ZZM;!ICUl^yt0lsXa^swDJxePY*`O&V*tXV zv_wMYC?NC+bjg4<`Q$!IX=g%n&TTmd-KTf^GurE^%kWiMes5!Hxr8MH;OB%f4SA)m zcFyAAu2!k-S7ChWn11)aROvg>OM898WQaxRcK%L~{am;*ymH{b@R)%KK~gPQZ?*#`R~C!i;nldKNLsblb&J{EQZsV6U{0) z=sv_j+O^AVQ=|3}dT(6;QyDNMMaNiVNXxysbG1{+uMNZv8z2%SNMINSkhM-CJ~kGy zvw$u1>ET8jkGU5lt-icBRlSf#KympMtWpt4Nx|SVX~tg10_%lBcb!G4jH<{Q0pG@Q z--6J;M2Hr~?NGA{EoMrK2hjW!CUpOGr>~!S&1J8FTf8Ad^o^`40;VREnR+?C+=qF~K?nVGwuIYH^d^)cO}W<4f9p69P0kL2F+zC~ zcy8{6i<1tKjnm_{B6%H^#=69l6VQ`UVoQADPe48hO>8m|kuS=^xP<^%VT#qYs)H@r zuBBrAMYT=RNUhsrZDvs?gF*5dQgU(XvO>EY(gX-y7*bmjXOh-;^<3ZXa}~Insh^|7 z*zK58(OG{L4@1e`E3u_Q#ZkDF+&%FUhy?;*vVn56;);RavW7*`kL?^JAZB(#eq5(5 zP=Wh^B+y7?|LDrjtNN=^9E+WVUU6g9&X~71O+**QLgx5^Z89dC)$x@E( zZE(xKA50Y{)9gt9%?H&MfHCQIqHQb`qNBgDuQ%+(F6?ILy`@@s=+{J8tIJf(8lb%( zuI?GMOnSHxj}C*V0$wcL!)Ao&P2+1Vq=0@5^69Ve@N|Wl8yY5; zGU1--Sbhify{O9))!&1ILTLlXobbY{#gIc;xNWGuO(64e5trJom$#XiTEi5P;QIyZ8oD ztBMXa+b}XfwrrjdPZqiVEsf{VjI@X;;X@(1vTI=Kk72eN?eZUpYgk*;i`qbCumL#p ze=f3{RkN}mQY~NV${PJ(*1X3S9u3;S7osPh9+kL6244qa9M+#f&UsrZS0#07C;ES~ zPZ1+7=z#Nn2NKo*@^7Yg*QN08wJc&b(3L)mg&`|5^99iy~<7a`>Uw;_a~C8_=%OJr7+2IDk+Xl{-p24TV$(R zGMpu!_q;OLnpcnPeO&jn^7`E`E3)&!i8)g0x(KoJV^?oLIf@YWcear_PDqP48%5(ErO82efadFg14F4dMp%U#lA2 zz(yIy#d!&1&kz6zL{r{SCDme`r~mujbSC9ZxvyIdtAR%_g@K|XgfXO0qQvf~yXaq= z44RCW**C557_gQL580oQpfOa?4y86r*k$T^H=DS=@XH7da*ce$7 z6;pLUst>v3RX-e%oMMoz;cRZ}{Fs=yB-go->3cs156M{6*xovQhZ&cAnIJC$kBdXa zq6B<9_aV+|ghEbjYY~LW{@tNYXV_6cOK3vd@Mx!fHX>=5J%c^uFD|r55I6Ux-<6US zwM=!&;G^ERk*XxbFBEgH%kn&C;9_}fnQua$Qgjw~9cCk|rFkUBtfod>>1+qr6;jU4 zHC(&#gXn0@WQhE0$WjwX4W_Cfn^!oR)p?U&d*}%XS}5E^J_rvD`G2ace@9l5N5SXHIm)_3{m zHasHHyJ~ZyL|cNYl>Zykxv##il3M-CQ4qk^W-)Ftd`ss#=Qz3K{Tb(mi2nfEukSx! zVM!{c?g}lqygoIUdmiweNKdO{PyT4h!E74>fpO)3wE%auyTzs^%g@%(8h;KPF$iQ0 zitZ~16bWWVnBGBUiRen-LzW!Og0P;G-3DpX*YWYLv8HD>n=gD6BO*T~9?Q1(q?&KH zaW}YO^ewZRxZ+ar@ivvLP&6T7C(Aug9$prpHQ#z9kb*kXi{I1xrBM-|pN3o|v`oKH za2mzhZQ5ja&5Gx$*?4&R0an;}5|_6;RYI6xKjfkojgQ4xiFHb)sbo!-Aqk|wGG7Li z2}Z2{$v$|9?i&`GWMV(5X9-h5Jlc1V%W81S&{uOgJl;&q_Bbqgh$$ceCmFYN+DaAB zj}WhkLdO;trh{M-$-WBs3~v(nqe32>`{jR zWnZNd1?U&;8M+uh{3t(?$_EhTN*8g?!KsEHL4nz>*I)($syiGpVo4JWqF}-1FQS`O%2ROXZg?g5s4<>?#>MO z13DOPPAmIZr&Sq=Q}@qo@=ar~Mu_*0N%iiDN$v@+#3hrAw*qnJF-{oBd#@g}6my-@V-ua8e% zZZeDDxc^)-J?je+OiI`7?G!IuH&wG1oJGAhO!|0&#F7bN@X{{_LF#XPG!_8 z(B3I2fncD5mUGikmpJw_<-)Wm90e-|y$f5n3EJ{HX?8zQ-YmwXTec~?KEJK5Ug~Hg-aGoiF)V+~uM=B)*|cU1yhZ)Z)TPI@4p1hw7sO)9hb< zRaUJ$s(uKdHYgtq#xDK;C!g~fqa9co7KW0m*-wp>aASZY#KsyAiRJhKUj|@=Q9*)~ z89%5L!rD!ISA7#ki7t-UJmLHF^Svd0R(AHwy2fV`m*OU8HuyiO%2R;TRb%v2>~lyS zQ&d&|@P}_m+8cK_O`kX=Xla|tm>fk?=-8BCEB8V>?d+d3Os#kD`T5D{QdyG%C^52I zjrwGtZdZ$*GIKu1e~H{Efi)R@%K5A(A!IpT)!)SDccwypmHZ`V%-t6hf`Mp=^;xwCR|3_EF-GwszZk_vmq#saUA zIo^y;NVtFCb^?KoB&fapUaxcJeQ~!61KKq@fzEE~i_$rZeoUA&g}&|LB(WZB@tHrt z*T9Z!P~B2TPY-EBtt`_z}-v@MKno<3;upb$o@)wb4Eq3 z-2>TAhE~*{naJ3$?7{w*xH)wD9%I)Fvcb>loMWn0xjnR_gdhfs{Ci%@1e}Fxc8SqT zZY7>52s`;F9ei7bJDursX05Kz*k?mj#}28KfD95^5G_PGLtsYsv8U(pwR?$9gb1na>JDX zyTqPk(A!Nx2GBKc5(93sskZ3$L##S8WeK-CU%~q|uU$NpZt*d{d(W`>Q(f5-2?;Wi zUi|YkR8!wsJ0w0uemQ!}L(+@)VFdn^ZN9kisl-=LUb1A#@7OG>FoL`4iG@9jPtS)$ z7+VM4FJ(!w;G9Kt8mI(zE~3+fnBnuKeN#aUgQ8J`93R*oo_@`?3}iPVIa(3XF%jP` zQxpxF(y1SCt#|ZD1u`x4*KAO^{?gA5Ys`G^A-u!9Y1%vL%!%0@?E>*#EsAzXA}LTl zP?yuZ+i>z+dFu9PbENTs+@{VPJI~g`9BZbfx2Lg>T#)1+8A@`Tq0WPTeP$L*H;jSH z*$-PxNSmj&skWOXCGTOvOuSrqWj>RdeNI{J=3SQ+orP%5#am3CvQfe7;Zf_S4ulUidj-Jpl zdg3SC&8dWL`KlKg3V2VgBwn@ko*$(z+rA{@9Am%yS;pm?xp3UEQp>I8~wy} z%QBO&p}X?H*7ShE{kngWlE2C_jJsJcO1UY_!q@|dD5-S%JpN`-uT3|vklgz&^6eAJ z?43RSPanLiGO6iOs4vGwYI+|(HM`%#+HsM|z>D|d<$P1e4IJw^y0c6zvKPH&`Aohi zdk-(o@Epx|#4bk2U^rxCqk|u6=0yMxZ+lreFAb#RNGvUkLK;g}_)NK9)HpbX)SE-^ z(FvTAVBO|4B`2zyL5DmkW7JT8eVajpu`9aQq&Oa}iAl`QhZdZKcMHALowVlyK#9Qk zE)k56K>cxd-fw&`!;AwVB)oB}`V!ph8#P<8V~Q4K3Bzim+*%cINz1EhYnap&3qRGA zgxLV15GrDL!m5E3h~WuwYq6!fsT*#S#BG+kQX7*hj$NPm9=1*uFSqW}nf4ZB3iNKv z&S9dj9@nqp#Nas5`@sEfsg}Cft9CQV(NEDm!~*N}UG74(uP;8gQ56LQoChj#RfOn0 zg+wO^5de61D$zQv$?JH*YZ?M8HO{a9CzJ7-NYMDlH3V?Dp2`=GYlJ&BDNm(No7dFB zZ%ObYUrYR-#fqB$ZL(vWGX!u$@kG;mycURLjd(??q;7G^ExD7#4h6C8z8%lQjG@d6 zL{uOiCr7%0A-51P)PM^PRd_E2s6FnS@zw=ob^F%w$%oz5pBg&5V{0ns6`7@ZDQ`8t zAZ1}CAfczYb=60B^O^~2=3+_UC5^&uO+&tSe=a(chp(%9)iKXL`wXRFgLA&7KKhe&rfN+T-WDJ7{$NuzYvKCkEb-u>?Jjj?{{a=Ex;UUQ!F$j{j@yMk;n z#oBD!#8f3$Vpntj`J{Q$Ko}X1@6zL4<=kw#c`YHc;40gh2Gj>_=@cGuIR;gA7w-0| zcB8p;G8Y^atVxz=Q~zYQ!F!NjvyF!_`2|8P3U{J~cM%a7Agg!xv-9Rke5J19_3jv5 zuJ3D-9e@8$1;x&gCfo`q3C8@|E6Hvh{-Ut?`wWoN z!=soL%k9j{&wJ;Gzm^j{;$`)K9P~He&eN8WUF(|@8-%6+Y`s%`^DQZ-L6bKc1|}{k zsY}@XA!{wOFx&=QAE8?r9CY+(#iK=gX1D>dEShxe>^C6ODL}nr95)N-hXFc*kK#Z* zqCRRe(}$84{;?BK0(E!sXb22xaFc^n^bF|2gF{C*aUaPg1Sjc#LyhbNDBUr5h3Av& zOG1;)l(q76v!D}E8$Xs#n;4UnE@ojNAZ~p9Sm5yB>l|5Cv&F$^)}vpF)Sqws$l|9% z6P}YGCc{uJT)BZID2!sGAeZ?evfS^HWlq zT$Kf*JX~CP8MD&Wz~GO%ygcsAo*eO*phfQX&zTEi?-@A^rRXuElja_l&|=!A)D^H;F+|t*J|elX6sLjC^)moLoKoha$L2pt)#$)L_-A zx`rxq`l|!c1q*P+BaG~HPt|sXgbzFXDepmElVglQ>!W+W@zo!aA>6=2hb23laBr^1 zE0=qh{{B}KCJY$zC)hJ58VXLzwb;qfuu&lSL3tz6m9vzM$*9>pqzPy&n5bhD@%sZW%gW&Mg`82{QPv2Y`K3VKS2g8%&U%s8;(QM5K~>p@`iaX$ zl@vK@)eZ*(l56*0F$~nl1m&M95dJ?);Tj&jG;bvy3a=pZa9HHloD914 zZEJ>5`jv9Tb(YXbc2i$xU(bjPtxqjF%e)w*nm~JK#=|nPA6`L%`5~|XWb;{BS;+7X zVgxXuH{@JG)dPgkqH#*r1Th31HTH3gSXI9k@Ayfz!onh6lbB9ju%lfyn_;p$Y`Z@{ zVbS!cr;#AzAv4kMYog`92*$3Ik_A!n;|rT*OlyWlbV0CNQS!G|A0Mv5lpqnUhg6LH z7rTs@MfTi10VJ2i0he!^C^^jvgXn1A|GM@j`cdL2#@$LS5%}nIg`c(#3u%AtlUo2E z^hiN+yHKI8QmzS@n~%G?vY^)FwOgb?o5uZQd~Q1RzVwjm4-jIU zC)I3zJ)gQ(9gThzC_^fs^0TpWY@Mb?%UOhsfPtR?+_Q|3+gA>8T>TEV|KDDKYznw$ z!s-eIS`F@BGRW7)G*diEZCsu)1N;k|F(5h zRa^D{;o#sPwZ5S9Z=SQu06*-@@lT^U>rVKu`r3yz206T!X`h(#eaSW< z#!#;;x+b1902tafEYUll8H8?<)T%JvI_pYq;T_HW%NQnAXI(M^1<~S-n-*G=Zw2YS z*oZ^#(M)>S3#Ot1ta(;2eT(Wo`mtb9-oTnM;Q^U`^e;Hg;%<%cvPoYLm3;U}hG=Mh z={CZ7!^Zz&P@&wChOZi4o`yu5rk9F57cPvZ>Y89p_{ z8VX!jnbf*1CqTiH)?U#UUbgwaEP`pNJ(l#s_UEW@;F()ws`L=j_{xRXoc^U8{auG`;g zp>QPJX!>ic=ug=F|K}JeFmU=dUAvl>yaioP5$QRi1`_SZ1!iNrXJ^cIf(#d{vyL9S z4c8lml`YA`g!s=A@chw*PtmXE>6md00Dy$tV<6D49Bg3jdqXmamJ0DMQwQ!3De<@A z)`Yn|>(K4L3`6Dp?(rVG;l~u~_v%W)iN0|&0j8QXI_I%y`qpR`f1e^P4cUDO#Vdm( ziA_Y`vpf4*NTQlnI2!{U%moHtV(PfzH;<%U>AZ#i6~=)EMT3yE$fA3M&l2}L`H9N! z&?k!DecA5J8#c1)-?=bXq(r8iZJtX&O&tN^nNuN!^2WlTS%aJeE&d`sqV5M#Rk*p~ zTF%N$y|dfSyvrtsce%Mg5T?RlP9B?GWb?0Codt?Q?=v&|y4h7f27xg=+pvH-v0nCH+pr@w=!fPI!$F+k+l{~jr%UmbTAo@X3Mej~dhGjvJ+fa|x zRrTb8j;nkwkY$jQ452NuqLs0{++9CbD}u?0E-nrmSxU<<7VQM=U_H-$c*;H`e+5pW zU3b%H#sBB~ouQal4qn>t zdglgCTmnY3tLh7DbG8*W)w16dV`19P7Yyt7i^Hto6nY>?#kZHQX7WJT@GyVmRBJ(T^(qE!o2NH|?$ zVF{CDmJmO`=Am|_&PPPOF~h5*@hpk@T)z9UtKPtG?>J?K>9*GaFbr&6YN$k=vAz)8 zrj64deQQcg>Uyq=E7Pq~K2Vsp2)kZPeEd3daQiN6Ly6G*ZWamOZ3=AHw0#*Edy{ED zRAWC?)qQd&;A2677#QQEM_GHLJ9Uf@BEf5`fg%f5ir6wEKg*r%Chj8^a!Xu~V)Y zl7ZB?qD!`zS~Ix&??&M>xK;x<2pDRnp!EhAgfOnF{*bJmB6|F#!&|Kv7lp)m`CuN zg50pQv`C;;KH=K1y*ByK&`?l#_-G2w=uCpo#{xwDn`>z4oH(V-S{g=MIcW_=8x~?; ziz<4i;@%lvE-x-_4^-iam*0c!`)o49G{dAw3v=5``dRR+k|akH=9jJtdlTRf$E7u! zd=TIJj^$IW?`ICT0Lw3XC%^2vd58$uc8{)}nOHu3ilYKDbv{ghkmKSy7-da7WHGte zw5N&$Q0Qk>mZbLL?|ceB`5gyg(Z5?g^wHDO$)9tMhv<;Z>}-02c9dU%ti~~gDm-`p zSg1?tyk~ruvO?MCFN^CgQlBy2prIyjHMO$cPSnh0I!HY_a=y^*ZQ-dqUP=a!4zefb z%)D|`Spi+C7$hX}QXy0OfA{Sf>-+o|zhLM9!etA}7*Sh|bs|tQbOwOLG6gCv(rPKn z`*&!{b#tTme9d)fA{lAPwzjsFq6+WK_zmE1p+W2p)S}va zo^eQIa{%9{Z@ZDQ&5yecCM3kfYs})7XRz=*g{?M7QJzxV5(Q4A-Wv5KBpSc2aSF3h zty->bCHnLzH?`n)PIs2$pf7NfOOQyIz_S>y zw?fAe&*uIF71|F<{yE9~;AN^Xtylsny6yu0Pem~URp+*lf{ki|R++3Pid7poccT`+ zd7L_d?%?Ks)ZHI#J)Y`(HlRT35y9}h)n`<0ca^?B{X=z$jjQCtk6z#s!ygzPs>IE- zL_!3=OqLedzIyd;)C!Nbszjq$`XMU|KBtMW#ArfHj%f`ZckI2;g>C1UHYWAx25{7D zxz>}v5vZ=ZHnzM+d+U|=FQ<27Qi%3o6FQ=wJ^Wp^1y2XsvfsJcO~yxR(KJ;zDqgzA z(eLr7cJ`dG(K5<1nVjnqX{gl{ujTBpo7a#Pxv_oNaJ_Cdg|EJt(e@BWUs>7b(U9WRxTlR63w!why59P5FrolhCAF@ko1wXxQVg&7fxjV$>)aK0TLM>fJbrkKu1%M zX%9pT#xo5b|8tbX+7R>qU_q>`q~whxJD|Lg#%uO?mK99ze2KO+9D(uPbM@Frre^6| zu2$s;3JB(|^2gj1*HCUQ-~0OhTtRd}hK6?_n=>05>*$ost=qhLzb5 zxgos3VP=xOVT&dm7nn?JZe_!GCN1Lk;iy{Rl%|^l>jZnuw-oaP%uIuVgXgYfxhZ{= zf5NjCE-&0?`bws?f|FMJ^!E0AQYNaAO{m-%TxTBSCF5eM zd_gdBdnAtnqvzi-I7Uzf*uRwS;g}enlZ&y;k?xXp?phy1HFD%kM~n%gWQ7`jG>ITnvEu&+kAOfoY;Qx z#q-=%*S?(y5$Dy|OkZzmoRQ-cb)MX{`QN!6CDA3x(~i^xf|-^)`kq3|LZm3Q*bfAO zM79wK#LwMsWEWN1m;JHJHuLM(FM_*e>KYihIK-@Cz|BJ`6yAqP6c)WdX|R;A9$6w1 z0aCmQ&C!ado}-xFuT_RltLmu zX*slX<9l=Or)zz^O8<4V)JB6D#Fn$b<_;|uIZ9To-6Vnjyxw5=Re9$H}z-j^<(Zd zef9X%TaJlcb)d2$^tfE8eYePy{h5+d5cMc4>;AX6MVh_?*#Z8v2&rcG9PMv1GBPZu zi6g5q%%y&>c#D&iG7OE4jB>VFiE)r5^`k9AxJ7HR5+ipvu)_dnDO93m_H8<1V`IZR znC^ei1WZzSKqf9U#OCn2HB{=R6rcqgGPp=J_2@AF6eA5rwwj5)+5%(zwMR`v~k) zh$`7~BoE5*^a<1H=;{49@QJahqa<(bz7|Yf+27v{N3C{vs?Aa2!pV@Lo0kq9k`E}b z&~;+>X!O6`EDyyu8kl_$jgNXn>rP##XNAdqS~cGJE_eRO2RAI@y3F3j`0<1B-<)+v z->&r)rRUyx_3W)~mc8Zk-YJdP0VLljA%Rrr_)oMxvmy~_rM)5DCM!4hDnJqBrvXaq z{j3H^0|aP)-LyPj#70g?8wn5{%eMXocLeY>OKmCBHZmqAInrptDVsrn;~`Zpz(sZS z_AbOx8y#D?Ot?%wB$}|rm%cUZ)-|jwJd^p$p?<5Pfeg1;vlPi8M#@8jy`be`4yH26 zCr`S|hAG&6!=Jm_38t1!S|jC_5A013gVIzzFwswq3ryov^T%!Lwx$0Kl&tM$idAI{ zu@pO})(kDi>qmf~2kHi|_EkSm(D#+|4E5{e!BP4-=sow9xfcnYskESie zT@SHF1oc=&B+h;&e5fm4E>wj=D?6TM?ady$=O)^)>)M2;*G^n+bSz6y zoq^3q>|J3|itC{&Lv{N$;t>Yu6M>yj|N1HAJkA+ zq?cO*UKdDhOi)k|WQvP}^I1`X!F*5XvDAFHA*c*MPiSFjGt`#rM9O_>di|?UMvs$3 zoV1$SZO=X1^bDFN8&vs{wr<@oP9@Cr?nZ)H>>saR;vT%saTC@{lQqphM+8xc9yPsq7q0d2mRNCkQ2}?FqkGtdaE%hf~S;ffa%g}aTXg8OX zlCn&D!KJA28!AA(g`o1v5c2O661sM8u1jE>N>f+Xn71*bp#2kJo?yp>9j{KeN@S1Y zszP8u{44nanT;XGHo-3IJ1dut#$u?XV0JlH)ep*J=@wH(ZjYN!(zU$m!%IC(BrD1>S;mbuk!nPkJWqZj{Z{KTGy~BOAvg&=fGMG4!NNQKt zuX*VYQ=f&Kh8NXUG!&5IOqwV6ckmxxIWysM8w2hi;CS@F);k`UljdXQ;7)Z;=U`{= zh@zLtsiD+=fUHgBZ0Xc(cf9|L)c8jj67~b)A^_b?U31em{M6v;N8+;~xZ6x+AOa{6Qx1&U$C=eB0`=-8P>cvV5i$rMWk!s(WF*xZgG4SPaWx20`6K$|}gO zT0ox;D1#ErjZdQQp^>iT$4Dv@ka6c`9i73+1E3vI*<`x4gy>1)t)U-!5{o}ermopF zSLmssNKu2lcGu4R(#ht8xZJ53qdg2S8Uy>q!b-6X(!SrzaL6EzE05-!tI#=W@#Zq4 z;FRS{Ua!)p;ogywdOy6|%=d-xQZuT{nx`5pTTd3cdzfvGa(h&l#=pX-?|v|84rM;6 z|D-Ld>HrBV7N2ohrkWP=TjaR)w4(n=vLdX|foa3((P3!bF{I<~I)btuNmA|Vl2y=M z(|;D+58|Y>XV8c;lQOXQ8cM}@?;p#gvmFRwTr5YoD?E8J*YKI!_SK2zVmGVELKSNf z_wah=%?55HrUF=-1qzIN3=9@0Y;1%XzfGQD){C_Ni=y@^mKy z0<#x;-In;L6}?7J;d_c{VMw)@Gic-IsMR)r<^e;+uE&G6VA3e>M(B7ef4iv%$-Z;J zjA?^x>zY0gSD(Hu^uNmk7r&J*2@Z@1&^9#ua;OERE)U!e;iQHv=bc9so{@wy{CMG6L zu!7W+VAq7meSo-2uo)|#WLPTGNlLSqb6JV&;@-RaY<^s-om-tw_0p7>U4&gvN0f`o zEVh~Rfhlu?*Es5AjxmO;Sw7Me)p^p(iK1qY(p@fPYCQCZ2;^ZNM=^}y9K&)KR zRULhGcC?MgK+5J<`$X@44yo$j^oX6r!dql_+8dI!zp|!7g#XJld=y#^7h9y2xc6dn zniS?&6|pz?+868NrGe8n_)4#e?>Vc_JTiJ-&?7c-s}%q6E%x*JYV!eVh|2QsG?%Pg zYk0>^CLgRd6$wF;A(zFT7=tgc2;R8L=D?}sE3B3x_~v^4v(%Ge7mELT z8$4R$WX*aA6H$Sw^nLI@EO~)-4xrj?FqrMqG-e5go@<#E@epx&urKH`Xf+mbzj1Qf zA&CW7Ga5?YikkU*;FGHu%b1eBDh$s7)`rD23t53M`GJ8FAdNn7vZB!AZiKFeNXDlb zy=TcbHrigJ(T7Ap4q(UcrYAp7!uV7?ud;J&H*KiPD|*!fbJ3Mck(ZIOZ_%UDr*U@YKb3ZB1<{QVvVlkMCVHM_WmelCaUV`@Fwu&9)8chI!<3? zx?rWEa*MHH^34HN|E!$=Z?aXl^+QReWK111>8g-7xhz*LrtiZ!4O;pCXg7BIc#``4 zSFd176c84$(nNL=#$?1Zb++%i&gjDk4i|s01BshA4t`obXm)*8HXRG0K0DpyGD`%8gq-LFKfP+tS{SkR!3EF>Bm^WZ3P=X$~%zS^%_UR5gjPwjy5d~Rvv!V`H1ZL zpylr1Ml=%3>JS1d5qM(`g29#sl77oYC~W}&fS+v5SHkl@pb_SG4}W=Ho(H>{K1gFV z@PPMGm)zP;oI%$KzVJNn(87HU8O`<3i`bi~# zkX4o=&RSrWg{`$jr}{dQzyN%bips=@!GrqKU(5?!3 z#?J8hXD%tQZd_9R#Bl#t-99kE5Tp_hvgwHR>qxVOCcu(R>JDWo28Xc^ffe+uv9fv#G`zt zcn22`!z|PZ++wN-PsKs?k4Uqqown!Oh4i`V4Q5_(?^pDYB#4`CO8sO{Xh(n92=89k zaY#z#!LHqjQ9-m&#hxkksu2a}w|KaU>Uq|m`Drf{w5$;faqnnr1ONyezN2GSoRz;7 zNAR^IeC2IKiF*;ZGU%TTrm8Ga0WstAmARUV>MpDPfg`JJVC&^_*)ah?Rz8^zuMv`k z;khee;^+?)E>&ae`y>iiAHn^CzeKjSI)U-{OV|K8>_*dLQH zUQvs_+8WN{J9VYIg{Or*CU*z7O4!e^cE1m}7HBQsf?F%*AMB$i;s>eBo|hGS8YNmj zh&R;xAT8y4<@bg|rnZLBsi_dS)`oW-))ft`#-_fYu$eI(K!q|=(&&^oVV2HLHE{0vn4?&hOOTa(G7zF}QRyhq}jOQ0PJq$LRd z1hfXsw?V*7{1_j{V*7Ue?Js*Q6fI~pASnZXeqk|AS)Ul9BA}D7%~JafGBY-5hQl>P zK7rFmQM||?%oMO=0nIxUo#J#!;}DnvF*yX~{Q^{FB)?#ye&)1ZKar}ib0BZPu+Beh zX=-AEM1iAlKY)Z4bNB2B~wFH8VH0>Nu}z~BH<5OA46%6b^g8)-GHG(-=tTXbKs zXZ?DZFWPLIewtcQ7bE#h@#*;eG^xS$X4!Rk^zC=OG>lB~$# z#K*>3zmPN!5BtFr3iRC&7-t}fgXfQP(V5zD@Ap7KCWC67a;O#hZR<0q;OVatr_>T4 zekPduY{I(6JD4!Uz?7s>(fiK+rk$)~Jumb?BQYkRG(qin))JD^X?)aqhotTnl$Lg? zDhlVyOKjG`BSR>ID~=3)|0_@+;+>SFq)--#A#4W_Lm>K+fd_?@vwi#+ z-be`)KqkZ|g5DT)CffINYU*faYs(HAkaqhqrSR)^sX+aI##4zw8eG-D3Y83;9w&}) zJ*eC6prDWY;*_83+F}Jjm(@3Ja42(;(^+(;Ra5QzYTFA%&DMt-~N;x0)M2 zKcXnQIF6P9ElRsf{jFC?biH9I!H;9hd3M zO@>E?E{{FlgTx9qv5CDZN9w%#da6Sqk6SjVH(Q^HlBI-#`NDW|=NYC3|L*>DMShu6 zikFV2WsvsH2IdXav&{a+D1&UOrB#J%PX##>q*)Fw=qZgw8n2}(?sZa5)*BtZFBDWi zROL$xUZ4!$bQCn?ONN~`51YQXbI#7Whe zNDmVs(pCJUQ1!uIxWc`E|32eM;G}2wl;jxxY9&X6XyyS9riNlUhYl+-9PG2xZ)e&; z?{E{C@s5rTZ|5p1roA9V9cgWWsqfbAG0j%hM!)M^fUw4kLFX;zci^~E0)oEtxv zHLolI0|s4mP48Qn;S=|svGHRg$q|WJ#*p09K3LGH^JIU;T?-F4vg9Fk#{AoT%HG$eD>L(eB3P z`uP1gvK4b--p{-*>yq}Bl(l_eDa$J)hG6Oal@RrQrpkP1Y?juGvE}xla^M^_r4&l7 z%G`lrK`!8b(Y$qzGU~77EOQX-Q(YUvH$XSbK29Ke^fqy;aCyZ0wSNVH&i&p&^}j4X z|AZfxbaZy^o-*g%S!%t<(%!#nVqa*ar6EnO!Frf%+t4kXtSuPLsJP^xUleY#ujbMc zG6$?8`uFu%E*2IX6k_tRi8U}5Lv1AtoM;)n-p9IH|NfvNDehGT-`K7%@q zIP~tU5NB0ze#tLuKW=GvRYj|~2>I%g!;Rsu!`y>khh2jP*DnEO{dJlc+iX;B0O%92 z%YJTy#bEAZqfKM=8hxlvW;$nbp7QwM42pQJI(vmGxu_NYXq`Vd^)jXIDeA|Pny}_e z=r`-P!Vq3LkI4E91O1V$thR@iNT&5YY!sx{wIy&F!y4>ZKzlu7w_V4o0C+x9oCQT- ztkA;TXkcLA9k0I83D7v&qM0e^Uz|@?^O4r{r|e&@K%7G>SY|-TK#;Kpe@4G^>QGxl z2G8Yn?S5PoNUfo5r^ApE{#icDG!HfmGev%9FGA@^Iik*+j$^fC0MY(~tkb>y{q3DJ zUX(W@0+gA;zTfS-?F4C3PJ&0wYv<>iUNnUFZK=^u1!X432!4Zj!;#EB*sP2vD@>gi zV>NkQhPkh*K35&34>zyYIcBCN;Fh}I3JrZ+RzL1LzIkImYOJF}4jUxzDnBo8)53N} zR+f0Sf!Qk%Rp%(*9C4$Rf6N;95ZG$SJ|kD>SM`G=2&1(hg-Fg6Y`CylW+vmaWtYqZ zznT~u%R7FNq2k_ia$kM3q9&$L#`4lw;|>aGkwz4p;4y%RxF2mqqurT5BuYyhDWePX z+67oNO2hy*Lbk8PBJ>mO(t)9qGOh&SN3Q2|6U)OWn4~D-!N+=sPB>5X(*vJI&nO94U_(E_>tI zYf1q-@8~8YD(F51D3gGSs$WyAtO7ay;B*AP47?>o;Qzbc4MWyU;|45fcyzTV1DYX5 zkK5XIN!ab6$*MY_#NrdQue!QgMAsow0XsfGP&4-|`8v3PAV|T_SV;Jkb*!t#gCzkZ zFRUSOAi~4~4>$Vld-74@vBH@Jso(G7c4B>Kv8skBW!1v>52=upEN}h0R!yk&=lMTn z$lA~b^ruh1d;0s|0kRD95(>#=)VV!}} zA^by{i5CNB@#;P1!lpdo-wc)df0?JXtM{G%v0cwdn#7ttYPy39q(SaH4$2$Ms=Xfp&+?;-(c8=BJ>F026BP{b zNN_Il^amP3DFjroH$!{qox2$pT3_dqSrz3-gU`nnwpVICZcLU>TEjQ*Kfb;=zKWT| zN>y~-bS4qpBuTE{blF#n?kICT5e%?GEhKk&3X`q6j}?95s#mW9O+k2Nxw?q{9gJOrKEx-YkwjMMra~**|hM0UoJJ zml0<9zK6d5R^(7k%ejUE&V#tB->~z@qt)tVGk2IrcW3aHLRkZ@o>}!46)`uI=;xiq zFg=w}_6%9X%X8Pr-JLW~H-x1NG{w=n{$p26m2-&Ohqi3Oy+FecYty~alWTtRHT{dP-CS@b>?fFl4l(sOg)LXbQddX0>X z09zV@&Edhzu?(28L6o+#zTTSiBpMw!;07Za!RgJ{vCEwO(PI)zl{j6oYkit^1qDIr zFCh>KnT&xMak#o}*C3-V(%MXWATdRfungs~ADCVChqDa>7FJoGCf8*4?7Fmv5KT0C zi6R?Uu5aR4^a06aUJ$RIlT*#7fzR@meZvH&AtS4jy1JA|U8mv6-fDv28)n#;oV8af zb75n<0ejoHo?E!r^3-1^*o`xDbKfbJNXf_`4P!~0Mkmu?IdBDS&gT8m{`_Jt^Dg|@Ad(lh`QkDO`gXq2!h+rb>U(Qa_h61z> znBCqXJkW)y51hs-?YOGpWh4<0WBfk$fjMETdfdvf#|@G&6ElwXu-Zq{(<^u>GvKJ6 zmAh}y)fy|FJ0?U0tTfWZ4R?&BU3r2ygatD87+!TmO3!TT_lZ%BJBhKQHlKHEU9FzS z`VI=R5qayp>x=2zbM5$rt3X<0W)@<4;sS_;nwo~iu&mK{g4%I%d}tSU2}%6H@mO7I{f z3U$QxK{}i~S03wqB#yN&6TChND+t%g2D|F+M%lm*4l0zs5602Y%^4tzx1m1Qfy3z_ zRW{fZ^cQOR=}a4wl`O>2F=}4ZX>{pO>esLx>PP9*9kHJ=Z|TK515IpNu%qsB0=KqocDNTY}=^qkLj& zv)baUd4#NrGiA`ZccRh`|0~=gOoBr!%7(U!_Cq}Pl}cBrivVfdVv(|wQZ-9|WX&7U zepInmg~QI3#PaLi|7Zaq-=fCb?JeY3rwG`ilju3$iKOXyTU?~z*RCFwfa0|MU59Ef zv{G#_xKhZRrX?cym?*3*=kMgiM3-iH(7sZ8_TW!jsfiz)D|1KcTW5Ec;G~Y6dkmQ%|F*cll^z?cwPgz6giYjQ6+t_2F=(hPDGV6u3EY zLPA6B!O%SquG?yEq33*Ep1SFgWj9W&hI7B>7fWX{RQCCec%xlE=mQ~&?(SuLY6_BA z<>*+IN5f-u4-8+?0wn{`I|q0kT4~+RbqFGlFC>hJy!Yw+(&aepSX zY1_^w{@mZ23%C?=PtX58V$uC%7FXz}*g2rJbX+1s44SKO9X_?Y`5`fQ(vn!k`ONrD zw&`dn=wrWzkKfr7%M!bYC;h(MIczX*&T=MpbOb2FnQ2f+c$ZN}%1DF^JCX(W1#wLt zLWe*zh?5^I1EZ9VdyCOYDl3}6x#XFn3MlH4Ba=}v?Z+#Q@(ox2gfNt;spGflltJR) zS5d6Frg?1)s_%x+;@MyH{M0*0o^J~#JmV+*7%I2@efUQ1<;d=hKnb3PU^#tMQaGN^ z+_~A{E-`U$7XRbBIP|xg6<{%MjXt z)?-Kj#wrki2_RIm42=ixtQ#*ESCnF1`GpR+TwvAv94cyDu8!nGNFtk#|3YUZJ=|6@ z@Fo(v=7Rt>dX|C>gj~qxXV7)r&aT*={U)WW3&)Fps@DaN9f&2mT zAdu>G1SQ*-3aXPL_$&R z?d^4|<#unM+LQ^Ab$7S){D{BJ3Uyx(AbWkzP5@o@g?3sWhAS{{!*1fOP~RZskVa7B z?e#jS#uS8HK#3lkna+0@m#`tCjP;C`S{NN{vPv|fE@CKS73j)d&cDs9!Kna>f+sGUgdYWtKHYk#D3cPc{BzJ zKF;akh~W}H&_%y^A~F>1DqtLCB@f1eR=Qrx#0&+P4mJu(31h+#tAG zP2fg->M%Bb2ZIvKe`u(~>9;hH_w!(;d*fS_!u*$M8-;1<*Yv9+K8C4=lqXmy2TC*6 zK5>n)!E%cRq6JRxrMET`Q%AhN4s3WZAukFuB6~Iu$58uBpr;PfqZsEr54lQS@KKPo zb<)~P^Nk6g-$^P!KW<|@+6^c!YqDzgPY6y(DktZlT$9ir9nlgrWcIAxWx#hUGQlu= zR!bWBZ*xE04?kbz3_C9}SklCV;hyfXj5DVD*8YR}^nqVtm(hk&;_~P!B%eC6A4Oyw zmVC~)Pw8$Y?F}=YklC{~nebloz#8J>bpBLIZfiT`)d;3Vc=H1!^Tma zZJ-ntR^`r@98RbJ^CP)RJo6dZ!=&iw)`fpRKXYWHsO>-LWdOfy6YQlA_Q4b(DK74N zPvP72ci}P6Rk^r;-lOlQ%C9ZOJaN-Ena9DVw??9(anNC;JY1L-uQYWx=H(9(ZKq2$eF*zJ+Qa;MKjqmb*^|c!7E?iF;_vI#&G2li($4bq$T30l1tyLpk9# zFxw8j_hUoI-k%zc2sr8rM01w#gh?E3&DcYOR@UcuDvuSKt>$G6BaZWjY4yLuL}zwU z*PovZYLx-g>2~Yi`FVX8sj&A!R=VNh8;YTezgSyS-!^9#f94sC(~r*{^veuw?lzBm zkshzJx8na^Y57d!d=*l0OXv9Cz6gCsl5mVuQzL(|gA(x+Hu~)`(cp%UD7GTg>TeMa z`c>$^xVl_gY&Z0R!|*gh;pi}oTV5BR>w}UW#JN@Mmck*WwFs^`j90VaGays7oXPSZ-W?FdhhZ5oJqTNEF)Fvv^Zcm65<&T}g;6}=t5Qv3OjuR6OGw6A zFThk}AN@iE<*tA-NSZc3KR5eJ?n7GEn^X6E9aY6p2@NGA+46-)l!Fr>J>p@^@DRiC zzCznn`GrR8&-c}pRFz0+cVAD`gIq%tYWJB#R~s=syU%QLf%1OsN-xWjMCnhU)`To| zg?EyD_pipvDMsexINj!6dYiI2eo__eoZ#M<|PILRdLmqT=BFG)C0ToVDjp3VDA%78kby z2c5H8=2~7`fp?;IO23zxVMFSi|>w=PrK z+-xuK`Y}XOrp{-a*EZ+0c2D`YdiPnjQf)b8e&cD<(YtcmdPR=J$&6s3jlh|b_K!p( zhcPnnxJ`e1W0$?pjh067*L%OKI2_IWjmHl)BH3E?Yc#VrOFkFcrxgC@yf~7%!cE*S z(Y9Sb@!}^|dMSSF&kOW%-oe27oP<7c~pTmz3osUw5y9e@X({d1nT%ZxLde8;{##EHj#jB+#LCcG2)_+YB^) z;@V*b$quBy3c15EF|!dJbqkcYh$j|!d2B%NnXpw(ZVia(A8B7y)Plici}!S0Ls>iX zDXnUIg)BMGBV27Er_?*J054ChXiiXSCubCg3Jl4Y;f!OXSv_CSns|*Wn>To*scNqi zb|{K%X1wY^dHX6Da;9=xuE}Ey68W&u`-{IIR=m@@3>R-Kl=aUVh2zv*8PDDx+UIkR zpGef#R;7nX>Vm-tWMoH|Rd}EW2Nc;ClKK4u@e^fw*7`&sB{5?i*`N)P2(Q6MraXHT8N+ zvOx>^cgID7w+&)%^ah1>9@w#N#y zj5K@iJz0=Nm~*-^Q6E3&3JIOuruICZ&J0&j;Cgs8kUxfQ+Zfi8@N-LFG%0)tHTc}e zBe2fGYn^yve&HqwNnourh0V{Q@P+_a-W#|X<<=Z)ElUfJo_4hIinsqQ{vD|(=(=@z z@rs?*-tYL?7tB)r{mje;Gz|KfNFX5_A~^5d4Ja^%_ zI93;8BFnHkBzt{-TpwR-J(HY>s9k@Fg@tANWW5xznEld`aMwue1Ut@tTSd3pt1-($ zDF2vkD+?3LyTq{KFgtiC%=Th!C?zfKdu)Fp$-QiRF_tr{KPS!o=SK2{7SvU(2?lbD zW8}exm4kQ&tf+yEeoXq9=kC=(yA!j=2O_wr1m9!bexd&SeSGz(H{1n5blO7O4Fy5T zfXD#ejPaf&U1B=JR^ZRuvf2tEa8H61H1`h${b!`M4^qD2>_UPnTBqFKN6E3ifaBoB zQ(4*BHAOzBURil7qB|m9G2S@?sYlwsjucsG=)c}~fmQNRL)T+}6sbi8G0TH!irZnd z*+5Ev{Zp`^7yKsbG2f8nuK5D--MJO5IH<*inLKy1yyS9xbQF3z6`qWNxliZa5;%vD`>avjJ#If z+!`AjL%nIV_Wh&VF{yD#+DRrfiy_Zd_We!MoI$5;Z5~j_KW-y zhpjW%9XWN&4({HLkI69Ex<6e{^6labL)YTK(7*uYjs5=qu>p5;nBLw&h$;H)ZZp4y z!}at*MlAQO#EylKe34m~xES}a7j6dzodL(!M1Q`rqBP&&?BHGyNNr8|irbr)){=(* zHoM-D=eJM|ZZXGGZ_7P#-Fjx~_EKAkze6f9Kf;lW!U0Q0N@)OyO0bS2YbI1JQyw!}g-N!S4LLElefeAC$ za3G%M4_!iFL6`~V_uo5DF!c37<0BjYk_SDsVFT*zNW3+u*ru*2-3n{ZHsF|LzEqYY z9;$%M1!ST8s@+D?z30BReoa0ex&(_l`t9ByBif6jxmAa`){HbpR@uk@34+bz*`F8%b9?G0dpOb zm#wKM_a02VcfYJVeZ#P(NH|H4TH>Wq?(V)FYxI>pJ~aCE-WLbR4A}G}bLnjv<{s|O z0o^Ck8Vkpc`@j|L3px`9`o9j`?E-i6EfXzt?O*%kK}rBGvrSWJP%hz}KFyR{YewKQ zqH~6bu7rmUW?~*~UqjEO$Ji^d@wK(eXL^EU#eRP`I_;WD_0*X5GiZ$05&@d@tKN9k zjpj7XSg9b{h!OK=aWqtn+9LeFowN52t0(X~BB**9y{SEq=DgRfH_?;$X1(IFv$BpV zv5x*`0LqHApwZpED;0g?=aqP22Up`qoF<)jo|`&~%vv`(l68`~H=F(ndi~@OC3tas z-}7kZ{OE#$X7-rn=T-~VWw4hMF1SQ79Lxe1CVU3wDxY=ktx9yhV=52YO60U3vt~Hh zY(J%`!OD3Rl6>u{764);G`g<;78%T?k+BKcB z`ci^7S;;ZdOG(n>X~f>Hsn?z!^hP~=M8!kp@LuTuF!kQ?SjTVsa8@N`6&V?qGBUHu zCPGF+wk~ClkiGX#nIT)UB71KN*?VMV@4Yv_^ZMT3`?;UjtG^^&KA-nE&*MCX66!WUc^~CxC1A`vSCh1P+HsgI^Sd8LdfrlID?T@BB zMBpX^qp)uKK6GBeTX#{XHH>ON`$_(R6*NtT#e8qe9pLU@0j^a>y=JZ|h`1YsDjtaN z^OFN{0O%Ar%Ofyd0#(lhPB9FR)wHd!{<$5!Ns3+$Z@+|ya!*i*%NCNsoE+mrqzD07|D&O44klf6H}w$H!C`HS=XV_u~7#Nv@e+tLpQ2RDM+T z_;vYH8Z9f`MU%At~C*tEzW3z-y$3FjqL$u&mJp3lWHq>S8!<+6JCS%1YrH0C{}E1Kj!s zic#T7)hMC?xRbopcoN+FYkYsY(FdrkVxXUZ5EN=9r`QY3jeJDx(C~1}Uip9IjpRjv z>0L==(fE6sFXaz%4ovuU&w4pwDhU$zm~oqe)3VZ1tO+v>&Gl1<`m;B#aJt;%F}<_c z8S4W$v&kxnjLtWd<$$lvQ_8HYdvTqFXK1*QEI5vb%MPDG&j)x_G-y1a z5redie~02lHpo zo;5rjA0GBc#o+aqJym<9tn33g=8c;3d&m600uF`Zw*yiw0R$t)d_mz zamGL%x!6E%{_OAkYhSm0&ZLV0kv@Jy!CzJ6ilycEcnG;3v-Wu_8=N>gX_3`f6^f24 zzTP;YxFu{Hpf@SsnshIu@AFlIY(DAC@>Ay7>Kw(QwWsvmZ@f$L>Svot%XHP$xKpjr z@l*^PEsgM64CJKNrJZc=Juz_jDoaBJ#gfTe~(Lp1*-B$@_FlEr48re zZqMs3xecz@B=@qfG#oW*fNUEMt}Dk6lc5r;PSMY(>!8wMCF&~f6?Ck->-pL7$$g?Zrwb?C}-@QyJsY<#S1(Zl&CA+u14kQVFZmOKBB-LMrS5_D+%@XuTr&dr!#%a{9 z_OZZM)3{Om0?xMCpfc+5a?3w3#Xf#SM2HBVhk(-2QKqhB?*+@^(c^wM#rtw=?Smov zTq+aUb;;`F?~6rLB_GRi2w(y!1TZ#hKQnpx&qY^$r<16>Mx?!H?T|gfMFi7v}mTmb#2SgM`nxb;p zUni@wjN91ip&9*(p|RP81Q@n(MtX8TKj6er-e^CC@QKXKfJ}ye%C%NrpG9=D=<4FQCp+DmILYUXcEp1eVcgPGE z-V_^tF6q9;okI?Zsu`3(vQd6|K$!Fa>BXE!^XDUvqhUU2-j(~cd|U0HtMgIaPgrkd z)Ptlpbw2v5Q8fkMy$IB}GKildt6+`0s;$Ugz^v>}#E0YYxe3Y?o|bpD#*k z*S#mR&T}Ma{=V@wN>FuGgqrt)1;7L+0N_M_8v9BP>{XSd~OEekOl8!qU$(^i&C8>{TrP{RImSl2f-RY!To zkn2@I%7Cc?%Jf5C9pGFrwh#`di`Ys{6bGS^AeF+kHl`N5!-T?;fPv&D`EH5X@P%|! ztx-D-{%^WZ-2zLmQ1ZbPy^lY&Q37=s`SbJhdlMae6IHR)sK@d@>dZcUR>1vwF8@}j z(BVA>W%1aCS65K`aVI+i4GJSu1egEn#+f<>)hrouw>3*ZiB-3!KSc5 zJZ|~!}`rH%lrip4MF)YWYn^ zgaerXq);`8_J%8Owbhc_0Y1>9!Mwaco#j^BPx{_@_Z<3rgT7%2!-mC>l-RYYYZ;3t zl=`$tDs8b&6Y+lIV^AdxLPZ;+Vdu1?fYE`0RgX9V~FHt zgx5R2m;qOdT!ve5x(Qlm7;o9Qa^!o5?1%cb@g&F98>TMAL&|LV6NPb1u|H2A4*sx{ zFYV4b!rCX{g#zZ&y~p0bTHX z)L+=UpYKS)82}s2*UxX|r8~@xVHOv44qV6As;ZBcG8K|HRRYw->7G0pSt9><78Jdq ziyIvib2gDf8Ie(ZI+mRGbjaDS#qd4+X?)*O+xhoX*I)OQcw8IUfN(DhYFtf`^?Evr zRYIqUhO(QggrpX9qBdQueVD^B|M{tE){AM)LHGhHGvEWhcGwY73^}z?%Vng&xN-@@ ze#!%%4@ToKbak$6_}Jr%wUQ7X-gthp7Ze=4*Pib_6D6``_mmPTq3!Iy0Um}0(2kwob7Zh3*aoSa;*qPwR45NO4iSXm9gY6fYS zO^Re?WPFuG=6!8AM?AWVpr7tiS{Uu51KleutV}rH?sMZDvr}V>=-f-HYVgs!6~tOs zqC}jkdFI@^=A#;=A4nx30I%t;KxxuY5x0+^7%<^jQp|s;cTkOr>^k*rf|)gZs(akV z1SwNj-cBtYbI(HrU&_iVlQ7@uT_Y{ZHO0Q?VPfFoR};dYkG$A*S5k_Ya$Vi`lHPp# z&8|LdZK#U0O;5oc30wtmQ1vKy_xn1GcCDULu8)-lkBw;p!c+SoMc?KA?HjbTw4W&X zBErH5K=r9!sEc(CWK^L_q341_-s-ro&5ESY^O?>#9z2jJ6yfF`T+2rtD*qMYb9QFx zaocdPd(@*4Miji31lliP(mH~s<=U06+{>3CyIM$Y(GWvElyD&&q#dUZW53D&QJ{I) z9P?Iy>Wwi*y>{yZ?_r#pz%a}$MwuN>*4?{z?l7`f!jr2qFxlvk(1z?kXo5~`f3Mh{ z8lPp0T#??qlgPXZ@r(k&!sd}BqeXT&)Az%Fk|wgW>Jv_~a3>lVFMO7>;l(?eQ*MeZtAdYFLN=t=hxB%ZHsX@ zw`gL1CwF!l8c7G*;@7SuMl)77gWMYHv^+V2wv%&{ruHVK6l0}W^@ta$xg}l&`fWte zptJ+q-gP~yqfZm^G@9C-`#4t~nC0F2^+GNcYFI{-1siJttikY1^i`_|Yuz9BQner3 zgT1DbrJGyrvy#>4`R!+oVNtu5Rtic|njI1)1>yx~?Fi!gBadn9_IiMFQAqf2P`O~NUY@Pg`75P^s0o>QOtTG?I`SzsD@81DfH=#?? z<#hBRmJjG3&kN@pl{f45ZCp(U)kM>U_<#{I3SWKg5DnSB%9DOHE*HNGZJ3InN0|)PO`HztO(;v4bT~o(Jif-qw0Wjm^kO(rB+)AS zy9*p7@W*@flS^zNS$yF|{}ZzNz(SzrdvP^>|4E6e^py^Z8jSW7*4xThDKjdd7~s_^ zeQ6VuAJ%NFtQ!>v^v$y#aNbxnlz`9@$=-c-wDrey2s!$%;p%#~(2;hhAr~l+0oP~E z5`?G{7`!sF4_H$xNK4bu)BD3oUuC}`V{FU_aDcDBzw-fCA%_b1Q4l?M9*}>6^67jg zE!T5Wt{_0<57d);{R6=o3(E#R30?#RX zkd&BM9K22-&JiliyTCL!PjoJr7f@@*g=?|qAR10&AadG9ngBG{{;6} zB~?{PVE4nCfj2+^z8{0$R;z1lI^yrjkC|7&l@Q)gS0-zb2n0_7Be&lA<>2?Bn4vo0 z7~@h4CjdDbjzhQIn@e%oNN`-=;>40 zZj5KVuSACFCWbbY#AKtDHldB`qzzy^~2IA>?(*PH2#`MtT{Q%xapop*r;& zPCQ@)?1WEM%zk7>DKBc)aq#h%fW^H8V;pdWEP$u*uy*_V`zhcUgZU)F<6=#xcJn!0 zNpGs{6_u4CTRnQWKF%04$@`|or_N<1B`CRSk;NoG;O~53>7o`t&pw7a27r3LF;bsN z4w?+;x88Ebx*|RQBSW9H*pF(@^nt^crFr<(6Tg9+Ns$u_iA zFk-$AZ|ZEbTH%Rxi*8|o`^D*8w%Ky;H$ZkVqprZ)YfrQF)mE{sIRBgnDi^+~xf#6f zQpTmQ=J(#cd)HpK%!MGzNl6ja2yC7C079iG=|^_9>E}ULP#ZRG&-{KNC)Z?AZYC)i zY+aIi?ZB3ID6K7T>!U4QbfW-5Bf5p4ufsXKXO;8$zRkYd_(@->4~8Sj(fAa37o{0h z)-r2wtKo^G5Y;GdX7v~KJ<*T~W-AQr`~AyGhBL;`qKFpG?aa9Mk`!uQ7<%jyIqSW- zAIm6(Y3AmgmwClPBXxcCTkUC&GhsNV$#<0y zFi+SWk=$^^RJ^DefHX66nv-3RLT2Sh8@LLDNH4#raIXb4W*r^DOB4&r>e zVmP1r{Uzn?WzF*wZ$K05Yj@U~x@~f&npe+SyqL+0Ycf4WhS>S-)8V6TqY=7LUGzu0 z0;QpYwo>RYf znYY!w%B$X-g)oa9KI+z`%a+)B_Z$^_m%J^7O46*yx=lAFL#etz%X|N|Q}5*&*oI<1 zdZgu+J7h96BCMXQk*f-&ljw^V*q|#Gc7nnfWN&Y`{?#Ih?*W0`5Pr|9NDR}d(=`FO z4C#UT8}Pdk1htNE%-EhO6gcl^5<&l;QC1cWq-bUHkEl}YmBVk(9@q1G^4}MGy-M^@{hz7kwlauVG@rS31|Y9Nr-Sr8i@?xZc>N5 z^@0!Io{=AgY~@x4>TpPtCCsL8vBc1&#tXbb%Csl`3FLSfw#C+rxzGJ@`u$`;S&y<@ z|7G~_#VbK23YFXydC~k|9V>qqa1YaK1F)ZlO?jPT-RFpjeVo64`8T~5lkAuw6FrJ9 zxu?6Eo{6cAy)w;VW6TEMl%4Qr*%Lv*gud@m#kMQ`#4<%bOTv@irSQS9b8di_C+Ly5 zJhvIGI+0?BYOhYKqP$#YS{h)y-~Y1g-a@>Zz=49emOgCW*?@@S>)HSnLKR=c@3kBF zb~7FD%80?Eo$y$J9!!S!s!O!s-2T2ccX0frM5Rw(H# za!LHzGn90{t)pYF3OSoEC_G=bGHEn8qBS8U;k#d9HHWgHSD*&ojPmNqLxQgVulm03 zj=a}TR{z!&{xve^Q#}OVf+!MVp^mSi>?lsV*jt0&N*j7cL`2w+8ijRU$NZM&ul~N( zqC66|`R|#xL)j`&wu9Z$den$%scH8=DG7;dNjE*9u5cx)(QUrv=SkA5wf(|hPB05w z3T-E7XLEL|77>ZXm%v$J{!Y%Lh@5lqL28o;U0#E!l+<*NTrpcaV3PW=`p`ruuvKE1)dp1aW z6}_gkm9vLctsXo4E85!mfMM?$@9*SKepR2|J|F-nUpAU$2F4!kv(dd}1To)LR3&qg zpwi0^lwrMzE}wvpjlCno+!9Wr_%Kix%}G0FyclkFc5B%L;=T-si1@f@E+_YCB-In$ zI_*cj@Pqe6`sH!zuQS!oBtO}lAXB1EdaE*9IjLcB4-OAMx*S;zcGi>l%SKIVPkQ$* zm=xrXhYq@_5`;M~LFtZ&Cp2Df-DV)8Jv3N8;SZbmyuQ@i`>Ni=hgF$g4TJUaQGbVt zL2F&q5d`RIK>7&EdJ@*k$2#cygN+iy3JCv}nvt@_$QGhbT@-2td_&;%=Sl6f z6HObwp>l+8CtS!L*$*FI_(5?Nm->sl|JQ_F#d8EM68kFWzF7b8v|^)d{0rktU^;=A zK06+{%n45W#c#j`gMekwHy78VDhBW>B%$UtxInh)F)+m*a(9xlX=f$ql$u686YVge zb)3{bDQEn%V#~>BP>{Fb&F#;-t1)a8eRNRrbs^BOaLP=Mcv2pl(pc!`Bx zhv=1qr5L0i%1mfVMHy&X=KIV^Fl}&pHyS>~h43gQ9a6Eq)p5UJ|9ZVa+wiczJ&G`p zW{9r%oKRL1voLP^g^Y|YRQ~QS_*h*I`cDR$u`G+Ea}p7`Kh ze__qS!qVAswQ82~q>adUH~q(tpx*)b%%_K5fm#RXcBZ;KOiV%0P?t>iAX)oW)~W*C z*%UZ2y%QvlHKJ2*rZxZc@AV%>gbkfpkMFOByL~J5T>1RuUu%+(3$U6OAq}Z7QM9$K zO>xY)P`yBNe7}!^f+7kl8PXNhblggn^22A+zG#U|P-B=WXns^ItU-`iSSQG8&~Z+rHo?LMx3{sYsC z1FkqQ$<-*-^$VT!BDqrDG9&EMRO}UB;$iOVWD}gXex9>veRbQU*I6#XtWo@FwHKE$ zU22c%XM20Jva!9axYyYPy+a*>gx272naud~;FrC##Mj|jGv|}R-e6t`Yk-lVqY2j< ztK2=t2z5N6U8xdrOGWA2GHjyvpqUmU-q(~!N4`#f%1(0Qy|MAD)(5$*%5ZOifvK9i z-KcJ7;1v8`Rle1XfEJiWL_sA8Khd-4i}Q{;Eh)`vS8FRO1K^>M(3>Dn)icpDjj~1^ zk%3~_G?lBUi@N~o-XX+gOtMXSSN%`&9TY)~; z+2Dm?XRf5z8b&L_2Okc&E+DM@C3H0Lz4baDzegnV` zmIkynh2tB@^urG(B$NoAqdF_ls*OC=P}tJ2H$>z3Yf3USZ;1Cc73Lm$&{B^Wyt zqd1w=)YPOvXbrny`;mgYt6xBXOPgVzsrPWDZqmZ2{R%FzDOUr?fE}I-Iuc@?J{KY@Tv{q49E*@**J-O+*7bp|Sf?M5HsS81S4r8%O03|X1qx->K*(XoUovjAB{`B%0hoHd<> z%)>}?OUE~$W%Q)5tO?Ida{dV3N!OCFb74^UXd}Gi3n`<@kd|1|<|(=PAY65#x(7g@hWG|z1MFJkcgdb{f{`9K zJ{CmNuHM0n{sd}TY9hHZ#luQDLpLare0_Zx`|49&Yu)Kx@8Qm*v#A}wKu)L*m)$if zp(iP6<&(XlZUP1P9Lr4|=DBptjd` z$V#DE*<{po6?ttF$qKT|0g-YcTDBZ#pYSzyYRtaB!kR z@ldHPfOWv(jRj0xFno}9(tswLmY%*P_?*z!zc=i4Bn79*T|j}LMS(^LX)=z%#HAEJErFLvJ5~J++bC43V=DRuQDUnYDh{$EzV+WcP%^Qvdjzz1BRG1=Y1E zI@4F{!Mf`T`$zyFA@LwXP3Us<&O+-#n?wo~Qx+Dqer~&4AYOrr_Dj$BMQL$uZ?OY_ zBB-$r9Hh*qU>S`mUFnUv6qa zb4_}m-!=t$R-5&e1(gvI0Q`||2P$lp^F*jS8je|D{sv?wyN@wj8X9Ko+J&js-*NBT zwMwa@{6y`S(6(}mPWsn>clX=rB_DOle>8C(e!VVEU!PhbM5|L{@$M09A1P(K({^=s z?jt^7(aXm*ffW`SL{%wC&%kJ}E5?~sNZsy1R4W6?_O8?&GeX)%0x7_^pnB4s>scHc zK`MuI_!g1O?>V12pHvx$AH`x(UN_YYjrT;7`xd`wH`@sFuQlL$<24Wc{EvB_7C{^Q zyOA;{!W%-j7abbvQZN=dxfY`qQ(B`$joFzP#Pb|L2UF$yxoZ7z*ap#Rt>{nF2r3#^ zCD$~mp8!2ZgR|1^ZU?(d`UoAt(8gen+9zTmiUUO9^SZg6+#%D4;3{H#mMX@kob#SF z@D!a;A3iP^J14sg&bLM0P1MTeA0j5(mH3*q1q^QnIL&tIMdB|ezoUn@z;_C}of5#5 z7KS%GYhiyPwUfX>3|v}n)STu1J01~tX?f#v>Q{9Me1>RnfXtd~s{JP<@^ycM?7MR2 zOGpm=YB5=51$)aHh^LR1&=>ATvRp&CoIweVvY;s+fAR7qJ;)(Jdu;=NGPI)j={i5o z0=8pS-By-+Pr2)A~AmFGu-gk zQJ_NE6!;nQrg6C&d=+-9QcDYNP@s(+3NFK9{{D7)1WW8^AgPj2>^0D;XRGAYv`)iD zfNJ3f^o1nb)qrYd<>oHT2D4umWN!yNzO7FS~j*(tt;L|8T0PF-LjrHG78GxBZZ90=xmWj z9%jsilm;>l|B5tTV7%qypoHr}am=N{^STM4XdiSO*nb zb1k|(mpv5i7)cebp4@!sM=SDM!cCL-ooNJF%|q7tv(R%jdImtx)*fmh@?xr}O$fa? znaHJ;nrA)~fGQN+A8p&jYO%nfE)#KtI1(wO#%=pqmMLU1bn&c~eIyyi*5Ek1H{S_Xg$< z5eW%$c6OyPlBJrblEL~UdZLpf3uQsZMwN+;GT0~`?0+|S3aXrci78%jobFzJW#HEX{E4rR$=RXuG(wjG*LGh15)qlw1YvM>}dvr9#JNmcjmu%-& z<(fvQeL@RIzRZyn6Z3jDeJkD%LNEVHywRQJb{>k zD*`nvS;w?2($1mU7Kt7V8)&z0`%@}y!Ma-xcY*Sfb|NzL)o_)R@z9St$xA@#+d4ZR zfNVx;EiLnF@2exGQj4NVi=((>aPFLi92irU9CG@<6k z)g(XxG2(nNIjqA81gyfu>8|aZnQ@(2!{g!YHFguObJOF4n2I(43+9?uNG#ZqtC@1K zzdqh&z9-@?2!cpYhPcX-LA87y^#qHwDz9XG80XwUO=7=6eG1r_?`W|RM2|}Y*A!Sa z*T-6?fExoK8WYTj5R13(^Eai4`G8vPNUcH z3m>LdG@*OUV!1%eFP9`33t%i|ZnFCg3fgR`FCR;$Y43od0sikQIF8ae^t%iWo_Sst zWWL8Io}zvhYj#6GTj0YSZR}BLM2D>tjCr3&{nu{YFZt?N0|YO)>uQ-2g@>{Efqj zOZg#sdEJhwiV?bdu&Fat%T+aNm-%vriYt)n>R&A`G$YWR>o1-geXJwGEosdL0jq%( zTWrbzV!&5kbG{fU1hT;PIufzuxVU!k!GH~VO*Ka)2$Pg>7#$i6r2dz%7=kbloPN2o z=W^$*OM_+E9>F_I4;~LXp#d}Xwqxr~t;>;ap*r{3XY$>HBPstJw~Y@^zpQCvO+3l6;E*jB#~lRc+}Ypk1B#L@ z5nY|jTsuo#?zVUTdpNyq5T&^%v1dgiB$Sw%I!)4j%149bfS`;XSWDOLcw0j4-mtUA znWKZmOAtODNWN@RQF~+8-%i@6fVjmB?xRCFYFyw94-By7p`4i1-1o(!@BwGReLodk zOJG&4+gCrM9~mBoeJKx=Zxq*X=EH|!4I`!lR4ofHs+(^K#RP8$v&Y)^;n?0VS9w&w zppXb&tYE}MM@NT|Ij}+(^^J6fo>d4|NdlPll zlt<}@@IHLCKIVmk-&T_!C0b^`P0()F&^WATk&+gbWsl~D!@jgVqnTi`#`kr~>mwfh zHUHOmeIB?_s)ZU@;O)Aeuvbv!cg|GD0Z7O4*|D0^K4;0wR|H$(Co#%;=+`Bv z`cGPnJm6n&2S?rOj&%v)bR0t$pn4SFt1>=Oq7OEpXq+p?CZ=CrR3Q$tP6V?n8J8xV zQOoe~@b!txft;7QfsP)BH&!W3&zhcjt_G0>v^@CO8V{%%IMMOY{Vq*;?%5umzgvd{ zAa}!yX1~WTEeI)GTbP@tY*}=@q`raRm5w+7EYJ)SVFSVlSy76qp#~?oR`&;qlT%$; zpCQZa;C_Pds5|*f4KN^UX zVa6j^}QhZMnsyJ5k$2(%f}-;R&!qhEx%J zR1POY?(H4)H#$072Z%RHO3y&)p;7VSTf{Kfa%@&Eae|R7-2HcoDyypE09S+i5yd9n z1*GIZ>^9@lgddvY5nCEK-~}X}A^x?FZ#I-)B-&FT#UDex?ADF*Oyd(??DE~tS8uXIR^dTx?8@GKnO|usv^k35SA< zzsYXXwEazLszsrtH~+vq7e?scwOu?2j7v)ObmA*x7cBkMC;k}?qwajhY|~rcbyuF)JXUG6t3Fig z>vq5B@QW93Hq$6`Cbjb-PUh#focqn7V`!o%K3($1EBcW@PR!5rk`sw9_UNwUw$vgQ zc{;Lf6mp-|sL9B7Y8G;Pb~jovybQ&I}8(YZC?*JI|$bvNx^eZsvDYKl)GkzN2=LdFBFX0x4xLj3X9H5nb zuc=9Z)eHQ5(PUvaxWeb4Nm9Fs2Gd8dev#JGqjNjmp8>v6BW#%=6*Z^l2W{curb-gI zCO@7C!(ok(Du8JbHTI{sflL2(YJraxtl;dV6Jl*aUP}>Rb|X;^+m-$KgO0R9mSn<7 zTCpI*yy(E?{^1($4UsKVUTD@N;lD(=0}LQKM<5y-&F*MW$&oWYBR29G3RS zwae11oNE3wt%Kz0&Q1sK2N78*pA(3R;CnDena^ZHQ`Fd5=rdI!e*jqnZn5X#=C7po zM@B|m2m>zHZ)0OCN(=B=D}`BUhK=h186r!Ubyhiz)GkmyL5k)S0u%g$P6a+C5stbpK&gd`vkG1|nqCnkut#S*|w|u@p#R3~@Tk|jVG}{c{ zzYX!$)}*=%?P~O>icOduD6(3s1RF;&MDL%bdOE5aA7DLZYw~vEY~p%$c}x5Y4`^fZ zO90{L0s6Nxi7|<}7K~qd(7m8(MFB&T)eg*NbfUmH9M7&xnk{$!jFr2V73}~FKH*@u z%ZRHjfuTO3y771a>Wc&>*&Kt4NS;_65k_~dit8KS1S&v=nFCH?+wV&KmfxLMh9dHr z6aSLmnOSY?8a}DQbMuwQ(_E5unu|!X6m@_@Ve1B!|Y{jvR&g@v+nzRZx z;rGZv|IT;WSi*rQcaQV97S9FlqDv&jw_3}&V7*lvHq&y}x83va9!LiC@o;;8t@~Xu zf3(NA|02iEyd(CB*>y|R&kKe4!bS&1I8KM;6!+b)Pn|DSS0yiz6SQl%o%KHv_U7Vq zI>1~Vkv|*W9ebn3QRIP3`0Wk$)=tz}8c&}q38QW+<8 zRh>*y9xUELJzcbh)b|;_D4L8^b)OlyvTLdD%yjJzpYr zw3BRo@v>V|T7l^7fbN@-^oOI9!w{o-6YnFdZTlom>JF%;b+DC`m18*#KJK~z{0?L- z@t`;p%lQ`&Q<}Q-e%j*(cyhu>5X4D0v9VDpQ&1dpxgLK2X!Xn7uIxI%avJ3p_y32! z21cTtH>h2wmF=aa19v&!KaP|72tBpN(TxS=XO9}Gc{p2bRhdBaFmae3jj z^q8aPUu?Fd;y<7Tm;@uENiWuh$P2aC$HdqpjlAk>S<@+-iMv=z;tX`F21|YBe|4a# z3vW}uUUHzJ6+}Ce)Y0wGDfuS%-Zb2TlknT!7c8x$c0!zd56y6Wo+wfVZbu&(km0cE zc2Li-9^vKkV*zkild3jkvVe`pN&&--Z_&7fY57#NRY1jqx&3b-k$=HzZ_v`wFh0o{ z|Mx?g;TphLX<_}Q5ikGJ-h9u)m;I9AR2BwvZ13HK|vU5f(Kn%>GKkeeJvr1(z*}Z znGWo9uaK;}8tfYz}I9% zYgH!l)?(AGX9I+prw>*4o_FGzV@lwZMnzE;cj-1RF`uv)p|MYj_+3U(?*-uaf7qF- z%cz>v?__^(_OA#3Ov`xUkO;p{B^6Pt{hHO?w?0=`Le>B)s!OC)ICRToDY*FT0g*3* zrP<6M{N#6H@^_+Zx30VRw?JdPiTd5S!jy^dNPG!L3>*3Ie+{P;?t(z&Szcf6&st8@I z%6FQbc~1FiQcdfy=C^ncX>aeWzQ=;q-}EY~Bw6cOSBHUC<6pmjag^S5pKTx6St(q_ zpnOl(h#{-Gd-Cylr^g{1ThM6NL_F6$-i5ojLQ68t6{tlv*Bq>QmG>VcT?ocxvKL}5 z_1J$lTA(JJxQY&!G^#jp%}41^yVF0M%EdHqtdf4-+P2MW?n zJUjzn&jW)W6=4EZ6(C6{N;VXjDA^9Gt9wcb*(aaDp(X@k8l0YM;{iZMTi6_2`ga~{ z^_)=9^rjL5QFH@1s^~Q@=3A-4+v{Al30fQ3E*UbJ9inE?t7M4od25sOld+jhneWaE z$c%e?$fOm2!EdlzAk-FJ@xJ|K_{*cdPR*wDB(|b;k=i!qoRB8ZBusy~TR5Y*9{SNq z{&^%!Kfw~?Ioj&b_e}=VQCz-!Rbf_a^jv-eIMU9-){71csuJP4b_M^nYhXRE-p1Uj z_}HS^+ur&?RhTAdTMM6=;)t}RnZe;U!k25`p5_RR?jpJ|I_wzWK0Kq{KuI(HW|Urw zA2Txb?$pr<`<_0eU%H($?DkCFv|UHFbwy%7mulvRUG9avd&yFHm*E~LDRNk$9|t?P zfx*E;v7)5Vh4bBc|BA9kQK28CSyXmo;8b}cfizPXCZS=bXg#F5Ks{yy(XgKa^=pN|_P9Y{w$?zS3_>dufqtE6 zW!~tUc1VrCSF2H>I?VG`>9zN{#|{WObrY|L;Aa$Ic2hi#P}F0aFIwB0P3F@nUf=w8 zM^M;DB%j|kyGx+b_{UqF^dMh%p*D|2>YqQOx_Qj!hU%9@m8gG_Kl<@SSWH;8$XCi; zAR#SjX8)-f4QZ#VSLu!U(2tXYcRCjif7%3X^d+_)bF;a)vIayULJDUcj0oLlI=%$I z-+Z*FaGODQHS;*nk!D>;^xxhS8%0xeAv))XukLq4-48Js=9v$PgEGuJ-JI}hjcWgN z)NiyevDY=`toIDEm4vVHJa%QCFXoddE@6Y2*e`kKhaeloS>2SB} zkmqOadiQ+&Meq&Fnom0##1+u=A9Vt+))E!#yVN*`{YoIJ)bc$fU+qhn#g#qdM3uWYPs*Ot?^pTkMV@#fcwm#Tu?L5e;^D?@aj zdJB^Fg*@ncx?Pg4s#y|+`(}Kljuy^iZI}cRQIoHS*^;XdS*HE2652}hdyEXX(2*|Y ziQL^2gEbCVGlXh;g-TL5Qx{x5+f4!|MTNNuEu|i5IwJ%iPQIBeI7RnvTDaAJ#DZ>Z zLfzR{OZpzK-wk1=*(@bj)-z`E<*`is#Au;L+4#^G(f4O^jIP?$!rfkQ2=KicwV#=^ z8`pSh#3}A9MMOm=)t+7)tM=jM=wu#-lc0beZd)y4nJP;9)Kcf$D?9Py9~UPf^+Fxy zzsHi+xX%M9Sg5FNSL}#8LeS)=wvVO~#9d!IRM~}Q^aTD8tUUEZl=do>c#bpR{vjcK zeq=GTFO$^x=Vf`F0$OMIKDBT}`1d~%b|kF*b#$?(^QMo+_$1vv zEW71>GOpg@wsi3^sV9@M)>imcZAXV_X{m_KFDT3yqFpUh3U!;Iz9+K$-r3hK(`ZXf z`+Ts4_au2SvBtWYFTor;GoXsa>#gh0q5-?NcnWU>B82-UvDd6fF8q6D=W5Nndv~om zLewfadAydlEqpb8CODk zVR{<~In+cj-GX{0WMCz&u+PQ?qR{3S7s19W{R^67t;7w4z&T+E5H{Ko@z!^&hZ=cD zFL*=3Ma6W7Wf0PPC#J-j2%#}0YTyp zk&L-df`S`F=@R^b$6X_>9zHem;dtn3bE>}nSrb@qGxw0cGjoyFXPx>u<#n2yr68Ym zE6^==UQLHRwqYpZ_p2pfT_i_uG+vgCZ`>gv>Ce@Ak}k*k+1#_Js4V8$=%1pxvIHHo zPpvl%m1NdjQ(TH^HWxq`w^*VbDxx$tmHK7c&28QtTuRj8z8blDR>aZ;Hpco3Y*?jNCgm%EAAEvkl z^Fkgo9~beRbpKhzOuf36}hK}bVJhyh6ECST(TLeTtEtJJeedx>OTGrX; zwb=_PN!n_t6jxrcHRhst{@P^D&^nrWHg(F-+W4eCs%JMoxZXfkp3&s@>6x_V*Pcx& zr6tW>68DA>aZMa#Y#`;i)~3@6MzqHc+18Z-_l>FQL@i{QOCIC}+3K!;H-qg(9M9|4 zCDP*X&0vb*{IXw5-MVE#@UrjL<=(HMgi2Rl<;|{zUhG{3hvN9t?*|nVY`1f(VuD8M zn!gp|?{4lIbY8fzP*7EV)WA7%MyzWca(Ik6x*yFDwg?}y3t#NNNvhl<_fIr$nXHL_ zl9$+Uv8MO+^1S|JJ+gi;e$1irWVOEZ1%+ePoz2@A70cf0ruCX_^t7z~MFBi!GRwl7 zh;9L{0@lWTGbgium0{&0JQ41HerwxDYm8IpY1U~S-JSX~*`yU5U3fmnKsI$wO;t0; zb9lQpacS!62@Z9&=lA4)U7bs1r81|3g_|>N8{1BFSbLYvi)i(F!&u+Ho}4MZcH8Ec z&8a#2e6_R8H}%;3wk)rOE)?c);Bu{4zJDpWNwC#b@imtE z{I4?}GvBoDvMkl&ze17SMdIXwdY(BF!WsV#!JOf$FOu^RKZk9C-tyeLDC~b znckyg@A&P&YJEgs-{*14o{I6SZY{nmgN0eOuYFv}e=J-*7XmcTekBQ7*YW?_zOl5I zd^b4uYQ8J2Jlp8xbTIegy>)zn_A$ey<2xz)x+AKS&)LG8_KG`=Zzj&$k&=R^*f}Gv zEx#Bn=Thrv-Sc#4#>iq4ZmbL?&l8cT-aGXw8KMV`;Mvaqhn$@Z{epaN``FN~T zUZEO)qAO0PcX`Tog^c(u5Ng<0G>^=y6Di-|`&lw1zvqzuc|CuK*5d(uZeg+cgVzTF zD|`T;+JWQ*4D$#wU8}6QMzD+kr|vyXju-6Nz3RA&BUolRw+#T004Uku>~I5a18Dr6 zpr%F(3=KVUb|PV)1D@IX=p3!u-tO+5m8ha3&iB0WyQA*n;usnl8egKKP~Iyb-&h8X zjDqmVgON85_hB*s1@a!anngxOOWN2JN8|&^K@h}ua*6yyOI!!=Q~WrH2=!J2g=zx@ zYj3syE#&Y^RG&bdgXpX}`)60}L`iAG^+#jPt(Qh$uo zzDm?I-?>q1y-%_iIZjPQ)eS)7igNw$KKeO?G}R7;U|Ir6P`;flC5IGB8Mad`;A4*rF+S=Z(;eJsymj$x| zpX+##q40{!5^PF5P6v{&ZMidzQ?%-=^81AU-gXe_%VrP|i2ofhj?mfPRB=97KEScl ztW5q`NH=cx8}G?>x4>3`?TQkL+?j6(7as8G01^VDY*aeZ|D)VlCZ4IJ=pomJh zNJ^(PD58V5BYcR78iPj z>o2HYT|TruPrDOKWK#pl=SX6&rvskW3zxB}CPSqr1S9P|iM>oThwGv7u033W4l2ck>EX+i>@_O_?Gl`L zyPF-^l?Ac)xKqRZCGcMy8>O7}GAzrjwe*}7{`$x1Ju>YPL>HbSKY19|-KA57tYXg& z(NLw8yT^4kRY$JQ<0F%k^Db4^@3X3^PzD)Ss#G?=3+ys_H5^-X36Fo2IO94Y6ujmy#Xw7Fp32lkZ+D z7Jq4RAlu(rx8*-x30&hp?{zOd?)@IRCfdC$gB`CJ$5ok8s8yG>KWWZabymPfpy!rS zq*!1uUTR)tDF6Kx+lNiQn9lR^YsoU(-3BtdjdPhnj+1Y0B^WQLt6L5;bsGAHMP)YK z&r%tt>vX%wc{C-^FzeRtOj-)(cwA6%ZFjx#$s#-5{n)YS^FLaE z)ScPdQzKa{Cyc}lnl-~9O;yE3*f z+jhu@9*cADJD!&DZ^V9kZpj=EPB`t?(fbmi9yJY3=GBG8bs8+h+lt_`n?X~M^hcs$ zabe93-(yHgGfLMt$eugy;!(v)zLAb18><8OBlCA&dzDgE3TmA26gJev9*|u#-m}6p z?46yL@M=xmiDg@haqg;of6N^a6JyNZT-HYs!uevr;y6f6Q4;&L$Azuq#??O$(>uL_ z75>^4dAi$Ee^>9b@CJwNADm7NSiiLy`*hz?<*mYy-Gl>2LuR^^+8X+=E5Bfcumu0|3CuGWHHggaH+1b@?Wq#Jxpv^BdQ^oIOR zI^iw!AnG|v?OM6E)k4A-sP$*o(UFjmf+w++HeuxYI&Zts=m?AK7Mf7}EC02LP){v& z_EL@kY3vm(-ufe9!cWz>`)k(M-MnrnY9c)lyL)Gu_N}Kqa)xUKZ?8kpE5=l=7ZqpP zRiwA3@S_sGo&{=c+HtY+zujI4ez%pI_RXGuZ9$xccKkjHs@ta3aFu7bw}l^WERmwB zj(A8X`O$rRPPT9qoveeVeSR}9Hy#tK`&L2ar8(#3C7mM2)#^KEj7%&NY~%(E8E%Ps zgJ`as+U=)uF(q@WcY=5_nl}jg?R1$@)f?d*Wcb^&7UJ*y-N%HXyz)2k-`!4Xwt@-* z@dwXpR~rlgP&pi5FzYe-y0~Nw?c#Vye>=LPQh|>0!)Nam*YWkrBGx%7MKmw%dg zaZ48ck1XC-hUBm(dPRhm`8GW2cTegIaOcGVFZ*5K@Ih9rAo3v<`}je;ftJ?P`G9HA8paua)72HO!Pz4l*KA5c*S5`_)`zg>dFhHbkFJ4&$C})b_O25w0YE}UfpF^AN7asKA$yh8A0>loPUx(YZ>Eh+D@G$ zqc=$E4skMlNP{RQ^NhI)lL@iIGeWY@srG)mL@}>^tm+CfC@LhoJ$O>Ci@O_nQkIT8 z)Oxhez{E7nKofUvbeao}A<9V2kR-Y3*n3HE83Hfb;V5+|(t6*T@vUsHa{O-eYe`$# z9z3|SKoT5fPsC+G{`9H$Hxa*cs^G!EgCCH3*L~FgGsdfPOJPF@W1f(|7rTlXth#z- zuBFC&PTN64>-~J&VJ^o<{LXN-@6%xC1ga(RDQ`4>P&Woe*yzM~mGzr>^TpBjE2zd2QlVZJcHy$2l zew>cQp6AIL4r_qLn=O2lm-jWW9er-4QZ=x4vE|dNqd@Qfj{jG$g=0eDlWkrnfpLK_@lFv+0ug zS-jm}{LqjbI^WH;1)hb5gR_%|DLFRw?!0TPG8Wnm@pn%YhCM6e&Sx}xDo1B*&MIAF z+~|tK8~TZF-fFTrCiwxex*f)qYx(d<30Z}wvfRNn+1Sj#SIx`TbUR@!ap7iH ztGJlhRt8=f$zFynrQ?KRU1H3?YHWqvPF`FbmdLKfvVT+INo8dG-age>KbdK<9@C7o z@aoeqsy5H9GM6@YMe=UtA=OpaKt6x+ERhb3;WS>vI` z)OJ4}p_*iQiau$DRui_Sa%{N3hcWiUv~Xbp6OG$AF`&W7+>-lQ%l)j#2qvF?15`bx z>8@cyyzLmmpXQSvHl~AnR=VeJ#G_evzAU}l(rCiKcxb;zW@RkgD&N?cmbFgKxQ+W9 z9sTs12%&+*>yf%nmX`Y)LH3=v9SIsaqeYP@ByaI;wZ9rhI(zZiUb#rFFYzD9$mI4^ z`=(A>Y5JA3c=cend_T-S8QZ&GX-patb9a41E5eJjrD&U7vL>Zm(67aTHPU%0`I2iL z!-~jOa72J3mN{T!{BX`;9lghqE|e$cdy^~&AN`N_t@uOx`6mLBTN#*?hei4Yg2GBA z)jn9nt>n(tarpgu#myq)jktMo+OU4uJv2tM#jN~8fx>s9U zUR5K|Xs|^X4gBy{%BJlalD9hWk0dxC{=h7x3^ph-UjDS&F9X2TV^A^%OPRl*5d*NQ zE2AE4ql`NxG{%!dR4ztxdmIZue#*{G2# zc@#crkb3jx!vsXjytlA;w^&eGFF8PQ{J_6d@oR?0sG)V1d1`%A3Uz-M4a)X7q1ipE z(!_g;P0rhK(}_pS0$o?VE4uab52d#(TL!6uLwCY_Tx)5OiR_)o=@~HUh#>6*+I_+2a~(#8on8w-4f*6 zCE3`2_;2Hq_3+??q6a%%R)e z98gz$cRW_a`bZQ@)PrwBzvER_-rc)VulIMP&`wM)KX=+Qh!}SQf~#)JZ*mqMERC0+ z4||k&A7PmMt3avLvWgPSEFa$T4SD9QTV=R0?yzXB**U|!x|sNFKt2mNg(;agdK*O^ z3^ylt8=30@ShYSCQN?*~1&0h%x+Wf%SW09%a+Hwv@JF)0|5hb7XqdhbZ=!2grQXS^ zhh8qKLXcWt5+Q=KW8XbCrEy`%5nH>SrnmBHx>M+G9E%f+L3%v(6!H)It%>Eu!+{sX z^YR(~(9B6Ms}@urJbx7<(EG{D(|?Hdh0RK4cwE=F&tG0`eN#7Tq{EWVzgziXASLeF z-D#8e`q-gerEHEiB~oo> zE|*6;o$0LE=~Ln)V+&JfEB^Y~{`GmQ{$YbxaH4nB*_Vbeb+&bNZ#F1|Z>`WBO8 zgK;;a(Ze;AAS=}tlqY^+wkvGbS_`_J`)uQ>p)!Z~7b?oQd2>q}`eSG7GKNVn;_)gt z)7%6S>zCTiy;?6j^d^tSvlo{=JM2|XFlenG<%O2%Vs#54!$dio|J-12zIoDNL<@Ao zF6|Li9aX~2`L3z}fmHcC^usCx1jI1<1a2f1dR2YB_EV*nP%=4)UJRuK`0wX^I~~w= z0{Q@FAD^H3Cv4Z@Ckc%<$ZBcQ5%qXf+4lQR2%}S>B0>mN}ZU`F-SI< z7jjy$-^$3SqCw$^swpoeeAQ?P4!_4Q&57GT7fTD~`kQ)Dd29=^Mvxw;~17dGDxmxrKLHk^kYx!t1k?5<(*G&posCUSV|TrLlZ8ThzA16q)>Ba0AiKH$^%jLs`d9x4 z>GRGgwND8nR3oU&6ywL0I^S+2ZR(#4tbOR+PU%REsbJ%j+K-}n)+y!O{rI~nC62hv z9dBXLmsMRmp?a1hn`3UqEOZ-PCoayTB`4Lj=38aQUDpLp9y({L)|W2TU-Pvu`=5mY zd9Hvz_Ha26{7g=ygJxSFj!KN?8oxjo0Zc(iQUdqWgH=!OV`3^h>V4gz{D{EtxgA@4 zF^t)YrfP@LKN=dE4LU9%?9?GX0-VX1E<)$4&+a}TT-=prA?&@&8g-#iSeWp_T2@{j zi#pOD`ikuOx4k&IL+iirzisylq4fBzES%klEIs&sZShxGr>8tthx}?JkY$Et^3&?E z*K|X|LMx9LlJ~W431`O0Vhw?IQcrQRRy@C!^Wxn;w%;v#`wN3(2?Oi}sEbzm2Sp{* zA5He__007!Tw5LgjtmnkTHL?f<=hAze0|iO;(K?z+}f`@p|yU!ONDEWqLIu`Q&G={hYPi=%)*_D6Mu}4ZTS)>I=fZosQiv-53fyc9JOJqz2OFe=3UVr5;EmKD4+bbO}54IdQ7o?9Y z5--q+-W=7LkXS}_MD@P5|NG*3%=F9k>%QyUsS=;enJ=t!H(ZhntdU(ZWGwj;kCf{g zQl4-TF*c4r(yT}oxai>?eY(T4`*63_u{LSp=q*vkJm}q%wq`c7)E9Gaq8Sq%70HHT zr~k;SD74rnl6iaAgLwCruk1=ly->0H60)ysO>n&@m&NVJ_(<6uq4q7tX<9S&AMz%e zvlwwqws@){tsRvIvYg0x&+ySUCj7ou@0^+~6q?jIlAIr02Cd9}dX^*fE7XUOs2k;S zuS`jvdLw;=l)}yF-qYCL*?L=%H3PQ(7fcDmg2!%-!%QYSYWad?GuDYMC#H;I1iicK zBV~tiEZ)f7A6n!NFb^9Xac?S^BE57xBbb*9C<~RdndB@+E@kl?Tm>aKFI1EY%2nzX znDAORkVP@;!fB=_+Rn4*c`DsW%>&j2p69Z9h_O3`#9wcLOru-n>+&<}(j=yl(iw z(6DEGoe%7L>O?Nfx7vq2(Rs)7z4zw+FlbYPs2w48p`!W%_KsiBpZ~Vi{A%!xoi37P zUQGKo7BK*fVBn0Y@#W4_%6%=nb}C30Vu9px-v>l3AVd2a6l4g^{bxVF63;8w?kbv2 z6SOUpIwW;7kGBGwQw?$lwd7H5O^5O!3;GLf)5#B3H#jlc-glB-hbyOvre0_MF&{&U zng~FyY{P2S(?GtvIo|z>a3L-qX%6pSKUVW24ewWPh<@D&Um8gx6#9_UtsHl8NogE#G7F>$j+S|WQpEAE$eQC{Kop6%o<#osrwbc9SM0K>F zKoKi<-CezP-Ih6)uBA@W2^7HxFqzpORFvZxLUEMSJEBmjaoobbmks<(SS_mpY6QA+ z{iTlRIBDw3tE*^Uzzjs~FsXrdSBC$ixNfV{1 zLC@%Nxz~z}&GWEo=d)IE{w?+11tF9{WtvI|I{E!JMbgUUWtqsRou@^yZF>4+BF207O=(N6RE@9f@#dB?Dl=>3L`gQ^9MPi(ji7}R@3p$+@sf;T%f1a#? z9AT{@Uh?83d2&@KkSJ$DQat*3<HRV+~vLIh+H4FUsB_^X~^UwAh3+K;lZ4Vu7_P76hXVp?;@gmTP3Rz4*RtX>9 zM!^+0WeGnC$uiI7J=W;RQE8E4uRhuOGBf|sdG6-i#?6{6gc!rP(&e_(3{Gdxn3J8! zhL_F8Z}O15#J`cLXA$Q+?T3413SRTKX)N_$cHR|KnA|;G*wmQvc|9Vo`)lmioJ40# z{b)d_qJnkC-`_vFq_4wJcj}_Q((KItb2PF@zQLC2xVztUC}pZw^5-L8<;lNL=h>9K z+aza1@9V~Y7tZWS3EUq0ZOm7(m$yA45kpFDvwMI3(&F?eC=-==w})M-^7K6LM=|M2 zx-H$|*LztOQ~b;Bgul@Yuv8z~y`os-yr+10&hf{yVI#1}qMfqDc; zJk`3Iz6;Ju0-usDa^@PuuYe*_EuvFoc=f*eB!sd}xvOB)VDQc%)gW1K=YCG85npcG zx#^>e@xyElJ|S5g3nQIO?>?@lX)h$iTXh3+49?QW+z0g-rbOK7I+-(5VhF$Q^Bfkn z#HNm9oH+?AI(va_9)!Db>?W8XLy?{CS_uG{oYuYhEZ=MmL!u1St>!N%wlkmcRKT_m zB|5sxHwmK(@r?etC2k%bf?ttH zpa4N^C)=KdhQ-IXLs!unt)kuD$=q;%RA2^yT1i(2WW_{O**NO%n%h69a$;)|M_5vZrg#ChbX-_Q& zRiSKzU;79kYA{(6ktS%o52X}!xE^?!20whj@1BigbG)#m*`F*Rm zbV#7NS*SR{zJMkOyaB`@>%A?yD|d7TG?2`#R~O2;9xc98=&oF*OON_$R@4{XdT7fz zijZR1ofTX7PW$+_WzYzv;YrJNy1fguQPGK9Vn1w&NLW-7ky25|a6OST-*%qwPKt{| zH?*Se0BQI|e=rNeZL~yZ_GUh?Oj)+Xj)Z7!G%Pv!8fbApq z=yQ>vg{)Jpiv|ob^)FxMVo#VVLP`D(J)yS0p-&B)xhB-su8Ec-Bb45-*BiR#_@&^I z{#fHc_*V4EJFj^wk8l+e?Kc|zj-QfE1r@Yk3h0`qwru3C*c+_A;CIW7-`Gx(c$uo^ ze!6FH-$LG;y_Bqb!+d&WJMN0XefDlka9zlcoy8|ShP12?G{O@fI)|NHd!WqKXd8_m zsn~aaM^#lM>D=`UKTh*RrklJPHC6XKpk($`^M2rUmw%r%H$^h*yrGxH;gY)`c^~b7 zeV;b>LW@t9sGO}{bB||9;9up>nuEXwuSQkzGNG32&ieFQETsg0;=Uu9dFaR6crdr4 zbVJ!YG7!kCuALxmN58dh<}UJHqb#}kCZXrSNL;-0ilY0zIsXZRcC+H&TYJIrEfdz# z6dw*0C%MhI>0%RIjq9uD6_C1(bL zIZV0l?@HFmO2*v(3AcU4Q?2_z?GeJTQlwF!H|gNC+j~;~ZPr=Dvb);0)h*Y>NE(By zmL+(jRjYGLjzKr03_ZbNp(pcZZmEcI>~dX8n%If+#gvd=nGm+^+g{bwkhpA3vD^XA z`>AaH1s(Zz)`2t&>cMH=p})>Is3!Sx0t#m;Q`<*ESA6-%Os-oVn^`EWjAk>gvfF1~ z7!FOS6?MEh#d&|Rt=BelM}?nrNxh){7&m2Xz4xP@ z$GwxX6S-4|-u-_~HjZ^R^viqf&hO8hh<{ki?zqJq^gp?W%~Tb;(f#6J5f75ThrQyQ zuEb7}$~&ICdn~M*wlDwfsISKPD06~<{MNc2IZF=JJL2qg(p^@&gGM>$r4C+YAzuGn znjZaTe<>HHE0nBO4z#6H!YZRZ!sV&Hke%tu#CrxUtaAm?Q75G0ukdR4`p)os^Shag z*QeU?J$_egSk@jcDskwX&_3yoth~vWJ1e3MQ;=hx4gb^3Q13<@`+)3EwAaN$C9Mmr zOm-&G#Ig(QgbK`OO(ryjL1cg9%&FOq!e5*f)B4icHyC#o^R4C+M3toc^B{7**-NZ^ zZp58IeI04Jm9@Lv`NAeVR9h>*r{D1&X;1$_@VG(MrPH>DrjQx;GjX}O=v0|Wz8gC6 zierWwo+I0q8h2*^-({2JBXt%-AosJ%Ush|A2sbz?*#78jl9>+M~yh=YMfO z#>a010VBtRBZNOR{{2e_d%(^Z#%fYqNV}!PBxy`~ag)CoT^BV(+F8IKH#B0%yvh}5 z_C8wkuWeeQ9P{ze$}LB0W0a7TE-fPd_y@n^eK)!@OLMMiZn(o8bsUZNa!l@B{A7+v z#;p)#cNXlOa`{q2FR}O{u{%Je;A6t-9(Hj1$moh1DE1Li--v4XlZv%Lr>#*2y^mC9 zu5w#VCB?EYCdr$d>#MPHOCrG2Vy2|1m$wCq=}Y(|N&HqKV1xBo-sWediyl8f&Y-@M z>%|l%gX$F{z!WD^#&*c+tYvr8`6*~|v?I|f>=))`o$oz`)lXI#D za@KoyfLOk<5th3kXJ80QOCtwYD~{Zfy+=<6xBKa?b;ryg;DY=HUM1o+kO&G2F2W3s zRlkEdCw%)NB{YN)T6@OD5R<{DyIY_Ue1PTRQnsC1(AXC7YPM8=K5fQapM>e2dZy}Sy8qM>ltmHkl^4x*XrbT%R|?#*w@C9?V?}@0k^ho zr9`^y8P7X4wYA0fbg}u{22L+e3@1u0a0B)2+?pMZtRC9d+pqK_P?kVT8}_%aL?YKC zMVQn}J>?1v52a>CPC`!>^OXe(&Q-L^lavEX9WwoPWD_I?p8z!krk=(G1-K@YLqANc zA%@^Fxm@nel5ljobkXU*EE%FNhMwy`vJshuI1vQ$0E40acEHeq{g!e5;U)&0EL#*n z;*0m9j(okA0U5JVAS~#v$GZBqL`$Ah0h0>ZK<W$5ryBB2qD&k zQ8z-?07N2$5Dd^qEm<;&0Ag`CzW^t8dw2H|0FClADndXST?`rGe!AG*i7&E&hcG*< z3!fJJB<{Fv)~Pl8M=y7@>-+=hhJ5{+27D6u3e6L5Ei0hkfM`3Q+@}EUhN?jlELN`o zm;zhT4psRX0KlYTU|dMC9c~T^e55R|Aj=>q5F7taVfu)+!HtFu1=E zI+quaO!oSj`J0Wg?d>y)mFSf#Na3hlO%GIsUI4(OEv6iBroDp41HLs>)wH(EgXMr( zncdis($ytLNGbq`VdwHtE}2(MRTaOg>X?Kcu2sZF^oLilxLcn_k;n>waNpFxPYryt z<-@gs+js94JMCz9J9c;!j;QQk#(pCWOs}OcsPsunBF;Wjc>A^yJ|%?{+Zf33BV<9B z;8jZC#e;wUc;<=acfKwKDqxp7P3YHI@}*f zh+dGw7J(qr)}FSW7GG;l#cS+*KbWJCr&XgorcY0a+2qVc7z_hIMR2mtmQJbqqIH0a zUlcw+fJV8y`7#PFLvGvo+kjoqE-sFM)efC&EI^iSqoN)_v^tQ!382vM4+?66a~%>Q zvt*My0ErF3LO{X?9pndD1C_c=b?3L!?i-AkD+6*oHoHjv_dZp@D~-fAN3Q)Zk<(lp z-WJ5aH?LNcT{sPQUVi~1#iYp8N*%=h|2a4a`~XxS3}R^g^p2?CtGg7W24T zzU#b$Mg##^|)oRH8DY^W9@8YmRcu-6q;dCP3}P%giEa0On4H;|GM zS?jHt8g?(@;#FZ+OKESUZq_Tozor~!ccT?27TetgRNMsO$w2z~`?oM~K7YajoQCM2 zR;A(qjvN|x_JQ|3l|K~)nQNN{{{4#+a4TOXJ{~kzwOoMFEwqF3j?ZB;6aRq>a%kYg zldw;aGC5!$eyz|;7rxU=p8SZ2=t3fKFZNSmAu}WpKzVl*%C*Fdcy>r?JtqEB6(F7+ zM47+{(ZuZVwu4F_O0zTInO2+>SU8-pJ(?e2O)pu5Zw#Je9w@|_h~9}tZ>erMkMO- z?Y`e?$t$0ea`)5*f}*pP=k5C>`i)~Im`>yr-xpNZ2tri>{dBbDe1q758UzDe*$He* zTEwfOgJv1hnPF?w;aGQ#wIV>}Z8)V>b)OZrY=0VoEjb*J19XdG)po&5S*bCRRMw{} zHCB)F4{#5yQV!TK1&Xry=MPn+la)!@tGTJ?N`sNI^;Mx;cLFDqLz2ML&jMd^1xJX$ z*m#5uPyI6Jsd;F8Dp}W#aLxFe!OMb(;E<}b%`ZOM4zF?Hay>LfFw?PAkdj){`?h0J zX%IkC*zP6}E)|S3j(jU%78E4)^71lzDP_)p&WA8NL)l7v>ru5&_DRc>^U!*R5K6y0 z2(g96?=#o#Hew)t32fk3FEd-BN=PL13FDi=Vn!=5?$(F$W`z?eZCI*$7~{3UYdYp@ zO?&}Y4*1y-{A<9QKE}qro#eqY?B-9(`+-*XWdA2z&Y*cg+>Kn8<9)?OQt-`@E*vL8 zoXBFgD5>qfCkEpwm|)XFBI!GA-{w(B_MmzGJOGY2Jr2UL1}`BvYY@jHRIsc@9oSH{ z-#115^}(ocnj4Z|21nOnT%K<%$oZZDZPmPc1j%t;%|d7Rz|pEIC&oB<*LZt-07FWI zTv$kn*I``Nmo`GDD#S@bKw{&@aj7rYZx=iG$R?^Ee_u@(UPyqh?Ezu<{dga~8^`FD@Hb^VJHSE1{mPwu3tP1;Gr!#)#Sen{|SO&HEcNIz6)MbVb4V)+whB+Sz zL%x(`zn=h}{+QN{nTvxPdKq3Bu3-%#R08qJOZMAa;yIIYKRLwf`wylPa&=th{b@WE zuhfFE`9feO?^@p{_l~k_+wdFHk&5HAityFJQ+#-ou?uOBN4?h1- zPi{=vuOmjwJ&53(yUyr7mC}d1ak}2}mh(l~``N9LEbj`P#Jk|9U4e>vTKA(&a29zy zvbM_-4gz%u=Y9`;`~C4ho`a;E`<%?z38#ClWbHjY#!xE38c7$RyyW6+LE_J#Qm0~M z42F2Mu%x7}u%{xYn9mEg?h|NQx8OrLo+ z;8Y>hfC@`3mKH8ql3VA^%_$G+DI;5KxUgnh*K$v}J#d)2JQbemfFYRRg=5~US3B(! zf18t;Tf#I&+&&3}=@5zVS-=$1;b3hEtFN$r&MSp6mT*l|pvN1jd8KX2HYq1J?Z~Uf zj(p{#UE$(I){vEh*P08;`b*4|Wv0S@(|6^m7!hhcxtMI3DutS%(oI#J**L0l5A;5b zSx_@DNI%6XJC~G6TN^4=iX}dj#k{78&A=2yeZnw7wJzLj(5?%i9of2K8qsT^uV zYqXXIDB_{=AZO3$Uk#HJsMiedqDZZL0fXGvBQlr?w4p+eO#4YneeycO+BJ{tJBQc{ z($im!(WRr>hBg(sYj3D(M};}vHO*9-$mQG-J-@m**_eJNmq~KC-f%o_9uG@M>$;sx)@ZxToVA+nC=8P&(XC+W4h;?s2L)bYp=$HHnAEdC4%KpA1s#5_M>Bokngs<-SW0=a99=|2>p2n6G(vA9u@qgo=yWzvb$m6titN z=Lql*J+wa^Pr>oqfl>8wIPmMaksSSa9iEqLo5I!|LkeAxF8m(D>j7;qo9(Gu`FQehSwAl(9w z6}6jFxuWY>u3F3}QjL2{XjN4$%Y_)6i=q%>;(YqYFV3+w`MzfvnaM|#2N8Ig<@yv4 z6p$8&R^EnA(W`}ZX?eIRn4{=yKD2nrKvs-H`@U(VK(KE2j~_6((K|4(+wYH|C{PD1 zUhjW)w~-*Pp{N_Y4KdJ`XW$#+EX>{cCVh&wDqvuwFEyp?ASmZ={}Pwew=$;vsmfx7 zG)0GlS-5$65;R+1PI~}5yZ-1V7p_2)YUvNrQBl8uC*5US5*cFw3jjpnbDLuH-tfnd zNW~?+J;*O*(H|~BTL$x@Xs*t{yYt-4%%O=^)vt>rtn+g41P6Pmcv7pGX{6(3qlWd1 zxUtsZOLX`|#U!&Wy3qpW6?t~HJCE8&Y^K6|M7AVY{kZ19H|9bt^mj~W4Vd<$g~Oqx zILXmIDw-5BBP!i*zgnV;r<*b0EZTU@(@1?p9CqLdSQR)41UTdoKc3!pWQZzj|0N4`=^nYDj~59ciJL1j#C1Hy1My5wYcRWPH3= z^bm#f<$j;Y!>X>8Ba7>e-}*&x`sKNA0|NS!No>FAA~=WV!zD=PKqf@P#T5go2GgDw zmT;_MH_CVB{`&bd0QBM0&I=EKQpV%3jt%<v&fX9Y_Jo*N8st_GA9;Fq z_6X=Q&`$V=hGqjJMJADp6$%5WV4!5po>yB9`1;N*!K`kv({OnD$}!()uAhNF=FXx4 z=b||T;+7lm1;#Kee;H$Lj4orzNm;qlG0-fz7i7tWOk~rioQBmRnYvNr#_q%+N=I2j z-@B5!VbAJ`)7`Vox5u-(&}U^s*>s48L*RNl09PSXV%2;K@6kI2sRLEnoq(?c`?rRk zMIA|6IEj|R+rZ140GVTE<7u+YBC@$+o*PH8!>YKcCB?-cwS*9(^WdLeb3_HM)k?iX7eLc;Yy$GLl&YHB~6MY6K8){hg< zYZS36)WbI5g)o6^)P%LgW3+uandj@_c4jruoMP8G6YR4$nU#Uiv5+p3q8CHOUUo`o z|D+^E^NZ#*M2JT({QLJd`$GytrD->hjfJ^^qi7D^1E}ty6bEcnHwntViGW*~r+Itt z`Psn=;O7C4795$+=eQ{^sX3R->~@S{H)6_x*q6b51^r&pOl;QsWh9=sV)_F`@0Ios;Jq830*51~T^nQ@*@LyAI%IN|{T zl4CRES4hIprsmmmiaCykdm*1t1s`^r6B5&TdhlvN~OQdF(KI){hf_wfCKHf1pIIVQN z!<^!Y`H@8gzxSdc3#%uYis!z!dg7FZ8g-0OuZe9zg|(3HvSzn`H9D%bF=MZ=3S}f8 zvs6`~mZi0d8-7RA4fN}vz*hO!Vfb~pM6#fj#P-?5!cR-}t@{`l_N&Zub4*{29j?+z zRr*S_l9@R;-o;wPOyIzX0HPWcc@QCNb^R2nGSrdt-fBQLhP)EZh}?bmh$G`WFTpC0 zdHd(_Aog@!x>m7D&a}YW856Zc^?Ii3+&T#`;uBzDrL|F-K1y+w&klxhOTmbxeJFARCG{BDARXcdqJZE6v-b+E$crz`y&5h^${Jc&oF^u19EYU{9@>P zy__&a*CFh>?HN#JY+Fg3Okie4j z7Z~kiE4dAz1T+O}HVms`UAbJI+QR$1BVRb|<4v9;Fg3RDJUGrTl3K>>FmCU^3V%fP zKktRAoqi_w89oRAKWKym${vk)c&AD0Y@GK-K3^8+OdIQ{t9QVv5z!KZa|Ut4BC@+W zlwE%{Aek5%BIab7LEuLLF(4#Xz;pEl(yVM2f?u$CUAsdR8Fs$%Tr!>8yL{E6S9BLT zH|Kcb8R5|8MW&>L0O%XU?n`}7-E3;$*tdrz15`M~rEEkSk7z(;+UEZRhyS`sD9XN= z|1S6AHnXbx1U}z!jlQ~nyMUZ=E#N!!7NKJivv{paAb@_>y$ z(dD`HtHF2rtvJupm-gy_ch$|+NtqhMxPQy9c1tT+8B4nOwy$P`biJ0tkkW6pvAZsl zFet&o!kWd7Qi!73h-KEQj#_99wV!er;TdC0n??rS(DJT(-#$O?+2__W@`|ggE3gbZ z(8^889+@1;-i8<_9?U^DWV2vHz1Y40_{__G|3&X%8BZ)DE&XA)eyCW-GW5JUxA`F> z&-1!3Bq}N0#wBV`t%0FxI`lL8Z3wQ*D*DPRd9x`RfwfTB4;VddP2LPXFBx`+CL3WJ zazC>xsGLX7v^uhXjn%1dmE*5tTMJp`aEBxFxikRmqS@00HB_0ed2;v-{mcN6+d-QI zfk&|-SNrLKu6f`|}h9IN~9MiTKnz4DDU73?+r zNj3u`*HWt~br)OSR8zBFZ07K*m5e*RWA6FzQRmbjm$#q zhG5xZyQ@7+|BRP+{EwSbfg4ZAO=`U=r{eaoA>E6<;`m+IfPt7P z75lvRsY;-dc!q-7EJwUF4Et<=u6xi{4|YJuqOr7F$!X-2ai4e3#+78*zlf!?K=u@59&+!n5fmc zA`p-Wa6EL;|DbC#?n!Fzh^FUpJ*0(ch%vl9aBrHsW~_x%@2h^GaB#nWscuG-FjU=@ zCMOtst-k(2kcq43N8v_<`RNbA*z&t>A6baxb?M0m`$AlG3w|(h3ZG3|8qp%8V z7#PSVaeqsc^Ux{%N~QPdycRe9d$e5n>j&X-VY&#zi-^`bm-$h6O6<=BEW6D3d|7L@ zcmxe=z5iJ;a&rj}#76u7#v4Hglh;~ys-%<@%I1t#df}a_tQSuFPqTv}PMm;AOYR|i+sD%4^d(+#o2Yu`nG)=!_`j3jQj5WW)&%#LF1U5 zgIn)H3*lfv0!CYI65c++HkvhZepSYcin0`p6jN>#Y#bb0IR3L;2d{qklAbZ(VrNOm z&)du_?od72eOnL5>IYl=T&HOl8feHse=+o?9!_rFJ9@Z*-|cK(Gfp(e$-a5>b~(l( zGM9vhBA5{F)sBug;=zPVcJA+&9F8Uxm?_Z4xLgEl5^w&$YU{5Q$IU(1Uc3?&y^R?9 zo~2KZlHCA2eHnH=4c(RYpZSYxZp2gtj7jV5oxLAoI6( zc*F~P?Yg>$7Dz%9X^*QnH_}Jv-W_OoL5jBV)I2iMRv5AfgtyfmT_|2PuNT-4!GbN5tqdGMxZ(hCf5z&B_@i!bcB)8Bz z!X_9iR3>!LqbEHHe7N^Mb^bw!OEK2WRkI$2VQl?0wyWqPA>EJj4(5yTWA}4 z^;ucK&IP(n*##+PRXt!`Yh8QxnTL*()}1j=ivrEC3}gcs3%DLvy4J%6F%`@n z^r=hDI11%qIpJH6Q>v-a{W+EYM+*??4}rdjP@v1pOJa-1H7tfiO($viUix`C{+7sN zk6xDA!&Ezo-z5UB8Jdkw2HaB7U+UC6H}+VPwkK1SK~t21kGCeG*Z3>UH_w zGmeTms)XJrlVZo$`9^ry*t^{?W-6su)}$ztJp98sUzGjh;7p*fNykfh3Ws;UZ|%+X z1Frp#0Ns`uYe0S8dk^!T!2NjfBgf`Wvo9*quS57jNw-MrDMS&C(YWuEcw0INz}- z?U01z`krO^W##$q2KC5|%L#;Oq;8Nq^oy9XF5sit2;CXHl{#3Ud%R|Xw7NbKZQD(4 z^IKW?J7vbx5D`zzr3D?qVM-pY@M70qrf`*=DvFb`8pbOMOBkU*<&8;LvArEms+k%6 zT3qd!ny^gA&rlc^!GrfbJ9{HySeM3J;AnSP{gQ<+xP$)@2J^c6ysAavh`AHw$f5Au z2_Y;(K<7}@!K$cc+{p#_6(*p-ffDVck)z=d|;!yezypR zG=**O^H0f@z3tmd8k&!??RZ=%v$=JERZ?Y>`9fmxz>a5M|4R&05$WJa**s7k&T47))8nSCL;#Sp2AVP%X`1fuXHe6Rz^ixP0 z9jU&J%(oK&A&r7tZ&5GccaP${ z@xI|$tPA^QvLYeOr+czv75?8Bspc-?7QJWIIOk3QA4QmD#eQeu=*i%LfPt~&A0`#C zx3A6hA-#nEd^H0JL7Rc6=rK1@9xWsq>uo>|{Zl%+d!PQKVa32Hi0A_i+pvDiMu6~u zPBihHiUZ;m;hBTp8UA>4x^CkA!+s30TZc2?361O`lzE78FJiwAXDDq`2Vyz2 z+Mf}f-*#)AT*u7rjob|mIX#~S5AJyfRN2zxxkj9Wu3h^_mtI@h!QYZ2Q;HwJ<*CBM zWE%GO>)x7Ja`&~(_B45L(Hn{+GSfZoEB7bAI5mY#>B*^9%<|6eV2*dCJg!vtKIM0b zX-kPx59})c}=}g!=j~Ua!!Ub|5&ydzTx9#}F6*wZct0JKNJ zHUJRcz9U;OX5)#A7LP;_M1VkOQY0dvYv$p8iDZzL6UMWf$Y0UFmZFL92YKQ?#%!@_ z?IDrv@a2aW1d%X@Q1b6S$G!R4-Ic<08uz14z29<}%WM(DLE`MZYJ&iaAjnIYR^gNN z?3W{nALbEvUC>baNLaXt-F!HI-xkhrW1?Lh8^c{iE9I1OtJ>8a(Uk_UwgA(`el(@T129z?rQw- z3LU!a+LyH!N!G{vWR1GOP-& zX&VLs0RaV(kS;-_qy(e|1f)c|k#6Y@MI=PJL`nha?r!N2=?>`*5w_Gf`-%6tkMEC% zmp{DRo3&=moHawzF+BmLaB%JUhTSr^-o3UgSeze&e7Ng65|8I5L zk<-vmqnyWGOqwkHUYkJ1Undl^N_UDFC2AY7dX8zqsiG61pI#!C1k&rvxh(hqFeN7( z=e_U1wjg+D6)kHmE3|tG#KM1M zs-Y1xZIf;+F|?gzrXlPoOQ@FLNqOq>5hRb$qf-!n28TFsN{*4lk>8}^)z#Es66%Jf zJnZa>iKkmn^1rQm6j70Q>KALH7f(y5;x+Ee9ePLG*23Q1x8>s7D-C5q1!Gn&0vZ*a z=?^8W`@1EpXGuI4rrNgktoNYn>6azf!|`;g=Pcvap5I8fNi2x%Dt~)%x!CjO3luN= zji0m$RehJ(u4Nj&#Jh9#32<$Uxe}9!f5My->LniH}u)Fr!R!13&+b*Z>~~O z-8iB{vpC&{cWScUjYHVeV!uT>LP4O|Q(1nH+xNnKuj$+_sKLk=bn|nR==!57kFTHq zqMA|6zK^4Mxm5n?p-zi}F%`Xva;{+ea3PMz;z!?4?%rrW$X4`xeo%>c9h%+6R5WtX zuiUa?6Kyato5k_EfA+`RW~S_8*T0KyZsX#mxLMJkyptrFw=Rw&xR>0dZ$)A|J0u*m z1sPn(i)c5$!y|uEveajO|NiKwy=u1QZM?ru+xnE!f*i(+1U9QWXX`cOS~bO;3T>~( zg(D@~PKwLxFZrp?n~A(D{_tM8%Cg;$2s1LACST$2FsX8QWPW?X;QX#u_N>;D+$bB) zcghX_KqbM>#=1cfeLn92FSkEmwOX)J|CPPQExry;JoMe`LvVj{ zq`#9r*S1VZ?{U>W)*x7jmPAd}&W3Zx@S5y!@qAq<)`9UHqkp2Q?aDXesCDbR5Jghg zj&;%MDz$UxIr3JLZjKZ!7Y%7YK3vGxpWWdg1%ezmoY!6s;0zmxX?*w;lR$1AvO$a4D&}bI6^9tY9 z3iSr_1gLEX_oa<&B0I3?x_gqebn`LU?f8qV-QD|Mk&VOF3QwAPI}#Wz?Q`Z8i#|>9 zMKulk@b=u|t&q`bG-gxMW8)BK>pnGDA)1fZ*3Q&+vGS;_t84bm{2b5peV+T}ikyth z&)8FYDc^efh7ZK$@veEAnWG~HHOn$6g1#%$(o3o~_%WT`? zVeF|6$R-Oz%zaH5Hz~sm1>f;F#W6G)D2hk-9erPCu-Y@yj19;mqM;Pno`ds2XP+abj~jXJk6Qvxo)hZx|V%Ya<;TB zLn$1`7cV5gaN*`|>ykScQ{pLDo-M4TJ`sfYQ#o8=|0pw+o`q_0pIV*Ubslrp_{gO} z_gr|NV^%6DNq?6j%wLP|EKe5^n(=MklOG4Nl`*G!x6H(+%=bPFn?^>`H zrPZ3OXt2(EJ+aIi1Fvy#Eo;os_3d&bR%*X}+gTGMExG;hMkiV!`PMdOcjGMY!mU3o^@Ytk{tcbLk>ii&XFn|oRyl55`+nMJ3iIj|ZH>R> zbG`JDgW7Z}`NqHIlBmMIwAY;-rJpz#+Af`%47>7Xu%-?kt1NW8ytFyo=JmhAP~y5u z<)v`i{9;4%m@E7n^oS377w|n@&hjIR2R2Cs`$hCQ6wF>G7TGk3 zi+Zso{Amb|e7nYTXG?5(L{Ok{-}LS!eT~zcR>b<3!qbtlW{&GwHqUe1@oSNuGuk;z z>U&~24v+a7l5=YxpPjdKmZ}w(EQ$$5uzG~eNN00h4WGIj`%`c0Cn~A4QF&h{M{p^Y z*$pO{xP56AJih9j9CeuGzNXA_y9gJ!){i*;*R^l#Hg|REZmRYmcc^)2gzuBlXxPwU zYk7jxMZ1Rkg7zIUSFiI*=JOL)cA0d<&>4Ldvkh{y3oI@ILFprX&Svw=8(|N!lJ3qg zz6)yy1OZl8W@Tnd#u%y-x^Owr%P=evSORPl5y1ovIgHNs_Q*s+m~|e5^a#e(dzQE* z&Hb3@=!RU08^6BefE*t570?18fCnPlmlc08@3Eeu>vwq~gjk6IA>t7gh{1fMm3IYVMDNWn!1dJjg4*#H@kWA_9o ztlwkWIXG|vx1sB~`Td0euniLpY0J6*J;XSN$!Ed$#5`STrKeqZr7EG{pcb>atZA1t zduO?s=CtykM!x+0Wr29$xFF>~I)cjOMTS&h?~t;a1ukNDs}8i@#Qnq^`a6c9|7t+a z^yQ>pCpoHdY0T7mfV=UK`RhFA*D7(Gvc{wIY~mha;Lw7+m%m`mGIeHBd{Uud-`g?z zR>M9`M@)lMc>R1{xc)guVqP4@e3iSRsT~Eg*s{<()h54Sq+l>(&+SAv&H?BZM<9TZ z(7VOjNt^JN-&C)9KJ|MJ>gV?D0t-dVnUZRyK2Gr|=zpm@^QT0QPjuY4YEp`yGmAKX z`Nxc?S3epmox^g@Tj5_N!k?|e8|VhJVA#G7m2#qz~A-nx=Ov|->0l7bSat?qs626ypw)wWB9;T>GwHm=~SOy z;*ZG?dzJ(Cl3O)s_zlVNDONUiCAoqJ%#U&0@jmxVQ9C5PQ*7A^Y%XdE6H8ST)fdYt zx1;khejssGo6Iq8UUD&JiEFw2&d+8}e@#E37fnZy>tuIm>R?JPQ=N5<__%q};agu; zGR_y5^}##wT(zFJW3qfQ=>;58p3yxKmQtA%f@TpSHadVT;c3(#th^c>Rn6W_ zBcU6eDQjgpUSbxC>j@4Hwm&QIt^E`d0wW`cL zdIJM8Tpm6x2FX1@Lr9xYS2*S7Of?4}{99XA{{H?O@E^}J2%u8|wyY1<+D_Iu(1Qqr z8sH}6PBlo~Ly8(e`6#2P7{2`Drt2HO%Juj!7I%NrU86snsrn{yru9ZqnCm`8k9lE* zBYtbT#>a=HlxT~g)0L$5vE9L^yV>}Iy$PEHcnBu4}9A?*8w>ktL<`#C= z__kWMo79!Zi}-rFmO`?bZ4hCJRB5up0QNB8GXT|*Mfmga%Yssw=Ky)voGq9C_5gL< zNAw_@h#Dm%(a(T0x(mbxxL#pX=6i5nU=^$t&21UlYFn=Ut00c)xCT8NP#eE|J#;O6 zFnf)qDhB>5C7=ivyG`MSANP!D{v;zQ+x0|mm|u>3$b>}lh$iULQNg-}f*+}W(qFG zcz%OW;5@#dO2y~B4c=}j8u5(;W2W*n%ZEDiEyLfJ{yjAGZLcj(so(PtP~t}`YKUHv z?fF#a`7lM;kYLcpCp3Xe&|$%A-~M!imLYStU(P9O*z{Vu;Nt4eaqF8`q|^F?J4Dwj z%R|{teM!XT&uaE)ynIEZ%A3$aPA49H6~4qIUHbZ=AtpRQ`?mKd)8Yrwmp}1@8h>X# zH+!q?m_{!7HjUaB&+p2IYP}vu_+ZT=2=#g|forYoHG|%hz$hQ>`h?r1l&kGip%3q0 zK4M8t?KlYd_NmrS9+3zB&75240Q;kKW@$WA^VH1 zkNlpvZS>P}=;<80f)(wqI}fF-h_BpA>jR@Rq(=V*j+8b=s7hi^pO3zDu88$iK+Z5G zmyeeG8NOWGM4p@tlEC3WTChO73~OO)h8Afh@vBAAUT=?~3h~t(8xbS77hL{3VaG-) zF_FUy&>nEpfeQn0^f|B#n-j&PKY#!Xq(dCmdd9O?)`tZr zT*36iN{r(+>wpQ$Hvo`-)w{j%{IekrI)1o+z~~%;Qyfr$p~lmBIhc5$u~4soTp?~3 zSwZ19f`uf%fkG~~IHX%GfBKmk_`Uf?m( z=TY<+?oLfE4zOOC44IdB@y)!QKGKGRuT|>^xWNMkCMK3IWnYyX^U#=Xxj*aQ@(9Z7 zdrY?LnTnilPM?K}sTf$ZGOvZptNcz6Wq-A!Di@d&QQ6HS96ggWtHlavRBd^EA z@9EOVkT9(tr7?@c3xby(klgfxF(A%S>OKJ1ikYeLY;ECyMt~=hs90r*vS7@&aO+IztyMi`R0@j)b7iu+P0jhx!-1l7>rA+nwR~r{IWeAhZ-%Ok+voNS@Y`O`NLa%dh17XtthSV z^TX*u?Jw2)Vo5lNLUywAJ2bmpxs<$}ZJHi3A;X zEE5Gw`ZW2A2iyb6XmILh19!LtD00voosT~7jA}WDpXeXtWIq&4qBnQ+V5h}`w*}%) zuDhn0KmAI- z>4cz(eZ)w_C#1=idB$ze#JqjsZ^T}@Id@p5K7aZelk4S6DFhSW2xp6k{w3N|F4F;K ztB9*-OVq2RcGT>O7NchZcT6X3v;}ly4+JL*En~Jas^*#_e5i;HHMS>i>e`FS>Uxyx z=HO2Ut&@ZOhL(pX78bgtR&#+Yr?a~FVA`0jnAQMv1UF2kQBnZesI3~oqJ=nb{~g%j^DS7w@X3QK8!bkl8#<$^Zv5x#s^j6`Tne%&uUZ4>jqp} zlmt)h$4HDz*V6QYwc#!y<+4nQ$&16%)N0eyr2D3zbSOJI|ipACSk}F~1;aNF3-MLf~d6}Z;rb|$<^#rXB zRc!T-RoO2Ko~MyR+UUvhUweVOcFp%=-^(4g7(KCxPYX>?8$Eut@1?}3QYmz{`hmjD zX9KiUov)CvL5FEn#2K0l;iwzg4`kVSyQ8>^8)v;iCZr06MyAguu!1 z^Suec&k6I#dh1-aW4%~JGgiz~>L@spm&mEay(I2ShcfI={WH21F@?2@A3iwvt8-$6 zIc$pj_DgNmmZ5XsZ-0W;NjH8=&qksSz9J{N8-V*k&~EtV>?ggO5*L@jDGyyM_b<5& zIUZxUqiqaFPQ-9+Tdt7T1-+b~)XTIC6nW>{+WxjU;?C&!MlU}kYaP@F_}TU{3hG>} zMq2kQkBuJlvam~@-F4X(nwJ-B3sp%q)A{bbY2@jQlleC&#l*TNX!7IKNh8tIq>cGk zzw5pU8|xdisLq>i6$~-Ekcr;BxK3+yx)YIJw{T`o7>O<+)BOyK>@$OfCVuzLTJoRn zArEQnc(u3i3T%G}>Ra1d>-ee-f7Jf*iY2}B-tez`%96A)^a(N#P(M8AHAP)r>$DF+ ze`n(7XEV6cKgC@i%BbtSu-+3hmBPLL#N5nv{y6nCX(@eS%G}BIw?VUhcFN>wkTJTn zF2y0mT1jD@pcoCl(wa;0L33{wXZ>1?i}%I8PIuT&!q}VaBZ`8Gyg^pM6 zc4R7H{Yx;LAiL15z(A+K;6bvzWI4sl9TRc6ocCUTHd>)7pAAR&jus$_G)vR9&~U2m z8NEo%Xooh{1AMgfd7m@hkq#|u-+NIC0w%)Zi9WC#ojp}tK?Bd1V;$fg}1yOgBOv?Lu zi=bSI{p8TVA4(!S6~MaNTNbUQ#$9Z!Y2B1zW5k9S`vRK1Muz_^>3F*5G~J zlTaaOw>@CQU^5NDW~>Z5@|`m$c&sYMS4$%iX-Zcp1`S8IL*9`V6*mevUGpuazdg&& zQc_T;)U~eTOiz`l+*`sQ^p|Rkn3}s5Ia@^Q3qalQ8Fx9UB+suaH9W0<2>*5n6V<5C5p;*#$m9QM0jSp!%~MN-CRVWJ5W1sdV_HSR z;xv$j86fZ6yHZB#wKe%tcJ1O~(MdcQOOkrahRtL$>>LbDUwUm_`ZxEm?W&Wer?u@G zPt=bE9rQx#x`$p0+~HI=I^=pr;P%h(rkkKVqK)e>pRY!9ZtSmt5L|wyh&8-+BI)#U z7OiYbvsQ_SGJZ>*>Q4ht5B0a&zOl7Zb9sH=*CwdQ&SA)TyGMI@UwLH{eUCQBMiE{A z6PFU7_}KB@!|mL3UhxMfcMBx{oue;Qcu6at#@uyq-kA+)VdO}&G(P_^T&qO=l+PXE zt|RT}_2+BQS)XtWyDVGlUYb~N-=g%;#RuyBYwl)W(YzN*ujHTp8eyx688#h z?U2Cy{_1i;N;Mce`i*+&#(T0~H*eGOnG{eZc~+C#-}cEdSvog((!_x|d3i-Q&JQ_h zi>g1z1jmcnCW{sLmwaQAZCtV0z8#!xD*3(8)+R#+=6?&Kva0e94GpDd_YjS8;2Jy8 zOs}c=3=#3qzZ;EFlWbGgFhET?;sFks#K4=Ap;#s} zr%0ZX_EE6HiKohOLIe?dx@Kx|v`1ZC@G;$to_pgwzUdx#6KBKks7d<51xuE0=6qUI}6X>v*Y#Xxeq$06r3=vCe8 z;F`RRpk!bKSUoFeHEP;l>7a+S+q}Wlj*)C zQ}=`cA%jUangQV-rK^Ci(nmTiMuv|{grE6dqY&d)lxSk@Fv$pYNky%@`*-|#xOmd} zuODU0W{Y`#7K5VYvgMJ#IQjx+76C55JKJ#73eyAaVXr?A9rLbxghkWZ$oJXJ4%0uV zzPP%Po$Q1|ID`nCcyqsfcjzkAErE5Z(NAf;XF@&bj@ha3JNn(bjG}IogT>nnuj}9c zrKei@pi_6W)YvYtKD}_*M*fD=Z%;n8$&2AVds?SPJL6$niaEjH?(!&Y^XuspEpL_l z7i(zVjjQzW4c8+3a(>r^XB4~MEqAbc)*TQZWMh@C?%x^w+?9Sxay(y#_gRnBjZ9@13pl z-J5qIL=*-uBSt7Zl6yZ?&pk^k96Bt=9y(Uv6w10dBVb-o%eQ8WrGPvtESRhSs zdZNc^2WHiGxlQ)h*mSBj3%HN|-Fz>>dk-B8SM(Fw0mc(34Kg=3h$ceW!WK?GZeyS? zCb~(Us9)?|l#o#d zo{gFG&h}`06eHG7uQGP6j5Y}x8(7rjDp{c|D(={`q6tE}_?1(H zH}MT+`I?-LqGDx_0xFIzwj%2(>G7gs9}(*PhU42Hg5hiYf-&0SS7$8Mj73)jiV!Jd|d(>{oNN>g6XdcRcf}?c1Ubvw(H;e2Yh19H4MQw7t#DBkEUAC{lzaCpX^1%u3L&R zw;KA3Vtjm?{kFJmROLr)n5p-y<~;RVowuSRTvZfISc>=0$miW1C{jc(=qL0%X{8e8 z+M4hD{oRJD_nyHrpKA7MUrN65NOj)Ngd&5z27hQECQ+v}2H*FO7d9p(`xU*Co>yI* zvx9S{#f$rW*PQQW3(L<2&Zr%x)T$3U+UW0H?b)g~x$t=qG_p@~ZD$Xz!I@w`$E|b!%pD!ei zRawaI3vI*`#2qg4zm(4B2d_U$>;Bjm?OodAyZV9V^Im%&<=yjrgRav2YWftG?1A4y z^j02-b^7~=Pz?e8ErB(K#^mtZK8?ng(`}d2SkhpfR63h!7}>1UH;8ZW@*`~mJRQ-x`8;Pd-W8gf)dJjQcrKWO` z&byX>E$hdLo2Xa+CYp~+V#{vh)V#}K&;z6%*?X%f~#nT_`qF=;`S)F-_=E=w}~LG zhu~eV>$rDAjo21tE%;WeFB`>w`$->2K%?OOOXkIT*Lr!LZ`>+r&>zv$Eh^n7hCEFQ zNdw>KmZoosuX>&C&9NDG?z-yu-|(F|SEw=G2TTdDe2YBGjNI+vc;+JnJ7UgxL;-Mz zpd8<3+ve`B5cAJxiW*9l1~3%&^zfB@A>Wy$YP+dPQ6M! z_(IgR36iORVRX6}PWUK&oQ^(_?xIkvr&k-*saoTdLxrP2cn88tkfQy8SK;gt`!}K@ z8jQr)7WS%DV6_co@T|iBB*J}{Lcyo~Qk@(3J+feSQTyp8RcoIjEg~?=+fE(T+&-Oq z<9keg6PL6FY)b=ND?JgM#+{#CDUJ?di~ft@b;6 zW8EM*_Syi@UM<=4+w5~9QP8c?-1z+;l@Ho?U7ZdVTXXijz^y3N!P7+u_Bf^r%~g}m zk3=k_LKX*yMV+U2`!rb1K@;3nPqrWjf>XNjYPPqU%~iNYm(yIqC)Rz2;8lb#X5t>7 zkGWKN-e(K!3y537dM*sOPUHQWEP?Y=I9JmoLDYA}&war5%?V89^|<=|r$4e^lM)ks zw(&XyH?%UCvLKl#Cohi<{I`&>;RxD!M#W?q7#3BsDsUt&baPPRD26~U+-t!biV7!^9zrGp94{|*r#2=e!j*b<4K`BU2dLcEr+$0)#FcJze|ED`Uhi6bW;?~gQdc~2YPQ=4(rdkaKt7*Wx0!`n3elcwQ^x~D9`qJ&9=NW zZr;q(vR7Bd)=A0D-pSqBU%$4fHs%|vUG6d@fYMx0PH@K;b7L>Xb)AQzCpj%`2p~P% z{RyiD+qt^2yXD4h0oZF*gGLIPPq99c^M&6LIcr&#D2Qk7%E$M(^~w>vCGm@X%THCm z38sBLJ-7+6E`}h_j2FVqU=Gf#dG6wXsoK4od&`mca=W;B5PS&|gV~>3qK<)&OM39o zFmth{fwd3|(~l&4-a$}c1ckuev@(W9@D{^a0lf0Qh&Mmr5%3-!!2K(CKQsbKZ-;4u zULaJhH-6{j$k2|w{30WeH_alY1>lQoI2qT0$p?u~7d8E}dLbw00sjJIIv>=#)pgNp z0pI2{{YKA2$gz0&@+FvO&{)^iB4xHh%U+-akPnsR_3xiTb@Rrtw82yxX2rZwaP>&$ z`KquzvBRZ*;JY|56RlySW4u&(%f})h|CSXHlsdcv&pV33K^ZxUY-?4^$J4(rWafJ%B{9 zECn$Ta>*?8Wc~tYkmX!mb%A#HI4wM*7xvuk!IB!oR7*N~Esh`eI!aa@N40B(U~|xO&D`8>J^QF3$>o z2*_OIGu9aNcFak)Do(4!5EUX3P|OZQYbl|fU8_nCn%EA@i|FWhJ6&z0`|(M>{_4~2 zRomH`sEUe;NY{A?>p{`=SdEJhK|xR%@rl#!QMTEGQ8YxhtGT{6yBlywz!4(;R*MRqsv|i|Og5 zSf-$gyHv?r-11w&CS?2^P}jiq?8C%1p7QIhdq=*_qAUNN;I_Xasc-S5<5+4etk-uo zp7?zjfESq^&LYtAwa$Q#cqiEK{xYe{Y&THOYTc6I@RSr=)i2yZ=6NZliNrgmH|jf| zj1nw43c^pps&t58H>&TCyO4aUkbueea3OtDM-BZC^n(+&)pLPezh6TT5Ut3lBc8T3C9YVZ4IdHTIjyHH{GKo<| z@R%$?kNQnFho`8d{O8B0%?rh9E|ut`rCetHqdr z#~v$D(i_l~rFkD=qkx(d=?(?3rwl6E)!*vo;c|1OK-~Ln!l$$CepkoTMRi+`9G#rN zfE6S=-6NOO`T`3pfd0>Df{TN$mG)21XN+N{&$JlROi#GbdrSo^46BRg>}P#HpFQU- z$2!xXJc~XFOYIBq-2c|2PCrk;@cqLtt;n9+{;24y`!p80!&bU1PkF|D;KwoT+MC*! z_eE*%Jp>;nJvs)RhE<&3R^=OM&&@qH=vlz75yKkyTDoI%%TObH(Cf^CXdYj+`hBIS zi*dK&cPqXt=ggEBnbVaj>i*k%b9U9_*&~*;JLtf)vY{8{Y2r%je!PT936?uNb=$Ma z3$wPiWV?Hc`mUGOd`TIoFs+GsnVApy3 zcD!ktRLABpa=zODe?zlni~Yvp)(hq|gQ@A)U?gXhWlbd+mNyF-I;vzkB0^yCmTNc7 ztt9PHeVg`mZ`3bO8$EwkW1ghF2S2EnoUr~2XOqKM8rxsr?mZc+s$LYn-LwCzJ@7jd z9-QF<&#WgTzA{$G2B_4-DKhxz{L%)BvDR@leW;6m5SMpYUr_{~Gl#M$IxgkYQHI1M zmJI_2*g^lrB!;Fo;G>-H)E|U5d_Co$(YI?tnBlZCs+vO_2aLf`;KBX@os00=-F4{Z z47*);X}q~m4j)_<()jCON{>=3OueGQ3?_eu7$8tuQmczh~~`Pi0w)HR5n z)`T28kstEko`4O%<@e!ZFe64@ZdDf3%e9NEPi}2JT+biZ1N=_#NK4vZvP>8XU5PvG z3}t@wZ&#OubD05&zrt!guS$0T4{Wwb=rg^W@kdqN3dl_=Mqt+bu51&BfK<;Ot{^+V4=S3;7TMXFmeBx9yt= zBxg+g$M*yt#d;~v>^JZvAVp|2Xp))?gw8z<`!UJN9q5< z+c&#^dM)YA`_# z00m`aBDeXMO|O%!A8>>rz;qD~%qm34Py3RP~?1vTbG>#%D737H|Tb>s8LUT zXkvP#y(We82G$PSksuXrw3QRvSCzJVYxH}6+bgy-hN@c3^2o-2(HD{AZ)+@}c*>xc zl?+;-P=qsv;#nLyxboQbol}Ux0N4>>jbS)#)@_R;y*ACv_hTK348Y$Mfp@6wqBZLN z+=#l+`eDArSwOFwUYj;Krcor3Np#;)+oPb{hrx#1+4OlCb`))lsB0DV(Mp&ewTY=| zsreAqv8H&_)?l&TB1df+MlHi=qE)1pc=tbV5hyx`o{iw&`|bP`R2inhY2{>p6lvgr z28BszafP-)ZG_3Sx$>P1W!c<+yC0p)eu%-G($RxH?03VJ_%T=Q-l03_%Zx`|?;8nH zY(Cs7q8HdzJsWn{>60uKdTr=t5E;@74p6nw(wo8~<|IwZ8VSlN_~QmP(Hj-IDDzdzxxa z;KW^s)u3s%LP`Zvu~H4Ck3!coiu5ZhD3q# z_yo4YUKr0nIv?~v=IbrNUoRU)YjoL1o=61AoW@vOB#0M>hdqyCt_s2QV5vn0X0bKm5ov#l$I{o5>i|Je&(M{c!F>LG$re!s{FmU zgoNLx=iq2I0T2c(xuOh8MDV)|$U2aWdNiTI*gYy{O~{?=MzSMzKaY=zOG^fo&p;I;CMUfQnH|VZh=A>zvpUnW$A+YVrrvqC{y^e@(<_Mz zm5B+Mks;jjvkMVJeo5@hV!;#lxyi`BP0(0_3Ua!FPJxF|r_QVJ%n!13Q4cPThu{L( z`qAfZxg#!uyi%tX82@8J!+-yYFy5kyzFIM};e&>u6LKLj*v1V>Z$jH_UF8jZ8Fk#& zzDdXFiPXAgR6l+Lv2)*8gjxDJ#QH2kHavF(vVAvCb_lerj)I^R09s^$*n;dvE`vXP zeSK4qd4}H*Pvv{|`uICIf_{d*79@%fKPZiqn$m*YO2U%6-8Z-pHtS2c;=E4VecK^& zZw#$rfG1<)K(A$$G0EJ$X-KZXPqLvIz57%m4pEg_pq_F zWCpf7!+a>UYKXw&Lu3J06@3o+$|ZD%({C;6e2H(V&7H;2Zn0eD6RM?CoHRg6uco?@ z7{F5$^a)QdaZ6xa zSZT~SV(nD?KOQ4dA$}O`$@%Bw`0qQw?0gL8iBC?ydcju^8WHHqr{b~xJ+X(Q`&~^g z`jnIBPWXc!*8j$+#QQ>>A)Q{8p|gI!sW0v74-3Of&mb0b@qCONy$rmw^V!hniCz$BNB__4Fh>2R; z2o^nfP#9m4wf)9vvdjgidcl(%U`VY>E49&ya>`+ggeqvL)<}^du^H^rjERu{&<5Ug zTcQE3FWd9ZJcyb(I|${dfkbb_;`=)wVpEbd&3#MO!uIQPOvr$Y@$~OQm=`-Ch~}#T zF!LQCF04dg`Li=K_q@vX_rC#|oX@r%ZPAM|Ns9P3FGODf1#ATIRSk%>Br{*Dv<=lp ztHipiy9=AYrdJ8EmoM^O4k5LS5DLKsS%*58|CNcSc! zjtGeP^ounFi8FfIALD{Y7nv3gTiLO_B7$8hwhtzaBOD-eJjmNXRn_F?cN~qZf2?_f49e`diNLs zkx=U}ZKJSulu^to;rEtJYt7j`#Ii>oo;?kvw_lI=Z=Y4XhHZsfHnt22A26Ov{9ed@ z*D3ZEJ#OfyB){O>+0I>*moQGLiy7*&RKZ%Dq;G;OVqijNV*EqBnjT%cDoEt)nYGbd9s>^&-E*xDotmL*~A>-QL^_ z&<4SJZb^IyzxWlnNG)fWvro=1<3;XfmQ3F%V=61)8Gw&iP|zRk3y%_X+^w_Yw8Fx| zE4n!@mGp_IRxnA~M)gRgnWewLjCwB3h2yU~DE;8>n0H&4!W7+#MaY4@I(1ZM>BuI? z_<{hgo}J}57nK$yV5$P_z-ITv#4T((cf@7YONdGir4CLhActMQBSh`OHBO!qu5NZl z=8V7r(X6zJLo~dcVUQTr!2h{?pP@Ilm@@G!zUwA>mw8PHVQurM$O{DpUR!R}jiXPl z(WhUmi&{6Gk(=jGTfJN%65(qzU#<(l<{(fwz5=lgt8r_%z50F}(^Ie#I5*@UGSNv z`3VJTeo#40@{jerz)E6rysqf+ET15oq;FMIw_W8HcDrA_D{lJNTQMBD@AA|O`=rSQ zbUaqFM3htCqP^;DiJmsA-*-&q!e$WZ^T2UbNl4f-&Rb)X5K*UK>TD>XpL`Pb`l}fpcbVp5JjVW+0l5qu!cvsFOP^k^%KSEX zz$^7t!NFjEvXmYgnd-|zn$EA@VL7cyq8A4e$aF~vQ?^0q=Nw>+I?*!T>~NAE)zCGE zv_3O?sgr2}ME<&N)Afh)G5+IzZkSlYS5H67=e=)i49Q8lP3`lC079x`6DOb@l=pMG ze{}f<#;mndaFI`kJVcaly)Kd?|9{{!j8a@ilE>8@Q2VA>5il<#-r`JbIWK~a50`@f zv82!Vtck1KqDhXi({K0a{zn}+b^n&x56aUnKLJtz+iqIm%l!Pr_Din&-OOM>s<>oX z*Nbyx!Zjb=64uQL%{a8o-D)y^|0}!c=Zjk&PuMHecwIr z7_5-Mi+3+M7VKZjG75+x6+rYRc{@kcO zt{Pu0tP*FeSn)Z!)XfRPYyat~LH_*bxD*MG0^|6qC)W2I8UomG!1_p{v{x+i)Uy$k z1d#J@MEkv+pn7={@~Li!4_!m-WXwwdA0Po+8L|k$lR{;rLo;#b3)V2?PFbOK=iZuz ztUm6@B?vYtj3BFP_RF=;vt4GrtAbU;+> zjARvAynWg!Sq3w-v*v`|fXYI8XBhURKasvpT!Fd(aQ`lP_C-no*I&;@T++vHksSQ= zlRl5o5S&W8I-w{Gs z`SBRkZk~UzL}rl9+b&Lj65mjN1~6;1yU=jQpMR6ry~g)T`tg6Hh5eskf`I@gV(q)Y zR~f-JpEWrJr<){y&M)C93u+*pZseiN7b#)sDhgki5DVmjaNnQH4CNaJYO7gt8T3y~ zbiH;fkt`MpRNCLrL9Q}U3cB*3`R4{`11kpjm*of}pyIL$3V1M^LsvIPk^NLH|Ak}# zJ&Q|6%-PPNd(QlE9OCj{-pN`Ojg#q-);#e!`K=o~CQnNIBp(NVqlv|sYN(82*rUx& zMC0+ihhgY)`6$$L3iVGc*1BDo)tWl`SpNlWp=2R~?-h+-kgXglOp( z-n37l<{&^&qH@U`u1pl}DjA>i#?CAm#|UFe$Mbo_u*4$u^(Uxh~!bU1MgICX(J4m-etqs3Nj4@bypV+?=AN z1M~J02=)Zf$6Io&Qb9-hX-kBWW+8Oejt|V3+NJNcnFuzNcVdo_k?F`R@rrdVdB)t` zyM(g;$#vo1=1fQMrz2ZOoWC%vW_ZeeBtF8C;z3Zc%!Jy@nYjdy4=$NV0h8+6-26k< z?C=>|^TUtdH~me3Q|3Lb)h!BsA%1vQAMP6fPbLtk%NYe{cjWY>;dqcc&ItIeCu}I- zF_DPPe%dCLeRfNFI@p`+2A;RtrCPA3))nj|Fw&Xd--?#YZ$i~R&FAYe#e%_zLTk-j zoQ@CWP>dx=t#wuc>?H()IuCe{qZ|rZS8;&Gxxw=4ZJqr}xsp~9I}5Mq)tT`Vn@KS^ zI&7=mtDy}5Ozdqj@omO>s8lJ3Le$wK7A^r^~ zW|mf$zOf&bR@uw^hj%HJHW%B`-PtLSFk!`efWt+MuJDba(zqTyu<1 zx|HuDlRLU&d(yE?5qd7(!8}%alGj6@Ion@})>j2z);Unw?QDgQg?R~bor2cR3??w; zIQle=xIY@hKzq*on_~XkKGwQ@0{yN8WLxt?bdXlHUCM)vbobjK*ysYHF43ktlcg6& z3C$))D?JVWw(_gizr%2!x#!pf5AVC3W5gN!&8(7jHgfb^xm6nM5`4@Lj<#X-EzE?R zBY+8lZkiRbH5i)QY|{k`N?w=Z5v)sBc)_F$#~e+;%Dz--@(e3&|8;wyR_C`lVFenq z2;%>Ek9f{n2?yYS3E7FJ!eTFzo2a9REguprsovp7aTy-6cGwsAv3-wVfeEU1tVw)A z;kmcS*47rQaXKWFFz8j;%~@%+714XTybKXtDt!uh%K+Gc>H)GfIqhcoaoZPxXyCeh z1!Lq3aA~k7^c@|s^+I}Qg-`8-?abK3`f*fBOgjL;65gNb5nO#%Yn6xk%jM+VVcVuR zk5$I{xt6>Go{O%D5h7SI@$TiBThJxzpq@m3@#q_8OO6^zL8i>v2(MQ4zU*NUie$3h13&Tzp-g??!E<;zrW)0j%DOWi6k&#s$@D_*mdzQVpMKdMqF;S@Ey zRYTOZg=Hdu_4PKLfkR=QM{o#v;sueVB+au#T|ysLOiCQ-pX7n!@EHKi2P|fxUqV>D zO5kUTQ>7C6H>RVzK7Upd478`=u8NuIS$Ed2S(SXd@jEUtNOW7~8@)VWM*wTr$GRR= ziysUhgv3!EJFUs97iyd4zV{q7#b_v^h{}HY&Wbd!_Lc;@%56iee{b`S-VoQzGDmb7 zUl9{pBJoyh7eMLa>jLUep&0EoU;E;e?zq-VFe*5osLUL}NLh~LfEAL=a@}}DHn_qk z_J91}Ttup9!y`ECU3Ph(YVa_e2r>hI{5w(D>VW|=NY=+0pJQbUM~A1x%fUvr2Fk@> ztOY($-2=X(quT>9>TgFjD{}7dc1nWQ0*Gzs;UPn@X@ud!(7G}7xIkpU!h@VbWM&&1 zyzEP^^_;lvs(N@7{E+}J;Sj9I_7|b0ckUVg?tM#ga@jDo!JG6l6qy zm2K45zafLgleZnOhD5K0;9uvp-v~?0spvs~1jDs-k{eHJuk%URy?{r$=eshHH&3Y$ zS#57RHKyUsQPgNp=tqbDRgY4VhP#q|x!Goc7K@j%Hh+y{MkAp74gMywz4ZLMV@d0P z*N%nl%(%sHp^qVulX?zJ^#|Q*@Ws}G`=@~qWlb{nZAzR(&E=zSY&0>BOP$GeO4VF6 z6e}WQxrX!vVMhKPc4g1qgl7;D`NqnOr!FqTVVD+mRjU`^la-N|H|dRKX4R?ckB*SP z7kWhw%MrjtW%gC}9XMFgT9O+o-XA(e2E zl!SCEDcv9?4blxN-Q7PLk&y20?v_UB?(UZEu4i-a|Gs$MIO>cudOT;rM?8RBG zKo~+6IUkPT^eQn`~WB`nG zNgPjvxYH#>Q*?-(a%%51a>~ofrfFR%G(7zMQtvbit`8?WI2UbTM-7rQlmA8caSJW> z|CyUKSAoQ}1WpMks*IcQD*H}v*;U$YNlgfJfFm+3&FTpEFlGP<=2?-;=jZ1mocge2 z00E0y=$~DKdc{{CeB)20;h(tZFdB|vcwi2FQ5ZkQ-iYgOWqIP75*GS5mNcWyeCC$d zsgTgo*&N|{wsl?j_!?9tGW(RaC7J6E5@OAoof>|s$wDaot9EIsH!_*+r|Nm)&GIn6sP*7ON z%zq}Q41Buk|W9^ zzzOw|8U!#CMyXxn?i!IFmbL$3NZYl!+x3^-*Eyr;al6-htM)i=ntxd~WP#$Lnu zzG{~d#{m->2=T0pl{V8|_YP;|Ah?~(GlJ-s^D5{5Va$Xmd5eUa8Tqie=npb94t1I)~%sRIratT;qtUUCAE{b}NvX|v8xnOF2&C5AExpaK3RVG_GpIcTotcVCczbp$? zn(tlUz;N8|jP(AJRWwuJR{AdBTU5Z_6Fdq|0$iqy3-}=C(!6--Fz{)a^Xurix#uWt zw$7PI@}rK-mZo?_llV}@edl!+%)W3pH5>Y}E$&g)5(%p?g=_K7!kfXnT+JE3kXXa{ z&Lny_19b$}Tho)0g2D0L8$kxPc#nK4lBz%qTB-MQ{A64z*duTL5%y%Lv~UjO&vxZh*|jEE-E69$d7*#y9I(` zJilVxFR53cZi z*}P~;2k4@jiP)IIBHV!qDQz-wApBU8-a6@cd;SzoZ}cx)>9G zag$A6oONa=g}>Ja4;U=fKU&VS0aEe+n79brvrP)*kXvz?d4MXmXarYgSwy(MLtW9=X)H_mSl z9C$te(deE4nAtG+&iI72?|n4Ifnmb>RRCdGNBRhb_w$zbBYBaxvCn9i;Q#enHsfoE zZ(rMhn!Bgz)u&MoebAsor2rhWLb34Qmc^h)a2@|gq_c-Fat?e{cx@{yS*?RCo45w4 znw6jiptS0gF2Iwnn#m>71q2>+v2S2*EeW%a4FO$xPIGe#m`j4TWoT>FcM*rS3kY)7o9_#Oys!MwjaBIeIo|YOD5!&f=SpK9ihJQ#sd|aOgVcB4zY9mL883qpASCZ`s-jjr82}DVAjr1mNwrvM)!83l z++hXDYxd~_TP%Ge;>50`K;z}nwc^SbN&G*_=?Q76DK~EzS5SbE6+LrB) zfWKNakTI~}8z9~;0&@7&i^Vi5>U$V>tbd)-4hoPpjHdMdpw9g*GrE6NEshn#y=d)6 z!Up3R_q0p%`d^aFdSR-K4&;rsMFqkc|IMzsOmhJuk-RKr!~UnT)T&=*iNE+N(q@ht zVwUkGYa}Hy&7Z$NRji_f1wLN#s$cXJbMdk!`gbZu|_>C^t3MVlv$lxcxT4olvzn|l32N;p-Q5fBIiE0gs=p~vw$e;bSaSVa)c zh^ffE`OXfYp%?(6L_T&Ykgi_qEmnoSr>^szfIdn9zH@&Ys}*^^wxW^?-evLG+O)zS!d% zYuDrz9aoOT!-dg29o)NLjp>{MC?0x6*Iu21#Kb*ak5#)dd+Wrz-I&bbNNr?c+uCA( z-vpZoU?{))%dxTclLX-_P$7I%6h~~(0Xh_%A3JZ5Y0g4MDv_S@|1#nc!1W9Q1)a=# z_s;o?=*phHkSTkO6iZgOoYVg`Cess;RZx+UL7R{Vi`h`eCV-gZki z0|db06ZU_6J?|_5y_$u>RAuQWC4iz*`Gs{S6ii$^FlGl4FHvOefF6$R>6mzCK$&$w zYTFXJc%;fNLni>X02Ly+UDY}%S%=SW=biu*;R9!ms&8l=D8q?1&+{lG3?UDvJwRYw z)^eo@1%UsVLrQ9TyqH??swzFf7i(qCybGw`lD~15IU0VJZvA(sT9%!fUi!s%K^Cc3 z`VfAOc05FIP5@XQe*Qwa<-ww~14};818Dj-g8UZY=3-M&mw)#3Y~9k(k5@fH5rPYL zSPOgv{sKsA#+w?Mb#Z%nOwW<8RK8;T1_e?NHljAak-1{kRVI4%X`|As?@~*`YAM{r zc(?k3vt6k{i3yC}#fK{roA%(*+*<5|a45s|PR4RTderFt3)Db*Ks8f4<6QxPE_QBf zc9Zr*>)X*S^DCJj9vVWel!;u(D{kV$$UBM`e3|fBWSCw)(RcxE6Db%1ya;{CE;02b z&_|r2kwA`LeN1k00(!)8-`aQ=I_kUGhZ%Fc%i^~w0&8MYy7z*^<*t$D;?KcVm`_(B!;q79ld|;IT!rSQ^y?$yKaShc&fPyv>cLqj}2q^$tlO5hI!pb&1Z%9 zI9T-O^bxOXivu&Ty&9c1J@<%7mU5kU$E(+H-7LAwhh=WO31+^zLORgsx9-vIxIo1y zX!*o`yrk6LUYz#bF`xNikEz<_aq7dO(=Z0kgBjeTIRDT)lxnQi_9Wxqd%-=0T3 zrv^ID^e^|L@&d}jK6Hk#20N-}u)6b_KlFxd7s+*WrgX#rx z9u8@KXWYS;H5`0XP0)7mexyq`P;Qe>Xs*MGUpyy#cDr^wI#{6X=Ocd(2n3&b$gKVb zp2)1x18^K6_%g{3;eQeHFnwxWYl7S7(M4|^WFUGtUid^^5A01tPbwn@pj zz}5yZQtP14s=bRn$M&K+CmBmqe>=rs#uVU zb$;Z23==U^-{lMk_MPMniE77*4*OD@X2<{M$lY=(SFt$47 zGk7NvOkhj&<~9jXBVvhUXzp1TFvKH~e62SkOL$eOegKV!EQmmqaV%;UOdSQ_#vwx^Ew_V;Da zRH^o-c=iJAn#`q_!Dy?#j>s$#=FEQt;94v^ndI5_`f)v%&z_3QTa#X$~wJ86$bP z35trc-cU`?mo&PI>)Y{6@@x4NA@4m;-lnxSvL8S0mMarNqm^$T!t?eL2?n`~zsZsJ zB;$PCB_1x<>+%vT`9VQ)dc9lx&*l(Irr{gc(Sxw(-HtKd@k5{~Q=E9Nrn%E3RG;@v zkQT}!vIBw~JR_Vy)OZ^#CHe&=&JE3I$ZB{dt2bvXi!MBi&orDRrxi5Z91avQlpVo< zIqU_(Q|V?U@^4HDvVuH;H|XE(nLZ|E%+Dh~yq*Xa_o7$}|irn`_%9C*{xT+KwHVC)yoVEa&v}M8>dtuk9eT5lq*kobKzb?ci=j zFBKA5YSKhRIWknY^7U$Mj7#7>z1D)?z&>GpjDo`~PqCz3g>irC(X(dEvYx@7PfL;; z386XD#D<%d4DyEz3)*u#V?PJv-XC0c+%J1XB&W^Ew27}6&k52nul2+;&)f4m3!bBG zJvTg&wl;P5Vb3+zj)g0yJT+eOe}QS-M^aU2>#or^(hvNm-9l|qv8Co_M8ehc=7 z!!k^QaP9+@p{ODzfTA#sgAE+W@_m8DFx+o_(&3pcJQYn`3;dc|q_~VL$y`Jy7!_U< zb`nQ+-xHw3`wB>bA3VK!&)k^%vQZe{_hZk*Bv}JY<511{&d8e&Njla{1rAqoD-s1u2?>r?(5*OlP$%fT9X$P0q?Q`>D>$k|0Ush5d-Gd=^|u zxq#cJFI~rmu>!(;HOBj;AhismY&cWxZeZlH?QAzHqv47=y$Zm65>Jfpm|P;AK{gW* zzLada+wvFdD?N|^AWpzHVAip83&4H*_D94)R4r?Dfv2`HV!mq0L)K7)re{#!oA(EWQ4&SDvGw5b5upaz{?zGnKJ|jX! zPnWzdap7p;3}5Bd@#ZICG}eJwBW%$Kb?9Cl_-)ppCG4kT-i;p9BkDn_RGVTNx+)2| z;Iu_Yc@KKvJQ7IYpTr^{EfE=rm1y=p`#xmte7>|_9jP1yKBC@0-3afE+QQlS!}c zb2S{>kt)VTwo6N#wp%W-dn22c9p@M?tlN`lw9?_tooAO=Tg3El2TZ#4m4tHxyiBd# zJNSZYnObgiIWc}=xX%GiBlZ=0xoYZE%tN;MI)7?rNZPsG`DXa_-gnE zOB#6Tc?i-$rrlF=$*v2Lm%BY#h}2X6ad!&7ov9g`!Esj8hsHDbD{O&5^AMb~v(o(P z^~`~W-Kj$wA4>>f{t8>XY_ZY#!oYCGp|c!Gm;L_x0lumorEU2~nqpq;wGZgTQVN@6 ztHx@M=9)x{e|GeUEY|EXMn05MC0+DdIo)OI%b|TpT3CJ(i@v$k`tWcOj%719v?E&J zrR|0`mw%^mwykIe1LX**YL1#8^m+Xc6OrxYRxo{aiYULraz57}H+P)b9bNFL?fPb2 zBF2?)%NpsiA()s3ZjAon+!N`AgbJE+xQb>6PDCIgTc*EFkwLo7qP*TeB~JxZm=|j| zbM4?wU4))*hmeX^5U#sMVgi^^=Sj-TbC$A-eqm;RpATs!|POd}9cLTlv#k@TN{gRs9VyS8tXPFp{7cgwNXeOgp&#%Ls$l zxzn<4i3O6Gmq;lv%`^A3#{DGy=@NPRPZ(02lJVYn|AJLL??Kd)#H~M_61Ch`_{#*unC72NMz%X$Q&k>1 z@GxxrWo#*Fja@sx1&LzS5M$#%m_waGOSKdvbXYZwEMfrR@I_JaFA$>uH7hvgKs<&% z=Jj{OpkDFRFF^IP3Pdn3z2${r+(@MbV)lGV@3eH*k*_FFso=1eFTTl=1FNjMX`C~A znbLB;L<8qV4dc|eb|cZS{Cm{!e8g`+j|3W7;Fva>)~FRyDu=&ppvwj*9%6pCgxyI= ztht@rg>@5^(G};(U5+Cp1KQBxZpWT6=&=4L3mgQLR;6GL{mgxwWoA_z4i8;aZ9GZ z&7=fL$Jpy3uEJp@ES8d{ zL%on&NY=e*f|}&c{|Nm}++n%%{f4dmF)75Yz8=Y^2I*k6wvTCz0{hE0-E8) zlGm0qF3IMS#xY@fUvu^k3PwBLY*~^ad%Ag+ea;gDA+33bUc*UjLH)ExR>56r!*^ui zpAI=|h9xo|o*<3f(YB3@TdiJ}8C^TYFzy<6_Y1cJ%hCxKpUBAKE&RgcNnB$+C_KCP zMJ`X>NbMepi1_%P{)VQo=u>+9)EQuyNge6M$LHg?zfOsUI$8sLuM_BKCC?)H+x zJ)QS!(YWr#V@z)jpcvc4IJ6Fw*rAn5K^Hx*^nPIRZ2o9A`JThtN|Ub6Y^um;04$^8 z=rzVIZar2;wGE!eG5~H0*r3u+D63su;~tq+dYQ6?E!lyI5!lHJftLZD7pM#l=4%Hi zGl8TZsNMkOZ30tS<}&SVgo?(V^Ily$2#p)!S#;S5-M+qWD>K{~&d@dhq5-lvJQ2h< zV|Df7R&Sj0y-bS|IoW8Vpzk_&>_2NWMMJ_UB&cVwusb0NB+cFMmCc#oO1l_4grc48 z>nK7RsY>To{teM1onTOWUcJ5tM%xAk?p$HxYf=i#4|!2v8a-9}egU#ewe7}dr4}`9 z?bow(7><_{vN&^vh-A%4b7eB&J=vF*;Kag&Cud+*+b_mUrUl@E{8XoRAn~(eQse!B zO1gdG7bO~_AHhmx)qCs=^Nd>SU{wx|r$GpOBF!1d`Yg+pWdZBo*=E=3(khLawyNCF z*QstAa0CubOE|T8Ru3qcs7V%12YU=N^0P(-j)z!hu|olSA%*l)a4Zes;@_8Dz&Z zHvS_A68!PfUXPNf5-|Dd9G7I&BG#)4Z$N8QVJ&hDIhvo6eOEA20Sw0xY-SnaxA?|* z0URb7R+m8#hQMb~H5=iZJ()eg5jl)3;Ax^m*Zf%{RP+T0L6>v;>bPyZy((sBWoQ>u z+n?tvg!ahcS!2Dm;R)Q+3Ee`k+<%*%-880Rj@+^6Ri*bU4zq5?iK^hrwoPzt`gFi^g=|PB#~CXz3`Q zXWy2u2#=^H5sIPXG?##X{M%h`u5NaOE`DR%_|R)v_Gdo>b?luqVoSVUr!&74ktlE+jJpMNxs_&1mjtBF`w66sqm_fKvLPovwA7!SI}2ZwUHl41C2U9 z{zWk2)-^fG@Bo_Ep`?{-XdcW%^-O?H=~-eC(a|jNBUM$llMZ-Tr$u@tJawuS6Coj~&bVS_aGXBSHq^ZH) z?BMzZlLBjasnKbpJy9sOz3_35d+D3XdoS&_U{q9d*|S>*ah!dEX}edW`6>czc>^)M zTO$N-N6Eu2eTFEZc;CGpGixC=NhZ4!I>HK+dACm*Ei7RAp-D>Do8PC{Gd((5zi39S zTvrx=U+{Sx3aCh8Z$i6UMXtnDC8H&J_IwxmibhRJ**2fXBg0`p1>xVRip*6z__8H9 z0mKF>1O6nZ{kS`k_iNMwDCMdR%j*w&65kU=*ZDuK>hG05Yq*GGD8v7NC<1=b+!k_}hR|tQBCd>grUb zU+tH<#}DLE9UaDun0ZZ4O##W-#5mUyF?BC#FA+J5@ao$2 z45;24_e!&i^V=?`uZh4?PUvIEiV)CgzmELLkzOyb!hO5hcvVQX0eV*sR9_+w1gZsUzRUF4R>njQyJ2mYcn& zy8h)Bm!KuMwd7u=e{joVsA?%Ocv$M1ErJ+uCe7(@!+$BRExDxHHu_O_a56yNk012t2;azGccj zz7doX>6J%3EwpNU^*Cz<^=|5}?H>0p*KK`beoKO5`J0T-EBt1iFNS6K>#q4k4}!_^;ht$gVw4@tvbX;7K+&n2TlGG=n ztlUR<>3LDSX|46nk`$S}I;iEl7_$CEv^NRh@GMRQma0EhOSL}jI!QhLw@T=kQ1e30 zYT)pnA_)S-VLulL$n!wcYF&rV`aLTJby$vaN`7bDCQ2mP_xjdwVdL}*=((9&j&d~u z?(C9cVhqS(MFs5UfFm*BSAdHx6CGVP5Mht&t9tyw6-{^$CJZZx?DGY@O2rxre4qxV zSN{#=9ZB)|oo)w913i*4lH1#I^M6#QDH-`)Og@)2u{o@S?Lkq5-P`SMXy_0xbw`^* zq4y{Z+r!Mrxf4_bmpkv7-vcSg=sL&y!CBCmZdx*}} zEeRyhNj&o?%!|d(m7F=b^MuODfUKa@%eu0gRLyT@>&2Cx_z+@(J&UZV*e z>Z@Ju5c=v4oF$FwenlSr@#S!xD}z;N=sR8BS9YPSD*@ked>tf&$zs$hpIC3kZBv{t z!XH00TBQL-f6zD7Pf;uo>32ewls*QNchx^hrk_e?ZbBWSJrwEN=>sPs{# z+voVYio;yVN3}$R)c3Fl8nvM0;vtg5MzKLtbW0UR+)-FIRZWakJAIKO2Dk%mDi9A?6 zNG>S4v=?se2Ab>KR^b|PjgQ7+T)dC-+m}tjeogMuy=%N`gOD%C{bkkrDSv$gRj%W* zNfrN1Ip(vOri%M}-kcFM-(xh}NfYJ}HeVZEmD)+t00ZkxKf^S4UGQA!^>La2%32%;GE_){M)^M$>Mruus2gKA5P5wciwo5=sk&+Y3FBh z^eqT*zRLcYEJ3=H*sPwaa}e?`+|^fl|X@MmPr^*6}HBA7BdP zwadP)vI^Dg*8KfJQ}+qvwn>%&px%#&Xciy3GFd69s+16i3UVjMOT~$FkE=PTZkQl% z#v8-mVpvo6yeWr8+jSDhmu~nUzk1uI;&H-+zGG*>k?Uml4aD()fEXgIJ(jKEi( z+z0GK<+{aFy}*#+g-`@|5I6KWVxmcav{v!%i~|kYcB$bi?&;xfc}V-TQ`u+);#V2Z z-_J7hc9Dl39uX}m)txRr-(!R#e&vrAtMPf?M)vR9$CchDM>g(C^oecdGr5wl{lAl4 zFZYi%Y9VAK{0;<6jPeFwJvsNFo~kbCwOD=@mh-n4EFNjI@FylOyQZNekwA}Iv3yKQ z;(T0&+afE2U#5^C4Tp1rsW&NehH}QB^!bSuvz8zdp^amrmwKe&i-|Wdiq*Yl10MnP znhdYNhEZr~yMOQa9h4VE0S$jRsgEa@CgKw{;cVy>dpFouJ$gg@)^f(vi`A_S z9n#w2>vg2|Rl@C-e>`s=j_iE29)4!t?NYnBi{B99%zib(nm@*ui~EKlG=SsR!(#Aj z!8XVf+?$6T5u?G|09QTFLFszEc7DCi@q1sg-&x-&icgxKp~733W0`h_^`~oQ@HyAt zEzdfU@1(Dw7T>u4{1u$Ycel#P*7nax4ro%U3G}<0vV^T>A z$=S8J-sXO;bmHauOf1y3K_OYM6AED+rh-V^R>m`{@vZ!|>W; z8#M4H{1Iqx#r^8*Lf<{iMd4R5no_RAUR?W*YQ~YZ;r*Q8!d>#X~$d;51ik9t&%SSHFr`HUuM_J$kWsV4^vo`LS=we zjm3(Ohgt6>>EsgwEp63>8N7KF+dOHAS?igrt4y!`XqH%r$wFOepYGE7XG+oW+)$&) zGC;}&Jfx0lrg6tcTkNnC)%{G&3*kEv>Yt$E2i%ZsvV{tZIToxniaTX=$J^Um>c0d1 zC}aJs>WBJ5>d3xoREt|In;br?{IoU6fbzZqIY$Kww3?W2kqg5+=fHVgQw3+nyN4vI z@WxdaorT}m<-)B+CW-9>r53Wu)*=4eq2@eNh{6R0 zI5wynq?J+Bk!|(kJ8_xGYC4R#FH{Ce!MQQ2W4uVCB&X(-*&5d*s!;EIs8+@F7V z;v~pWf`4-2;D{#|}eM9J}4w8e`)dR@LY z0ecesu80Y_{ME)&8M=8XBtbXrze3ThB-^{vnu$&GV=)iN=Nb>omo+O~LAGis11pSp z9awrKl*doc8%-nD6m;uy4{jHY*YH*j#caa8D-ZwE0%*Nmb}rklfriB+eN6S-FbG2_ zySQ$T?C)ao>V0fzayj0%?-P8aXM}ubXRyDY`0(K$d5pt$HRQ1`)xg>_q;hA+eqICD ze#gsLp=#d+zXIAU*B*Pf;jNgfyOh`0e02ht$$L4r><&%9Im1@M$9 zo)jC~1t`_B?}k}!DI&lQ!o{xWA1DnbHTUdVc@9^B*9Hx)NJg|en4@$dp*a=$p#l2A z)Kkvoqr^pjw7#@BPcrO&pMw+mvO>IyiZq6UO-jraoH&m$+~*UXaH!Ggxge5a{zO>s zfym*qcDJj+5dEEk(cIN!tKX6NX)Y`lsZ&l(`fNpFF&zEdKaIgUqcf`N6CBpARib`6=a^R=T>x44O4x*E@sq+%NNzt=8v^)7i(x zln`}N9h}79p{%8OH8z7&g_~RG0|7f!GEe!BYK@q}JQYEaf&k~5-y31P??D_mAOQZG zo4F#ctP-11Q`5GEf4*ONR5n^F&(<`?d|O(wjRd~_4cASDq4=0f|GSEM~(Yj0IX%m`;Ss*lg05;;hrwV zveDfHJQ2wKVg3BA0;g)Wk6Fj|P_lVyPkIor7DvMcg?9X;l8zf~Qah%w?5+%HXeag6 z96cP=W6-Ti05H(UTaHKg7kzh=U*XgCy&k>WWJ^j> zqDUP3Jx_t}OFURgxEph$R^3SZuQu-JKvdkAhA=F{sv7ops`%|Vb6>>#Ebh%zZwK^2 z8FjH?l*TL<5KcNBFPGM;Q6m|wx4*I@*hT8Md3lXqN_?=`?!8_=2O!rMP)~k}om8i{ zagi*~{a@3vqRW^8Y0wllt4;BhT3{g6D|POdMy8C;5m*tTw3tA1yQDq1qLvMA<rpj3>Kl%v@ptdMFs{G;fgyH3U{*>;(ZE&M2Cu!WYp>%uu(ijYvi`v;uKLPzrc6rTi=`TE2t*?p&JOJN;0KN>ht7qtE*gTAjn_&c&@C+T`ngz?+ zZW8|$SvECQ)p-MZxYzhBouuI}KENXY!Rd%9cacOF(lxsu|GIG^3HH_CG~_g9*%j z;H<$L$7Weu1QpO-+V~7tKn7>E^9%wDCXbyj#c!elz6w7qLLmktM4{W)LhnhSnnBgG zsfX&5VP*fZ)K3p)|CXvEEhS<3LA$go1#2SNZR)lp;oPrpxwgw3mA7BY*-VlLI#D!8 zwDX5KMJ@ldxY!AQk=8t`^fsy)6&5~tRa!el9;cki|vEM7Ia|Z}8hev2rpB)$XH(55X#&u}0(*Cv@4JEDFHN1GYxd8NALX#W)tCbZa z7L6QRD3ikWguGzr!l4mZ_-dkB%&DGg#C}o4rBv>1dIfNa*4#`;rYKX^2|lGLNZdaWH6Y7IDzOW^KKA(rqBL&Y)=&-YbM7i z#ukSK;Y@;@Y&+^DQ&>i)I9maX0PJUI4Vf5#}VJEa5tKweSuRGvtgR_H6uid_4-PCb1 z>%e*V>5N;2jjvCBC!y@qiH@)dv&g8qtKO>GJP+@w*5$RFcqsL`C13w+yG?eAp-M=o za}4-#_uqkNegYxnUEeQM0#2LnMp^)t^t~uK?7dy@r|^*6m$HD7LMqNwvv16ii?X2Y-%Jxmm#O15Gh$Eob&b><<%?oYNOCyx4CZ6inEAn zsaxbn_bKWuO`f0qMyzS<093=*yi8ylr#>t;c2SO}Wab4Dc!sd?R2G>)`VvT@@q9QH z-{5upHn4G;5a^DwTy()F=BYrx|HeSUReLzz9yn5aIl)i4wD8LftfB;4!FR?0cfZko#P z_lYkGw8lcHn;B_M zC(ct^#Ggra+2>$%r--}{0K#v^U^Y8#JBo4q^W#m-&$09qqi zBG$$I!FN`3Rb8S;!RH_wafVS8NpTqbcfgRn0(qf7BG&f^Nt;uIM#- z&X=550NxId#j3ixT0~+CtkKhVc15h{F3M9v$y>cmzMpwRf%pj z2urQC`J5$3TY@9)5F)tO0Inw`uz{H^B*1O7wGac*fowFNJ|+|c1K-2VDcRu%iSKlO z^}d3xi4V}nK4)lhw;U8Q97N(WZC%BTgxE5jVJf~mo2@vT2W&=iR@UEwI^v{S@Gvng zEn;p<yALD!dfMneN0G$?yX~)@Mt&!oKB{;q8xY4pT*pV^ zx``1L6@{kd$$^Fn6plSR=R~#3gW$ym;%qRG1Mp=7P}t=ic7uU`9CUE!=`;i! znwq9!QBQz(dTFS8rR#wa%blf?#zNtky_iR1NWamxIBkEnGTVtvoLX#aH4>)wv_cgZ z%3vX$UgP^epMj(`bjl#0WH)QnTY1?Rw7!_|0ZR!RU^3)q?KW-cd(a|qLpoh=@yVnU z{++%3LS+sW%~8MTbk2|%#2?PcJtP?bt&!B)q@H2qX$O}HQ0VOIYQXU8_RZv&&9ZX~u>5unI?EBKvXOIjB z9RSs#G3s1gsaOtR#M^l+xzCbt zeNqzV!R^$sh#165AsPQzN6ZVefGTTDBeZ0Mj;^NQ%#h%kr9 zP~7&-djUt(WuqmXZ>{0GC9FhjxYcyf_!=xV;Nx?6NE)%OB@D?JH%M- zQ0j%m`r|I{$6C3rc8wj z0=GtAU!0-`M6f^~`&k#Jv660HM7w;#R<)-_bI0ad4Yx}~Q>`LT=vihtY z4f0f4QmEM<*Y0Lj<}P@A=oMS)!*CI{+voiB<071>GiX@uBBXDl5mw~=n}gN(y;U!Y z_0JOwd4h6g-}@}^-x6dIw0zq@07?dJim(5`2a)xvk#h4*$^3go_n>2nB_+H2B0KE0 zehl^BHZSbQ@1U)Xg9}Rv*UlSOVvX9VJ|UjoqR6i&pL6uD#|x)*#gTM^UInlqSl=@& zTIiy^nRHCHM&5mSlq(BAa=&x|IAAi-_=8l&8F=5c8#_|2 zVp~!X?c?)XVI;fC=nk_*pzU?ghcknj_5h}0GAH#Vdo%aG4X!A*5E){*6s}0Hn4LEf zS$kva6d4MUGs=fIWDU(fsWBkHwkq+EDHj}T7!zzcSOafXM z`-zE(dGPPbyS_&acT1ehgFheI3=ku#U?$uF<>ahMW*PnS99&#_mHr{}O(^cEbF505-V z4GJlZA`Bo6Wlc?WxvKZ7qN(s>WcC1w6uogpmxF>_ehY-*RnrZ=WR(=QQ1Md@7>Fl- zeAMQ)-?%;G@{XG}{6@^bIMR<1%y=&BwuL}o40Hdix)%Mc2ODJ9qCU~wu$wnCx~e(q zHRuMZWrX-FYdcO&uHgJNU8rNAN%?|xOZ{%djV_!!71xaG`v=S*OZL1?j!7bMy34ie zdsJ??RJLG9Dd`s6hg{(pCM4rxPsrotOejxIUS3k~hs0G(|B@tmAP_)(#|E}zV{Kku z8_g-i~?kYCMMn#&Yzz#c$F!fj9@aN*&_v0RvUL->> z$7Oq;@`@N5PxBF&f58>o@&QIHMJTXJl$87eHG=6O0D$ZRbQ_!LxPMHwsiVKPK(rf#&j9%(Clt9ZicJrZa|JkG{jk4m!IOVGIIKV2 zQq#j{!6%w`{wQfwaI%ANl7HI=u@Ph-+_gY15tj)(+mSJ*k$Nb;Exl`MMC-M?%FoOu z=0qgkX7Aa+R$<7iWsTk*#(}u4>O4%D51W7{&o{B}B=KmC^-ZZ;4&DL$iZ zj|wuwn{U=bFedtWYW^QlZyA+U7p{#0BHc)LztY{^NU2Dtq;z*FjWkGiE8X4Q-QC^Y zoXOc^@9!Uu;ZS&3YtH+=vbuN?#4{;?v)mQjlr~Sns81htnU@(o{P-EY?+|}DluySRWtmQOs1Y$=605#&b<^12M z!1s85Y%{*spv||aV4$T&%N)OIO`+KfURjvS;8VH8xLgIlSd_tMEdouDn(||z>LUmY zeCzfd0X`=Xd~04x_dh@*$m9GC4jdrtL=vq9R=>QT-ch8BjHBLBJ#yfcwpILVpwpt_ z5^aY08w>;osuGJxMjG6J61dUej%YFw5K0Y@KHm<>^U{`$WMKb5u zA#2#>Xamq=_Q<6)h}nn)u00CN|9e_`Y$HHO3qj*U_@}IU7cv7d2Py#TjO$@>ZK!=< zq1AW`^xWO1&07IFTLm8NJ;aY-lxzHRAA*moZzW^B#O|R{6jEPxbVk5R#?b%a-d}SL zQbhDE;2xyA^6Ps#Fl~Z}974EnKuZ!Dd8Oi4Da0i_nT#@4W{!0sj{Elovo{gY@c4JJ zyd#uN${Y=?sCSTnOg`(7l4#%a9D%I;CitjsUr={1bW8QjP7z$gL zK9TPFYKg;KG$AgFi}m5do7?8cRpBPF&z2U5-Uj=61-(?W0x?e13CB+nUl`NVFlk(V z7iMtrPs}JYDxwX8;Wd>r-6jN=S6nRA|B&FXX(8W9U1x%75fCW2t{?F&jp`NNkDC3; z;M~@X8b#$lgCOyKDklpjZ?T^Giw>m1yPc>)?Avc~1fZqt2ih>m>oWpfKkNV{_4^YW zad~+u5BX{)<~GpfSalhWB(m~)w;7RFFG)WkVMc-1;QtGtQo!krZfh&@LVvPsV^}}^ zR9rc1w&L8l41{=DfT9_K@UVqxLHXg9DRmz!|MLuXyL=(4m2a%fJ-A4og^HZ)F^M}z!R&IBb{vKvaILo-9{ z5oIWm3+HFEJFT20RqGrg>o{#+{8A0;c}@&EgnjaWxGz>Y`B;smd|8K0G!d&GOxYWc zxi^;SyYCK}nj=nmtaY#P-Q3vN819!o7MwgyYUTjnUq@vbxn*3{!7sJ@g*T^QT#$*O z_W#2W;SVDGj_V>V(O)G5i6eT)%+gp40?^gu6tWkX*cT*{~WN1(l#$# z-{SN8B1$^(mGvBI;Na~PRNQ_~ug)okMk`L`U5^w>dt$bf&K3XXpD){naPej%v-@>jF;s*4Y8Xt`TIkWN4xHke#sj84f}ap zrob5Nz)c$rg20AB@uf0>>eNokMb?{C*D17wZ42NLfp=r%1CLEQY1A+S(f&7O56ys%gnffq|11Lx+xJQEp8<{7ty;-0_>tspG~VA& zphMD@GX)XCA?wiO*CL=PgNqw1c^{%{u|(*^Y8>w`w%M&$_>cJ22*}l{mC_XbIdHY=V_3{2bqgi>OC+$U5 zRd3td-H(5&3A!)kgswPAu|gM)f0@y=<`68j2d%keoSbps>Up;#5e9A=phT7eBZT~} z|4AwTjbqN=ga|_>GnSd|jz0?2lE)OT>sdfPIaR|7Uu^`lc#hQK@e9}`nPh>FPL-?}jL892PgXX^GL{qwHwAJYsi8EFiFC*J>2 zh8>UI{#bOCSlM6**6ZXxBiOa;QkWqT$kaBV>MZz~GDo=i$UCBTf~*BG1&#b6!QBR* z@2T+o{mkXI1Re5M@i__$LLdoC<1m-I{&0=0kz0XNKzifAbjN$49w|s``tOoh8HaF- z{SABtxI$jjw1G&Z|E07J*pfhJ7%Ts1u{7~@9p|8dl}BuE=t z?lur9ex@v(GWKgK*QiV8kXq=64j9&+;8&NB|I9^-9hzqN0rwXJvEflJz-q`}7Bzw2 z+GtT(Eli@&{j0E5%-hNgVBgKkC#}fS2rxoSZX^hU?-eB93*u-yMC~`>Qf#!|EmN5L zA6kG;62$ZiEhdX7c(dv>{V1tfDKLoTnfw;!R=lzKO25$v(vAX!N%f9YLT+AS2fqzE z)@za7#&MT2P8=Lzy>7p!6n`&u^1oVu_`z=A?Fs9~=CGs`Cy(CT+{_;6{eM%4E}|6C zcnY|PU9^b~fio@}#8;Eyd$i)HTtINX@QY_#y0Et&I}vCaPsh6?p2cQj;IpDrH9d9R zf^%;xCq^Nwq9PjL3m{Cge{gUzn*8&oKb6k!#cFdYaLdfRQ>c~_rV8=M6^!AkM7n;O zkZd<6a4zmR)D6RwF22zVZ1T`pGIFjV7CH>8OE z{a|SeyXP!8D3U0-+V|lUI#sT*FEasx2D(fLJEL-WtvN*?)Loel1z*7#hF;z9p4^qv zdbuGMq$>Rw{L`Of;}@aK18_!uu=$ahcA^Wa7`@eO@l#BLUX^~s0w6$>%5~G-vzVA? z>iPB1oT5NX173f!edSZ-X~x<`Ko3!Kam52o4PN?taZ+K(c>t`|z9lGPW^RN0Jg_mF z{yH3}y-1j-YYqEE z_MF8D(-ZJ1|lsq+b=5VruyH>Qt~S`ta)^8<=+Y%>_uZ|%97|DR~KzX|L5>Fgd0~?khIG8o`IhHu>>3l4JHUfl@*bRKl_uDdvRjoS}=K*J%#ZujuWEH8; z{xNGm*P1aHKZ7M&nS_IlZStEArJe3bEkNf;y^Nr~3BtC&Lf(4$BL$2Xq)G2>Zn6nmI~sB277QTyfua_R7LfaShY*UkFt&OcY@nS ze)hK)0MNXGUM|6(OlOJ`$0b4W7#EI?3t4IFOT)j_E~q@Yfx-6KZ!VSQ3o zCWX9(>Dvb7eR|h?UuS0v9702ZsAa|b)f1n?%<$+ea`3}uZCTl8KB+yRU45qSG%FX; z&MDW>L%(kTZA=OumaU;3$F;arj7Be{{c8VzPU?T=5^%sEwUZ2O^p;v3?vz8I!+l1x zzlpGC3!i=ujShYGL%hx(={%Yd6Jb2k{VlT`OjvQ0#_H;CjsY;2w~_uy;xIRM`=<@6 zCuC?`x`NPqLYUitjAdS#!Tq~(_yG@9>rdbzN(OU}hMQ{t1>Q#8b-yX4BQnM?UbK{* zgdQx44`%keIczmWOetQYU)M#bMaG(X0uj7I`dVvHgnARUaj#Afs+IOSgojey_>|5n z@%YHgD93!vU@e&OKX;n07PGP{**9AKJv4z%)!^~|AG!4}Y)_gVx#x%L;IOdi9ZUtg zw%>CDiltwDrQr4Lu?1V^zmki( z>3RCvdbywf(l!q2Fw)&Yt{>Vlu=2n#_Z#o^lz0>o@HKRQpv%&Zm!kX^2Y!nNFO>!H z8pf9VGC-~a)^Y$4(z1Rp8Nmc${+!{nMd}9h?82W1cELuw;fJZfToTj23P=h3Ue;el znz-@rmjB(R-+@b_xVVxZ8w{|Vpz)&L-S*T!S*g>LX?7Bf3%@u3LTQGtO8yMurNi7i z4zD#}DzPZbekw&VGh2i@aC(P%-Pb5aIA> z(rfBuXExTj6w7dm6(?hosw_7yg z2bF?Fn2a);6wJc3X~9sm_mqot7X?K{>=rYw9EID#m-;wjl9G~Y8{ck71J|I;!TEU( z`e$$*V`XILRd|9jvA!wVPNUc=xXg+&&xlb*sBn-t(gWlrhReC`oMz;oC1IFkWy0&X z4!$Jq&+9u<PBAQ&tYc~N;BabM2kPx$ru3RFi2TXL-`nvvBET4}R@0(8M{%>Fb zE0z@1TWBpVrv)y^mb6%`IhIaVGJgV?t`=B$zBCKZVw-)Y;C7N(G(eUrf!yHp51Rs^hPYo zPozjq2O=Z&3W|CeX66|BWJtFNnONwz!c6cS7=SGvW*zKQ)(9E2x^zAMSi$5_CHy~;Q3-b21iCXhj|+G!W-eV%i!C2L+;;dN*P<9?0oBRx^l5x zi{07~WU#U9NPfSMwb7Wf6X?dp!QjfG2Uj7Wp1?dcJu_L5S{!t7yXw7)3kyhOux5M( zsGghTL7J?c*99T@#Ln(6fm427p2o^(1CLao%_fc3Ps`=I@h~CVR*l#+V86F+quyu)uM(moU6$TC26VS=aT zy8sN(fdDnp&l|oVIRwB4fPhwz&>Rpv6l+9lc;V_vz=XH^ZJcb{5^Vrtm}+AVKIdeZ z`ns3c013F`QGL3Fc3tIX2+D(1ZeD(u*jSJ~e)$=)3lmK7 zrV{!(pjjJ2l9V;IrAW@NpsQR?tDiD;_K*trhPIABo`{|2FYYiNeCJRNa$;g+?Af-n zz38VQ;FLPRQ9l9aeuew3RfF@X6*6)=2UNR_y{0E zR@cUX?LMbq10W&*1uyDANNSSins@H0rIlh^l$@@Ns+)>krB?KH@lz^S$Fvf0JUH>+ zQjFPw6OYr!XW;tVDZ@Mro}H$y%esF~ZZ6)gQL`KK;qO9?oerJ)Cop@{($OJjX+XDO zuMT>W*Jl1LU4l`ukJe}ftur7eY50-_0|cM&4@Fe3?r?@He2Z<%z-GQ`)$4vHe1cC) zffy|63?}6Gs{woJjgahJ*ewxzHiG+O_Co;|!U7Olly#0Wg$U{o_&6RR6PjuQ<<5&O z*wQ;5#hTiP&C@UeD%`uz|0J)erR6bqS%oeTt}-9G>I<&%$w7UPwl1Rf55Kyj&>S>2 z3!e$fOH04SH@vL}(30Tx1AIdluuOrOAW~SH^{ow~W_9q)t@*o5n%DEgxq-~spcb{g zzns4uH{vMJ1=b_k(!=c%w<4L$joval99wRwq$sRXH{)Kln%Dgp)Yj5)WV+=MT+3{G z?^2k{nWBd_vQa8%lU0dnF4dhh@GT;l-Bc88dLrz-GylXSjq|AX=`n46{=9W*fX^2P z>9hq%dUwBer@VbhU69+O${FNP1UA4#*fYO7{UhI+MtDXR4 zqK!IO=OI9^q-5VM>z13Ej4E8|XYEAZuk;w141HgCEOWY1@xXipWInj2jya8yu4gLN zuQ-;iK>CucwO&uRNOvL|l`ba?kD*A7x!p}1TZaMucgcJ3G+4Jj&*W^=-G=m0BuPM) zn~T8X^jGF&4DyAH%cBe73zX?m%d1)$BgM z#k4^^@j=G~==jr%#`uEcxMdEKX+uYgHEThfr#&!OTmaWJ!G5<^2F5Ft4|nXgOIOw( zX_^T&hKoMKYJQb%0}dNYu;A^xt6$<5ElSt&i85Mu_`#F4N=U3+2=I8ncuY2DFEoO# zAk6Z&rarS*Fkhu1USvfj;E40`C=%@#nw1TPl=H&p+Kh#n{`#@g+R6?kh%M-fE}+3h zp6SK5WU?|MC1i@*D~#tKkt%ZOW^%cska#{fnpc{>HPD2@ZvHvmFNf2C&zUgYnjiP6 z!Hnv4q{O##9qztx@%Ep=gzV@SRMtf?$;-9Vzpdmdg7B)|(7QsgmqndoPv7T+OpuE8 zMSK6S)WEd#?HJft5Pc+6^Wd}GjIMJzD2>8YeQq-lIGi|ZlKC^Z>zz6%pIF{iLonzQ z8J3SF$4~RC;W^!CvwgUUyR5`$l}BHL#dzeUQ?;G~MQFw3;ft!$EbsiQv61o?VL08l zW4&{4E5pybaqPb%XwLmcQaGG2y7h+$2iQ7WgLh&7GoYo8HE$`vlX6#W9uCW|rpeXe zN7iuAA7ePJa4YTMU%hR*E&Y-*&*5t%jPUyovaCcPeZ)PwQU7kw;lG;ri^o zgRHr@hbYE=Gvmhiye679;aqcy^C^FzRWU)#=UTGiWmm1sf!iZNq!73-^Cs*)W;y~w zsSnLPm%h_?Az375N_onSP)Dy1yc)EZuFEf@6<@9#KRh>{2BPA+OTs42C}w;)Ow(fh zj-DGhRszv_e+`2Tklj@L5C&K;AiB<;WyDxCgBxPz#5*~jK^}#eI zIvF?32}-4*4=AYG(syVY-C;W)=eCdhydz?Cgmk5|pBd(fPYv8R6gX9^GEPpYuVhaZ zLwx1;lw5hkZmC%FXa_u%Ug zCy=Vm7#|lD<17!lfdznq8QeKYsOP|53F16mz#UP4P*51^0Xl2mAal)QB05Yn05Wqf zaDwtO@i?D(cjXftksv<`1f!sO3jpi_Jb{z4c^caxReZ>CRvRZ4yEMG3vO<+wvRi;0 zb7cKsryx#j4ut-iW{TJTAomFk&hX3%XOx%_nbF4DpMLsgw+8?!)`xEvsk5fld4RFs zc5l`Js6VoRW4!`Y)@m`-9tc4X#b(gJbsTr4L+p!&+Tct4GpU^)-L20Uy_gS3hB%`G z!NSPiifR2|?zqF!8vki-?7oqanGx>>bI0Q>f)F5f%l3YKp^nBgJ0V*CMHjQ}^8|hO z@_2gg!q0y*X8?o;fgraV^vUTZAx@>DUvPi0<0scu){(GeB2q`ryhNPhZ`|?#-c4|v z1vvbk^CzqQ!oAlb1i-5L>lsb4ha#~1Nv>S@1k$ol>~w-d@;HSm=G4v|-rd2lC0t8o zm;K%gCOO1Xiv#mW-sKoku^X6KtS2{ZcOlyzx z6?=|WLTrJ*Zil}IK19DBVo)zVU=S#_#Faoq;~c@-d5PnM-Z})sC;=6g;W=? zUbj#DQlcd?uCX^(jd&dvP*V{ zo%HpkqCv>SyN_YsRz;Ph@$Y21wOm%}<3P#M{ds zNzSH>7}U;}jF7w?)NPK42G}Ud0+-$O`|3CCTbO9GfX6Q@SNAevrQP1wtPS zh{ay+VE}oF!R7drSX&|#@4n;5n=^$Sb^Na2lRA))ykCB_d8Q%Ab=UU&?}4m}Dyou%U{7S{Q)IfeNHujuPnmiWd1t)67}k+mq)yo*(H&9b$UOs$&-m_cnR z748FK0>Si%x3ya+dOAM0(|;jyxS%8x3lw;moiyL-jDUVnz#fH}7d1Vb`2tAk^@QJo zkk^a=`sjzx6BO7<-bi*dk1uiXNb9Kx9Qc31Ki3_CliWlO4g~b$7BKdWIUdhf=8JqD zbgKun6I=mh{6ASbOldofpCBTo(@KQ-uqqK`o0Ki{C_iZ(M-jfWxG2r5bVdt1%tKH1 zh^%U0=nFLsZj_-${(4X@aASgju{mFR%H?#rDi`={#W;TvxsJu)1B1{}pIwPrDA}DQ z>Y`a|x*RYS_wR^t5nz>I8OTfuimTyp2HmM!`%U1;BAn))S2PaC`D`HLsQXw7=5r)?#=n zek<+191%{AL;W}VC1K)%gWXYKnTM{ciYcYdy)n$%;`Lzqa+QW<6 z2xf?g7jA%CUPeuoC)KikI&#|Z_R<3PG{`2g+raqa3( zaqUV)6YLgC#-xH55bVgOJ0H!702BLn-$J)@(Gk^9u~e-9tvqFSiAQ%i6t$1i%25$> zSforkl0JR1^aTh(KS#_Kzyic(H1J_kpdfnh!b1%VB;>vCx0W%gsce;x?NaF@4jfy- z;6KTahrCtaZ5GuP;PY)$~Om5k4qRLt_kAZf=IK=kNNj6FOaw` zX^rdF@XSZeNgmFgsIy2v|G0f_uH8a#Ipy4&z}Ubft)^%~TRM`|!)XG+%%;fK2V%W!>%Oby|E^R~ zmjpksMrZ0Eq_}Z>fUjVIaHspetBH0B(TlFPNED`+$gb*L=xC_i{@dV|>aIO{~@U z2P;;_aNAJNCI>d|@`BC&hkYk(6KjPaTe?@Qa-5P2k%rSg&QYV%<0M5k`bdIt%2a8C z(Bth+S5NOcMmSsIP4nYKt@ZHgM|IOFzOo?iTfV3rDJ-_pP`q`9#C`l#yEp-4cpJsM@6bK0(JGH1^&JqlL~o z17nphJ+Y`QLzc}ME?>x6AP6VeI(2(SSYa6y55yEyumKHX=(sOl2!le}HnRV^olR7~ zbeYbFH$f4i(|NL8ZToyK|AMMi3k&O^H!Ek=Y6Erts?p_4BG@C3gF;^WC^PN)Gusx1 zN4pWv$??Lw-&-(bJ32lsmvkB)wskjkHhy9&nkK=<)w{y}qVAyHq@H}+UB|09@*TG+ zn;UKSYD=$BDSu!kjP6i#Y1rlvZ)=&$IImZ!fxGzQ&w}dL??c+UlY0X)O>XL!aEQ54 zk7P-#6xDRlbCs2$zWtW{{Us-jMfAM2^6hF?zsFh^g}kC?ISuV^H8JbVYy>+`U6V~D zyUwR$NnDWIoFbsoNVrL z8vo}HGeAlsA0-HZ{C4hJ+!;zG`OB6)@7FA#?s^AnUh}(8V`!sNj?>wuHs5rXRv#{U zh|z@R0J}CTitT;xFT1Z?cYpco{OcqkpB&pr2r{ffV|>F`g9ecyf&`brluk(0Ax+C}umN zUv@hD5doEr1Aq}0uxTCa_56{&_#F`^tO74yjXY&%D5^vqJ#`2T*5dgVPd>DR+~NTm zICAwZy4&P4&RO(lmD^y@n;eBbHm&rBW>ppJiXfR8G?^nzMSgD(Hf9aZ^-^v1dXBWW zn{P143})D+38EKqJABX;j?NQU!j`C1Ie5{sRN;*gbu^ zH5x@Jv9$>Z-~c2%{i}FDyAbfCgPIcp&Nr0HK=jBD4G2Cs0AsIlq0(IY&C|#=Q@l7C zfaUz^&jDY0|2**kMFGI0WUaO6Jgv+B(l&*73hKf|C4n%tDQlq24e&hBPmP>LYiD*u zWXQ4v*OqO%`ulg^GNW4>R^!PPS%joSbBOR83R=C|#S0W^*cl8%`qT+S> zqu)yqLIj=mDh+z+%^=Q>75-bfW-L)ix$4m9uPJV{%}WoGjqw;Qg1ztE4XZy`KeQ!* z%kvXekA$&SCl%xCG$p1l0dd{<`3-`Zt&JC8&3u0oi1+4`6Q2N5#LI2#7D1U1(N zCcm2z^0Q#IxWFIC1-6D2Q*RWGZ)vGDV5pQ7dE$A)6f|8Xu-5trzIvoH8INu~=a=Lv z+I@gFo{ng8@Di+LGV9;Nd5z#n7f|rJPu5bgc_pjfW%-qWxj$YE{}_*5A^LaakDSpb zTM|hm*|oulmXf%BxX&6_0*40nd#OqkBiby75-WGEq_tX$@giK>VT+geOx~FONWHoU zkOe5jTN!tS1sx<1`dTSYgPTo!2E>;pFY$%ROgp+b&#C*{4g5E(n94en7cbqgl`T8P1RCXAE%vz2Crs5hM^Bq*VyWE0BYbr~ z@=@9UR|}9@EchcSG1$tJtiU8-wYO%1TmRN_eK+;-PXo-~x$0zJ78yz|>}_7tv{d;* z-$L~-gjbv|_s=vg&ay;F7AP7oPIb!K92~vV=UpCtatv{~ ztoc<{kXz%`TRQhR0n;TA#yv1Pj!WGfG$3Grg=JG-Ik zf5I+zkv*1t`69)R=r?I8kTT}FNrV9WZe2ht3Sgc$aWH^lh+z(W(3pPz5+*gf4_(zH zA>iPSGh%aa%kyc94(1xOmSCc#)qgV&;(R%WLKb=M2NNBE$bFmKQr~PpaU2Bbk|Ik= zR}uFOA2S8=!49tKjGsOr#}ck>zc2`Lftzm~8p>Q_!dM;q@#aKdb6;}igEdvI zj{VJ-b{*RP?4O2e5|FFH_q!BXWPvN~8&APq*e9>t6iC~5cp7ejWZB~hYkmb7D-|Ar zq)b^+Gw9+~^rhqFN;LY1Q)JYP;lReX>A`KSH_il{UElx5Xi?H|KubDR`1wu6tcRdN zh54r9%>pn#Gd({(uiIamqT#&35i_=1@pyG9ZZ)m3=1znId zq;kJEB4JN|^sQf$PE?)CX?qj+w$b6BT|gL_oPEm=0&S9k%X7g0)W5zw%0o9S9_JMm zApzM6sQw9k@?*Hz2&DZ5W$bBH9e$uTH7$QjAbGu_eA)^o(n`-qr#FjRReDMD)NUy0 z{Pxd5eWalGk${Z=qHyAgh=zMfXyk8)3}VHtXQ3*OsAkxv6j3(^&iY=A3=D5UNvzGh zf)3IAcIlwCkPsX8_a?IPVoe!Cq`2ATT~f@5aSo^b=NcmdA0>P4>}$rW%H!9Uk>i*{ z+kFbI=v=F~3wPJUDCdtP4otP_7bcIau;nx`Bg9CpBLUV0+agY*KKGEgZoJ&IYyC7C z+hNS-I(;N?ssfOsD8Bz9+U$_`%O2zt_5<^U0ty2=+A?ic86wG>%XyR9BJDGEnfizj zHm&`hR}(MoDMeq|zPAb2J&E8hVj0T^Hn;t{k?3-yq%>P1f_@`~_)O=OaTsKfre{I`2gB0f>6_sffa#84)bx!&oi_F+QCHH>L zLi~At`+SO(Nox1cr57aL-47a4?c_(gS5Oh7*4=Zpy4wNmo_mSTA0vd^8Stn`Snu75 z5bgLgP_!Q%D6AHpKa`Y06{tO~!xruHLB%TUA)`Hr1#OEI@|1@$Bdh+YAaRd?}pt8E3oot)%iq2(Wcq z)w$xm_BiqS@qx$*tKvtoaRvMnzE+?4eCksZv7z(v;5-g80*3c51`p;JWDnnT{fT!J zcw?6z0#?@p8NMo%hT&Pw<X0*{GE5k zKwHAclgj(YULj?n&XlSndxS&~+S%AErJVZsdYY)!CkzLl7zqsx0~OGY2oJ@gSJWf> zo3y)1?bDZb70s(EWjAiK#YuzenSx^dV^s}rtm>~40vll}*=SRL(TXX9SjjP9$o(Q^ zpz0$LWp-|R%baF(DsSY3xk*n(4`Wqtj+$>8j;m)^9xwS1FCB`F=AVs@j(_Tzyi-hC z^DW^>VMQ0C&Wh+7>ppNun~y>S%m|HOZ3aa1@3D_G?}*IEzT@1uMy{!FK7}OQ7n6x! zm=O~2&Cz3UH)|CYuf)I01;ZmKlPfcyWi+@yJnt!=5E$v}WA5t%EcSUjED2$ZN2Y3R z8JK`ReIn?62k0t5cckx`5n^pcd~pqC^6P`VC;pK0^V30)Cy?9#n%aQSji304I6MUd!ezdQ2Y?UZRg`HkpKN~hf-m1V_a9Eo9>OEtrFfKKGI>ynO<^KYv=-$Zf^ zSr$lNgNA9@q!#21Pun48g$*VBu8&W|zUhRLJGh>aJ}HvL7EEly^_aqE>c~01ZIK^l zd~-WBiQkycMnLnqZWrdjU62e0jxp8nPa-cj2N)bcXYpJMg+(iUDkN?N*3X$spp*Ry z0yN6c&r@u75*J8)Sli*6#nV<#cdfl22_Tg6<5;nnlU8e%|_8)^T5ixLBA+i~{g%4>9c$25ubRS0*vX>Fmw?wzL&6ywJIdkdu?Tw7YtIX6N9DijOye{*DQq6zd=%A|jITC*Z6r zZjnhWjS0H`KWXhmTp>VRl8sYf_OMPJGGN9xn3uQ>Blfj|!U362pI8lL9rlYJzG`X4 z`b`Z7n(?NR(NEMAxE9G`9xsb?zPw3)DzOCsVf``mr+PZV3kcFLa$1fd+D*N1p)dc0ir z&o&K@L&iKIhX(vgM!#=Da-WjB$)Lh&*|2ceigdr6@e9pEr$Fwapa@Zq)nHjYbGihI z*&(EOa}k;aI?-Lwz$lQs3xq0bg}r$paO!E3*bO`somJ^bQ@GP6rlj?G5;0@Z^{FSkOfp&M(?P68wYwiLIoI!n(5 zloiiwtF2mYJ45i`)(Cr?y&ZVUOJBlv3lxck7BIuTaO`FmqtlKb&F`+KxP4$bFZL8o zm|c&UzsA6_>EBQs?OEl^bMbI5d6=Ioa@$X0P|GK@E1q}=SpRE3t<(F-KHLqzG~Syj2Mj(h zY@z>NU}C7{a?S!#?QWf6EB62GA~C&wZa#FqXHry(Zw(?*JfKk~Pj&Tv;p0lJi6cpi z5*77;>fg+}Y=hPALhaWpn`+X#4CMd(B=0q8gFMP#o4^(^*2qm>bZ|?BcFn66JD=|r zW;DUHx^;Qr$t*z_x;~h2Ouz3$WRnq%k8sEN&1I6O> z^fdp=-6kkX#rqZ9LR$x{Xn=t3w(ZxXf^!VI`jY8eTsrFv!U--x+)LV?S;AO+gbWt# zzpcxAxxp)=pxlFs-S6t^iJ6%vw~w7ob8p_GcjG{nA>V6w%G0_E+O)AjJj3^6^y}!! z-j)=GGz}CfrK*MY&h5k_t7K3X{q-X9MjA2)Fq60ok zps(i<6*le~t~lrJ*M0)Z-W=Pp`t)}rybT5@=s1|YEosYDSEVLuLwa8ed%r%ar1ZPj zw~&2c|8!H9#_IaJoWY%Ta02h=$As7<75Ua{5N*`cWwSGHLa;Ex+Ky{V>*-~K&#rp5e5YiDmSKdX?UsjO^7OW-E+kr@_K>2&hu#z`r) zSehGn%R!7ev0~{>rJTk+)v589@H!m^1_nvbZFbuEkFqdu6$(^0kF=+h3ls}qG&Koq z1t(n{4@)wOd>Jy5b+=41n#emp(dj%F-^f!cs$Q#^nVJ2N2rx$4e^4~BxqN&EruGC- zJFKLwjhukYsDFfojg9Y!RrsY#fYwJ?$F>_Qk8_}_7}wj5sL1DW-^YKT*S}o&=rClq zCY&(-^xe5Ph&u#Lr^`8(sfmer)Q#l3Z~nqk?`QK)mjkE9Fn3Ww8Xyy8e=&s8ElK}j z@7}26{tY*B>Xxa{wltjOTocFdYw9V*@MD8;NJE3#v~2Cy0hq2F6V|SAY58J@XZM4- zMkeV`lDwX;;>Y^Cl|ngZ1+%!XYxpWUr^vT**&$(yLY*_;yNBrZyy*+Pr-JZcSCioi z(|zM4U2Yuf42h9!Aw-IN6V%(#kDJ77da=%4r#mboI{8l9bV~xx_Hd26dLWm{>ccbc z)@D3-V10!NpLQ7j79Bl5cER3iwl1h;<-_Wa`owd7y7z?E06z+NrdhM?0U5aNaz-Sk+$n0b(X&Hy_OsiHIjHX`42NKN#FE;aA2;BnDzGhSQ(GH z6<^xiVW||&p0hU2&!#VfuiWPNdg@g|T;Z!c>W$klO7t$#WpmP^q}b$kck%4BaQ*(? zv@2(u<@!pEH0{o1k7uk8(l;_)Lg1bGn^4Ia6- zLUCgR*xb~5b+3AT5jNj{{rWXuP?=+PmgVPFD5X!edt_?-qM13*8m_4ELzH8O3|T5! zA7iUf4h!B#m$CDo58s_9<+(uOK*yoU#a2Hdw+-p1gBAlYnk+yl&}O-s|0|0ZxIv~V zv?qGUJ6mWOKMQ3ym3U=Qf zmm=Y~s3OOl+Pt`_InF%H`lS4GKH0TbT8Ky0uPTwim#?o>Q#`<$5_XdSH|dy~gCenR zPHiHF6?aRz8?uX+uxc`NavfL@Gk9>@)@^M1<`uH-nZiai^i#{LCc1vrQG?)v$;yEE8nr4Hl7y$CYq~(i(zY7Z*#GY4QCe@9MO9T(gMVDfTC!@}OC-7SOSp}>PYr$R zLM;+rmFNrOE?KF@=hapRm@w%8#B0Lk%SxuPu)~%u_p0sG1Dmus#g{&@Kcyepu6{Qb ze)_n)u0P<)bEPa=4-Ed>d_pe1=eMmrtED{Jil3c5JA`zvH(MNFVj^;HXU0ikcC-djA-H@aT&qPd;tH^V4Lk-oUB;d%FS>eg3bF53y&?{kgkLO9=+Zd&c$O-As z1#gP(MZdTT5mri$5fYi&wn6et%MK;z4D8=KFR$kfJF?xxrFp4PH2I6(cJM*`2%7OD zq3Cl1&i&?UTDDOShgRAS#72Lk8*%ok?#S!o;o%dXF)dEIvx{DJYv(3i4a>_;{C!!L z55nf@JK|R_-sIO8ZW4#IF_qM%y_N2s-@IQL8xwW4?vd?A`D21(dZI0o2noj~4VKa& z%1_|6&eOd!9VRd79b(VdvI)3998%p5soi|@f>EESBjO6TP^6`CTR4`$Nf&tX+!2WC zVtTpf524YJ`>MN>hz^~CA2Cx$$tpk$qx_txD_9fAR-)PE&)CM}$2KCJZ*u7-_ygUQ zee=gWf6y#|}T+1a(yBmFUD& zr|q)PdywlP3(wmxNT-!ToTS9pC{b#xl+`D&x54OHewHgdcvn7ibvO6V37T;+^}tMv z;_cqQEfcTz!Nyp`5i}M&H|Ks2<&)#KhU4%jO_vHU=MkUlwtzVbA0IzleHkPRWzj_2 z6y*q8q$~wR2vy|!(OZ&v6AqB9f^{%1sl3CNo{8x#ZRYFOXc2l*X&jX;I({t)K_HN% z#`s7>BSn`?Hi0O9!G9e}j8)!Dd(ZDR0Y~UZJ??AXu$STQhl}IO`pDMC5?SMG$qr-w z1Ab-_63I3%x|7PI3m=AOncD_eTP(Koqxx(!$^HJg&v2vvHQm;n-~TM23)pdRrgkf3~h^xi#hh| z8kVgX)ajTKOTnME8TdEeck#c1gnuPfRg*0WIIh^fNMvd|L6xmixu7e5!eGO?aaZ&K zG?6`roG4HvOPwkE=@XKozO6P;np>m!UEGoIInj@~3(-&q===w0_WcI9QG;_DcR9o$ z_lNRcVhRv!4zzJ)v2fro9hL+#DgsCDEvtSPoRa4By|`drjS>gzb+@@jksaDXUBS7? zRV)9ldQ?5FE#Yx}0h`@k4P;5<39rG+A)@PlVkM^_S_28yNIhFa0N7lhK=|F8%-<6% z;zj_IluPBEb|{e}jgO6G@wl@I06{}Xldi0XC-5Tw6%w~XRSfxB(W`0W;IaPl0*C9n z^+IMKD0mZe0`m*PC96(@!#{8cIbv-ibl{1?zzt6P{0M4TSb_>>%JZ*cK1!>UdI8OnBT^i!T{^c}#L~-$kU`9+T+gRBf?f z>t4Fk3e4JFS~#x?e)V;C-Qhwl+dd+(+vI_rCwKk%aC_T;^Zt;t%uADgcT17~BV0u0 z>aRovwF_BXR#ZlePD|3KUH!WaMVo1XvKt1M4VAln+5}g+EwiP_W}%<;AIl7>mu``o zt~viSy|dgf;CVkn2xH{!pFblaL1nR2f=d6x|L$^a_x;%|Nyo7FFAnQ=^U-$mMbTdD zblA~lIH6~@rWfp{bEu_Pq&S^M))Zf|YFL%mcTP1Oc(WZv;&s=WXMwS2JDO($F=t&5 z6t_2m_h^Iam5elnFQzY-QmALGrKJYT3mo4*H9(#3F86I*^17V#%s*X?j$VRZzVjZ$ z!TQ%kdC!BW|K8 zi)?8;vpPLpDTH>Rtuh|Y?b}H6=j;)!MzHUz#D{D~aD{>bR7o~kl#M*p)Md7%_)Iyi z*lGTm`ogOeuO~*2a-&&nf{@n%p-(HDoxi=6YVtxylZcRAJI3c(kF)%z8q zr|0xT7xU#-wfi%QqIr9aedDS>XOF8b@(;J(J>4Ut?yAThS3HpY|Do?Ej@Pfx%E=8I z_UH=cCtG2Bqrd9ZS(6F5H~4lWmm26-<%%IFe9D>!ow0odujcfcHAg`cLU(Jv z9w0hG#XTDYO0}$NwQ$wHtI}G z4JYtX^Z-HHM~}NxT2fg0La4w?OXdI3ly1F;`eS5%oqv^$>H_~wDu#LH3x1RZo(Yy ziiwHYKRiq&B$N)^u?TtC{qLBQ;?oqI#Hh@_Rj6Gj4G#>k;=wrH zCLUnX&q~Y)ECWA^2tK^eED)^&sbNNZ#;j|=??ZAQr~<=Cxu@R`ap1WEl6&(>_`Mub zLsrllMSAXF_~)p<=tQa3@jB|A+<+_GK6Ig7JHIM8J9)nBXPvSUMFLpn&e^auowB zwPxNRwzD%^O^|w!f3GBduAlEsF=NDjBP^79JbPjJ@eQV2_Do_l*fhb4#0sLbowceAG%JLn0nAD1fd zcLZS+b#hXmq1`@^$ zh4EK~#vX?jm34U%2`ImsjSUcH4w7RDv~dW#YEgjCBV51m8-5XLj*GhS@0(_4$=%iA zJ{No7)nzl2kRGA=Od{-S#EdaY*qPzZx_KVSn(Hy%)~Z|Gp!jsBCi!yFF>EH@yhq3x z3%?`h9Qq^l26&+5ys6uixR34Yl!{EV*k7M&vW5dNjxUw&!W0PiI^mj7V>Y(&=Y zsx7iVBWd)KSbgnrB*)YCOsi*|Vk^Vnco?N2uH^w4Z}jc@`p~w^(CSQ$@5=zYV@rMV zh3NN0W(-{Rw;EpN^7{Q>m)k--3M?d*EOB{BMCd|Pbj+0%I8X7mxieKwd?IeU!d5ufn*n&HUED&S9S;qXNI=T7Bq`|N1# zgZjnobkWtwLl=V3qIP8WZ{mguQ)KurtK0M#<++?M8jmiM{EurBlwk*}-77b%eXCl- zUu`Z5EX-IEzml)xd_3%MSbr5@CXyBm**$u6Udxn zX<1pvXML3Ogd>!HNWj4HChwU+o64ZNF)M0PFbdO_+&}g~* zTt8upA31X0E%2d4Erf}JIOR97xe!<13Bd%B%%tbvbbqHOC}?ZTY778Pg;J2@7i_Ob+7V5;O6Al8XhGKt1nu_V8SMMdc7LrRdJx zWf%t{wm@7aT9s0Iry8X}q`}Mm>=Jm+^}=}2C;g8Xpk0d0GXxY`&l|$e)JzqNM_j$3 zaSU-gxy1I3fxs|H=(P*xoDkk-0lN?tKOU2&h>8jhn4I{mT0-mDO18JeGRr#AS`uTE z?x8|!Ipx#iOE&`eknh9uq%Uf{$iH5$x2NnNBqP1H>S=?_$d{F|FPDukkRT`0E7E}@ zTKH*CaY10JNzxtlca?VmAG20X2ml*M5hE#Gsueh^6`Op>;-7Y+0gO~(&;bGxMK`d~ z-u%evZoc^7|Dp8YD=wqQZf=;oejl3?>-OXNy79#152c=H=rzTUBtOWz z59eQXCD6)&&j2NnTKV8~_2p^RcBM7_{@zQ@q=Ja%0)UEgTU(dXaJKGAhxxzZzI90E zT3{DiXnYM}Hg-pCH}BZgvQ7EYdw<^qif#CNSX&Z7fL-Zq+S!&;wA=^>_&Bd_9`lVk zDh~UjcEOpS4_CLH$Fm!-Ee5d|kiQ80-%)CPSP@p~rq6ty@4=1y%W^zV=*Lqx`7>tx z>w7jHeKrEFfhBHKVy?p%UDiiw3h#Fxf|C0(PXA$Vh{Cy2u^z6+JFthK`%=PX3_G{FdyJ_kC4G>(7RlF{TbjLa#crNV1< z6B={B9PpE`947WHQJ=0{++)bVum$5)9zKAGYWGYIHFavTif7#C0)(>Q0OwHKXq-3Ry7|g7J zG2-Uf1a8LaL6gui*{e0oNm z6mez|$W20d3eN9F0SX8J`2ibFaNnrM zDT4bQYzysSo9Qt~kpbcEVh)_w;VnA120?VBj105{(8f&Lrpjtfyl({oG_P6|D|&N^ zg9Q+^1UI(4by8+|65QRc?yR>&E6b{$$gKXCRoMLsE5iKl!zZ7{*RNlbD68I8QGwYt zt$N#ZtEL8A$W#b9UN8b0AKl7dE(L)l`x`79%ABY-%*>qevTUlu+r7QLKSiX0%dNLp za>eK3<3{!v7A+r)CD?4e^?({E@G^~|>!iz~g4nS-`du^_)xn%nEuODYBSDNVhxNW{ z5*T0@C#7lPyWR%#JSDMq?O&!$;;w*eKZTmBL=Y}AJq&-PcHLKC^?{*8Q-x;C53v;?cxMO&Dk>y7 z#?dOE3M?2Vu=UJEaQGi=;=tun;czpQ-_tNMMuOd+e{6mF5wKuhg#f+ncWtO(Sn6!q zk;Vot80QR$*IF0QYg%ta2c!ys%7G+jPRaEn_g|?XGi3=??4vOch4bJ)F4_|GfYXt)ShwvJ_VR8)n-F@Dp}(2L{a$B(KS8i|m*q|!}48S_3)4|I{71R(H?ROy|47(dT8 zebCjmTIvw~o2Zpig1PCUC>nQtP1=YNWimISOX8$=$-z6{QIwvPM3X5)T6+oS2p4>K zs!{Fsz_ouM7NTC3A0N|b4kT?T1;opIa`f-*EFyA01EKf!ZW;JW=6_`xm&@K7+Ss5J0uUgreFp0M@5P8Ly# z-~wCVpsGUw1h1$RDR6GR4QGy}e?7&*&d$yho+{7s_3TGR$5wrb8$KJ`7_sHw!CT4` za!%{lm{jv0T3iDgHU%W+si5*8>2W0(E-o%;if-wcIKEWUPHVYL$9l=(GlIVk_V+5tN^~ z+t1LTSlTW>sbsjB{@~G9R?bCxrcY(O7pu`z0W zz4cXKtG=$Tj*t;uR#sM?@zv(TpPh^J{T)Z1pFx%xy7Z!Oh%kXaaS^RwwBkpbIgDRG zIC%HO*BckL7rmpFloY&4cB+J(wo3c+XO-poo=`Nop3dL&xp`tQ8qXA{0^@G~9fhC( za~WZoBB*M6`FrEc@nV=e<9YxtJi3Ynuqn*7U-_4c(aAwNsCTHlPXQy4f#-I>zyAcj z2-VQ$#U*3jjEUj~~&%8NtED#b(-%X(wE|B@%wCdSd7HS7M*vsZ#zn(ns~2i<0uSrzG8p znlqru!~r9FMijE~hrobFgH7H|$aZUOb_;2-47OF(Zu4@Rq9{0TQtw5$nlGxCQ(){( z0;mGG@$IMlfyvNl6)YH+guhL@?L+mX;BOeHtoUPPh02&UQD}W+qM3%OXSbd25)@B06sAKxlmy$~`U#fa5 zaqN@%e56+B*oW*(@`w4mKP;K=mtA{n|4Ca@*OQM;irXj#j2Pm`#Bh*^SiF;NrgrUs zZ)usY_eFUIv0+C?wY)?TkrA}KAY#dkj=M;rXClaSlUrj2zxTK8$* zQN@p5U9}xe!rvuEm@Hod55K(raOw50+cuXSh2VhrV5q^6#rU|ylmr#)W zHozoAqJ9L202uK8nEOvZR%3{yvflQ*>V{`F~_Y19asGb6%c^qj5t?6O;VCFZ|Th!IhPjtXWmJ zw?AJse`f2X>rxc#FMt3tqMwFRSuFr-yBEn+O5sa@q@31q>EQ(Sk@>kk7QBgelbtJQ%)BfSKI)ptrdJS{m$I z%-%<(*?*y)9&U;NYfE(-U@E)sMcPKEY|PD)Cax;HK5n^82l%e1F=gZ?hBhBmwg4Fb zAjYf(Lr_pqqP-P-b3lUOt4Ml^RO(|Xx7MLvxGSQ_OTOP)H+~iDG!X|(I0u-^8T0$3 zY!fX%1Qf&XrTG7kl^2S(3p>sv)Uy>ULhJ}8{A&P?`sWjSn$j-UunI+g50tw`YC)c0u7D|f83n7!ncMNX}63Y7^X<)o_*J(QY2%F z6yNNB?f)Q=5$fLO>709S@_Up7(S!>HUXUOv z5lbf=E$jNO6b5Mz5b62C)?EXr2{zl#8|G`y z*wMM_s=Xid(T`u%6cvV=#XiD!0!KyM@VosYM2iJ5DG-l9Zb$H_{ zUd^j$Z*H7Lac_ScsO@`L;gW#7Q zd5*WK(xEt>ImL;5y>2}vhlF-&EFlGHaA#FyD*g{oet-y``Lj9F3xKZjE5Qp)av6TW z6X=CNU;w#mF$0ddVlniTl@DMN0ZOyOuPx&H6QH3+RewjAF9!s!VXVCNbARY8Wm!p@ z;FNps(|=u4Q&S;&24H`HDX}Qm^FgAl&rLq7;XeBZ2WY%l(;~DJTwGk=_Vd}>OG0V_ zG)2EtuTW#PT6ap;VLY5y7A8JonrXxD*DYB5*s%ZKXa2@P^c;>}U=R2Dg%u%QBNkSY>jcx|0fRdVS2Cj5&{Ra?r|P%6k%0pzKAQ96Kp zq~(GWZM2=Q`MFV}VP5b)CoV1k$bN%_se&v~rg*z=k=U5sU%{@oocW$pj$Feb@P_?c zRrz3{h*J`S#R2CY*d4)6P_VrA-Qe`J$@L!)wRkX>f^iU^NMMl#E~# zL%WjvPurCX%ZHf!Q0AjRpkp!^`Oxyh8Io`W87*MCjn3EnP8X|Du|O^M;5$h<$^jECG8AV_wkC|N z2QjJJ{yn!I$UFLA$eSFAFTry&JpOR0F7ZMtvoGAQ+p_Y6YK5@7|Ey@u`O0LSm-ld` zB{*xkC4BEQCb@h;pgA2MOMdT}Pz(hR6jA~vi8S#?%n(q6TgVfL5B}poKeWp&s>WS? z(BmNElH8QRG{)L!FQlKVv+3%JjVhGyBxm6-DAE+1B0^r5@aZsfoCpoY>g|&L7E? zH-YkO2hzNr9bgi+v2pGll6HL0_~4WtZ1Q8YsZTYPyqT%Fd8j7_O86sKVU|`_l+@JS zX*y=qK?{<*Xy4y#F9E(UFtlnA+;2Ji4=y?{hKPzqU6hwIbth^NumSr`l*`sZaU#X| zRiHq_&}Nf>L2!4Bohr7p6#640k5{Kl#> zybua1`TM0gby(hm)!SP9N;5Hd zHH7MHczmp;jA$0gZ`A8D)b>z$bEJE#0H!N3DXHiFs!d-;{UTbv7`eCx#af&2+|!!y zyw2Xnh8?6YQy?bF%gdVrPq9e2NO5VYaeo|T@7&eH)8nCqF#BNmrfBJYa_NRnoRSy| zNa2bHj4x2<1BUG;SZ*Kz0Q}%lVWtkQ0Ch*+nO*ENFl}0=mPGP_cmf+_uR38hD%mUj z`XDgdM@xjB6uPlN14 zHYW>s#tChA{o3~!xp#^wO5?cze532N_XC18?eAm2bOD?FJ=q^kD_h%55COskKM*qJ zky@2c!ZXP#^FAp#Sy@+C9_)NzzC=zmBjj;3)O^{$*O^5;Ut+--vgZHb>$bRm0?x0* zZGR)9+z9#EWmaPah+E-aaYr-7JlE&L{+q==``UEZ za^HMoNIY7^zf_biz(*)YR0yd1kSr9*ShC?bN^w-ypI{vY8zuyY43ICWUwi=cE>Tl$ zPsROOn-5wr@2jgJPE-*O3K7Coy{C_o-Vfuo9r2B61fkK=Kj?Gg?JcO6W4M|vd-ojw z$&gE}B)!e#v?k&Ys#-@vaDuVx@*)uw98jLsW zyMg7!(VG523-~H>A|z5ceasw8M9TpdQ2Xym>qU%{ZW2Ev7AOO}4i%D>!x0#%Lmzd+ zYfHtRvrBnWN7c6Z_#tWjpBt zBdR6|b9mTq;*Sm7%1H+v*64sa#nF83+@hBMFFY#W;U~>EMLK5}fORR1 zEyjsJB=ZOWRhUgIvYmK32QN0bYI7C6>I}?$)Pxjz5^hzn*eEZ+7)1bNX{l<~S>r+h zzyTWdRtSFDyMo7{yDi}_qwzUZXNd&8T|H#&tcqh)Q~s2 z(f>=BQ-KRO+#v!TT(xZD*8_rK9qs-Dq+MwyPN?*;muW1w@qQzuVPv+qRYV-B`4PAS zZ@a(FT}tbZsXNnK$8j}{EH*eakX!&F5xC<(&W4R{x3ol)bs7)`mO$JRDCWYzFk<44 zpaeYzrS7K>A0H;NS~TN zm{A<(*10z2D^>TuE9Y#>X+q9I7mzpU6f<$6!3gCkFdl^+X$VKfBo%A4eTaE&fXlj6 z^}A07NNQ(iUJTv-nhX@Qw0|i6wd%8iS5augH-XA8_-V2vI(8`7KMD&atNc>3HTJ(OH_(#@;!+S4$HR!bPgvfaX~9^;U!Yo3A#0|ZxE)WcdZ;nqlU}; zxfVx%3_!xcSY>6?HqnMAcp8h!H0P2L319D!!Y>;U384poyLxYq6aCs4#l(L4{ z*Y12J3Xva~lue!c>WbUvN|Q0|kbJ3%Y_50L98hFUT0Rm@my^4H@)ZOL{WWkI<|GmD zh>I1v@1M&_NHE51c3wGmP`&|ej1&;AS%BqI+xkf)ZWIb4ZR|7QB!fV`!=$1;@o)Dwd)fwCl0gHkJap|5ipp8y~70vLda8TB@OTJ@{ee3=>yhIM?a zT$^+YcQVxYrw^FUtDRq;dWfC#8?z){Tzj?kx{Zs%C99z^`gI61@G|As)lHwLO%LMm zuBz~|05SVN3V3L=Nn~QSrQh|u#T^JQQgr1+h1}5#PgYh|koFi4pMxXTheu1NQpBo< zX7QN=0d>f308X+(iU7=eX;6khYDe?9L#M4ibFruZE7~UnSYl~{q7xUx(LJ*bUA5{v^J^$yk!xz)^eaczUxKR+iT$G>R zO(Akm6=?K9a%iEF59Bv8n`hnB$O?g}jnArTS|b|jCc}d!N>W^<9n@K6+1%i|Hqq%f z2fg7yAVNUoTx2*Hi1!6pC!;`fh{)wQntP?VqHGQ?M9tWk3X^CSpi>B7?MZuX;wL7vj%vMhJ zl9C99GiK_@X36hnWa|2R9KjeLB(w^9P(76OszKpi6z%n!lUTT{!(MQZLPrIBalQi+ zG;dW3-?{E8ftG#rXVAbWNFa26GL1EKvOQb>lj(asFGUSpKrv8SS{j8bUNa8T`p!TKWyr8W5XH&<{;LBbUX?_ZteW@Kaxfs{RIS=m=WY$@Em0*`OV*G;AadhA%p z_|qoroSex3c|<Xg5{%- zi#Joj<&it>`Frt7x&X;_55yaw09%jQy7J{0pX`w`)wq6e&Ol}korS8|f(AT`-IOAZ zr5E`$2kgOgs+G(Pcr0au_FoWC6&GFg-Q3(X$-o4Kq>`+%1|TPc@El{R_zwY+PL+Ig zo6iY5MAhdK*(jzH3nw>;nVBRr2zARfrsyHZqn2grRD|##bVM{UF_HJ6{Fgk!UtqOM zj2E+To!C~;BOs8WR@rx~l5gKtmSLo6VD&#egLf;`JC|*FAktgxa~ny#VfZhg zBIrOv;j!pi7L=8iQh^}_(6&q*m(vJiWt1soC+UxiCNoH$cKPp<3@kVW5-^yib>qbB zFF=YxGJxU*3^gEFvD|94n&KHC_F@L~~) zsRmR!Ya1K1i9XOnKK&;Ox@D-?#o&oSrTm6t5FVhQx?9t!u~5`+jJKpRqU=Nu2etcG zvs`HR2=}JQ?}J7v&Dp{Ve!2V8lP;t6e7-ROnX=2vS+#Dn;uxsz@_ppG;%qT-EWcol zk)HnWk)VDA5E~QnmNIuX=UZuX_;ntFU&*%%)(eY^(9)!tr4=>a!a9pO^8e8k?HZ zLD2wtMoCG9tqC&alu-xedFl)`-mG{#wJa|IkKAiKyc*{%*%hw?=JoY;dCynk7NF$K z?si536*S$LoOQ${2)BW_kl$3*)+RMK^O1ROVo`ShrwNfK;4Ux*8BhocLITu(UTekY zg1K9~8hPV`elD1gVIq;CPD?J20=3IUWAA6&%o)ofV~2Wi#Sf zSrb?ErpEjYS@G)!CIvvgH*$mX*o>D#ja3^T0b)mf1*o3bC%#s%--H#!K$!6+LNTiN zZt~%+f@HDpXCVgzqap~~L27d!@C5T?!t1RRpH%W0jCr_D)i=YzKFE{8AVyLFTQQen% zp6A6uolp-Q6H_40ly!IKzKTJREI>Dv-p3pv;tPt;XZw!0fB|oLw1l!OfC|~sJ`($!GZTd<(U{)-EfeP`csaW*JS(ffn!4RL+t@^baC*h zXJcvUAjO~?I8Dv=w=bmKQd4JBQ&P@|U^g|g0NJ-I%WnF^e! z{muPg)ClJHP6rV7ok1EbkoZ5Y^q)Jdd6r%Kf|UVWsoS|>WNgzIVy4B1v<_xHiGrt; z5@Vp^AD@^o))jt_0H;+JgP&eL1>Y74m;9)90UcG%ywB(WN|9{8`@NqgeBeq=bpHh^ z*?ylodEhG}kW?c?&KV6`JlYOIVfhEt8Ni`e`t(T*pz1}TP>?=p+gpIs43g3bDon5^ zz~Dm{Kv2zBQ`heQ0PtDxWWi(Amj~(&h-u!%-LgcPWG#QBxrzEwwt<;r{}6X;NYx#Nw(~2R z6E3WybHTmWdI&#+`_fD2WO-69N{T9oa*45tHG7oJ^+638U9YnX=(lM|ibw|771T$j z{UJ$SejHSDUmp`kZS3qggGx%qqD!PD%Cuw3Ad&hQd7=W7B3RT`_V!%aIO-R5O9;@6p2WC(dBUKf zZ~3tPClaLKAiq4{bVLhmdMc2X8M9!67>x9#)S*^TuLQ)68x*7-kRbtsRWxMe2CO(3 z5Yqu}4&ZqJ35k=Mz%39(Cb&@i0Qh3_&2EeUh5?3!+06eEfT%!O@UsU`c{3p5O8Q_p zb)W=0$jhUGr4537K@SQw2vQ;%IpLIlr%rWqA-^2%_h6#sx6L#zM%1S=of5`Fg7HU? zgsv75{(kTH+yI>(l9KlkaUt+mK#uPKn>SLOs9#+(GS7x1p>Nkr_mzD_+_sD1(YWf^ ze~#W;>rUjht{4S%@ZI|9cA&0eSiS+j9O(i?doUgCpJv-z9rSo+(jAIxy1peXWA3I4 zI?x-z)up9h!G*95$mvP{RTdAqR`laD8l$`max2-9C{2~EH8VG_0d4vKEflS|mV8Ms z;72a7H((}>VNoDw|273py~{HNwLG>wEvjQ7=qhfj!#B{<=E{9k)R!*%m}|a^j!iEA z%2(4>+*^wM3ayUEq=nFH!4QE*#ZsY!3Z186(IIX*&nL^Lw^%tJRgrU-Hppy3lP*;a zTXW~m7FS}-T8CS4a0{3gmnpcu-z;d#^lHYVm%4r-(PSdRB8l!KerFgEzheC-OqK%0 zK^WAt(iE8QCZx_ke;IphHU9JJ@j0&7SwkZ=MHSZ)4DkEU4K-C%L<8(O!HpOgocQ>3 zbmfI+=fYc@wu`f-_f|mJEJ#{PzN`bZalsPE6P0ZO>0WN?b$Mp}vmc}sh6<8)N84Ma zE@{Kl<(svyel=T*T*JheFHOM1)DrDTl`2C92LAe=H-Xnf;eABwA0As9o9_Qoqd|To z_m8&g1)IC^Sic?+p=?{wz%~O0UqkXbBo=@S0}P;O7{=3MG?itYpuPC9Pi@qk6uMHM zT2F7#vOeWULPAHnMx;8!4EIGnq3 zB0Vy%T}n`ZN@;5o`E{&nZcWb3Sqd-$QobU1`~d^gErz!eJ{}&(<52`gFyQ5QyvTXk z1jAS+BbmJ5JWpXYPyn|B==ZVM+1YJwZ#zR$q`TnpmGtzYC--QCgvgNMXFzHnu=JBV z9b#wMhWfl{4UeAJdmY&-TA&3%uRLwsq_a^W&jwI>bll}Up6rko(j4UocCX9z#dCFj zmXm@e_gD@y(sD725KP zMRaYawIRzG7PAq#GQuN?CR{5@D>N!B8U3cyBfp`bqcA1ay{lm(OFnDFTG&MlZ>Z-A z{F3PI(*=#lPBSqtbFUGZ%Y;EkB$@e*%%|Bze8F3Cft-*enB#kqIyTp{F1w9gZm;(z zWC@=UbxsBS=}}nt5{-g&FAszXMtcaEybRG=__i)|Jodjnqoz5sJHQ2PmwT5szO?$G zHt%nZRm|S;&06$WR+_-1KDx0E&KrEZJltN3yw{4+kopU-ww3H&LPbzP!x?vd%r5=p z8-@PD_;0D{FOFXPzGQ`QMCb^wy=1U|h2B{ivcMuEKx}C1C%q_)PhQCJgPkB?w-dT) zs~a_Lwl>=!XEm3OikyG3Ou2SH`(yLcefW!A#+5dKH#cpywO#5WbKm@gxFIezVUV*d zIZR5C)4yG*Y2%P583GfdQk--El~{47OW-CZx!YDz82# zNLsrIgSjo){Eq8nvPHXlaVIT9YRlAy_>11@dTw%nj6H?5w2Y90SmM<5~bTxx^arYf$wtMLoSY`{R4-53wp34U*>P z#xT|BL`7&x%Ul0ZG`m~UOehFl1I-phm|#mj@9vkPEYQip_b)Oy5$@@_d5`CPc-$a= zF?_r|Gb$);ya7=KK#>haFQXU)I~Le(NJ06~^8R|3Y&*xhf;l zbV6MSu*Dh_vC-HhfzziS{mw_o@3x!V8O&3jfkD^MXyUad22^Cg5sOp73Pl5!3(z#1 z^QDW$oxd$+ml#~B0vi@#FYVhmYk`vL$;GY7$XJWSutQc1s(Bj zke4+60l(UIo(%vuKy9_TwRJY7qNp|Ug)e*q(!P+{;GGay!IxmXIfx+pEWnmCNkqO?s?|{-AJ@a|;C!$(d+KrVW9jK{9k>h)! zP~5Pdop&Ma+OyC*&?o_K15z=^9|b4}zM4emz_LO)^--QA!Z|g)2z&34;j3l6yZ|#D zv;+$*($|={wKPJ*uis2-aFw@flFaP2=4UFK?ED(+7C$%CFV-)b9o5v?X-qP++YJAu zsu`nVontUvkVZiLPQ`}g?9|BDAsjk-<}#AWZn(!<<|zoWOLW{#EG`2!&5NX#SQuSYDiA9-+SWHmko|?wW3m@7UBEmNPhb|LHt1y8J;8 zFI_`uWXH+#ac`B;V-{nGP3PxQZv-a{-og;L9Yxyi z>I`o`Gp?WI^!~d!Ds{K+6i#XVbFlQ}_9VsBVuczkFTB={aewbPPRu0x0=@bZ`!Ptb z)-7gp@FBJOx{ce@SRa+vzXQm}^RZZIZP7^;jTw&-DouA4L?@97y3wuvt4HNL34czq zeG}DKmj`O=IhQ=|m|JtRHor%n?`)q=_O%6*<3>*KORa&AUV-(tC7L^RX4B!M|Tm<-YO=YNcrPb^B+* z_ec8}MaLMDWz(g%Y&OB_PcIU7cFdrwMo(*(E`8C3=z#eg3-fzOMW2ira}CaEk>8-@JP$P%vl2!%w^{$K>5b;>IGX9E@!IE{g?eUy?F6*gJo3-`dDP zO;FU&sE0mu{PS4ONEh+$zV$z0a>P<;d#wSc#8Je33?(&B`QdV@H#hi5N|OHd#0x(E zG+Tx?f2BB*`7T(2GJa4zo=I9hFfh)O4Q^ofXu<13X(r(Z7}q50qWR+|NLw@x7n<^T ztT=4#YOkn>5gi@f3~l|Vjed}}9Cg#%1Wa2%%xaE_zUv<89Fqzpdv$dbw}8LCj>V`t z4z{+5nDo-B*n7rvypV?aO0Sz=0s5X29avo->cV4VHH0GTZzNX+?}pq4fE5?mQiEUP zjWIZ1Q7kNlA5P6^RS9{S!C%!S+O_L@tigYw!0j9G8(DDucHcS)enDz-U=$(&`iRPX zmQT4pKk(I0<_iIFuk=ATZZN13|4GWPum4B@a5ZRs^Su=cD!3yk$5t;s*mpyki;R_x zK@TS#Ily@&CN7@rdoHM{sac#PUO$M*V8Kg%C*b7&H9|ReFm;H2;e%!@DA*G~QoWoU z3MkLu;Ng|EwPk_%3IHu36OlmqVDN0HtHUBAQvlv5P`%U8(kkoe4OqN1?Q zP7#PrWoXC*+reHxFRtYor2^PmddFt!yOhM#;I{&LAmiMvc)N}FW70(SYE`A-U+VZkA#we zm&wBjFU;$IWL@{rzZ_p?3(FuAPhdd>CT{^Lt?-6TwW|KjtDZw z2P_ZWZhax7=|iLAc^A^JJo_^*H`u)@meTY-aq0~_ExLX)58UKoayWfx*`2>Y14Y;` zNeOHsywSNxzoCOI*ej~LY)YEooXqxgovOx+XfGN?a&4hoYHlH|KOr3shLbiJju&de zX6ny%OV^tZNsl)ORI@LE#5r?6sH$K_Z;^3IkJrBH%sP+R_@7a8yp47#{Alv+oI9C4 z^jWEYmI8Z}Z+6*WG-IS-6X_9loxt7RfIM61%eeTrH}?ly^2Gd6(khsuYvSq7FBYzT zPj6JjruK)AKQ=gN_j^2_H(4IB9G-t0tt2H%2WIM9rY#2G+JUsLkdTN_6Z)k+(xS}H@`x{4N<%b#fx&+5^kjM z^Yw|Kh|7VH*J3a-8gf2$DNJ(!OXJUvcB#4eNbioyIY6oOgS=6RDhb%Q?JPZwT(jdH zew7E!6q*zS;nfpLnkJWjdcBA!Ce;1@04Cq!NBqaH*?DK7#P(1E!6jC)vlpMIuRWQa zN~Hp_8>@iXxb~x zaJ?A<=Z{MLP{-Taoq<_-xcXX6CQyDu^)g~#A1{~r9JBr_Y*>|LtFDwf9-4g^^?zmu z(u7*&G{`toomDy(UyvbfB3bXqE~;)Dg~@Mg)2q`YC?E&8iE^#F25U7`H zLW_ur!Bn+f6M-vHRaG@EIr+=HtvSflgdCRufeS{?3EvyTL3AMl|0hn!Z2SB7@c@ly zhHZH`S6!~(_HBFH9K`s@f%7yzK7P)Y3y|a9rOV5IGZpY0z%tRF);ROXA&ni|B|Fx2kb$Cce&)xtED{xLelE?pP}K(ff$}m$f*t%F8*?2|n)m!n(nGPIIU)$IIR9zg%vY3nlCy zXT8h)cd(qb^|u!uz2EXGb1@cSBV>)R8u)%W;LkQau3CBblZ5y018e)pN=VMd&KHY3 zbEC)bwq1MsjJ3XN+MziXEdJ+imYsR-=K#+wpKU>vV_)MvOIATa!9fFulal^~Y>CEi zZy7zpNUJYA*0M0}EU#RaGTiT>NE~%Zo_D#N&4m?Rt_544$HSPOt{m$h?<|&X2cK2` z97*C=vLG5f-e|4VV9=iwSujSvgBfW|Tp#?{>a(awK*kXe0ux*SPr{;&KIKC5CViYb zwl2HOkF(*gPQ+Ej%TLQznWx+R>T0J8%Df^25lP3@`Z(mw9NY+#3(59<=tru%`H8Aq z=cDdNpGQnre0dT#rB#Cd?=gJWWcy>aPn|18^f2w8pSD3!C)`dRr5)S;9G8~nks!O? zT@u>gFAd09w|e;9n99n^b4Q=eM>4IXLoE@Xyx??fZOhNKP*?h5$zy*w@V?1soNJC1I=mF0ySK;0J!K#oBE_ldDR>h*vm%};r}p`HCZu3&BWilXcp>T1}> zCo4YJVgq9}xqryJ@uTNwE7El7s0qk?f&g({4V)v>)ho7yQAnIxTddC*NvA18jHF?ub{2_ihRsEow-UrL zX(KN9fRw)qcV0K9va$c8?53@;QB$j;0Dn$Nhb3V0KI!&cs7>Y-wIx06skQ z`p3r%b_;ZTeUIE419_!gL8&fw&8@Pkc3Ge;b#-+O`cXenwc#4DRWsbjbgwDVF&i5j zTiV(lHdL-;FRy#ft`>ygdG$0&FIv}~Urs7AKG<>*1Ntw-mF9-_hb9uM+O|$xZS<|6 zqDkZ*F(9Xc!L*w#{fU{h5M1hY;-r>VKQaG+`d z@17&$w=4yEpoDJ$F$`8|!SwsJyBITTLn7*t>EDK|@Vn~VhV~dQjn~L$32+0#F(Ev{ z-}d+STgD0)B6u&j{F#-jENy zr1Fs_?BlRC?~B%`Uw-k2xr#Pa<$CsK$^3$7d2wi+w`T#*PUpmo$ds%6bL{oM-1Euz zjT3ibbZgVlE=%^Cg>0)_9@(y*l?!uh3448MK>7O)MIm8~WWL^p)b>DYz||IQ5j_Ll z2lEp3{gUfqy$B!t=9CVUjyucuDCOR!3q5PLySdxJdeKik_bue5Gsh%py3U`Njh#qV zbID03M_(5l>f1*7qqV%aCnl(@SiiqGc6je*X`>C`l>8Hc#DKv zeuhoGq}x%eIKz**viQiw*EvY!CtW;wPKq!o!BCy>yLXPq{PeE~Zn_S7J}bHO3^%st z>2H|&k-G?RW2zca`g{9QSzM>yTy@MlUxZRn+9o=Ew8nkqC`lkND`K_h=C7d=FqO;Gt7r9P)W4agC zLFMh&7kNoP-O#HA&nSVTMnn{HMJFg|AffjAA5CIk?pOOYu6GbFfT7PofLg?MlmADRyo*dVQPFd0ED8 zLssrNvM1u{`xk6EDKDE5n`0aLj!zDs#-QhbM)L z-V~`vSSb~!BITIm6c&{nD6s}sKAuU#atAtvK`BR6;t0y$fcvH&lb=r(J*+hiz&~e> zp1Nn|vGF^uaaqO)B0=2f%Z~}G+5di4pWa$$3S-)Jp}wcPqbMVzEX`B8>+e;f>8pX8jlEMx!MzapCIcTrm|YsqAJE z2h1Znb-fjHyKrRUKX{P;h9^fVePBz|y}jN`e3pue3iOsrJY3+&<9Dm}w#>f%lMU)c zht4^z5U+VSL_U8Yo=CQUV9}tUAOw8^s1%sExcSA!k&}}eFgEY;y*{J>D88_$Xcd@~ zpQ@_jmte?*n4KY99D#1Er$-8-*T+;;{y-an6A)^*+?JMfpwY&SkE?xp%FD;sH#`hB z;bZgjkYwgb%x;R2g=56H1*e>tj?RZEnFjw8U1bYux5K5=74BtG%|=E$EZ!T6MD@K- zmAlVs(=yjB7ML0tPR%vAnmSlB8Wo?KjQ)u^>wc&lgc^*;Lz~hgxJ^ZGOFz1lue|VT znXAKco|DAAK{NX!hE(v)iiTXKC-PYQ-xrXJamqc+N5+l1TfK169&*Exn&U)qysa(jBr)ibf-dU1#UyY|2|55(DV^xqiRJM(BZ{7%GNIWw~~{!+DDir;BSFeB9y)Ajyo zY9j8k_r>n=n<=}DNRp-e%qL5j@MaZXHlZ9(0U#u>c^9L)stU>jsH z`ktWR5d3?jq6_{gsOacFCKiHoTf=*w5s3H%5;<~rEy+nm29Ah?+YUsbY-i0$q_tz; zXoUU?^?7iHeylQ6lR{leb_WNWhLbU*BJ9~}D3=IbP_rc45y2_73iw57aG<0odwqx? zP6;=nmZ&1fFX=ZqwO!an;n7?Za$J+90cZMO6+aJ$k&d0?FjZ4A##JM&GIbALB$el9 zV9k=$6rDkletCI$K~rqHD!*2!-i#yeO*azB3L55696s_H4BB!hf>Wtfy!qK`|s;3NxQ++K)4AJcjY@ zURr6NGZL&E2sV};V;I`Z9L*Zq-LpH{nSm-TcwSynQ8R8}mj8&>5W&Xj_9ap34vXDp zCFl)kxPMIOJWf4&cz8$@dAE9|q)K8~OHS-BD!u z`QBASR2BQ*`au0UmHQj0B9d=tJ{+jBPqb3)PiE2=PPta1UM-bxe3c2v zY!^au`e9SB=d$967W>@p;SCetq=oCwWjyPmj+r=r32~u zjZeI*?uF1W23hmSTOX`M0|GJc zV42>uU2#7m;qgBD{X|O4u0EkGT0^3Cess&v76XS^c45(ZWL-sV$Vp7t?irGl*lXKa zsddd4PR^vXU-%QZ1di26J-T+wN0CfUHU3UR{?f`*bY#Nb!NFs#bILFy?Y|2Y+192X zSMKVt>*P@#q^OVCcn{Pd#R&T??`b+_@jPX|AIYLzloHK#=NJ}f>J5-%kW=u7LpF6r#V)$d8vrNhp)WYc{PZ7nw!a>8GH*elh zgCP^F`>(ujCYmK(h;>vZ!;U6xDWIESRIFU0=kzyd{4AF$3WW90drJj(B%hQGnyYHh z5g(g1l6si^_?MB9QC3g}(;x-)b6HtgwzNUU0Npt*RG3E(QOEFif`h#pYN3lL?jNOZ zy3F@K35B=RAQ^YNq*f&TYmsA*JgPn2uCtlD#V>7pPJG_(C+B1((Dd{^HcYA!A_MXs zaY;$Wgla zln~PB=;$qgkyq`xwJMB|0O;CTY)u1gAQSl*pX=TekOoapYr$4`TM2#u3Jb2ytu2It z4Fr>!0FxvFz4z@}FFx>w5g;;r!+N$R94Z62e*T`G(t(o{{8JOPWhEtQWij2xuOJ9C z#9O=V_G~!!IrpxGfO<2zR{-XV%TUEv{k^s?1(_vVY&@AF>5JIeUh6#aM~!E*x%b8J zfwCG+V)|1;--oH-Te-xLi=xzqpOK;Z7%xYEY zBbIZvEfN}T)XCkSU9LCz+1l7H zO+xOGjPz?ZpKdMv3M|QsA?doVDyNj#DmVESYZd;AQln+*>E)lp!_Y0_=VZH)tC$wnm;Q2#OMSBWmhWHAOV0ftcF2a!J_#;YU+xVCJp0G_GV1+%VxZ0{ zDus`aFuwKrlP$Da*v;%cu(In?FI6(iZsgGBVx(nYP)3hms=*W^bj_VWE3YDr#HRG1 zi2vaMCB^)ytaMn$jMj}o5u>PpJE4HL>R?qoH}JnJV(~&~Xz=my{EG84sKkshF~j|H zN1!Y1U?ujTa_m*(jUjz(8mnFT!}1~OFIx_uh3gu!EpxkWs>_&@cw(;fWj~`2vx2Tt z974$4D?*01JrYG&@r;0U9{LFP_hfTPi5%6ta$c9_iuc{U;eS z*57RFf7)}ay;SER%VvL`D#z%kv7MimlCqJ#Rjb8pkn;6SHVxUJIS0h^R8%|*o}Q#m zx}CEKcEl=PR%Vugl>K>yXRQ2|?*g!`vY)2RSkpqW91($4E^gi6I~o)!C;jMH z_q@Nd;W025tPknf|yr_$gJACOgo9h}$MO6a`Lzg+{H;N|x(P#e@+ z7khmhOJI}({CqU1USjJdd*F}I>=qQzt*T92^Ni^X9Z${0`}7x`@K$yEz9mMNo67Xlu)WvQs4=*2H@NA53a>WYSQD=ik!5k8T1#FjgVv<;n6l3W_L%LhC;N%ozYcxf%`g8@?^WIWY|68_ z+-;iE*3s(HjnNw}Eq9K;^5u$W!{F8#_#j2TJj1nQan-Z!ewx(ou+Y+T=4dJScF6gr zjdxZ}VkY^x#OJS1+3<(n7jI0?27NPD`_J~@*YH*E-{?04-n63DJR&9Wn;U4nr4`J# zyo94b`j_`^J;f2LpDzjpirp>G3!Y&L*Q`!sqx_+3`emJYBqRznPUIWZM^4elA$R7# zpk#KDQ96L2r}mI?DBYQX;a&OPW<$YmX%rP2 zf5vE^PRcU-T)o}@vg1SfC$jNHrn3(k?Jzo%762#nXp8A zh@gJZ^k6t+eWVfh&t;B-LHFS+)%{;H61kh!KNh)JW{d0p{tdZn9eXXvu;3}0{<>`{ z?ERNv7L5G0m9(>;18>ePzj{pCTs-=Oc@^rgZgWUndAP6VGvUqb=_)``?i)jN;}MN} zn(4vy+U|V&@_3)Ms>mKC)7mX_io&pC_~ztc+ylctv^W$`IwzaPw5a!}Ea#_FM`HsS z8~eW`dfeyveF^UxVyK^P>=fB_2UDzI=DtXf{2KP>l$w9VNg)y!t+Qb{IXJ4^{X?3q zPl#*eoSaGdytKco|I0_NdD$$!%F9<8>fo-+JOe(G~Ln&&}l_lGf=8FHve*MshU6vsiLU zX6D3`6EG=k`SJRrK!>#8xg!wWU^4Q@rfNX zUwIzSUG?Wv^+pFVS#3j-YNk(Dd~!Q5xnFIDUXw3=N3L@IHkvENKu`bdNx-pJ8rmZg z5`oL)cl;mUg;@$n)ZB;jw$nfz?WkNdxx6t0OF{4(i3nfpPqZ~7D^W6*gh!Hj6?ML| z)|?W*>B1;-uj!VsJt8_Fkr2ufAmhbcq^=>1{##srT3_d7ubO=ai-b=7x@3G8n=62V~MI}R3yyt2nuG9*tI|iwTFz1s#a0&lVWbo z>nkNSwYAX)>!(51&C0+cf^p2) zxG@a46}ca%AYiByIB0J2e^pp|KIiLDEy374e8D!qt&KdgyK}8C0R~~DphIDXPs9CD zfmZIlFg%|eEpkq4VtZ?33mE9b{3j5CO;l7=?0G-JBuM9zT>WV&<(NVj@$oQdY`)5f zQWKY&$F>h7_$~&ZUAy56_m?Lho_G@!dR#tY8EXD`if-6b<$68j^s1BljE=wR#H@_1 zbiLmF0mpvdBlepM&YQ+c#dkYa-LIHd3w6uaat_}%tlk)8tsd!W{ayK?_h^@Vo)_DW zj_Dt}t^1DHZ2o1ctI$oN6l)aU3JZSEJGJ?f2WTC^9mdOkDL*ODhQ5&H?OV@_9I7}Z zG%no_w4Za-yFHJcjysRz#_~t`EAAQfUXl$i3F#q5#Vxlc)`c5n5z?iwi;V`%ZBKi2 z0=@pzM9Yw@@6GOq-P;eFjzxayJ0kH2>G$fA5i}T$VQ|UtTHa}Q-=@BP!54Mcw>d+0 zxZUp(4Y&I9(Jk`JP277v;)X|*F@_v^3lf*ceeNai2g?`btOl|6GJGEjwK`J8_)LqP zwC?|%X|9i(WPMB6za}Iw_;gZu@Wf!}rZN1`;=57Ek?WVIOgw0fV>j)8WS6%rmX;Sw z%ne$P*&SIL-WQWENElB#4TT+`Uxqbp$_RRGqc_EpvBoc*>lT2z1xg}&MRAo>&Ga((`}!khQ#&{=1QE#esmk& z=GdEizTB6+93@m`wO$%E?}4kiX3*z7r_!)Hcykb1eY*&AKWDu|VbOgvWzEn{@PXl# zlm@5#N?HBVM)}53_?rvQOdssC+2gL7Vna*I%|h3ybn#v*8aqUx4PJlC58BVV{l;34 z#$=J)fM0MSz$qZ0&qberyCiUZ)+2PV9Ej^P)&0kh-}0o+kd$M@2gg=I59q5?2A)q_ zTU%Se%^HO@<;)3p2I1#HGr%jj#I|Mi@JStMiqL+wxi9M}IYq-Mnf(zmJBK z_#_k^%U_i7E2f*JHBD#|huU)tWB!-PTQCR0jIQy2{jaJ zs~{G61p-a$`3B|FX*)3|%T|wLe(x^}6x5F&C%QlgkBasqtx^qjKdw?CcU9Gd_(d4D zst+8ko4^@VSYECf=X+prZop9#*#KM>z$*~kVG!`G6WcUNo)(-u>bEj#b+nvAnm3&W z4=k=b`<`DoTVYWQ2wV?)Nt;Y{{E3aykqz7QK z125$OM48)*hK?D=k44%htIY><+S)RJYZ-G5%LJu0dDd~>_vQ-98%B*MC|~}Y&yoM> zQ+LI?+sKWEnAi_lH zC4BIpxIaB5CA7U=2n6u1l>F#Q5Z2b9!c1e*v(4AnkY9-zLK6ca-MYzM(# zgu^ZBAxA-3+2^XNdkKBwR#uE)=gkXL>BN+jAB&3$-rlV$zu*#t?6;)0S4aF6NAjeR z7SRTL2>W9Gzg-06Hs(kCq!@q=b1j>+V*`NbR_8-#ZiueyUq{Hhc1e;zJMN_+v}`?eUayNgn4AQ zwFqSRQK zzA>3azaM^(BKS3jDqeXFf_~FzN@a=jmcsR#Kws_D`$RuazKmZy#+8+(e9RnmQpc&I zt1A=r`cr*<%2)XbCl}J}&nJ|jy3u13qu)jsS=Q$(zF;0X@w~L1&SH@v! z)2Es_SErX*_hb)B$+DwFk+O+WeW{r;l=O8WvfsJrE0Q_?aFTC-gqZCH-vWzZgyV0> z`UDF$SK6RKpkn_s6^=LC$#B`q4pbK49vt|d>!tP*;U#k#r{VYAal><)9bOEhcx9J+ zw?hjO3&1H)eLXSU=;5qIpd9-EqaO7e(#G#q_YT3Qkdl(p)2v45|8W8Q5V3XSoVfY@*0!lDMOLP#N!h(+&<;e zX7&y3WzmnZF==^ub$7Rc;Zaz%-G_#InyUtXTMj_e^m9nHaUQ&Y zn28^)3U}}JOkTb5F7^KN1^w>iEjwhI4v+a0((4YiC9`ZV_(ecWSH?SKs6S9sQ#;GV ztD?Cy^LaFolFD~j)mGWBbpCwF%FFu!1-+#dpD(!%SFo2j?6EcIjzCJl@v0NGLjdmq zs-IQ_^X=f-FAdxZ%xL$|p@(8XG0px~1)t?k<}_Wt+4Bw})a>Mf@q4IRW)i& zIi#4)K~Y>-DsPxEGNNiRV4B7Mo8FM3)dO?xPF(vP>UP`gvevbDS^lk08#7G0&o&nV zp{<{@ZGHzJme~Of9bM1Qhxh~pV&dXKjv0#ruD$5gwbK*~l z+v>IsFPW~6pi?ODlynOm9RGlBvJQvx-3?Mb(hql|_Yv|E%3Fp%f1kutwqO zh=EKMs0Tuy0z>D$4hNg&QdkYk#5E}BamaY{R5skc3S;0=c;UeYL6`|;i-i`o&^I^D z_b2B6vAK^^fe$sMsCi_xNkO+EE8)g>duMBs+T$+ zPZcKV-ob>v^5!)}5s?ba4!{&C{GE08dO&Z1cur34?>(!$h2M&*Z~1CHPY=5l_-uxR z^@OEdnMCxLDU5Qi{m3pu@rXF$M@Fc`L+eFwgF@dqqTk&Kz(4+@75Hyd>%=`(${qDQ zJuNMg;f$Egg0Mreu5n~fb!@UAzLo3^A%+qw*{#S2`{qaj0h7`)*5kvdRL0`8+aH-Q zsGAoQfQNw~cL<(W-(L(98PROs`l9P@_M((qV`u6OipZTeGAv324M5-pL{&xzz|2U!tP9~P}$ zqW1bgsr)C#_fl-4-t@-K!NAls&x$C-Wo*p0-V+1uXpyxle%iMFEyx!^5Zg)SI-gDY z;Ne4H<3>8-B6x0S*!O`WiHJCbIX@ssN*WrHfT;ob1XP0`KuTTEPfkHmj=>CaONeQq zq^FmrI)yo6xt8C~Lh}PZAF=41DXa64-u&^z(M?H*et=BS@sTCy@lv@!{k}EMcXUJiI~2k>u-3 z!FJhn(C9YJ;ga!op*=`Hd!bat-W{q+FgQ4v{&t9GN&DIZ)o;RTJ=G#(rR8vl8cgG$ z$}7<*jvys0;>@lI^jEY*;9RFWutjgx+gXB>BBPCs!DC;xiphKZ2U+TTE2eq$*1S6! zHT^GF*$Pbxs^%Qf&Irix`w}tDL+Cz=C>aqCxu7@b0qc5YN>xP4^F?SHnUgb5VbxSc zeo^Fwf{@3ln5!nP&-JUFa=u=`!Z1!;pJ8zE%)2y1Y;JNa)0glq;}pGu^%*-1AiUT4 zdP))JEfZvIS@D7U#ItXYqbELdz_@e0TG|5CKIB`QK-LyKUn5v=KGAVg-LevTL)75W zvmMv57;wA4YfM#9;FIL+< zA1sdOGiwccXKz*o6Axpl&@~C1aj~#ev^m3oa6e$9t);bz&#WfKkg)U&h7Lt7!5`E*tT~yw-uqEryyH)Kci~@$$E_8l!jR~z)`2;U6I z0Zm-O@0=CU4f*_;_LC1XaMNE3LFN4}z6|3@!Jy(Eu45~NVJ13B2uS$xI<%Z2d`!Qt z7=flY1hr1N8G|VdU=01ge)uBg>SJ(p{zPy!L0z~Ij_Kg#(H#<5R@$asPR93cUjdkt}`$*s~r@Tl$dUf7iuxzhbfArk`f+pHxXS1RRf*;hrC4J z$r5eEWE`vmAlo37&y@wC`hxV_u5aG}78e7(CHwEk7XwfP69w?Tc%jZ98%PMERQxE%r=4siCt4#$=Lw# zJAm>3c^bQSZe3(sxW)HrUv46$U%+=V9^)s?1FqHom|Q7~zV7axIZNPCJdp3-{DH|S z@pEHe>MT|~ARrKfbX-C+G%!Md#9@5ywdMH-{kb-yd>ht(r%=oAq|x}gqL@V%+gXEBc}&tQjm%XIqERS2%hUE7bu_-j ze=XbwatFPOn>l1_m{{5}%u6Vbhr#8bXp7+h>_p8+vPAs&B&DRKG2kL7@}Q%mQ&m;{ z3W-!e)XuM~ONMg}Nb7`rF|gf$IVcR0Y2c{?QF;Ai8Z2dCVD}@VD2-n^I5_lI51X

|dT73sX$hd41ZE7>%J>f-0z9UP;hgPt|4J%RfSX$@mA+c1v4qWxS1gGOd=v8_`^bB z5V>Bx7{3SN82uNyTxi87TC$lo-(XlN5FNM6q0x4J8zi14n-!9mC??@-G3GlD9|lRm zIC}>944;rx#9sQ@%1R*A8{MPsx7stP?T?;OWrsVtI6GtwDG1x4tl;M+*5nRa+-=VOcWlxC9Wbt*;SVsh zLfAYV6a<#EjZ-TJ*B3Wr){+nCd8I zoE?|@-tE};Ips4`5B#L~n^{nod5^M`oeJwuA6+JWPxy_Fa~ZuNxF$>S)Dqw?7xuey zlag~{ie|HB7EiG(UPMlxULFpk{OLf!bt_1gIA7acSXhARaS<)!S{q&Dy~otlNS1bX zr}Q!Jvtsw{X7Xo@E9p-=W^3Q5BX%IvNvcp5gN+x|8M&2}ad1fl1O%utp`aq^!z2mJ zkpaYNJ80Y8+Imb+9|oiYs4m6W4SplCMlJf+_>cN`WJqu z7PsRX1`N#QAb|)l4{hK4kN=9VA^n+`m%BG_l(ibQb{u@5)v%Byh<%* z^0o#Y^{V7Qal2?oLkXBqsDa0Ai_7~c(OYK@>#w)*mF~F4URLe7?1v9qnAnl#)>e-h z7;-VOV?O0Kf9&Y^a_14Du%#C9wer_6p+{m7G#@slF|Yz&Ro-pj)o?FJ{YouaSw^Ka z!%2Hge9n~c-Tu3#>KlEe4F4-rx9X0O_`$2V?~Z~VE@S~wadZt`&T({iZ;P(>Z2OWdJxmhuRJ8mNM;F-P9fNiJX)-`K z56++5DjmGMI6Vc=%vmkkToIwLbS_IeOdv`+8pzAPE3%%wG{aCYnr0zPc^sQH&BA0@ zJ0&gqfn>(vNGd*D*fwYWN@V|HdlwrEE2pVRC+QdXvpU5P^_w*AWB>aANmw3IA{R4MT)m-`}$Z!YZq9_$i4{f@o;m2crSFSKb~^XfoMo{CBE> zIN|`tgJEZh1{3h85Y>Xl)*}iEML4-((?n4SWk82nRb4&P;?4n+-+bU(!D&ZBZw1yH zh*kCenaJyAM9p;79h7qCybXUuq2&&0Pj!3;0*d%=PlrxndTAN{3#xH9>w%%6&$YG3 zBv-M5_RF`Rq73=>^nTpQNg1Fu8HFtjNypO#bDrCMiCHwpJoV2t0!%{M_a7F$=OoAcvqfL&#ha^Gm?cv|3 zOYa=un%cYFic@xY&Q*{9qTyZK*O=5leMP_Ok{M6Pxlg3$_4gjm+kp@@IEe72q>`@D zCPQ-VT6Ie~ERQKW?R~9XcaKaoNG6YHE$TPn+e8nJ5AXDkAJ#D*2;-mdN!~}BiPSU# z_Y$m`Rr%J!jYF%%n36og-IX%DRt7Id9~<{&IRE|oz=+#@0xW&vwLfqZgrcj1n+ieO;yyU?^wo6HM0af4>hTK zID2?>k>ip^N;w3V|1mOWQB2(etQm1oV}i}NdOx?t5NYSvuiCX%Nmlo?r^#Ob5QH=f z^|_r#Oc*vK1B>(Q?)181mY80<7L`ITUQGP-rrw`Y2(uiZzKpMRE-EkYvF3aW2DwaE z@`A(0m485BP)z$+oG()5QE8?l+%!c?z3VS@3Mu!{v>%r3J~&vD2M3H7FJ3^+D|oR< zO|t-oL|}>!?p=?e6-C%sfuW=cXIgkT&Y`){vdQLgO!aC@1LdHH1l{hB+Tx8ebOa~?>61%kAiceZuf-cr6CQejbNZywEp~IjSQFJ zL+GCD3A;13>%PVcorXfrx0~B@Uji^=Q8?tPpATp)iU3NL=Mk&_b%w0uRD}>9a_;k^ zwk6;{WMXOtQ;#p|9(2*y#6cn+-^gSdu=2QL{JSy2mkq6`Ch zZ!Ip`V6Ol4wQo=4{?!B@E32Y%8$dOxW)HK_&#xyt>HlOXFM9O!%?%A>%nTz3BS8pgiMNq77Q&G)uPSfrDP zfO0}?YzO4`BDiI0$0MJwjF$EUiwH!g|8X4f-jLx3i&9}t8~g@74#Mi{L~t*I zZCAnK9I_(?&>4XRPG7tqwN*qx`P}R{;ly zLa+qm_3e+}qk!wKX#U@2`+4sKigb2xLMO<`hA7X z4x2#0gNZVrNmzZ%w-@0}F-quYXe6^M*;-m6Y`B4B2puy9F75_&2#q;^q02ixFnO4YLbWWrdPq zRW7@-Ra=Cr9>CB6-;o0vq2$H#em)wIRDYrM} zr3UWk9(yo+0^_f$p32p8x{KU8{d5I7kfwl?0+FHMCdUp6Go~pxANzl{QckI6$o=8e z&YqIQzR!FsTH6()*IS!@b^UPdd3ANQvy8bz*@Epx_XEQ`u-5|FMCK)!ac!)GQfSns zC~L1TNkI<}TXys0d}qg6JxhMK@gOMHkJHXwWda5UUgwTbJVZ)-XlMmnAkp|ncIU))8ymYqGP0ic@dRVMc9#yM zZABDmPfx%y8RFe$uCt!WX&&_AGuT z?l%z&NkfRt%#@wty_$U|3WYmfyB>}pB}hO4N)0J|OXBz{PuoJPbTXj`>*_O5a3}8a zo~$J(R@uzeCB$!l1+1IO*zro2$x@p)`M`}Lr!{AqXd8SGAPh?@C;&zh3n2+m*yE7u zax#0iN6<6^`wI%D9}5feP$>h#2?ZAXoQY;<*VorY{PpnRQL!$k+ONC8cm>M%m(SQA z&YJB9Q0ldLHTGOzmvF5KJKW06>yWJCs=jR8Ib;{y)HP#~{&m)Mr~4x3c%)}sQ&4^* z4rN@uG$i-mZw%|~)>o|PIEnaVbtJwz@b2(2l(0*kC7tC#F#4;o6}*ZI zk!%~B-S;@g6EW5-)me8asc0XO9T>A90kOquTs~zg8UyoIA&n@!4p@{g$xIE+Q&E$s zGDv`K5`vnC|1k06$K4mih2*z$ijw-;p=zWl$Z;#%a=+-$vw#t!RlJU8$>^a(4E@Pu z%z90f^e=?BgOK>TNxoca000abzJA88lo@?4%^$%Qxu`7LfTZs@qojs1YI$URzrJ!ANA7k{^=7 zVTY|)sORaB(F;C07?BdYG*6M&I@$i+ac^(Pyal7?&;5pa77lj<0|KO>qXTvy8J|mq z-I5>(gTlhYv$M1PzlP$%oEZ_#BnDG{7`Fq52FC3}@P`TGwTHy$Gm(&ykrOWfq1f8m zf)g2wZO4gMJ?I7&Omv^=V?I9J^*EdAnS#Q?(N^5!@t=;Vphqb4;;dR9T{P5jZjSPg zo%|mhLh$m;ek|-)SXh|qSVBWqmaz5#%TG8K*lJqO>SEDH1uq+x2e*|@HV9GV*zBQu zHvtx31IghHWj1)FCg zWFw$6gJJ@jRH9YIJOa?tFnR*ldNmvS8+o?J@#LQCiprkMOqu8#eFqWi`hL|$pBtCX z&Rp)b=})o4KCOm7#*Wa;^qDX%nLZV->tA|u77zUpjU6s0BGp}{LPt)-+%G7wlo-6U zK}KRcCyt$192?!6`bJ1cnv;2&dBU+(M8$d zQrMH-;d;==l@}JuP)Q#5Dm|4cI-Vw4duKqdGp6O4K4_i`j@;DTAL>1&^ zCM3aqOdeFDOerk#Y-@o)RM~cX{~fL2(M7SIZR-W_Dk3fbOYs=jE(_dT0;CJLg0;N2XB*RJSGuZI6FN_a8r5qgkm>WZ1%E)$*ZhB#3{i*` zxt~UQg&5~CY~4vU`n%E-3R4}=I~Pzh`5nX!u$Jo>1Rzq$`I{Ss8EDy@0{OQ=SY zJ{?01)NNZ|4HpI@Bje`Yo;f(&0Fc4~-sr$=BYKQT#DSkx8Q9tBDe$@J)4Dr!i=#_Q zOVt^^16z&IxwPKT%(1n$=hwT{|DO>6bF2jDgv`u7MSP$5T2+0o@S&I7AamHyi>o>H zCsma1biZb0yQesoa4QxY+~4T0d$_E@5y{?nLY6Dp7?Tpd_!ASgfF}8v|3hsZiN{97 zRSs+4KdC5U5tx%^yVgV(sNiiT3#)-+m;nlE-1zPuPvEE$g;j${0&@3F^kb z^hs2{Q$>Q^J~lJ!9{rrS2aG6)5~kpofnXCnn40F|Nbl#`o0Rrf8jbg|d9oJUNznO7Ys*a29{?D#caQYHgzw zLXk-8|F?d5OnLfR8Fy4FYUsrWFHn>tFdjfV5$;`PB&4cQpY!rYzzO3BMfn6gFgoPz zhhXT(qqrT&Duxq6e}k?lI%{72iZf09N~`VHY&gn{lrLpatBa#ZqL83q+tNWG-+KcY zneZYn_CA*WGQ`rg2Or=VO!+@8nWn_@pZmfhB2>^wfkpmbEjt`j%P^nH1^p!qcc5SF zg0|{b{ihf>_+SDIyc}==>g(_CG_O`RG*pC63#vi5l7pea3WjxykZDBilK z^lM~+HV*3@nlX)19SLX#z!wOZK1>=v9%=VbU&HX<|3h>UXKGY}=yTAcWVo${C&V4eh)GHH)brj{4+|cmk)9(N0muPV zN}t@f$G7dEH>FU>S5>CfDb;|BUoG$(L}US31YxiV*8rTDG5*f*Y(%jp#>c_oKpGAO z5ZVGsDIM@!sB>Z5;&t&m{|*^%B4o0z*mDD*O~=ND4|pHYIB*4y@a(Pq+F%=)X|s2L zV1^s0x$1#(+8=2NwE}vbxJem}XGzZK2qUUouMTGHM zvVthjgF8of)&8vz<3G(L$$X!^6B8b-Eck|K!sps&uZoaxvnavDIQnC;l;FS|dXZQ1 zk5TGR>&sEbHzV0%Gou#uk4-2Uxs(X*u6jHy3^j|FifK47AEdPASbMu3&ZEu7dZ8pH z7D)A)q0N(8as8*+y|ER0MBEo#(S_v4Taz<0;e+O1e>*+8Aj9s?^J`EDP$IIDOFd&` zU{H>8^9K}LkIV~&AE%+Bf#FY56_FwJsxX%=|sD%5`Dqh${qzpTcVPh2h z?$8@^ObtdPU_H!ZzwB3~uTeE{B`$X-%o|QDiOBm7 z&~Y;^nH^}9Umt8hmh1XqI?r3R^&~pNwT+Sz!l^(x@kkR>i6*a%Ne_`VZ9~KIw7MuD zTj|Ki`uJkT3-IyH5n<*i~cWYJ4+(r@p_{N>?? zW5D0mWA4|X$KTcO+8I~rsfX@@!y5zO8LJ5LZG>bYFVE;1v9z@GGDN*0=xs;aQ;JmK z04>YHa64Zy^V`%^iqF*r8_e55vMBB4)nZ&p{Vn>>=6x%-(U8>)=!`YPOn1F0XH_zS z#+o(t@ zq@IY38o&rl>gR}RS0E1{5)>;-OPTN{0WFb&9|Q0ZC=VT>r7^12NriqV0t25l0kD{&J>R`&#c2&ccub zQ&oWWVshU`74;m^T+~lGQbwE9Key3;FBGcMspAPh4eHdTP1n~pd2W%rqJUP4etwA$ z;xQ26kNnt6s9%Wd^w@f(`6PxZN7b`zG2VyG1pxmu=&?VZ40M$-sfZUF+mtOHxFsd! z2SokwNPZ*K%oHkz+_$*K?$6+R|GfF2n&_o*qXKOLX5g1BenY)DY0^RF;)$2(z)C|!MWtsnJa0I0N5(;}2hevgjVm`;kFFK-u6w4O<5t|*EN5I? zM#d00Yly*+l;AgGn2@mYZogpn>U5EMvD?-06w!gMg4DQJ-BIi|ZOeP4d>JIm$J({- zTi&;O1oVN6we!HeFT$yH|EWzghD5bXJ8`~bZXBW-w<)jZ6)h)2y+=R*qX@O*R;E?0 z46oPWW(i8p10q@PB&ne~fdGy$nAOF9{P^yR5ha{%z{xZl z$9ICGvw8vz@QQ#pD_VIGyDz}@ZOtOGm~H9a*vteEx!bZon9cp?%b&OQB4OsKc^3l9 zJrur(#P%l2*8>q^xIPrINr@ZSqK(fX_5(f$w5S>ev?j*JuwuVh)!xI$7Xj!zr-+c% z6VR53S^1VkavsMZz_bxbE6~pZ|NrdF4GItpY;2S90)PqC?6<}lK>Gt6e~8pcK-gmU zGnGHHTjWQe8c;+dC8lWaVt-Cf#48dLF#f84Wd>aV$dUh?9H^Z1t(BE9lh@kuNo=fk zPNX|O>qYX9bJ`U|_EVi8>TlFxHRm~73O^7~=;0&&$30{2=R?`i(7?T3%_mVsT44v# zSPJ5ml;@_RI_br0r-nsYz)6J8I!ttWvrzar46RgDBP2QR-iRtybHA$RM;Dp)6Fr-` z%}<|F6lGD6njWv41{g$nidbXT{)LCH)>X`BmMIsjTdDzrpN|-JrM|42|7Ie##mUyg z{cRVTcs^wxbKQU91f0aGBGEh=U6)=L`T*(gFe2Jb`7v>*d_PmS)~XvSQk{7z@bGah zt{C@Rv$RQ~u_4Z^(8vt3To`{b2UT)HKVG9F>4FE6j2|~CQ z-2!2)BS@q$#H$3_;``Eq0ww-$yDoh2TVAFK9gT=Z2%P{?;-R2dgJ?}Vm`Wmu2$fU# zR~q243{wZ-VJJAq($RG7qm0@C5(YrQZCr9W01uM3#YtXBH8gwP->RiqUbEZV;{Tr$ z6_-v1-r2v#IZUAo* zgC-geZxM{eIrx^Z-#5Qz}Y?kS`d)uv6UdMwc)R^)iXD25m zO~adlNQl-%e#tejqsv(!P5j6UG8pNC8$T(ff)9CaLQtEECCtF)VeJMM!VV3tC=?uI zb=nj(*ufZZA|g-1I261^04K!(00_otDE2k^4GQFkRVw;#njd=_V|PF2Ca5UeDi_$> z*vLPinan7+LD>~YY0zl13RFi#B^Pa=6{znW)Mk30q{i1N*+;7L==An`#)X_kkL^uG z-&J;@prD}RO9sdd&f&@#Yc);HYG9!O#2^jBVz?530OSaJ2z=&4Vq$RNC_-@Cbhov% z6X33m9aha(Sclu`zlCR6)d{d5i`4Jsu!3wdNganhn;DVm3r9CKwHVbew8Eac`ly4_tiI z%vL2-V>NU5kpqYkB_d1X3PdXyzBD`NCM1#pipZR>UuXo5gNc^r`dh6HaeXs(ZfTQO zY1uTH-F1G}AOD_&b{9FV3Hu>KU88Kxp@)V%eyHSP7Mkr^#x2D?t7_lkg(Z{*krbpPq)}8tNdZAAk#6a3q)R}$loAjSq@+8f z1*Ai|ySqE?Sm(UweeQEV?EOWy?6u~c|2f7l0jy^{LpR7YwzD|Tu!|wGb#H#c+m=$9 z5812+cUAG}q#|O9iNceNN?8mF%%4C6v={*D@>OL^gE8;1{-*C*MM$;4J{n({|bGx zSrsby41YtvYuoAlaj+bc0@+A35oIx_3q)`OB%ydeIN5C<1F(F=^Frluiip&Kz3p@3 zhYt|N0-yXY*rwa{Q^DhGkP;ain<*vG?#_{<+TPwSL%;#(nhe3yRCh#ZA)nJ@FopnB zr7%K3M(-GS7MwxOdzhISW5A?)!liQ@)wG(ny8p;?9zjvq;}? z#|NooObQlE0Cr$ag*0txIk_*)-{gU)dCSX$o&>KzfK|O3KQvfY$b(M-C?04EdkDPE z?Cb}a3M%LP$a(CRLyAR}8BqaHSFLm7h0eVUU=N`#5wReGR|O93x7M_BTFR)!Tq?0K zq$Yu13FEZ_WFH8okfT2q=n+o6o~r+3HJ*JHB`i(oQ)1xfHT*)vb-SJGoIqq;$g8fd z&a0_kSXOn@RJ|9sDRHIPJTAqknl`d?eBsZCI)mb&Ld$qBC-2(2+oxrP=tK#P>a+*e$ z*a~h8wVQLnM-73O99&?T$lK%l0WN{mpE*+=ji_dY8W3eC&G%FIYW{&opT~JWZQz@& z*jE#ar;Ei^^4XoDh2cFRVZ`iN|en)2Rc7#t)(1lot#aN6;LO4sQ<&l(%dCd#DF#GjEP~Y@`%{$s*y2|d+9iLC2%>WB{VB-e_>kIG7_rMIpJNSDC zsEwlD=pgB&!xxf!-fexjD%W7c5wLO!yk+#BPRW>p!1U{%a*Eu_!g)tYdunYLQ)fpv z6_LA?PP^hQU!)6dX}_D=yRpw;m{l~b{nf6}Kn$$JI1k1SkyyBinNMC+(7}()FRlMr(9H#iO|8@?cQ|O=g*&^k41v!H7XLw zbbS69DCi99f=%=(655xwpeW-&}w zMz(e1ceo^V=6m0m4D@~NRO476W9p0I6DZSDe93gHNAx?TNv`&5^TjW5NlHjqKm5JKMZ6Mp zDJp1I5SjdlbFrQI?Azui7K8wtgToP%^-*Rz{j%uz`0uqXlIBte^A6{>j`!B(-PRv9 z?Xpc%h=*QkTbU#Li1s_viGb4?AU7I6`wHo*;D$I?KMlfijRv3sQbY>J%n_2w>}LkA z6etf;>oxgb-ZsghA8z@Wuh2Kng^WhSu9ReaFeo3?8HvG0e=n9*H8mbPdSD<%)=GVG zAYGCK!M+aCLZSjBBhpLbKT{}38s{ssc;>YGfj;RL4}&{gi~pn^p`%lCa^8dc6@XTl zRKbNo06UA5Q>AUPzpw8HPTrb9Jw3fAWT7B*NdVXl`7Rk5C}+9gKued5{cZ8|U-kB~Y3IS%!tJ7*H7fjoWSVbn!Xx{l4j7b3d1yCmro+AIW-J^vHHSCjAs*39 zl(&t8<*LtcT~1M-S`4i%%jVyFdK5X{XQ|7;Oj|afeK4{*Tv}%=K%TgKH%HYY`V$we zR%+JvI}B?Z0gtbA1`Nau98!;UsC<&?JY8GS#gtJlg7hi8~91i-b%?l@a z!C3SM@~}*Yn3ryI0wxL*mlQ)}sv!YonRf_CY(e<_89`&g4**c5?Quqbi{IrC#wx9L zBiLh4&(4Yv6D0}?0JFLP#v^*dp)oxQ-fMu^Gchy6-=0IL&j~0Fq4&FRQOhv5mTlJ1PP2jWLLC&?!6gBEXG^Ip7VPxU9=3P#jd)lT3A3r9i&Jzyjdg?n3eLa{@n{(2V%W9y&VQV z|Lkl`5H`WEw|8*xA20%n(1AdKvw{(1e&GLylOA+2BAS{M@ce_j0LEuH`i$W2Lihw! zpQB2bQ!_-qVX8hJV>y?rW_~qTo12U6(eISILE`r{_lQSAZ%BAEAG8K5O*Xk}pFQ2a zt~lFmx_w!863$v>fP9iGc(Tct*m>ZoE%dL2`#^VDyyjrlY24f?gsDWUb@EwBzr^e|wf~v}HCWob+$bdK(Os#fm0Tap`gV$qq1f5!|LmXk{9X)q& z>o1<&{MwXQoonGc&|+f0T{)eSCU_G4b7#0fZ%w+^*n+fML_2Atck?7JcJ{&Hr6b-9 zKHsh))DB2{ZpM%<7YzQ6@X>*+?GpyGUi6hSzl<`=0 z*T*LP!$w8)T!fhGeY`V@-gUh6XkO>3p&4%Hvfp0!)IycV8oqe^^O?Qf)4 z7cA#w!6y1v63(p-w6>uxlV?dPt%=H$%_NzZifMXNNuMXL7ae|UU7&U<<xj~+QVZV#L@tA90en|E-#3jUvjTrLrh&v&X zaYV{Yw)&c3{HVsm0-%}X-bHpE_-;M523XkG(nb7nJA!p2V;o#|TfN@xW6Vo!`2V8M zZT_lUq@iBp>%GtdTK_npV4~;WWYsqBkHVI^q?Quj1?LEKcVRY00d@!T5yTr}LtXL; zWahvxDRJ7tMngZDQHLY~{eV67he1GFh8Y2GP;}mvHWZ75F@?XLbI2&iz{QXW< z^;d|qFj={%!CKGE@KhBjPQfqO5ZD&AV-zPkOdFaBJ>akhMg4i`>6jK8^9>Sy-i~`m z*nUKi=%6kG+4lOqCflhcfx8`&U;MKosSCjEJ+Z^4tY7f$L(H2(nZy^r+=9ib%08M- z{VuchY+v|0^sWEv>BFhypZa$YFL{Is9g*+SA9c_Td+qrfz8g4#odLu_{G(V;)4cdY zLm=-_(J5u$*G%2?U@lKN4@XqKtP5Ru+7*1aJH*rJ+;gk|{*!;4-&0bT3(mJHx5Y+JxT&o3>BK|~^8 z9!5ZlfsEGn{LloF*Lp$bfDV%g4Gj{U6#(plXpQ0VpdnKtw@kjN5g0^2i;Es=?d(s0Va@S5!sbOXEJ+xoSm*h%*M!LC$u0QP#v zZL8yjE(TH^SPJ-KLuUp_R4>Edq=nUfA&I^88U6E_uYR2;)M?=AuOgwjv;Rdweb5uV z%)Nq&?FHKzTJvdz)prDEcq{D|N_B2Flp`S&B7fO>59X!$c_S!QP^eGJ9g>W)1Q>djq=B#fD;=k(6DEL{&UDJ~oCqPjowI{MDKadFeIN-7@zDUo{V zNmiZ@+We2EXFMO-L;wDaSjHQ18;!DTH~WC@yF~P^o;-gOXX~ng`xbj0veKBE*4CD+ zkpEq$KfKdxR(G_7`S0`T($R{C=`ZdEW0);T3oQ!04zb@PryPk>a*f@O?YtMbJ{ra) z;DIWpCB9trG&hOJdnO>3@!qDS9&hm9Q=M;zl)CFxMf)$OzeT>)sGz=_@cVbMf0oPG zr@VGW)5jjuoK!ed9Ld~xcZ6y-@+Q}C#c?MhZc1NVvBL4?%dN)dN3TV=5z{A;jqf*UvT52LITK|UccRseV_oZL)5g*rB3iZ(uUW)5Hjz07L z6`6Ss)rb9v;8oHO)T7S=%#z#ZMy=jV?T~kBYdQHjkA%<|91=;@-@LJ0)$Ek%)cUMK zCo9qNzg&RanF}(zo1&P8ji;(SwAd#+4sgHB zLRrUiYl-*%z%X@kR~avuR=}A#{6_o57N*_k;m<*ykDpnS_=9`V>U!qMrJ4JSK5kCA zU5Vgg?IiV_K2f&4qAjqypk^G6a+H~K4Jyz&=RVW4(wW<+urV-w;pwVJWB0kzNd%X0yFBFcf9?g6xtxI*}R+COH@?Iz|alBe%Xse{%YDu(v07$@;m~3`jN5 zL;>3pZTtQM?CrPS?otCQ16~wBRN-lasEM~AF9moTo>dqa{=jM%7#{IVvKSCIKQvXd9|-b*cG6hZ9F_76j+oS#s=FiN07U-D{@s1Q9YN>!54 z>H>)ESKBg#T)YZRdFwT>d>N~$`k|E2rDJ)S^@V7XKQ5*Hn@TSMoxTU3Zg)pwY(o;% zzA^(<*+`I(mvM&JRnFVgR62L77gthQ9)dS}TZScg^2?O%{iFTZfsqZzC;4!|6=1G1pov8%7r?7cUthoP zr#K!2#Yss>1kAg$c02?Xnf5Uq@sX{fLv1?-ucpOC`%3$kA{Z?JMNpjX$?y5hFt5~G zLjFK+XktR0M*gS=p8&_(x_r#MLRUxxVZQMs109)K0UiOZFeu=E{gg7J-1ko z7g9v_rxIYv>^58g9!Vdr9ijzR*yj$Q+}%*yvU_r}0;Cols2t#RNg5#_ zL?M750cwr}8Y#k8DSu0-N_!DwJ0>e`s;tOi(q*u#$N1ESAi-P!`?o#MeEUeYI408< z2U~8n2Xuw8cmiMPvQlcIejZr_ZsX_IM4X+TOK{{mbi9?Frx+uUXZbNl7p-`gv_IvI z>LQ6`eVx{W>01AVdc~Q4cbr_AyVP)h?)di#_{8pb2~T;I6gtqCQle40-_D6`C@bo7 z!nUNuDTr>U?ffu=yc&;YVp7d*9?o6xqn_rVf zzn*f}o%3!8y2lS@w{*2RMbwmZYhPE3<|JWn&U}jBa^B=?eLF;@($e8gBlU)RcL~j` zcTE48?PPJNPaeVj@2fc)TD9AX)7Li74lF5OL)P*ibNAqpdXrB$t;v|7gCj$7kFM7@ zOpH<0;wts02UyihK7G&St^$=No`x$)vf^60P0;h38b7oHz0(y}-o+)iuAB;4>inPF zeQoU@DpH16BP+S=_HD-GVU{!%eGOiXBm-o-xWNqB7QEyFS201a zZ@sMMUXiEx(%jH9pRmdLGN~@iGiIuJpQN?FJy&Zm)@7fb1x#}-{-BdR%Q;Rk@nZKbEycot#$rUH85Ix(( zWW(VcEfL3qLa42KPDoW&lT2d`&)aEFN+|KSf_wwQ!j$koxQJTAL;bOH;9j(;NlWrty7CHfguBr4c;%p3SAk$k$0#Rn^~m z9TajLddppLZZ}sa9V@UiM8w95gO&hZL$Hm;fO!T{r)8g3p*a12^}`uN_hTkk_;j?vbh28kTJ{U7#&! zK>vd@7}j8#@TNb1B;LFMx7@4yM!K6pZy;$ZHR$=gDd%cxF#CHY+*N7ARZUuv3%=v5 zxI{T^rB|wYkLPsmo$XA0*$vZDh>DtP{x#;f*Uu(f?6_Mynfy;!9A`*qY{k*0)%9A+ z^O9>`9Yw%~4sSnmc8bKw%8KYH^rHgRwD`aF*JQm(RUbIU>j}%$XZJWhjK6X^=CE!z z{>DRoUS{?pbKggPQ zka&PCpYJQgVa(|N^XTr=dw%q<`r+?s-s_*(d5_NQhqL0*uU6;xm-_Sx8tyPkSwtd= zJI7~htKIcm3k(gr!V!FwNxyMS%m3gyZlsZ?oQjazv4pr0B-MX69JH(_aPt4>*+u%A zKAd_hJH_4%DfnH<8c|ZuTE}HNR@KMNyIgvfcf6#7Z( z$7Iz@gHw!Y&E3F`&Li3Ir&Lea+R&(y?L6xeE1%@tsd@R7jy6%!A4j*Z?ak%EKh?wR zF1-P*MDp^zQoV--2e;nK-}%~SMXIck;5UY5%&OBOZzV5q%*#oY)RC2z5>kJKLs@f) zt!?PBN1ia4L%Wk)`-JqxJ=bndx9j4FM}NuEjl#I6*$gk$2wvVuQ&Lq1JHNRiy@^ez zvTdFj6|`Z(GWys;zPldLIDl2q>bR#e@2A~5x%TsZHP81)Gp+$TD|OdB+fMNbTE;CD zR?}jsDRG(F3vcS&R|{$!Y_Y>HX>SX9opZhod!^ze9++z`)+&?ojFK%S7s)s)b@;CE zf)RHg_rq@uGJ8@kr;@nI+$2n}tM@zbTZtaPFwmp?{)WJ~mZTRA#Jn)jHSYvjp9oR0 zVW2Zcl1-FbAfz&44;?p#Lt*9va8Gd&7H?v?ozE`$#l`PwGJX4*o@D=EO$`B0m%4(0SC@joaQIU zMHC&#)r_MZU7Gz)CqaIddY3pNy4id6sxG|FrE0UyaL7pbAzG3;+FHj8k&n`e+%M}! zk$5DQL43tAYfIfABIX|uGFV^7`%3k-U5Ak)v$3+N;n^h&l0?5SOl`$`C(6=;KJeQr zZ)+>B%kkfPg&Ik?uE_sz)c6_mNC&EtWKDzE{iUKT#gCoIKq9^BP-P`nY!EKO6pE4@ z9Wrh$qaH48{{4=zliEOUcq~L(|8v*0a zS7c=P0lo|U$iMRP48U*Aj+Qc@vbV@b(@9E1M= zfFlSrT!@qvklVBrO;A!))G1SIM*x*x@xjj@UM3&?ppa$z^ys>cLwrGY!bxDkmXhy@ z57AC*c7X`gdmEv5@lDEcu#UD;d|2zV>^*b+Cm)`@+Y7Ww7j%`VCULtjNs2T@{9? z#056@^QI}i4{M5#?a5eskaPxTld*qJ{24#$dxy6%+?4Jpym?YshrNC*b6m5n8++21-f#IiV{Wi9 zZ0D&yY&&z8icHpWC9htq(JM(49b;Xn;*gt1#q&<}G|q;>V#islUDWmEdvB58azpI zjuytn7H4tBJgUvp^RL;Hcp^&~wT%@!@sjJiAI&5$@RMytQH=It=wUuBxGzx{OOn@d z0O6jYD*+v^roZ1H8(F!9O`JcYJ+fdmx~eq^@oY-=%vJkyxGk-%8yY%$8A{`BN!0y4 z9Fs@EI9eFLn&rJ9~U1>dmqu~%<$8dTF`#>Kp1tmHer zYSI)E+Iz*M71G(+NksJha-IR1+@t^p3rn8RUJZ+6uGekMAl3$$SUBDiy?rqPNThjj zgnhqBg`uB-TmYmp2Sdu*2!I`ovxvC>+${^RG65}G;<%#)FjzA@X|kZya)!tgqOUIz zA{cc2Rs7G}8uA37W2rTk)UBil!3Y85s_-m9XE)XtAGb7@sKl}-_tYD>#y zd9Q-Yz|{Y5nFCBQJLLRWxXK>~vY!~B(?5Ck%VcRbHdP96z$G>ohG_j)C14Wg&8I&H zaZ|5eT=TFN$B1l{+{O;Gxnnc0nzk-mDP4sYwLlf$4~87gP^36Qk_e1f))DQXV+4=g z541gO0?~SjCdKJ(!f&&=`os~Bh+$U*apo^hlUt_2cWSBa7$TdLYal8>oXTBcjAQ)= zH}R5D`sA>#n~4R@VqHw&%`$7iA;Vq+FZ$16JhdoIJX@;cwE;xhG-P44$_hR|dlOXm zCGW|tr3Dde$Ffln`bP$W>g)C!JvT1VbXIKJ;e!jIJ4~bKb^qr`ga?;+j2C3 zP?v&$PtYnWt=mB40O*$fLhzhSy~h>EE}`jV;P*!}1eXDLBxvd}X*7U=SCI-lZ;up# z?`UtXr@fs9aA*jM0a+)MG$@a=va{ntQYeI}MhkfnJd#0u$Dg^#WozJ^dQvk|ou7s{Ow(0B*o+LHTfCU4zGo7382Qx>cC^hZ@RQ*&pSQ@Q2#Jczi zBc3!HL)D@+D|j{Jm=29wMTMuY1MVY}%OKZTFT5SSxE;cWav)DV$HCK<;_%pma1rc% zpLY%LHJ+fbhx-nh>CBK6_M+-tAeZg-DHaxDUssWGS^AD-aLYb$y|440jIa*#<{We6 z)1=4AZfbM|_u$a)Lo_RMbJS!VzDkNPZ=(-t=-Co1q=5JeLp#`eHw}8S}Zt z<(mj+eZr9ttfmPoba~DYx7tN_T*|Soii-(Ox5HZxO64fdf=Rx(no{-R9yN7#VsUU- zc|T%ZSzWVo+7NU-`}zJrkX)-#l>Ru=^Ty8eYJQbcrJJN8+^EO@NMmo+cG&XLFFaZ5 z(I5JWC9yVo*&^o|N7i_X#%+=Unv@X(z68%Z#%V=GMEC=-`G7_l_!nc~=6I}V*3S(4oT zUhg}9Cu`~$_36&buID>7y&@Hpe`zJTblV?@k4bVLta2Ou65OTfw3R8mSkoyzIcVxF zV8g&$v@4%A@pGsQx&6nga*t7a+T;FO@c3Q^*y&-!eS_! za`bp8p1ZFP(D+H-)J1@K#IUtP_H>SKiZRLI%3$j}lP(?@{`vPy2a@1#=|xE5)LlRl z2h>|8$gJ4IvHl2M{CT9+2Z~G$=6?uZ392Yq3*hAn9?AbkCC-8c7xe*ZB6Y3#$|i@X z0BGh&Ltg`v@ajcytOlU&Ft9;MI3mv$VK#wT0~F{$5~ISN2>hlu^dH;<9VqZF&|78% zVRvuOTCfUZYWjx7^DDeqQafD2K$2mo`Ud;)vv)JP^Q|J}Q5M1vFFx*wG}#!vQtf3I znKhWu$!zd+`E(19@}2gh0L_$Xl##`fTrC)ql&!@&*1q&|+DyUfT5e?(#5wR_tst}T z^YYNo?KY#h!+*4&Q<%QRv%Ei@htfjefn?4~n{k_n&bGFHgBJisfc(4FoKMpDl^Mds z;(TLEr3Ov&o-LN5w$pF-LZoE0cwx?lXgnx_<=WSsM@@GG5d~4ciz|_*kX7iU9#{dbz0c^v~3PnbvKtJzj=hqX)LmnykE`rFzH zp2F3EOgscOyHgJ+9i->{j98p4+;(1$Gg5(oX5c#@LD?S#4fmbAya+7OfXV{>bQdBy zq4gf9{=_;RL|JA@H7xZnR5*|dAFvbae z^g*45uJ_a0&lD>v3C@igKJM9Fe zJwC{gH)l;G%iUzgrO#02a0#sc7QFgkSG$YvQmgMpn56s*TemCbB=-aN?1FENmG3wj zV$;^-1ILR4l(lZY?x^9+ebrgV;vy*iN{H7xodcU@k5I{w&!O|xq_Ub{@G z-eQoXXv#KZ_KD|8Qai20>O^ewH9yAtsY0#3z8}A})yWqs*TY8IruS${uz71vmDtPj zy6Fxry1!gfQLB+v)Vkp7VWy}`PHW?YwPUQC{mQ%H$f#V$Y@bn-ZWAL(apOPJZ0@_J z_{Fc#Hh2EoW4zV}CG^YTI#XR@&0}1$w;Vg~F)cE8w>|jds_TqSaE1G<^p^4r-Dr&t zWVRDD2HMH97W|b94A#F2ZL40<91x%kE*VcHr1*IAUU$D>{o}a4=`d`OOHF5j{)FA= zqUM3c?t$4fHs99yOzDQz5qJA-pLTs+un@~I4;*}gvn4b35uQgqBH=o+L)s7hoWAV= zkO=^cts6*ZtuzPc6`KF6L&bd04ZEN!8P;RtK5BY*VZt^#IU#uU>d;HzfZxs7n6cLN z#1QrrDM&tn;1)gt`TV!?={wEg)49G>B?UQ)BU zHOK*>;qoy9otTI->z(Cf!NX8+L{yeG77lHKSoe^yODAy%Uj?(L^v}!IoG~FUHQhH1 z-Uhm_!qH;_jpOu*QHv;lxm}*xR0NsWn(E zJ~sZv(YU;dG%5C-&us)FCKi~eqWogy#wc@&%E~$8{UDz)_tanF{^6w1X%etedc_nl z2=>V6w;Gllj@IefglCoOcFy-?1gJiM$K@?=X*reGtHXBGlF_>L?3^g-tXaM|YS(9w zqG>yU6T>`zbFT5G0;G8 zE`dt4g*h93rli2$(Q#kJk zW6eGFN>~Y}eA9%(I00%$IHyW)*b}?o`fpOBRvn?9(Y(iw>J? zjktX(9YJWxD;J~W-zIjR%}8RtQ%@K19DHXJaXERE>$0I^NRK!ByZ6=UhUaznkWRg3 ze~%;SWD>Tdl~;ZJ9W(9*lAR`!3k~f7GcFAZbVn)Qis6Ry@DIZZqZ8!YQfLJ(DrfiH zVo+i%3falSQ2yffS)*&Iqm!369BZglQ>3((jT=zpA3mzj+FC{mg)`}=t@yS zKbxt3IYN0vzU6k(gH;n*7HAQ()25mLz`66k#!)1W9d-@(3;W+&9^Qc?e9iqs8)Jpn zcAVPoK4olysON&O+#4||-RIeq4BflAwLKeyNS3X)7Su7w?4HNoDcgLR!f+yRPvlS4 zeA(6D#o^r7D47RpZX_o)2RLWdY;IS{p8LHwmlCI|l4~0aVizf~5sM{Ztt)kHE9wqK zEIUt=>bIDX{D|ucO%j%dGa-XrLE!mqd|az%kF#A)INVj3{>B(^OBg9|>M#N}aV z&oU4%XIVkEZdO;W#g<-lR8u1Z9}fhbr>r}y{9>gJFwS%LqYgMCobMA=Gt1+0Ia*KG zU?CU*a7p32b?HhkeMH&9pr$8R#b6yh>KGUU?J+n%QG&M5N_#*(ljU{}-*xFQ>3Fd* zOy=oJF+z`;>uQn?V6q8pa4s2mV_8@&OMBfB#$>Flngz|H6e+{d2fXi>66Kx#rv=!HCK)kq z)rHKF)aDV|C{0!QXC#a7C70_UrAB5LoAVb_PSetFF!Bgo9m?08Et5wVl#a?k+v&Ja zc|)ICj4{F;e?3t=J~nkllOIhJOL3UYvad4KDL-+H=pI$pu(^#eJpgHbmXCilD5JKT z!Yk&Yq4Axw{pZnUOl!umz<}k3J4d@oaCul*nBo3nyU>8X94yHDSM1{!;Aa7<{;{~1fW-nI4DlcG@(U5a5?_1_f_!-~MfPg`8oNkk{reE(7`JZrfwcnO3k zOHuOz>YRD01fO~NaA>rCJA8STIwck3agIuhe2a{6s`$3L^pj4*M_<66dU@3A6vzKj zXv@;JLeb7;Ktv<;-@x6nU6l2K7#J-=7**vXx(Yx~v>_x*murcX|%<~Z2L{(qBatMPOUnGa>X zj)(eY(MCe-jLY2a>Db~KKS#|t z;dM;nm^@(*vGSex+u-#nV(-P_s(*1ak0HZkJbFR5|CAbvB+6tF>T60r^6T54qWNRo zYXSmJX2gl*e18vF*y)cts@&`|sA6$9m)|8;Y`16&sxt^d5yVQTOww;`8bg@r}xw!jCw9?4c%eTzw;O=ak@n zS;Fff@`$reo{5V6+B@>5n)$NlZriC5r?a*3eXFiI-?VF#`yN+l-@^hQy%@zZ7VGM| zsCvHlxS-oJaq4+1Z{?Fn*Mj@f?{6B@ri$%j0(_|LX3^-ahj9 zm-9_iVreYujh-SpdTiaxDeZfYx7Y++m)|3MDe+s;9xR}dzB}X`3EdR0mwW1*?sV(K z^OD`pwKOC!cOtfRc%Q7!lh^0E-%;m}mn!SaP3rv#y6L8llk3+fY9NqOm8TZ^ z1pWrQtkt_CX+uxkMq4n2H*qtOQ|9Ld?5~D(BJuB%{(2Y(BWo7xvs>E}YyOU52P~>? z8hmFjAE55Ro8T9}`bKdsC*m~CF?IM1E@LA6JVm~WW`pR`Oj0xb|4M|_Sfi>0^ zX5XPo8EI)?NztpP!0rb)w(Rr3G`4W93HX%nIobyMC`!v#rP3CQSbAN zp{aSk;S)+wkouto(>BW1`0GaSc4jY3D~f^*7hOrXm&s z?&pU(W5ov9T=D#_T;M%1wRzD!2P_mKGA~!7>MN6cMg-(HEfySUTAFA!SLtfFA9Qnf z9IylW2hq9)*l-Fmmn(s|nvR7|!TIBNI2V(MpZ$8UIksi;1H%OVCrB_Kk$9P=%%USZ@> z^0aIy!if zQZxwl@p%T_;r;^~6-(njobd=Vl@>OnRPeZ;KLgPdd@+n2toY50p!E0hx&`1a07_6; zp!2dqV`O5&CMO*F?twrDfXQk7SLUs6h(!3F?=+7eM}S#iD0pFQAoC-?;1OZ&xJ%IQ zpqnppa?HJEc^oD02wFvlvLz5R0x~k~+J{XaV!^V{!=HP!x?a`72oXMBQPra!tAB^^ z>-`^)3o64xSjw!2q|B_Z+<432;af>&Gr`UvlRTFf(C+lAeSvt;H#`ZG@X%dL^C*+@ zAMIa9J0!H*sAnY*(i*!0UrpTA#YxUS;Yqm0Yh_cH+Wn3Wl|5Ar5<iP z!aB8nK!ph&Jjl%=K3a#|;>V=e-=r8c6>~Ju_Eb-4prYdJ5glDt5|M46obncRRHklw zT@Keh1JIFS{>#Wq(9lYGA47x2Omvr7#e!e#9IRjnkw;jCufkwXK@Jxbj5APE3#DH} z<(3@sG59BRo{=f0l`u8|VBN`oGTD@`Sq-1~L5Ka%e_1X)?du=TriqvO4+e-^HJRQX zAtSA))AYChw_rY-i_l=OJp6mX<{ZE2AY)6vcxgM7hUKFoN3n^Nnylvq+!f?3!`$)m zVyNd4=G+*Pw{kNhsv937AknnP|KTx>A&CtD*ys>^L^pSLA{IolPP!%>V9^c$c7tpW z&?2IjOeq4#M@Ne1)9?_MtHAyR4p|7~hD?QbgL5G8f?S*aDmx=cD}dl$xW~QVu?1xz z!V31|N5h-v>=nW0?R2s(CKeuQx{{0Qb^o>QN5UUNa4_7|;I3Lqw}C&p#heV!x%hiEwT>F+gUXd8SA=aG4s@svvw@%mIAjpU zc5pB(K<*TD+R8%*HvA-f#0JBXy*?4VfBBj(8)`j&N^u%r(cVUw@M%LkL}kIhp6C{b z)WRk58a(USIk+#FB9YWSzh*AK&xy~L6Th^jCzcm=Y0#Do2?{^{r36LNpq&szv}-%2 z6^%NqH0H);VdX(Z z=cC!|npa1R6S{4mbdLD6#k7E=D2ljyVc@NB*VTJ+sQf2o9CM^742&4-OjLqk8P%nQ zV6RGmOQSEFj~?PU-xE^$V2VQ9aYWd8a$CP&eL@^AVD|C7tsMGHNJt{$aENTj|E9p` z2l0C#FnTFq**n1r8-LIWw$F>H97tUi|sJ19f?Vd>a(wJU!A+_kn_H;FShgk>+-MQ z-6ZFzJ59}|6c2kKS8kwfsC-ft0wFC1#Uj^XSx{DYn}f*2G-YHa^-7f7_@bh&ZrbE1 zRD+5a-3khNK=Jzav5-zQ;u-;o4ERfiELE#x2M~19aDqZyKO%Mixw| zm%8I4?3|(rb%>Cgif{}oJ_kSwznE{F=tQ~B%Y^MR*nXm z$G)-N%l#+ws?9gU7)uptbNf1$X2qyv>>ICL2It-nZp*{+mNGW?YtXeq?7gBe&XQfT zz8U~)*@>_}pFu!BQWh+*Fi$YI6!WPvqKhHLy^GljMP0PlFDuac!DW*;{p9T8RVnzh zBXkdFSJq7LiJJ%i#v|tn0XrR&0VJzAY)XI#wiAO{P9RPtHc*qTDCx_WlnvV46Ssfl z^7EB3*tY?U^ybXhZ@U8K_otLwT4ts^EMtJxLsAUFE(?!R467=HQ)WPd-2+}*RPa1N z5V|zLTaZx32SFi-Be!BAFd*Oq*y`Y_!fFPFZBWdJ{HidH1us05*ZzULhC;PG$Q^$I zifVW^0sn-T&-}`YKXkeRK`k_JKnK=548rfQb&>TJKb#ukXY4nbD9 zaK_yKA9w@N49K3$sa2jg*CebKXX4k;n|S~6hlbmoojy1GzV3cfKRP5Ew;ZY?NwOie zi?CbU{V1B59}06#O|$237_|*FL*JZlKIMyIeU~QbET80XZ~a za|eFa&CLzmc>0EhpeqysjS&VG7RZde0d@#`YShCh&G}p zkAA3p-I94T$&x`5J+*-$rCr8t+By_^?eSX%s`Gha{niGdcrQC@KdMmR9R4EWoEA;37HJL83AkxEnz z4AtBGbZt6g$U1;~3&~pxTf78QY|j2YcUl64@ma@W=J!Iluy<=8vZ|nly#CqG0Ja!q z{2*IicQ-c$gMpXgISs?hzqU9&K_nv)!duH&-65i+6YKyd6ac1(?5&0;!o^U^ELOzI zDkU`K$Cg<6r8e=lYQa@c-?02n9dhd_!378+5qZ=-(Qj1#W!mlv^G<=a3j8*IA-`Pl zEMNhSk!<_x!6A*VF7UiL6XD8VBV@U@#C)lqf-z!Klw24-3UvIEdgVpD9 zQ)RK((9n=9#}~4k!P>=DvjNQ|W>I5n_O{UGv%6W+TMS*E+m#ErknVs(juYD{1_?Dh z@IHs@;kOjNTQ&{Wr`d!qK$4%0m*(g9eDmt;>e7dG05Ihe$TNf^N-FY=uB~|1H~IJP zZ`};h&D*&qQH)`}rIc4}%i$V-WsTBE?T!90;J^Q}KOMW<4JRrW6OJsyBGs|*caPB; z=aRJ&r#A;KwSPI4!&~)=pO6ZA@Bx|XRI3GxfK+FI%%LbvM(%Zdr=AcP$sijq#@vq2&h)R*3aj5~{aVmh;27!Z{CWVI^FG~Od{%-q$OS;^v=nnvcjgK1 zg+L01p`T$5#6jXmH8t@0=Exf0QP$g@oY#-v zhaU=mH-x61FR>8Bu0Jo*Nq|}`@XkWuEL_~xnR>yOj@!?Uc;mbx0~Iy-75^wD`bM}n zDXwmcH0%2bfq@0C)L%L+_|$T(<$U8y$7=N+{4ftb{rlu&iwK$pF8HQ`M zIBH#vpyKEN*oyPdipduL*k3W_zM}Aiu(}SIPvMsR8%`w)pUAQz0hGh9L&;iTzY2t$ zgx?$ah%#C@#9%T01Q|74)9ygtTJyM(>rX?$AR_AvtbF*;eE~ZpFg8CSD*{NZ-;O(B z18a!R7FfM(PIq;n1$Qoooq+(7z~VR!Fd=&wMzztw7+tZb&Lu>N=ikM!UD4P_X%l34 z6D|(+D|tzZIb3-EyMqz;vJm1fh6&~8j~}zHZ`2jNHYX~=;T^j}UqJ2Q1W8nP8VY+O zw3`>Zi}WA9jTnG$<7a8Ur{^;THVgA%^p{{`ATz%bu4ze2995hLxQS+bVQO#fOzgufYomFhzvJ+_2~S8^AV; zm{N#net49-sCL7Qo?kbuFP*}i05|Gf*a=0BudRYTUgT}RqJP?S_SP3H$t_2ID9H(J zD;%ck{?+5|d329Uv*QTv5sYdqS37R)=_=((*&EBg$focoQwk*+Ne^ycQK0Y7m0%d^ z7sbi>it*xhilV@a{`Y0B_-k!xafRJ?4WhU1+Z$9c7Z9DX3cO5|fm0>)@e6OM2#rsd zDMJF<@89b-R|I9Mp=Z4nl@l2Io0^u^93betum1qozi2GeYjPQeV}@e&*!l+*&}vmM zl9Tx09fo+c+t;Dk`FeCgpfLyhtcr_|{KzeLX{{&T>)m-+xoCgAA6tK#NMIoUNK!OT z^bB65ih%j+o69^>`moB^yW~Ne$<(vKz*nPH@FZ|{&q=EO{^0(dal&`>-5|}l3~;6R zm0yn50P=ZLXeCxqV(L7Rp5B!!i~7Qyt#A;fdzn%gHuCdc@(1LhBIB4_{h>NuHYY(*cG7?XkDr+<8ImKFVr+yg7E~ zK90afHVi>Xbu-8yKzVNd7?o-BixMG(*A;>fSFa2vjs&S*V-pi5M8ix9UF^m$%gri(FP9$y7M|^ak7w%pDe-GDK4ckB)H_qt$#eYOU02>I=M@wl-_|3nNbdqUA zRyskTQV}oE+3f2j^*SK-Z9=zS)7)cxG0?LB=JeR*(75v%DsLpf)4R zQ@188*gbpN>07}VE|l3O<2PcWuGRHPp^a0YsIMjUXZ+T_PnQ-QA#cH_{E#EnVl@-+SJ3zCUKxEZ58$*!y|z z`?`LK#=g%;k;i0Iq7)@HHd|BifRlj|ku(pMFH3j)oHxG|7rJrD*cY;t4exD4+Pw%S z6PV;I*g(}D6f!Pn{ske4uUaf%sM9Y@)r{|G$(bf-@lBTN>M|b7{;_h9^D_}|kmY3b z`syMcpd!a3!A>hSh(bhUmzR&}28k)Dqu1W^hU^#vL&GyTH7{RUmwN@SO6(}u-KgMA zu;)Fhs#*OV=pN%`)A_E$3L>Uup}QS6cr;wPFt8BEF>l-hC7%u zX&p{!q=vcsF!p#R9rLXv3FWSG{7)nC!^f-nZ8yS81tH^quCCGk_j#H8V327mY9ka=(eMb`$~emEm|>la(0PO>)B5fc z!S1^UV~KBV>Kngn_$BnkesLpe_t}f-9)6L=jj;TB&3JbAo;z?6%~QuAV^6D1A7?O& zwO|`n%vf_DNiZU5d=7Ds5~?)5O{0*b5su5gkA;tKGXAB*Hor}s^lVUfB~hE3@!~6R zKu$Z;?vw69XY&^;_7f|(oW>8)KF+mN! zIS3x6Yf^Z~80l#@ap#C&qD`z%O1M6`>AP5;@EgNOjTfd&cwv*k#-e#24pv8DaHDmGnK%!^%4(ohg}!dUAXsxnl-oI11Z zgiAos4yh)$N@=AeCH=CmR-9Ovn3f?A5|IlR`m-Q5nYh}cABrHTNoO8YEp~~QcPRUk z@;N*~c}VhX#tm=V<&WdCJy4^!05@iD#TEPmq!Cv0aEb=ejzQ%wcJu3&1xE?l5Il)z954snyjJZ+Iz=UqV3yEokB4JR~B%#Yghc zP;?1yNw|Z3VNQY>q90Hz*!iBdUFB<4E;{f9?`|JwMNd)ruWb4lsrBdD-bp8%K4tyC zV=3ZNKc=E#XD?Z4XK6VJhHVX2rv!4&{wbTrMCb^(M(O47-z5OIrZHURh>%JEjUk-> z0XsGLK4DT}PBD>q1i#uRiim#TEulRcBJhl$$jD)PG8%x~com&R9>|%8IbBS86fi%0 z7H$9GbtAaMp~yBCkRNy(p{uzGX7eel%3{Y&HFyHdtgX46%DvXpV<91s|8lPxp5|gG zD~Iq?$c{3C;~oBhkQjNRD-|JH3n?SxziHBwlQG%Ljzb=FKRmTgz^iO#Ph>f^m;3XW zku*87yp_GmJ8O-MljJlZdS&5J;hOO7*I7;D=f9qhX*Ub*3W^QpiDGpf{B>8uYRDF@ zZ9?zRH%8KG+ipC2pm1~6e|tFmLSO6T$$%qoq7Ba2!ux07_)UUx%8$lOPoB&xc%3W9 zpJnx{YDIqLyWIKEXb2H=_aY_C9COYPGjOe%(f& z*n)yzZjC7grO}L-hHj|gyCZ%2@6uctFd64M^clN921rCG5Z$@VA6pH8J^w8YzB8hw&Sh;JQ@tb@TkbS z`0u`hEd(*h1_n|A8_?15GL1E>-*=68(K9nW9nMnysA52WAuM#sfe*$7T4v^8BdBI zVK~J648T1HOif&t<9nZ0Nn1`nL00iFSnQyR)-X%}{>N>yS=}p$E*dD-e9!X|!l7X% zL)FsOwxpsL*M!voPQ1MqT!n#38@)(A1y8oTtSk!n>7>Y9S||!W`{aVf4^|+gfpQD= z>wlR-a6LQ(NtyA%Cp^|hTsk=lCZ?~z&LMQSHeMH6F|2y>g}U`$vYDCxs|5f#xe4fD zd*Zo68$2$~T^cm&>)P7dN(?jmi9}|gx436Uxz=7SAyg5s<=MARV~yfVjm-Y_hB0>? z+EfXm#YQOo(QTN4OrhXgm9aLNfCE7j?w6PoJ=(Z@|F>pyk{@dv9CUlxB|}I$$A)ms z7^xJc*tM{8`BFu~P?Kn&x3LIX+51^K)1Q$S`#aW8uJxoXa2QRPhD=hcjIZX58~U>i4%HH-zlR zs3)bM;Ot|IyZV-uQ&9E6)`nR=0|g8zEiO!)?QZ`aOP|6?rgZ8^#Fr%qzd9Igzo2Awkq z%q+)?5b?u^985?f(zl_cGnHrn!)V*z@B@4Lt~VMQ@0?i)@bQU=cY#+Rjv+m`UjKBI|M`c_u|jSS!R>qwn3m)LxM+wiTZuiOkoQ7-Vn!PC zN3Qz`Z(Ow%6@?*e^qsx%9`mLnUm^%Q_{l=|Q=e`tcBJqHKQ7fz=mzeN+>V1nBF+7C>Lsl$1GmL zuw*gGBv&DV)lc-TlXcWfn~rSsQhdUJnA~T=Kw7X6hsWo=-OFR-nq9)mDJz*_lTz5E zAs3fd9;&hQy|DcUA`kJ%T19)al^eQ@x4`12M`)C)N6WQRp?LV`^N}+@Fa4#a;wxR% z76AHmkQT%dH4N(!v0jTFOZJW_VMftrlA0s$RVhe9p>0>_a^Qa_Sj@e z-$3}FowKbw3@kWAL|q^oE;|vuCh1Tp%@4knU#FDsZ+3f>d(8X*pl{;%TLti*K2m3{ zltD!irNGp2@#(M^^HAu4QbLw6P*;a~01S zD3aCtC$^omSqLC%pb370+0xW&xC8x8iZEP|iYhAplyylzBqkt`f-CAPr|M!U+=Y9e z)TH^!8~xoFBY&}{#Ky*cX_S1duGSZ{B408ufM=|4d3He9=MD_R6@RoJqkoJqD>A?qBKib2ijUBjg4tR z6WC_{37B9ourOTUYMAR7F(s{rA65@r=y zz7n;}uTfV5tr?>1Mx&`~H=@0&P#**FQ_wz{r&SpO7H0%f0Dc-CfHB4!y@YN-?G9j8 z_8@&JsQydD=d{%Uju;5ip@v=pD4fOmMUke%66<96tX%M;KJP6-oL^~KUyPp@^Yp#6 z;Cj?4`nj&ZwwK3GE&3qI=;aLhE2(1~PsuuLHM-Q_a)LLGzX{rk>#*N$3ntgMu28e0 zxcgS&#bLM}s9O$Xib@f6uP!?;x@rmb!2!^6c($6sra-5zDk>r2#+9JF)J3E0rs|-a zA(zt7pey^e!#^nK@CCgM1>Ka}n{2)nd$pugD8!+iS03K*--HUq#sFM>;?xR|p+vn~ z;>DI!o7&(~j}-dUcwZ%KuB4y&v`+Q2j4mCAf+p{hN=Zl8_D^m->VzsuQ?2@@wY?o`v-9&~PeY>myU*6t)H-l^ z)x^s#wX>K0fVI4%vvUEWfzx2%1Jdjv89%D9fdLgfbb_(F%bTr5aK;*=)^0u9=1V!+$SM_ZFHx7w)WNmgWq8{@-u`Dr3Ts zc%W(HDP_%19>FAZycIZyEGYYSw!^8ERX+AX`aD<5} zt7Zhmx}^B}sI4GmM3Bj(?Y`d%zc-oZsXk!Yd(QmeNb-jgSD??naaj?;{S9tZV&7k| z<05`L(CH&kWJIO~bn3$9IaP6ns`sT?#MZVrB@4G9T1`fp@ZLoDpHFbK{+i@l3ip8dzqgV-%!raNM`OI(e5!;9C=*>qUg!H|5{_E7b-f8_A2YKj7mbZ zt-D#oDrOW9w`S{KtkbJ}vug~GuI3v`sb4OY$;ckiAngddXc|nDdPO!`;|?EbCseE& zMTyXbiwhV<$gZyDP{%m%cwSbCbOjtMS)q(Lem%CXT|K-*~aX^I5v{-Dnan$Q4FH%%LKfO5XGRA$^X~p0_EqwLz=fb`- z;^Xb@?agqr@1zynj0d*>@mcOkF0;}fI53UQ!MSB(&M{Lj1cB~s@?GmQ(5NbTwj#~8 zm#wk6xf$Fqs=*j~1D}1Hqoa1rVKJ2~vcvY-w0%Dtz`Vnb<-7h%;C3IT$;7bL1563} z8+d@9E7wahcfP&v5d-iQggS90@vmncKe)ZW6?m*uX`MKCNHw5#k+mMQ2fVCb4)MQ0 zz2^-8>cc9vv0)C7kT-17*OzCIhzCXNCSRouo@1Xrnt(RTHX6SwmaS)yu4Rr&q~cg< zhVJj5&{BKId=3cUr&mT{;*#s4DL8q1Yz@+=wxb154t6@A!-b*r818Ur-9`YF01zXB)q(Ih?0XRkiaB5$5s8EFCG;e| zh=o5ujJJ><2L0bq6*y~jn_a)@F3Cd_(5lG(Sc^FTq1q!D)SbnQj$N) zk#x5cH&=wKSkWaLuatfTsQ*yHY7>i|3n{950FW#J*V7^Mphp!-FSJ^RJ=B`JeM>BB zDGwfv)dE{JZjx0*#cCwlZ(dzq(7%2e<>=BmCa#BAZQ&d6+|cJ$fGF8j#*tjeXh}~_E8M{ zhmfK`ybdwXh$*Jg*-pc^u&O8->q@DhR*_O{vx+HJO6@Mnd2b3%hjpdRon|;ff!<#n zyFMr`qB){JY;6sS!EKrHW?Wu+C;BfZ5(pKZ>_7J1{yTZObT|GRK znWskIVP&Q2MFPe``kcBfMbUnrDpk>< zyZ5Vd>$TsWrf=j$b5;G%BY=eoIn4&7ySe?z$(mLlYwEon%hM1;khIWC_DUbNJ&1*+ zGtL>6)q^WvL?)ZK!&?Iztw9h5mDS9I!vsa8n5d}7%P~{i8310@9Zy;Ss|w^2WXqW@ zG<}|S+pW)gQ|to_2BPa4yx+RFK#Yk1m!NPNVwDisDZp;U#e;9|S*9BdF^GbBNJD*b z%0)#Dr@Q@@c%`Ce)t$E$zp!qM4>ZP2KE}D@cbV#^-_BpQ-w%A4u{9EW%PL&Z4#62) zX{xW~aRAm=wqZPhzgTN|_elXgE$zbDwEC*Bc#(`QTFF?~Lot+GG|cCiqZPN@WzRo9 zRY~#>@5}*3Ps#fQQQ0B!%x|ij8MQ3!s`UJKMGA4O?7sW(JQ7dif1U06GS^7UtsBKe zDGwAbyS4K2QkFk6a3VL1e5wcx?!1WZiI(hA%~~_Ot%ZG1@n$- zFZIq9L<+2r6(+B1g5D~H^PZOlnub73VxmUH45Z;Qrxo{_81V2FcmUq}%0u@J18Ri2-(_953t)>xM=EGsujvL^0Q){*%$>e>upIiN zlprP4r$ zJ;jypSbhNpRnn6WP;iS-P&BP^soV3A02HsRsTnBtx~VISo&fvo{!d&x)wmD#CDql3beX89doId%bt#%?zql!OifKW;4Fr?BXfRk zpqZX8uKxWCu&g9FF^gH7VaVHeb|-%EcX|2oiRu1gt0eiK(RV;=d#>hnF*bJ@Na}ji z&czE~d|qp_*Ac|}XY%m>Ge@Z&JjMYg-Zr^K#xhi2^^3TKs6wMctH~5l2}>e~HyS;fcTODi~y(<2*4|Oe!TRQcrSe zia+wO4k732(b zcgeYY66b9Qc|x!N=vXo3x0iD(cCP_lSF(Wxdndl;cG7qHGHbt_V`6=qw|K0ILcxK7 zixAYZ3f}!Tm_Eh7%YKzkq<@KP-}>qO@tuEyD9(t)e|`0KSTVI%>2J|qo6 zCjd1e_6V37Lj!F0Wh>aAL}qi2$e_&Yosx*(4%vOG*A2V3K$@AJlhbudf`^BEy1_!X zw<3*`JBkL&Ok44EL5*#XIg;LkO_&ZQN;CBuhgJ%Sajon2C4ZgtuxOODur`cs(gG@v zP%lF>3>=&Q!2Vu$hya6#zCI;PV=!7R3EmIFDI7y^riexQkQ<~I-E+8VxaDe&1Vts^ z!lx9!k^{+P0teRQo|Q;%W_?4S$lcq*=zHAr!MF5@K5lwr%G=FaeEjm!ke+wuzi@o2 z4$n%!-{YJw{X9z;!=`7*t453QPxyQUdxdmROWN+kB;$TOVd|Mw(LkrlL(VYeq7Jg*xZ_ts#pe=~^HR#Wvb z;X{^cCzF^Ogz&x|6o4bvu3^y`R6|=wJ61>GYVP5`zsubtXUID=$2Tgr3<7~R-15*Y!vaux z0=EbIV)Ko5)GM{`fq2B^?(_W)03}kB>)Zdxu~9`*AIo5O=+EUZrrh}JRJ#rf94r}d zW)cS)>7!A#nGDhaexN^F=K}iDW_I#wvIC>6$s|zI!6+3sQgyJLabHL0;@`TV9AEa8 zl1GKZ_7A`4W-!7KU&%zhCQy%^`_HD$=I>Cx1!1`G{0CNonG{|XxMG5XZH;rWU6vF; zwb8wDK%52x3An@CJR;QDJ6yD`{tO7XZPTVt$xfqSx19Llzs2{KUKaa>B+T@33XLYw z|3s$<$@u}#HR&)fp&3%l9lh&u)Y2{;p5Eu|5=x_&?^KW)$(jtUFAvQQrEr1-?KR9@$ zmwV0#;^JYr0CLo4)%Q8Er_5JW&G*0&rnUSa|i}w(;dv(}9wg&5px6qYcKB(@nquRW_ zr}gudMLZ>Li_fE&PCe3hd1NRu%EDx&dG7J>J-jMR61citHNLBPj`7Fo(e{zSpY&{M z6yqrj($3LRQw3d@6}+XovCSjpfqPVSQwMQ>G)&i2La7wuz74sg^U1$?-qO}aB%UDW zl+*9`vU|mDVgHm1C34}&HQ1C13%*7`ZT#+Qn^C zDiZ@5Rioau{PjJNf4RP(K)w&}ds4t!lr(pB64lo_-Z{XSy}^uekt2od2E?ad_Y z+yL^K(mA!NikGHm0M2cQBnSt^KKE+y`<*>F&PO{>V#|GVy5&!&O-dW8Cuy+EdN$R7 ze^@SNW1G$#1$50Hp(#8j9`#9MCEu?zx+xmmaN4?av+BD08GAig9|+b`e_o#0_wHj%q0rx6 zw|4fj%)|~3%N8f{7QCBXQm4+VtvAmZZyfOMD5nM#wGJ6}Jm*(au_~Tl;;B^^?0glQ zC^fc*+UGCR6nAK$du`U3y-PBE&evE?bH~l-?rZ7QXLghP6{MD4L{ir-c;P8EZUp@g zcF%TZQb>bbe$KlOEm85NDf0{TC;y7v^;!|~8ZV2-)T@v6Noe>vX~=uCzdh%|CR?PV z02%1`;-wp{B;@2a2P^y#JrIjs>5Q+@v+9-<{+ zl>#mes0OI#0^I^&YPg~8&47HGnVCJ)6>dd00E%c|R7+P^9`336(m7b9Q(uA61ekQt zR4_0y8p81cwW5SS?I2zZ0CdY6O>?+!d8k0DaK%ExHnR^`TihD8ow3#f zsn8u?6~7`lCmK~^h?Dxr!N1*v8fr2sBPM(tc<-f*9Q!C+n5zbzS8K6+FUFsr4sJjE z2v*#H=JHU~)MG-h9&PnKd76p>qt z)v@%?S8C8MPyxA9vd_UvYUcCNrF#f>UdM;(Mt{2i_S_Zhv(U$EKEU^1M2mbCdP{fr z&cy4Fp}$Dk417hdyIi_#A(%MWVa0Ym&NOLXnJ8$rb@S-^P}sJr_*A!tvRY0~<87mU z(`wHeu2{TFtE&*jZ3Bel6!8~`sZ2DVE2^uvgYDOOE#=F%7h~LiyJqLj1#3L16jJ?p z07)$?D+?J+W%YKk!N_%m!_K^Z(s3a_$tt&OX>k$E3WM@LP~QZj=SZNQ?gS|o5a8k2 z4oVP!w&GL2>!<%}0miFr)Arrb`;GO*Xm^V#DB5sR!anej_#uaEbz37dzQDla3w@7Q zqHYh%#eO1QhpaYAF4qHxoz>ta_vGX7L@HB`DGFc%-bc6$NXCP(7&AA zJ!hiX7;+tOH4=tVhxzro82#W-^qU2d4MDyEfPZ z&$?QBwvf7PddI>KtK} zUYGk!j5%h0(yRB`J~u4ee79eoaxHw5k+XD6HPEK1b_&V-NY*VlEehyBf&m$9xPI33 z8U2-RuTK`1J|igQa9nq$tAVuziSK{d{3V!}hJ$`M$05&km#>Y1hD;88tQw^z;qmd^ zFlZq3XaC_*f%`|)U&HE3%g>LHoFxl-09EiaJ>3>)DxkX%1*gA#kP{#)tnTul8=*FI z)&O!YgZ3Yc@t*NS0kPUg#vcsV>6YG{Qg#2qtLJbX##tinF=E&FvG32Sr=L3*G3m2v z?^Rxu8QDDka_@J|`!386Z|4RTk6kMFPmD>g4x&QAz=!sYo57;njj)IK-}*=o%=TQ^ zgM755A6dws0|kf^{6*92b(e>%l-%0ON8ZO_JbV&Aq9#B3Ud1dhC)%&#${FDql@gH(n_a@~OM%2e1vcG$ZfKRR5pIuOx8XFUGk(v{w z@~4KR3i7R_n!Wh7=N;Xj9foFUX2lriA0chTTPIhsF)21Oy6_&PjBTLOksE_y@Jfvc z?e65Q!F7kBTy@s%E46%gE~`l+nLC=?*2)*3w{DmZ2t4Z%%D-$iW2IUUz@IYhSh+Y}Rk4IgtuA zx}u2HAw~aHc{aV89IqbK5lOf}oRdyfK+9^xY&|J%UYMG; z2RZgMFce@L!v#JXk_LiJUt5kmp<`R_#CV+qTj#^&l~Lg7q5EG!u9bgZaz_k|1G z6oW4Xez@FW719wG|80M{?bROfVuLQpZQE;IYyW9KQ^65K$iu?b04)>6$wM!VgPtdS z12pz^4KaK;>jE7TCMFrXg@vEK;o4X-AAO$oIN}iJuZwwLBh(BaE1EE$#1-`ej}cBfg-6D7WE7aneQpGU^Lr!)1Hz#3lC#NQI=sf}FpubOvx z+WJ#ED3&)?>Me0C7TaRkh*yhV=JF8hbH5JxfPaLx^fuAt6;JyVh!KbCmgA+n!#U2@x^4sl)aM5my{YB#dvzDj zmi!W5iADv#X~!yX$$9gF?KF+LjJg zzV2Oz<;mD2dLiCNqKh5LrNO;Hn*NzZ*c1g>chy*!xF`#s}= zEp%5g8yh0J`^bfNX|B2o-_~C5ZM$k>^|I%waL_Yu+XVhlI9x|gv3vBsS{p2pzMfa- zak^c|XNHg~ekDnJEv|`JQemU$Nft^56R%-u3d~Xn+!au!hXZgQq`pPQ z-S{<5+g-e?39u&+zp1b!1l?6;c6I>pSFn>JG}j=9fRojBYn%-f&7EMy7X#-)?T6jJ zf8%ZbhD(vbB*tOfg@7OsEh;Hr$UuA%84-~>Z290EPbE*NVcxqi@ssWZqdcv0f80vJ8eHT^eGFrzG6e*}d zQE*?1WX&E58;1{LFNM3_Sb~{e>&-OgsHd1|b&5qZgg@MRe0=ZWm*$`HF_a2#t7oi1 zS=a+p-@Y?Hczoj8R7Wi|b$e;L_@E8U&d%&w{=;Qspp1QOnUs@}wwe1> z{6+3blZ;jF6soc$Bwm2&{}w2e{%uV}!bNCZyUisgV)J|f2zTHG{#m&3*3~gk2zz)4 zXjNFUb?CjOo1ybF*Xsg95LmxU1WQ=UstTxcS2&TaYu4%b9QM{39Mou^Rx@^GQ>Qz+ zKn^ej*4-y_-xGm^jaJyho%dS_%CB_8PM$98fR4>AVmI}4w7gtZVA;^+a$}~p@}06& zxlSGyO-dtah*xn;dD1gK?Q?Wr7rie@yvzU0jIO?+LyAWacHDS@^YVmW#BX z{F%2xTOGfCdQ7H5kVCc_)F{+ixA8tl_l#Cx(I7y9xM|eu60_EkDo6Qt@UKU28TJ_G zAI_&cwOKW-RwiIF-O)v9Kx#{>x>t0!>fvK2s?a&vvB^&tAKBkhDq>6{(4t@ zc3i!uV__ONA>>PIgK2GZ#fF(wvgZP+=}9HVyG68~RHd^Tzq?w!Rxn*mE5*Vmny#Zi zgugge-LNP7n;*^Syj@|P=e4Ik&AHpH+;lv1pZS%p;PoowWpXC5%MC}^vyV#`*+RDl zZFQdgsT2Qa{HvOBYqnPU_+zd7;}9p!lB{S*FR-5HM$`{NZF z{N?|!Qnbid2xe-q;-h{eM<$!<%*%Kf-kmy{s@!}h#R;)k4^BO~_+RT0O$8y2r#mSj zIIPt^S=%GoxQO%~-LCvPQ)5*vOUu0QSqRMsev+G?>h}p%E%@8SK0|LbAA&50=mFbm zZ4e@Hfb1MW4uSRW6|k*9Sl*=oj~|>#pmGTYi5B=kz>kIScZ2@uF%axyIv+@(NPYoQ z^7TPJ%abS%Dtg3m2KYWysO-Vq5f&eBp=7NQ?v)y1U@tIWbN7iQhY`+%PU+0UQ*`rCynzEuVVMliNbeFcGq#ZoKiodIFPy*-q~Z!9|Uv_Lg+ zX=&+-E9K4{2W^rRn=SQ_Ee{C*kwPoEVAq%X<%FLujhI$)`m6K@Q; z^(c(~HpDDB1Mw03K8S!70DUkI8AQDbW}IA)ZM;n1@44@W0^29aW}c?6m7ld7?sAoX zZbn*0x~P+8Mg!;=BWi8t8rm{K z*j*<7*pQ#Owuj`)p02nruf8b@U5lh@;CG=Ax&z}q40DLoH(?vqAzdGp)wC^Mwg7&k z4lD#WZOD3OpEUn?1{6i#+f-&gr2OK(ni)^>G(e8~5fT(MtT|a09Wsg17&XLU?-ia5PT8}7t9jZ+Bic4~Id%)t?w?jeOm zkc^oOVUMqy?t-2Kqs!*?;i-`%S);1~dM3@7JKHn7sz=U9u&dHuH!_mBr}@grZ} zbDkI1Nk%%5k5Vp3yTe0}d~i;Ky5srCmyUh!pu76X1(M|ThP%VGUtmT#hf7Hn@rQ=% zr{jAEfnS%Veo9We&-pd&6mbdXpG;kIKGu5kSfBoys?RMfRKD}} z;)OUWwy9pnH(5`SV_L(it-3xdtuJLNhktPG_d{I2BZuO@fBom|YxQQ~rGATk46AeD z1El@-rq?n%o1c1Pgy(Wsv5z;^T`Z$!)W?cEjW7d#UhejnyuY{|QcjYtfAa9@N#%gu z^0Qa?NAI%TKGkvbQ`AU3Jn`c9rN4G1UUj;Qx{{~A8tLgk%POGLlSDl*R2CW-SZHSb zZgDRh1}Ocu6jg=8e>IP+T~0NXnA)P!lDN-$Z?q&Pw}<1FQISKGuYNzBCLOMt_xloe zvGer$u#$ns^F3x`!rs%QNOo$3a(uENlXP%;U_jW(se+c_(2CO2EP2b})9Jc!ok~VV z#&`d*qs_5Wi!l}uC!&;{bLMtEkF$JVJJS|nsh_!ESB=;RJ0ob}eFQNBWUwN-oFT02 zwX$+^ zqd)0fr|f41mJ;rw)RQ|IMeL$MVshptW=Daux($g4U%E{wH>xe5CL$D-rqse_v;h*X zIT0Fk;f_iDcHhDH3<9bJNb=yS7jV4$-SxpFT~0n1hw^T@j37NdeZ0G&vC<+qZJ&+w z05_)TBSoOVT)08Z)U=73v02ziW~MsaMPmz88X&!}dV}oLGVG<#*3bksU|NRC&%Tu1 zM@S3{x7hV7z|I7#d5Swf_zi*3^8A@5hhaTkH5kgHva3Zg)K1ONwo=n^UyrweA`N+v zd6ho0jD6V+(4ohiW?|%Uv|RZYbV-Z$e|u6gG9;(STb(URC!j?8c*=LTxSh=K{NH+p zXI6~rHX}5{Ks`<=c%-(!(P_nIHS|86q{26rrPAToNi;_2{}hC-MxqM%^(nm?J5J>I zsm&)=jw6#X2~!oyPAWsIl9H0Fox8eWbZ)yEuwr3Y+;p#Q<+)>0OU-M=TlaGK{)Rx* zg(NgMmzws|!Hok_K-r;k5NGtyN-|gSjLpskr;^o32MVv|_c?BiNXLhc`uV7#UhiD# zV|#WcGvuE7O!{4^3b-oH(C9>KS)_X&dw|1$j>C)XA&~&*4Y=Pj#1-F3qHxYeBU?>yPsv{+xRjdK96) zd0uIg-v93H(sg~>87`N{^vkQ8SIbQCg^iNqeFg_ZVkG(3J_5i;R8wE=oDyt~F|Fp) z7yeusWz%-(zaTNYEsDe7yx^GOsMQ&~+Jb{kCL*^R&R@FlWC2auq4+Vk7+>hZnd7EL z{j%zgpec1@^`4B0`f1Wwk@pG5?mG5}V0^PiA|H;)i=dQ74RK>xerdFnZJB0aS!P+? z>lbcc8;n?F$ppxgNp^Wg^|lsH+;82hw-`~lsh$Y0+BKrXz zeh>tKCT+>C8j8v&L3Ix*6ELi?C?}w^)(wakRcW)};Cf8GTU}WJ zpYkhUlJbdz6cFq*?oh?1?Kr9mEFlPmrJ>;nbPlk9v4Q9U)Cw@&{Dgveh(_{(*P0zn z+Pd!h62KZE^vKZsgV5xH0bl@N7@*ubKrD=~4e8XX$xfE1M??#uPhp50Y>f0U*K3Wd zu!alKqZ;WaE)-0V4X`vvWj<2>p`c>nV%((VEP;Mmx!l-h3t-p*IpsjwaKOp&n_z}M)wt`82TO+syF{?g_nHVmlnVq$aThn z?zIJQPQLk{96?Bc^JJ|`Lauh-Kc8SQ#$GBD$Nk@ov znhR+p{43wh+dYj8)Dpez+=DCi-F!ZlwSz~3d*+j%^!c7q@Kp`heBL4x=zJ);0R)`Q zQ+7j5qa#wpyW>O13!PFuoiMs6JV8n>bWO zFP09_6#DxSbz6K)ME&rzXKJnV1KQ0KK@4A9vWM*_W5sjMbLg2`<~Sps659;YK2LZ; zLcd=9#fZmT#8aqK|MC{pw`8bF&g^?61H{SEet4qk{0h>JOPB#ze7=57gC?@XUt(hL zQHlG=XIazoE zQ4cwXEqNKnL}g`Bl;|4zq>S@DoVx!goSxoT(=OHSu%8G}Ql${YiLvNU>lBvEU)wWy zow>{k6r;F(u}*U_7-ccH5L_MZZ}@S%B*gZF^J|a(o%{=NGgGC0(hgS1nO|QkP3=^> z?ULeZCn{f3FUy_JoqrH4$TmJPeX-}R+ABogGE6BLq;LAcQjds!U{R+lewUQ8cK-hM z{eb2v-M=}q)~1`rg{23hjMC8&n3$NK{9KQT(fr<<$lPZeIfy=4b|<_yh1Vcko8%;3 zI=sFNj(oxFcP7ThY+l!wKXR5#Vc{16%6ne<8`{kTn0=jgXL|u$c@IJ@IyxL|Y;T~c z>guK`n2CvqoLvAmIs9%~i7nm6AQ!U`yb>vu?a{LfGDcQnP8i;sW`{z3dq<8Uqal+}QktY4QpP z-2d&&#Dm!wfSUktM_b9z{h*F>;JW9d9Rb1&^S?VGYDnsI{>DBU&d+O=*xyN8QvPIb zQK+{xt}UL?*@?}RaXwiayo2`?EpO_vBArkEqt2QlZ!Ut7^kE3PNeecYDjXCHV257z0-mM>~xCNpG5zwFf0aLH3vs8~s1(xS<_ z`>o2vSeYu5d36E`)(q2qe*y7*$5StmZ_1Jj;Xi{s)`0dU$n1_k7|H$$8YqmWU5Ha# zflL{WiHeRD)hS`R`^FaG!tt#jEe0s1d^zi3>ZL)GNPcL?oVh*E^BGX$f-cT-Buy%m z4D1!!THJ~KWqpO3JIN(d6~pU4YihoqpPzs1kCSJ3DA@goZT;UXFV@cGIu-?e`_v4p z=+Maz$VTjXSDumd-oLz*WD=)w=G>5KY-MJ@KEwLWxbsQ%#wK*Gl&BKys~OV2Di(#| zIMBhGw0a^|%dK3JI*zqTmir`i&7Szv7t@0onrHNHCI;^I@zRGckrx_%qA1X8Xsfp( z;Bj5#k&wo^)9x+mPP{6?u-f>b>0`sGdqQIn`X|!l{sR;D3jAw5hWs}{yG}g&R@RRn zFlE6Cs-bD#S~ncKzZh>=QG>Gm0SZ9E0Z-PwQmUWBIh zf3j=5S2{(_*wy)O*wwwR2(ITgRh76yODQCB z+=L-KO-YU^P?|ZEX2J0pQ?M;3i)~tSAk9Pk?Mu`YN@h-O zhEJAnI6EJrBr@vGdspk(^}SNA>M;KuB|(IuRxfLNNZ}b5zs7wsuGHvLd${{IQdV!N zp5XdRLB?)n$UmM!%)}5&gBdzDE&GJ;3ezKgylZiGC5;%Lw$H65kIJaNS6WTAQHSyy zgpt#umu#$0WeI?>`WDu|ch>=i9buG^Pljk#0DUI#Ler2*1m=9(wE;?9x9#VMl@^@l z^5BjFpELo%n|q3PD1EP;^QH|MWm<8=(`MErz0*+sWTTaq?>O1h_gVgwwt*+Xf z<}0j@6HnOT_^ZhBoDsrAH(+TfcqhhNN1Pvk_niQY&lin?)ZHLim{E|xuw98h* z18y8)FPL0qQk?khzWckT-oY{EP*DgRtVaN3AyyTksR!lx%T?R7R#QtN`JXnD3yCvF zdQtN!=-3;iy}~I&m8q-&`h{vC%*T4G)wB3{OuC-OsKhPI!z}Xy@r}j@%0UcI6S@<} z1SI1O**`2#OwrE^=(a}CXC8J5%^HqgV_9-UIdWXMO0o|1f&3DEmFaof^?^5eR~Tt%VzqXoI=Ip^ z=a1EOuTTpcYXeWzui}weucPtwl3ZmaL!uj7$-!lk+BE83bS^OK>U4jsXI!{vMcww@ z*Ilhu=b6>0e7)AiiBNV1H>@$1;H6`3-T55xxuc9D%t0ZRIK75T!giit7aU&whhBPJ zT_-|sR~rBBDgNH>ncFqm!i%FnH>7r(CO#|L+vWc-_V}LerBp+QON`6Ok&sABCH;es zCS8I|DT8djd8H~c2ajLqdiYPwqQ~)7qqqs-ZyfYm<{oToU*L8ux`Jx~e_svi)zK-wmxEWd?h6GV0>q#XlV0_y3Hg_z**4hQuuc$ugrzs^IV z>rHaK1!ho=<{T@<{Xp%6*W$<(2Axq1Zvy-y1MwG_A12CmvbcI`YN};MY9uPJ8fEq| z)VgdK8E3?N*C1?XPpgY^zRmobQ%dD+lw3F^OX_^^*%h06yiK8on+a!r)|DV8rrWV@ ztW7?=%@e!le=hXl2SL4m->1_^wAN`G3nJ7Tejaa(q66*N%NqQ`5mpU z8vwr_DESSbiM0xt|9x2hsG#T}U$a~kQj}pb^Mz){M-XW4yb`SrU14c5R=0k^(s)ba z^)$YUQ411^my0zy{)SUxWPLGP@%y&!lgEL-Z`QtrJ)R+n3M~j~zcv4%M`6?e|M~Z` z>Y+uY;4N=@B#nDiA%Oml*0~y$(A$_4%O%Aaaop;+58?Jv3(ceTKZ$X(I=EmBK|YrY z!d(;<2QB*Z6wNvkB?$Z|?Wr_jkYZ&l%?oj)SxJT5Hbv%qO^*_97^906BKdA>$UX4wv`r;Z?|O z=GV5>-BSKFxsiKE^WC$b6lg#lrl-&Q;Y{i2RCtI)Dyd284J7Zt)mTlSdY)Y}_VVAJloJ5c%`%30m*`S?_Zf5*A)-~0}L*0(u}tKf=G3MzO+GKz9r zzP&|30aXy}V_}h{FZaS}=DsWn(+to0g(=I{vC7X3h4Hz+gS%f3v6H?=Vj%DoCrmW9 z>mKW8?|m{7X0yB^Z|8?Qb#XLJ!!Rc&fv86k5|2w)znt!>@b#c;xj5FMG?QlR7(S!U zmZ>n^!aS9ah?e)p_IaDGX0xMcC2yzx=bz5^tun{D!bE9>ioFjcjn_1t#QaSVQ&`R} zddX#obnNd`0&?dYk41=Thy{Mn$2m3;NlZtghEtVRDKad^^Xpg|3WimU2qBnB zc#>@+QIgOsiA9^LE_9^DsvxIJ!W#n2$?}ZGHo0_w`w-+FQ?~D`Ago1$$i?D@qW=Mdv09` z)+Co;;~384(C2i{`%HSJhePpR=JUW;VOR7S9fQ1sgtSNb65O!-MTPenOh@&k&{wGi2K~jtM)4z zw1}BAGOzGIv)q%B1ODsCHcFl9*X>9E@*rLsdORYKCMbjX z*^7lXvQ#-QD#+OVK5GBn@EaZ>VH1R{f)PDh{&IABnhk$CsLE_7tHi-0EDVQ$Y6i$R zO?er<`JTR*wb5=dx4|dGt5^Cn(Z%kcj?l<3H+JNTarRIc_+4jacE%lD5 z%CJri)sE11=54L(G~2gb3f;U`ive&Tn{G+B`a50xpSQf837sSU!mn0BMli|Ast|B39Rv!%Y$dSdQoQ z?0ebe6(Pa#EdW+!UVMq=@p)JicNi{^U>XEw9>qqUvE!sDY^Sof8NewJYuJ)qd`O7{ zvd9~>-Ew}abA_Ph*V3@=^(&bikenkubp-Ax!XJ7(8vl;npJioK&{iEvQ|(g;wb>-4 zVP7OArp3erfZ7ispkp7y!3|7)ETE4WR5*Y9X;R|byY|%Vw42@v$*q$f0ZHMoIy484 zIxG^CjK(1O2aFH2<+#h52R_6-0W(oh@`kT2ek<1toMtX5g^c(89ZnhFyBYV+MQu9k zTO#Sjr}fjvcJ)@@4+%15@OqbqMDv=BEq<8*6Fc}tu`+x;YyYJ&SfqhCu_|-X%ofB3 zzn&%1R|vIrbSUrmFPM!*gompm&PeLZ{nbbM2_pEBMqo7UpHb8}O$KvBL~RY8(8>N> z{qjgSR<@ZSG5kBoxXhL=Im@T2^ScUs2)}0(h~>3quzDl{dac3_@hbw9O%6i~4${D4 zMJR&P4XEdPf4MtBZZVkpqYatS-z9MJzq_v7hpERBj-TyN{xwj-I)m~8QVlHNPy!SD z7JM?ou)70uY74ONL5uE}y3@iT+5<8pKAP3}qRoE58^alr1i-wC8B(&)4w}M1i9oyb zqSK+l(JSWt``2*cvf%ilGfQGJGNOU{09M|zpqT+7jGNap)Oag~d-M%jT3m#}*;dev zl#kDaMV)M7m2b0dkN>g03fjks+p1*KJ|op5Lyk@f zGnqT^k;;|@jNkRSbr4A_s`ewhUe8oofQQGKfQQ?YJN7_~JE{Ftl$8|&)Dw=_$$4I^ zp23IfthHeV6>Kx9vLTyxa1(GkeA$_k6 ze$H}Pto$D7u@Z}51GHT55Y7Vhs_f<_4u@Y3^s$4(Bk8tE39T76MCt$?lI8k!e48J%u$@-}upTYb0M`Y2_{SDN z$bi&?w#wH=*lG z6-ywiE9oiOHC9u8l}6F#FaJX8J`)Uw6**6Jpvio`(~c)77pUwMF7Idi_*F_Wm^7DbPG(BKB5?G~%mg z+_tv0$thAZMN_)yViVe)s_G8L8xuRq9CnwEum3G~$}lopUhHaXyBA%l|IJo`agCq! z8WmN(kMg_yy4!<#C-6CEmz6!z0+a19z|<$r1JR+8zwK{YHov___l4-H@m=Vl$$zkc zyY{PJi~vXG-5my~t=vDH?fQ+VI{0r^KFpD0$=3X3dLbOVAlu}XDPg+5A)3bR1zzuf ze26_esv*sA^R27w#4RUtj--E%g;Skl2VYCVm|CU?auP0fbX8lnJ1}Lo4os9Yw74kX zC`|s#^#4^-f}fQr%}h|8?h?Qgl+7)%pn*`7TaMYPUH%vD=J`BZB8j$G-l?e?PMY)? zUgF-HjPB{(y3}X?a{%j|XzTE^Xc1E$^F)YRq*W?`zyiq{JUn)7v{?M~P;Nna)C{{? z08*~Nk;Y&RbMHH_YV3!JNrihDh|jb$ak|6}fSzbN1io{o8Q(-nM>P zzdP&R+w-tar93H$ktqINqvfprI`=nsoj#_aT(}Q2V2DY#qpwD{+auER^zKuUq~x{j zTP(Xj(|=|@^JUqTqusvM%Pv{H!mvihys&*E7nNBJ6RkUIeWu0Dzc~w-Xx&u`NS0oUu`f%CF)cgfv^|wtGJ3Mi4dhoW2`prlt-7 zF442G)>E~g`Zq6{PRS`Lu_01`eCW(HbmlPf(sZ`92eV^~_rg6{t z%pMx)Chu23(#(U$Tx`o2>ser;_eLjR_OqtxA=tWQ3hXQ+7f)`jzI_H(`XE^oOYg^K zqU;~2X1Vn$y60L}TFKLMV|*L4SNTWxx#B56tO=*wXe*qJP@rZB zGp%mCdf}4VfAZ+Dwdnsmi2>7?z7#5;Jxm#z-^I7j!oA4y{%GFz^vshrJf{%VXIVZT zlb#+0FC&N(!ENWEnYg4RO+!NisGpSA={p=vB9O zIt1r|l5md_2Q0I0K{gP8c=_}xDJkJ#-NExVkX1R@b^%AyiX(2Sk;o5Y(zL=vE&)m2 z+R~IIJm$5B&z5oLCRT534}_Ml58=*aj5FYoA~YG3!zQtCNh+*FQwxs+yhu8#llI%5 z#)KAr{W?h6oT^FH0bawd?D>`duISi3o$3^sQ>|8?3XDkVvMG9*kqK@0dSP zoT?ChZ^p{kO;On~Pv(< zm`q#1Mdm-Q8ij8dY9$e3af5TaZ1jF}K2p>=_vF4%NP{dppW`l^wp_xUy9w*JX9;ZQ z{>~Z>RoB_}1@66v<}?~aJ-_1DiGH?at7q-r+_HQg=Mf2!Yb#4ie7883@dtftHigW5 z$6uT_?J}U~8KN(jw#t4tjca2(mhyC|BlLcPX`4>J_fOb7Qp#^Mpi-AtO zw?0k{veo6uUlM3eAH0{K!=eNJa|%p|cw zs2liu^F#Q1fr-AaznGJoTQzk3KqltzmoHzQoAo_a)QH+C1DW>crq4X? zEMwfBB`^Em6~4Hiro8uvL*^(jKd<>=pI&KkF&PlCF=p7X@09-?xYcG?RFhk2Q$7xc zEQPuA1eC7bj^*fq&hKJ3Lws!5|Dblu)AlT^4E;@lDf_!IZO9|-j#s%K9-`#ryrB9D5JwVH0MhN58K%4m$b7F9C}T! z^fK?(_-0zxvalpDQd8r`wR4n)$#<;It~AYjKw-+~=_XAr6}YfkTD$z1YGl209*WwB zw>l6AdaI_1U7P9hr}u+_n(*J=uinYumPzVmP7f13DiEj=5;ZLZ7|QbVBP2T)@RFr% zP`#300^{Qe*Jl{itd-!T3FHcPUS0yw?!#1zP8Eab1M~m^cIFmfBe4ttSm@0sI_1cq z##0A0+K{X=_v|gJ5rtHowpFFVSUk(p!;|~+cVl)OLsrH5W|he8PGP_MkrGKb9% z5c3;>Ixf!fmD{W5jrV~{sB@9(PVS;zQN#!W_ zFKXCu2G{xR_P}?Y!|E&raY?`o&E$D&G$WmftSyBvAu4M4uc?_?H27kha=s5U$XlzH zeLQp1Q3HToAjI7>G|Z=!c%Z<{o0a>cJk!I1E-*c+Dq>KN5(n&I;44%F2bn5M#ZXI%NM6S^5|T-oL5^t zS=|*8KbKY{l{Se=Hhp#Kqgk70% zO0+^<1SvKS$LUe6I(rIh?lmRkxl0Nb#>>W}C^$JU4muz2S1&*AWW91YpYxq3l6Am( z2_;F!&;CudQHqa`FogIymLJB{9VW9j;~J6u+XPPI6$J$a& z@iF~2xi;oX%(O`FfhXqS4yTTd+?*lDbd#7d!H4lrVn`OfQIVv#F8C9wDj&OS21o}M z#JkrQTS0|z;|_jB+kNd?vY766;ZYiJYY&`s)DJV=*@+*zGlMZ^MPQIh$}b=Qe7Up@ zALt@%emo{(Xvg1&a12WzE;)*@GW>i8L4==7ixhXAaI_s`sc&ZPd&fuO>zE#SHhr2h z<_ns1R0oK=ueUd|TfAD^(3O;0sLhm3-`ey@B-&e!&7kN~#f!%Y$}?E1FDDGgbqnni z+{tM>DTEn@eZHZ!f}4K7`j3>ARk4JL$M#vJr+SCtP0!d$vb7ztsL#~^v_yW5%-i{F z`gle~2f5dc&gp_N^*;wDD{KjJya}__BCB|;&G<0Apf)0)HT#KJuKD~{5S8^Pzsu$~ z+9SWhbQpFELBM(fXHPodZ{W;$He77_U510g2K_qGNIJ7X1}LB=q_nhQu=$*YUM(~% zObH5S6qDRrup(pU=O;oJS8yXij7V~NHBmb=E#o_rVNO^^2Gt4uDck5c$#zNPd7tq9 z?f|CNROhyK`R+oDCYb(ZV<^UVW$s!SB5p@G9uRN5(0oy#C%a+3>K}w_yuOs)Y{4Q= z%oZVao&T;SsY>IAKk+MqyC_TEU&&2VrkZC+4pD>e*5?}$cT zfWtc3W$IMb$F|qsG4}6^gGdjQmMAzu@zo2j3%HTws=B1mXRGRpVW65^p$-nGvcJ@~ z$p{69*?iCHlAU&&KJ63DsfwIU<42FUv;=wMf~?p>Jryeiws5dt#C(FR8BCF%mL;Xfp zDVm1*&eMyUp0$`yhd8x4sIrwVzX{^F_SY2L+RMYUT4Sm={n~saE_JnWBLp2r!5mtU^CKVuw=es_M3u&ZD7QM3=Q1lA zWQ03_Mw_9cp?QAsVpo#Qj=&i(D$&e$^jjwchZ_4HFQQ8zB%h#B3m_!3%E%aTI$4#0 zzlbI9@zM3qb-byax!7c`6eQ-a-9qbS!lyB2c9@m|5bXt0Hm+iK$0Shm3&MBIw(K|) z-#7ZDIIWp2u~7I<=zqF`$&p0pNPy4;l((pMC*M&DU^2S<2DxdPt!E59tuO~cJ|r}& zt)CK&15p`X-Ij*i@}U`WpHQuHANC(nnLu`!3fxnhp7coc;_UQrvlW;+582ci{H9j- zKKWjKkQ+iPYBO_wI6d-C(Y5n(Z4~m*EewTgzA~I-Bq!&Sf9UJ$quVt2G5Yn&G9~Mn zGDogQ_lW$$jCI(->ZoFCs^+zUXeK#2bpCs~@5wVn;f0`pz%Vu@wy_L8fN<4UXx|6O zI)h{5*C~3)v<$Qf@yDA=hYv4a%n!t<=$ZekVd-71we{m|>~slXVci-O7@XkY<8N0^ z!luizB?7XiexqY=pV0|;y%5+BAF;LH*)2h$!CtUp>%Dy)N$(E+TwuxjX}m^(x-GpJ zK5AfEqgRhr`xzaF*LtujDBAZ@+fGmxjd5w7hr`rhx{p8rdt>3%y73ZeAUD0O?)k`D zU_r3smH)SUs_*d!e*`ybn*y`H2^p_}XkLWy9qY&8>k%6E7RgY{4IP zLROQ4oO}Y)O%5z$ftlLiHewP2-Uv!C&LoI1|Axq(V$aT+6*x`r;^MFhhTcMc?SJl% zNktxAy!tUv7R6LTBQ!}fSd&7ixz7ztpQp?3<%qr=PplZ5R=E);@Z*~|$*RtCIbIFr zb-Gc)(({ParPiq6yFdRBA$q?yci!1}U5g*OO8zE!l`c^(f@A639rMs(Ya1aa z;pMuB@0`x$+G=ep{6~oT_t*8DVL1a~+2sCfv;{Ea{(JCIq`6t+hE8e^^4LoBaDpmh z9U8P5fLZ!Capb#I$AAC+4Z=IK+v7LvM9)zUJ6uV>2b@E9-|+qA3TO%ONME}8f|z_@ z8;4`mV)(c*5ozRv5uog?CRnp~|KXZhQzf6!AA8#{G~z1g(C9=ChO9I~EXRpA=Ox0b ztNB|hYHmA68f7~Piorrl^1u6mAnX(@T-VmGIj( z^{VpjLT>fZ@d}v!Ml6cDE=gu_I7EYS_3v;_C^~XQR4a*3yzlg+=l{b%#Is;mYpAug zJvGC^_=Cq#xXZglKtiHk@aUTuhiJJHgCKToq=_2K_WHhO8D`;jYsPgrVqoOdA^WgsdtS>rc z4>JxkrVbPTRZpGAwin;4fmcsIYzbU6!QHx`f&2P8U@Ro{pAsPs_aTyWmB2I_)?B6E z*I&t?V_aeSV^L5rOFWvtxdWnHKE`ki3=BH0XZ4FK9lKNI^DDXe-vM+}|< z-Q{a+C$J3Ah$09?ht@n#=0)hORBnv2j$c!B00~{34dI{K6qPwiQBl1gZS1*+R?MY$ zqR&7Q^&2*TZk%ZIwUr1hJeK(f`8sP{?|f!#R_=H9t5v;M>eJda1908l$E6nWNIyUWs+7 zp)jnA_C>jU03w47KHT_}02kR5&P8(6r!;NpON!B;tzKe-Sm5d!~Z)cYyLP3WwPRbgeop+7D zqo>__;~QSZ;kRXBJExt_g#~7uzIlwJ&uP%1(A8`Gyi@HC^E8+Z-n*kbTJbLC^&Z0- zGGf3z?Y4cmwaYIwg#yNhFP5Q#<}ZGMf#65S6tK>rJ4LKBtT;=GAz^8y92q$$w-B)2 zG~?&Z8hGdf3%`3tMg_;dsKdY>Wa|5zDyib@@-nHNi|^!~Rx7}+a|^b&wyO{yBmrTu zu;!hd)7dKVU=H2CS2rNOQOZAsa*4S|+K%cF_@(JGIpD(Gtj(z z%*EO@sxprab>`z(c26YQp8nr}pWbT`wgl=av-dBh`do#Tc4)5{UTI3S*OrBF-DhQ2 zdo={>y32FGtx@)5IU9Z#x{}8n14rSdSv&w=qH8P2qs-yA01#70{umnyZr|TOdY*mEYLRd(c+2L$eQ^{(*;S!TFYx}E@|7^ zktmUvj#QpU;}3lhcMlCB?XT!?$8|5i(CqWj=>Sub&&Pc1G1ev2h@6woT1Ad@>%~y3 zpXBu6*LWX!?5SYMQjpXxvvm}n&h_Q;Tm_vDIv0}9xZ+;&ND3+~uk1zEfYIng?W^@M z4BHKAwwvD`6(oZoN=2@<1H8QVZ+~$8_gA;3TTZ2tU!~E?%F1@<3NEf)s1@dl$Wtq; zOrZKh)F;kNtn$0kX^Y~|D0nXOW1TE2Veo!_c~eZRVxOBaPV7ydx%pfmT?RF!suCD! z<}>S*&<+Z!T*8(BFi>(J0$tfwRJG>emzzTCeW4qwcD?@kA)$CB2sn{2|7eE z0{6j04zEF&D-h_!!iRDWfq!w?nsBfk1^H4%LHn&KEAyvH^1zb zG_ocqPisBl4&oXmC7f;p&T8;#&B-ZclI8!ix?a`0Mz3Qf+$(F=wn~owO0I1qoBLNa zS>ON7QiMl=RCmNSCx7Wfm!k06Z-aR_Sbx_EtM;8gY;KZWU@ZwU!`qsg53-xEc7$md z8Hu3B1=tW+G`c?9e7w8^KKOuT-PYDtv$g%a*KCpyGR})G3Fx;Gth9rTsoY{P>YbvQ z-_}kM)LHt{H9o$9BqM&G{vB(mHz)3ny_lK8@~fydW$ryKMHu0Mle36)Sjm1hVt*#GZAK*`;sXby!(D@L7~IwIt7n^smu?z!!TTzl`Uh#&-hH5BwFiSY!+JHLxicp@G=G&9NHeV@!3cNbu;G zx3B^eZtN-wu2ZD^0e}$?Zz-T5u-!XL0WIRl-k1H3u#<9J5S_+vT#q5E6TwW`X=!f$ z;!-qqbPCQMh>EsO$UcH{4k7GA8VR@k9xJTyziwNF0JCPa*?!;I0 zbay{mkH3=<+Ed2Y#>VIsF4YJ3Max`Y{xVeL-fQ?Zx(p<#@rjFx*aEsT%r4H_WJ{6b zwjYC90!;6zf#oHzZQNKDU*{p!siyriM{wun-kbW8WlcnUB~;|SZc%Jt{=cLH`#u51 zS{j~|aiX2k|3z{D(vkRiJL`D2N1={q5d=G5TF-EfEduOX>1-d9n$^oblOk`T_J#Kr zcARJ*Q1m$f02z82Kx_tgRw}-JC4^j)&qYP8urotD-bE7gm4}a0UAwlpy=Y(`F3~t) zB{KWZteqf>#MLgW|hn;q2%=WHM7O=11<$| zUXto=VYi;W_`;RJjZavmmc#0kfb*b#*Lx{PoICD%ngP09>s@xus>;8cullE*t>*M) zp<(CQ4}0UbHWZjKWkF|wHcktMU4-A;^8MrGxce+3wAWjxT~%J*U}MAF-`{_}rQjQ> zcz$cDkPX>hqpqi?_wYF4`_s58HF~iq;86pO?=PfU)AYuYr|;j+t5%~ z!E+8?a@ezYR=S9o*mHBguQ^wneM#=Q3{5WA49BKB?PHDPOJI;X@8({s^OL>v>Yd4i zJoNKG;K1CfCRO!OyKELKsf^C+8+eVoXRTnhwfH!$bTp1yWHhVXU}42~wJRyT78kEX zUih~4|Me}XAS!h+g@eDA6~KTKxI2p8&qqVMj)sF}AiXAQ5Qk=mw$5g`=EF9%k8tEa z)p!&Hr_%V_>_~EOV8gh8PQe8QcL2mpL(~ohh@!#!5R{uL+S-Nl4`P<}6Q=PcPOwQ~n80I<~Obllggr}wxA^z(Z zTY|eI@7iF?FJ3~6ko6R0o_L)5g~FM;5;zkZ2|DoZOu2x6danoTTDvva@7?7T+KZ~W zTMoEFdxb(R%(C$tCKEEQW>%WJ=!3u7nX9;(uQ#fq53s4Y}#Lzhbg8XJttXhQ%y}O zz!ADb?cIcmrf@4kp|KZqX9mo$qJ+eRgkW&}088U+_!9HQBB$m){#E~J0MsGzo|{8G z)`~~&F<;lyLru~XG;%{5&YIrn$mw{=1txUZY{}MvyZ$V2QdL zc65|b8Rg}fKpl)8D{6$%w2SjmG#3d?R)<3c`>C&w3UbXnNI!uj6~jNcZNYLPE-@~m z0_|FUaBUMebKh#|-3nKnqbR~4mFfs}@^Ppifo%_NYW2C&1*OQ)(Bb_+s!(fFC!k~B zQZ9Wh$?aG9RM?Mo`p45~{S`uODi^1xHI}rWqd*eNV7HUGU=_$MXQ}P$5!X)&J>{AR z+Z~Q%NP)f*@;d`@%vYhK-bUhf|e9s&ubp3bJyowJ2{0ABjNNh_*vAJaGoHWGiq$i5V)EE{$Yaav<$2(AUP-B zQ$^>45C+(d1F4us)P@iU51({r@l{A)(p$CejZz#>;N^LC$|d2a-dj>}osGK10WFce z=2xzaX(j~*;|IZ?xn&B{yV)vGqKsy*2HEzla_0f}wN!5)){;7FHWK7vuH#x7*fpRE zd*+mZWMo|*`=TOo$dTai|s62;dHpyB3 zft;mhO_q0=LC!%>8F^ua(Tiu?7|cP|Frs954*-u zks=#7wV+qYKj3*gw-jHHm)Bi0s>=58N{uR)v>&)3e?}c)J_7bDI^A(-;K9-x60t+6 zn1Gxj4WEWqJ-9NUeVP2XX!&;Ov7!KmvgZz%I9FNf{*#IM{1vJoeivj7L`LS|bau?n z8+fY$SClBcnT=@qc9R_A+9W}3oANqJg{Mwn!+)#nsD6EWA*st+RAtA=zPx-|&%(3@ zN9@J6^4^ETrLeA!gm}TAh@9Nojlad&DYcanBKoh+y{WpJg>P@EW;N;6)D1fEVqNhi zIC>)b-Gbe@dWE}W-pIV`)y(Sw7kMaiXA`zfBq<8@ZzDPX-?>p0+x%OMC0KX1qk7#) zaO+P`007L&^2)f-Jws&48V;`@0N{yjI)hngip5@TVC*R6xDjMfJ3zDQD5#j*l%QfLwEmm_D<{FqxJ0p z59!myV~s`8vyQXL1?i^w3;jcvH>3xx+TfFk9`i9g%gd zm!f;#f2hn=bZ!HyH$szL%j!i8_@dx~AMyQY(?+1Id_q;K-@xT=hJcK_k{$hqd{pt~ z33uLwVwWsm7xd$U{Q=7*l8eBZLG|ppg4N0E6giD zuG~m=DO3JWTiZKRYHIqXOCasGLVUUp7hR?Ol_Im(lJeFoN0oqO4-OAMe>J_#|FN6#W!TU)(clS!$AtRxd_x7EI13e38i z5A2p_`f2h6j=Kdep5SgbT*M`F5P41i#u{nPw)|!Ox`ktQm|7zH{w>c`zH>yJpi{Jl zjeWzjwAF5=6XsllKr)Zf?4y&;H%?Ij)41B->gXpi&t_2Emv*B69x{l?D*Cjn@RMXc zHOJ<%%GgRj`e!N|H+W_JvVySm>?}<1g_AMw&#FBPdwWvRp(iWMfqgbxe$HE+tku$A zBR6Vx36_I@jbv0gN1itK;hm=1^{Vv`4~PBuzUy8QH#3<0WtmO3&f&@>E^hPFgCqA3 z?t1P&>9_a}JXiBtM5;v|(CA_4R_qdtN=iqq_mHUP`I}quNez3CJq~hO(rW&0%Gg(? zC8YV{(ZqH?m*ijfv|R(%C9TRUFBr$N9757*yhn_V5*&u5iv{U_l-wtM`aJyRx^&jl zKiHiYt300{bBAAsa62+$YM@B5ao&8in~w1?|3Z|mY<^0dZRY1$SH_ctL@PnS+`W~5 z1Qi6nwMBwgsVRcJgXOujQ$N@KH4RNn22zv+Tlnu3bxJa#w^^T!@{uf@chL}$#HR2V z7g2?&h>MF0sC+-i(k`r*!32ngvEXfk6qc)Kot4({1UPf6x~5kjAGsAfxB~tz79Rur zUZ3Vu@utErL3i}olj;Y;7erYSXIT1?)8VHxX1V*WH%r%8zJ>hJ)YMdYlYJ|`i!|u; z%gUP>KmT6~Z^{+@J>MZU!(YDwNy@)ZpZd3#o^2~v3qsll8=;kHIQ*U*yYS9qAYdo_ zXrTXyvRy~#;7_&ee!8WcMHqz#Or+q8aD%lu!+OJn4~v`lI?YTaxy9aNH9{9D+`Fv< znrYJ42&nkpd8UQ0So_>Xc_74q%lzsdLMA<9Ov53e%gZwy^YyQdDuPd+x&p+XVc0<< zh?sB-mr5$)xmtU?L@&`E57cFJ6A7(VX%epD8oZy+u?|g_RQM8;Sui8Vq3&n13LMwO zAeGi4HGI>=c9CY7W2!2}sX&9qa_+i3laGzixOeYe)$VH)I*cxtq{-`#l8R*c$bbd; zB6vi&+ZE+8Uh$M3nR61E8mT2sOs&s7Q6+KNK7HW*NaZnunY&Xefp0#lNV7XsS(j2` z5=py9qOV7X0H*W2>@4Pa$+tgj~MqAYU@=b@g}t()_TnpX$bT zE{B`h+-zUD>}wU1U@4EtSB77{#rqjC8YVK?%t+h_aM6=}Ml&ZiJ> zF#GmqYw-_f=HwB-?yTjyq}#WvmLzoJsWn$!3hpGu#oR~h-64kq=bAuQqb?4YeGt`*tf zWJ`=?3CnA>&u$c%pVG-D@I__o@pxJ?IC{JgG<>#%%N@mcst{4(&d9d;ID%;WW%1F* zZTk;WSNuFraYx|V@;sUlCwKRoxH4~cLCSoA;=;C?eiL(e)>FE*`nBol4;%AQd|oE+ zbF8l(Yh;A^Mq%m~l8l=Y#rXjk+|F6b(o9K*3f{@*(z#|;)J571(NA9)e|V_>KbQDJ zQDg|SFAX5p9Kev>h~C_720E{xEfRG#wnwNsx%9gM$ivMsYR`5wp4AubVjR}TIp}kT zHvHmYhM;zr2TY6X<6)#MBAP|DK#MCcW0Z7806K#X?-i&!dx_p30}t#*5?jI$5MgS? zV)+5zy02rP&9O`th3)wwTBwquI$q)C8hv;GVny;M*CWojmAVM;rPrc@d8Zhv`>qFq zyXr$vchYbl*nst`uA%X&ugM&;bGAS%IHDrgKX48y*MmYUChDh|!6#9-r@hT8hH{WS zriQGq_FWImA?Wx&7&^e6G4IN)c@@e?2d8k+)H63p21l#lDHpyUiRj}UeK)-b0+{=6 zzRk&;oMIq+x0Czn)3bgcajPlc9mwds>6tD`d;2mwD{F8b_KjL~ZEb8N+-xv^{2g0= z6>nY$s?ts^uvK#OYngx)bOuY6=jn_WvM`pR5jqf)t%}QuB<_SM$$v3xD)Wr3 z&pd+=U`fxt&r8YnAs92OdeBP}(ciQ! z*v;*Bc*f6(g}x>hboO>Dt`5|%h}J8dU@~$cn$BgSF;^S{wwZ4xdL4Sh zmwjme%LUjX9jUZCd8JgJUj72*cHWz<=k*hx@RrA+QSsL-i~_D?(x#fTRN`uJHoOK2 zeto%_)FHF^$S=>9=_#Vh*4bW+?vu>Ok%aT`Gp(OyPIJ~@1Ul(z5N?lJeD!{Mt@hj# zKjE9*!9Cd@Pi1PqMJwK_W4f1dFd(yalDZ#SgOaO`86uVv?D{QW5|t-jwO7;Pwi!&Q zcFFW{i)8ur)QH$*PeXeJ$HeAb>3(8h9ezzL?vvikrMma8ZGXzu(Ecc_#Ew}XXZfy0 zlT}oWuk(#RBwg9p^4L>W?%;+>NU73V8CTQ6sREzgtzeLtJ?dyHDeQ!OmdmXXGZb+R_R8OtZ~gB3eaVZ05@Pe!ufPmz3R`JEsX{qx>ful>xnv zph{g?=rkANyZxw$?9ogRP|vA}KKIWc7UC@-7X9fn&X5&G8C2Mq7V)ix9n0tlA!JZLBfxa(4aYk6GC* zB$HlEx{W;9nrVR61}*QEE~|3iBu3;{heT-h%Os5EB@V~cV6)i(I|4n*b|G(p31y1D zFamsBKF@zR6y#oljo||+;Ou63uD%FNNEeP3o&gpV%gwtm=1Z5#rQKa-U;$&D}~ickGjnQu-7*wEPu$6Vine0`KX1$^vq=| z^^)7UNi`#;oozn`6_XzP#4U5?aYKpG<#$(jAREDC+yo{4<@o z+`#TW!)R;Asx`pWq{qbmi5X0U6NSQ>zNzKIz2on|9Z*;wYU&m?fxcluIiTl&eTmioQ9W;Xm}W_r5$>DtS! z4FdNkneDikyZ_`nYpxTKIBo>C7x}*3XYNrmT)#DuevG}NB~epFgt_-cLo!zqA@>b}TBT^A3)Vw4TEBv1R~-@&Zp*lxpj)*z;?))X8Q6ki$lQ= zS^5DdBjS!!cW1v0^8hO%|9-sy7gV0X!@1Zuwz5^%kem$_(#KbSVmkBrvA>c$wK(e4 z)O1VmcwL)vlH?7w;=5}JIC(^oJISkx}hxMGr8wB5<<{w(@7i?Onhlp7j`b>{5 zex!)-ZPwWwN!Z%O_U~9rbfUfZ_5@12)4XhD{J|VF?FU?N*vZbkDI9N*zVY- z{EQHaU4(Gwhxo0)3~p*_s)yMg{Pux7s0hw+Ez!&*i2T;;Gi*Xl)C~&fD>{hGn9X;i zS1X*nK#~WT%kSE`^Hn76$4#9s%US9Tv$}WkTc1xNaiz2bpeY&#`ZCN0oMVnC_fukK- zBcWwD)-Sk(dM#0IqQR+kYuyl-(le#P9BQ_Io$1Q?RbKy|v;9_!$i= z@g*i$F#mKIr-FtmxtS1D2T>RTqwII{oxxuht?+h4E!W-N+mT=rVSaYl+yM%<^cCBo;9x&l!R7NXEC|Cj&WDr2P{=!StOwD{< zaO62xB{A*x7xmXWr{kq|`Vu}iHKUJHr9J*K-3iQU zm7mGq4ZTj21a?HyU!Vf|u9v9l?M?y2vasIrcUUr>|EDl0Kt{l#89N!Q5 zXC|MUA6%U&6s~u(3{dUx*La2T;}Tc02UGn9!iCw~K%`fYmc|{6bQM=j+CTegfT^;- z(z$=mlX_;{DpSv*YAQTItlH-%NWCr28A9CJ9-O;9n36Q@wBrrz^ z5nnC+pXOoZm0>WslgR{>kOYt&B9y1FO{D`Ec14@P$v#9No?tuVNC1yyEf}M`r-3Rm;9^Swx25N?J9&WaY+J@CN%7LX5B%)g zy&JU){Z*GXQE?R5@K%jB)zwLn zb+*4qY88ps5+Q#O-E5%*eHfbQK^_hb8rq=)_TpPTeiwSm!+%y6eAr~TLY2mWr~`-@ z2!w?!n((wnMes>LK>-5ixb_9EkS8}&hE5ys^=dto!jn9e9_@3`SC^`LFa7J>^@PCo z{wk|X;db%FN}@dl0fFv$(GC=;&aWG`COkwgBAOhIG{}_owd0&mdnDpU%>*G#=8TK2~ zjQ}lK7c+);FVljX5ku{UgMB)7FLz$OSI6LZ?;&gO+Y<*IB`z?;X zy43$2U6eczPVZ3?EHfbc_15xivI;Yt0MEa~@4LQMYlxY@@$}Z9-U+3X3U_GdV0DqFsZh2^)lD5gokbq{3f#w@_Nb=#-r=HEvMi=5^o`3nu zeJgyaDlsE0FXcnL<(c7#GOfW#d>@%5{u{-3VzrAs{ETC>o9KycGm0eo%hsb$!v}FH zJjvE#hLuVQ%kitpo(8ZrbkQjjHnCy0EQFOG6dF(8s1d9r7OpgAe{34JX_;`2_y2k^ z>~E)g?Ue0-lvOPy;yaJ(dj5GdykB$iD-ikTeIq2*r(U;XTZHaA^IcqpB>T69REi85 zFjZl9+0{oVm3tp>{rizO2a;(N1Q!oacFUp2)gA%)Qzty63phqQm82c?J>JFjq zj;^#R`~YEosjT%Lba~a0O&m5RdjjL@P>%S?SvPAnG(z(QcO`Al>LY&+k&)NH7hcbcC#K+QJu8}Fp5mgGPkwc7U_gfDE;(pF6`+x0>P|P z^;)RCQzKc`DR-2@i+Ll}z00&noe)p~;HU2?`9^=^vD}x`U$UzBbiY8|H@SseZ{a-N z8z(Hkbl^wZu4LMvP;OAP!$%qyVO{@1HmN-F%&*j~Q@2+5Ge%1EG;aQb-mR6l%P`{0 z9ytOvVs=*(lrC1&RVq3S-}ECdCEktMf0^nuw7V)3Sf7;-b9sXW5jgECnW z$1f#?^5Wux$Zqi!xlj?x!R+|^Sw?Q}KfA%A;a+O<**OVU`G14Q`UE`w#Xb3QHm?!l zVZktBHRW?H6zyv^{d1V$$9(Ub?z)1#kqooH37ixk_eSSWn=layd`T!lbz5&ebjAdo z>Zi-do{ChF)p~sp!@BenNb9}n-TXCN)6QcWtK;X%PfkT9f2Z;{``&sDZXS6Gxb zvqA0EUSanLn4f7FA_QK%d)6>+PcA%hku>abh|PE(jc9y4<5tYg+1h}wfwRFnqqU)B z2UkI)<(<5Q52}vEuBp8nrX7S^>I35zr%7flM?&fmU_7}vFOwkb;hnNY127fhJ3Fn1U2{v5L^>Q7Q!$74HPA-mQchqpXaI((3K$ZjJ@D~1JZ6_ zl55$97+%JsYE03%i2WrDp|=xU@RNQg3r+S!-?I(<0Gf)MMJ+f=LW+vxr29)nt1N4` z>3Xsf0SuG1^k{h9ywN9`4hUn`6lvgczyF2}WZiLN4;SJl7`CM%w(?)zj$5gszeyd{ z^evWcxc5BHJ@Hl=OvLGH*=WRZC?ml)m5mbj=ZPyPl0s`X*mm^nOKdD=$v9rlFyrvA zW!;h?I+(tUy4-Rvj} z6;5d|N2)m-kcE7zz!d?#+f+)Fkybb$Ve6FlPMK`@_`2UPt}A-H{TfXa5{ST9wW1n6 zvw+5;`|94zS%=nazk1lGPxjGYB9}i4u^sA2gLYC9WCRn*V0tw7V;|t&W?&WGEIyU- z(DiJ+E;-(sf2p#1##a7CwBv&uHc^xuDb+nzYU0m?%`Q0lOSkSz;>AwLm^a`V_?DkKZPg1m`tx8g&U;Je;A5uSm;}d~XX&Y~ggJgmR{|^(i zfy(UoT+p@Hbmv`t&tGTH&C6%h!Ka?Oqur;q_Z~dR+an>&63p&RONKl5*NK`~FExLM zG=K2^&F@rddP!I^O0UR#?T9)0u{w9V`_S}x=>)uw)k~4OaCAhPhW{{cb=}X`4)#Yq7ZkiUS+1rz3no8N8g5r zogd|k8(rZ#%iM6eZ<;gOuNl$NC;I0o4Z;K`f5i0<>8U2OU0j6;QiPd}rwLBVmm8Qk zeO7lcys8ggY5mRdOAeysBGkds9xFK98YOi;>V~qV)Je zA)kX)?t`*&bLQ={&S3hV9=Nli^sUz{EY0IH@avA-(mwSfaLLNo*QGey=QV{D2i~Pw zPxDk)Ar3PRn`}3gm$N2n4;I?`M`joP1hG&3Gh!IIW+pRO#ZP@RiqjHGibB0eA&gqd zi{CQ-9;>ep=a7;Y@Lt%qV<|Zu1;>^ z;md3vi}q58j*gdLXIMFo_vn{yJ}TcVI}H|prma17r~l*Tq}ry*d#x=ykND#IK;{Zi zIpD^>L)0ow?M4B&?Y*b4$8Pu?&lw4rihnpLfnx<{?EiD%K3B6k~uM226qzbV9|2{6&Gy)FH$t6;1+4ZBJW2#vHgCjXnFG6}JVQrtR$6b5$e z;ZiStb7%Jx@}Qg)Jvccy_6^iS=dnV++H;zZpNZgpJVIz^!!&ZLrBV z(;GLW9!qKs#c2BG!(6On2h(xo7qZYP9>kWY2UGa)*5}#@tbdpYEt#MyGb!q7*xK?)&xjGNMIaatpa`LZDfdHf|pYlGL`Qi&{t7mrdEP_k%Nr+j8WD-|@-rGNg3-$+&Cm zaGJlk3-&euo&X@P6`6Yi#|oSlj*gDl@@fr|e9#wxRT|Pu2z_>zixg9Y0SAGDxANKG`nB*i6|DjPw}MWX;%X?OiQ-K8y~8!xD+i%`2bD zu5KjH`g<_}b8nc4H^YsA)f0d^s`Eqs2BRKSXCOC%k0CAbcxXjCCw^2b+(ku9;y&y( z7ofV633gOTDD6x?PF$syE#0jH&m1{e`c;Ioynlu-arC`-VQ*iI4c`(#SbV@6+`R5c z!^3m;-o1OUVSq^A=d*R5{X;|k5Ni?IS_1zLJ5`hCSUyof1OZA4@76B!Z?@X_k(&ZX zJ%L!oLumB97^xo4q2F@avdgL(Z`!{~8$*lv^b^Tz{*!}*OgpBZ7l$c95<9h@Y$R&} zC2wRdJgqNy{_ncxeZ61=-&jA_|7ro;w(281i4HNnPVVkDO*fofWB!mwH4(XC#g|I? zT@tm>2#wttv8yN15K}2C|9E#sfGU%%?;ZKcA&b6(u&p5v`>JBYmLf`h%}u^h?3x2| zc289HZJs%4lHHTd2AwA)x580Z{-FK|M4M&a)rdLjMEw+iQfrM_$GP#Wf_-k)8_mQK zMI`aY6c@fNGfKcTBBJ1XDSrb&u@4C)ic|NBE>VM`E}FF^qV77SVKmYbzx#@RM*B<$ zZ{qA>9p_t){rVz=jq{XG=VFwn>T2!aUV6Dm%Yysa{9<=}^&(?lQcU00)CCrt*4^d$NJC2OCL-KqVkY#v|O@(-Rk`yfrE=)xO%@)#01DxW~ilg+80eK@?rLhe*DnM|Hlo6Ph{e$M$$>ObmdhOdWTC z(;ZL5vrvnUu+?b$??1l?_P?e<;$x8U*04@mk?rgiU5k*u(;&Ilq52t&Kai+G&&DPR zYy6YhnVI}jjvs}Bd8Y@fxZQ)54y)hF%I-it=+z>Jr25Q(9Upn1l$u4F)Y#{g$u<&r z?V^!eWwnE)CL%dDe@K2Mh>S3B#jr<8Q8sXNQzdGE5#5~vd)<6p>OsOM08GbN(Z3W} zQ(j>ZihFQo_wl9%$MaqyeRjEc4vgpd^%MZN^s^@?dTn{LzP$kL`}32Tte1Pbw6y}i0P{?(9saKiDkU#a9kt3@7^l*K!wXINB zZ*^%&AIbGDHS2#=`k39Y4G){w9ys8Nel{Zh zIox7<%>XhpkreK2hcF~u<}1(JTlR9rcSSOovpJg5>zJ?PMc*STm+lN9K{u%+U!cc+}PP zOCRXjYSpBAvL|hM{lBJfrt1{og*er6uumLyrGm%s?c29ag)0d&qI&R*P>xSLczCcp z*IjxA=&@%O78`M~DJa}VxQ~Gv(LuVM)xEfPqA>#D;(O1ufQt$CMX&;y>ka_k6a|5V zOVxW_>X&IEt9ygmGUzWN+X2c@2${;%<&7-Ys`=VD4U$Fyfq}uR=%*OU`EkjuD(WZi z780aZeiv!RV_R#;72kC~-cso@@PAXA`;2P*CZpP0`MiM}8j3Q{e>thH^PySjn5YO( z-H2Z8EWm1OPX}p`nKh2ezfccA0il0)suwek#i;Pn}ueDuwWM zSS|ZspA}rA&Xv@`y^JKY&wg>J)CM2i?XAB@Zb&{9G7c!=(A5RuWq*$m2Up>*Lz5!6 zHA;#V=I9*)^qFw5QX)ejcTX0>EfXd7T_2COF77pe@3V(@_7GRn;HL*ye#IY00NkZC ztMcoiey5H8Z6E*ILGntM<7>|s=t~~k3~Ogx;|HR>eEHJP2$Qh*j$$fl8RX*e_aHq%rcR1pzGW)X$r2(oi)D=5^vL3w^8(rx3{(qc@9-H={_yHVf zj^VRjFSWZxzCpTGz^`9C%?xuYn4>Z=BJQ=iVz=QRd&Sw3cR?ma1>-PI(?2bL$4g*I zW!KG84z18l7+mqWk7T}9efiQCm|#fBHbCV0>=yj{zGIZSm1Yp(o^-5$@1xnG>;|r> z&^MWI!a25I{QSa9cg8DqC5%6;95hzFuNt_=@%nDRZ{qcy;OpMbCsds#^aps)gt1Cq zjL?P}^W#VLMjT{p0znk%IaFuIY+B|6{Y?7?#MS=~Ijp$&76ez1EJ-f~eiBVT)C14X zqxqgRnozV(;jFH%0^=>+CfF#n?zwf1nv|Rp>AM-RLP)rJOnAr3CeP#PRT9`G08q29 zS1jd*U>;JLsv-3>wxN@*@-12?G2!b=g^@sU9yDQBbjCo6`POb}jyoW*Z$rX#^{&rG z5gu<<0IN@(@2W9v%?tX3d8caRHwKVI3Z#nTa(~|N`LCcyNpIrUxW4uz6f57)eqvsv z-tywBE-C7cWE9^-kzt^EAb-&9xc1STyi-2$oTfLD^uycJHFBn{^91qAc8=?gg~$b6 zl+**2MK(LV)Y{nv9)7p@+x1n|Uc=n5b>23$wpNF; zz_qT%8;);)XkT^#LNp8wi#560#=_!O=B*lCHt>K_CwhWT_oJ;xbn})IE^5lAo^zZY z{$~S!!LY-T+q!z6jYz!P9-ug>jjODC#BdHG~0==Q*&xtJa<+yqx8(z9-$V^*eV zP%<8olES9zsKZJEp@<;>=W`LHSnht{Oo(y9+zXtOC!k$JGysGVNt;3VvZV8!1iu9@ zR#=(tkVlNP?o~W-N2B9c<28QNhqkyDYT_8_RD{=cIfn$^bTw0+&NO4qI0g` zawe0!Ju&XDABI2^TD$}j3%mD~2MiNDphH-o=caQopURes01%A99T{{@_NK3+lHX15 zGwwC6l6~igKZpUwA8EnN!H?j%vCPf?m>bi`5|gBmX}jH;=e=$wR1iJ6HDa}5OQWRX z^bDW^Z5%4Pk`*x+<^E39)Ayf+Z2bPnHaxX#lr}}OuZdyy&c^iw#NS~2#AZ_NntW3< z2MRl{MIJ#x?OeT~o$EcyYZN%)!Jqwd1)k4}X<;Fqc#ntniBjsi1T>>A;|!Eh4AgyX zV}NjItyPkGGLsAq!mf*;da)7C{=osaA!c9x7NnzM!)eHzd{F09slC7(u<^8I^XLWajc<>llKY3JYakb%Sd@qi{!=maSU07S<F*!hDoYSZ2Ny*`@TxHJ-2!Q=KMv_)xJaI z6B~w+ryGmmBu@%0cXRe>w-|i)h!Y}#i|RHS~J@WcD%SO&sP*et0zB z_ZrSR$*I+c1 zg{~iXEs4UOnlT^49rzzq%DF9-bnWxUxcKy@&A`Eja3p8}N#4bX&rWJcQ4UMvi`@D{<_{e&^jxp0DyH3Q#TR z1RJZIR%oLrW&(u?zM6I$?{h7&FMvfr>HC9YQ4PVR)WpwRg^q@lA@-clVI^dZX}d4n z1~0;xfo_H`jZ{ii+*(9~=Y6~KdP(+(bJsy57Nt1g@Zl-@yk%N4UifyBhgs{FTxD9* zM+X%RECPyEYYT$e?y=x_=${|m{uwrmvY|f^_XdtIuOSMbB0J zkzS=$g$N*;XcXaCFpyEvq@}&xvdIAzvdz`i-#aX*7yK0;08>A9@t5daaz+j&!uYZNew4WG56AL?hk1OAC z495>-5R<_irR1uUjvpJoZsof-D9Ol}GKl;l-8_DS+6I7~2J)6XdPA#h^z?+PMU2I< z#H;oxQN#^!E}eLWcg!;g#p9`Yj;_6Zqa^4i44IbG{50W}5NTXg_j9F;8RfYl`xiS% zzy)N{t1j%$quhc55@R-K*Z|!Q>@Q@NQdHC}AZ$`GGt2$v?-BtkN`{K6Dkg%@`$}+P za`H0By;h#`idpGP_lKDPgb*#dWiN;sO3TVncG)ro>#8Pg7d5Xgt^OApt3S6fpYSL_ z1qhkY z*Tw9B{B@(@cwZi$3dY<155=LHT*)ecQ&Ltom`WHitNy5)bDSeI_p4;+{SQwJ+t59W z=&YD)`L2WHMoM%sS))1<3B$+;Gjj^$uvfU)BLWUOUeflDj9_LC{w!4*DKSyyzoNCz ztE|+BXw!Dq7?L(?FOsJ=xB!>LB;O{59A+_PxrSR4jAl*nPImkT;An%l0H5Xu; zAT#qCNvWBo@V>A^77J?iXP;-)=Pa{7jSUVaFI!URXyvJjjHAtcYZjR3m`7)g+njR< zTveP~tSK$MO(1kgsE{o9QOl(Dk70RkBA-6sIJ=B4fJTkApqY z<nhc#^K^vrLmC_Y0|>Lx;o(|zpf(V1!S z`dxjDU_LsE&3~VjoN&u1vn%K)xWyfuY5Kz5@!g23CLq;_J2#>Fo@41RKrTI(S|jR) zquh&4PdpY3#Ggpq#@!;?2qFby?#`8bJ9H7`^AIa{2JM-dnVG1Q6Aw^p7@3$*MERaB z;I~cvb>W_)6@k!(&&KF*2-TmovLQ~mY@~m^ABfW9;pAv%OxpaJcxv~GPl!b)qLHDK z;Xba(__O$?tkkIKxlzHHy{QxojkiqVt^V8-(bdM9 zY*-Lao#8})dZrnQGZX|^;WAS0mLz|tp<`yCtb(P|SiN`sV{aiQ?ctZeHi&eC-=V@) zsFEBtQVxy`sT)~5GW3^l^oZ@+(a2okos^m#Z8T4c7U(j*BB+oG>$cU4Xo%=$)l

=3po`(P?x)@(g@g4!u=1a3}+9T;XL)BN27aG0U7ln9^0U4x`XsM`UKnGza2Jb z%hxwE6K2@cj`|D7SIU6K+tASP`G76v#dpr7-9{sB$WPkauHHFY_%MeZLEN;yzAgiW zhrs{*uerkOO$|9P*g<_CTJ{}JC`Tq4Q-}%5G}uNyfl3JJVAd+PzB7NAJE#&{yzk(Z zkrF2@A+VO$?&i8dP58u&=RC3RWi?bgIIp5g9aJ(%Qa|G{0Pc61eQ7CAPH@okM!WO| z@PyY!;qKhottFZq3CA2LOHbD(6?nD?0E{VCFQMdRqUhi5RS?j zn-U3QoImy5AC>ZRa^6pF-8Jkr;`qp)!E3YB^M&ob%krX1SrOtST<=Qb=<;FQ)4sN6 zRN4&RrvFn~H;j@9odK@xT^TNQI!vAx=R0#z*V$JX6ARMyhN3`y(KQR55vvKrx5s$ zkJy;|Z>CEUdK1}7zHdwh;{q)=_Z?5Sqk%O}G?Mn@8Pb?`Z2$;?G#3|FLRfJB3;?WnE zyTRw=?p{rm?LrPyB8ZcQMHRdOO+cC%&Q<|^-ZLf*6|6a$mn^GfSyyVPz|-{-f4pqT z^A!oVfYSEwM44>KA0*TA=9u&6yP<3?N9Ox;b)2^ zXRlJbzQ&PMRODkNy!XeVa6y121Oma$pe1*k-8V6H4#m=V?g4q#2#>GQjVs;A=0$L? zh1hF7t0{YbkO_@H?sbo4GIX{xOu5NDzcu5D|DadaFYm=iL{RadzjhEK@KuOINA0~1 z4rx^y2>^l*-UET#aHmdlSU-dC+zRc%vLKkpLI$x8UOl#;Qh2Q3q3a-i5UnWu z5y~w83l3X`6B@Q7-;QY6N5-sJB4_>Kh44IDP5#>Yv~o~@SzEU#9>pjJHxFFim%0y) z2jZhu4x4^=K8964;3ptv@f)Q5Ap?p4o>u6vs&KOrSgx&iMyzb0lw&u&Xg>PD#xE z;o)q-U*;50czu7zg}7J?6lw8IxSxjQ@zYWQ6q|*AbMo`suppL~%H_K26dm_^Ej|2A z|2GLQgQJcKeb)evtHUNh*vSFp2EK$Q15$!={YF&5>x%;~^CUjIXX?&i$SWIf?$$zP z+)(=H`_t3q9Z9Lh8{Le_XAJKKtY4wmr5iG?qdSgmG}jOrATCG|Zh{sZX9s^_QXw}k zaD!+5Bp~wLCq-r5Ajolyp-GaWw>SUEh_|%A2On1 zqRjGrEU!AnYo6gBA8I-ejIGwtpE)lT$k0NI;1mA0cIfc=J@2%b^BhsG?tP*Ej&iCf zVPN2AR=1MD$$U4s?|W@5VUWIErAOF&g~}`E=01x$j#R@^``Jj7l5wkl4mIKrIT0e3 zj|Q|K!;)7lw_-eU9|~_cCva-VzkDHusXi8>&}mB(UL|D4*&C~VqL~uY-cO|t_Vxhl ziy1MP8VGw&Y5r^63fY1ud+bYd@$wq(FLja%TaljWx=63u--$P5>k@CdS+PdQc6-ZM z=oF7aEp{$qvC|xMf;Vz3HE8ekIipLBPW_~en}{g;!r%G3*^c9@l*yGKD=R)Sc5VER z!~I*Fx1+`_%4pyNKr(2cJ@HQ$p@~1WvmQT}nPu#}7s0qfnKo+pBOZrgU2p zrw>EZVU3G;Kfgz>r|@d86vAb=*Y~f*#XCSHX()kT4LLZ1AZ1MOib*=!GX)Y8?7m@V4hlrG zw{KNO0>fEqD75II%+BYNDp`}i!Sy~lTtgCEmPnende$wc5-S-30qo+$CGYR$% zs3|jy%O_#l=I@|Qq58{dC5n_a4i|{fD4X}!u1NNJ#mx80mSm!*;-bCi?eZV<|KEx= z*fPw_3$g_A$HFI>PSfK{$qR1d<*jUEcxzw`86rc8d`8BJY+uGH9}UPD;nuz;rj{`1 zY#QHkO3%nZcUb-N0Sv2_mN@}br`yi;!Cdb+T2g%MM=g6zFk zWctEao4R|SKYwoOPx&N{>G$;d716T`;YeyY6ug#hT<6k6KBrDGMjsR}*UUq1$mx8< z$t&5^TW(Qju8zq_WN$39*wDOmzopU9Eov)}OQ(BI%2ZkGAKq5%VuQ^ zG)nWT-xavUz-U=F3ocyb@c{R5F!b(P#J!%49Osb2OMJ|b3~_)u&eM;&Xo#0;Sd1in z5~V(SKI+J@g-v6MYJMV8CXTGXz>$ZO8O|EVv=$JUyi$7c_aj|0p@RBPX4RbGUK*{D zrnq-sWo2c#m)@qHrb)WwbTNA4bBzKlkpA!!TC4KgeSb{~6|L^&<%H$zQkJ{8&=IpJ z*ug9NEhh&TrXoshi${Q*^#y{~v~?h8KuDRhcy1#u>rQCsFzE>N$_2Rqo+GTt0I@);RZhzt@q-iyBTR*o^7M=2}Ue)Mh-Vf+|ugx zOKAVT`KKhwucGp{q|d$sO^)mRebdjaT;IP(t)~hG5RmKi>Fl@Vt23kkeAT-Cd5PtD4za2PDOL;p4z zvpitQ;I(R#U^29a!-_0yY=P%~N5!9(UVmS=uPlV6+_b>R=;-%{D}iQ)J6bqir3OZQjzGpcV!inL_{bBqquOt0_62#H&EnI%W|oP zL9p{eE=5>Ju(!K=a7ZgmmhQ!&lv>s7*jNy-y`ZRx44() zDaxHz44_~tgyG`y55G?r!#RP1`G*}kr(U4^2&hndE3+q0p)&b%8-v#R)Bz}F3TeBJ z^ekU{9w$B=SjmTe*plA)Q&+d>S0xzfL8>XJURq&^kt$n*c16aXX1$<&T`b-p7-qQ`g(|E05v(pUTlTG{bBuD*XczU?<|RY$Y#HLhM_auac)!R^3ytft9y zw&^GPmM*-VxDU+(vODz1ucBVeEI~9V5{e6z7~}%O21;B)!rCdSS@R@Zj4iZI5HM`RBQ|;GgB7UO;b=1g6F?WzN}Y}rAvmQ zrat-rhs$mB!yn$(w|bA5Q}~x0u^IQ{7a-8vf_dt-cpejlgnCf!0?440M#k2&@bD{KOh(_A41sh=GjGzK`w z)6OZ6L&mK})=Ily;oDDxl{Sk`V{G4+B3x2x-8r0V-Llg{5!N%}od0wux!jT>DLng}$?1j?YVWA22bV4XL%_fZE5TX)79;TG*zK330JQeWT}Mafey9qX9-c`F zznS~~D$GgYKX3g1;l=0Q8mRVHg($%G|;I8weFv zk`WvA@W_!!QozW*2)`dX_JuT2WEMlQge?^CCv#Ps`NVc>A_$@Yz08N1sjzAQX#j{q zj;j?T2ID!5Z)j?1zO0=!wTq9kf8qh#hQf)(y)|9<*gU7Az#(u96IaN9w%5MWU{kE+&-m1hla1_I0EGuV3vh1NAfec4dy0X%;P~%&dM?&? z$t`$xkUVrK{b_(ASW3%}i=>Ew@AHSJmZl~l1qJJNYfB3RsA?SpUL*VUJMWH>Ft%&)V%-8dYbVJ*{-j~VJc=q9c85i zA72_ojg?9|IFzU#qfna5uXm=h1GH8>5pAOKPdA}i64V&Tn@mzN@P&+Dru06A^N&Vw5{M2jQ2+j9b;CFkp4vk4-2 zV-Oxf%v_Mcjwxz6EcZ~%x%4xNXI{6y9ddDeNX;+3erhO zE*h*CZM?gE^+G}MVbw2RYWTi?hlM79x-{yh`P(riaM>I`hz#MVBd7O0n7Lb@up&f) zJ=2$*(G`zBH+NXjV~ic?GdxU!C>mr@2Z?M8|0ZoDjg22AyDZ?;fRw9gfW5ECfi?8o zeG+oVl&c(OGaPWkJPTKmpo!p=c}72g?qi*OAkh!@g|ie4(SChJmR8T*bfSRd)C zs|P`)M}qV;L%1Lw0_jO|*|z0FN9pR`b`&UbTz~ZvOLX$OCe$d&Xodtt6$yo}c^E}R zTyL-WW7hx*b^%#g-nz4e;tfeZ)1k z8{JG=y0%Pvc;_N{a9tdpH2AhtrJsM_N(PWt|BKaLBit2H%Sa0yDpv}xl(r6JPBjcM zVA%re&yVbI&s3bQe4V$ijKRd-KkGp17~p0V;h6Ol!(WwoA1*1hInTB*M2z^Bp8ig8 zDXR&KQIY=cA2)p2|8o{c*!2+hz`UU=u7EAu+>}S}(2EDXLHK4;{LRI)&1d(8PQamUss<+CoM3ESh3`gr9=XYs{vzMsQvk61iJ?qogkmG<|A*`h>Ph(S{pprMw})L##K_$8 zXX!22A*BMcEun@_1S5j;ztv9v-eOy5Gu(|W!6`G5 z7O0f%*|ej)iX9TlC0Hre*RN@Hh@{&5mbkOESzo_aO$Ff*|6=Fi*fvBGEe==E%FPm zKPP(?^8sY~DeNfH@3GRM^@2`Rz0QLlPTdvf77a!G_r1$XOKgW{YDbBbqcAa9kP?|r zH{6F&&;glu4W0+SZKpr1r7?bsL=3&q)ujNbrW7>R*g7j48y2Bf0nEb<-3$ejjv2!6 zp#w;1_!6Hg9utB+lAbzSbagIMF1a|$2?M$wl8mI}mxDUjdgU3 z^S6_~sCjr)Y2_QfQ@d2IRgZuaY&;TP3~I8*O}Ve+NCg7Gx+H|wpN1Y&+OPpj@6R6v zNQG3+=$U*SkUSL3$V}9l{iLb=-nG1#gKxKiQX+Ii-=KD&wG-d^p%$P&w>)>Ck&Fe3 zl#Z@07%ng&FY4`_IEwHAlp974w#9y(-^!%f`)kDKG9 z&CX11!k+u1G)=l?OZ)_0f6xpqtIH`WNpIIv@B42Dh z1b9~SP;ugruGoh^-A}KWdc$~Ic38H|e1=?ru;O!95+s z_e;>@#CGp56rc!?s(I+TO#dYAIVim_?+fNH_d)Z>AR(-J7u7ZKTG+1|4m$)%-lxh( zPdp!Y;9nwAK@)XVapGD7XQklfUrs;ud)#hZUT4=7|1)B-`BxqhEi}W%+8Zd`Ju)0` z$oatvvs?;y1zRb$0z9v3nx#L(sB&_Xe1mV1!^3ZQnDx?Str2TaL{ZQe^oBHceN?be zp93oUuEXE<#_+I%BdK4gkF>KvM)SFhO=O@T>hIiQcpP=#*l3B1@~}K>!Q>Y3xry$& z9Zo^>OieAem=#|BpqCetlGd~GVWfoM;&Ky|@1PH`S1x<%RdT^f8NGtCQHLs%(RZSb>_yG8H?i=fL2^gFlU*GT2ofq5!=Cyt8v;BS zLNn2e`X?r`?Hs>DSKbD%ek61=WY!fZ1@%_~upxb7+;tn0Bk|#njoef9mzXLdRa55i zo$b_=&9L@><3zp6@h53}@uRQsQFiUS!jh8j-4C>Cr|oAeV{#&rKIr2&;>k~1Zw5V= zDegUeKycvNyqX2G5xd0~R%fdsPX+{T!7u=(ZyYV!_4xnwS!#gdXI z<^vCle3djbK8{{pn0i!sK3%}VZ-Hl5$<-GR$4E$aZZon=EO{oOB}smr$kEMmoTYq< zCKpd-q`}Ql>Rq^&%D$lS=Cx?-1ade86Fj7hD_L0+O6##ohfFhKMoNB5&aa*dM=*;> zcPt!%D-tG~1`P75??EJwY{s}$vtsC`Ilq?S-!sOt^M~UQBDmN8NE8SCs3@OyA_G8- zV_xmgnqtFRSs1>x!AZ0WgbrkzdHv7kIsm>3INnp!)6w9gfAh8zR#+Amj0#BtkM`xI zq#D4{1O$u;+(+)ZRU4BP@_X=1)$e##*2l77Y zN8bxfCAvnZ;MPD!67fmI9AK3iRzl-3r19>RPg_TY-Qq4>^&ed?kpDdNkO}vzo6toy1hWA?hDNF z#Wpeh2 zqdhV*@&+XJdY{Vnm;HKIl}2UnAx#KS9K@`zQ4h`jiaR?WEj0UY2spxwC80o||Dt;K z61m=mZNSdI(&e~N(e~cc$X+F{h`@~}7c$@AT89+ZHW1qNaUlYB>1)F|BuFb8{6&z-yYQ#3H%XV^z6x@T z3a8G&CINAu;cTKs8$$sJ_%i&AR{Ej`cDc?6_T6gNHa42(X#+7%b3eK7FELm#O!_I7 z+q9qE-0aVEriAHM8hqmrMc10~F*<_F2-~`5{zXVHMfg&Nk+`IUq4Q@&Rs%3vJ>z+< zVnY-E(PM8{FQliV0Ul>Rh*KtlS|53(r;5Gro0#|nPl#bF znavz*{u(nU%NHRoiNrjl=ePgylC)UREk9}fj>|`sz63)lZiXMQUs1#@$ivnQW+wf7 zQcJFTi<9WJ+=}75_{(2-hQ(svr zca2-|05Qfw$|z?zJMwo&Z!d{J!)?W#bKil79ACShEmQI1HAvFK^zQkfB-lOH{{BVY zz+lYn;DvY;I9%e6bfUj}!3IMCv{#L=Nq~thj7s<%*9c)G@iWp5JciGJ3K7e!fr>!J z`}Bc}4Ups(BhRy)Wn@0Rdf^wY6*Zaa0cV}~WdDjNJc;7uLLYIT!7L>J|G_8NST$`P z=?*wk>~IQ)+0>nyAXS5`U7~F~P^OTAC8&lL!To?d zOd%lUBN6QjWE3`-#X-UL3?4Hio(j+wuyF%EgU2G-Yy)y61uG)hZY0TSP_;}y`JBmfvh7$EC z3LV`Z$=3-c5VX&k+VzXY{wMw}VU+3?neWJ9)s6@YJNqn^3+98K;pt+Tg=z;Gy!6k*) zBcD2j_wpcRZLpf)J{ehmNv2|dAodzgB{6$?D#Ejwmi^6%Ei!4FRM3U}MHuwATSS@y#9!$9`hSEdgFt3p@4hKKXnP8~*Ow0W# zKFl%T-AL_RYy{Rw(1DJQ*AjF4(nsPVAlT~MG!P2b-|!a7kx=pO>MOB*O*95sd#w-v z?{1u29LqirlSr?Y(EpFB?||pBU;qDFg_KoDRtVYIvR6o@jF3XILTQKWmQ~0Kp=3lu zRH*DdGcuCwl~i`N{_p#o^E=P^zh2MloadaUr@p@T=l)#R^$%Ufs)>Q20AF?9;e0{F;E=hPuSRvBS`r0!*xO(6i%GkrQ*Uui*EI zF>+@Y%iR022~C=@iqQMo+uP$EkiI;22nUIs+iRK(y@Nwj{B5|b2weih0#YNHZ#m+( zjZa9xrBAqWP0Y-m78UgxW+Z$~`aLsK8su{1!)FzwFV5@*@O2aCrFY@}R|zR8qwi*) z9eQ9q8E3T$JCwdg?R6%#u<)CkmR@sKluN>ASvT%i!--fTjRMn@Aiui)J6twnStThW zX#9Duq9P=F6EdB2E+N9QCIpl@MSM(CXS^Jafl#WB^W;bySEs!J7~80vmy}LS440 zJWw>5>=U7RPv>7>F&PbY2JXt`vm0|)7CNWZm#v-6S6msI{-M16Ttc0!a_xe|>o{u3 z6&b#dzD0kz%*#scsh!C6YHW)EL=7;8`C$NXFS1e-Jh(}m(|@H66O2Ix=4NVLZ4OM3 zUy5$X=0U;O@xsOJhy`D(^TS;8}5YsK`UfhQn7l{;x<|11R&UfB9 z`3esx{*jt5*O83R*)L5g*>AVglko~28yyP3ZJRA<@n=dywoZqeD(8%^k<;HP^ zmNpSf5S=_^b-X9+2M-fh2nZZ#Q|{okT0SRA=}ck4els#GHBQ9$dgkxCT_o73x4Y1h zh%pT~s*Z(4T;Pow&g(Xa4J2kl_yh>2%d3+?`jG-pKrf*1`tWBd%eg1}$z53>8z(7-Hc2-CyO6Qa+@gdR_gm?mA$lD*mB@N8(-Ye~RRa;Jc5#*+7roGGmQ zy~GP5yoxBhI3Z}0PG0Z5ii<~{$OJ_Hycrj-BoZZ1IYUqoovQ z6zW8kzHgyyJ37|c;1^R6V=qfxR_jQDn~rIlw+}V9_u9T~?VTz0qngnTw_o<;1x@}^ zy56G=Asf1 z_4UCIfyiP1>Kw=sRTjV9ga;ODB`UHdK%vSEAGlM<2wEW!A($P8e{R;ieEyty;RXKq zU0=Sv7rv(=j4kGOK2KEQj%mdL%)wBFaM3{L`4e$E^u#3BK9R!c`sB?UW(bS`F6mfW?s{}Ykof#qcmt;apNPm7SaD!hBK(y^ z0`WJP@}O?fL4X6%6+s*|JRGK0jTK0sU z%gaj{MdSI!O$xYEQd3hOW0L=He-@MYwZqQ)C!6kK|I!QdoD|Ep72e0o4*&Zuki=TQ z%{jB!L1o51nfjZ&=;tZg{rmT8ZWAeaedTV(l)-H!T}2}SC#&{hQ->1iV%`GMkBE(GidyC zyrBB@Wih+0N^(5&D%To`jLR%MV(55P^_jJ!XLZH2OTF~Dr3-+;+9isC z(RTTd+)$W*w94q@EuGNBdpL={Wb7i~i~k5pg1o-(>@RIG&=t3SHXPQad!7PC7P=;T z5B)p*?e7m(a*<$ghEvex#|1zj_BUXonTeYPDw*;PO?v!(Al)Pa8e99}l;0!UuZEXB ze);g<(LeB<;b*3KHr(|0`M{<3SlAwh`WWGJ@+1cwSRf6fhJVzkZS2G8xX-0R3!J08 zTob)+$?L+#Z)Z716A}|&T8fuubi3yFpgpD`4XGJYOf!~IdaTLH%Tr7za|7J-xv040 z4v#PJ)A#0%WY&L~mb|kBJ9>Xzt2m!e;g=q^*Biev-a!&Wn~dk2(W?aI4Qj9AX|E-f zl|!f9K1>L>etE5t+Ms`Jr*>Y$<^3(+(q|-MZ^!ONimF7>JQE8 zlxySLW-J7*Q=Bq0v1%7mHNSrJvs_b6yzJ@G0{qu{+hDVOc|xE+M7}f+Xr>v9q`D6! zEBe!^I|*ZbOYkHFseATv(p~y`Yp-$o0KT*#>31JR`_;o~lGP>V=R;Rw7c;s1MY0`b zHn5{f_V}auL(vXG{CUo6bysP$!$dL?{iDqEvS$)Kzf$z!89-KHKUgN3sb^(Z!QiR7TB^g2FpcvhNHOfN#2q zrkTh_r?ze`^voU??IjrA#&eAfE$D_oac6+ z-;-uS+!Yw;*Wr8{1qFsx;&TJqJOjQCxyd)XCW*xy)ek;RE;w7wE^l!-bLOdgnTdtt zgvIQHMP_yN)}wdEI~%VwrOB9#ym2Laxzb2ur^v}=B~Z9|EBh^JPDko^{0h5DsL@vr`Rko&|Vkm(^)3$qOCp|Xy9`ooaTVyImJhPj!7l1JKWxM z%iPN4NGjFOv59HEbSkj+IAbfck(!PPNv(6(54~k4ZQRnE zbX_AP_gL@;!PC9hzc+cE)9u2)P_BO#KenE6o?N=@eLeTA&0W%CzsfaE>wQ$lU4iZZ z#4KJ=AC|O7wP~_4va+VG;TJTIhix|n3}OT2v2A0+FTwGqE(;i2u8!H`XV8GkJ)Ltz zv99a9>Y~Y+!(m@yC-o<46C|^)ASD5J7Rd&Lt55T26Sbmva)yb3RhXO4Tmoe2n%EVL zhV;V5nuphFPk%MkhlKH-ApLZ-v?#W5?!T3rE0x1Ii^V857~0UH)IdXU3#;o0Wi&x5 z9Xwbb$jFCVA3_1jMXH@FZGB--)ZjLpZj^5Rm(t!`lo(9VNk$!Sc*3;O#RL@X$udW< ze`T7N+AZ>;sV)D|gPW+$?m1zXi70x}j|(-bMX49JG)Pc*N_d$GOBAu*?y|bE6%^K; zTL-9Hl+qjPRB|u8J@Hbr*gpx?>R#F&dis-ZEBSbr;~bO72Kba}A9RmiqA}R7!h7E` zscu&Mq^gF1_~;e8Hc4OrrZ=)GRpO|}!s{G){e!%^-sp`DNU>kqPq}0HQGC2G^&ebk z8se8}=#Hp1Xiozcx@s>s&toZO3~89+p(`f7$hH$sT{skG$9rK`k-=Ytx%G;n?0r|c zgx6es5T?091+f02ll)xN1mn1{QOtODFl@9~^)9oEr2XY^oRrSD&ygBg+1ZOdSDq+C z=^?Xi0wDvk_PbL;7pW#RF4t|1?-Jh2w30MEOFpji>Z?xvw z=j?0kFMjNGhYLXxXu;uch?Ch}ML6milibcP{Oo2%tInR%ZYOp2m8t#EVCJVwD(;H! zJEUGF5|2+$Z#weZ00VNNnXKKq|n;2ay?sj^po*$iQDe?79n>*O?a44p0?Y;8&NI~IW(@(--oJw~F zEAA356dd~k#MKb?g2L6`A3@N)34cc{V}~MUV@~ZaGrYu=sHwMyzX9IBvf82kzw7

ozdxvxuC*Rz?`_|S)r-GO8{Vb02i#2fmR!vrT~9sIN4Cm zYRz=d&o_?AagS+&RhmzTeroJ?^iA~sGorlO-JG4z+N?ZB2Tp_t$9O$(5ArfL4i0T! zUo}jH$aq^ENV@S`!`hnr!-o$KGxF)o;-wam3Hjxn3oA+Sw5X4u<*mqj6h%Ig)b{_J z@~KTzmXf8YqJx;FCIZLwC6u?bjaN`dv@;MS2A|}BWa(xV=Iw>0} z@GY$3+9yMx{zzYm4)0rz*%tb{y8ZY;f7gvq;^~RuKSy=Sif3LAf#0 zUY+saYxQOhW{L$eR*Lz$di~88pG!pqc&SD?{Aka7_Uu{dt_;IBH!?SWpwAufvGr57 zI92)9+uK`T5ZjTB?X1rS84rb77VJy-K$h%*~+jxK03N;MbB-`c)jXzpz^bmGy9AD zLJ)jXjrpkC)<{^?BKH;*)!`kY;-`2NJsr?RW1G|kBJ9rj9bpA@$KMjN%Hi9rR;56h zvGdyRs8D6VIAn1t&=_K6x(*O8*uw6@PeY(>@GBIo{CJ+@``3q%O8`RfgDVAq-feTy zJ1_@t!4y+47Vp9kQq|Jidyj~kf+nT{#K|;h9UDBF@87?}f325G$F%zU=6!-XBp4dB zL1eWQ>$Ag5elicA(M<##oy9mDK*s)Gk3LD2r;H?smGeU$4_4+6eq&NRnd*|j$Tr=! zd(zmVg@?XcR?e7%o_XtDp#TwU%Mm9TNvgV_iP`9w~V#ynM`nLx7vb(FB;7meOOspNmYH{-k% zN$ZHg1dFJ-AEch?#iQe#7q<;fYSUg}?qHuTWBeUoDS7W_4#7gG3zUkDDZ zVkC-+iWE@hhh`M;Q#gEjM3~aB;l~!eVxTr}=nL*oUJDurKIj<7$@}gECbKc=T^&u*y4)@5!sb9aU9_%r=W3RJ2Kv|{teEuD$+@4=x zJ~ znqGz5QPpi@NpGGS@gr#-Gk@5Sm>qU>?DK<#+esaFM8&M{h;ov?ykOpWnxdBGM7K9- zUhE`EEN;)1?E@1i}d<>lmZFS!pD;#mUUYg_Y>idAd2 zw5hcfo&H6nkex5`(B@@?!r34ho_wO{9Nt*Fn!Eq=U)5xKkPk$zw*p6J_;{|4a#&48 zv7p;I#x(^Nnkh&x$^Bl%n|C&6vTU*EFIlp9yTGRAqf9JRKkL0bjMoZwuMDqipWpev zdWqi!$}C`M_{0pfw+WXZ?nc7>fa7qz&qENaC-D491JcRMM29Hp_=zKwQ;7wLIx%ls z$^;*HDkLIuCfE~M{w4ibszS)a!hGhRvPlcfj8CG{cF&zKG77+oKyngs+KBy8yZV)>sB<%@{IL|5R;DQ51Y7hV>j0cZ^N$OdgG#H z2|+>KEUp-_q*}c}lUq7jj@tYwG%~NC(x%`UeBLagtM!CoyH2a}mK4uOK^2c_4O#oH z`mg$AL+Dyg@DHuVeoYE~OvSXtoF(LTbj2d`=q}pZZ2r|}6hcn)Z~V!hng489VJDR% z!~J)uW*>02wT;D+yFdw3gaQvdrM|7n-Z6t{v{2$Hi25e+u++KvY#THkDdc_l^}sKq z?NrUGtD;I{(L+!lw|NLN1tCifaW)hM?#)1ivptRkhDI&yFg%{DczKhd+WK38fg!xF zGG~{)+)G^9udhkhM>cyZ?EtMMF<}uSCNOjL;AoYo?aWXWWC&-Hjm6Gmb|x;=KN`y}cNpmYV;r8PaXrR*t|WcsIn#2PH8IRo~ln7t)0PX#XSh zw1;PqhU`c%JOFv;7Z>^1@1+2hha)M+oDQV0faQy?(2gZ+!QF=K1Kr*|xaVL^4yoa~ zA!^@$YOmgclHe}up_EwBrVG^0MN|JXL5C0KGB*){73bfN#vD5qlln%fz-Z?DMrr?t ztIrwPF0i@FTi&sk7))hg(HG)9_g&|q8MMj~{JEj@qEsZfso7^W(;r50PDVUpK1Z{Q zI=7VJ=4?>vYp&%(x7zM;TUUOXq#}=sXwD3vXF8E!DeJ$~hX3s^7+CezvuxeHgDpC9 zF(5fQ`uk=p{l@3EWa}?~=PF((xF+Q3tgHS}C#hb*R=-iJ(8^6Y&B!$U`NyA%_07$W zmHC&-Is^3bQR>M_n>KBd;TLo}_2kk=a&3jgBcu}slyM82|GqHtQ&3OV=C|#`RPlmi zeq}ehyQsIgsy4IYm3Q=L{T*zwNJT1M>BuGwXHSj>c3hljOC$0Zh<6mWB~lR8F3;m1 zKYm1{+Th$W(PeOK{jAJ^_S<+9Ks6=&C&rt z?``BX5pA}o+>O4R&mTs>z)@3EEgrX?ynCEToJ0w78e>*5-FG3vD_uQ|BvbjWfPq(Y z>iWr_A}TH%-CpG=b9zr5IxWAY$o=RpewJ0wqDvz+o3P;qTU^&+i&e0I_~uce zTc9{j6ARr7-S_QRQW{)bg+l)hx-&kGZA7(1Vk87sKd<8x5QsRaH#EV-B4L5=0-U&s z%O|c#&Bia@;bLR6Vc}h0UkCh8xOd*^Jt@pA^0KL=r#)XVxT#lx(UYO3E=|-gw7P%% zpG#`P<3e}PSi<=aG$r^#5A1PM;cgY-oca^C0iw?aTQm49<9wL{M;_J;pO$z!pDS`> z=O~T3&asClJmIrE8g)xhB%CK0ufV0tmu0&?dwA-Lii%eDxRoSEmHd38R}d%>Za~4wy$^GFA%8uiPEa*(7<}KP7j^c?L%BS z+N$(s6QaU#%gs`}afNXczOA0a=?Uk{D}z|ZE*j{i3A2t1&2Xj7UFO_IR=%0bxIbU*J5=F2(eJPthr*h?ccsl1$IW1N6a9ONYGlScfCyouJ`H?Hn z^YhKLXg}LVWMu)JIi$Z=*p?<`N7ys+tM5;SuBGab)f>1i-d^fO!~o&h-l|dU_7cu? z6%*5{cv%;jvOY|2NPG`K1OQ5tVE2423$?q1L(+@k&(*g3j&IBM?A)d6r8bkt_4ea1 zv`jx$nRh?hW^%uOidcublSY5wdLoH+N25&gwDvpdq+27=)7mE^HGR<%H}2QZ_E9#9 z_*}6k-Cz5)wvlv3ZpCAlsw#sGFe2`p@mk0`7PiSKLX4ZA*jE63gp{aEA0PIb0SLOWoF03z zkN$Z2l98$DQ}NNDcwB&ov`$c*P%}y5;oo!W!>=JP#kIdC1pl)3)cARD+ndsXpn)V~ zn%OMZBRlyLJ@(8YapvcVjfc${?H0ld7stYa)&w+>5+PH2J~+fb4pbSxK(MW)_El^Px{$$yBd9*rR@iOKUVZg_rQ#^W3e0HP?<6s{}7EC z?bSyn!-H5aRSC+n`3FEPf@FiJ4~px3@7|^e{j^At3JS$o2(H}EIb3umFk0K+V##MaxsSB7lQj0iD>zl+fh{v?kzn*!?lQJ$v2v9*K$f*ZE#DDK+ z3^Nvc@yxm0FhMZRBZM)esywQzFgWqCu22Y9gR=PTFAcS|HXa#oZZKV!udPqpU!Nq) zz6%aP7}!vdaL2H*vj?OIHSS8Ne$+g!1@#jM_)z(NFJ@x8mtohrdR2A=+!!HoP+I%@!|v^p&+TP+a+DhOCTZ?U z+kNwY{zxS|Icw?b)AUejY?0!YA!bHU?o%tCMav@<>d*c;MN0#NxlB#i%++b>#u;5m zOm@P{^%wT+Rf1SM7y~{#3wtaz@2!RH9`lKf^l}{Aq?vfP(-LVsKTkS1q*q6pdbK`1 z_nXqQo8@yowUo+inAM}`2ey@)nI(Q|vt{u4>hM0)8~>$rouqeMbaHv$T&1jA*KU!& z;47WZ9bqWQG^zC~zAlxV_u@q;qjSoyI}f=Hl{0v=aDan{h90C!c|17qhsk%Z_FJd2 z-AaNMN z9>Y7!hT~-4{ofHsCcw*kMbfFO1S>2mP`m@%-U^(tHwLZD_$!k$aoD*lLZV zF=L0A&UdUo!!o6m^E*qc#vcfNGrpH#GOiQCPCLJh)JK z;gU?z2|0>-22BmtwUVL#C(Lr7!>qh!bf8h&PS7#`!t}Kz*(zIF7&Mbs}M zAAl?#jBSLp5|opchle8Cd1n_FBAN_8iNza-L5$!(J#cmj6#}so1i~=wr^oVkRXMyF z1Vw~76O4fl=4gc61qTO{PQHC>xNoc7 zur2@BKN@e?_WhSDn=UK0HdFbljIeC5hLOOaW*!tz!!|x zE%R2jIjgOeUn0 zCVQE+B^)BCtu9oMUrVYTHF7-55*4li2TzMmT<6oSH~Sf_IGKj z^32A55}pRHz==z7HDVVox~3YBkbm8mqN_?@qo&*;=fR^PT4lR0ohyA-U;nw8+Qyqh z_k=}^4-Cx6kw1e5!Fw0PEU7kw%C+jvU!$ zTq*MC!~6VvR?Nl3{!gLpw#Sd>E>ErFt*Am5sH@x`!IQjI=k0$;Td=n~#YI|y#NPtM zd(XXiZOgP1Q>hg1=s|)$Cp5V`M2;8so4)7Ou)N)|g|_92Fc*q?+fj949u24CrlwDj zsgWS>c0h)`Ba~0oy3b1eR%m0(bLLTNKzk}%Z;&~e)=rQwF)ptzp7O2PI=X`-o)zh# zM6SwhLDJ|Ok6W~5X?XGC1?7b@-FUvDz@wdSO2a+&W$-31Pc6KVr}k34qUND=AH&9o9 z>0>X-VOw~d$@OAxyk{RievD)Z`0jf`Z%9m1yWD!zl^bsiNXl09^fr>ua-1J5WSYCp zJo>(qllJzP-_$C5R;8PjpDurLcyqccc!$E(AKOtY;;(S-z5FIO*GSx^^>VuW-M~Mp zwmsjuKt-tO0RBacqD)tCuU ztPo2;cu7y*`1S7l)ReB!_Hx$ZX)4H=iPa~VQ)O_mVF{fipc14B<1b2bGUP>;xyrri zufh08NKDz-*h(qrmHo`DJg5j_mNBe`k#1A>99)+dAdUvyat4JDdgw0E5$ul4NcLez zGl-(u{#MJ>w8_>KZy&xq`~~FGTy?(j^W2=z^J{|GW=V5YDZU`8#HD}A=YQ|KDto^8 zu59Zt+|l=G8I?IC+9O0K4;o1`<13{l-LaP5{FVKA#z{Vu^*^)cK!T3YB(oBCD(e07 z<1aPc+$3&XTn7do>LgR2XAv?$6O3h0Xp>!jL>~MlY&%KlQ_Q*v0ZJ$asV?m*?Tn9&G@^xedOiekC>n-b9)_Bxze~x*8i?LeEkaIaA%%9b=W7d0b{L4>b)%T-I^%-T5*A}vUtHONO&JgRXfMfhD##@==Ki2u*R*{U^HA z!jgct%Iu_ev(ZU)Tto~7A;NQ4CfI#YXPU>h6Cwa;KM_qxux_AcQQgxme&(2q0$D}K z4Z+1{Wg)szt#~#%+XiAWd`bkF0mmiucNi4$tr1(W&b6vG<%dU;zmtqClQ%Qd)mf zbDyxEKUfKR5ET2GA@Lmbcr~a~E+HUoYm1!kMLNvmfegG1gdzg(Hys^aDQ*kIw&5pm z|I_Ul`IEZRCg%Nn8p};_M)w7U=4+)?rvQR)Z208qSZqr265w@rZZ%2QJCYVKMnP6z z-1Vj{JfivX7(ew4G&7P$58F@9D@MCXXG(i$#_74JEJztT)7QLuiasXC{Lq;MvXk+D zr3_WEoZRTd%neXusa%_w`d-?exR_92)ob5Op>}OymZ7KGvM#)c?A%MiJ%iZ6klNGb zFbf`3W_+^2@>&bW_bdA&^^AD- zEi&$G775I>4lMZmar6Az?C59jemqo?3e^`LN%E_v+b)ue{egS?cw>`#|T?gztu#h&+n zxW8TI-B}h{#Cx_eS*h>Zqs;sE!cJDVUyN5BTAr@)tRJthKe%qQ3{Z1kI`|`G~t}X+L&Ez!6BS6H@V14-uF-)lVzM1Ka8e@lO7@mlB-u>|f z=|qHTUg3h@y0|WHL@E_4m-6Xa=I5y=J9mA|y-2~|zC84ax!&@c=<3VCDXNm!eB!f# z%|e-R#$pervqmA!XKB!UWbGvAZ)Mf$v>jgyF^2R{>Ec69&H;3o8AM&9@ zm)S4`r<9)0f3xq$;wlmQiEDXGWE(&ENb%B82%;n_;UB|gI6ao&#>=q{r|c$UBVuY0 zX{iNv6hbK!c*1akPY&kI;VQ9=pvkrwUTx5zUyAlvyMcp%WD<1lv#enJsnVmeBp8|_ zRp$OShTo&9kgNDV*D6BLC_tH@Tt^NgLNZSG0-Tl^BZ)bIn;^7#>h)$U|)G=k^lM z(NrT1Yh&}kvNDZ7%SJD67%|4@dTE!3=HHnhfnE_NW~QdYkxgAU z&9dFTzNH~@7KyU-822HVE8O>oIK=~2J|Nlp!_w}&Nf1Sc+NPv>EsLnwi^fH{!X|}> z?1wk$HPS=p@_S^V<$ zEHk)E0mGzF%((l8cY(H}3ccI}PIOI7K5{Mb!-2jW*^ zXEA;{gdBhW^-G7J$-jC0%v?~?)s|7s)2DY|`}K99xKrbf@3q-~qFvRUaireEPP zZ!&w{&5b+SYnfHdXL4q=+)4PrhJ~oiozHhu&(FFmPp_^M%>tjFj<20nhaLmXi#vBV zUHiGXy3-=pW6oiWrf#*4oOMTJ6n(b?L*=YC`5sdqb>4!mzt>bq-m=nv*CW0&j=lFP z{H1VTJB&Y~$+N4ToNQZ0 zEY!52;VJv;+RG}A(HgG`z2v&saI;zd6ptpaRF!AYqSTJK#xBEbE@h|9Ti=BR_QHvF zKy`WD=kO_~S7hQ$4W&9mMK~c^^|R{&lhP^@?mQljfnVfPx&ExK|0~QNCaAb^pbO?o zXJ4i5Ywhl?Ynyqz^2$7i9GQ#62Er?oJU+TzMoB}z`Hd=r!}qS85;tp;7Kqu)msdr_ zopUZ%%6_f^XwESclUuA-?*6ABlDSH=j5r()B-4CVjXRMzJ0d0swViP>{kCnn1HM3@ z%0;pZ1F%ho8&PGbQZ?|1bw6}DcdiO{TL!vKtx&I|8N|YfNE{pjWV}cRlURARCnjJk z&xt)zQBkE+i)X+>yf_C>@)ummpAwbsUQoaq=wKVkTCZe#@1`lg$7g5{6=5X-4sYie zMy`*qFDMd7iN)GKqk_%A!Lnz}P3Yv{vqK;P!t@UFQ|;#5eQ|HWw@N7ulMDAY5egAd z3SQ5|Wc=)!^%=F9nD#Q=J0M$}l%gh;-9D@#@ye%!8@KHE+`iQ<(8CjwfZ&wJA3rK( z`jqNSlGJy--n+wJbS(0qeqE14ZF{4qRim=@sI;MK2(3M1u9QJy+RxQoMf=dwt#>Po zsHA!5DXD9t8>QMFs*TY&)*G)`D;p|QWj5(ZMe{r`o(Pcr!5CG6e8#hLb91fVzCF@j z15oC0l}F^R8TsV0S_p#}wKg&WPkZg+NG z+J`hF|H+8Iyp=AMH#F8WuD^W2(S02$h&BgL(W`HZjd5yVA|x66{Y$pt)R)m{lPg8YMh*a9x;(Nrg7YoaYwFD~*Q&_s;_c2)*s$uRPv;9|oCN5)@m2|-7Fw8+KT5q(ITQgE3N zvuArgU_bfZE6l)zp?ZFe+Sy5uM)ZZ(te-Wwf!`&6eZbeH0d%=XWr&`1I3a)`ef8tu zB_MwS-84J@tL~A!u*ar7XpBJpVDIMMF%)BUlzNI)QTai^$#cj_=Z2Gg;Ym)5o^Ejv z&%1r$M|1ZE2Ouj{`hj-X$Y``D<=0??TL*zMqP`PfCZ-zh_3ye538wx1;f0j?9*0!p z`X3QI@l~-8Y)KW1M`I$IamIL;MJp}@y5tV<^w712ScJKAZJVz>ljN1IT=m!9{>aBa zCnh>wi*E4qU37n7_SU^+ZZ$f>G&8R&p~(S6vU9Ckv8tEP+PlK6Xu*b{$~L|f<0i{1 zVpEZDBzG@(^8bPMlVJR?>|!$kp%K8t-=(m>EvZiurT#^k6OoP>9f%X>Y)R``lkZr- zLw+hdnaq0&-Lc(?2hWOVUA&l+PKO~9u~0Z`1N6R2T1Kj=?LWVNZwbFCV-~UUr>kV+ zU3y>UHSg(qN8Z~z_Ap*J>MEa1|BESNFhZB>G-wuGVGEu?szW1UB^S!M0otuC)uICV%CfF(#u@jU$8b*JAx%pCrPhTvCaFb~6 zLDx@~ zbq8*a`9WhwY|r|s$otnx6C#r@b#RS~PpAq7m#=8J{pLCghu&$EIr;xWyEZm&C4Xqo zLA1Qf3s*H)bYXwC-T*fX5nYd$VeM#mQ!Z z+RIn4Z;)6i00lu8^iuHYO?2)k(8~+T+iB|=C-{=fLVd&tOI}T`HZs@x#cUtTk7y`- zxct`BPKrnHsr{dw@Hj!m+*ox<;Zp2a*ZN|A*p&Cwjrhq}@l#+yY?Wtg`9doNa${zLYK9R;00w>2 zg_)hliLw7SW5Js39Yo7b3jOYTsCe1o!HUJ(>w2TDFHatIAhK-H1wra*V=od+j>ZY- zeUtmZ>RvT9Yi4PG!>3tUWBXTD{p!cgU8>9r-a@;k5Zf&d)FgOswy}RU^WVZ$zQ76g zoyQJqkUUbqGHQgxwxVW|sXy;_M9K(2tfDFJE$?HEI(|)1r)WmvSFIDavpZqIr^)Mqqu|Yb? z@exx2gk5d(qfiQw@wd;bYtkJ46?3m2UR@(J5XVI)Yo#}xk%=O3A^nE1+}x#Qd^i&Du}ZzY&mS(jy$X}UW)(sq7s*R|d0=e1A&TI2JV z9%-*0<^kwEBe+{6^8Puwgex;r9fg%Qsl7~1p=#bIDM>2nZ=QwSVdKtlO_=oTd-$mE zcALMpAp?wor(I)=Pl0oKk5#5h5x~VuhbK2z@{5WRf9d6( zcnN;~^!P4zcHE@c{~YOh_?ZN7aUxj}%DMK%i47}gkZ-{>3WFs6-}D^Qom=hah;@MX z@84%^?)vZ4=;zx%sT>V(xV)E9JF1V96e9T54s5|Rfs3TFG#6(G5 zR2$5%g)@a>iRwfQFQV4P92idrWz3UqAw5aIG5;T zUxQ*hQLo&3HK5yp#Hw%oyhC`wWb8?XS4`&PAg?jg#>};cb{Sa&Eg@-KQmYf1Z3PEq9%V;dH{M{5bV>y@?=g27W@BjfnmHR zO5VczsP)W3N|i>Ed#dX0UGy_t!OeU2W_uj94%Sxg*R|!Y4R=0b0qGEw2N1|s{t&mS ziOd3LZ+AX@Il30BGK*PBj(sv1uuRSj-@m;-MNoP zSW`q;_{;StNA;dE7;mQ{e9eB8{+hRfs%*>P8-@>QIm(XaTs~qj4(<2?$qt^!_B%wz z74fAsd;h-tvq~PyE^_sSKYwy#J0RI0(a?98Q0Ah3(NKJlW1t@Rb-k}TGs*ZThaqJ{ z?Kp;wwyA}Hbqm20t(UXLAG9~v_N9F?+RiFSeUWi3D6sxq{5{g4b+ZuG!Q&)#rOQ=a--Z+LiJTEDr&<-m&l2Mqx z!n7=S^I_8VXj{+RMuzoJvH|41M~;d8>mXz58-8+^t6aioW(#qXYG7a}{_`&T2|oTr z+|25FX!uZ_5o5b!%DsTlsA09a(NpyWP5>Ec-3ZS7B7$g$PA4lXB|l&OEE(hzXH8nl zY{K6$7ks~Q=xT;y$d5{iVn&NYA0?li(%zUI@J?8s(dK%eS-RMYZ*>~Y>A%ua5wRnZ zEJ)+KRKabF@K$|((aiAW{eiR&|KxpM3^!l z4pH+x>vsUtd4rBX=b?G(6ekD<47fS&GqxC6Qqt4!EG*y(lMNv!CT55ci0%hs%r{jw z&LClTK`HYZyF|fB!S+cZV)lwMd}*CXuW_*AZ{S}^h^XJeN`WX0n9h-HMWa6CfrTYn zaOCvtMfj+SsLRXiHzECkJMwI}<^LXA%FsAWYtQUAU{g#p?cd3^lTKGBh87EosQg5# zvn`HoZ@OmbsWJ9)FCk0d7ZrBjfw*@^)rgUCK=5(VI)G~YC|gGsS0Q4Q_4h-hNa_6@ zI{r-#XOhC;SSB>o78W}R#UsS+uYau;PNnPZhv7nCFEvZrp6^9p>H`mwoX($Z-4jH! zwtU5^F@^X2xJf`DDB))rHe(H<;(Iss=`+w#CLJ9!t;&2M9mv!9rdMyg>QVhvTs>!j zx)+0c`LP44^(<81m8rr^Pib58vJMGP|}n=MA_w&LQ#!nT*C(*$`tY;zC<&ECKK z={k0Lb$e+qJjrA17V1p=&B)m7RkWn;hsJ4dM?v8OHj*)CL)(v0W@<{dv+rR#JrIKy zoqJ>Y?!QXy&)LgQ*xnj8^Cb%QFHhN>i|I)8XDwa-KP|xhm&aY&Qi6V-DEd%a8WwHB z!m*w5Xrm>|NF?=NunB_q6xqioe$-eFpnk74l&oz5(u*GDreLxc6A^a0PeCCN<1!8$ zM9*bYi_mnQ0Y?HihLfu+oQ{OMMiO>9f`x-FfPPNfQ4K^242+^N40bmeGkSOWP|K8!aTh*ZlBMZ`?W)4b>DrBnrA$wD}%5VaLf1f8z*_qXqdHk zASsIlDKxQEEr?yFvkqjTfZ z)LWA!HrCtcq&K}ydN1{Tw1PS5ZCWz7d|`8Ds50mIxLl8}U)Kz1q?{8vobCPd zgy>C8VQ;R|Q_ERX+n5O>QVg$5%5dOk6FphL0Q^=BEiImryw7J(h zM`eO##*T~w29V$6;iAnLUk$akHz&x`qt|nvNQ*UR&yrv~k7olctlHR6tbck9hURvQqx{o2MVQ@W>KC9 z9eAl|clk+UbF6yO@LD-}NsHE&sG)~Ya6u28v(dh5SL}yrkuAA(vDglgszIW$Ey7-1 z5LOQ#B&yFbsoc$+-Oc+IdZ9n zfL{a21tCT#>CiY3Nwgk(qg$xKsePO!Ozuy@?K|_; zC3_H_F+%46-xn2vo^UJ;yl(m*oJZ#j z9VzrqmPh$5nx*wAU$vpsX{QZ;-?TIQ0c~DKZ&CycOSD=>sTuZI!q;lvl8RDyfCq0i zo)Rw`9WP5r8AdO7eE=U2L?2je5Z?i1JjnjAP#ih-0ZS`LG)y%USMaOLVfcrp8eo2_ zQ&dsZwr$&n@XnFMg437(@Dx)(YW@PCPhv8@wqu*d8u`RTwyTR?Svb$3i6>Ziu=NcAu=g_Wl`c& zlxiZrptNRHH%R{a1UYeJ6?O zC*I=L7oz0r*S!*=4Pkt|xXQb#g5C|+AJ89Si9Dv+3kw})XMmDH(W~vd>)1C(% z$)mN#mo5R&4gJho7hFF#G5bvK#p4d4dAn@Hl~;Vnb8P{?=NzEj{19zOmj z^yr1-S$y6lXb)my1XC8M%~oCr5h_*mIuEK}x@M3khgtOvz1ab-mTlOyC)MGItnaiC zb^_znTaGX`u&f&Y`KaC31qS5i&7063)foEBG82a3xVShXpaAlG0^|kgLA0fi2?F*Z zqy^w&00eBACgu@P+L$99w4Tr&T!7O|;}}z4TW|^r=@6F1!khqu6uJg&(47b+qk&Ke zLu_No>z-5y+uj&!@PEdL^-h6tRr_sc!AZ>@d7Ql6L|Y?xkY=x%GyW58#RW=03{q zC59AFZ+fr(8H5udR#xG0p8;pYG3~b_V`I6^P?3km% zD$on719d{lKaX%rfQdtdD;<$`xc~9v%$-v8UXcObfu$xyPy+!g!hsLwuwbFn@;?g@ z!Jwb*v7>wsB1H95d(xF~Mz)_+s{!XWVYDJAo2{uZRh=t{Qun*kn2{{&f-O_e9Q}9C zS#4^&A>PmyJWwZFgh|R^U!Us{UROK9x%52aK69CM&1%Yzv>jmx_)lqlmfmPmucQ;P zd46~@!CADvmTkoqDz)HCMxqZqBVIV!tzTUIl|LD?d_D()BnQWe$Pie65K&o4WC{L! z(>w$#d^um3a`{)ybNng6jT%=iDAy7F);*Y&;3wJAf9O309*v{0lnq?RcnL#AX3r4-qeDYKA- zlp&!MMN)=}G9*(-PIe`gA``CX@aFYl3+GBwl23$0MCKn^*t=ftbhI+nO9amA1+hF;JTIuv=-*}lGFbYF zW%*9*K2#y|$XQP>I_Ha5e8RMrpp{WW-whq*+g1I)=9FG)6Kh%v7An?;f}KmWX){dAuH?3(pdVXnrX^*n5Og@ z0(-$~QwxiRS1@@~*ZxQ@RWuL^HMbE}qX`0|4oqUzsb!0I?}R3_(;I-PZUmC8O&CRT+PY0Ji~D+7BAaYTvo?CFk3Us3L9 zZezLsePE@A=?}A>IK7q|Z{CEs-yO7&>uNCjrjm{A1JDLdbb|LER$fH?+hSd^4ChFA zULFB1G0sj|7db7r4P-bIY88y70VQIKj6ARi{ID;BJCDQWm)2#P7{O38{Dx&-qs>P2 z-Sc|o<7iK@+`o7Kehqe$uX}?@{sevlaohsbdiVwOqIhV~H)Ka#^mO=Y?XLcABr~BN z=&1cNng0z#0n+m96!6aE0~cm_jg_c&l{a#Swbxk`ovQaRGZNVza4?ib_M(`iIyR!3 zH{N7wv@VlCb}e9AP%R{foCEFcDP(nr$5PmTRN-t!y?_-zk3uJACk#tOM6>(s=pKLu z_=Yh9ljSxWrvQ|zx3FmiGX@JTqC@uXzvd1;9OLl>Q;BX%^2Ha434DG`121pvQsCz` z2%ne|No#1!nRM)LbXA*3eLB)p9aI43(GWbSN(9zqc}M7~a_dy*Cucl;9dC6iiX^Iq zf3XQRZHkUzA6h1~C_FxMRjOJ#(`^6F#T&C+2ZhUhd&wtt%-L8~1_~ z(deoENaTo7H`5xm;-ODoM>9U1dTc$8DkY`1tydvL#Lm%fSSHQ6wF6cIB;EH;`bp{Y zVC;entL)zOdYR3*um01UTF=9y=pYS~;}un#6cLbaSvXdbP_2DvC_&+m(UL#)X*+4V z;CeyW|8qlkQzPC%vI0Wu_EUu&ZbYV82_$Iy_U%2?AOwP0cA zK8i=Dcl#~y{jt~tI_eexZUJ6U#81WYHoa4S`ne^_^*YtL&uKgVYcWGOL3T7L{{LO2 zhqtzN{Y-H94jZ69cx%4TT)hQ=^O^UEw#~I1=_dXSq7hdQTCBrPUID!lc_SWHOn;g; z;fQMpBgij>d|x}dd{|JtNYNxDc=%}D#w8WIw1h$}g9ZZ)beN=mQV)*x{4q?ExLqi& zoIeF(>g3P#(u8(;vcg=93=ObqBFSL*aPaB0CwA`WYPJZ}07C;Gj(k`Lf(D=IWd-q^ zxcv0}qsF)N-IN&3Hi=ghde-ZEOepk5qd-0^9cLGgCNBz{lg+8-=B8S`i$_}pD{kJt}^&QxVbHtol|yAIi9ccLSIw4-n|x*PRjAI zn6BTvW2=JVoO=Fh9v(dVoLq)>Ph&lC;(;l6C~=_2#K3{m2OcqZ^^6!%&KDV&8eBiQ z7I(<2s7N26?#@wM1Dg$Urb!zMql6QixH?BY=Ox1a<_@H@^nX_4L(wL^Fl@({qbNY@ zGQC@@>m-Z_($YAwQBqE``h9lvV@MbWwoU zv*uf{!boq0|I)m^YH_5hH)wGn2p7ol^z(}6osf}*z)7+Py(Fci@50<;H}@H#y21!Y-TaMWL9MrAPg%P-JLnL)AYW!@1Cyx z8pJ**MK+_g)v@r=Vo!t0`|9tWg*%hmD0^^~&0+oa!<>sV4jvxzxp9M&QtIQ&N!+!} ze1!Y@%t)Wuk3nM6zu{mp4y2%%&B!VvAQkiF+^-?MDjApJ)P&)HBeSY?j0Xsu)441Z zk|j;tZVCQNJwK#BizGDnFM;zv28V_;p);stw7BWnoCpF|G&T%J@vBOQ^X?PT zCE!~pXXme`nRBbLH#h^S4v`#^crmyGq4E^Z-WFjGQo*&wWLKm5hOyJ5~c5x&x~2$CHSo(&8SVAI-0AxI4(F8o_lHDvz@Z{RkCtM0H!ly|L;EHtEn|X*=bUBX%iBUBk_kp9!WvNqYx54> zx2*Mr5~~effS6ev@oJB1b%HR4!w%yx*#gme@V;P5R?1Ve{at^bP9ctLlz1oVo>p!d z$wO~Wge}>Q7K1r&!7bv_O}cv7Z(bo3nNzK~84})#+_sDx1wsIMRy~46ajox$Yl=&1 z?hg}&*O^P5HomAKFsa8c@d(4sKDQCJzg8W38-Q8#iy(pBzQgCn2K)5*2ZO`7k5Gc%?(WC9qqy^gKfSKaUVfvr>S z$q<1RN3d1eDz0BKe0VNBQ6{Bsk?+(I8fK4sYx483O13>ebqMQNOmf6XU=~F-4zL?P zXw86Uaa3VDf+urtb3||n9@q%TGe9uKk%kGGa(v*;!}C8*-pkDmLDCh*+0#`hIUpYA z-tm2&hLs@32k3hMH3C$F%P8#OM9^(MdqPEzjsuJ^?Xd@{uXh0b3y$oGs@1talWPio zTv&fvK9ur5bEesU1@pEb=>k}B4eYU|3$|fNhc`|5+Jg%L_PZ)h<*{pX(3F#tljC-E zY&qRL5T?Y7Bja=1ZcwH1r2;+Qc7=g~EELBb92q)hwkF3UG^~Cbh%V3vxX{;eAA$!3 z{2sC6@HoR607)#iBhAcg;G^U2AhaqAx;@NEkS1c9wnQU=X^1d~j~r=PwlSl0qgW)& zu_OBX`|sF$vM#b&XfKYR@AoXTFEn&&a)eAnCrd|g+#k$UxE8$UsrCz@FjSpfweE;z zZr;4vLHJmuk8Q)V(4~y0?Qj}CvESWAjSqJGMFGF^clr>Q@rt{KlAUV;3lglZ4`v^D zd?elOYJ9>=#|=KcuaHg@n#+4jAg;kQDRnE)&5R$Bw&_s^xmcO6&(Y2I)1U>GO`n_Z zyjfKxf|eFXrLped?@iH{dM z5=qRU@&U_&LNL!*IPts=XbA5(D{IKQS2%Fi0T`V2Pd=u5d9vc|I300ofLWw^hvs*A zZE%2$$7CYua^23zdiJVEcXxc4J?UDIwd5DsI9NQ`yd^1HN0r5%^O{q(=w5;R zgja4&u%(5gw|K75y2;*d5kF2^ZiWsou^z*Tv*|(RamHTX#DSn^TKsDna^lrt)uOw9 z0ysev4YZcHsSqkNc5avlfK%6^u0}ydHYz>1V-7xH;aSp<2Dv2hW9Q!Ch;EIzOp*Q# zhzb}x2;Ag=>T!4!Oqe7oFB>RIfR^A{ZedomGDl#vKuWT}9grb9vY0x#1BE8zwh_2sVs-M<{5D*VN`{I?#ME5D$i9>YFN8^PCwoDUnt zSUjd;Qc{r&tt*aJ&&YR!(cVd#qLI1jI@`J}{YTSPctPDWGtwN-^1fLd7Y z@)Mvui2D7U|tbKa;{D0Z7w=8&8< z{o4^3T%6=!%(gu)Kes)k)%2Hje{<3XP#kl2lp4I(cY5OIpkrWcoZzxml&6ro)$-MF z^S&IOH6w=+8u_hdi|OG>0(hM}_cUk2LNBwXcHl^hMtRmEWXnKlVP2%Iqr-uZBadJ! zLZEv%8C44ox9|sj2mDnw zjFnIipx_>e*Bw5LylxBx%&Tx;R%jX~DP6^+DXLeI-_DU-Bu}?J2)-^Jt0PH8|C?n6 z1y9MxxuA`&Q);&ftN9|Z@U@piW0nc!LCwVbD9`zIrkcjz)N|OocH6>Cmdpouv|j6b z-Ptn}yC@ZBI?>^^EB)`VhaMQO!G^m2ki`+wn!@OT5D!Q+2b}!a4;=y|bOv=-941Tv zXt3HtX$P-)556DF$Z`L;9%18&;g0}GIdDz*eERtc^q48g%p`)lt^!B<=`;t=2vqJjx*UDq91}>gc zKb;*qeDhKpzunk2wsX?Ovp=<4G}S;Xu@R6ffoMD2%WM$@IWr~T3@l~L_V`O|= zXV#a`&dgN4II(G-*|d3t!B`8CCEUOj zpKfz?b&WprF(?V9RLVPcobm7gZ?NHwer4v>fg6e+umss+8(5Y3I9>2%iNWc1C&lP= zm>!PpP^fQc*tm=t5A*oML?|9s{3JShx$c$lm>5pMSnZ^dt6v6FQ`bV5ybs}9-;>K>uQy18Agvl}_LJ*`Di#~T-B%O!Itc(>Ov=1om!!YpZn_)r+v~xevMcVZraE*Uav#6suPThU z!fNZkdLK_VJe*!DqLV#4HU+ZqwfzvZOHjusj8U&PI$a*ulNOa-`0{C(#yJhoimNRy z&PFn;*Q^mw(0zdp27Azj1)*HCi)vHFRaJ2V1IPZ;+K44LZ%j9Y1#|E8w7|^F40@(` ziRDlHX9Ot}7B)SarWsg{f@{}SkBn@do}TWRWYDLl!2@N-nSz<$sn|+LLG!?+Ry?c*2M#o*#A@t|5FRo6tLpn6 zM%4*_|Mk(dy%!W2mrCZ0hopO@nAtRg8-HE4zNyn7A}oyOi#4u+1w&xZ@9&o3`FNsH znlWS@c(yDwxVc$>S|@pU1k;VYAkq-SfdK$S2EKre??)d*w_pPL`03M2M5ud~3DJzh zCG<)wD=)wRUUZqIl~pyEvzya41-+vsQms$#bIyO2p5vs#5}Z9}A+e}?@561{F^cCX z+n8m4XJe*Zq@8(|^6?6^V(nFS%{S^Je40-rzFGh@(BxTSE8Mg@?frDD_HBexf#PD} zz5m2_!S825J&>|@__DS;kUTNPX(8h9+(<#jLwQ;FnseLK0NB}%};q$ zSQvsQ9RUSLaU)^fc0pxhyBuBJxU#(b67(lexW8*W@5~smk+KPe<^6{bNnCN7KfTnC z!F-d1RfBr_(C(_CW8lu!e<(av_|cqvc$v87(XAkijgDR_>#X_uC@0MuxPoYEpBLJl)763l0)IR+a)De%a&rb#sAzec{C%X`9=4= zmAx~EADE-H0|RB>6$#xdtm9NO0|`Ed!7Yn|G-Dc&u=xXamX%cFj2oL;tz#9ew$JmZSs*Vaa#*Qv}_C`=9);3l~)D8yrMn={SrZ$eJFl{_QBStet zRYw7PBRxkm8|yEMW>!YPAEBTa=olEb8>;E)cG80Bn069#ztA)7B>OTlZwCj`G3

<#7bFWtiE@L%KwL8tyqqWqxBrpxC~pFfM{26XKnnw)AGkEUG? z9T|=eB{S}llg5hWU}a=vboKVatnKcKI668$n@ks}kP#8Br#OXbXwQs>iK{d@TS=#L zI1OL;(#JEePH48I8-+BjnW%sroSjKYNOGqtL#gWiIEho%)w@bikqjB*^75L`mJWA^VcI!4ZIAN4G-n;dqoDN8&nG(_&cs_R zZ$z$VaJ$E3WN4GOaT#%wic=PujAmFaH^%$>zxD9+gl6-8eq_Ge?M6dG6STFZOQg}# z-|UG9;3-lmv-83(DCpnX`ZHOmMCEnA50*D*1QA{z&BqD^AxFo>DIVErOjKmVr1-A< zhWl&CvVMFVQB*_~i5&SS7redea(kw?w7euHDgL%k#)Vk~P9%F&1Qi!IED?-pcW!r= ziLMFOeGWn)q_NjHoGr_IS(%=W-`X;aiH!}3hj z+rMOKs%2y(L`s*+H1PdoLZ@GwyfQ1i-A%&(DAI z^0FuQgCin_U+ASJB#22!NW3$*yU{Q(g!T2mYSdcxk9O+Pt!*hH<&4MaLTkBS+%vb@9uV=UiK%!mj-T&>f|$5CU=F0PZvN#)CovfrvezMQTaS5W z`9Og3E-Kmg6d{k|xDI0eF6w$?hPq@$bX2m}l;QK|&%WcPTR^XFAMSR+RJY48^$m@7 z>l^PLA0ICg(I2%@X|^)Bup&n8GC4WeHV!rfLB^EqGmft>HZZg?wckM|!u)7qOR@bK zu=-suqK~g{U{44tnQUki|Loy48yg!i2gddtP1UU#l$0tKk4ai-rPU_(962mmG#V}_ zB=C$Vnu@pMUG9b>_k}NMPa)1Z;+)0#?DG6VNr87(LH_SVf?w(bNq)?2l$oQ@kZ=+&r8Jf*&&!-+6W z5tf!7VRk#X4t!ko(Zm6@w2t+Ah}p$qBxaKfJ@>>h+bAi~VXoEv;`0IUH`P#**N8mf#E=P>-T8KY`@T?vFDar)=hsyR8;w zQ<~l^or=n#*%!0lW$xm~xwVPl;Dqvf-ERy~x+3nz>(OC}N{V-luA)3mQ(+;(0@klk z{qE}Ox^{37+OA9PMC|{OAKuPgwL}>(Reh4{r>cHQX=UkkDn}F)6g)gUz+?4s=hS;# zzcvi!49X@a5B1e969G?t!pHaA{;;e|2Mklb0vK6MO-+bp7oN!fWA=twN?@MZUEP>V6jP-vvkYlB&_cjfbzccY!}UvGagF7cmcc8(nQ99k#vLC#GrV_(#^vmjSj z&B=EE8liEdBV%GFK8~v*RL)x(8W}~Wq^Re~5nSfG#g_eh=!}ECeaGY^YSp}llo4`6 ze2bqS4B*CqUc|HOc&>yq0-g1*uUT4JDp&n(Bwj@RVPs^4JXC&Ti_=Zf?OF5n>~&gN z+JI)VPK&nMfq6|m1$MwkrQr5dV{TZxRi6?6`hHYu{w3?eLhVTp?I}z5ZqJ>gBh7pM_dv*p@k&yB7O{&8ze$lWlEF19hZC zVj|N?)eanq28M@+k5h`Q)1`a&#&a4R_doYW5yIJ1U5@97ROxqr0035*yhXbV{72bo zAB{}VD2q*@$&Jz1vuJb2vOQn5UzB60M+aqXDT~+2d{30OIgmtS)Ig-YMh*qUeEB16 zxu=r3V9I7Dm?IFa`VxFMxD?p_=_ghxWrx?fjn};q3g^ww&O1-M2(iu+Jn_U8>N6I% z_03Xy4&gjSjBKtekZ1Jp_TfwkjPBLm_>U93-5il9G>V)dGXl&iu*0L4Q+j$i43BX0-vD?FBeIT-?q7Lx0NT?uQi7YIfW0oCBCtBGFDvPD{ zD*f<2x%F0M_UF?Zlaah^xqAM(-lH|J5hoPP$}sW%(pWh6HJe5)9&w9qy4BU6er`S2 zeWr=X;~mpVU`Uq=u3n+v3c?>e&}}{10-Bi^wPmP%*Xm_``_N>|RsyRHDkn?Zm?A+6 z-Iuf|n2vGhUmoA?I-kAgW!GB!pjmM{-fX~$eDJV#Dcm=q)IKG}+(-dbZaJ_H5 zTl)vDvb(1P@n!3}L{*(4PUoXO-a$-$MeSshNPAKRfsz#;Vdn5(4jBey3KW&mns#~5 z%hYGA0tXemb0Dr`agOev94>W4eM%%xL(0k`Vn#Gw5o1gd;o;%@gJ?oofT#BW#wCFA z1c(jK=S?!l3zdp2q@frXC9H`jVdS$A1|gqQO8aNn*|Fr=FR;^r^DMP$SQ(oo|$?_T}8 zbnKi4vQUbWku*s(-q{7lju@QAB&_M5r z6O*1UWo~ZXaA4AH%4FW!+B#LL^LFM~r9?&Z z_ppF&z}xx#`DeTQH~;TXN~hQ+r&Y}itZRlg?I}tQwAcIdD;<1TcD9FEeQA!poJYqG z0d65zQF=)Lf^CzsltiLM0p_5vla2QQi?u{s#iW|Ymw*p#+O?UxVXZ6mO--0j7x3E! z5%w5gfSVnRk$wBNw!N)1GJW*tTURVTR|>n$6M~LAN64=8<=_zn8@1u*Ui=^yW_BA1 zbYjQ>->8`cymTdu^T^W~+GgwJX4@*4kOj=|q%$kS{QBG1F-VoP8qa4VCyp zt-c~O$buh?$CLqS^-QLzweo1uWmTq5j*sR1q&$m4D?|9E^DFklJaP=JPOApQv%eFv zBB0uma_b7(K%I;06EUgcE?B$vWC5#4@3vd7PhCQYev7FHk1p}^7Z6Y5oSRJr)>hN}5qmI3W)T{d>?t@JZVBvF=92V0tsB~!; z1qOxh(rgDrRE!8xcG=G@n@Kz-?*W?V!+M|pc=KqwvXHPiWfgT7wpzD4W_^H%L8IN3 zNbA`Be0dq}p~qYRWvZ#p8{obCg5H0exjmRGk<7dhbv!A2cH4nvZF%MPuI@&wUShfT zKH~fi-SOat`bbWF?8I86kEc7+;-#lzba6=Iiu-ak^RE^r23;#ew6)pevu>1DN4;0n zd2AMK*^o{T$|+*U?cpS%yBBk!H961gwDGu-lapgDZ^SQ}7O$laxZU(Vzl58-WnYfc ziJ1GT5oPk$VBFJk(HYr&@b6MUAsiB?W45Oi`ogl`Ziv&><1?$Xu}f|X zQ9?K2&@MkDx!A)C>g2;%HV=h2)5bZWvV&b8e45P{`|c_P$O?0EqL;>C09>G)R=@G= z&hZu#o|Fd4y9p@8M|Hu820zrXpVIg+eddfY*j06O8^becX%J}M{lJQ~$q>hKD5l+( zJ)~-oJALZvk+{nx(pz$1dd2xYZ}rE{+M#f(-0bX{?mTIp@S<^#Ktt#*I%nPJJ3bw~ ze>~qGY(5``y~&j7GPmOwt5hInY)X=L0KM^hBa4b!uM207T`yhWST&8n{fTTsEQo-PPgx3E7r z6Mo|a5emH7)e$qSiz!KA%lz{*%AWYsD@GdSL9Va6jjQ4_D&Ygm&xbr+pjt`cG`XM7 zA@<)O*3H689lhB16MSFuT1S?Gf21+gp565I7dwGu_9N~SZ&ibdvze)C!_V%wc+;TBZyh2+PLSUz zPcB|s^#Rs7i?Wkh&GC)I_`*nFXGj#b3uQEpz_ZBu{nEfqS>AcbLiEQvH0Q@vrkyS( z!-@Rbr14J-`dr+tSc4LsJ+b$2VY~8Q$T{=qLSgd%Ce@~Oi zgVU7-5gsp65NW(}`x&tV>px>lZXg6+n{ngd9Z414+_Q0ee)b->8NFJpwsfKFmY)9U8rvcwuuAM{@c$TyXePdX=V;tvg$vaaEWO2@B|&~glnfaX*!v|bJoOo7aYVE5w%rMs?~gg;!Z~u67Z>`Y8Qkdj z67Tx;AHt5Ys!!!uXgt;ij{PJMu$8^v3=HKA5pF4F{hNKc<1qOLyvNUF!UO%>X+skZ z`=c_qr<$la7%M7*I#920U|%l;89Q}kKYBjmgB{@sBKeKfxsusiwSF;H|LR92QvPoz z7T~S_AMaU{eMP1gMW z@MN2SkT9yMiV+}OLjAa(mHv4?@ku5oDPl&(*xOrIAk(IGz%jc#s8u!#T;$U(+aX&3 zJi))-IyCzikYdZLo?XV3PMLpos2XL(*Chu>9#65q#Q%{ryTdqehLVE3ytN+rzl-p< zpdDXd?t?7fNzkj$jen&lude&|3`#*%UjNbZ>yc4jV^fogBjUen`0j~CqI4%xt<8uQ z>ulO`@BUpU=IVMYHOlDnhwXSqX5=$Aw%g#~>ol=WWVV(a@8TtC^13Nw_@2RMqrQ|J7><=iF9cb5mzZ{@sV@tALZmh6g=J-lX z91eez+|>mg!oZ7mcTSSDS(zj$bfP7+oH$}9o8Ay!xG&X*|OOZc!&qbT8S17}4D z4GmpK$AH_5$vqf{q}P1^41ds9{sZV2je^B&F||RZ&UU)X3Uv3|P|iJ^-Bxi=LfA%- zWCqtAhOjXi=o0chl0$l7*mZ*LfvZWmRM*0Bod>PfAaksNN8OUgmJeUqoIWa~Q7Ab^d%30i_olEx=_^FM# zxPKRZ%$Pz8QA40s!D}wS#goLhf!pc>?pZllG?YlK(Q~mqXk#%yK~V}n%Jc9&zrZ%O zh>_at9cm+QAH*8Q_29U`|6yN@y(TQ5vD9^mZ`J=`F%xALQnp7246D3aqoY|C)#dhJ zVvZS3i#w#1dV6;zAbzl%KTjqT`DQZi;e%F5JL4#q!cp&x=i%JP-JZ6U#}rILoFAhE zp7p2En76hIKOSjUQD$Rm8Qm?v>D4UR+Fp@XKYYW$8~C0zW-0xA_1SN6s&}y8*ZuD@ zqPIKo`Mbpd1qj1SzqbD!yFqRJ2JS*s)Xls-Z&fc{Q|fymIoT^dt_F6vnBDPN{jAkT zD#mjo{D)`?m=uN1?r=YmkH-YAiAWW00dwrn!>Syt2pzrCzT>(*HOg#$c_l=`3r7JT zU!YV}cH9zZb-Wf!ryR-a-x9gjm7>K4A~+^(;IPZQ!A)$!D|lK z`ocS%Fr6OabhxS|7sRp=_gIc(&g9DtMbMR~{&HTTnOTK{-Y7@*M#|a3ql}q#|Ju|6 zwxpNY$Ec~L-k9iC`w?>g{E7RUV~I>2&kx+O+Di_5b)h_W@|EG+Uhx{!TctC2-C!Mj z-L4!1GlE-WtrPcOK_a|AGV`X#VdhhLH%cOyld7*7djj@g&L#oh%$y z!ZzPkJKMqg4DxJGPzjWkf>vi)lUJnf@qkcaK68JleI!1;vZt;Vs#S&J zK7mFuo9c7j_TxuyjOf&9?Wq%s9$H|Ch4V!Jjqs^`zq;81)`r^CHvqy8^SeH9EX&=b zBHTeHQk9L2IIBHc$~zmfHioPT8H z!(pQhEWl=MgK6($v-goe&tNH#CLDH_n{SNMo$O)rh$robdx21>os5Qy0Kus2-LQs#QeE zdfZwF-llec`EkVh*?rCz;-Tp#{|E`V8c-i@5|I5RV=YXBIh@0?A}tmQ=As0~ArajJ z@$mpscmK)mselnohdWeP{cFJZ{%YS*^Yi=Acd~rfFz${gLEX(Ncmx#8I)|kwSlpXj zdghJ$D7z1enm&y4I&gu zN@sBO59A9sKb$oEI6;57+LsXb(7~8*G*^_-={o8sbl_q^8s6ahp-PsacJ(2all={m zq-rH>5XI&8+)rsa+%LzC)W#SM@I#C z1TRDeCr|J#E(XFLV__@IA9_n%QPw7>FWvSFRFXMv4QLLYOlKS@sa8OtGsvt4Q3ynW z+nZZk{$*u0$&-u6&XT0450KL~l5_H9cgI;|e6FsMbk4yVeMw2glarIZ>s;1)>(y4R zJQ?&?8x^Zn1^)f}<2!~#@&s`4kuxW7G3}+to^nxqSC^oNhljXSQC=>%|1ZO9G(eKb z$&<_#_%9=1&HxR5rPKeDA$ScA`V1^`*<4QW0RDu>X6u81NdvXEzRu?di)6Z3OAROt z=y+Lxi}U8-{vyzZ0VE_Ub=%*tSkBoFGy0E@j|+;3R5>53b2#q(U2FFnoZ19Dy?;IW zA6Ux3Y4dF$fwMc7B>>0>3pExZMam@?Wj#QkH<;=D+}{&{dk35k2?^2b@P98~07NGF zA1Qqb`%12gs8!2-0L^fHXQv0CL)aXSL?85O` zgu>or1rth+NKSD@MYNQ>@lvfO{&+V#^O<6?#agR>ZxkA;f40^>ODfO34>_UaM?LmQ zXI$m!$!~aWE_eKJjOe4^!8;TJ!cVN&?@w(N1BR)P4ZXDG;1N8CYf@)4m|&z0Rw`14 z0>8$d zH#3?-@infDP2Cl$cRm05qk%wVP$Ctgx;U)2+mYcU*v+~<|E{glc$@!umLqVKjAz7! zeL4AJTi)y5`NQz2$3Uk++gdgLmoWTE(D)&scyM2%Q_a%on^ze$Ga8Z;;>CcmU(FXo zGfzTp-Ply5!DM}1?HVfKx!}D2qn==aC43WnO4vK)$ppE!6(REFAWJMi3Rs;_p-)i1 z$#jGGc`jW~@U7q~A)wbc74$^v+*hpi=5Rer(%HLf1Lh-W;HTxUF`tGCJzC2%TVST` zI~Ij&fEig557j_=OtrSx$3=FkWEKjnsE8Kr;0mwv}s8P#QNVBrC(s;cyN;K-^!P4mrB~?y`%1}5= zrnXc9FyTqzx>fTRyHn%1NaS-Bi_lU63Yzbs zzEeQ309IIGVWr)s@JJfP(|eyuuna0XdO%@ewbkMci=Zl(rz}=Pn*4kVZ?rlQk^fek zZ^5BfExS9w7ZiC4rA>Y)x4BNNPrcTcmY$xrJHk)oMwz{;z49vaFx56MZfE!L<$gsalCNKVf5N~GumNu29Hr8D80QTPOoi%zGv}mrok88=e497# z`ue(&dM}V$O-c%mijpZXyC$vT2c=wj(u8W4ne2^aIqr=SdEZX~G!9Luy|dGAY)tl~ zVK*bx#u%V^=TTtD}{oJ|eeizQzFpSZbExP;@GBsaKtEN&Fx>N2GkgP=9#Cqs^5F zh4+?jl~!BTFrWnxes1vRhP{QOwja6?sJ?U*&9k-cnFU5<_S(6*0%_A{dPVQHN|{gh zGFL;Bqvv;Nqi%+hvcX-Ww zU+z2S-_69a3lo-ItU{W6NkCNq2v;JA=3Y~%*S5Fc!g$mj1z=)|h8#ZgnY+q6K(dyS z=RbhQFBg}s(}=@WOY^W}Gc;|_a;b^RD#?K^G_B{DFFYK0jD0bbXem)2OS{iZQ{oz! z0U2H!E$+xn;(7y*To9F6H6-@M|8_SfYdG}mX(K=qi#7VxTeYuZQ^d{V@!N)hLB2{I z0XFu&>UU&3PUpB&Oj<*L3s05cDuVI~$(~lUgiN#X%N=$Wd$E{jGcgmSv(lkuC2xb4 z1NB^M6hCiFoZ~)Y>qJ=j#AFCw{Ztytc!tOK;_fIME_0B{Js>MsTi91pb}rmw10Y7f zz`E2L9lsOb1bBqU**apQ$jTtG0RagyF@9`!cvUPap$A*eV>~<5{{dF>emNb9&t&XNq&UUx>8XOx}n=J=Ar=J@2 z)k9S8`)xIEJloSE=6^M$CwFpA{7HaA7A8iX#-+1Uf`w8)AlQ*^P88;eOu}z59lNII zS&dHPjW2S7d=IR#kvu+-PC_J2^WfjV?-Q}4aJ^(bZW-S0hHg;O+T#=}6GghGF1Psv#P~=IANfx44z^IP3|H&A?cKSpnO~v5tWsc}l zS=IFX-j;vJcLs*zUrxWK!&tKjuSq0eXM2)T!WB?a=VTa6Oic*p=i|u0wAo>!LM$F^ z0lkd`-#iCxB;jWaqE}Ixb9=~aLvUd~XU-Sj`fL%vsnA^3lyC-5 z^G|?PHj=@aRMkgyI^H{$S7s^9W+QpSa<})lpRiPSNsoDPgW5bIY+}DA*BFta+*AI* z{OUVt<~EDCqJIAtA;_@m>{<=aiX&c2NBWy8oa3>eLgd6*+hj6CQl)2>#=y=QSJ?uY z-RwMV=^B@ihda?>`s@Dkf+PFSNOi0G&-3l<-tlSFgctWVuz@e-!Ly*IY^e0b`$Bs%bJe2?>gp-G6DhYK8Y8Bg{$@@I# z0D88VywRE}(m-)>aZwLg9fpKq+HZ87rz)zGHq{>USu7>PpHd~x_l!w9o(-;*S;3X> z92qU@%)fO$5?p>XlT|WzK9UT!!d!ITjjQ-h^`LDL(yiOoKAaht-cz;2=7T-Rs~7BI zmw4-}?|igYeL~ad*jF+HZEG%&ID@g_a|s$n0m0t5Ynu-Ph}U8J{kkQUh?4;;t^Ql{f?4OKObYV^YRe(r6cW+5tpO^wzkU|hA(*=M<-ccR#3X6fyRwV#QXfs3Eh%+u=DRT= zd6kb(Hf*wz2!25D0(-wD(LZP9a&g&Pr!#u);JO=9TD(w=P&6DlUV&qWS%w&$I%{UV zQs=Ngox^ISQAcckDZH>U`3x&Q{fWVxLBM#qR{@4h&$E@#iNWQfd#a8Ni{oe1y^?^O zZXct8Yh5oDB7wn<_ltEn$P~Ivay}T+mPq&Y$2%r2uA(e_onhbAz)!X|o|-ljcPUxd zY#GN4iFQ$l?cVp_8eMe^JBRu`oGX~iWR8N92O(7@54Xk(i;95aw0hJs6TLqVnU#hZ0(s z4(CW$ztsdTp(k#e^V5@MteXMCTi)7WCC1Zk0qC)R^w+{GQijxXU?r8^HAOurs7<50 zxK$a0dpxn!lVI~uLd(@=J4zCf+BUw7EjvSND2&*B^6+QfEvGKt>eB^Fx)v1LQj_=J z1Cr6Pqa_td95k^+cagK9T?@7Z#S6Q91h2TLmA#VL0#jv#9)2o& zN&>G=arKmLlu&iF>qh|*P-HX<6gI*mB6jIl#8I>?TlZSmRe8U7b#!(PR!0J%Ej|4w zLc&b>$pe{m_5eN?Tw(GeK^~7RcXO%C_Gjq*kZhB~$kDYKlA_NBO`I+(`I9a{bDFezhRZoTx#{hrEnq`+`+KXtLp+PUCOc#?nY7-KSXwPn z&n?7KT7CAYZ}t9X2A8+!_CX1#LSex^Wvv`8!xvvViJU>J0s99p*F~~ua&q0e*6V<0Rlf`^J#F@n2Oe|&Ywx-LpA=?6ts$%qG#8}%}2gSw&6*iWN zSp!jjA!TlGc*r@@n=xTz*!Rq?Mwcnct^|GLx0%I>+(8e)qW*OydX7}_=G%9b(k=ekxqEWn9SAe*4xbEmg>HKuA$rnU(Qa-)#@3{RA*>w zevL@l#uO}Keqzuss&f>?yRrV_;iuO@_Q+CC(9>m*Rxw3G2dN8@o}9h(k`ejQotsCj z{>VVE&y}>@YT)X$k~-DD)Sre4p2!jTe8|!wDG`>QR5GaQM(Ur~`s`mjUHonCO@3}( zIoE*;@+>IwE>mzV&CUOvLgrd>1@0d6wh)h3A?ZN$9T%(F8rcXSyq zSA6CmEYbT1s*KbtLgDG=u;EdbJ|wx4k>B%FZdouS14!sa-JjqQiIc{@hVI;6xR{XcqgAdH$DO^P2l;;}NyP%d)1zMf^sTY_ssWayiWmR(POI=2odt!G1O#1PWFLy(=*t|ny`t_NRWs+yo@BvT z=Qf~Or7Q==7_X zk93fLQRQweKOIY&PP~tn&)&QV_Q&kc3i#>xR2+evDLDo!9_Q3@aWuas(61YI={Q$Qd*;!+JS$NQyvxTO z7FdfT7yeGL-p2zqa=?a#RB8xM6TSa<7{u;uHZi2{FVu} z5-WPRaQIyL!o`dt9TpNfpa%SPzJ&=yN*igt-@G-v17#}@8+hEt@59IIZ`7;NA0oky z9raD70t;5ML@kFjR6Y5gWmOoH_To7RL)-Nay*A#alXGXRjJ(4_^&+OtUeWsGio`l)RcM|WV(TzC$66v8 z@py&A*=b^r!Crbd1K)A{r+elJdNVl<%GsGZJLQ)`(*8d*fd-sqi98f*$>7THGVmzT zRr`)>G6OrF3yJqMRd^mV!|h`_#gM~sn9774gTN_RCgP$8sHam()T~C^E~yK?JM|X3 zy){UQ!bkWa;~)b{akn1_MYj!kFZbwb?p@xvJlb?HdTmJr7|I93x;?F$(85MQ@336gzf`y9e*VN>m44XUO>d6@$9X*S?c|2QB|Df#= z9S8%b?D!4H8K1~n%oG#R(R~c-mIvwE2dUL99v`i?WuBd#F_ZvXCd4EqfsIArsp^R> z?Kp0CQ`K?$*BE8{_Y6W|ko0tXhWzWH%XemG=9>Q&`N>;3FK+J^1NlXGIkkdPn$rBj zp=`>3L5qCsYf@dw=f5QfZy2r)@q3()P(io16ZlWJbT*w{*pPa>8z|B^-?M z5QY@(bd7JcX4{OJM#|j!rAN5|5eHUFogbnK(3Nb-DFqX0y_)4_yM`j)2wYYM;~^|S zkNDMQ*%OX!x!T&&H-Kj^a`|dGM&luJQWeZbq|-2yNBNzyM#pIroZUpP!G&T{L|lx( z@j70@Qk~xL743hulH{o9Ka{qV@27zsMae8yIAyK(l)yHfM?j@8QZM`C7>OS=zDgUN z*?Jcc_6}F*$VBzx7`B)?$U!F<`M&~r+~c=>xYo@Ap7p77+pa9o$4>@4n`II>sxLda zbi~ubkD?3P)#^)_SGKkWdnj%Oh^A>Tf2c4Lp*>>r^`f+TE&MtQ_RTx?*7%NhP%f9* z&6Y4~2;wc*~nT%5D{Bmnq_g-ezd;9_K!0%ypLI$)3!@jMP!9rsF-~;e0~;zzy$B zOcS}ERqBiH*+{jE)NW$Gz};%8E-CF&-%NzW-EF`3ryUY9CtzA6_m|yT8U60|LmB&O zfpnQ5sB>~=ygAlkGk-D_EBA6iogK2=(@wi;7;*y5lm74>W}zng={M%x)xL5Uwc6i6 zL>THu=dR-+&)k&c!9bMXbI-oQ0N;2O9Q=t6D>;b+~1G zD8QbjeObo&%UQ3=Q7`FHbK@anM&l|Nq>Oof=LPl=5_7idLot)ymSSy8zh!41=0o|t z`_*%%`L-0N3Y;0wA~jrvOn3Jw0k9(Y^v^ld{exLYCy3#BIrm7aI^Me%SUmMPeOuqV zZGnw+ce|M;19239AoU3YLpkqSTnc>8csmYVe|#HS_A)|5eDHF+qv}b3g~~Us;A}B> z{M&{rI+xR>!eVxN_N3+L#T^;qMzyvS!h9{sfQ+KDxv#?T(@EOK8ciD7ih{ z9A73%rLjc=n4rJw4Qvkb4+>(m+vt+NbP4f@dpN|~c`>HmNL5??yt>01{(;I`+YKQi z1-7$7E6ui4MpU#fUd2{w$L`T#-UGM(>x(0SyW2fcqa6e_w(*kg`VGQ)O?5wKH4GL_|c2Td1o zH@f#^z4L{qL$C?vsSTI!Sl`BL&y?+e;(n+x)8v6i@W4ChSnj^Q85(l( zdLiT-up8avD)Xd~vP?5NH^Iw6luMVRv8sUE^JV#y$j&SJpQwoWUAVvDl^0o3ZA>TFeCM zv*`|UPv`78k{??yXrjY$HiDLyLb4Jwby%4Q2iCqIX{E}ATe{xWhCaO^%WgFo7#pen zU?UYJf|-N-_=`OjXK+3pAba}aZO~8E+)a>j&&8YnLG}u%v3FLht?7MzeTNZpuNK<; zUv*tFF0N+DLqN#^Tmt~16wD={$1Xcd<^Ao~(s4y&b4^V=mZtwevJvU%e+s_;3(;R< zt6mXa$>)D6CVG+X)`JMyY}fuW4T^5&%L!lF2LM=*X0u+^`u76h)^2 zf@g*0JOfZ5G_us-0Bp$19Q@_L0e*Q5&~efFy>_*&>T)42A@hdtF&aVL?ojz%x8(~` zIlj(doy5zQ=8V+98P5MBeAKQK@|VUXv}WqGX|%7Nv)X;w@E$rR@vl#|@3mKX{(d4xMpR(O7OK6IQ~=y-@|; zwCpiI&rrtaYrg_QS)@s+MJKZ(4={o@2g1|NDiJklx77>&$kwMHwxXVoX;k}mo)VF? zM1o3SxUr-72Zk?opX<)Y?=2@PKUhnglw}E%+8VLYODRAzW?H64wSgIVr4JQa-#A@k zG1G?1vEsR9SRxO%Mzx;e3+s?9NK(f5T7Xs5<_iF+3Yzul_A~z@YW}?1JUY$~K!fIe zzBPz00}AvQwqM_9WQ3Gi!r=b4w3(g=!u)h`81a7D)xcx+aW)mzUZ;#_Az;scYQo-R zwTPOI{6nbzpK08n^7*JsYYj&29B*QqQ!}x}WNwz2a&>DqHW2E9=Vt_DEuN4uno8$| z9}9u^o5u9|ju%!B+hefoI5ss=c{bK+1^_Zk&A2Qc}%qt zQZMYyAo@KD7R)398i#Ex4=Jg;RcqY&HXeU)13shl9AB7`^B-&>xeqN@PNWqD)%)8F zEc7il7C2M+fqvsY^EI$i?lK#P%M{(#QOA3W)hrJenMx|prS>emV!s;R)9$RkDgSi& zz{xdMN-&Kdjzw*K`>rl~cJQ$Nt?l)B{HN~27LCdB1UP9@7-2XWUryd075B+fld=y) zh2);X!m!GVC2g~+X}^Abd{t3tH0xze8-jx1V##D^6bRfPV|)VOj#AV__hYJn=dzD2 z(nMp6(G$D5#wr&bUoh8Y#3Z8UzJMkdxDXC zd*qR>9Qe)osWNRjBlh;fkH9rnFwn)*(Ffy!cvFPtPy0h^(wrd`@j!KV;=ByKiK@wS z6?L2)?eKQ`7e+Dg1blI>!2h4pw?v4>r^T{#YLNR8Su$faW7Lu5K(!&K-9}%*E`6Ia0*u)nB5)fH@LCijZ0)Uxw zn#IPrC&W}7atHEOL(Q)HnaZmZ)*hi+sx`p$((6>zM`3Et4NgF`x3ePM#g;D+qGo2} zZQN-j042&A;w9=_Mlqy0fulq66P-44ty4;*Z;WHZUJ8%w&fxl`$|XZjPE!lY%cQpa zYK2-Cnh(w5=pA}R;#_tQfz%Om1+IIPa70B{AddSfX+pkfc14f2{?QwGbo7MfM?xaH8cJ$Jd-A@~;HZ$Buxglw&s-CUk*GQT~Cn#Qc%yA>bfP82C z)u_6RB+%El!yD1bQIZKqX~b=}vA&+p^=u6@4%EotVrNHR6nVw$!1qx$K7n*RvQ6HQU+oN74wpFxjU0cskeC=upZnk!#u zA!OIH^pbNWS=aY9;bk^4V33fEe(03(MP1vNk#xkY==i-or+q1`Vx9KjP5LbMXT^{4 z>s*U2D_u?2ewg;Hsj}-ytRF>wNY9C6?of&5)BEA;BzDde-zaU}=M&TvF20$5k1#A^ zA5AKm;uI`hRTyKXMJZBYJ%L99hq!SYgI{|Q!5X(5ieCr3wVRz}Eq%&(iZei;e!{m2=3{0QY)=)dxXIJ85f z51Qta(>)X9Y8P9l2R2TWPfR#B_xjnRFwG{W))eJ$SbZ32Y$B03t+#W3z zxyM-kvgQ&{7cpwaot z62;%w^*lCsOO8f~Hsq?w2_|qxR-BDwv3C>W|1ZwoF}kw0+ZL_ZHY!HNwr$(CZB&wq zZQHhORh(38+s0k>y?gJw_c`Car?oSGCUdnl*E1iC-uoDRm3!^SzH0 z#vq%Mq2z0NOer6=am<12KzFp;{eTqU31*btq}t%;5_-~zM77I?2hQn@bru(+Js#T<+NR3;)LYkQCC z*ZgeaSzj*p#PN*?OegtcL9iDtgc;mnNUNjtF-icuxQk<-#%r1lA6~xg)A)Xqugrs` zLbU7!NE%Zfh8i>Bq@|8Otj@x|yDL1-sHl-lF^lUqz&@h*E}y3j#L+0n zP#&6#cmMc(XR=E#kx-{1AEefyZ-_C87$?P{(vXYy7BbJF6fTR*%^=hWU(lygg2Oke z@E$|)KF=g(SlX5+pm<{;(ozNVB1;dFFC7?6?@HkZ;QAKo`sixP9^ADRnjcD%HhDx* zhOCNiS=qo&-DH`445ty~*Hm=5{BjT5IW;L~rO>g6=*xbMA@}8x(T>=~dU^0>y7bPN z2l8MQbnEbE%$fu32BH8b`3BMhw~gPP!D`F{N+2mO}kF!<1{^a=Yi_z!tU9wcD*cMJy9 zQ0$(aMHCekX*`u2;k4QB02fInF;+zO=@ans;vpc!P+xt>ox4#eb~0DcEdw*U*@|T7 zOpVEkwG1C@X6ZviW99NS1ap)ygQ8y#OJt1>eV@m48%+a0ql{03DGCS(5LA69M}76@ z<-v@d7woi&R7=$+4E-s_1aDScfj{*@W8?6gGUVx1czc%eQ#sv}W`O-B-wC35Q%g9@ z4V`%?@{z7P;<*mF?hmm#n*|7lE#G$BEOw0Gfd!`@M8O$H_b;17XlUp!bk3}3K$b7x z#5Gjv!;4N{ba>>e8n)sn86`d^^;=eY4AZBr@LQ)TxTuHTEaJKw47sM+dGC+Xtg$Cq zHoer@ZYkSS?%%5CyiABU*4zm~QD)r-o@js}3IJ5B@U0yXP24j1P)^*!oOI4#0ZqbN zW$P>;B;Xn5DZu(%;cIHcfE#s-^@fBbseS9y{pz^@95C-s?z(wjN_`XcnZJl1GYAiV zXQi|t(OrD~#BnpCQ1YT@yBs$4X#k87AoA%6eP$+|ml21acG$C}rs2&PXVY^l95Pcv zE2;+U>bcjtgrZ_%Mu~~faW%UhCcY=Ks6eFeUpB02D5;l!mBUL#>OTr0A&`3HBEJA^<*?ts)9;$9Hm4X^MzAH z%h%Rht+K{`x4repeRvt>e8W5R%#LcH26bfYx7CUh1>tWj+1<@J7wgbgS+dU%z^Fsx zgXVW-eQ@a%e#Ls|rfr2r3l*TxmMRkj7O6(W^w>2gwSSh-wpMJIw-W&f=+nZFt{1Bp3PGDCjb34UzFj3 z)BZ(tjX5rces&Sc_(8%m78Yrn-Fm`4mW|AN0NgWys)JQIL$l4#HIha$UVABvR zaUQh>xJAC9O~dy!GU zz^js|J{LPsd@pYrJog693L32Y%kPyi+qlbMIj?Nb=QC!9rH(l`+E51kTuRmsjm|SU z{2yhoXL2RDJY%#*V*)8tiL%G)-dQ_f2z_bQPpq$@ZF|)!=x!=ksZHdFJwRw|q%EXG zLYl2*fcA=tymcEuU)HVbW{&NzZ3fCA81=U=v!NPkk0J_+;NLp&XAKwNZBHAXEk9>_ zaMr};Iy>=gS(Djc6N?@egt)aF#CfMGmk3dR??oo5MkGmn^YK;9l={0q&}Uc2IZI63 zuf)|3831y+(mr-lcp@qYgM$Pp#6DR}3JUr3rl2rEO$8J0XSes#TL-mea%fnz$mmw~ z*ax(e;VOx*XR0g318l>H-Ei>-+dW-15g8?!OkPB5viZ=A2hK81UCzT^IU>d<$9FSb zW;pPBwr87Zs7l_?><2El2A320abdbVrv?UG7OgOo*NOWaobGa~8k%|xLg zZW*F(`&jm+TF9KWgC$`A0%d7FC8$a%?MY2U)Eb`j2@^-rRxIvEV8*xPp9ahb(iQpA z3dn9XxdU-~+(ZO4_Z84rb1sk-rZCC{`IpQc>F35rLv@KzQ}kuWQk~^+Z+`1kBij3l zjiGucyX?lMnsTeZ*_2{-7Vo}M1t&9+;+CnRudM+!rqRbR{T5SN*IohRa)ba!x?f*b zLLg{YDwq8(=sgcB%DyJ(g z-Sz98vlvVk_*&r`0`cvP$s(=cnzJ;_V*!!eOK_0NOYPpn-%!pC(QdOltnay5JM;?& z_2$m>ApqzezbRDPHafG%IR=73f`qh4o}dQDqchX}RX8T;*CUuoHk})~!^S?z?(ReB z`S)6v$^n1dPuwhqgwVnY>Q7UY6Z zJ}{003W~Hzc9)lrF{(kt?^e}no{y{aBHX)47H)8Ve2UHa{`myhilH6)RrgU{rl0sfkZ98P=D zFXOoUvLw7n){ZL#`Nh{qdJ2BS7?Bq)F%^D^xo+-|OQXxHYy5`X2qyHpX%ZF1C=!+& zNo`8w2~sJe&2(psw<;Ir%%ySk*g&AdNum6dWogF^=goxes02L)gY8OY9>RH%D1)QM z$3t?e3Q%8!UXQU%wo2|r{B(Z^D@He5Db~7SeRudmbDf6%a0iC`>mZBXMSX&vOY;0u zh$z*rCQwD!yghOm5-d2}eyLb*eaGONx-iOSgos6!5C^5Qq5|c&w-El4#XHyQ%r1#~ zoulo6gj8QqC+3qTPyilyLCIu5E%~UWU7%D-%-xRpv0F8kT;Aa9G_vWQ1f#~ZbbQ!+ zL*3>t0;b72F;HNml6d=R+QMi$Tt=r1cS@uC9@v zj1tCXhM!qXUlhRd?y`;X>Dl~D=kS#Bp^YA)SRYEU7D15udg~SiERGxxTMF_6ukdj5 zgetZN@fY-m&+{Am-Bf%JU`qbzB(&s*qP~OvM8VJ|m*K9oMjD~5-Nco!sEAD--ucL2 zYBk_ubhsVtIled`=OB8#{6LbcU~&<+0l%k`C}OZN-(%07o>;Xv8$kuPkyo(W!9Zo3 zXEjzR1pOIl{CExa+H5a?@OTP}g9bpn{av_H zq2KBYQ;`8@I^g0pPAqHt=kI>skoXakq_O`-NPvis(NNhKHD2MyQSI+n%0I^{@JV}y ziWZH%PCcbQoc(dS*&RxmvSP;8Y_XN8*46;KR{iJ3+7~&{WDY~gfgmd1xi3{G53C<`;ae+T+0zI6DHoNL{NHcJBl4e3^~jAz z01E8$2jCM*%5VTKy4>oS2A~*mSy^y>fMb{SO8qYyt>#)l)lo8_+#FyeHd*=t)e?PS z{O4pDW56Frmhq5S&6~@b=&@^^fFQyB0#WNpmt?QE(yn8@gP+XvqGaENW_pn6iq|9d z=9O2~mUnm~vGR(gV~X!cacv+19L6@6+7ht#JFNy2_gkJ}l7&)HJt@HhfeL0r0Z+xk z^4D-PGb`)n{=Sg^C-C#z8ww&Ke>S&AXn6Q|`|bkY^X2?7th(RbQ0I04&8F|?^9#Gd z%@UbY49ANM+`4iy^Xttl&QcM%p*C@P)F%gx(OL)XlWnd2V_#1!zHT%AVWdW_BY95` z-^+SceU_;xV9F47l;ZPwMpiw9WX-P>4n|G#<{sU^yzt8K6)=wR-!?SVQv-7z;(Z|5 zscErBS;cmNtAL%fatB1)QG0ND(oTN`1<%*ys;UCbA=cKgCg+qNG~(989IvEa!81=; zFaRdRryTu|V~V3KCpr>RU$IOEBR3$qaIzd=SDE|gOhPg)ZJ8-iqDy*Yu+d1dCSCdz z>-9W!eZo2NLN(BfK?5rVE)!o1If{S)Qgd9oJyM~4sxh2%o%2dG$2BF>KJ!Iq0CH;2 zKdFi9XVYultK%wxV6@RzYq2uy{cxXR#L{q}qml23v3RlsH*;okLH3N>o^bgwV=|GD zqFt?rJx{p%YHm|)AB&$x_xi`vxvpO=n}-T;06}g=LntOzH2yb&ryw}sduKixU?#Wn3_YK`0aFtw5Ut%GS3e4aU;S!E+2dT6 zxe?UT|0b4g#rsl1>#m7vw16*q-@&<4UNP9>ClOm8r`k*uK)~%5y4geH~lrz@9YXkFi ze6hmevTrIaDR($BcE2FrexLuxvz(y4^j#pgafSBOtOO6$ISt>@pF)C1b&bl7*X!`Ud z4T;#ed!J#8`ca81HKZ#Bt~8gTWdnycx7nle-ar^Gii2T38(jhI-mw;{=0accsD(6xC&Xl#geri;zPA+;SM_)a zR;V7-%UYCwMdVk{r5p2597MESdV%-pGMHRd zhnFJ^w$bw&cMGYxRfg}o#D9`{ioUzE^E~zINte5`a(6aCK>>d#2;=0#z*yKBXifm^ z7yHbX0tF%!zuTy%X=!O;@wlJCin6OGb+ol7%ZYt{Ya@ax=le@0J%pQ-3kW6~2T`-M z`~R}?g@ypTp@#d-2aEkm+>qw@1LGt5lRrkEMLs*8iLS0=7keoaQzosx*wfip#X`Q| zb_-fO+EnOk6Sw-2M=Zmg@N^6u87fYJMC(L3LIaggRV~NGe=lXE%vV4+??eBPrrkantMg|4k_!-f?{8eKHm#Pc7=2LS zu~caRD@Q?3kJ%@ZNo77m%raGBsR+i1EdY=`@F^hR4(}sDP`mX<htkc&b^j6S&zn>gFIcW``IAa_Ax}tS*|#m-m%(B>UTE& zqEWlMcDQ3qn`%E81c9~Uiat~6HdyK1Rqu9PTP#)5mD&$OS@+0-FU&q#9y9h98h~`a zpoh1Fem)Y4j37H4*fjsk8RF$eN5n`msU1d=rAl8?c%CdWIWs|U)>8)-6BWQu7S(;+9f+KFGEHb^_xBZ1wc;fRljBQq z0udO@;N%8!b@$jD-B!k`r6&xn%V@ZlbL%Y889zoUEab4ny*fSBwfkH~!W7~eIq$K) zZ!ct>NSP}13k_wN=*`$aGW}#aBdFJx3)FzX)I0D917(i(aQ~ znt3>DOY8xIkup;($n4D~%(>AKBu<_>6Yu`hkXS-k==0VCkK zsX}p!OHT=!X&IV8A?%^(F~FeR{Ln;2uz)kO>tHO6yqmCO80gn5mu4UTB{1BB7Ve7x zG7d-Ju|Rm(3^nR$gW203!B`cnbeJ%;V6B-d%cN>w_nV)(iaHJjMci9fYs{g9!$GHT zZbqT8$`)qS9ip`>Hjli(@f5fZbcMv>U69*@wwuS%xe6v3;qN`8~@~Gn!2>p5)$>XOyyf!%x^+Q8KyM zEa?YgTI#PcoeQZjeXilEjNa#RWR=Q-wlYeo3~aj1;;Q8=U$hj4Trc8G;y3x8P#D4W zoXo|PLbHf%Y13L@)@-nwC+|z;aglRjpr#Uhu=NJT3`PbB^af5!I#L*RLbB|=KN(}C zSy^=$%=Il2 z-4T(D-0Uh0pB_0=CFuW`)}ffCZJ+FGx)u{sy4J<$F~ORj{bqRha4xjj7j@IZtj(LuocZ}O zJ7%7Br%?X^%gKx|d=urFf`yDw{XW@0%XREV2emSuC79H$Kil$sj0Sq<6{q{H358gc zwV-$teQP`r(t0xoiK+x;3*bC)CQUqBI+IoPs~7T(DqmP2+_M)jJ#=tjv4B2p$1bS3Z*2a ztNTlXN9$YIkaBTxIskGPtlnT>z(-4%wW7MBy{11vInkpT(T`ATXWxF&zc=ucb|F`MScLl z8rZwu8Aznl`_!Pu&`8#M&CJ#!`DpkNE-Wl8U#?8iuu6{!3rGy!+u4ab=(0pWkW*CR zJ-@CI2~RP70Gm(0&eEDSO>wH9pRICeb0bgf_rv~3W0~YABCPdilRXuty-Xc$6`EpJ zSBsm}Cj1MiHqlN;N8j+@vHy(_;@YsZh;a0o+|2$yVb~>2+2e~PUR3sHbhJs)`LcJ( zE28wS`cXaOE;G3c2BcN^`~h-FX0`X%8iKoV<8XnzNBY!O-?3-3=1_ip$!@J zs3V*AiF2$3hlTeS9RlDz$mxgI)80vT)6@DFQ%CfN#GAw#Q)lz_1m^;c*0x@+?l~^IqF9ckUa2=!78HY!UyScf)Ps1HzZe)`+ z&)E5Aa?3LuCoU{aw+HPZ)ObKgH8EIsinv4O zdS^0E3No+s%U`}4b@t9d5q);<(=ROAZ}L?rg`=mG356?!o9pVrP^zIEX!^73V06)} z4`lLijP8ECM)cxOOz8f(WbuChvb0tN=CTmnH=Hd$BuN7~E^21<<#x2~f>$36uZ>Zw zC%OlO?zct;kfp6jdl;QV@pTxx@RTHM1yrO(PV0?ZrE*scGMlf2l9h6)zsSuD@jEFN z>7vrGwE7LzM|zUMSilt&jB8$D&e)$^xr90CE7dG+Ti0)}?}fNXNNE`ddZN3R;}q0V z_5%->$i>xR?_cS05^m~q-SAyYWQxsKZk3yzaVGPgD9LMRUL~1W+NUV_VJyjJ&zF$! z_{+avUk1#NpKg|`!>u{WSGka zpRC!)ikFCU*J1JT2XpAB-Kql13=EePS7!v<;o0{VnLmnh^;g@(-dt10mufZ^$|dko zycc7sR{%>30e6!xT?&M6;8QU)VWNnLpfo0AI;_8!^ho76^QnLiCX}iL(JWa{d#_D! zFm)-Tv-m2Hf=L{#Jh%d!xD1MB4G&J`9xkOgzDPdmc=X?LH4`77hG#V+hWpW{i5@Up zZ#bvDO1axw!-3!=l@{TOXJvvVe4uV?_G3wB;UhfW{WkH6rQ;K?|x+E$C zDZ|_Sy;l(OLM#Kp`*QKErvwnHv^b^8@*F%7m*gtDP_Ds*>Y_bcPZ~CVBKK{gflzq6 zfZKG?9AtxzLS=5YCGlym)$5<(J=&&Emx}t9ivNS$?31>EcHSH9Xa*v_#@J{y8Sm&28t&NNhYSv_KOOim(BL|dxS z@VFE1JZgFR)j=f`<|{Lri7p)+_Li6yfG3i)bL!mZZC&lsKA=vz?(wA67kif%@+Bfkev&}YIe?6KC zB@zG~Iu06SzhB?n08V#+nX;*Fkt6EaQKgt=V z{=rYbo!lO#C{mk)j52^5goi(x&_r5%pfXj&#l^Q(>C}<5!vYE{?0|uF5Zvc^@isx^ z5?_vhbNz`dA&8d=b#%TH&^LHeq=h2vY$8Zm($X!GuA%>q$mm%7{ikXu;VhLux%}P= zqNFoCvge5D7`lw`gmbMK(onc?>OALJJP}~?zv|nx?KWc2f3YbR%35){UJ7Q=`<)M| z-6L$P+(MFhP;1{QvHv)}q7T&=PsqMf9yX`fpDBs8zd{yMjWXR8fW$-<1wu0i9x%sC zb+t;%C%M!W2q7Nv5bkY2>_mSVS0ZNyr9o7rOw;peulKPd@%i9sZ8T@ZQMp*@wnkj6 zlD?hpXo&HztKeX-fPdIhao7H<-@*t}VH{;9?{t~o?vJT!Y69Ee?22^1o>Cba83Fw@ zwrMb%Ha%S^GyOxZqt_SEMcepZ8BF0^aV!%teO9p9=HJw^Wvy@0`p89&^1V#GYkw=P z8`P|P=|{Bt1A7UwaV6zqQTqeO<9UoQqptDQr&y5hVnRN~V=bTLu)QzB8_`FpQU?L$ z_Q?SYtfgYK|9Ukbc~`-spF%MqC;lCps_wrbHh>%h=>9MgOdZB*|25@9(#u%O6Ct~~ zGwriA*S`ncz)K<6C#hFQb-OsdtuqF~e=ExCGLu_Z+qc-l{JU7YVANm58dnn;u55jk zBY7z)@Y=y?u#YD6^GzvMDLX!1Vl6;O0J>dBS{W93ER)9t=pzek!9_Abz)YmKS8tZD zdt$?V==?9DH7(5<93*OO2k>!MG`zgL_g7mvbw(qm?p=0U-OsPD=^7b7=cUkZ*7hod zm1k~#-=%=U!KCQqPt5TDBj{iq;ryIb^cywa)qYz4XkIi&G!!_x;6u?NPR_AS+KX_F zYHKz`UwaZ(c-fS#eqAWijm1`sVQ6>2@wGplx+iV;v6HtuRZnNm&J|%h&iG#-?!}_S zf0zMbdKVd5b)Vu33S`1hFo$<*zSY}~GpclI@r4jeS#s$XGK~j=>7WkMV0~Jt)TCl) zyf2WuO{Y%MiJsx#3sOl4f>EMy@y4LWBv1QUT?{ z%qq3v87XDlnP8y{(zj_nwaFJ=ifB5nW=uQ0LLi#+ci0(GQgC#>jf;|}=G8a0`rB4{ z3`nw3vamgj-LX3lw8}|$X7m>!C<=nwr&X5S!dTch@(~l#7*f^bYkJ-ru$ueI1BnhT zdlJ2{_{32H=D?kIs42{FCR23`%a>4oXtpjE$fwC;?R0B_q4%Am`FE2uG4)H>?EG0~ zvN)2HFRMR+fM`rhV5~VAh=PLRuRk52dLLNd#zqDZC(BoCojZ_T=!~y={dB%k4?z~7 zyQKNC(9JubT4Ox+GcJ*4E!6WeBJEEDf(HcK@YdAm;+?}Z1qB=sX?T8CPpSe_#4L~c zzHA{63t!o9e_zrv=3+P-+>tvE4V=sK)c#yJ%2S&6fL#l#O?ZQ<(h94oK?_dH$+C!! z+~GC}qxA~eeJvpZAq>zAUDy%+fX=9(X`BJ*8dFgA^3XRXbczaYJ6D&JHJZ>^3Y(W@ zM|K?{7{i=bf2u!?LC!Y(eTjOQZ!6G>RLVuh0tnWH?6g;D1NSJDz#%HVIt#hurGEHk zgfXir$bGJnT5LaWR7lI!#hjE>l37_AVn-rv@GQTGP?4K!op%j^xe|MS6Qxnju7n*G z=i83}F{jQ)3&3&3-K)SzdRV$UpW!-yan3Yneh)YfjcDi%6gpdWrcEUim>P#i1*D%e zD4=?R11xc2<>cg4E7b*d`hRhF-v0n(9Fa3KCju%q0H%Vqb#(%Wpa8SGU=j)KHpgGN zxdbE<`Cd<#bZV3%bw($qyU|jvisnYe)j831Tg<_YsUt!w z$YOGOa}1BhvKn((p-sy zOY-3^!6X%|)>TEHsDi;6PxQX1_v`+Z&)3Q1pO&*^m~TQW>8d3@pWa=QID-4D8v6Wq zJpSdJ*SkJ8U8G1&{czv!h;6b>GO19k&^Aq!Zn>e-KBd$Z7qln*2=;wi$%GsH`C`C3 z*p{6q6k1t+(ejjmFZi4bR!`Sx`Kw0B4=Ivwxw`BPrZKHhVq#&16%-U`G%WoWIQ%@5 z&f(4K_IYFUezpgcC^|Sf4XmzW1Ja(N@%f^gnpo6obV&&a`~feFM52FsI;O+z%JFQ8 zCYe?zeO~8ZI+gnfF0XegAnA*^h(>Fo{(bJ~{zv{vj)(#Yz;I2mNHT3P_&;*vVk#3# zDXfmMW?Jm@z5xm=@8+5S!U%9NofKk_ncqJ;nju`w!i|!et)k`#G(Cv-IIHb&u??Eo2lVmhYRp32JB<0G1@m5wPDL{Hlzu=>}?)2UbLj0B7vE=c$7anIi}FVgKyoM+Tor;>Z~lpU4QB| z;NAZs&{AP_3rCEK#ys7nsPHRAR98=AHDw2eN=w47&G8*L6P%^T7Z{Li<+4e*L$t@cE3e=Nkhp^;eN~1 z_5_@X^32}4E?M}5bDr|l{;U&+N0c^_DomB$XL=g`LQJ|dQDjg2y{R5&G2&?8_tbrK z+p9|PMPW``!Um2KtF+q_#8~e!|qsJ>7S052o_H9%!iZqIO1IfA3Vt ze$*^Tk6|ov(aSui1oiju1!)BH6M!JG1A0JlTpH{8FO?4CY2g2$(zz5V?Iyct>TKK=AX`J31DwI&9CvKfCKn%wPc~}MXh~_WWjttZ1FM{? zmJ%P}a~K`_*u%N7o}GqLyz5SXv_#6!;a-tMU`z8dXRRg^l;VyRd>p|c*O@(`+~i^= zsL~Y{iV&4x!0%7+c2UeYk_@234Y0hR-hsm&HdOyi{3@gJ5KbHH`hc=(29!@1*Lr&D z;(bq--7<(eIe&z}S@rDl%q8dBbsVJA9%Bl^KT;iHeW9!fc{0)e6S#o$$g+hn8fE_= z7JPpu65@UE>?5qO5c*HP-}ljrO2Qp!cA-}v*^%`k4#pqfl0LzEE;xQJ9!;ok^`h;5 zZjUGkovcqL3!0HBio)cpf$`!rq<(I~L(cXvdi4^ly58;0HOsn(#iB9Dgg6 zuqF>Eg&M5=$+_Lwso+i$s!gb7EYZLW%*UbseEXi*+&)}x;A8$&2gXZIElWKp!mNC*jK+n>qZSzco>Q}}C!MGZj1Y``0TI00hsDc=psWj)97R*O zHzCbvimO{%JR=g->CKv5OWgR|^-=uI`*SYiyx+^uY7b%l;jeM#K^0RM8X3@k5(2fe zZGD1UUKHv?(Im_A40p_%YtEuXs;0aZ*N}de?|0P2(GdIY9M4zp*R@Zdjzxr(wZ!U; zH16k}ycD;JP8p)=&{o%m0r6 zduu`H^F08vN-aup#Q_3igF>YQp0NAmD+hL=N-b2usoCk;LFrUug5+{zn6M2vK?tD2 z%OC6S#OL(W`a9>i*pSuf+(A*LJQmiboveeteG@zlN;j@n$f#dRqTsb8qUtFZRjaYS zCyrV$YQXA2Nv~QSy)T}E^q+l!l-;eP-v1$-q`4^L_&;mWjP+mvfdUg!m3F2RH-}Wa zqMNJhR5K&QJhmsG1J@{HK0&U6i7%u-uZo~uERqP}8xwfnPsgNiB3-_T7coY0gwW?l zCc%hl2O=v8e5K&B@*xk3J5_=>hfJ>F}-evjhOd+Jh9BB&(uEh~BXI6rgGl@iWk zpOOLe99XpX{YYz~MDPW3E*ut4$W7e<#1s@)zj^PSi?TmCxKcBBrJ3%HyO5A#jp;E> zBI_eb#>DHT%lqyzq{*I8yY8{aROS?Sp$H%m+d7%xz_Uw+pY1gCi20i3;2D}N@T&om zE4_H`Qs-g!78`@SW!+4AwoH4qvK0%Yc=P>KHdRk&Vl@ifFY^VYxah~DhVVmc^ zGOqcQ$^4*@aIT5&+@16L3^>flek!Hc@p{f4{2aQyu z(dw$6IAy|MdJc)8+2V){!9Wx3KoW=Z=P3a%h@XM9$s3y|2&jTEs_{N7gcLBP0;mvW z8J5nl@r$5*fyaQ%nPn7qo7hR)X` zp({l4^xbqbs=#?6_A!}G|4u|xS7p)tWD{wLtqf_ErO&AO44dkz0?@=cN zN0MrC51sn2J8J`zFwJOUUIp;8mR8_0_+0nc^r4a({!et&aeL7>SB6Z!J}e=JVc0W4 z8hj-2o#GboootVTgVy=XR$4`i;~%T4Envo-AnTvHXKENEGjjSbI|J)+lG}H4`>KNl z<_g?}ESX&w^moh{DnObpmHnxNQW~oFP<$uYcSay7k!vh~G@3t1?|AHy1A$V8 zFQRZ#>wL(4Dul7FKx9$WkQN+iK!^?x_ClKuaTQ~+Uq$|?M0mfTcM{t(0(*FiO-dj5 z>;RC&ecIj5^w=)oe<@uX`9Y~bz&OjD;5Gh0e735(JCbib0BYWTfF>ELbi-r^OFLI^v4%RR})YRZ6Mu(DeNl|q1k zIE}{}sN2Td!;|Od`tNkbh03`a{`+E)uV!f*_PAmilVImkVcm+7^&WSK6ww@ofwK!b zq|%QFdGY1`xv&VRb9rF42;*wu3_EyqTo9;RR%Bi~SgOu+r0r6o%V~8I>-pDxp$WXG zv~^EVnT|57#d641t{y~RW-#b<+ga6f*`DwT%$Y8vsW_ify+JU-OS!32sksIbdOJUD z;@!nYrib9BoryfgO`RtNo`GM+VI30?^ryKX_;l4j?GJE|zJbEY^7^``F{CnWu1+pM zy;$5R=nnR-%A5Sg9fO&g%>f;;vZogUK*idjxycFrMiEXFZ_JoeQYfjeVZ1>jfaspj z*2(!^p)ZvusY20ei)V8hxd+v}PpO%OSE0sqZej(Q{nkKEOy(=NSXu&^{MhOa zj+8!v4TN~-*B4GRc8|}Q(ZI0t*D1ho#1d=G2JQ| zwWXa$ysd6U=EdsC;4aPnksd{=(A-BwkVvS)rLf16Sz0fMwwyuAw_f!0+{dho8KG+u z6_|n1C)3F=aV4eo^WSR6C^9~dcC0ZM2tB(MSbG*|coDzsG@#3c5mkzhs%V94qP*&` zSrgMxIO+K~v8tSSC7W{uLJs@by8|gYw$)Q?tGYDax~Q_a{1PSfa_sHzy7LKm1n3=$N_Lwu?7lxemokHHCpsSpDbjY{=4f!Wy^|k+!xX0$o zZm!s6Fu!n^){38rxlQ%OY$V0(bl_3!QJ_9s@rUxn2uF1r7DQB_u*d>{X|5p3WX_l5 z1{m_`?BD-cK&RKHn>GdLZ~z4ZEWd!~6=@Jj;gh4u(+4qB04Q=gP}=m} zy3pvw<>a}pt!v2#IBYLnB}K+G*Uo|3r--AY6Aa{It;u1is~feQT7#p#Hc4E=TK&!_ zN%|*@%*GQ7P4@H}#9jLr5$)t>n!uj@# z&l;x7Vk3({YtLT<4(QR4hmJt~hxwvBN6IiF@tt~t5#S&%EGn8z^|$l3rzaLBMz@8y+G{^5SD7C!T&X_dH?*H^*9gHn_yn?yuP0D~zjuA|ICH5nTMq zR7y^Hw>H&ihs5-B99DW5lMz1_r;^~|7s0jR8&0W5<$ulg0BqHxD;w^IsnU7QFk*Mq z(PEmQXh*FRAYwub>6YsZ3!pDg60zq27=K;Ib-Zp^*^j9ulKRo}-{2=8WOjyqO{%yOn&er&z| z-ML!1>O#|CECO)1pvSt6O|e@Mpxp=}3d%qnu~@ZwHY+!GW@+h<_m2-M_K*Mq$o>ym z<>NmFb?WM^_JkR1cHIlsibTA;*??s4r5ZgsKs%A+jSjcAc6?9(HMt`zpKBf_z9Weq z@ry#K*#3N(0nox$Bm$k;cKvy7-W}kS1F*f+|4Z$xx5fcFr3Ax&r=)br3((;B*fSrt ztsd}F!Xp=dw}9#Q5dx>=W}nzF2N0ov55Zz!U;r2}p{?$}7BT(*;*KEU;fnzxMI;sz zIN-n0cs%1Ve4pyGE41WMh4}a-^=3?DmmO)n-}^VDNPXAj-f^AMts}jO%lNB&_V)HlU41a6O6ltp2nE9mD4??1tO|R-KcJIMAGH`XUAr}j z#F;p=y0$*6lsL2ydN;G2JO+U&&|Pb2fy9#}ea?Yh_k*K=KT!q+tBg$Fzyq=nvrQzW zK!V%tY8x6U^iHvOueJkt?^T+=FfOSk*W9a`VZgH@NzQ8PoQP{hrCvK<;rxn1GfV{# zFR4kH2n8Y?zd`_1BC|{ZU=Y=m5C0%zVu}O&W^mYSNyx~8H@m#_jHIZ_j%4F;?|~yq z9tP**g(S~)Ri~c)^S-;qbr``A+qnePoR0}5_>mLofGJN+`~4JfdiS_XscW18i3j@P zWM%K@97$(wNmfp)3>zd>XUIzLuh4_rf5Hf$&8Vn~Yrluv)JX|jd?BJxz5GD>t_e>e z;qlD#NZJ4qLVRF?=(q1?D&rlk+LOKgWP@T(YnTZcU>_2S*Q^MjIWheK-bP7YIeoXfc7@j0V34Hv`7G-~DjG zpo8JFAa&Rq;a(vEMc~4*w${0Zv5`)3V~hO-=j)=0{QbL(vojSo7zg25XXy%K`>|V9 zI`S@&!RrGBcNER@y|luRpXa9j>QY5;Oal$8C$Vi`m50M=O6QX?j^#6_A$>bCE>92` zxpWGkZ_i4S-F%0JODC?iL)Bc+2$>CG8%e>E@NNQ0fMD0l-auI8Si7~_9dB`r7VM&+ z{kR+vg&39E3eB6@T#boMxhIFg!daaQO#Vy4{IajbB3jZiKDa#j3>;S%oNIPoqtA{P z{DDrg>!rbA%sHT3j~vz$1U_4(bpF-C6#uIuisWh(SoZ{7BDRCa6>l-r_fYE57_B6) zsP6M4TUg|I&(JC`DiA?tS(I55cPz?0c(H4@#1YyN0R?)l(u#Gdn>Wy_W!Nuj%< zCeW!!+_S6aa{T#zDZ={I{o5>(FZ&ATj$RFfT@~lFUtXLLVo(M-<-KBIQ4!GkjB{hW zjZ|?{QiLfXxi4D;?^_y*tBm=dR(8wOYUqn#pFxBQwz`9s8u#HhgiT*-RH|^Q!OYY@ z$1^W7pZDJf8%eFy?-9C8{TmfA!Sc{wCVANFP-j&^7$o zhGNw7@+;|XMDgn#gPZ5s$}nQD%&ZzmU_@6he)iA?y;^JH90TOp$r|DFNr;;=*Muy= z(2?Zy;pV=1a<8jK7S)Z)oaBr9Css)Yljl3}vlN9kbsNl&f^*AvS>LaD;joP#OIaqVfiBJfEKd9ON63z$A9}N#!ps->So&a-pa;} z<`7P()S3yE8BJx8|45_*q1#m6+#!kJZT5U8B)r8|u<*_oo#i9WMvTVUDs@~Ae{x^_ z+1z#NyATZzKcU4IrLhzWPqN8k0GM1#aQ94)sbvPAbJE9Z=+tsOu^zKB~-_d|y-*OE(X#FaE&s8%c% zGv?f6&hGt<=_BWG!L1`*n;Oa}U-5Nt4x?44wnaf!qC-jEP?L98#E{#+7Y^C0m^}3m z4c|V>Cxa>>15N5`>{|U03zwecrB{P)?L#04!aYmThgOH=8+fX`54gFxk&uu;e0)4X zL05i3UaRuHaNz<_wBSrxlt!=d>z94-l2i)PW7+@f4BmOIEuFQ^tb3&vO6G39dE*T} zU%i*p$@v(Z^<-IX$uH2re25*p3#j@;N5b!5a2LrX0Dng-M=qwK;fjQew~rUHIi2)u z4fKcEeITEV%lhOqyQqQ|EL`Dor4BK;>b^H>u` zFKUH@(^;HIBQ?Evxy0+0z4Wt5wa_5sw4|bbc+AAE{(vzP7O?f`1u}5L-cpFxFrPwA zC1=-8&gmL6ww?Pm)^;!8z@EdH;`Z~P+c$szTD4%34O~dq;JPa?S~xVm5w_!t&!cQl zK$G5lx_lCSyrnYAS4xg_m8f3Lh&euq3>Azg_pm>+fFr}JV|OWlfriy=#WyYi6;YuJ z!u?9oySt-_3jGQZ5fLOLB(Qz^_NyxNYuUbiI{@L~;bm?s+4~Y&qbB|`Ky4yhL}5G< z$dj{wB#!9D;MFyG?UQ+Qk8sCwa2ovw{8qfT1&dYs7v{U$V6XwJ)k;ZKs@Uj} zP*IDU+%-){VE^w~F|y7TH=@^2;e6O_b&xNOsKh1R8$ljHf&(amMug@MU^?y zJvKI$n3x!3Stcqf>c$gPbIHuIfWe4Cjb-oTr6$SE%p?~(?Cm5#Po3w6(_!jBW}m6gdo$bN z2q4?zV5^akk%?-}xqjKp!E$I9`z-YsH})AiRgr;0&iU(+;sIoQ!oqMf|HkG&a_QT? zv?1rV)T|o{zwhOYV|6+PmU4ox`v)Uo^bMy$gL+pF+P9W*ZOcKaR)?AnIqW=~PNipC zadk`wZ+kc+P)Qv`3eA<&x8y{*!IFq(|8Xx^^N2ef1 zIDL-nk}qeu3VmPf!H18%NzdmM-sx8ho4Ae4-d+eHxA7#DMfRu9i2h9KK9Qb%HC`Lo zg35OJBpivuY!m5nAj6j$gV`Sj+Ei97L4@5VFX#h*FJ9tV5K%*aC1Rla`N z%RvdPMVPdV?EG1pro*tJ3%up>;q)LcKVOs9ANA*9+cy~8 zJ_KiTGRIHa(0Xt;LUc0jo^EKT*Rt@pepKmP9cM92MiA}`N`7AcRfD_)=-s0V$_uJ z^qZZEp=uLCbTY`ge{tG^glng%tX<;Am~pci-s?RwH3$5{+w)rVQ?&DgoU9x)8*l6{ zJ*paM@XS;iTydD93Oy@56BVa2%3d~I#7lhli>)^yOD4!4if(JW%Omoo= zF9`PqsZo>0T5?hnyLaurp&jpsc<2_3g&%+XkxiR6U5au0PqHi%9UV>2o;@pW9d|9B z&)Wy{y8j|B%5N(z!B;qLBEL_`G5n>R04GyCmi+P8?Ad-Oz9^T$oe_g zEa&=fQ%OA?!%rXl%;EFNWLxd=32R2rS*v)ri|Z{k2j3^GiR@oKi|N}>k&s@1;#!4z z9mcR^;&5(t)m=dlgo>nW-5P_x@4x$mDclMf-yT!h(qn2xXXM_bZ@}j5hPSiE>~sZq}KdOeRl_80*H0Tqxd zK@bE%`1dGKw7loN?BKzJJn+B+sH%F!G=Yqa41WIkXS#Rqerem1X#)WP0m!llHYePK zoNavi;-};dn#*e~#UyV*5bh2NfbJe&Db8ZCV6j+8PEN*ZwO%pb4`BK7C)xq5;P^ScjGP!Yj&owpSUTw8(2?$PM7BIqJM82OP{WCM;F-9@(%Osf)zM- zy`5cExvU%3fZo4%Wy!9OXekyG5Cq`{{U@H#iz;+87K;T{Rj;Vj-QC?W8jaZ5*`d?v zkY$;Kgaj^Lym-^;S!3rixZB6nUVe_oel}(AAlz}1oj1Xup(x&V_vq9;1((3;gjEl~ z`QE<276hS!{3rU*tyU`*iaZF4MOP4M!^%WBnQ?6rJEEY^A z6FG$%6Nj|tgP}#QiN&uEhIZhCA?+`{J{(%~dhhvm#HZw3`@mWn>)-E5RD?e+wl>%} z_|SCRUswRtL}qm`AW0IEQjHPY%m5UgUdEff8dAx{h|$rDkk;eaR#-*>@?)6LwJ8yS z?l>6q*f{u7uh+ZGn*K5mHLQx8odE~my7c@ohSZY#6)l66!x~c6!yX&G5x1(%88CeZ z8O85g_RpkW%i2`+a>A(BW9t?~^CzdVJ^k++9_ztrbdT`E*;tfjtp{Ia=~?q-Ff&L?$d}Wu154W_P7Pspn14~6xq_mTsOoLcbyvOBGT6I%Ir}|_^Uc%;@Fs(N@9OB-1hNOcX074P zrh1SJcm(Oul9w^KZ7-I34B)M=-lwKhE*DZg2`+2gl<6#guHA*>^YdBO-4o0C)l3-n z4$sH5V%R&Ad7+w-_~qjm_WI+z-RLOOqKzOq65jn4rgRIy+qQrci{Iv@;r;Naf0&P( z*`UVnKbp320j|c0?KE9L*qlfc|63mgWI^zh)e$9D$+_#MIcR@<}gBh=krvLNR zIlAI0{A3dcKki1`*JEiu@tY%AG2QP-N&E6YxibGgo<`~K@hG~;T5`vhX-TEjJcvxFR9Eu zJUq&E42#8r*=$CVBy_TbPFMC`)VdEr#d|kypb;~#3xEE39<^C;(Jy6BYPao3o2oLjZiUy$HME+)lD|xyX=4MD zTYb7dQj&f{DxX`*(s#G9&+-(0=HL1FqwRP;yM`a%i^d+n49o1tlTy5gY1<4w+7iI< z?O*a@9R+AcgQ-XPEou>qcD+mECZ(Uh@{n9=(!NU@B1=A@s*$cuBwk(dJ1NgTiI-Hs zA1i(*v*utPtg3@68d`L?R*t|G&@$FDtoJ-J+D&2ATTP2%u$O}&IEn{5w8aK!_dqmW z={0$F!dJZ3^G#~rKskz7Ir-gq<|en~lZ{_8xRMNLgdU%ayr7JH1T~{``_|Y1ts@Kg zqsm}bu1n0OlB36MMIXQ z+c&LQYE}rMT5P|JWi%Khl)&Ku=s;{b)I159We=3N)~s+`+C4 zXIehcw5T$_ips^kdxMoF2}Xy&=gs`QPriZ!&%l^`p(GmsqqanMVSC z;+Nz`4DVU(8cp~r@e7CY!XjIqSuur&Zs{gVLe|Mh8dpqz{QGSkIvFhHYmE+2u~<}4 z^tad~rl40q6-zY>f=~)2F);ymSGS7J2XNyRd5NMvbSsjikepRWd|Cm8mg_&mC_0Jc z%!2Fppk!glY4av6Dsuv2A*Rv_nX11jbp|Z!l zIk8RT=hfLrBEr>7sqtNmLH z*E`d5K@UoO@Yd2`Y*IAkJl8bdAh)Q+a!47A-^UNLc$R zV}CT$>eE5gQ$TX?z{A$ewk31e5jB8DzJYY=-jLT`dyA*X>v*QAA2zu=h&7k=X(`kl z^a8Cudx>E^M^X4%cY>`aSh46J7FyrV6C?=2ee6F`q06$2sune$7n)V<3}qKfk|gp> zmYZAtRo{%!v)zoEd4@J$cG=DkGe2c9kCr|t z;0lUu9y@0YVao9g41o=KX!2?%4K8lpx9h-&aXr{S?p5Ad^$;tb@*;HT56nv$!W+|{ zq5E4V6h{vNBU;m|TG928gP&vGvI0iDK8rDrOe5PdltzIzNV0r)3}g`m;hrbi+S_UF zu5KJSaNve^OiWC~)zuY6DZBFAxpOBSJ9fO;JeFy|fC2c0HD&X8C%pVT%e`N2ZUMm_ zw#*#S?vCZ{KPBrY9S-poj9_B;FT{P>@rFj`-xwc6HL3@?W5_$h#+hST zCbwlq`%?PLh3nEXw(-N(bf*|~N+?7r4m!{v`LG?cV8Pe_2hr9{77EhR{>2;#cQc){Go7kA;3=Y;3WD%2Q|#^S z$j#0vd&~QfYO&y8E#RY^q&z_kSgED8HgJC(;EIRjXEP^>^jeg>DF4WzJ_gXu#f71yTBo|f4d6@;MC^Tvr!Q@CI z7f)W~n|0a57fQIgIuPlmLsE;<@^H|j)7$cNb2ollk;>)m2(ptGFGbp8BNyOdD?!FR z-fbZ1aIup~K5~jT_T_`3;OXwn!;OOYx{8tK=Et)4+6^s&APDz7#lgW5RlQKr`M5%; z3K{?a3T;V5K~yV+csfwkUE!m-bBT?O<*}aqnZ9HvjY7RxziusEnp9`k@kD$aG(KEB z7w-p$lGinV zNq`0@v}hg9=x{r{43L+T%jTVD`EXAT*?`W|oA=uIP}|*rhd~CDi6f`t`FLX@2MUUh z?BT=YuKq+i>oKSn&c-G4+1gk(WR>J!A)*(CMGb8&nVeRj0 zSp3sZ%=}^&HL7^>)yz+EuK&PIr=u2H$kxDDuPeursydq1^1wGQh4H&Cugw2JQgE|{ z)YIqr-Zh998@n_Amt;}_+1ZPyB6Mt6dzQTDV7%>gNT_I7Idd|e4^Np$v&d8m31nn+ z24IF*{u#q*f}XsX61pL{~QwryFwcrn@8*-V={1#d4e4kYB_6H)Dkk1y+r zn%rAP`q79yzCV>$_EVl@AjnmRB_)R=*K0zS^tjnVW?mjEk0o6B;=+fC?1+5^LO(#k+kwd(b8?BoB6I} zJn<^XU{kybnu&cU{_c1_nRKua6*!Ot5miI! zP|e8P9ipRN5QK`Ov18BirX_3BsR*&5DNb5u|)Ry3nTf^x0ThsOD|0#u_Om*Pzf zZtgrATG%Hu|^EMtk8;1+(mdzthyoknEsGzGkTeK@jdd1rQbbbtsN*IMr-P#@=hN;7 z#vi{Ya?}c7CEo(J1|51NDtp^wo0-CQyVE(W0)DEyiIhR}N4NPis9;uQ$A&zFgO|V?u3Q@*KwJu!kjR`1o(yjrMuvR?o0H9GwnjqaT;?Au{U)HCnd4NN z1?Q?h3UF$&{RF z8SccEy;&rPsd9oK{7Z_yu0?%*h3u0%QS6+^IlTuP7at0fW64iAiLGCCtOYsf9o>)= z14v-bN&yYbSxMNq6ot2Q3U78p>0LZ}mT6&i7~3j-PV2Z*ob&w!eq z46Po3qfR3`C!eF|lUb*LWTV3#mHf+U!0fmL-oGNSn?}A_1%rZv1ZNJNW~@t9o^KSw zS9UU*#Y#qQK7W?k)LqP)&8!t?af&+^ML$SUVKEhTeo+IWJQZ7R{T zV+4b3z+|$JnwHJ^>pf~;LFK^KBRrp9iRWuqVtfMyoyAOSLL$far-KzN@ritP$dRFq zE79rHA-)wO-vvSVmq>noewxwNmR&n{-q4OW8V`N+L8qI|kU}4lF_?(V=c%7O-1kIfh9j1Yfc)TE&En<5$+u}?o5298ulA^ zGxT8DtrLPE2zQI=P1L(99(qbj3W0&;?IpcGIM-+ifLr}eSG{LnrFPK|ng){e_rF3p zNK_8?roOI#bJ-Tmih;`=m_YEsMwjQR}){4%DAPB;LkCKp(fS;e= u9ZzV_h^BWu4M7kDLHM_9-FkODo%|n51*mU?XL{BE0000(0) ? false : true; } using std::placeholders::_1; using std::placeholders::_2; -Module getModuleType(const std::string & module_name) -{ - Module module; - if (module_name == "blind_spot") { - module.type = Module::BLIND_SPOT; - } else if (module_name == "crosswalk") { - module.type = Module::CROSSWALK; - } else if (module_name == "detection_area") { - module.type = Module::DETECTION_AREA; - } else if (module_name == "intersection") { - module.type = Module::INTERSECTION; - } else if (module_name == "no_stopping_area") { - module.type = Module::NO_STOPPING_AREA; - } else if (module_name == "occlusion_spot") { - module.type = Module::OCCLUSION_SPOT; - } else if (module_name == "stop_line") { - module.type = Module::NONE; - } else if (module_name == "traffic_light") { - module.type = Module::TRAFFIC_LIGHT; - } else if (module_name == "virtual_traffic_light") { - module.type = Module::TRAFFIC_LIGHT; - } else if (module_name == "lane_change_left") { - module.type = Module::LANE_CHANGE_LEFT; - } else if (module_name == "lane_change_right") { - module.type = Module::LANE_CHANGE_RIGHT; - } else if (module_name == "avoidance_left") { - module.type = Module::AVOIDANCE_LEFT; - } else if (module_name == "avoidance_right") { - module.type = Module::AVOIDANCE_RIGHT; - } else if (module_name == "pull_over") { - module.type = Module::PULL_OVER; - } else if (module_name == "pull_out") { - module.type = Module::PULL_OUT; - } - return module; -} std::string getModuleName(const uint8_t module_type) { @@ -171,6 +136,20 @@ RTCManagerPanel::RTCManagerPanel(QWidget * parent) : rviz_common::Panel(parent) } v_layout->addWidget(auto_mode_table_); + // execution + auto * rtc_exe_layout = new QHBoxLayout; + { + exec_button_ptr_ = new QPushButton("Execute"); + exec_button_ptr_->setCheckable(false); + connect(exec_button_ptr_, &QPushButton::clicked, this, &RTCManagerPanel::onClickExecution); + rtc_exe_layout->addWidget(exec_button_ptr_); + wait_button_ptr_ = new QPushButton("Wait"); + wait_button_ptr_->setCheckable(false); + connect(wait_button_ptr_, &QPushButton::clicked, this, &RTCManagerPanel::onClickWait); + rtc_exe_layout->addWidget(wait_button_ptr_); + } + v_layout->addLayout(rtc_exe_layout); + // statuses auto * rtc_table_layout = new QHBoxLayout; { @@ -194,9 +173,6 @@ void RTCManagerPanel::onInitialize() { raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - sub_rtc_status_ = raw_node_->create_subscription( - "/api/external/get/rtc_status", 1, std::bind(&RTCManagerPanel::onRTCStatus, this, _1)); - client_rtc_commands_ = raw_node_->create_client( "/api/external/set/rtc_commands", rmw_qos_profile_services_default); @@ -206,6 +182,9 @@ void RTCManagerPanel::onInitialize() a->enable_auto_mode_cli = raw_node_->create_client( enable_auto_mode_namespace_ + "/" + a->module_name, rmw_qos_profile_services_default); } + + sub_rtc_status_ = raw_node_->create_subscription( + "/api/external/get/rtc_status", 1, std::bind(&RTCManagerPanel::onRTCStatus, this, _1)); } void RTCAutoMode::onChangeToAutoMode() @@ -230,22 +209,41 @@ void RTCAutoMode::onChangeToManualMode() auto_module_button_ptr->setChecked(false); } +void RTCManagerPanel::onClickCommandRequest(const uint8_t command) +{ + if (!cooperate_statuses_ptr_) return; + if (cooperate_statuses_ptr_->statuses.empty()) return; + auto executable_cooperate_commands_request = std::make_shared(); + executable_cooperate_commands_request->stamp = cooperate_statuses_ptr_->stamp; + // send coop request + for (auto status : cooperate_statuses_ptr_->statuses) { + CooperateCommand cooperate_command; + cooperate_command.uuid = status.uuid; + cooperate_command.module = status.module; + cooperate_command.command.type = command; + executable_cooperate_commands_request->commands.emplace_back(cooperate_command); + } + client_rtc_commands_->async_send_request(executable_cooperate_commands_request); +} + +void RTCManagerPanel::onClickExecution() { onClickCommandRequest(Command::ACTIVATE); } + +void RTCManagerPanel::onClickWait() { onClickCommandRequest(Command::DEACTIVATE); } + void RTCManagerPanel::onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg) { + cooperate_statuses_ptr_ = std::make_shared(*msg); rtc_table_->clearContents(); if (msg->statuses.empty()) return; - std::vector coop_vec; - std::copy(msg->statuses.cbegin(), msg->statuses.cend(), std::back_inserter(coop_vec)); - std::sort( - coop_vec.begin(), coop_vec.end(), [](const CooperateStatus & c1, const CooperateStatus & c2) { - return c1.start_distance < c2.start_distance; - }); // this is to stable rtc display not to occupy too much size_t min_display_size{5}; size_t max_display_size{10}; - rtc_table_->setRowCount(std::max(min_display_size, std::min(coop_vec.size(), max_display_size))); + // rtc messages are already sorted by distance + rtc_table_->setRowCount( + std::max(min_display_size, std::min(msg->statuses.size(), max_display_size))); int cnt = 0; for (auto status : msg->statuses) { + if (static_cast(cnt) > max_display_size) return; // uuid { std::stringstream uuid; @@ -276,7 +274,7 @@ void RTCManagerPanel::onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg } // is operator safe - const bool is_execute = status.command_status.type; + const bool is_execute = uint2bool(status.command_status.type); { std::string text = is_execute ? "EXECUTE" : "WAIT"; if (status.auto_mode) text = "NONE"; @@ -313,16 +311,15 @@ void RTCManagerPanel::onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg label->setText(QString::fromStdString(finish_distance)); rtc_table_->setCellWidget(cnt, 6, label); } - for (size_t i = 0; i < column_size_; i++) { - if (is_rtc_auto_mode || (is_aw_safe && is_execute)) { - rtc_table_->cellWidget(cnt, i)->setStyleSheet("background-color: #00FF00;"); - } else if (is_aw_safe || is_execute) { - rtc_table_->cellWidget(cnt, i)->setStyleSheet("background-color: #FFFF00;"); - } else { - rtc_table_->cellWidget(cnt, i)->setStyleSheet("background-color: #FF0000;"); - } - } + // add color for recognition + if (is_rtc_auto_mode || (is_aw_safe && is_execute)) { + rtc_table_->cellWidget(cnt, 1)->setStyleSheet("background-color: #00FF00;"); + } else if (is_aw_safe || is_execute) { + rtc_table_->cellWidget(cnt, 1)->setStyleSheet("background-color: #FFFF00;"); + } else { + rtc_table_->cellWidget(cnt, 1)->setStyleSheet("background-color: #FF0000;"); + } cnt++; } } diff --git a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp index 59f1bd945f0a6..50f6f10ebfc15 100644 --- a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp +++ b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp @@ -75,6 +75,10 @@ public Q_SLOTS: class RTCManagerPanel : public rviz_common::Panel { Q_OBJECT +public Q_SLOTS: + void onClickExecution(); + void onClickWait(); + public: explicit RTCManagerPanel(QWidget * parent = nullptr); void onInitialize() override; @@ -83,16 +87,22 @@ class RTCManagerPanel : public rviz_common::Panel void onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg); void onEnableService( const AutoMode::Request::SharedPtr request, const AutoMode::Response::SharedPtr response) const; + void onClickCommandRequest(const uint8_t command); +private: rclcpp::Node::SharedPtr raw_node_; rclcpp::Subscription::SharedPtr sub_rtc_status_; rclcpp::Client::SharedPtr client_rtc_commands_; rclcpp::Client::SharedPtr enable_auto_mode_cli_; std::vector auto_modes_; - std::string enable_auto_mode_namespace_ = "/planning/enable_auto_mode"; + + std::shared_ptr cooperate_statuses_ptr_; QTableWidget * rtc_table_; QTableWidget * auto_mode_table_; + QPushButton * exec_button_ptr_ = {nullptr}; + QPushButton * wait_button_ptr_ = {nullptr}; size_t column_size_ = {7}; + std::string enable_auto_mode_namespace_ = "/planning/enable_auto_mode"; }; } // namespace rviz_plugins From ee4f381ddc02d8b551a84a00eb7edafd75673381 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 4 Oct 2022 20:34:31 +0900 Subject: [PATCH 06/28] fix(avoidance): fix avoidance path chattering (#2012) Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 11d5661ccabc4..5d1bf1dd510a2 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -42,6 +42,7 @@ namespace behavior_path_planner { using motion_utils::calcSignedArcLength; using motion_utils::findNearestIndex; +using motion_utils::findNearestSegmentIndex; using tier4_autoware_utils::calcDistance2d; using tier4_autoware_utils::calcLateralDeviation; using tier4_planning_msgs::msg::AvoidanceDebugFactor; @@ -140,8 +141,11 @@ AvoidancePlanningData AvoidanceModule::calcAvoidancePlanningData(DebugData & deb // if the resampled path has only 1 point, use original path. data.reference_path = center_path; } + + const size_t nearest_segment_index = + findNearestSegmentIndex(data.reference_path.points, data.reference_pose.position); data.ego_closest_path_index = - findNearestIndex(data.reference_path.points, data.reference_pose.position); + std::min(nearest_segment_index + 1, data.reference_path.points.size() - 1); // arclength from ego pose (used in many functions) data.arclength_from_ego = util::calcPathArcLengthArray( From a6cf5fc99c84e7ce6d5edcc9ee7bddc66b41e37a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 5 Oct 2022 12:00:30 +0900 Subject: [PATCH 07/28] feat(motion_utils): add new resmaple path (#2015) * feat(motion_utils): add new resmaple path Signed-off-by: Takayuki Murooka * add test Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../motion_utils/resample/resample.hpp | 23 + common/motion_utils/src/resample/resample.cpp | 59 +++ .../test/src/resample/test_resample.cpp | 460 +++++++++++++++++- 3 files changed, 541 insertions(+), 1 deletion(-) diff --git a/common/motion_utils/include/motion_utils/resample/resample.hpp b/common/motion_utils/include/motion_utils/resample/resample.hpp index 0accce28499c0..5eb42bb2eb91f 100644 --- a/common/motion_utils/include/motion_utils/resample/resample.hpp +++ b/common/motion_utils/include/motion_utils/resample/resample.hpp @@ -126,6 +126,29 @@ autoware_auto_planning_msgs::msg::Path resamplePath( const std::vector & resampled_arclength, const bool use_lerp_for_xy = false, const bool use_lerp_for_z = true, const bool use_zero_order_hold_for_v = true); +/** + * @brief A resampling function for a path. Note that in a default setting, position xy + * are resampled by spline interpolation, position z are resampled by linear interpolation, + * longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is resampled + * by linear interpolation. Orientation of the resampled path are calculated by a forward difference + * method based on the interpolated position x and y. + * @param input_path input path to resample + * @param resampled_interval resampling interval + * point + * @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and + * y. Otherwise, it uses spline interpolation + * @param use_lerp_for_z If true, it uses linear interpolation to resample position z. + * Otherwise, it uses spline interpolation + * @param use_zero_order_hold_for_v If true, it uses zero_order_hold to resample + * longitudinal and lateral velocity. Otherwise, it uses linear interpolation + * @param resample_input_path_stop_point If true, resample closest stop point in input path + * @return resampled path + */ +autoware_auto_planning_msgs::msg::Path resamplePath( + const autoware_auto_planning_msgs::msg::Path & input_path, const double resample_interval, + const bool use_lerp_for_xy = false, const bool use_lerp_for_z = true, + const bool use_zero_order_hold_for_v = true, const bool resample_input_path_stop_point = true); + /** * @brief A resampling function for a trajectory. Note that in a default setting, position xy are * resampled by spline interpolation, position z are resampled by linear interpolation, twist diff --git a/common/motion_utils/src/resample/resample.cpp b/common/motion_utils/src/resample/resample.cpp index fd9e8d46e9e39..79c03cf0081c5 100644 --- a/common/motion_utils/src/resample/resample.cpp +++ b/common/motion_utils/src/resample/resample.cpp @@ -335,6 +335,65 @@ autoware_auto_planning_msgs::msg::Path resamplePath( return resampled_path; } +autoware_auto_planning_msgs::msg::Path resamplePath( + const autoware_auto_planning_msgs::msg::Path & input_path, const double resample_interval, + const bool use_lerp_for_xy, const bool use_lerp_for_z, const bool use_zero_order_hold_for_twist, + const bool resample_input_path_stop_point) +{ + // validate arguments + if (!resample_utils::validate_arguments(input_path.points, resample_interval)) { + return input_path; + } + + const double input_path_len = motion_utils::calcArcLength(input_path.points); + + std::vector resampling_arclength; + for (double s = 0.0; s < input_path_len; s += resample_interval) { + resampling_arclength.push_back(s); + } + if (resampling_arclength.empty()) { + std::cerr << "[motion_utils]: resampling arclength is empty" << std::endl; + return input_path; + } + + // Insert terminal point + if (input_path_len - resampling_arclength.back() < motion_utils::overlap_threshold) { + resampling_arclength.back() = input_path_len; + } else { + resampling_arclength.push_back(input_path_len); + } + + // Insert stop point + if (resample_input_path_stop_point) { + const auto distance_to_stop_point = + motion_utils::calcDistanceToForwardStopPoint(input_path.points, 0); + if (distance_to_stop_point && !resampling_arclength.empty()) { + for (size_t i = 1; i < resampling_arclength.size(); ++i) { + if ( + resampling_arclength.at(i - 1) <= *distance_to_stop_point && + *distance_to_stop_point < resampling_arclength.at(i)) { + const double dist_to_prev_point = + std::fabs(*distance_to_stop_point - resampling_arclength.at(i - 1)); + const double dist_to_following_point = + std::fabs(resampling_arclength.at(i) - *distance_to_stop_point); + if (dist_to_prev_point < motion_utils::overlap_threshold) { + resampling_arclength.at(i - 1) = *distance_to_stop_point; + } else if (dist_to_following_point < motion_utils::overlap_threshold) { + resampling_arclength.at(i) = *distance_to_stop_point; + } else { + resampling_arclength.insert(resampling_arclength.begin() + i, *distance_to_stop_point); + } + break; + } + } + } + } + + return resamplePath( + input_path, resampling_arclength, use_lerp_for_xy, use_lerp_for_z, + use_zero_order_hold_for_twist); +} + autoware_auto_planning_msgs::msg::Trajectory resampleTrajectory( const autoware_auto_planning_msgs::msg::Trajectory & input_trajectory, const std::vector & resampled_arclength, const bool use_lerp_for_xy, diff --git a/common/motion_utils/test/src/resample/test_resample.cpp b/common/motion_utils/test/src/resample/test_resample.cpp index 798a4dc8356cb..bc89645bfad01 100644 --- a/common/motion_utils/test/src/resample/test_resample.cpp +++ b/common/motion_utils/test/src/resample/test_resample.cpp @@ -2129,7 +2129,465 @@ TEST(resample_path, resample_path_by_vector_non_default) } } -TEST(resample_path, resample_trajectory_by_vector) +TEST(resample_path, resample_path_by_same_interval) +{ + using motion_utils::resamplePath; + + // Same point resampling + { + autoware_auto_planning_msgs::msg::Path path; + path.points.resize(10); + for (size_t i = 0; i < 10; ++i) { + path.points.at(i) = generateTestPathPoint(i * 1.0, 0.0, 0.0, 0.0, i * 1.0, i * 0.5, i * 0.1); + } + + { + const auto resampled_path = resamplePath(path, 1.0); + for (size_t i = 0; i < resampled_path.points.size(); ++i) { + const auto p = resampled_path.points.at(i); + const auto ans_p = path.points.at(i); + EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); + EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); + EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); + EXPECT_NEAR(p.pose.orientation.x, ans_p.pose.orientation.x, epsilon); + EXPECT_NEAR(p.pose.orientation.y, ans_p.pose.orientation.y, epsilon); + EXPECT_NEAR(p.pose.orientation.z, ans_p.pose.orientation.z, epsilon); + EXPECT_NEAR(p.pose.orientation.w, ans_p.pose.orientation.w, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, ans_p.heading_rate_rps, epsilon); + } + } + + // Change the last point orientation + path.points.back() = + generateTestPathPoint(9.0, 0.0, 0.0, tier4_autoware_utils::pi / 3.0, 3.0, 1.0, 0.01); + { + const auto resampled_path = resamplePath(path, 1.0); + for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { + const auto p = resampled_path.points.at(i); + const auto ans_p = path.points.at(i); + EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); + EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); + EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); + EXPECT_NEAR(p.pose.orientation.x, ans_p.pose.orientation.x, epsilon); + EXPECT_NEAR(p.pose.orientation.y, ans_p.pose.orientation.y, epsilon); + EXPECT_NEAR(p.pose.orientation.z, ans_p.pose.orientation.z, epsilon); + EXPECT_NEAR(p.pose.orientation.w, ans_p.pose.orientation.w, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, ans_p.heading_rate_rps, epsilon); + } + + const auto p = resampled_path.points.back(); + const auto ans_p = path.points.back(); + const auto ans_quat = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); + EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); + EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); + EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); + EXPECT_NEAR(p.pose.orientation.x, ans_quat.x, epsilon); + EXPECT_NEAR(p.pose.orientation.y, ans_quat.y, epsilon); + EXPECT_NEAR(p.pose.orientation.z, ans_quat.z, epsilon); + EXPECT_NEAR(p.pose.orientation.w, ans_quat.w, epsilon); + EXPECT_NEAR(p.longitudinal_velocity_mps, ans_p.longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, ans_p.lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, ans_p.heading_rate_rps, epsilon); + } + } + + // Normal Case without zero point + { + autoware_auto_planning_msgs::msg::Path path; + path.points.resize(10); + for (size_t i = 0; i < 10; ++i) { + path.points.at(i) = generateTestPathPoint(i * 1.0, 0.0, 0.0, 0.0, i * 1.0, i * 0.5, i * 0.1); + } + path.points.at(0).longitudinal_velocity_mps = 5.0; + + const auto resampled_path = resamplePath(path, 0.1); + for (size_t i = 0; i < resampled_path.points.size(); ++i) { + const auto p = resampled_path.points.at(i); + EXPECT_NEAR(p.pose.position.x, 0.1 * i, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + const size_t idx = i / 10; + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(idx).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(idx).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.01 * i, epsilon); + } + } + + // Normal Case without stop point but with terminal point + { + autoware_auto_planning_msgs::msg::Path path; + path.points.resize(10); + for (size_t i = 0; i < 10; ++i) { + path.points.at(i) = generateTestPathPoint(i * 1.0, 0.0, 0.0, 0.0, i * 1.0, i * 0.5, i * 0.1); + } + path.points.at(0).longitudinal_velocity_mps = 5.0; + + const auto resampled_path = resamplePath(path, 0.4); + for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { + const auto p = resampled_path.points.at(i); + EXPECT_NEAR(p.pose.position.x, 0.4 * i, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + const size_t idx = i / 2.5; + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(idx).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(idx).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.04 * i, epsilon); + } + + { + const auto p = resampled_path.points.at(23); + EXPECT_NEAR(p.pose.position.x, 9.0, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + const size_t idx = 9; + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(idx).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(idx).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.9, epsilon); + } + } + + // Normal Case without stop point but with terminal point (Boundary Condition) + { + autoware_auto_planning_msgs::msg::Path path; + path.points.resize(10); + for (size_t i = 0; i < 10; ++i) { + path.points.at(i) = generateTestPathPoint(i * 1.0, 0.0, 0.0, 0.0, i * 1.0, i * 0.5, i * 0.1); + } + path.points.at(0).longitudinal_velocity_mps = 5.0; + + const double ds = 1.0 - motion_utils::overlap_threshold; + const auto resampled_path = resamplePath(path, ds); + for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { + const auto p = resampled_path.points.at(i); + EXPECT_NEAR(p.pose.position.x, ds * i, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + const size_t idx = i == 0 ? 0 : i - 1; + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(idx).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(idx).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, ds / 10.0 * i, epsilon); + } + + { + const auto p = resampled_path.points.at(10); + EXPECT_NEAR(p.pose.position.x, 9.0, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + const size_t idx = 9; + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(idx).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(idx).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.9, epsilon); + } + } + + // Normal Case with duplicated zero point + { + autoware_auto_planning_msgs::msg::Path path; + path.points.resize(10); + for (size_t i = 0; i < 10; ++i) { + path.points.at(i) = generateTestPathPoint(i * 1.0, 0.0, 0.0, 0.0, i * 1.0, i * 0.5, i * 0.1); + } + path.points.at(0).longitudinal_velocity_mps = 5.0; + path.points.at(5).longitudinal_velocity_mps = 0.0; + + const auto resampled_path = resamplePath(path, 0.1); + EXPECT_EQ(resampled_path.points.size(), static_cast(91)); + for (size_t i = 0; i < resampled_path.points.size(); ++i) { + const auto p = resampled_path.points.at(i); + EXPECT_NEAR(p.pose.position.x, 0.1 * i, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + const size_t idx = i / 10; + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(idx).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(idx).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.01 * i, epsilon); + } + } + + // Normal Case with zero point + { + autoware_auto_planning_msgs::msg::Path path; + path.points.resize(10); + for (size_t i = 0; i < 10; ++i) { + path.points.at(i) = generateTestPathPoint(i * 1.0, 0.0, 0.0, 0.0, i * 1.0, i * 0.5, i * 0.1); + } + path.points.at(0).longitudinal_velocity_mps = 8.0; + path.points.at(5).longitudinal_velocity_mps = 0.0; + + const auto resampled_path = resamplePath(path, 1.5); + EXPECT_EQ(resampled_path.points.size(), static_cast(8)); + { + const auto p = resampled_path.points.at(0); + EXPECT_NEAR(p.pose.position.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(0).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(0).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.0, epsilon); + } + + { + const auto p = resampled_path.points.at(1); + EXPECT_NEAR(p.pose.position.x, 1.5, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(1).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(1).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.15, epsilon); + } + + { + const auto p = resampled_path.points.at(2); + EXPECT_NEAR(p.pose.position.x, 3.0, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(3).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(3).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.30, epsilon); + } + + { + const auto p = resampled_path.points.at(3); + EXPECT_NEAR(p.pose.position.x, 4.5, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(4).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(4).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.45, epsilon); + } + + { + const auto p = resampled_path.points.at(4); + EXPECT_NEAR(p.pose.position.x, 5.0, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + EXPECT_NEAR(p.longitudinal_velocity_mps, 0.0, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(5).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.50, epsilon); + } + + { + const auto p = resampled_path.points.at(5); + EXPECT_NEAR(p.pose.position.x, 6.0, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(6).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(6).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.60, epsilon); + } + + { + const auto p = resampled_path.points.at(6); + EXPECT_NEAR(p.pose.position.x, 7.5, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(7).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(7).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.75, epsilon); + } + + { + const auto p = resampled_path.points.at(7); + EXPECT_NEAR(p.pose.position.x, 9.0, epsilon); + EXPECT_NEAR(p.pose.position.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.position.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.x, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.y, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.z, 0.0, epsilon); + EXPECT_NEAR(p.pose.orientation.w, 1.0, epsilon); + + EXPECT_NEAR( + p.longitudinal_velocity_mps, path.points.at(9).longitudinal_velocity_mps, epsilon); + EXPECT_NEAR(p.lateral_velocity_mps, path.points.at(9).lateral_velocity_mps, epsilon); + EXPECT_NEAR(p.heading_rate_rps, 0.90, epsilon); + } + } + + // No Resample + { + // Input path size is not enough for resample + { + autoware_auto_planning_msgs::msg::Path path; + path.points.resize(1); + for (size_t i = 0; i < 1; ++i) { + path.points.at(i) = + generateTestPathPoint(i * 1.0, 0.0, 0.0, 0.0, i * 1.0, i * 0.5, i * 0.1); + } + + const auto resampled_path = resamplePath(path, 1.0); + EXPECT_EQ(resampled_path.points.size(), path.points.size()); + for (size_t i = 0; i < resampled_path.points.size(); ++i) { + EXPECT_NEAR( + resampled_path.points.at(i).pose.position.x, path.points.at(i).pose.position.x, epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.position.y, path.points.at(i).pose.position.y, epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.position.z, path.points.at(i).pose.position.z, epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.x, path.points.at(i).pose.orientation.x, + epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.y, path.points.at(i).pose.orientation.y, + epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.z, path.points.at(i).pose.orientation.z, + epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.w, path.points.at(i).pose.orientation.w, + epsilon); + } + } + + // Resample interval is invalid + { + autoware_auto_planning_msgs::msg::Path path; + path.points.resize(10); + for (size_t i = 0; i < 10; ++i) { + path.points.at(i) = + generateTestPathPoint(i * 1.0, 0.0, 0.0, 0.0, i * 1.0, i * 0.5, i * 0.1); + } + + const auto resampled_path = resamplePath(path, 1e-4); + EXPECT_EQ(resampled_path.points.size(), path.points.size()); + for (size_t i = 0; i < resampled_path.points.size(); ++i) { + EXPECT_NEAR( + resampled_path.points.at(i).pose.position.x, path.points.at(i).pose.position.x, epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.position.y, path.points.at(i).pose.position.y, epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.position.z, path.points.at(i).pose.position.z, epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.x, path.points.at(i).pose.orientation.x, + epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.y, path.points.at(i).pose.orientation.y, + epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.z, path.points.at(i).pose.orientation.z, + epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.w, path.points.at(i).pose.orientation.w, + epsilon); + } + } + + // Resample interval is invalid (Negative value) + { + autoware_auto_planning_msgs::msg::Path path; + path.points.resize(10); + for (size_t i = 0; i < 10; ++i) { + path.points.at(i) = + generateTestPathPoint(i * 1.0, 0.0, 0.0, 0.0, i * 1.0, i * 0.5, i * 0.1); + } + + const auto resampled_path = resamplePath(path, -5.0); + EXPECT_EQ(resampled_path.points.size(), path.points.size()); + for (size_t i = 0; i < resampled_path.points.size(); ++i) { + EXPECT_NEAR( + resampled_path.points.at(i).pose.position.x, path.points.at(i).pose.position.x, epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.position.y, path.points.at(i).pose.position.y, epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.position.z, path.points.at(i).pose.position.z, epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.x, path.points.at(i).pose.orientation.x, + epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.y, path.points.at(i).pose.orientation.y, + epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.z, path.points.at(i).pose.orientation.z, + epsilon); + EXPECT_NEAR( + resampled_path.points.at(i).pose.orientation.w, path.points.at(i).pose.orientation.w, + epsilon); + } + } + } +} + +TEST(resample_trajectory, resample_trajectory_by_vector) { using motion_utils::resampleTrajectory; // Output is same as input From a6b4a8699885c7ca853def10aeb699d9d5925673 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 5 Oct 2022 12:20:29 +0900 Subject: [PATCH 08/28] feat(map_loader): make some functions static (#2014) * feat(map_loader): make some functions static Signed-off-by: Takayuki Murooka * make publisher alive after constructor Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../map_loader/lanelet2_map_loader_node.hpp | 12 +++++++----- .../lanelet2_map_loader_node.cpp | 19 ++++++++++--------- 2 files changed, 17 insertions(+), 14 deletions(-) diff --git a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp index 72408f4af8185..82a90dd5c4ab4 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp +++ b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp @@ -31,13 +31,15 @@ class Lanelet2MapLoaderNode : public rclcpp::Node public: explicit Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options); + static lanelet::LaneletMapPtr load_map( + rclcpp::Node & node, const std::string & lanelet2_filename, + const std::string & lanelet2_map_projector_type); + static HADMapBin create_map_bin_msg( + const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, + const rclcpp::Time & now); + private: rclcpp::Publisher::SharedPtr pub_map_bin_; - - lanelet::LaneletMapPtr load_map( - const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type); - HADMapBin create_map_bin_msg( - const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename); }; #endif // MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index dc5d560b98e8e..da35f74eaa59c 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -54,7 +54,7 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options const auto center_line_resolution = declare_parameter("center_line_resolution", 5.0); // load map from file - const auto map = load_map(lanelet2_filename, lanelet2_map_projector_type); + const auto map = load_map(*this, lanelet2_filename, lanelet2_map_projector_type); if (!map) { return; } @@ -63,7 +63,7 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options lanelet::utils::overwriteLaneletsCenterline(map, center_line_resolution, false); // create map bin msg - const auto map_bin_msg = create_map_bin_msg(map, lanelet2_filename); + const auto map_bin_msg = create_map_bin_msg(map, lanelet2_filename, now()); // create publisher and publish pub_map_bin_ = @@ -72,7 +72,8 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options } lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( - const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type) + rclcpp::Node & node, const std::string & lanelet2_filename, + const std::string & lanelet2_map_projector_type) { lanelet::ErrorMessages errors{}; if (lanelet2_map_projector_type == "MGRS") { @@ -82,8 +83,8 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( return map; } } else if (lanelet2_map_projector_type == "UTM") { - const double map_origin_lat = declare_parameter("latitude", 0.0); - const double map_origin_lon = declare_parameter("longitude", 0.0); + const double map_origin_lat = node.declare_parameter("latitude", 0.0); + const double map_origin_lon = node.declare_parameter("longitude", 0.0); lanelet::GPSPoint position{map_origin_lat, map_origin_lon}; lanelet::Origin origin{position}; lanelet::projection::UtmProjector projector{origin}; @@ -93,25 +94,25 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( return map; } } else { - RCLCPP_ERROR(get_logger(), "lanelet2_map_projector_type is not supported"); + RCLCPP_ERROR(rclcpp::get_logger("map_loader"), "lanelet2_map_projector_type is not supported"); return nullptr; } for (const auto & error : errors) { - RCLCPP_ERROR_STREAM(get_logger(), error); + RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_loader"), error); } return nullptr; } HADMapBin Lanelet2MapLoaderNode::create_map_bin_msg( - const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename) + const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now) { std::string format_version{}, map_version{}; lanelet::io_handlers::AutowareOsmParser::parseVersions( lanelet2_filename, &format_version, &map_version); HADMapBin map_bin_msg; - map_bin_msg.header.stamp = now(); + map_bin_msg.header.stamp = now; map_bin_msg.header.frame_id = "map"; map_bin_msg.format_version = format_version; map_bin_msg.map_version = map_version; From b5d4e05027ac483c627080c751fd58d311706c60 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 5 Oct 2022 13:40:06 +0900 Subject: [PATCH 09/28] refactor(motion_utils): resample (#2020) * fix indent Signed-off-by: Takayuki Murooka * rename to resamplePoseVector Signed-off-by: Takayuki Murooka * fix dependant package Signed-off-by: Takayuki Murooka Signed-off-by: Takayuki Murooka --- .../motion_utils/resample/resample.hpp | 122 +++++++++--------- common/motion_utils/src/resample/resample.cpp | 8 +- .../src/turn_signal_decider.cpp | 2 +- 3 files changed, 65 insertions(+), 67 deletions(-) diff --git a/common/motion_utils/include/motion_utils/resample/resample.hpp b/common/motion_utils/include/motion_utils/resample/resample.hpp index 5eb42bb2eb91f..88fb59550e779 100644 --- a/common/motion_utils/include/motion_utils/resample/resample.hpp +++ b/common/motion_utils/include/motion_utils/resample/resample.hpp @@ -39,39 +39,39 @@ namespace motion_utils { /** * @brief A resampling function for a path(poses). Note that in a default setting, position xy are - * resampled by spline interpolation, position z are resampled by linear interpolation, and - * orientation of the resampled path are calculated by a forward difference method - * based on the interpolated position x and y. + * resampled by spline interpolation, position z are resampled by linear interpolation, and + * orientation of the resampled path are calculated by a forward difference method + * based on the interpolated position x and y. * @param input_path input path(poses) to resample * @param resampled_arclength arclength that contains length of each resampling points from initial - * point + * point * @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and - * y. Otherwise, it uses spline interpolation + * y. Otherwise, it uses spline interpolation * @param use_lerp_for_z If true, it uses linear interpolation to resample position z. - * Otherwise, it uses spline interpolation + * Otherwise, it uses spline interpolation * @return resampled path(poses) */ -std::vector resamplePath( +std::vector resamplePoseVector( const std::vector & points, const std::vector & resampled_arclength, const bool use_lerp_for_xy = false, const bool use_lerp_for_z = true); /** * @brief A resampling function for a path with lane id. Note that in a default setting, position xy - * are resampled by spline interpolation, position z are resampled by linear interpolation, - * longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is resampled - * by linear interpolation. Orientation of the resampled path are calculated by a forward difference - * method based on the interpolated position x and y. Moreover, lane_ids and is_final are also - * interpolated by zero order hold + * are resampled by spline interpolation, position z are resampled by linear interpolation, + * longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is + * resampled by linear interpolation. Orientation of the resampled path are calculated by a + * forward difference method based on the interpolated position x and y. Moreover, lane_ids + * and is_final are also interpolated by zero order hold * @param input_path input path to resample * @param resampled_arclength arclength that contains length of each resampling points from initial - * point + * point * @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and - * y. Otherwise, it uses spline interpolation + * y. Otherwise, it uses spline interpolation * @param use_lerp_for_z If true, it uses linear interpolation to resample position z. - * Otherwise, it uses spline interpolation + * Otherwise, it uses spline interpolation * @param use_zero_order_hold_for_v If true, it uses zero_order_hold to resample - * longitudinal and lateral velocity. Otherwise, it uses linear interpolation + * longitudinal and lateral velocity. Otherwise, it uses linear interpolation * @return resampled path */ autoware_auto_planning_msgs::msg::PathWithLaneId resamplePath( @@ -81,20 +81,19 @@ autoware_auto_planning_msgs::msg::PathWithLaneId resamplePath( /** * @brief A resampling function for a path with lane id. Note that in a default setting, position xy - * are resampled by spline interpolation, position z are resampled by linear interpolation, - * longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is resampled - * by linear interpolation. Orientation of the resampled path are calculated by a forward difference - * method based on the interpolated position x and y. Moreover, lane_ids and is_final are also - * interpolated by zero order hold + * are resampled by spline interpolation, position z are resampled by linear interpolation, + * longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is + * resampled by linear interpolation. Orientation of the resampled path are calculated by a + * forward difference method based on the interpolated position x and y. Moreover, lane_ids + * and is_final are also interpolated by zero order hold * @param input_path input path to resample - * @param resampled_interval resampling interval - * point + * @param resampled_interval resampling interval point * @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and - * y. Otherwise, it uses spline interpolation + * y. Otherwise, it uses spline interpolation * @param use_lerp_for_z If true, it uses linear interpolation to resample position z. - * Otherwise, it uses spline interpolation + * Otherwise, it uses spline interpolation * @param use_zero_order_hold_for_v If true, it uses zero_order_hold to resample - * longitudinal and lateral velocity. Otherwise, it uses linear interpolation + * longitudinal and lateral velocity. Otherwise, it uses linear interpolation * @param resample_input_path_stop_point If true, resample closest stop point in input path * @return resampled path */ @@ -106,19 +105,19 @@ autoware_auto_planning_msgs::msg::PathWithLaneId resamplePath( /** * @brief A resampling function for a path. Note that in a default setting, position xy are - * resampled by spline interpolation, position z are resampled by linear interpolation, longitudinal - * and lateral velocity are resampled by zero_order_hold, and heading rate is resampled by linear - * interpolation. Orientation of the resampled path are calculated by a forward difference method - * based on the interpolated position x and y. + * resampled by spline interpolation, position z are resampled by linear interpolation, + * longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is + * resampled by linear interpolation. Orientation of the resampled path are calculated by a + * forward difference method based on the interpolated position x and y. * @param input_path input path to resample * @param resampled_arclength arclength that contains length of each resampling points from initial - * point + * point * @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and - * y. Otherwise, it uses spline interpolation + * y. Otherwise, it uses spline interpolation * @param use_lerp_for_z If true, it uses linear interpolation to resample position z. - * Otherwise, it uses spline interpolation + * Otherwise, it uses spline interpolation * @param use_zero_order_hold_for_v If true, it uses zero_order_hold to resample - * longitudinal and lateral velocity. Otherwise, it uses linear interpolation + * longitudinal and lateral velocity. Otherwise, it uses linear interpolation * @return resampled path */ autoware_auto_planning_msgs::msg::Path resamplePath( @@ -128,19 +127,18 @@ autoware_auto_planning_msgs::msg::Path resamplePath( /** * @brief A resampling function for a path. Note that in a default setting, position xy - * are resampled by spline interpolation, position z are resampled by linear interpolation, - * longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is resampled - * by linear interpolation. Orientation of the resampled path are calculated by a forward difference - * method based on the interpolated position x and y. + * are resampled by spline interpolation, position z are resampled by linear interpolation, + * longitudinal and lateral velocity are resampled by zero_order_hold, and heading rate is + * resampled by linear interpolation. Orientation of the resampled path are calculated by a + * forward difference method based on the interpolated position x and y. * @param input_path input path to resample - * @param resampled_interval resampling interval - * point + * @param resampled_interval resampling interval point * @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and - * y. Otherwise, it uses spline interpolation + * y. Otherwise, it uses spline interpolation * @param use_lerp_for_z If true, it uses linear interpolation to resample position z. - * Otherwise, it uses spline interpolation + * Otherwise, it uses spline interpolation * @param use_zero_order_hold_for_v If true, it uses zero_order_hold to resample - * longitudinal and lateral velocity. Otherwise, it uses linear interpolation + * longitudinal and lateral velocity. Otherwise, it uses linear interpolation * @param resample_input_path_stop_point If true, resample closest stop point in input path * @return resampled path */ @@ -151,20 +149,20 @@ autoware_auto_planning_msgs::msg::Path resamplePath( /** * @brief A resampling function for a trajectory. Note that in a default setting, position xy are - * resampled by spline interpolation, position z are resampled by linear interpolation, twist - * informaiton(velocity and acceleration) are resampled by zero_order_hold, and heading rate is - * resampled by linear interpolation. The rest of the category is resampled by linear interpolation. - * Orientation of the resampled path are calculated by a forward difference method based on the - * interpolated position x and y. + * resampled by spline interpolation, position z are resampled by linear interpolation, twist + * informaiton(velocity and acceleration) are resampled by zero_order_hold, and heading rate + * is resampled by linear interpolation. The rest of the category is resampled by linear + * interpolation. Orientation of the resampled path are calculated by a forward difference + * method based on the interpolated position x and y. * @param input_trajectory input trajectory to resample * @param resampled_arclength arclength that contains length of each resampling points from initial - * point + * point * @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and - * y. Otherwise, it uses spline interpolation + * y. Otherwise, it uses spline interpolation * @param use_lerp_for_z If true, it uses linear interpolation to resample position z. - * Otherwise, it uses spline interpolation + * Otherwise, it uses spline interpolation * @param use_zero_order_hold_for_twist If true, it uses zero_order_hold to resample - * longitudinal, lateral velocity and acceleration. Otherwise, it uses linear interpolation + * longitudinal, lateral velocity and acceleration. Otherwise, it uses linear interpolation * @return resampled trajectory */ autoware_auto_planning_msgs::msg::Trajectory resampleTrajectory( @@ -174,22 +172,22 @@ autoware_auto_planning_msgs::msg::Trajectory resampleTrajectory( /** * @brief A resampling function for a trajectory. This function resamples closest stop point, - * terminal point and points by resample interval. Note that in a default setting, position xy are - * resampled by spline interpolation, position z are resampled by linear interpolation, twist - * informaiton(velocity and acceleration) are resampled by zero_order_hold, and heading rate is - * resampled by linear interpolation. The rest of the category is resampled by linear interpolation. - * Orientation of the resampled path are calculated by a forward difference method based on the - * interpolated position x and y. + * terminal point and points by resample interval. Note that in a default setting, position + * xy are resampled by spline interpolation, position z are resampled by linear interpolation, twist + * informaiton(velocity and acceleration) are resampled by zero_order_hold, and heading rate + * is resampled by linear interpolation. The rest of the category is resampled by linear + * interpolation. Orientation of the resampled path are calculated by a forward difference + * method based on the interpolated position x and y. * @param input_trajectory input trajectory to resample * @param resampled_interval resampling interval * @param use_lerp_for_xy If true, it uses linear interpolation to resample position x and - * y. Otherwise, it uses spline interpolation + * y. Otherwise, it uses spline interpolation * @param use_lerp_for_z If true, it uses linear interpolation to resample position z. - * Otherwise, it uses spline interpolation + * Otherwise, it uses spline interpolation * @param use_zero_order_hold_for_twist If true, it uses zero_order_hold to resample - * longitudinal, lateral velocity and acceleration. Otherwise, it uses linear interpolation + * longitudinal, lateral velocity and acceleration. Otherwise, it uses linear interpolation * @param resample_input_trajectory_stop_point If true, resample closest stop point in input - * trajectory + * trajectory * @return resampled trajectory */ autoware_auto_planning_msgs::msg::Trajectory resampleTrajectory( diff --git a/common/motion_utils/src/resample/resample.cpp b/common/motion_utils/src/resample/resample.cpp index 79c03cf0081c5..ea2c40dc91f58 100644 --- a/common/motion_utils/src/resample/resample.cpp +++ b/common/motion_utils/src/resample/resample.cpp @@ -19,7 +19,7 @@ namespace motion_utils { -std::vector resamplePath( +std::vector resamplePoseVector( const std::vector & points, const std::vector & resampled_arclength, const bool use_lerp_for_xy, const bool use_lerp_for_z) @@ -164,7 +164,7 @@ autoware_auto_planning_msgs::msg::PathWithLaneId resamplePath( }; const auto interpolated_pose = - resamplePath(input_pose, resampled_arclength, use_lerp_for_xy, use_lerp_for_z); + resamplePoseVector(input_pose, resampled_arclength, use_lerp_for_xy, use_lerp_for_z); const auto interpolated_v_lon = use_zero_order_hold_for_v ? zoh(v_lon) : lerp(v_lon); const auto interpolated_v_lat = use_zero_order_hold_for_v ? zoh(v_lat) : lerp(v_lat); const auto interpolated_heading_rate = lerp(heading_rate); @@ -308,7 +308,7 @@ autoware_auto_planning_msgs::msg::Path resamplePath( }; const auto interpolated_pose = - resamplePath(input_pose, resampled_arclength, use_lerp_for_xy, use_lerp_for_z); + resamplePoseVector(input_pose, resampled_arclength, use_lerp_for_xy, use_lerp_for_z); const auto interpolated_v_lon = use_zero_order_hold_for_v ? zoh(v_lon) : lerp(v_lon); const auto interpolated_v_lat = use_zero_order_hold_for_v ? zoh(v_lat) : lerp(v_lat); const auto interpolated_heading_rate = lerp(heading_rate); @@ -459,7 +459,7 @@ autoware_auto_planning_msgs::msg::Trajectory resampleTrajectory( }; const auto interpolated_pose = - resamplePath(input_pose, resampled_arclength, use_lerp_for_xy, use_lerp_for_z); + resamplePoseVector(input_pose, resampled_arclength, use_lerp_for_xy, use_lerp_for_z); const auto interpolated_v_lon = use_zero_order_hold_for_twist ? zoh(v_lon) : lerp(v_lon); const auto interpolated_v_lat = use_zero_order_hold_for_twist ? zoh(v_lat) : lerp(v_lat); const auto interpolated_heading_rate = lerp(heading_rate); diff --git a/planning/behavior_path_planner/src/turn_signal_decider.cpp b/planning/behavior_path_planner/src/turn_signal_decider.cpp index f2e295cffbc52..6ab1f7cc3cb0a 100644 --- a/planning/behavior_path_planner/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/src/turn_signal_decider.cpp @@ -321,7 +321,7 @@ geometry_msgs::msg::Point TurnSignalDecider::get_required_end_point( } const auto resampled_centerline = - motion_utils::resamplePath(converted_centerline, resampling_arclength); + motion_utils::resamplePoseVector(converted_centerline, resampling_arclength); const double terminal_yaw = tf2::getYaw(resampled_centerline.back().orientation); for (size_t i = 0; i < resampled_centerline.size(); ++i) { From ce93396d7b17dbb37666a7251d148fa1dc26aa4d Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 5 Oct 2022 17:14:57 +0900 Subject: [PATCH 10/28] refactor(ndt_scan_matcher): modularize get_transform function (#1984) * refactor(ndt_scan_matcher): modularize get_transform function Signed-off-by: kminoda * ci(pre-commit): autofix * add explicit Signed-off-by: kminoda * resolve precommit issue * ci(pre-commit): autofix Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/ndt_scan_matcher/CMakeLists.txt | 1 + .../ndt_scan_matcher_core.hpp | 11 +--- .../ndt_scan_matcher/tf2_listener_module.hpp | 43 +++++++++++++ .../src/ndt_scan_matcher_core.cpp | 52 +++------------- .../src/tf2_listener_module.cpp | 60 +++++++++++++++++++ 5 files changed, 115 insertions(+), 52 deletions(-) create mode 100644 localization/ndt_scan_matcher/include/ndt_scan_matcher/tf2_listener_module.hpp create mode 100644 localization/ndt_scan_matcher/src/tf2_listener_module.cpp diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index df79a2cfc0dfd..d2d5568e265a9 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -28,6 +28,7 @@ ament_auto_add_executable(ndt_scan_matcher src/ndt_scan_matcher_core.cpp src/util_func.cpp src/pose_array_interpolator.cpp + src/tf2_listener_module.cpp ) ament_auto_package( diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index 2be9c8084be81..4545a3ff36225 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -18,6 +18,7 @@ #define FMT_HEADER_ONLY #include "ndt_scan_matcher/particle.hpp" +#include "ndt_scan_matcher/tf2_listener_module.hpp" #include #include @@ -43,9 +44,7 @@ #include #endif -#include #include -#include #ifdef ROS_DISTRO_GALACTIC #include @@ -154,10 +153,6 @@ class NDTScanMatcher : public rclcpp::Node const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_old_msg, const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_new_msg); - bool get_transform( - const std::string & target_frame, const std::string & source_frame, - const geometry_msgs::msg::TransformStamped::SharedPtr & transform_stamped_ptr); - bool validate_num_iteration(const int iter_num, const int max_iter_num); bool validate_score( const double score, const double score_threshold, const std::string score_name); @@ -200,8 +195,6 @@ class NDTScanMatcher : public rclcpp::Node rclcpp::Service::SharedPtr service_; - tf2_ros::Buffer tf2_buffer_; - tf2_ros::TransformListener tf2_listener_; tf2_ros::TransformBroadcaster tf2_broadcaster_; NDTImplementType ndt_implement_type_; @@ -238,6 +231,8 @@ class NDTScanMatcher : public rclcpp::Node const float regularization_scale_factor_; std::deque regularization_pose_msg_ptr_array_; + + std::shared_ptr tf2_listener_module_; }; #endif // NDT_SCAN_MATCHER__NDT_SCAN_MATCHER_CORE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/tf2_listener_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/tf2_listener_module.hpp new file mode 100644 index 0000000000000..159acbd75ce3d --- /dev/null +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/tf2_listener_module.hpp @@ -0,0 +1,43 @@ +// Copyright 2015-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NDT_SCAN_MATCHER__TF2_LISTENER_MODULE_HPP_ +#define NDT_SCAN_MATCHER__TF2_LISTENER_MODULE_HPP_ + +#include + +#include +#include +#include + +#include + +class Tf2ListenerModule +{ + using TransformStamped = geometry_msgs::msg::TransformStamped; + +public: + explicit Tf2ListenerModule(rclcpp::Node * node); + bool get_transform( + const builtin_interfaces::msg::Time & timestamp, const std::string & target_frame, + const std::string & source_frame, + const geometry_msgs::msg::TransformStamped::SharedPtr & transform_stamped_ptr) const; + +private: + rclcpp::Logger logger_; + tf2_ros::Buffer tf2_buffer_; + tf2_ros::TransformListener tf2_listener_; +}; + +#endif // NDT_SCAN_MATCHER__TF2_LISTENER_MODULE_HPP_ diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index 684a723754a08..53e2e8c199dbb 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -51,19 +51,6 @@ tier4_debug_msgs::msg::Int32Stamped make_int32_stamped( return tier4_debug_msgs::build().stamp(stamp).data(data); } -geometry_msgs::msg::TransformStamped identity_transform_stamped( - const builtin_interfaces::msg::Time & timestamp, const std::string & header_frame_id, - const std::string & child_frame_id) -{ - geometry_msgs::msg::TransformStamped transform; - transform.header.stamp = timestamp; - transform.header.frame_id = header_frame_id; - transform.child_frame_id = child_frame_id; - transform.transform.rotation = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); - transform.transform.translation = tier4_autoware_utils::createTranslation(0.0, 0.0, 0.0); - return transform; -} - bool validate_local_optimal_solution_oscillation( const std::vector & result_pose_msg_array, const float oscillation_threshold, const float inversion_vector_threshold) @@ -94,8 +81,6 @@ bool validate_local_optimal_solution_oscillation( NDTScanMatcher::NDTScanMatcher() : Node("ndt_scan_matcher"), - tf2_buffer_(this->get_clock()), - tf2_listener_(tf2_buffer_), tf2_broadcaster_(*this), ndt_implement_type_(NDTImplementType::PCL_GENERIC), base_frame_("base_link"), @@ -272,6 +257,8 @@ NDTScanMatcher::NDTScanMatcher() diagnostic_thread_ = std::thread(&NDTScanMatcher::timer_diagnostic, this); diagnostic_thread_.detach(); + + tf2_listener_module_ = std::make_shared(this); } void NDTScanMatcher::timer_diagnostic() @@ -331,7 +318,8 @@ void NDTScanMatcher::service_ndt_align( { // get TF from pose_frame to map_frame auto TF_pose_to_map_ptr = std::make_shared(); - get_transform(map_frame_, req->pose_with_covariance.header.frame_id, TF_pose_to_map_ptr); + tf2_listener_module_->get_transform( + this->now(), map_frame_, req->pose_with_covariance.header.frame_id, TF_pose_to_map_ptr); // transform pose_frame to map_frame const auto mapTF_initial_pose_msg = transform(req->pose_with_covariance, *TF_pose_to_map_ptr); @@ -378,7 +366,8 @@ void NDTScanMatcher::callback_initial_pose( } else { // get TF from pose_frame to map_frame auto TF_pose_to_map_ptr = std::make_shared(); - get_transform(map_frame_, initial_pose_msg_ptr->header.frame_id, TF_pose_to_map_ptr); + tf2_listener_module_->get_transform( + this->now(), map_frame_, initial_pose_msg_ptr->header.frame_id, TF_pose_to_map_ptr); // transform pose_frame to map_frame auto mapTF_initial_pose_msg_ptr = @@ -558,7 +547,8 @@ void NDTScanMatcher::transform_sensor_measurement( pcl::shared_ptr> sensor_points_output_ptr) { auto TF_target_to_source_ptr = std::make_shared(); - get_transform(target_frame, source_frame, TF_target_to_source_ptr); + tf2_listener_module_->get_transform( + this->now(), target_frame, source_frame, TF_target_to_source_ptr); const geometry_msgs::msg::PoseStamped target_to_source_pose_stamped = tier4_autoware_utils::transform2pose(*TF_target_to_source_ptr); const Eigen::Matrix4f base_to_sensor_matrix = @@ -733,32 +723,6 @@ void NDTScanMatcher::publish_initial_to_result_distances( make_float32_stamped(sensor_ros_time, initial_to_result_distance_new)); } -bool NDTScanMatcher::get_transform( - const std::string & target_frame, const std::string & source_frame, - const geometry_msgs::msg::TransformStamped::SharedPtr & transform_stamped_ptr) -{ - const geometry_msgs::msg::TransformStamped identity = - identity_transform_stamped(this->now(), target_frame, source_frame); - - if (target_frame == source_frame) { - *transform_stamped_ptr = identity; - return true; - } - - try { - *transform_stamped_ptr = - tf2_buffer_.lookupTransform(target_frame, source_frame, tf2::TimePointZero); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN(get_logger(), "%s", ex.what()); - RCLCPP_ERROR( - get_logger(), "Please publish TF %s to %s", target_frame.c_str(), source_frame.c_str()); - - *transform_stamped_ptr = identity; - return false; - } - return true; -} - bool NDTScanMatcher::validate_num_iteration(const int iter_num, const int max_iter_num) { bool is_ok_iter_num = iter_num < max_iter_num; diff --git a/localization/ndt_scan_matcher/src/tf2_listener_module.cpp b/localization/ndt_scan_matcher/src/tf2_listener_module.cpp new file mode 100644 index 0000000000000..364952a631f06 --- /dev/null +++ b/localization/ndt_scan_matcher/src/tf2_listener_module.cpp @@ -0,0 +1,60 @@ +// Copyright 2015-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ndt_scan_matcher/tf2_listener_module.hpp" + +#include + +geometry_msgs::msg::TransformStamped identity_transform_stamped( + const builtin_interfaces::msg::Time & timestamp, const std::string & header_frame_id, + const std::string & child_frame_id) +{ + geometry_msgs::msg::TransformStamped transform; + transform.header.stamp = timestamp; + transform.header.frame_id = header_frame_id; + transform.child_frame_id = child_frame_id; + transform.transform.rotation = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); + transform.transform.translation = tier4_autoware_utils::createTranslation(0.0, 0.0, 0.0); + return transform; +} + +Tf2ListenerModule::Tf2ListenerModule(rclcpp::Node * node) +: logger_(node->get_logger()), tf2_buffer_(node->get_clock()), tf2_listener_(tf2_buffer_) +{ +} + +bool Tf2ListenerModule::get_transform( + const builtin_interfaces::msg::Time & timestamp, const std::string & target_frame, + const std::string & source_frame, const TransformStamped::SharedPtr & transform_stamped_ptr) const +{ + const TransformStamped identity = + identity_transform_stamped(timestamp, target_frame, source_frame); + + if (target_frame == source_frame) { + *transform_stamped_ptr = identity; + return true; + } + + try { + *transform_stamped_ptr = + tf2_buffer_.lookupTransform(target_frame, source_frame, tf2::TimePointZero); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN(logger_, "%s", ex.what()); + RCLCPP_ERROR(logger_, "Please publish TF %s to %s", target_frame.c_str(), source_frame.c_str()); + + *transform_stamped_ptr = identity; + return false; + } + return true; +} From 28a3ccc1387effc706aafd6d572d580cff52577b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 5 Oct 2022 18:51:59 +0900 Subject: [PATCH 11/28] fix(behavior_path_planner): not run pull out if out of lane (#2008) Signed-off-by: kosuke55 Signed-off-by: kosuke55 --- .../lane_departure_checker.hpp | 6 +-- .../scene_module/pull_out/pull_out_module.hpp | 2 +- .../scene_module/pull_out/pull_out_module.cpp | 45 +++++++++++-------- .../scene_module/pull_out/shift_pull_out.cpp | 15 +++---- 4 files changed, 38 insertions(+), 30 deletions(-) diff --git a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp index c90ced556912f..c377109744578 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp +++ b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp @@ -107,6 +107,9 @@ class LaneDepartureChecker bool checkPathWillLeaveLane( const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path) const; + static bool isOutOfLane( + const lanelet::ConstLanelets & candidate_lanelets, const LinearRing2d & vehicle_footprint); + private: Param param_; std::shared_ptr vehicle_info_ptr_; @@ -131,9 +134,6 @@ class LaneDepartureChecker static bool willLeaveLane( const lanelet::ConstLanelets & candidate_lanelets, const std::vector & vehicle_footprints); - - static bool isOutOfLane( - const lanelet::ConstLanelets & candidate_lanelets, const LinearRing2d & vehicle_footprint); }; } // namespace lane_departure_checker diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/pull_out/pull_out_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/pull_out/pull_out_module.hpp index b7134413d0597..87b3ef00a6ebf 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/pull_out/pull_out_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/pull_out/pull_out_module.hpp @@ -110,7 +110,7 @@ class PullOutModule : public SceneModuleInterface void planWithPriorityOnShortBackDistance( const std::vector & start_pose_candidates, const Pose & goal_pose); void updatePullOutStatus(); - static bool isInLane( + static bool isOverlappedWithLane( const lanelet::ConstLanelet & candidate_lanelet, const tier4_autoware_utils::LinearRing2d & vehicle_footprint); bool hasFinishedPullOut() const; diff --git a/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp b/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp index 271e1f576b767..04d4fb714ed8e 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp @@ -112,27 +112,36 @@ bool PullOutModule::isExecutionRequested() const const bool is_stopped = util::l2Norm(planner_data_->self_odometry->twist.twist.linear) < parameters_.th_arrived_distance; + if (!is_stopped) { + return false; + } + + // Create vehicle footprint + const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_); + const auto vehicle_footprint = transformVector( + local_vehicle_footprint, tier4_autoware_utils::pose2transform(planner_data_->self_pose->pose)); + + // Check if ego is not out of lanes + const auto current_lanes = util::getExtendedCurrentLanes(planner_data_); + const auto pull_out_lanes = pull_out_utils::getPullOutLanes(current_lanes, planner_data_); + auto lanes = current_lanes; + lanes.insert(lanes.end(), pull_out_lanes.begin(), pull_out_lanes.end()); + if (LaneDepartureChecker::isOutOfLane(lanes, vehicle_footprint)) { + return false; + } + // Check if any of the footprint points are in the shoulder lane lanelet::Lanelet closest_shoulder_lanelet; - if ( - lanelet::utils::query::getClosestLanelet( - planner_data_->route_handler->getShoulderLanelets(), planner_data_->self_pose->pose, - &closest_shoulder_lanelet) && - is_stopped) { - // Create vehicle footprint - const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_); - const auto vehicle_footprint = transformVector( - local_vehicle_footprint, - tier4_autoware_utils::pose2transform(planner_data_->self_pose->pose)); - const auto road_lanes = util::getExtendedCurrentLanes(planner_data_); - - // check if goal pose is in shoulder lane and distance is long enough for pull out - if (isInLane(closest_shoulder_lanelet, vehicle_footprint)) { - return true; - } + if (!lanelet::utils::query::getClosestLanelet( + planner_data_->route_handler->getShoulderLanelets(), planner_data_->self_pose->pose, + &closest_shoulder_lanelet)) { + return false; + } + if (!isOverlappedWithLane(closest_shoulder_lanelet, vehicle_footprint)) { + return false; } - return false; + return true; } bool PullOutModule::isExecutionReady() const { return true; } @@ -510,7 +519,7 @@ std::vector PullOutModule::searchBackedPoses() return backed_poses; } -bool PullOutModule::isInLane( +bool PullOutModule::isOverlappedWithLane( const lanelet::ConstLanelet & candidate_lanelet, const tier4_autoware_utils::LinearRing2d & vehicle_footprint) { diff --git a/planning/behavior_path_planner/src/scene_module/pull_out/shift_pull_out.cpp b/planning/behavior_path_planner/src/scene_module/pull_out/shift_pull_out.cpp index 88642b7c431b2..9aa8feda2670f 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_out/shift_pull_out.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_out/shift_pull_out.cpp @@ -42,7 +42,6 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) const auto & common_parameters = planner_data_->parameters; const auto & dynamic_objects = planner_data_->dynamic_object; const auto & road_lanes = util::getExtendedCurrentLanes(planner_data_); - const auto & current_pose = planner_data_->self_pose->pose; const auto & shoulder_lanes = getPullOutLanes(road_lanes, planner_data_); if (shoulder_lanes.empty()) { return boost::none; @@ -69,24 +68,24 @@ boost::optional ShiftPullOut::plan(Pose start_pose, Pose goal_pose) auto & shift_path = pull_out_path.partial_paths.front(); // shift path is not separate but only one. - // check lane_departure and collision with path between current to pull_out_end - PathWithLaneId path_current_to_shift_end; + // check lane_departure and collision with path between pull_out_start to pull_out_end + PathWithLaneId path_start_to_end{}; { - const auto current_idx = findNearestIndex(shift_path.points, current_pose); + const auto pull_out_start_idx = findNearestIndex(shift_path.points, start_pose); const auto pull_out_end_idx = findNearestIndex(shift_path.points, pull_out_path.end_pose); - path_current_to_shift_end.points.insert( - path_current_to_shift_end.points.begin(), shift_path.points.begin() + *current_idx, + path_start_to_end.points.insert( + path_start_to_end.points.begin(), shift_path.points.begin() + *pull_out_start_idx, shift_path.points.begin() + *pull_out_end_idx + 1); } // check lane departure - if (lane_departure_checker_->checkPathWillLeaveLane(lanes, path_current_to_shift_end)) { + if (lane_departure_checker_->checkPathWillLeaveLane(lanes, path_start_to_end)) { continue; } // check collision if (util::checkCollisionBetweenPathFootprintsAndObjects( - vehicle_footprint_, path_current_to_shift_end, shoulder_lane_objects, + vehicle_footprint_, path_start_to_end, shoulder_lane_objects, parameters_.collision_check_margin)) { continue; } From c2d5b4fcc9603e791e5c825fcac9f00665303e89 Mon Sep 17 00:00:00 2001 From: Azumi Suzuki <38061530+s-azumi@users.noreply.github.com> Date: Thu, 6 Oct 2022 09:50:32 +0900 Subject: [PATCH 12/28] fix: modified to reflect the argument "initial_selector_mode" in control_launch (#1961) --- launch/tier4_control_launch/launch/control.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index 044c5e3a8136a..d9ed65fd9f80c 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -239,7 +239,7 @@ def launch_setup(context, *args, **kwargs): launch_arguments=[ ("use_intra_process", LaunchConfiguration("use_intra_process")), ("target_container", "/control/control_container"), - ("initial_selector_mode", "remote"), + ("initial_selector_mode", LaunchConfiguration("initial_selector_mode")), ], ) From 5695431cba03794159acbf539960328b116df9eb Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 6 Oct 2022 10:11:44 +0900 Subject: [PATCH 13/28] fix(ground segmentation): add elevation grid ground filter (#1899) * fix: add grid elevation scan ground filter Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * fix: merge with scan ground filter Signed-off-by: badai-nguyen * ci(pre-commit): autofix * chore: update docs Signed-off-by: badai-nguyen * chore: remove debug variables Signed-off-by: badai-nguyen * chore: add switchable param for grid scan mode Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * chore: refactoring Signed-off-by: badai-nguyen * ci(pre-commit): autofix * chore: refactoring Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * chore: refactoring Signed-off-by: badai-nguyen * chore: refactoring Signed-off-by: badai-nguyen * chore: refactoring Signed-off-by: badai-nguyen * chore: refactoring Signed-off-by: badai-nguyen * chore: refactoring Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * docs: update docs Signed-off-by: badai-nguyen * ci(pre-commit): autofix * chore: typo Signed-off-by: badai-nguyen * chores: typo Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * docs: update Signed-off-by: badai-nguyen Signed-off-by: badai-nguyen Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../ground_segmentation.param.yaml | 12 +- .../ground_segmentation.launch.py | 6 - launch/tier4_perception_launch/package.xml | 1 + perception/ground_segmentation/CMakeLists.txt | 1 + .../docs/scan-ground-filter.md | 43 ++- .../scan_ground_filter_nodelet.hpp | 53 ++- .../src/scan_ground_filter_nodelet.cpp | 312 +++++++++++++++++- 7 files changed, 396 insertions(+), 32 deletions(-) diff --git a/launch/tier4_perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/launch/tier4_perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml index e3bef09e52b47..bde1b024d757e 100644 --- a/launch/tier4_perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml +++ b/launch/tier4_perception_launch/config/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -11,13 +11,21 @@ max_x: 100.0 min_y: -50.0 max_y: 50.0 + max_z: 10.7 # recommended 2.5 for non elevation_grid_mode + min_z: -8.7 # recommended 0.0 for non elevation_grid_mode negative: False common_ground_filter: plugin: "ground_segmentation::ScanGroundFilterComponent" parameters: global_slope_max_angle_deg: 10.0 - local_slope_max_angle_deg: 30.0 + local_slope_max_angle_deg: 13.0 # recommended 30.0 for non elevation_grid_mode split_points_distance_tolerance: 0.2 - split_height_distance: 0.3 use_virtual_ground_point: True + split_height_distance: 0.2 + non_ground_height_threshold: 0.20 + grid_size_m: 0.1 + grid_mode_switch_radius: 20.0 + gnd_grid_buffer_size: 4 + detection_range_z_max: 2.5 + elevation_grid_mode: true diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 42278ec4f09e1..a748b1b1aff34 100644 --- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -56,8 +56,6 @@ def get_vehicle_info(self): p["max_longitudinal_offset"] = p["front_overhang"] + p["wheel_base"] p["min_lateral_offset"] = -(p["wheel_tread"] / 2.0 + p["right_overhang"]) p["max_lateral_offset"] = p["wheel_tread"] / 2.0 + p["left_overhang"] - p["min_height_offset"] = 0.0 - p["max_height_offset"] = p["vehicle_height"] return p def get_vehicle_mirror_info(self): @@ -81,8 +79,6 @@ def create_additional_pipeline(self, lidar_name): { "input_frame": LaunchConfiguration("base_frame"), "output_frame": LaunchConfiguration("base_frame"), - "min_z": self.vehicle_info["min_height_offset"], - "max_z": self.vehicle_info["max_height_offset"], }, self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"], ], @@ -215,8 +211,6 @@ def create_common_pipeline(self, input_topic, output_topic): { "input_frame": LaunchConfiguration("base_frame"), "output_frame": LaunchConfiguration("base_frame"), - "min_z": self.vehicle_info["min_height_offset"], - "max_z": self.vehicle_info["max_height_offset"], }, self.ground_segmentation_param["common_crop_box_filter"]["parameters"], ], diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 3253c1db4d1d6..ae5c5df34af0d 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -5,6 +5,7 @@ 0.1.0 The tier4_perception_launch package Yukihiro Saito + Shunsuke Miura Apache License 2.0 ament_cmake_auto diff --git a/perception/ground_segmentation/CMakeLists.txt b/perception/ground_segmentation/CMakeLists.txt index d2711bc59ecca..08bf60c8bdd08 100644 --- a/perception/ground_segmentation/CMakeLists.txt +++ b/perception/ground_segmentation/CMakeLists.txt @@ -56,6 +56,7 @@ rclcpp_components_register_node(ground_segmentation PLUGIN "ground_segmentation::ScanGroundFilterComponent" EXECUTABLE scan_ground_filter_node) + ament_auto_package(INSTALL_TO_SHARE launch ) diff --git a/perception/ground_segmentation/docs/scan-ground-filter.md b/perception/ground_segmentation/docs/scan-ground-filter.md index 03723fee4423c..75dd290bffb05 100644 --- a/perception/ground_segmentation/docs/scan-ground-filter.md +++ b/perception/ground_segmentation/docs/scan-ground-filter.md @@ -9,12 +9,13 @@ The purpose of this node is that remove the ground points from the input pointcl This algorithm works by following steps, 1. Divide whole pointclouds into groups by horizontal angle and sort by xy-distance. -2. Check the distance and vertical angle of the point one by one. -3. Set a center of the ground contact point of the rear or front wheels as the initial point. -4. Check vertical angle between the points. If the angle from the initial point is larger than "global_slope_max", the point is classified as "no ground". -5. If the angle from the previous point is larger than "local_max_slope", the point is classified as "no ground". -6. Otherwise the point is labeled as "ground point". -7. If the distance from the last checked point is close, ignore any vertical angle and set current point attribute to the same as the last point. +2. Divide sorted pointclouds of each ray into grids +3. Check the xy distance to previous pointcloud, if the distance is large and previous pointcloud is "no ground" and the height level of current point greater than previous point, the current pointcloud is classified as no ground. +4. Check vertical angle of the point compared with previous ground grid +5. Check the height of the point compared with predicted ground level +6. If vertical angle is greater than local_slope_max and related height to predicted ground level is greater than "non ground height threshold", the point is classified as "non ground" +7. If the vertical angle is in range of [-local_slope_max, local_slope_max] or related height to predicted ground level is smaller than non_ground_height_threshold, the point is classified as "ground" +8. If the vertical angle is lower than -local_slope_max or the related height to ground level is greater than detection_range_z_max, the point will be classified as out of range ## Inputs / Outputs @@ -28,16 +29,24 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref #### Core Parameters -| Name | Type | Default Value | Description | -| --------------------------------- | ------ | ------------- | ----------------------------------------------------------------------------- | -| `input_frame` | string | "base_link" | frame id of input pointcloud | -| `output_frame` | string | "base_link" | frame id of output pointcloud | -| `global_slope_max` | double | 8.0 | The global angle to classify as the ground or object [deg] | -| `local_max_slope` | double | 6.0 | The local angle to classify as the ground or object [deg] | -| `radial_divider_angle` | double | 1.0 | The angle which divide the whole pointcloud to sliced group [deg] | -| `split_points_distance_tolerance` | double | 0.2 | The xy-distance threshold to to distinguishing far and near [m] | -| `split_height_distance` | double | 0.2 | The height threshold to distinguishing far and near [m] | -| `use_virtual_ground_point` | bool | true | whether to use the ground center of front wheels as the virtual ground point. | +| Name | Type | Default Value | Description | +| --------------------------------- | ------ | ------------- | ------------------------------------------------------------------------------------------------------------------------------------------------- | +| `input_frame` | string | "base_link" | frame id of input pointcloud | +| `output_frame` | string | "base_link" | frame id of output pointcloud | +| `global_slope_max_angle_deg` | double | 8.0 | The global angle to classify as the ground or object [deg] | +| `local_slope_max_angle_deg` | double | 10.0 | The local angle to classify as the ground or object [deg] | +| `radial_divider_angle_deg` | double | 1.0 | The angle which divide the whole pointcloud to sliced group [deg] | +| `split_points_distance_tolerance` | double | 0.2 | The xy-distance threshold to to distinguishing far and near [m] | +| `split_height_distance` | double | 0.2 | The height threshold to distinguishing far and near [m] | +| `use_virtual_ground_point` | bool | true | whether to use the ground center of front wheels as the virtual ground point. | +| `detection_range_z_max` | float | 2.5 | Maximum height of detection range [m], applied only for elevation_grid_mode | +| `center_pcl_shift` | float | 0.0 | The x-axis offset of addition LiDARs from vehicle center of mass [m],
recommended to use only for additional LiDARs in elevation_grid_mode | +| `non_ground_height_threshold` | float | 0.2 | Height threshold of non ground objects [m], applied only for elevation_grid_mode | +| `grid_mode_switch_radius` | float | 20.0 | The distance where grid division mode change from by distance to by vertical angle [m],
applied only for elevation_grid_mode | +| `grid_size_m` | float | 0.5 | The first grid size [m], applied only for elevation_grid_mode | +| `gnd_grid_buffer_size` | uint16 | 4 | Number of grids using to estimate local ground slope,
applied only for elevation_grid_mode | +| `low_priority_region_x` | float | -20.0 | The non-zero x threshold in back side from which small objects detection is low priority [m] | +| `elevation_grid_mode` | bool | true | Elevation grid scan mode option | ## Assumptions / Known limits @@ -49,6 +58,8 @@ The input_frame is set as parameter but it must be fixed as base_link for the cu ## (Optional) References/External links +The elevation grid idea is referred from "Shen Z, Liang H, Lin L, Wang Z, Huang W, Yu J. Fast Ground Segmentation for 3D LiDAR Point Cloud Based on Jump-Convolution-Process. Remote Sensing. 2021; 13(16):3239. " + ## (Optional) Future extensions / Unimplemented parts - Horizontal check for classification is not implemented yet. diff --git a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp index 1aa0bc01f25e7..9625507b5398f 100644 --- a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp +++ b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp @@ -54,9 +54,12 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter POINT_FOLLOW, UNKNOWN, VIRTUAL_GROUND, + OUT_OF_RANGE }; struct PointRef { + float grid_size; // radius of grid + uint16_t grid_id; // id of grid in vertical float radius; // cylindrical coords on XY Plane float theta; // angle deg on XY plane size_t radial_div; // index of the radial division to which this point belongs to @@ -67,13 +70,23 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter }; using PointCloudRefVector = std::vector; + struct GridCenter + { + float radius; + float avg_height; + float max_height; + uint16_t grid_id; + }; + struct PointsCentroid { float radius_sum; float height_sum; float radius_avg; float height_avg; + float height_max; uint32_t point_num; + uint16_t grid_id; PointsCentroid() : radius_sum(0.0f), height_sum(0.0f), radius_avg(0.0f), height_avg(0.0f), point_num(0) @@ -86,7 +99,9 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter height_sum = 0.0f; radius_avg = 0.0f; height_avg = 0.0f; + height_max = 0.0f; point_num = 0; + grid_id = 0; } void addPoint(const float radius, const float height) @@ -96,6 +111,7 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter ++point_num; radius_avg = radius_sum / point_num; height_avg = height_sum / point_num; + height_max = height_max < height ? height : height_max; } float getAverageSlope() { return std::atan2(height_avg, radius_avg); } @@ -103,6 +119,10 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter float getAverageHeight() { return height_avg; } float getAverageRadius() { return radius_avg; } + + float getMaxHeight() { return height_max; } + + uint16_t getGridId() { return grid_id; } }; void filter( @@ -111,8 +131,19 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter tf2_ros::Buffer tf_buffer_{get_clock()}; tf2_ros::TransformListener tf_listener_{tf_buffer_}; - std::string base_frame_; - std::string sensor_frame_; + const uint16_t gnd_grid_continual_thresh_ = 3; + bool elevation_grid_mode_; + float non_ground_height_threshold_; + float grid_size_rad_; + float grid_size_m_; + float low_priority_region_x_; + uint16_t gnd_grid_buffer_size_; + float grid_mode_switch_grid_id_; + float grid_mode_switch_angle_rad_; + float virtual_lidar_z_; + float detection_range_z_max_; + float center_pcl_shift_; // virtual center of pcl to center mass + float grid_mode_switch_radius_; // non linear grid size switching distance double global_slope_max_angle_rad_; // radians double local_slope_max_angle_rad_; // radians double radial_divider_angle_rad_; // distance in rads between dividers @@ -141,7 +172,9 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter void convertPointcloud( const pcl::PointCloud::Ptr in_cloud, std::vector & out_radial_ordered_points_manager); - + void convertPointcloudGridScan( + const pcl::PointCloud::Ptr in_cloud, + std::vector & out_radial_ordered_points_manager); /*! * Output ground center of front wheels as the virtual ground point * @param[out] point Virtual ground origin point @@ -155,10 +188,22 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter * @param out_no_ground_indices Returns the indices of the points * classified as not ground in the original PointCloud */ + + void initializeFirstGndGrids( + const float h, const float r, const uint16_t id, std::vector & gnd_grids); + + void checkContinuousGndGrid( + PointRef & p, const std::vector & gnd_grids_list, PointsCentroid & gnd_cluster); + void checkDiscontinuousGndGrid( + PointRef & p, const std::vector & gnd_grids_list, PointsCentroid & gnd_cluster); + void checkBreakGndGrid( + PointRef & p, const std::vector & gnd_grids_list, PointsCentroid & gnd_cluster); void classifyPointCloud( std::vector & in_radial_ordered_clouds, pcl::PointIndices & out_no_ground_indices); - + void classifyPointCloudGridScan( + std::vector & in_radial_ordered_clouds, + pcl::PointIndices & out_no_ground_indices); /*! * Returns the resulting complementary PointCloud, one with the points kept * and the other removed as indicated in the indices diff --git a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp index 77738a831197b..1ea0e47223bd7 100644 --- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp @@ -37,14 +37,30 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & { // set initial parameters { + low_priority_region_x_ = static_cast(declare_parameter("low_priority_region_x", -20.0f)); + detection_range_z_max_ = static_cast(declare_parameter("detection_range_z_max", 2.5f)); + center_pcl_shift_ = static_cast(declare_parameter("center_pcl_shift", 0.0)); + non_ground_height_threshold_ = + static_cast(declare_parameter("non_ground_height_threshold", 0.20)); + grid_mode_switch_radius_ = + static_cast(declare_parameter("grid_mode_switch_radius", 20.0)); + + grid_size_m_ = static_cast(declare_parameter("grid_size_m", 0.5)); + gnd_grid_buffer_size_ = static_cast(declare_parameter("gnd_grid_buffer_size", 4)); + elevation_grid_mode_ = static_cast(declare_parameter("elevation_grid_mode", true)); global_slope_max_angle_rad_ = deg2rad(declare_parameter("global_slope_max_angle_deg", 8.0)); - local_slope_max_angle_rad_ = deg2rad(declare_parameter("local_slope_max_angle_deg", 6.0)); + local_slope_max_angle_rad_ = deg2rad(declare_parameter("local_slope_max_angle_deg", 10.0)); radial_divider_angle_rad_ = deg2rad(declare_parameter("radial_divider_angle_deg", 1.0)); split_points_distance_tolerance_ = declare_parameter("split_points_distance_tolerance", 0.2); split_height_distance_ = declare_parameter("split_height_distance", 0.2); use_virtual_ground_point_ = declare_parameter("use_virtual_ground_point", true); radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_); vehicle_info_ = VehicleInfoUtil(*this).getVehicleInfo(); + + grid_mode_switch_grid_id_ = + grid_mode_switch_radius_ / grid_size_m_; // changing the mode of grid division + virtual_lidar_z_ = vehicle_info_.vehicle_height_m; + grid_mode_switch_angle_rad_ = std::atan2(grid_mode_switch_radius_, virtual_lidar_z_); } using std::placeholders::_1; @@ -52,6 +68,63 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & std::bind(&ScanGroundFilterComponent::onParameter, this, _1)); } +void ScanGroundFilterComponent::convertPointcloudGridScan( + const pcl::PointCloud::Ptr in_cloud, + std::vector & out_radial_ordered_points) +{ + out_radial_ordered_points.resize(radial_dividers_num_); + PointRef current_point; + uint16_t back_steps_num = 1; + + grid_size_rad_ = + normalizeRadian(std::atan2(grid_mode_switch_radius_ + grid_size_m_, virtual_lidar_z_)) - + normalizeRadian(std::atan2(grid_mode_switch_radius_, virtual_lidar_z_)); + for (size_t i = 0; i < in_cloud->points.size(); ++i) { + auto x{ + in_cloud->points[i].x - vehicle_info_.wheel_base_m / 2.0f - + center_pcl_shift_}; // base on front wheel center + // auto y{in_cloud->points[i].y}; + auto radius{static_cast(std::hypot(x, in_cloud->points[i].y))}; + auto theta{normalizeRadian(std::atan2(x, in_cloud->points[i].y), 0.0)}; + + // divide by vertical angle + auto gamma{normalizeRadian(std::atan2(radius, virtual_lidar_z_), 0.0f)}; + auto radial_div{ + static_cast(std::floor(normalizeDegree(theta / radial_divider_angle_rad_, 0.0)))}; + uint16_t grid_id = 0; + float curr_grid_size = 0.0f; + if (radius <= grid_mode_switch_radius_) { + grid_id = static_cast(radius / grid_size_m_); + curr_grid_size = grid_size_m_; + } else { + grid_id = grid_mode_switch_grid_id_ + (gamma - grid_mode_switch_angle_rad_) / grid_size_rad_; + if (grid_id <= grid_mode_switch_grid_id_ + back_steps_num) { + curr_grid_size = grid_size_m_; + } else { + curr_grid_size = std::tan(gamma) - std::tan(gamma - grid_size_rad_); + curr_grid_size *= virtual_lidar_z_; + } + } + current_point.grid_id = grid_id; + current_point.grid_size = curr_grid_size; + current_point.radius = radius; + current_point.theta = theta; + current_point.radial_div = radial_div; + current_point.point_state = PointLabel::INIT; + current_point.orig_index = i; + current_point.orig_point = &in_cloud->points[i]; + + // radial divisions + out_radial_ordered_points[radial_div].emplace_back(current_point); + } + + // sort by distance + for (size_t i = 0; i < radial_dividers_num_; ++i) { + std::sort( + out_radial_ordered_points[i].begin(), out_radial_ordered_points[i].end(), + [](const PointRef & a, const PointRef & b) { return a.radius < b.radius; }); + } +} void ScanGroundFilterComponent::convertPointcloud( const pcl::PointCloud::Ptr in_cloud, std::vector & out_radial_ordered_points) @@ -91,6 +164,233 @@ void ScanGroundFilterComponent::calcVirtualGroundOrigin(pcl::PointXYZ & point) point.z = 0; } +void ScanGroundFilterComponent::initializeFirstGndGrids( + const float h, const float r, const uint16_t id, std::vector & gnd_grids) +{ + GridCenter curr_gnd_grid; + for (int ind_grid = id - 1 - gnd_grid_buffer_size_; ind_grid < id - 1; ind_grid++) { + float ind_gnd_z = ind_grid - id + 1 + gnd_grid_buffer_size_; + ind_gnd_z *= h / static_cast(gnd_grid_buffer_size_); + + float ind_gnd_radius = ind_grid - id + 1 + gnd_grid_buffer_size_; + ind_gnd_radius *= r / static_cast(gnd_grid_buffer_size_); + + curr_gnd_grid.radius = ind_gnd_radius; + curr_gnd_grid.avg_height = ind_gnd_z; + curr_gnd_grid.max_height = ind_gnd_z; + curr_gnd_grid.grid_id = ind_grid; + gnd_grids.push_back(curr_gnd_grid); + } +} + +void ScanGroundFilterComponent::checkContinuousGndGrid( + PointRef & p, const std::vector & gnd_grids_list, PointsCentroid & gnd_cluster) +{ + float next_gnd_z = 0.0f; + float curr_gnd_slope_rad = 0.0f; + float gnd_buff_z_mean = 0.0f; + float gnd_buff_z_max = 0.0f; + float gnd_buff_radius = 0.0f; + + for (auto it = gnd_grids_list.end() - gnd_grid_buffer_size_ - 1; it < gnd_grids_list.end() - 1; + it++) { + gnd_buff_radius += it->radius; + gnd_buff_z_mean += it->avg_height; + gnd_buff_z_max += it->max_height; + } + + gnd_buff_radius /= static_cast(gnd_grid_buffer_size_ - 1); + gnd_buff_z_max /= static_cast(gnd_grid_buffer_size_ - 1); + gnd_buff_z_mean /= static_cast(gnd_grid_buffer_size_ - 1); + + float tmp_delta_mean_z = gnd_grids_list.back().avg_height - gnd_buff_z_mean; + float tmp_delta_radius = gnd_grids_list.back().radius - gnd_buff_radius; + + curr_gnd_slope_rad = std::atan(tmp_delta_mean_z / tmp_delta_radius); + curr_gnd_slope_rad = curr_gnd_slope_rad < -global_slope_max_angle_rad_ + ? -global_slope_max_angle_rad_ + : curr_gnd_slope_rad; + curr_gnd_slope_rad = curr_gnd_slope_rad > global_slope_max_angle_rad_ + ? global_slope_max_angle_rad_ + : curr_gnd_slope_rad; + + next_gnd_z = std::tan(curr_gnd_slope_rad) * (p.radius - gnd_buff_radius) + gnd_buff_z_mean; + + float gnd_z_local_thresh = std::tan(DEG2RAD(5.0)) * (p.radius - gnd_grids_list.back().radius); + + tmp_delta_mean_z = p.orig_point->z - (gnd_grids_list.end() - 2)->avg_height; + tmp_delta_radius = p.radius - (gnd_grids_list.end() - 2)->radius; + float local_slope = std::atan(tmp_delta_mean_z / tmp_delta_radius); + if ( + abs(p.orig_point->z - next_gnd_z) <= non_ground_height_threshold_ + gnd_z_local_thresh || + abs(local_slope) <= local_slope_max_angle_rad_) { + gnd_cluster.addPoint(p.radius, p.orig_point->z); + p.point_state = PointLabel::GROUND; + } else if (p.orig_point->z - next_gnd_z > non_ground_height_threshold_ + gnd_z_local_thresh) { + p.point_state = PointLabel::NON_GROUND; + } +} +void ScanGroundFilterComponent::checkDiscontinuousGndGrid( + PointRef & p, const std::vector & gnd_grids_list, PointsCentroid & gnd_cluster) +{ + float tmp_delta_max_z = p.orig_point->z - gnd_grids_list.back().max_height; + float tmp_delta_avg_z = p.orig_point->z - gnd_grids_list.back().avg_height; + float tmp_delta_radius = p.radius - gnd_grids_list.back().radius; + float local_slope = std::atan(tmp_delta_avg_z / tmp_delta_radius); + + if ( + abs(local_slope) < local_slope_max_angle_rad_ || + abs(tmp_delta_avg_z) < non_ground_height_threshold_ || + abs(tmp_delta_max_z) < non_ground_height_threshold_) { + gnd_cluster.addPoint(p.radius, p.orig_point->z); + p.point_state = PointLabel::GROUND; + } else if (local_slope > global_slope_max_angle_rad_) { + p.point_state = PointLabel::NON_GROUND; + } +} + +void ScanGroundFilterComponent::checkBreakGndGrid( + PointRef & p, const std::vector & gnd_grids_list, PointsCentroid & gnd_cluster) +{ + float tmp_delta_avg_z = p.orig_point->z - gnd_grids_list.back().avg_height; + float tmp_delta_radius = p.radius - gnd_grids_list.back().radius; + float local_slope = std::atan(tmp_delta_avg_z / tmp_delta_radius); + if (abs(local_slope) < global_slope_max_angle_rad_) { + gnd_cluster.addPoint(p.radius, p.orig_point->z); + p.point_state = PointLabel::GROUND; + } else if (local_slope > global_slope_max_angle_rad_) { + p.point_state = PointLabel::NON_GROUND; + } +} +void ScanGroundFilterComponent::classifyPointCloudGridScan( + std::vector & in_radial_ordered_clouds, + pcl::PointIndices & out_no_ground_indices) +{ + out_no_ground_indices.indices.clear(); + for (size_t i = 0; i < in_radial_ordered_clouds.size(); i++) { + PointsCentroid ground_cluster; + ground_cluster.initialize(); + std::vector gnd_grids; + GridCenter curr_gnd_grid; + + // check empty ray + if (in_radial_ordered_clouds[i].size() == 0) { + continue; + } + + // check the first point in ray + auto * p = &in_radial_ordered_clouds[i][0]; + PointRef * prev_p; + prev_p = &in_radial_ordered_clouds[i][0]; // for checking the distance to prev point + + bool initialized_first_gnd_grid = false; + bool prev_list_init = false; + + for (size_t j = 0; j < in_radial_ordered_clouds[i].size(); j++) { + p = &in_radial_ordered_clouds[i][j]; + float global_slope_p = std::atan(p->orig_point->z / p->radius); + float non_ground_height_threshold_local = non_ground_height_threshold_; + if (p->orig_point->x < low_priority_region_x_) { + non_ground_height_threshold_local = + non_ground_height_threshold_ * abs(p->orig_point->x / low_priority_region_x_); + } + // classify first grid's point cloud + if ( + !initialized_first_gnd_grid && global_slope_p >= global_slope_max_angle_rad_ && + p->orig_point->z > non_ground_height_threshold_local) { + out_no_ground_indices.indices.push_back(p->orig_index); + p->point_state = PointLabel::NON_GROUND; + prev_p = p; + continue; + } + + if ( + !initialized_first_gnd_grid && abs(global_slope_p) < global_slope_max_angle_rad_ && + abs(p->orig_point->z) < non_ground_height_threshold_local) { + ground_cluster.addPoint(p->radius, p->orig_point->z); + p->point_state = PointLabel::GROUND; + initialized_first_gnd_grid = static_cast(p->grid_id - prev_p->grid_id); + prev_p = p; + continue; + } + + if ( + !initialized_first_gnd_grid && global_slope_p < -global_slope_max_angle_rad_ && + p->orig_point->z < -non_ground_height_threshold_local) { + prev_p = p; + continue; + } + + // initialize lists of previous gnd grids + if (prev_list_init == false && initialized_first_gnd_grid == true) { + float h = ground_cluster.getAverageHeight(); + float r = ground_cluster.getAverageRadius(); + initializeFirstGndGrids(h, r, p->grid_id, gnd_grids); + prev_list_init = true; + } + + if (prev_list_init == false && initialized_first_gnd_grid == false) { + // assume first gnd grid is zero + initializeFirstGndGrids(0.0f, p->radius, p->grid_id, gnd_grids); + prev_list_init = true; + } + + // move to new grid + if (p->grid_id > prev_p->grid_id && ground_cluster.getAverageRadius() > 0.0) { + // check if the prev grid have ground point cloud + curr_gnd_grid.radius = ground_cluster.getAverageRadius(); + curr_gnd_grid.avg_height = ground_cluster.getAverageHeight(); + curr_gnd_grid.max_height = ground_cluster.getMaxHeight(); + curr_gnd_grid.grid_id = prev_p->grid_id; + gnd_grids.push_back(curr_gnd_grid); + ground_cluster.initialize(); + } + // classify + if (p->orig_point->z - gnd_grids.back().avg_height > detection_range_z_max_) { + p->point_state = PointLabel::OUT_OF_RANGE; + prev_p = p; + continue; + } + float points_xy_distance = std::hypot( + p->orig_point->x - prev_p->orig_point->x, p->orig_point->y - prev_p->orig_point->y); + if ( + prev_p->point_state == PointLabel::NON_GROUND && + points_xy_distance < split_points_distance_tolerance_ && + p->orig_point->z > prev_p->orig_point->z) { + p->point_state = PointLabel::NON_GROUND; + out_no_ground_indices.indices.push_back(p->orig_index); + prev_p = p; + continue; + } + + if (global_slope_p > global_slope_max_angle_rad_) { + out_no_ground_indices.indices.push_back(p->orig_index); + prev_p = p; + continue; + } + // gnd grid is continuous, the last gnd grid is close + uint16_t next_gnd_grid_id_thresh = (gnd_grids.end() - gnd_grid_buffer_size_)->grid_id + + gnd_grid_buffer_size_ + gnd_grid_continual_thresh_; + if ( + p->grid_id < next_gnd_grid_id_thresh && + p->radius - gnd_grids.back().radius < gnd_grid_continual_thresh_ * p->grid_size) { + checkContinuousGndGrid(*p, gnd_grids, ground_cluster); + + } else if ( + p->radius - gnd_grids.back().radius < gnd_grid_continual_thresh_ * p->grid_size || + p->radius < grid_mode_switch_radius_ * 2.0f) { + checkDiscontinuousGndGrid(*p, gnd_grids, ground_cluster); + } else { + checkBreakGndGrid(*p, gnd_grids, ground_cluster); + } + if (p->point_state == PointLabel::NON_GROUND) { + out_no_ground_indices.indices.push_back(p->orig_index); + } + prev_p = p; + } + } +} + void ScanGroundFilterComponent::classifyPointCloud( std::vector & in_radial_ordered_clouds, pcl::PointIndices & out_no_ground_indices) @@ -224,13 +524,17 @@ void ScanGroundFilterComponent::filter( std::vector radial_ordered_points; - convertPointcloud(current_sensor_cloud_ptr, radial_ordered_points); - pcl::PointIndices no_ground_indices; pcl::PointCloud::Ptr no_ground_cloud_ptr(new pcl::PointCloud); no_ground_cloud_ptr->points.reserve(current_sensor_cloud_ptr->points.size()); - classifyPointCloud(radial_ordered_points, no_ground_indices); + if (elevation_grid_mode_) { + convertPointcloudGridScan(current_sensor_cloud_ptr, radial_ordered_points); + classifyPointCloudGridScan(radial_ordered_points, no_ground_indices); + } else { + convertPointcloud(current_sensor_cloud_ptr, radial_ordered_points); + classifyPointCloud(radial_ordered_points, no_ground_indices); + } extractObjectPoints(current_sensor_cloud_ptr, no_ground_indices, no_ground_cloud_ptr); From 5549db4fac767ece528169b2b867aff93153a6b6 Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Thu, 6 Oct 2022 11:33:09 +0900 Subject: [PATCH 14/28] refactor(perception_utils): refactor perception_utils (#1954) * add inline Signed-off-by: scepter914 * divide file Signed-off-by: scepter914 * add matching.hpp Signed-off-by: scepter914 * add transform.hpp Signed-off-by: scepter914 * delete from perception_util.hpp Signed-off-by: scepter914 * fix include file Signed-off-by: scepter914 * fix include file Signed-off-by: scepter914 * fix CmakeLists Signed-off-by: scepter914 * divide test files Signed-off-by: scepter914 * fix include files Signed-off-by: scepter914 * fix file name Signed-off-by: scepter914 * fix test name Signed-off-by: scepter914 * fix copyright Signed-off-by: scepter914 * fix input arg of object classification function Signed-off-by: scepter914 * add unit label function to classification library Signed-off-by: scepter914 * fix compile error Signed-off-by: scepter914 * ci(pre-commit): autofix * fix include path Signed-off-by: scepter914 * delete inline from template function Signed-off-by: scepter914 * delete inline function Signed-off-by: scepter914 * add TODO Signed-off-by: scepter914 * change to build function Signed-off-by: scepter914 * apply pre-commit Signed-off-by: scepter914 * fix conflict Signed-off-by: scepter914 * add getConvexShapeArea function Signed-off-by: scepter914 * fix unnamed namespace Signed-off-by: scepter914 Signed-off-by: scepter914 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- common/perception_utils/CMakeLists.txt | 2 +- .../include/perception_utils/conversion.hpp | 34 ++ .../include/perception_utils/matching.hpp | 151 +++++++++ .../object_classification.hpp | 51 ++- .../perception_utils/perception_utils.hpp | 215 +------------ .../perception_utils/predicted_path_utils.hpp | 7 - .../include/perception_utils/transform.hpp | 85 +++++ .../{perception_utils.cpp => conversion.cpp} | 37 +-- .../src/predicted_path_utils.cpp | 6 + ...rception_utils.cpp => test_conversion.cpp} | 303 +----------------- .../test/src/test_geometry.cpp | 2 +- .../test/src/test_matching.cpp | 286 +++++++++++++++++ .../test/src/test_object_classification.cpp | 63 ++++ .../test/src/test_predicted_path_utils.cpp | 2 +- 14 files changed, 697 insertions(+), 547 deletions(-) create mode 100644 common/perception_utils/include/perception_utils/conversion.hpp create mode 100644 common/perception_utils/include/perception_utils/matching.hpp create mode 100644 common/perception_utils/include/perception_utils/transform.hpp rename common/perception_utils/src/{perception_utils.cpp => conversion.cpp} (65%) rename common/perception_utils/test/src/{test_perception_utils.cpp => test_conversion.cpp} (51%) create mode 100644 common/perception_utils/test/src/test_matching.cpp create mode 100644 common/perception_utils/test/src/test_object_classification.cpp diff --git a/common/perception_utils/CMakeLists.txt b/common/perception_utils/CMakeLists.txt index b6d9376a790ae..338874a41a3f7 100644 --- a/common/perception_utils/CMakeLists.txt +++ b/common/perception_utils/CMakeLists.txt @@ -7,8 +7,8 @@ autoware_package() find_package(Boost REQUIRED) ament_auto_add_library(perception_utils SHARED - src/perception_utils.cpp src/predicted_path_utils.cpp + src/conversion.cpp ) if(BUILD_TESTING) diff --git a/common/perception_utils/include/perception_utils/conversion.hpp b/common/perception_utils/include/perception_utils/conversion.hpp new file mode 100644 index 0000000000000..1497114eee532 --- /dev/null +++ b/common/perception_utils/include/perception_utils/conversion.hpp @@ -0,0 +1,34 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PERCEPTION_UTILS__CONVERSION_HPP_ +#define PERCEPTION_UTILS__CONVERSION_HPP_ + +#include "autoware_auto_perception_msgs/msg/detected_objects.hpp" +#include "autoware_auto_perception_msgs/msg/tracked_objects.hpp" + +namespace perception_utils +{ +using autoware_auto_perception_msgs::msg::DetectedObject; +using autoware_auto_perception_msgs::msg::DetectedObjects; +using autoware_auto_perception_msgs::msg::TrackedObject; +using autoware_auto_perception_msgs::msg::TrackedObjects; + +DetectedObject toDetectedObject(const TrackedObject & tracked_object); +DetectedObjects toDetectedObjects(const TrackedObjects & tracked_objects); +TrackedObject toTrackedObject(const DetectedObject & detected_object); +TrackedObjects toTrackedObjects(const DetectedObjects & detected_objects); +} // namespace perception_utils + +#endif // PERCEPTION_UTILS__CONVERSION_HPP_ diff --git a/common/perception_utils/include/perception_utils/matching.hpp b/common/perception_utils/include/perception_utils/matching.hpp new file mode 100644 index 0000000000000..e8aac78e32cb2 --- /dev/null +++ b/common/perception_utils/include/perception_utils/matching.hpp @@ -0,0 +1,151 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PERCEPTION_UTILS__MATCHING_HPP_ +#define PERCEPTION_UTILS__MATCHING_HPP_ + +#include "perception_utils/geometry.hpp" +#include "tier4_autoware_utils/geometry/boost_geometry.hpp" +#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" + +#include + +#include +#include + +namespace perception_utils +{ +inline double getConvexShapeArea( + const tier4_autoware_utils::Polygon2d & source_polygon, + const tier4_autoware_utils::Polygon2d & target_polygon) +{ + boost::geometry::model::multi_polygon union_polygons; + boost::geometry::union_(source_polygon, target_polygon, union_polygons); + + tier4_autoware_utils::Polygon2d hull; + boost::geometry::convex_hull(union_polygons, hull); + return boost::geometry::area(hull); +} + +template +double get2dIoU(const T1 source_object, const T2 target_object) +{ + const auto & source_pose = getPose(source_object); + const auto & target_pose = getPose(target_object); + + const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_pose, source_object.shape); + const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_pose, target_object.shape); + + std::vector union_polygons; + std::vector intersection_polygons; + boost::geometry::union_(source_polygon, target_polygon, union_polygons); + boost::geometry::intersection(source_polygon, target_polygon, intersection_polygons); + + double intersection_area = 0.0; + double union_area = 0.0; + for (const auto & intersection_polygon : intersection_polygons) { + intersection_area += boost::geometry::area(intersection_polygon); + } + if (intersection_area == 0.0) return 0.0; + + for (const auto & union_polygon : union_polygons) { + union_area += boost::geometry::area(union_polygon); + } + + const double iou = union_area < 0.01 ? 0.0 : std::min(1.0, intersection_area / union_area); + return iou; +} + +template +double get2dGeneralizedIoU(const T1 & source_object, const T2 & target_object) +{ + const auto & source_pose = getPose(source_object); + const auto & target_pose = getPose(target_object); + + const auto & source_polygon = tier4_autoware_utils::toPolygon2d(source_pose, source_object.shape); + const auto & target_polygon = tier4_autoware_utils::toPolygon2d(target_pose, target_object.shape); + + std::vector union_polygons; + std::vector intersection_polygons; + boost::geometry::union_(source_polygon, target_polygon, union_polygons); + boost::geometry::intersection(source_polygon, target_polygon, intersection_polygons); + + double intersection_area = 0.0; + double union_area = 0.0; + for (const auto & intersection_polygon : intersection_polygons) { + intersection_area += boost::geometry::area(intersection_polygon); + } + + for (const auto & union_polygon : union_polygons) { + union_area += boost::geometry::area(union_polygon); + } + + const double iou = union_area < 0.01 ? 0.0 : std::min(1.0, intersection_area / union_area); + const double convex_shape_area = getConvexShapeArea(source_polygon, target_polygon); + return iou - (convex_shape_area - union_area) / convex_shape_area; +} + +template +double get2dPrecision(const T1 source_object, const T2 target_object) +{ + const auto & source_pose = getPose(source_object); + const auto & target_pose = getPose(target_object); + + const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_pose, source_object.shape); + const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_pose, target_object.shape); + + std::vector intersection_polygons; + boost::geometry::intersection(source_polygon, target_polygon, intersection_polygons); + + double intersection_area = 0.0; + double source_area = 0.0; + for (const auto & intersection_polygon : intersection_polygons) { + intersection_area += boost::geometry::area(intersection_polygon); + } + if (intersection_area == 0.0) return 0.0; + + source_area = boost::geometry::area(source_polygon); + + const double precision = std::min(1.0, intersection_area / source_area); + return precision; +} + +template +double get2dRecall(const T1 source_object, const T2 target_object) +{ + const auto & source_pose = getPose(source_object); + const auto & target_pose = getPose(target_object); + + const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_pose, source_object.shape); + const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_pose, target_object.shape); + + std::vector intersection_polygons; + boost::geometry::intersection(source_polygon, target_polygon, intersection_polygons); + + double intersection_area = 0.0; + double target_area = 0.0; + for (const auto & intersection_polygon : intersection_polygons) { + intersection_area += boost::geometry::area(intersection_polygon); + } + if (intersection_area == 0.0) return 0.0; + + target_area += boost::geometry::area(target_polygon); + + const double recall = std::min(1.0, intersection_area / target_area); + return recall; +} + +} // namespace perception_utils + +#endif // PERCEPTION_UTILS__MATCHING_HPP_ diff --git a/common/perception_utils/include/perception_utils/object_classification.hpp b/common/perception_utils/include/perception_utils/object_classification.hpp index 841466c6f8db5..a73eac253b17d 100644 --- a/common/perception_utils/include/perception_utils/object_classification.hpp +++ b/common/perception_utils/include/perception_utils/object_classification.hpp @@ -17,11 +17,28 @@ #include "autoware_auto_perception_msgs/msg/object_classification.hpp" +#include + namespace perception_utils { using autoware_auto_perception_msgs::msg::ObjectClassification; -bool isVehicle(const uint8_t object_classification) +inline std::uint8_t getHighestProbLabel( + const std::vector & object_classifications) +{ + std::uint8_t label = ObjectClassification::UNKNOWN; + float highest_prob = 0.0; + // TODO(Satoshi Tanaka): It might be simple if you use STL or range-v3. + for (const auto & object_classification : object_classifications) { + if (highest_prob < object_classification.probability) { + highest_prob = object_classification.probability; + label = object_classification.label; + } + } + return label; +} + +inline bool isVehicle(const uint8_t object_classification) { return object_classification == ObjectClassification::BICYCLE || object_classification == ObjectClassification::BUS || @@ -31,7 +48,18 @@ bool isVehicle(const uint8_t object_classification) object_classification == ObjectClassification::TRUCK; } -bool isCarLikeVehicle(const uint8_t object_classification) +inline bool isVehicle(const std::vector & object_classifications) +{ + auto highest_prob_classification = getHighestProbLabel(object_classifications); + return highest_prob_classification == ObjectClassification::BICYCLE || + highest_prob_classification == ObjectClassification::BUS || + highest_prob_classification == ObjectClassification::CAR || + highest_prob_classification == ObjectClassification::MOTORCYCLE || + highest_prob_classification == ObjectClassification::TRAILER || + highest_prob_classification == ObjectClassification::TRUCK; +} + +inline bool isCarLikeVehicle(const uint8_t object_classification) { return object_classification == ObjectClassification::BUS || object_classification == ObjectClassification::CAR || @@ -39,12 +67,29 @@ bool isCarLikeVehicle(const uint8_t object_classification) object_classification == ObjectClassification::TRUCK; } -bool isLargeVehicle(const uint8_t object_classification) +inline bool isCarLikeVehicle(const std::vector & object_classifications) +{ + auto highest_prob_classification = getHighestProbLabel(object_classifications); + return highest_prob_classification == ObjectClassification::BUS || + highest_prob_classification == ObjectClassification::CAR || + highest_prob_classification == ObjectClassification::TRAILER || + highest_prob_classification == ObjectClassification::TRUCK; +} + +inline bool isLargeVehicle(const uint8_t object_classification) { return object_classification == ObjectClassification::BUS || object_classification == ObjectClassification::TRAILER || object_classification == ObjectClassification::TRUCK; } + +inline bool isLargeVehicle(const std::vector & object_classifications) +{ + auto highest_prob_classification = getHighestProbLabel(object_classifications); + return highest_prob_classification == ObjectClassification::BUS || + highest_prob_classification == ObjectClassification::TRAILER || + highest_prob_classification == ObjectClassification::TRUCK; +} } // namespace perception_utils #endif // PERCEPTION_UTILS__OBJECT_CLASSIFICATION_HPP_ diff --git a/common/perception_utils/include/perception_utils/perception_utils.hpp b/common/perception_utils/include/perception_utils/perception_utils.hpp index eec280ce6c6c8..352ade44a783e 100644 --- a/common/perception_utils/include/perception_utils/perception_utils.hpp +++ b/common/perception_utils/include/perception_utils/perception_utils.hpp @@ -15,216 +15,11 @@ #ifndef PERCEPTION_UTILS__PERCEPTION_UTILS_HPP_ #define PERCEPTION_UTILS__PERCEPTION_UTILS_HPP_ +#include "perception_utils/conversion.hpp" #include "perception_utils/geometry.hpp" -#include "tier4_autoware_utils/geometry/boost_geometry.hpp" -#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" +#include "perception_utils/matching.hpp" +#include "perception_utils/object_classification.hpp" +#include "perception_utils/predicted_path_utils.hpp" +#include "perception_utils/transform.hpp" -#include "autoware_auto_perception_msgs/msg/detected_objects.hpp" -#include "autoware_auto_perception_msgs/msg/tracked_objects.hpp" -#include "geometry_msgs/msg/transform.hpp" - -#include - -#include -#include - -#include -#include -#include -#include -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - -namespace -{ -[[maybe_unused]] boost::optional getTransform( - const tf2_ros::Buffer & tf_buffer, const std::string & source_frame_id, - const std::string & target_frame_id, const rclcpp::Time & time) -{ - try { - geometry_msgs::msg::TransformStamped self_transform_stamped; - self_transform_stamped = tf_buffer.lookupTransform( - target_frame_id, source_frame_id, time, rclcpp::Duration::from_seconds(0.5)); - return self_transform_stamped.transform; - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM(rclcpp::get_logger("perception_utils"), ex.what()); - return boost::none; - } -} - -inline double getConvexShapeArea( - const tier4_autoware_utils::Polygon2d & source_polygon, - const tier4_autoware_utils::Polygon2d & target_polygon) -{ - boost::geometry::model::multi_polygon union_polygons; - boost::geometry::union_(source_polygon, target_polygon, union_polygons); - - tier4_autoware_utils::Polygon2d hull; - boost::geometry::convex_hull(union_polygons, hull); - return boost::geometry::area(hull); -} - -} // namespace - -namespace perception_utils -{ -std::uint8_t getHighestProbLabel( - const std::vector & classification); - -autoware_auto_perception_msgs::msg::DetectedObject toDetectedObject( - const autoware_auto_perception_msgs::msg::TrackedObject & tracked_object); - -autoware_auto_perception_msgs::msg::DetectedObjects toDetectedObjects( - const autoware_auto_perception_msgs::msg::TrackedObjects & tracked_objects); - -autoware_auto_perception_msgs::msg::TrackedObject toTrackedObject( - const autoware_auto_perception_msgs::msg::DetectedObject & detected_object); - -autoware_auto_perception_msgs::msg::TrackedObjects toTrackedObjects( - const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects); - -template -inline double get2dIoU(const T1 source_object, const T2 target_object) -{ - const auto & source_pose = getPose(source_object); - const auto & target_pose = getPose(target_object); - - const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_pose, source_object.shape); - const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_pose, target_object.shape); - - std::vector union_polygons; - std::vector intersection_polygons; - boost::geometry::union_(source_polygon, target_polygon, union_polygons); - boost::geometry::intersection(source_polygon, target_polygon, intersection_polygons); - - double intersection_area = 0.0; - double union_area = 0.0; - for (const auto & intersection_polygon : intersection_polygons) { - intersection_area += boost::geometry::area(intersection_polygon); - } - if (intersection_area == 0.0) return 0.0; - - for (const auto & union_polygon : union_polygons) { - union_area += boost::geometry::area(union_polygon); - } - - const double iou = union_area < 0.01 ? 0.0 : std::min(1.0, intersection_area / union_area); - return iou; -} - -template -inline double get2dGeneralizedIoU(const T1 & source_object, const T2 & target_object) -{ - const auto & source_pose = getPose(source_object); - const auto & target_pose = getPose(target_object); - - const auto & source_polygon = tier4_autoware_utils::toPolygon2d(source_pose, source_object.shape); - const auto & target_polygon = tier4_autoware_utils::toPolygon2d(target_pose, target_object.shape); - - std::vector union_polygons; - std::vector intersection_polygons; - boost::geometry::union_(source_polygon, target_polygon, union_polygons); - boost::geometry::intersection(source_polygon, target_polygon, intersection_polygons); - - double intersection_area = 0.0; - double union_area = 0.0; - for (const auto & intersection_polygon : intersection_polygons) { - intersection_area += boost::geometry::area(intersection_polygon); - } - - for (const auto & union_polygon : union_polygons) { - union_area += boost::geometry::area(union_polygon); - } - - const double iou = union_area < 0.01 ? 0.0 : std::min(1.0, intersection_area / union_area); - const double convex_shape_area = getConvexShapeArea(source_polygon, target_polygon); - return iou - (convex_shape_area - union_area) / convex_shape_area; -} - -template -inline double get2dPrecision(const T1 source_object, const T2 target_object) -{ - const auto & source_pose = getPose(source_object); - const auto & target_pose = getPose(target_object); - - const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_pose, source_object.shape); - const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_pose, target_object.shape); - - std::vector intersection_polygons; - boost::geometry::intersection(source_polygon, target_polygon, intersection_polygons); - - double intersection_area = 0.0; - double source_area = 0.0; - for (const auto & intersection_polygon : intersection_polygons) { - intersection_area += boost::geometry::area(intersection_polygon); - } - if (intersection_area == 0.0) return 0.0; - - source_area = boost::geometry::area(source_polygon); - - const double precision = std::min(1.0, intersection_area / source_area); - return precision; -} - -template -inline double get2dRecall(const T1 source_object, const T2 target_object) -{ - const auto & source_pose = getPose(source_object); - const auto & target_pose = getPose(target_object); - - const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_pose, source_object.shape); - const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_pose, target_object.shape); - - std::vector intersection_polygons; - boost::geometry::intersection(source_polygon, target_polygon, intersection_polygons); - - double intersection_area = 0.0; - double target_area = 0.0; - for (const auto & intersection_polygon : intersection_polygons) { - intersection_area += boost::geometry::area(intersection_polygon); - } - if (intersection_area == 0.0) return 0.0; - - target_area += boost::geometry::area(target_polygon); - - const double recall = std::min(1.0, intersection_area / target_area); - return recall; -} - -template -bool transformObjects( - const T & input_msg, const std::string & target_frame_id, const tf2_ros::Buffer & tf_buffer, - T & output_msg) -{ - output_msg = input_msg; - - // transform to world coordinate - if (input_msg.header.frame_id != target_frame_id) { - output_msg.header.frame_id = target_frame_id; - tf2::Transform tf_target2objects_world; - tf2::Transform tf_target2objects; - tf2::Transform tf_objects_world2objects; - { - const auto ros_target2objects_world = - getTransform(tf_buffer, input_msg.header.frame_id, target_frame_id, input_msg.header.stamp); - if (!ros_target2objects_world) { - return false; - } - tf2::fromMsg(*ros_target2objects_world, tf_target2objects_world); - } - for (auto & object : output_msg.objects) { - tf2::fromMsg(object.kinematics.pose_with_covariance.pose, tf_objects_world2objects); - tf_target2objects = tf_target2objects_world * tf_objects_world2objects; - tf2::toMsg(tf_target2objects, object.kinematics.pose_with_covariance.pose); - // TODO(yukkysaito) transform covariance - } - } - return true; -} -} // namespace perception_utils #endif // PERCEPTION_UTILS__PERCEPTION_UTILS_HPP_ diff --git a/common/perception_utils/include/perception_utils/predicted_path_utils.hpp b/common/perception_utils/include/perception_utils/predicted_path_utils.hpp index 4e5593bff3412..c02282f9efeea 100644 --- a/common/perception_utils/include/perception_utils/predicted_path_utils.hpp +++ b/common/perception_utils/include/perception_utils/predicted_path_utils.hpp @@ -15,20 +15,13 @@ #ifndef PERCEPTION_UTILS__PREDICTED_PATH_UTILS_HPP_ #define PERCEPTION_UTILS__PREDICTED_PATH_UTILS_HPP_ -#include "interpolation/linear_interpolation.hpp" -#include "interpolation/spherical_linear_interpolation.hpp" -#include "interpolation/spline_interpolation.hpp" -#include "perception_utils/geometry.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" -#include - #include "autoware_auto_perception_msgs/msg/predicted_path.hpp" #include #include -#include #include namespace perception_utils diff --git a/common/perception_utils/include/perception_utils/transform.hpp b/common/perception_utils/include/perception_utils/transform.hpp new file mode 100644 index 0000000000000..54af7c04a006e --- /dev/null +++ b/common/perception_utils/include/perception_utils/transform.hpp @@ -0,0 +1,85 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PERCEPTION_UTILS__TRANSFORM_HPP_ +#define PERCEPTION_UTILS__TRANSFORM_HPP_ + +#include "geometry_msgs/msg/transform.hpp" + +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include "boost/optional.hpp" + +#include + +namespace +{ +[[maybe_unused]] boost::optional getTransform( + const tf2_ros::Buffer & tf_buffer, const std::string & source_frame_id, + const std::string & target_frame_id, const rclcpp::Time & time) +{ + try { + geometry_msgs::msg::TransformStamped self_transform_stamped; + self_transform_stamped = tf_buffer.lookupTransform( + target_frame_id, source_frame_id, time, rclcpp::Duration::from_seconds(0.5)); + return self_transform_stamped.transform; + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_STREAM(rclcpp::get_logger("perception_utils"), ex.what()); + return boost::none; + } +} +} // namespace + +namespace perception_utils +{ +template +bool transformObjects( + const T & input_msg, const std::string & target_frame_id, const tf2_ros::Buffer & tf_buffer, + T & output_msg) +{ + output_msg = input_msg; + + // transform to world coordinate + if (input_msg.header.frame_id != target_frame_id) { + output_msg.header.frame_id = target_frame_id; + tf2::Transform tf_target2objects_world; + tf2::Transform tf_target2objects; + tf2::Transform tf_objects_world2objects; + { + const auto ros_target2objects_world = + getTransform(tf_buffer, input_msg.header.frame_id, target_frame_id, input_msg.header.stamp); + if (!ros_target2objects_world) { + return false; + } + tf2::fromMsg(*ros_target2objects_world, tf_target2objects_world); + } + for (auto & object : output_msg.objects) { + tf2::fromMsg(object.kinematics.pose_with_covariance.pose, tf_objects_world2objects); + tf_target2objects = tf_target2objects_world * tf_objects_world2objects; + tf2::toMsg(tf_target2objects, object.kinematics.pose_with_covariance.pose); + // TODO(yukkysaito) transform covariance + } + } + return true; +} +} // namespace perception_utils + +#endif // PERCEPTION_UTILS__TRANSFORM_HPP_ diff --git a/common/perception_utils/src/perception_utils.cpp b/common/perception_utils/src/conversion.cpp similarity index 65% rename from common/perception_utils/src/perception_utils.cpp rename to common/perception_utils/src/conversion.cpp index 2d9fa20da8458..ea42bf18739ca 100644 --- a/common/perception_utils/src/perception_utils.cpp +++ b/common/perception_utils/src/conversion.cpp @@ -12,28 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "perception_utils/perception_utils.hpp" +#include "perception_utils/conversion.hpp" namespace perception_utils { -std::uint8_t getHighestProbLabel( - const std::vector & classification) -{ - std::uint8_t label = autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN; - float highest_prob = 0.0; - for (const auto & _class : classification) { - if (highest_prob < _class.probability) { - highest_prob = _class.probability; - label = _class.label; - } - } - return label; -} +using autoware_auto_perception_msgs::msg::DetectedObject; +using autoware_auto_perception_msgs::msg::DetectedObjects; +using autoware_auto_perception_msgs::msg::TrackedObject; +using autoware_auto_perception_msgs::msg::TrackedObjects; -autoware_auto_perception_msgs::msg::DetectedObject toDetectedObject( - const autoware_auto_perception_msgs::msg::TrackedObject & tracked_object) +DetectedObject toDetectedObject(const TrackedObject & tracked_object) { - autoware_auto_perception_msgs::msg::DetectedObject detected_object; + DetectedObject detected_object; detected_object.existence_probability = tracked_object.existence_probability; detected_object.classification = tracked_object.classification; @@ -51,8 +41,7 @@ autoware_auto_perception_msgs::msg::DetectedObject toDetectedObject( return detected_object; } -autoware_auto_perception_msgs::msg::DetectedObjects toDetectedObjects( - const autoware_auto_perception_msgs::msg::TrackedObjects & tracked_objects) +DetectedObjects toDetectedObjects(const TrackedObjects & tracked_objects) { autoware_auto_perception_msgs::msg::DetectedObjects detected_objects; detected_objects.header = tracked_objects.header; @@ -63,10 +52,9 @@ autoware_auto_perception_msgs::msg::DetectedObjects toDetectedObjects( return detected_objects; } -autoware_auto_perception_msgs::msg::TrackedObject toTrackedObject( - const autoware_auto_perception_msgs::msg::DetectedObject & detected_object) +TrackedObject toTrackedObject(const DetectedObject & detected_object) { - autoware_auto_perception_msgs::msg::TrackedObject tracked_object; + TrackedObject tracked_object; tracked_object.existence_probability = detected_object.existence_probability; tracked_object.classification = detected_object.classification; @@ -81,10 +69,9 @@ autoware_auto_perception_msgs::msg::TrackedObject toTrackedObject( return tracked_object; } -autoware_auto_perception_msgs::msg::TrackedObjects toTrackedObjects( - const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects) +TrackedObjects toTrackedObjects(const DetectedObjects & detected_objects) { - autoware_auto_perception_msgs::msg::TrackedObjects tracked_objects; + TrackedObjects tracked_objects; tracked_objects.header = detected_objects.header; for (auto & detected_object : detected_objects.objects) { diff --git a/common/perception_utils/src/predicted_path_utils.cpp b/common/perception_utils/src/predicted_path_utils.cpp index 96ca74d2cb234..baabefa77aa2e 100644 --- a/common/perception_utils/src/predicted_path_utils.cpp +++ b/common/perception_utils/src/predicted_path_utils.cpp @@ -14,6 +14,12 @@ #include "perception_utils/predicted_path_utils.hpp" +#include "interpolation/linear_interpolation.hpp" +#include "interpolation/spherical_linear_interpolation.hpp" +#include "interpolation/spline_interpolation.hpp" + +#include + namespace perception_utils { boost::optional calcInterpolatedPose( diff --git a/common/perception_utils/test/src/test_perception_utils.cpp b/common/perception_utils/test/src/test_conversion.cpp similarity index 51% rename from common/perception_utils/test/src/test_perception_utils.cpp rename to common/perception_utils/test/src/test_conversion.cpp index 767ba82cc0460..95ca28ed4f110 100644 --- a/common/perception_utils/test/src/test_perception_utils.cpp +++ b/common/perception_utils/test/src/test_conversion.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 TIER IV, Inc. +// Copyright 2022 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,16 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "perception_utils/perception_utils.hpp" +#include "perception_utils/conversion.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include -using tier4_autoware_utils::Point2d; -using tier4_autoware_utils::Point3d; - -constexpr double epsilon = 1e-06; - namespace { geometry_msgs::msg::Point32 createPoint32(const double x, const double y, const double z) @@ -30,18 +25,6 @@ geometry_msgs::msg::Point32 createPoint32(const double x, const double y, const p.x = x; p.y = y; p.z = z; - - return p; -} - -geometry_msgs::msg::Pose createPose(const double x, const double y, const double yaw) -{ - geometry_msgs::msg::Pose p; - p.position.x = x; - p.position.y = y; - p.position.z = 0.0; - p.orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw); - return p; } @@ -56,40 +39,8 @@ autoware_auto_perception_msgs::msg::ObjectClassification createObjectClassificat } } // namespace -TEST(perception_utils, test_getHighestProbLabel) -{ - using autoware_auto_perception_msgs::msg::ObjectClassification; - using perception_utils::getHighestProbLabel; - - { // empty - std::vector classification; - std::uint8_t label = getHighestProbLabel(classification); - EXPECT_EQ(label, ObjectClassification::UNKNOWN); - } - - { // normal case - std::vector classification; - classification.push_back(createObjectClassification(ObjectClassification::CAR, 0.5)); - classification.push_back(createObjectClassification(ObjectClassification::TRUCK, 0.8)); - classification.push_back(createObjectClassification(ObjectClassification::BUS, 0.7)); - - std::uint8_t label = getHighestProbLabel(classification); - EXPECT_EQ(label, ObjectClassification::TRUCK); - } - - { // labels with the same probability - std::vector classification; - classification.push_back(createObjectClassification(ObjectClassification::CAR, 0.8)); - classification.push_back(createObjectClassification(ObjectClassification::TRUCK, 0.8)); - classification.push_back(createObjectClassification(ObjectClassification::BUS, 0.7)); - - std::uint8_t label = getHighestProbLabel(classification); - EXPECT_EQ(label, ObjectClassification::CAR); - } -} - // NOTE: covariance is not checked -TEST(perception_utils, test_toDetectedObject) +TEST(conversion, test_toDetectedObject) { using autoware_auto_perception_msgs::msg::ObjectClassification; using perception_utils::toDetectedObject; @@ -207,7 +158,7 @@ TEST(perception_utils, test_toDetectedObject) } // NOTE: covariance is not checked -TEST(perception_utils, test_toTrackedObject) +TEST(conversion, test_toTrackedObject) { using autoware_auto_perception_msgs::msg::ObjectClassification; using perception_utils::toTrackedObject; @@ -320,249 +271,3 @@ TEST(perception_utils, test_toTrackedObject) EXPECT_DOUBLE_EQ( detected_obj.shape.footprint.points.at(1).z, tracked_obj.shape.footprint.points.at(1).z); } - -TEST(perception_utils, test_get2dIoU) -{ - using perception_utils::get2dIoU; - const double quart_circle = 0.16237976320958225; - - { // non overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(1.5, 1.5, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double iou = get2dIoU(source_obj, target_obj); - EXPECT_DOUBLE_EQ(iou, 0.0); - } - - { // partially overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(0.5, 0.5, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double iou = get2dIoU(source_obj, target_obj); - EXPECT_NEAR(iou, quart_circle / (1.0 + quart_circle * 3), epsilon); - } - - { // fully overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double iou = get2dIoU(source_obj, target_obj); - EXPECT_DOUBLE_EQ(iou, quart_circle * 4); - } -} - -TEST(perception_utils, test_get2dGeneralizedIoU) -{ - using perception_utils::get2dGeneralizedIoU; - // TODO(Shin-kyoto): - // get2dGeneralizedIoU uses outer points of each polygon. - // But these points contain an sampling error of outer line, - // so get2dGeneralizedIoU icludes an error of about 0.03. - // Threfore, in this test, epsilon is set to 0.04. - constexpr double epsilon_giou = 4 * 1e-02; - const double quart_circle = 0.16237976320958225; - - { // non overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(1.5, 0.0, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double giou = get2dGeneralizedIoU(source_obj, target_obj); - EXPECT_NEAR(giou, (2 * quart_circle - 1) / (2 * quart_circle + 2), epsilon_giou); // not 0 - } - - { // partially overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(0.5, 0.0, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double giou = get2dGeneralizedIoU(source_obj, target_obj); - EXPECT_NEAR(giou, 2 * quart_circle / (2 * quart_circle + 1), epsilon_giou); - } - - { // fully overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double giou = get2dGeneralizedIoU(source_obj, target_obj); - EXPECT_NEAR(giou, quart_circle * 4, epsilon_giou); // giou equals iou - } -} - -TEST(perception_utils, test_get2dPrecision) -{ - using perception_utils::get2dPrecision; - const double quart_circle = 0.16237976320958225; - - { // non overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(1.5, 1.5, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double precision = get2dPrecision(source_obj, target_obj); - EXPECT_DOUBLE_EQ(precision, 0.0); - - // reverse source and target object - const double reversed_precision = get2dPrecision(target_obj, source_obj); - EXPECT_DOUBLE_EQ(reversed_precision, 0.0); - } - - { // partially overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(0.5, 0.5, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double precision = get2dPrecision(source_obj, target_obj); - EXPECT_NEAR(precision, quart_circle, epsilon); - - // reverse source and target object - const double reversed_precision = get2dPrecision(target_obj, source_obj); - EXPECT_NEAR(reversed_precision, 1 / 4.0, epsilon); - } - - { // fully overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double precision = get2dPrecision(source_obj, target_obj); - EXPECT_DOUBLE_EQ(precision, quart_circle * 4); - - // reverse source and target object - const double reversed_precision = get2dPrecision(target_obj, source_obj); - EXPECT_DOUBLE_EQ(reversed_precision, 1.0); - } -} - -TEST(perception_utils, test_get2dRecall) -{ - using perception_utils::get2dRecall; - const double quart_circle = 0.16237976320958225; - - { // non overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(1.5, 1.5, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double recall = get2dRecall(source_obj, target_obj); - EXPECT_DOUBLE_EQ(recall, 0.0); - - // reverse source and target object - const double reversed_recall = get2dRecall(target_obj, source_obj); - EXPECT_DOUBLE_EQ(reversed_recall, 0.0); - } - - { // partially overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(0.5, 0.5, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double recall = get2dRecall(source_obj, target_obj); - EXPECT_NEAR(recall, 1 / 4.0, epsilon); - - // reverse source and target object - const double reversed_recall = get2dRecall(target_obj, source_obj); - EXPECT_NEAR(reversed_recall, quart_circle, epsilon); - } - - { // fully overlapped - autoware_auto_perception_msgs::msg::DetectedObject source_obj; - source_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI); - source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; - source_obj.shape.dimensions.x = 1.0; - source_obj.shape.dimensions.y = 1.0; - - autoware_auto_perception_msgs::msg::DetectedObject target_obj; - target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); - target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; - target_obj.shape.dimensions.x = 1.0; - - const double recall = get2dRecall(source_obj, target_obj); - EXPECT_DOUBLE_EQ(recall, 1.0); - - // reverse source and target object - const double reversed_recall = get2dRecall(target_obj, source_obj); - EXPECT_DOUBLE_EQ(reversed_recall, quart_circle * 4); - } -} diff --git a/common/perception_utils/test/src/test_geometry.cpp b/common/perception_utils/test/src/test_geometry.cpp index d966b8b30aa2d..f9734f3323fbe 100644 --- a/common/perception_utils/test/src/test_geometry.cpp +++ b/common/perception_utils/test/src/test_geometry.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 TIER IV, Inc. +// Copyright 2022 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/common/perception_utils/test/src/test_matching.cpp b/common/perception_utils/test/src/test_matching.cpp new file mode 100644 index 0000000000000..bffa14eafdd00 --- /dev/null +++ b/common/perception_utils/test/src/test_matching.cpp @@ -0,0 +1,286 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "perception_utils/matching.hpp" +#include "tier4_autoware_utils/geometry/geometry.hpp" + +#include + +#include + +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Point3d; + +constexpr double epsilon = 1e-06; + +namespace +{ +geometry_msgs::msg::Pose createPose(const double x, const double y, const double yaw) +{ + geometry_msgs::msg::Pose p; + p.position = geometry_msgs::build().x(x).y(y).z(0.0); + p.orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw); + return p; +} +} // namespace + +TEST(matching, test_get2dIoU) +{ + using autoware_auto_perception_msgs::msg::DetectedObject; + using perception_utils::get2dIoU; + + const double quart_circle = 0.16237976320958225; + + { // non overlapped + DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(1.5, 1.5, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double iou = get2dIoU(source_obj, target_obj); + EXPECT_DOUBLE_EQ(iou, 0.0); + } + + { // partially overlapped + DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(0.5, 0.5, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double iou = get2dIoU(source_obj, target_obj); + EXPECT_NEAR(iou, quart_circle / (1.0 + quart_circle * 3), epsilon); + } + + { // fully overlapped + DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double iou = get2dIoU(source_obj, target_obj); + EXPECT_DOUBLE_EQ(iou, quart_circle * 4); + } +} + +TEST(perception_utils, test_get2dGeneralizedIoU) +{ + using perception_utils::get2dGeneralizedIoU; + // TODO(Shin-kyoto): + // get2dGeneralizedIoU uses outer points of each polygon. + // But these points contain an sampling error of outer line, + // so get2dGeneralizedIoU icludes an error of about 0.03. + // Threfore, in this test, epsilon is set to 0.04. + constexpr double epsilon_giou = 4 * 1e-02; + const double quart_circle = 0.16237976320958225; + + { // non overlapped + autoware_auto_perception_msgs::msg::DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(1.5, 0.0, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + autoware_auto_perception_msgs::msg::DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double giou = get2dGeneralizedIoU(source_obj, target_obj); + EXPECT_NEAR(giou, (2 * quart_circle - 1) / (2 * quart_circle + 2), epsilon_giou); // not 0 + } + + { // partially overlapped + autoware_auto_perception_msgs::msg::DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(0.5, 0.0, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + autoware_auto_perception_msgs::msg::DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double giou = get2dGeneralizedIoU(source_obj, target_obj); + EXPECT_NEAR(giou, 2 * quart_circle / (2 * quart_circle + 1), epsilon_giou); + } + + { // fully overlapped + autoware_auto_perception_msgs::msg::DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + autoware_auto_perception_msgs::msg::DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double giou = get2dGeneralizedIoU(source_obj, target_obj); + EXPECT_NEAR(giou, quart_circle * 4, epsilon_giou); // giou equals iou + } +} + +TEST(matching, test_get2dPrecision) +{ + using autoware_auto_perception_msgs::msg::DetectedObject; + using perception_utils::get2dPrecision; + const double quart_circle = 0.16237976320958225; + + { // non overlapped + DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(1.5, 1.5, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double precision = get2dPrecision(source_obj, target_obj); + EXPECT_DOUBLE_EQ(precision, 0.0); + + // reverse source and target object + const double reversed_precision = get2dPrecision(target_obj, source_obj); + EXPECT_DOUBLE_EQ(reversed_precision, 0.0); + } + + { // partially overlapped + DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(0.5, 0.5, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double precision = get2dPrecision(source_obj, target_obj); + EXPECT_NEAR(precision, quart_circle, epsilon); + + // reverse source and target object + const double reversed_precision = get2dPrecision(target_obj, source_obj); + EXPECT_NEAR(reversed_precision, 1 / 4.0, epsilon); + } + + { // fully overlapped + DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double precision = get2dPrecision(source_obj, target_obj); + EXPECT_DOUBLE_EQ(precision, quart_circle * 4); + + // reverse source and target object + const double reversed_precision = get2dPrecision(target_obj, source_obj); + EXPECT_DOUBLE_EQ(reversed_precision, 1.0); + } +} + +TEST(matching, test_get2dRecall) +{ + using autoware_auto_perception_msgs::msg::DetectedObject; + using perception_utils::get2dRecall; + const double quart_circle = 0.16237976320958225; + + { // non overlapped + DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(1.5, 1.5, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double recall = get2dRecall(source_obj, target_obj); + EXPECT_DOUBLE_EQ(recall, 0.0); + + // reverse source and target object + const double reversed_recall = get2dRecall(target_obj, source_obj); + EXPECT_DOUBLE_EQ(reversed_recall, 0.0); + } + + { // partially overlapped + DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(0.5, 0.5, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double recall = get2dRecall(source_obj, target_obj); + EXPECT_NEAR(recall, 1 / 4.0, epsilon); + + // reverse source and target object + const double reversed_recall = get2dRecall(target_obj, source_obj); + EXPECT_NEAR(reversed_recall, quart_circle, epsilon); + } + + { // fully overlapped + DetectedObject source_obj; + source_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI); + source_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + source_obj.shape.dimensions.x = 1.0; + source_obj.shape.dimensions.y = 1.0; + + DetectedObject target_obj; + target_obj.kinematics.pose_with_covariance.pose = createPose(0.0, 0.0, M_PI_2); + target_obj.shape.type = autoware_auto_perception_msgs::msg::Shape::CYLINDER; + target_obj.shape.dimensions.x = 1.0; + + const double recall = get2dRecall(source_obj, target_obj); + EXPECT_DOUBLE_EQ(recall, 1.0); + + // reverse source and target object + const double reversed_recall = get2dRecall(target_obj, source_obj); + EXPECT_DOUBLE_EQ(reversed_recall, quart_circle * 4); + } +} diff --git a/common/perception_utils/test/src/test_object_classification.cpp b/common/perception_utils/test/src/test_object_classification.cpp new file mode 100644 index 0000000000000..1d89d73b7dccb --- /dev/null +++ b/common/perception_utils/test/src/test_object_classification.cpp @@ -0,0 +1,63 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "perception_utils/object_classification.hpp" + +#include + +namespace +{ +autoware_auto_perception_msgs::msg::ObjectClassification createObjectClassification( + const std::uint8_t label, const double probability) +{ + autoware_auto_perception_msgs::msg::ObjectClassification classification; + classification.label = label; + classification.probability = probability; + + return classification; +} + +} // namespace + +TEST(object_classification, test_getHighestProbLabel) +{ + using autoware_auto_perception_msgs::msg::ObjectClassification; + using perception_utils::getHighestProbLabel; + + { // empty + std::vector classification; + std::uint8_t label = getHighestProbLabel(classification); + EXPECT_EQ(label, ObjectClassification::UNKNOWN); + } + + { // normal case + std::vector classification; + classification.push_back(createObjectClassification(ObjectClassification::CAR, 0.5)); + classification.push_back(createObjectClassification(ObjectClassification::TRUCK, 0.8)); + classification.push_back(createObjectClassification(ObjectClassification::BUS, 0.7)); + + std::uint8_t label = getHighestProbLabel(classification); + EXPECT_EQ(label, ObjectClassification::TRUCK); + } + + { // labels with the same probability + std::vector classification; + classification.push_back(createObjectClassification(ObjectClassification::CAR, 0.8)); + classification.push_back(createObjectClassification(ObjectClassification::TRUCK, 0.8)); + classification.push_back(createObjectClassification(ObjectClassification::BUS, 0.7)); + + std::uint8_t label = getHighestProbLabel(classification); + EXPECT_EQ(label, ObjectClassification::CAR); + } +} diff --git a/common/perception_utils/test/src/test_predicted_path_utils.cpp b/common/perception_utils/test/src/test_predicted_path_utils.cpp index a433b0a987b33..3d9e2e5790a90 100644 --- a/common/perception_utils/test/src/test_predicted_path_utils.cpp +++ b/common/perception_utils/test/src/test_predicted_path_utils.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 TIER IV, Inc. +// Copyright 2022 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. From 5af51266407f14cb93144a1d58e599ea3398a0cd Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Thu, 6 Oct 2022 17:24:37 +0900 Subject: [PATCH 15/28] feat(rtc_manager_rviz_plugin): add_indivisual_exe (#2021) Signed-off-by: tanaka3 Signed-off-by: tanaka3 --- .../src/rtc_manager_panel.cpp | 111 ++++++++++++++++-- .../src/rtc_manager_panel.hpp | 21 ++++ 2 files changed, 119 insertions(+), 13 deletions(-) diff --git a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp index 2058942b051f7..5f23fa6ff5fbf 100644 --- a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp +++ b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp @@ -18,7 +18,6 @@ #include #include -#include #include #include @@ -77,6 +76,17 @@ std::string getModuleName(const uint8_t module_type) return "NONE"; } +bool isPathChangeModule(const uint8_t module_type) +{ + if ( + module_type == Module::LANE_CHANGE_LEFT || module_type == Module::LANE_CHANGE_RIGHT || + module_type == Module::AVOIDANCE_LEFT || module_type == Module::AVOIDANCE_RIGHT || + module_type == Module::PULL_OVER || module_type == Module::PULL_OUT) { + return true; + } + return false; +} + RTCManagerPanel::RTCManagerPanel(QWidget * parent) : rviz_common::Panel(parent) { // TODO(tanaka): replace this magic number to Module::SIZE @@ -100,11 +110,16 @@ RTCManagerPanel::RTCManagerPanel(QWidget * parent) : rviz_common::Panel(parent) rtc_auto_mode->setParent(this); // module { - rtc_auto_mode->module_name = getModuleName(static_cast(i)); + const uint8_t module_type = static_cast(i); + rtc_auto_mode->module_name = getModuleName(module_type); std::string module_name = rtc_auto_mode->module_name; auto label = new QLabel(QString::fromStdString(module_name)); label->setAlignment(Qt::AlignCenter); label->setText(QString::fromStdString(module_name)); + if (isPathChangeModule(module_type)) + label->setStyleSheet(BG_PURPLE); + else + label->setStyleSheet(BG_ORANGE); auto_mode_table_->setCellWidget(i, 0, label); } // mode button @@ -136,14 +151,54 @@ RTCManagerPanel::RTCManagerPanel(QWidget * parent) : rviz_common::Panel(parent) } v_layout->addWidget(auto_mode_table_); + // lateral execution + auto * exe_path_change_layout = new QHBoxLayout; + { + exec_path_change_button_ptr_ = new QPushButton("Execute Path Change"); + exec_path_change_button_ptr_->setCheckable(false); + exec_path_change_button_ptr_->setStyleSheet(BG_PURPLE); + connect( + exec_path_change_button_ptr_, &QPushButton::clicked, this, + &RTCManagerPanel::onClickExecutePathChange); + exe_path_change_layout->addWidget(exec_path_change_button_ptr_); + wait_path_change_button_ptr_ = new QPushButton("Wait Path Change"); + wait_path_change_button_ptr_->setCheckable(false); + wait_path_change_button_ptr_->setStyleSheet(BG_PURPLE); + connect( + wait_path_change_button_ptr_, &QPushButton::clicked, this, + &RTCManagerPanel::onClickWaitPathChange); + exe_path_change_layout->addWidget(wait_path_change_button_ptr_); + } + v_layout->addLayout(exe_path_change_layout); + + // longitudinal execution + auto * exe_vel_change_layout = new QHBoxLayout; + { + exec_vel_change_button_ptr_ = new QPushButton("Execute Velocity Change"); + exec_vel_change_button_ptr_->setCheckable(false); + exec_vel_change_button_ptr_->setStyleSheet(BG_ORANGE); + connect( + exec_vel_change_button_ptr_, &QPushButton::clicked, this, + &RTCManagerPanel::onClickExecuteVelChange); + exe_vel_change_layout->addWidget(exec_vel_change_button_ptr_); + wait_vel_change_button_ptr_ = new QPushButton("Wait Velocity Change"); + wait_vel_change_button_ptr_->setCheckable(false); + wait_vel_change_button_ptr_->setStyleSheet(BG_ORANGE); + connect( + wait_vel_change_button_ptr_, &QPushButton::clicked, this, + &RTCManagerPanel::onClickWaitVelChange); + exe_vel_change_layout->addWidget(wait_vel_change_button_ptr_); + } + v_layout->addLayout(exe_vel_change_layout); + // execution auto * rtc_exe_layout = new QHBoxLayout; { - exec_button_ptr_ = new QPushButton("Execute"); + exec_button_ptr_ = new QPushButton("Execute All"); exec_button_ptr_->setCheckable(false); connect(exec_button_ptr_, &QPushButton::clicked, this, &RTCManagerPanel::onClickExecution); rtc_exe_layout->addWidget(exec_button_ptr_); - wait_button_ptr_ = new QPushButton("Wait"); + wait_button_ptr_ = new QPushButton("Wait All"); wait_button_ptr_->setCheckable(false); connect(wait_button_ptr_, &QPushButton::clicked, this, &RTCManagerPanel::onClickWait); rtc_exe_layout->addWidget(wait_button_ptr_); @@ -193,7 +248,7 @@ void RTCAutoMode::onChangeToAutoMode() request->enable = true; enable_auto_mode_cli->async_send_request(request); auto_manual_mode_label->setText("AutoMode"); - auto_manual_mode_label->setStyleSheet("background-color: #00FFFF;"); + auto_manual_mode_label->setStyleSheet(BG_BLUE); auto_module_button_ptr->setChecked(true); manual_module_button_ptr->setChecked(false); } @@ -204,11 +259,40 @@ void RTCAutoMode::onChangeToManualMode() request->enable = false; enable_auto_mode_cli->async_send_request(request); auto_manual_mode_label->setText("ManualMode"); - auto_manual_mode_label->setStyleSheet("background-color: #FFFF00;"); + auto_manual_mode_label->setStyleSheet(BG_YELLOW); manual_module_button_ptr->setChecked(true); auto_module_button_ptr->setChecked(false); } +CooperateCommand setRTCCommandFromStatus(CooperateStatus & status) +{ + CooperateCommand cooperate_command; + cooperate_command.uuid = status.uuid; + cooperate_command.module = status.module; + cooperate_command.command = status.command_status; + return cooperate_command; +} + +void RTCManagerPanel::onClickChangeRequest(const bool is_path_change, const uint8_t command) +{ + if (!cooperate_statuses_ptr_) return; + if (cooperate_statuses_ptr_->statuses.empty()) return; + auto executable_cooperate_commands_request = std::make_shared(); + executable_cooperate_commands_request->stamp = cooperate_statuses_ptr_->stamp; + // send coop request + for (auto status : cooperate_statuses_ptr_->statuses) { + if (is_path_change ^ isPathChangeModule(status.module.type)) continue; + CooperateCommand cooperate_command = setRTCCommandFromStatus(status); + cooperate_command.command.type = command; + executable_cooperate_commands_request->commands.emplace_back(cooperate_command); + // To consider needs to change path step by step + if (is_path_change && !status.auto_mode && status.command_status.type ^ command) { + break; + } + } + client_rtc_commands_->async_send_request(executable_cooperate_commands_request); +} + void RTCManagerPanel::onClickCommandRequest(const uint8_t command) { if (!cooperate_statuses_ptr_) return; @@ -217,17 +301,18 @@ void RTCManagerPanel::onClickCommandRequest(const uint8_t command) executable_cooperate_commands_request->stamp = cooperate_statuses_ptr_->stamp; // send coop request for (auto status : cooperate_statuses_ptr_->statuses) { - CooperateCommand cooperate_command; - cooperate_command.uuid = status.uuid; - cooperate_command.module = status.module; + CooperateCommand cooperate_command = setRTCCommandFromStatus(status); cooperate_command.command.type = command; executable_cooperate_commands_request->commands.emplace_back(cooperate_command); } client_rtc_commands_->async_send_request(executable_cooperate_commands_request); } +void RTCManagerPanel::onClickExecuteVelChange() { onClickChangeRequest(false, Command::ACTIVATE); } +void RTCManagerPanel::onClickWaitVelChange() { onClickChangeRequest(false, Command::DEACTIVATE); } +void RTCManagerPanel::onClickExecutePathChange() { onClickChangeRequest(true, Command::ACTIVATE); } +void RTCManagerPanel::onClickWaitPathChange() { onClickChangeRequest(true, Command::DEACTIVATE); } void RTCManagerPanel::onClickExecution() { onClickCommandRequest(Command::ACTIVATE); } - void RTCManagerPanel::onClickWait() { onClickCommandRequest(Command::DEACTIVATE); } void RTCManagerPanel::onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg) @@ -314,11 +399,11 @@ void RTCManagerPanel::onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg // add color for recognition if (is_rtc_auto_mode || (is_aw_safe && is_execute)) { - rtc_table_->cellWidget(cnt, 1)->setStyleSheet("background-color: #00FF00;"); + rtc_table_->cellWidget(cnt, 1)->setStyleSheet(BG_GREEN); } else if (is_aw_safe || is_execute) { - rtc_table_->cellWidget(cnt, 1)->setStyleSheet("background-color: #FFFF00;"); + rtc_table_->cellWidget(cnt, 1)->setStyleSheet(BG_YELLOW); } else { - rtc_table_->cellWidget(cnt, 1)->setStyleSheet("background-color: #FF0000;"); + rtc_table_->cellWidget(cnt, 1)->setStyleSheet(BG_RED); } cnt++; } diff --git a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp index 50f6f10ebfc15..0a16a84b38ca4 100644 --- a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp +++ b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #ifndef Q_MOC_RUN @@ -56,6 +57,13 @@ using tier4_rtc_msgs::srv::AutoMode; using tier4_rtc_msgs::srv::CooperateCommands; using unique_identifier_msgs::msg::UUID; +static const QString BG_BLUE = "background-color: #3dffff;"; +static const QString BG_YELLOW = "background-color: #ffff3d;"; +static const QString BG_PURPLE = "background-color: #9e3dff;"; +static const QString BG_ORANGE = "background-color: #ff7f00;"; +static const QString BG_GREEN = "background-color: #3dff3d;"; +static const QString BG_RED = "background-color: #ff3d3d;"; + struct RTCAutoMode : public QObject { Q_OBJECT @@ -78,6 +86,11 @@ class RTCManagerPanel : public rviz_common::Panel public Q_SLOTS: void onClickExecution(); void onClickWait(); + void onClickVelocityChangeRequest(); + void onClickExecutePathChange(); + void onClickWaitPathChange(); + void onClickExecuteVelChange(); + void onClickWaitVelChange(); public: explicit RTCManagerPanel(QWidget * parent = nullptr); @@ -88,6 +101,7 @@ public Q_SLOTS: void onEnableService( const AutoMode::Request::SharedPtr request, const AutoMode::Response::SharedPtr response) const; void onClickCommandRequest(const uint8_t command); + void onClickChangeRequest(const bool is_path_change, const uint8_t command); private: rclcpp::Node::SharedPtr raw_node_; @@ -99,8 +113,15 @@ public Q_SLOTS: std::shared_ptr cooperate_statuses_ptr_; QTableWidget * rtc_table_; QTableWidget * auto_mode_table_; + QPushButton * path_change_button_ptr_ = {nullptr}; + QPushButton * velocity_change_button_ptr_ = {nullptr}; + QPushButton * exec_path_change_button_ptr_ = {nullptr}; + QPushButton * wait_path_change_button_ptr_ = {nullptr}; + QPushButton * exec_vel_change_button_ptr_ = {nullptr}; + QPushButton * wait_vel_change_button_ptr_ = {nullptr}; QPushButton * exec_button_ptr_ = {nullptr}; QPushButton * wait_button_ptr_ = {nullptr}; + size_t column_size_ = {7}; std::string enable_auto_mode_namespace_ = "/planning/enable_auto_mode"; }; From 7b63dec5d2b6c824e13bbbe5dc9e7cdf90d30e04 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Thu, 6 Oct 2022 17:49:46 +0900 Subject: [PATCH 16/28] feat(behavior_path_planner): add turn signal document (#2023) * feat(behavior_path_planner): add turn signal decider document Signed-off-by: yutaka * fix format Signed-off-by: yutaka * fix format Signed-off-by: yutaka * fix picture Signed-off-by: yutaka * fix spell Signed-off-by: yutaka * Update README.md * Update planning/behavior_path_planner/behavior_path_planner_turn_signal-design.md Co-authored-by: Fumiya Watanabe * Update planning/behavior_path_planner/behavior_path_planner_turn_signal-design.md Co-authored-by: Fumiya Watanabe * Update planning/behavior_path_planner/behavior_path_planner_turn_signal-design.md Co-authored-by: Fumiya Watanabe * Update planning/behavior_path_planner/behavior_path_planner_turn_signal-design.md Co-authored-by: Fumiya Watanabe * Update planning/behavior_path_planner/behavior_path_planner_turn_signal-design.md Co-authored-by: Fumiya Watanabe * Update planning/behavior_path_planner/behavior_path_planner_turn_signal-design.md Signed-off-by: yutaka Co-authored-by: Fumiya Watanabe --- planning/behavior_path_planner/README.md | 32 +--- ...ehavior_path_planner_turn_signal-design.md | 176 ++++++++++++++++++ .../avoidance_and_turn.drawio.svg | 4 + .../avoidance_and_turn2.drawio.svg | 4 + .../avoidance_first_section.drawio.svg | 4 + .../avoidance_second_section.drawio.svg | 4 + .../continuous_turns.drawio.svg | 4 + .../lane_change.drawio.svg | 4 + .../lane_change_and_turn.drawio.svg | 4 + .../left_right_turn.drawio.svg | 4 + .../turn_signal_decider/pattern1.drawio.svg | 4 + .../turn_signal_decider/pattern2.drawio.svg | 4 + .../turn_signal_decider/pattern3.drawio.svg | 4 + .../turn_signal_decider/pattern4.drawio.svg | 4 + .../turn_signal_decider/pattern5.drawio.svg | 4 + .../turn_signal_decider/pull_out.drawio.svg | 4 + .../turn_signal_decider/pull_over.drawio.svg | 4 + .../sections_definition.drawio.svg | 4 + .../image/turn_signal_fig1.drawio.svg | 1 - 19 files changed, 242 insertions(+), 31 deletions(-) create mode 100644 planning/behavior_path_planner/behavior_path_planner_turn_signal-design.md create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn2.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/avoidance_first_section.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/avoidance_second_section.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/continuous_turns.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/lane_change.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/lane_change_and_turn.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/left_right_turn.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/pattern1.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/pattern2.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/pattern3.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/pattern4.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/pattern5.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/pull_out.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/pull_over.drawio.svg create mode 100644 planning/behavior_path_planner/image/turn_signal_decider/sections_definition.drawio.svg delete mode 100644 planning/behavior_path_planner/image/turn_signal_fig1.drawio.svg diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index ba8b01f27e1fb..8380ece58826b 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -491,40 +491,12 @@ If the target path contains a goal, modify the points of the path so that the pa ![path_goal_refinement](./image/path_goal_refinement.drawio.svg) -### Turn signal - -Turn on signal when the planned path crosses lanes or when a right or left turn is required. The turn signal information includes the direction of the turn signal and the distance to the point where the turn signal is needed. - -#### From planned path - -- turn signal direction - Calculate the lateral movement distance from the shift start and end point and judges whether the line is crossed or not. If the vehicle straddles the line during lateral movement, the system turns on the blinker. - ![cross_judgment](./image/turn_signal_fig1.drawio.svg) - The timing to start lighting is when the time required to reach the shift start point is 3 seconds or less, or when the distance becomes smaller than threshold (default: `10.0 m`). - The Japanese Road Traffic Law requires turn signal to be turned on `3.0 sec` before the vehicle starts moving sideways, but it also gives a condition based on distance because the turn signal may be turned off by slowing down before the shift start point. -- distance - The distance from the top of ego vehicle to the shift end point. - -#### From map information - -- turn signal direction - Determine right or left turns based on the "turn_direction" information embedded in the lanelet. - -- distance - The distance to the lane where you start to turn. - -#### Conciliation - -When multiple turn signal conditions are met, the turn signal with the smaller distance is selected. - -#### Limitation - -Currently, the algorithm of turn signal has been chagned, and the document of the turn signal will be available soon. - ## References / External links This module depends on the external [BehaviorTreeCpp](https://github.com/BehaviorTree/BehaviorTree.CPP) library. + + [[1]](https://www.sciencedirect.com/science/article/pii/S1474667015347431) H. Vorobieva, S. Glaser, N. Minoiu-Enache, and S. Mammar, “Geometric path planning for automatic parallel parking in tiny spots”, IFAC Proceedings Volumes, vol. 45, no. 24, pp. 36–42, 2012. ## Future extensions / Unimplemented parts diff --git a/planning/behavior_path_planner/behavior_path_planner_turn_signal-design.md b/planning/behavior_path_planner/behavior_path_planner_turn_signal-design.md new file mode 100644 index 0000000000000..14ae3cef68b8c --- /dev/null +++ b/planning/behavior_path_planner/behavior_path_planner_turn_signal-design.md @@ -0,0 +1,176 @@ +# Turn Signal Decider + +Turn Signal decider determines necessary blinkers. + +## Purpose / Role + +This module is responsible for activating a necessary blinker during driving. It uses rule-based algorithm to determine blinkers, and the details of this algorithm are described in the following sections. Note that this algorithm is strictly based on the Japanese Road Traffic Raw. + +### Limitations + +Currently, this algorithm can sometimes give unnatural (not wrong) blinkers in a complicated situations. This is because it tries to follow the road traffic raw and cannot solve `blinker conflicts` clearly in that environment. + +## Inner-workings / Algorithms + +In this algorithm, it assumes that each blinker has two sections, which are `desired section` and `required section`. The image of these two sections are depicted in the following diagram. + +![section_definition](./image/turn_signal_decider/sections_definition.drawio.svg) + +These two sections have the following meanings. + +### - Desired Section + + - This section is defined by road traffic laws. It cannot be longer or shorter than the designated length defined by the law. + - In this section, you do not have to activate the designated blinkers if it is dangerous to do so. + +### - Required Section + + - In this section, ego vehicle must activate designated blinkers. However, if there are blinker conflicts, it must solve them based on the algorithm we mention later in this document. + - Required section cannot be longer than desired section. + +For left turn, right turn, avoidance, lane change, pull over and pull out, we define these two sections, which are elaborated in the following part. + +#### 1. Left and Right turn + +Turn signal decider checks each lanelet on the map if it has `turn_direction` information. If a lanelet has this information, it activates necessary blinker based on this information. + +- desired start point + `v*3.0 + 30` meters before the start point of the intersection lanelet(depicted in gree in the following picture), where `v` is the velocity of the ego vehicle. + +- desired end point + Terminal point of the intersection lanelet. + +- required start point + Initial point of the intersection lanelet. + +- required end point + The earliest point that satisfies the following condition. $\theta - \theta_{\textrm{end}} < \delta$, where $\theta_{\textrm{end}}$ is yaw angle of the terminal point of the lanelet, $\theta$ is the angle of a required end point and $\delta$ is the threshold defined by the user. + +![section_turn_signal](./image/turn_signal_decider/left_right_turn.drawio.svg) + +#### 2. Avoidance + +Avoidance can be separated into two sections, first section and second section. The first section is from the start point of the path shift to the end of the path shift. The second section is from the end of shift point to the end of avoidance. + +First section + +- desired start point + `v*3.0` meters before the start point of the avoidance shift path. + +- desired end point + Shift complete point where the path shift is completed. + +- required start point + Avoidance start point. + +- required end point + Shift complete point same as the desired end point. + +![section_first_avoidance](./image/turn_signal_decider/avoidance_first_section.drawio.svg) + +Second section + +- desired start point + Shift complete point. + +- desired end point + Avoidance terminal point + +- required start point + Shift complete point. + +- required end point + Avoidance terminal point. + +![section_second_avoidance](./image/turn_signal_decider/avoidance_second_section.drawio.svg) + +#### 3. Lane Change + +- desired start point + `v*3.0` meters before the start point of the lane change path. + +- desired end point + Terminal point of the lane change path. + +- required start point + Initial point of the lane change path. + +- required end point + Cross point with lane change path and boundary line of the adjacent lane. + +![section_lane_change](./image/turn_signal_decider/lane_change.drawio.svg) + +#### 4. Pull out + +- desired start point + Start point of the path of pull out. + +- desired end point + Terminal point of the path of pull out. + +- required start point + Start point of the path pull out. + +- required end point + Terminal point of the path of pull out. + +![section_pull_out](./image/turn_signal_decider/pull_out.drawio.svg) + +#### 5. Pull over + +- desired start point + `v*3.0` meters before the start point of the pull over path. + +- desired end point + Terminal point of the path of pull over. + +- required start point + Start point of the path of pull over. + +- required end point + Terminal point of the path of pull over. + +![section_pull_over](./image/turn_signal_decider/pull_over.drawio.svg) + +When it comes to handle several blinkers, it gives priority to the first blinker that comes first. However, this rule sometimes activate unnatural blinkers, so turn signal decider uses the following five rules to decide the necessary turn signal. + +- pattern1 + ![pattern1](./image/turn_signal_decider/pattern1.drawio.svg) + +- pattern2 + ![pattern2](./image/turn_signal_decider/pattern2.drawio.svg) + +- pattern3 + ![pattern3](./image/turn_signal_decider/pattern3.drawio.svg) + +- pattern4 + ![pattern4](./image/turn_signal_decider/pattern4.drawio.svg) + +- pattern5 + ![pattern5](./image/turn_signal_decider/pattern5.drawio.svg) + +Based on these five rules, turn signal decider can solve `blinker conflicts`. The following pictures show some examples of this kind of conflicts. + +#### - Several right and left turns on short sections + +In this scenario, ego vehicle has to pass several turns that are close each other. Since this pattern can be solved by the pattern1 rule, the overall result is depicted in the following picture. + +![continuous_turns](./image/turn_signal_decider/continuous_turns.drawio.svg) + +#### - Avoidance with left turn (1) + +In this scene, ego vehicle has to deal with the obstacle that is on its original path as well as make a left turn. The overall result can be varied by the position of the obstacle, but the image of the result is described in the following picture. + +![avoidance_and_turn](./image/turn_signal_decider/avoidance_and_turn.drawio.svg) + +#### - Avoidance with left turn (2) + +Same as the previous scenario, ego vehicle has to avoid the obstacle as well as make a turn left. However, in this scene, the obstacle is parked after the intersection. Similar to the previous one, the overall result can be varied by the position of the obstacle, but the image of the result is described in the following picture. + +![avoidance_and_turn](./image/turn_signal_decider/avoidance_and_turn2.drawio.svg) + +#### - Lane change and left turn + +In this scenario, ego vehicle has to do lane change before making a left turn. In the following example, ego vehicle does not activate left turn signal until it reaches the end point of the lane change path. + +![avoidance_and_turn](./image/turn_signal_decider/lane_change_and_turn.drawio.svg) diff --git a/planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn.drawio.svg new file mode 100644 index 0000000000000..719da920f52d7 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn.drawio.svg @@ -0,0 +1,4 @@ + + + +
current_velocity * 3.0  [m]
current_velocity * 3.0...
required section avoidance
required section avoidance
desired section avoidance
desired section avoidance
required section left turn
required section left turn
desired section left turn
desired section left turn
avoidance start point 
avoidance start point 
left turn start point
left turn start point
left turn end point
left turn end point
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn2.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn2.drawio.svg new file mode 100644 index 0000000000000..f560bb7014493 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/avoidance_and_turn2.drawio.svg @@ -0,0 +1,4 @@ + + + +
required section left turn
required section left turn
desired section left turn
desired section left turn
required section avoidance
required section avoidance
desired section avoidance
desired section avoidance
current_velocity * 3.0 + 30  [m]
current_velocity * 3.0 + 30  [...
left turn start point 
left turn start point 
left turn end point 
left turn end point 
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/avoidance_first_section.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/avoidance_first_section.drawio.svg new file mode 100644 index 0000000000000..2eb279f47b086 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/avoidance_first_section.drawio.svg @@ -0,0 +1,4 @@ + + + +
current_velocity * 3.0 [m]
current_velocity * 3.0 [m]
Shift complete point 
Shift complete point 
d
d
avoidance start point
avoidance start poi...
avoidance end point
avoidance end point
desired section
desired section
required section
required section
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/avoidance_second_section.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/avoidance_second_section.drawio.svg new file mode 100644 index 0000000000000..0a7e158c67165 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/avoidance_second_section.drawio.svg @@ -0,0 +1,4 @@ + + + +
Shift complete point 
Shift complete point 
avoidance start point
avoidance start poi...
avoidance end point
avoidance end point
desired section
desired section
required section
required section
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/continuous_turns.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/continuous_turns.drawio.svg new file mode 100644 index 0000000000000..c36fba88dec7f --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/continuous_turns.drawio.svg @@ -0,0 +1,4 @@ + + + +
required section right turn
required section right turn
desired section right turn
desired section right turn
required section left turn
required section left turn
desired section left turn
desired section left turn
current_velocity * 3.0 + 30 [m]
current_velocity * 3.0 + 30 [m]
current_velocity * 3.0 + 30 [m]
current_velocity * 3.0 + 30 [m]
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/lane_change.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/lane_change.drawio.svg new file mode 100644 index 0000000000000..f58a0428f8fe6 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/lane_change.drawio.svg @@ -0,0 +1,4 @@ + + + +
lane change start point
lane change start point
lane change end point
lane change end point
lane cross point
lane cross point
desired section
desired section
required section
required section
current_velocity * 3.0 [m]
current_velocity * 3.0 [m]
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/lane_change_and_turn.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/lane_change_and_turn.drawio.svg new file mode 100644 index 0000000000000..812216f6a6672 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/lane_change_and_turn.drawio.svg @@ -0,0 +1,4 @@ + + + +
required section lane change
required section lane change
desired section lane change
desired section lane change
required section left turn
required section left turn
desired section left turn
desired section left turn
lane change end point
lane change end point
current_velocity * 3.0 + 30 [m]
current_velocity * 3.0 + 30 [m]
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/left_right_turn.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/left_right_turn.drawio.svg new file mode 100644 index 0000000000000..1518913232d7c --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/left_right_turn.drawio.svg @@ -0,0 +1,4 @@ + + + +
desired section
desired section
required section
required section
current_velocity * 3.0 + 30 [m]
current_velocity * 3.0 + 30 [m]
Lanelet
Lanelet
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pattern1.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/pattern1.drawio.svg new file mode 100644 index 0000000000000..3e684ed3e17f2 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/pattern1.drawio.svg @@ -0,0 +1,4 @@ + + + +
s
s
blinker1
blinker1
blinker2
blinker2
Overall
Overall
required section1
required section1
desired section1
desired section1
required section2
required section2
desired section2
desired section2
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pattern2.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/pattern2.drawio.svg new file mode 100644 index 0000000000000..0177c7e77c318 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/pattern2.drawio.svg @@ -0,0 +1,4 @@ + + + +
s
s
blinker1
blinker1
blinker2
blinker2
Overall
Overall
required section1
required section1
desired section1
desired section1
required section2
required section2
desired section2
desired section2
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pattern3.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/pattern3.drawio.svg new file mode 100644 index 0000000000000..92ca29483b669 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/pattern3.drawio.svg @@ -0,0 +1,4 @@ + + + +
s
s
blinker1
blinker1
blinker2
blinker2
Overall
Overall
required section1
required section1
desired section1
desired section1
required section2
required section2
desired section2
desired section2
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pattern4.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/pattern4.drawio.svg new file mode 100644 index 0000000000000..428700e4bc2db --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/pattern4.drawio.svg @@ -0,0 +1,4 @@ + + + +
s
s
blinker1
blinker1
blinker2
blinker2
Overall
Overall
required section1
required section1
desired section1
desired section1
required section2
required section2
desired section2
desired section2
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pattern5.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/pattern5.drawio.svg new file mode 100644 index 0000000000000..7f4a73afef4df --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/pattern5.drawio.svg @@ -0,0 +1,4 @@ + + + +
s
s
blinker1
blinker1
blinker2
blinker2
Overall
Overall
required section1
required section1
desired section1
desired section1
required section2
required section2
desired section2
desired section2
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pull_out.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/pull_out.drawio.svg new file mode 100644 index 0000000000000..c2b25dfee44d9 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/pull_out.drawio.svg @@ -0,0 +1,4 @@ + + + +
pull out start point 
pull out start poi...
pull out end point 
pull out end point 
desired section
desired section
required section
required section
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/pull_over.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/pull_over.drawio.svg new file mode 100644 index 0000000000000..838c7ac38a843 --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/pull_over.drawio.svg @@ -0,0 +1,4 @@ + + + +
desired section
desired section
required section
required section
pull over start point 
pull over start poi...
pull over end point 
pull over end point 
current_velocity * 3.0 [m]
current_velocity * 3.0 [m]
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_decider/sections_definition.drawio.svg b/planning/behavior_path_planner/image/turn_signal_decider/sections_definition.drawio.svg new file mode 100644 index 0000000000000..a3f645040263b --- /dev/null +++ b/planning/behavior_path_planner/image/turn_signal_decider/sections_definition.drawio.svg @@ -0,0 +1,4 @@ + + + +
required section
required section
desired section
desired section
s
s
desired start point
desired start poi...
desired end point
desired end point
required start point
required start poi...
required end point
required end point
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_path_planner/image/turn_signal_fig1.drawio.svg b/planning/behavior_path_planner/image/turn_signal_fig1.drawio.svg deleted file mode 100644 index 7ece2fbeaca6d..0000000000000 --- a/planning/behavior_path_planner/image/turn_signal_fig1.drawio.svg +++ /dev/null @@ -1 +0,0 @@ -
shift end point
shift start point
sss
(1) Left signal on
Left side point crosses the line during a horizontal movement
running lane
(2) Right signal on
Left side point crosses the line during a horizontal movement
(3) No signal
Points on both sides don't cross the line
\ No newline at end of file From 84a66fec2348e51a0400f0b561471aff51b15573 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Thu, 6 Oct 2022 17:51:38 +0900 Subject: [PATCH 17/28] feat(rtc_reaplyer): add rtc_replayer (#1993) * feat(rtc_replayer): add rtc_reaplayer Signed-off-by: tanaka3 * chore: small fix Signed-off-by: tanaka3 * doc: update Signed-off-by: taikitanaka3 * chore: add debug print Signed-off-by: tanaka3 * fix: fix * fix: build fail * style: spell check Signed-off-by: tanaka3 Signed-off-by: tanaka3 Signed-off-by: taikitanaka3 --- planning/rtc_replayer/CMakeLists.txt | 27 ++++ planning/rtc_replayer/README.md | 49 +++++++ .../rtc_replayer/rtc_replayer_node.hpp | 59 ++++++++ .../launch/rtc_replayer.launch.xml | 7 + planning/rtc_replayer/package.xml | 29 ++++ .../rtc_replayer/src/rtc_replayer_node.cpp | 131 ++++++++++++++++++ 6 files changed, 302 insertions(+) create mode 100644 planning/rtc_replayer/CMakeLists.txt create mode 100644 planning/rtc_replayer/README.md create mode 100644 planning/rtc_replayer/include/rtc_replayer/rtc_replayer_node.hpp create mode 100644 planning/rtc_replayer/launch/rtc_replayer.launch.xml create mode 100644 planning/rtc_replayer/package.xml create mode 100644 planning/rtc_replayer/src/rtc_replayer_node.cpp diff --git a/planning/rtc_replayer/CMakeLists.txt b/planning/rtc_replayer/CMakeLists.txt new file mode 100644 index 0000000000000..877c283b41ea9 --- /dev/null +++ b/planning/rtc_replayer/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 3.5) +project(rtc_replayer) + +### Compile options +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror) +endif() + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/${PROJECT_NAME}_node.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "rtc_replayer::RTCReplayerNode" + EXECUTABLE ${PROJECT_NAME}_node +) + +ament_auto_package( + INSTALL_TO_SHARE + launch +) diff --git a/planning/rtc_replayer/README.md b/planning/rtc_replayer/README.md new file mode 100644 index 0000000000000..e758edfdb38b1 --- /dev/null +++ b/planning/rtc_replayer/README.md @@ -0,0 +1,49 @@ +# rtc_replayer + +## Purpose + +The current issue for RTC commands is that service is not recorded to rosbag, so it's very hard to analyze what was happened exactly. +So this package makes it possible to replay rtc commands service from rosbag rtc status topic to resolve that issue. + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| ------------------- | ----------------------------------------- | ----------------------------------------------- | +| `/debug/rtc_status` | tier4_rtc_msgs::msg::CooperateStatusArray | CooperateStatusArray that is recorded in rosbag | + +### Output + +| Name | Type | Description | +| -------------------------------- | -------------------------------------- | -------------------------------------------------- | +| `/api/external/set/rtc_commands` | tier4_rtc_msgs::msg::CooperateCommands | CooperateCommands that is replayed by this package | + +## Inner-workings / Algorithms + +```plantuml + +@startuml +title rtc replayer +start + +:rosbag; + +:rtc_replayer; + +:rtc_interface; + +end + +@enduml + +``` + +## Assumptions / Known limits + +This package can't replay CooperateCommands correctly if CooperateStatusArray is not stable. +And this replay is always later one step than actual however it will not affect much for behavior. + +## Future extensions / Unimplemented parts + +tbd. diff --git a/planning/rtc_replayer/include/rtc_replayer/rtc_replayer_node.hpp b/planning/rtc_replayer/include/rtc_replayer/rtc_replayer_node.hpp new file mode 100644 index 0000000000000..49d0d9d60c93a --- /dev/null +++ b/planning/rtc_replayer/include/rtc_replayer/rtc_replayer_node.hpp @@ -0,0 +1,59 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RTC_REPLAYER__RTC_REPLAYER_NODE_HPP_ +#define RTC_REPLAYER__RTC_REPLAYER_NODE_HPP_ + +#include "rclcpp/rclcpp.hpp" + +#include "tier4_rtc_msgs/msg/command.hpp" +#include "tier4_rtc_msgs/msg/cooperate_command.hpp" +#include "tier4_rtc_msgs/msg/cooperate_status.hpp" +#include "tier4_rtc_msgs/msg/cooperate_status_array.hpp" +#include "tier4_rtc_msgs/msg/module.hpp" +#include "tier4_rtc_msgs/srv/cooperate_commands.hpp" +#include + +#include +#include +#include +#include + +namespace rtc_replayer +{ +using std::placeholders::_1; +using std::placeholders::_2; +using tier4_rtc_msgs::msg::Command; +using tier4_rtc_msgs::msg::CooperateCommand; +using tier4_rtc_msgs::msg::CooperateStatus; +using tier4_rtc_msgs::msg::CooperateStatusArray; +using tier4_rtc_msgs::msg::Module; +using tier4_rtc_msgs::srv::CooperateCommands; +using unique_identifier_msgs::msg::UUID; +class RTCReplayerNode : public rclcpp::Node +{ +public: + explicit RTCReplayerNode(const rclcpp::NodeOptions & node_options); + +private: + void onCooperateStatus(const CooperateStatusArray::ConstSharedPtr msg); + + rclcpp::Subscription::SharedPtr sub_statuses_; + rclcpp::Client::SharedPtr client_rtc_commands_; + std::map prev_cmd_status_; +}; + +} // namespace rtc_replayer + +#endif // RTC_REPLAYER__RTC_REPLAYER_NODE_HPP_ diff --git a/planning/rtc_replayer/launch/rtc_replayer.launch.xml b/planning/rtc_replayer/launch/rtc_replayer.launch.xml new file mode 100644 index 0000000000000..9b832b369c77c --- /dev/null +++ b/planning/rtc_replayer/launch/rtc_replayer.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/planning/rtc_replayer/package.xml b/planning/rtc_replayer/package.xml new file mode 100644 index 0000000000000..9101a1e86633a --- /dev/null +++ b/planning/rtc_replayer/package.xml @@ -0,0 +1,29 @@ + + + + rtc_replayer + 0.1.0 + The rtc_replayer package + + Fumiya Watanabe + Taiki Tanaka + + Apache License 2.0 + + Fumiya Watanabe + + ament_cmake_auto + + autoware_cmake + + rclcpp + rclcpp_components + tier4_rtc_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/rtc_replayer/src/rtc_replayer_node.cpp b/planning/rtc_replayer/src/rtc_replayer_node.cpp new file mode 100644 index 0000000000000..08f037fbfc390 --- /dev/null +++ b/planning/rtc_replayer/src/rtc_replayer_node.cpp @@ -0,0 +1,131 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rtc_replayer/rtc_replayer_node.hpp" + +#include + +namespace rtc_replayer +{ + +std::string getModuleStatus(const uint8_t module_status) +{ + switch (module_status) { + case Command::ACTIVATE: { + return "execute"; + } + case Command::DEACTIVATE: { + return "wait"; + } + } + return "none"; +} + +std::string getModuleName(const uint8_t module_type) +{ + switch (module_type) { + case Module::LANE_CHANGE_LEFT: { + return "lane_change_left"; + } + case Module::LANE_CHANGE_RIGHT: { + return "lane_change_right"; + } + case Module::AVOIDANCE_LEFT: { + return "avoidance_left"; + } + case Module::AVOIDANCE_RIGHT: { + return "avoidance_right"; + } + case Module::PULL_OVER: { + return "pull_over"; + } + case Module::PULL_OUT: { + return "pull_out"; + } + case Module::TRAFFIC_LIGHT: { + return "traffic_light"; + } + case Module::INTERSECTION: { + return "intersection"; + } + case Module::CROSSWALK: { + return "crosswalk"; + } + case Module::BLIND_SPOT: { + return "blind_spot"; + } + case Module::DETECTION_AREA: { + return "detection_area"; + } + case Module::NO_STOPPING_AREA: { + return "no_stopping_area"; + } + case Module::OCCLUSION_SPOT: { + return "occlusion_spot"; + } + } + return "NONE"; +} + +std::string to_string(const unique_identifier_msgs::msg::UUID & uuid) +{ + std::stringstream ss; + for (auto i = 0; i < 16; ++i) { + ss << std::hex << std::setfill('0') << std::setw(2) << +uuid.uuid[i]; + } + return ss.str(); +} + +RTCReplayerNode::RTCReplayerNode(const rclcpp::NodeOptions & node_options) +: Node("rtc_replayer_node", node_options) +{ + sub_statuses_ = create_subscription( + "/debug/rtc_status", 1, std::bind(&RTCReplayerNode::onCooperateStatus, this, _1)); + client_rtc_commands_ = create_client( + "/api/external/set/rtc_commands", rmw_qos_profile_services_default); +} + +void RTCReplayerNode::onCooperateStatus(const CooperateStatusArray::ConstSharedPtr msg) +{ + if (msg->statuses.empty()) return; + CooperateCommands::Request::SharedPtr request = std::make_shared(); + for (auto status : msg->statuses) { + const auto cmd_status = status.command_status.type; + const auto uuid_string = to_string(status.uuid); + // add command which has change from previous status and command is already registered + if ( + prev_cmd_status_.find(uuid_string) != prev_cmd_status_.end() && + cmd_status != prev_cmd_status_[uuid_string]) { + CooperateCommand cc; + // send previous command status + cc.command.type = cmd_status; + cc.uuid = status.uuid; + cc.module = status.module; + request->stamp = status.stamp; + request->commands.emplace_back(cc); + std::cerr << "uuid: " << uuid_string << " module: " << getModuleName(cc.module.type) + << " status: " << getModuleStatus(cmd_status) << std::endl; + } + // post process + prev_cmd_status_[uuid_string] = cmd_status; + } + if (!request->commands.empty()) { + client_rtc_commands_->async_send_request(request); + } +} + +} // namespace rtc_replayer + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(rtc_replayer::RTCReplayerNode) From a07358a3c4451af567ddc8e5e0979608f5308db3 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 6 Oct 2022 18:25:42 +0900 Subject: [PATCH 18/28] feat(autoware_ad_api_specs): define operation mode interface (#1570) * feat(autoware_ad_api_msgs): define operation mode interface Signed-off-by: Takagi, Isamu * fix: add message Signed-off-by: Takagi, Isamu * Update common/autoware_ad_api_msgs/operation_mode/msg/OperationModeState.msg Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * Update common/autoware_ad_api_msgs/operation_mode/msg/OperationModeState.msg Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * feat: move adapi message Signed-off-by: Takagi, Isamu * feat: change message type Signed-off-by: Takagi, Isamu Signed-off-by: Takagi, Isamu Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .../autoware_ad_api_specs/operation_mode.hpp | 73 +++++++++++++++++++ .../component_interface_specs/system.hpp | 50 +++++++++++++ 2 files changed, 123 insertions(+) create mode 100644 common/autoware_ad_api_specs/include/autoware_ad_api_specs/operation_mode.hpp create mode 100644 common/component_interface_specs/include/component_interface_specs/system.hpp diff --git a/common/autoware_ad_api_specs/include/autoware_ad_api_specs/operation_mode.hpp b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/operation_mode.hpp new file mode 100644 index 0000000000000..f52b66cc88d2a --- /dev/null +++ b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/operation_mode.hpp @@ -0,0 +1,73 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_AD_API_SPECS__OPERATION_MODE_HPP_ +#define AUTOWARE_AD_API_SPECS__OPERATION_MODE_HPP_ + +#include + +#include +#include + +namespace autoware_ad_api::operation_mode +{ + +struct ChangeToStop +{ + using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode; + static constexpr char name[] = "/api/operation_mode/change_to_stop"; +}; + +struct ChangeToAutonomous +{ + using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode; + static constexpr char name[] = "/api/operation_mode/change_to_autonomous"; +}; + +struct ChangeToLocal +{ + using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode; + static constexpr char name[] = "/api/operation_mode/change_to_local"; +}; + +struct ChangeToRemote +{ + using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode; + static constexpr char name[] = "/api/operation_mode/change_to_remote"; +}; + +struct EnableAutowareControl +{ + using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode; + static constexpr char name[] = "/api/operation_mode/enable_autoware_control"; +}; + +struct DisableAutowareControl +{ + using Service = autoware_adapi_v1_msgs::srv::ChangeOperationMode; + static constexpr char name[] = "/api/operation_mode/disable_autoware_control"; +}; + +struct OperationModeState +{ + using Message = autoware_adapi_v1_msgs::msg::OperationModeState; + static constexpr char name[] = "/api/operation_mode/state"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; +}; + +} // namespace autoware_ad_api::operation_mode + +#endif // AUTOWARE_AD_API_SPECS__OPERATION_MODE_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/system.hpp b/common/component_interface_specs/include/component_interface_specs/system.hpp new file mode 100644 index 0000000000000..e7143d64fa05a --- /dev/null +++ b/common/component_interface_specs/include/component_interface_specs/system.hpp @@ -0,0 +1,50 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ +#define COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ + +#include + +#include +#include +#include + +namespace system_interface +{ + +struct ChangeAutowareControl +{ + using Service = tier4_system_msgs::srv::ChangeAutowareControl; + static constexpr char name[] = "/system/operation_mode/change_autoware_control"; +}; + +struct ChangeOperationMode +{ + using Service = tier4_system_msgs::srv::ChangeOperationMode; + static constexpr char name[] = "/system/operation_mode/change_operation_mode"; +}; + +struct OperationModeState +{ + using Message = autoware_adapi_v1_msgs::msg::OperationModeState; + static constexpr char name[] = "/system/operation_mode/state"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; +}; + +} // namespace system_interface + +#endif // COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ From b8a19b53ed0c934ec11090ccdef55ffc7917ca7e Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Thu, 6 Oct 2022 21:47:34 +0900 Subject: [PATCH 19/28] fix(detected_object_validation): apply transformation to shape.footprint.points (#1981) --- .../geometry/geometry.hpp | 13 ++++++++++++ .../test/src/geometry/test_geometry.cpp | 21 +++++++++++++++++++ .../object_lanelet_filter.hpp | 1 + .../src/object_lanelet_filter.cpp | 11 ++++++---- 4 files changed, 42 insertions(+), 4 deletions(-) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/geometry.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/geometry.hpp index 2ba61fe321cbe..b120ec4377413 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/geometry.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/geometry.hpp @@ -29,6 +29,7 @@ #include #include +#include #include #include #include @@ -490,6 +491,18 @@ inline geometry_msgs::msg::Point transformPoint( return transformed_point; } +inline geometry_msgs::msg::Point32 transformPoint( + const geometry_msgs::msg::Point32 & point32, const geometry_msgs::msg::Pose & pose) +{ + const auto point = + geometry_msgs::build().x(point32.x).y(point32.y).z(point32.z); + const auto transformed_point = tier4_autoware_utils::transformPoint(point, pose); + return geometry_msgs::build() + .x(transformed_point.x) + .y(transformed_point.y) + .z(transformed_point.z); +} + template T transformVector(const T & points, const geometry_msgs::msg::Transform & transform) { diff --git a/common/tier4_autoware_utils/test/src/geometry/test_geometry.cpp b/common/tier4_autoware_utils/test/src/geometry/test_geometry.cpp index 70ebb8ac72dca..96f1be9de6f3f 100644 --- a/common/tier4_autoware_utils/test/src/geometry/test_geometry.cpp +++ b/common/tier4_autoware_utils/test/src/geometry/test_geometry.cpp @@ -15,6 +15,8 @@ #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/math/unit_conversion.hpp" +#include + #include #include @@ -891,6 +893,25 @@ TEST(geometry, transformPoint) EXPECT_DOUBLE_EQ(p_transformed.y, 3.5334936490538906); EXPECT_DOUBLE_EQ(p_transformed.z, 5.6160254037844393); } + + { + geometry_msgs::msg::Point32 p; + p.x = 1.0; + p.y = 2.0; + p.z = 3.0; + + geometry_msgs::msg::Pose pose_transform; + pose_transform.position.x = 1.0; + pose_transform.position.y = 2.0; + pose_transform.position.z = 3.0; + pose_transform.orientation = createQuaternionFromRPY(deg2rad(30), deg2rad(30), deg2rad(30)); + + const geometry_msgs::msg::Point32 p_transformed = transformPoint(p, pose_transform); + + EXPECT_DOUBLE_EQ(p_transformed.x, 3.1919872760772705); + EXPECT_DOUBLE_EQ(p_transformed.y, 3.5334937572479248); + EXPECT_DOUBLE_EQ(p_transformed.z, 5.616025447845459); + } } TEST(geometry, transformPose) diff --git a/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp b/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp index 1f63ff28401f6..e8413761fc2b7 100644 --- a/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp @@ -62,6 +62,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node lanelet::LaneletMapPtr lanelet_map_ptr_; lanelet::ConstLanelets road_lanelets_; + std::string lanelet_frame_id_; tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; diff --git a/perception/detected_object_validation/src/object_lanelet_filter.cpp b/perception/detected_object_validation/src/object_lanelet_filter.cpp index 0c9cacf178292..ef73a76cc6489 100644 --- a/perception/detected_object_validation/src/object_lanelet_filter.cpp +++ b/perception/detected_object_validation/src/object_lanelet_filter.cpp @@ -55,6 +55,7 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod void ObjectLaneletFilterNode::mapCallback( const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr map_msg) { + lanelet_frame_id_ = map_msg->header.frame_id; lanelet_map_ptr_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg(*map_msg, lanelet_map_ptr_); const lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); @@ -77,8 +78,9 @@ void ObjectLaneletFilterNode::objectCallback( return; } autoware_auto_perception_msgs::msg::DetectedObjects transformed_objects; - if (!perception_utils::transformObjects(*input_msg, "map", tf_buffer_, transformed_objects)) { - RCLCPP_ERROR(get_logger(), "Failed transform to map."); + if (!perception_utils::transformObjects( + *input_msg, lanelet_frame_id_, tf_buffer_, transformed_objects)) { + RCLCPP_ERROR(get_logger(), "Failed transform to %s.", lanelet_frame_id_.c_str()); return; } @@ -90,7 +92,6 @@ void ObjectLaneletFilterNode::objectCallback( int index = 0; for (const auto & object : transformed_objects.objects) { const auto & footprint = object.shape.footprint; - const auto & position = object.kinematics.pose_with_covariance.pose.position; const auto & label = object.classification.front().label; if ( (label == Label::UNKNOWN && filter_target_.UNKNOWN) || @@ -103,7 +104,9 @@ void ObjectLaneletFilterNode::objectCallback( (label == Label::PEDESTRIAN && filter_target_.PEDESTRIAN)) { Polygon2d polygon; for (const auto & point : footprint.points) { - polygon.outer().emplace_back(point.x + position.x, point.y + position.y); + const geometry_msgs::msg::Point32 point_transformed = + tier4_autoware_utils::transformPoint(point, object.kinematics.pose_with_covariance.pose); + polygon.outer().emplace_back(point_transformed.x, point_transformed.y); } polygon.outer().push_back(polygon.outer().front()); if (isPolygonOverlapLanelets(polygon, intersected_lanelets)) { From d707d2b5c05605e11dbfe4db3ce5ff486bef0fcd Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 7 Oct 2022 02:41:11 +0900 Subject: [PATCH 20/28] feat(obstacle_cruise_planner): add goal safe distance (#2031) --- .../obstacle_cruise_planner.param.yaml | 1 + .../config/obstacle_cruise_planner.param.yaml | 1 + .../common_structs.hpp | 1 + planning/obstacle_cruise_planner/src/node.cpp | 5 +++- .../src/planner_interface.cpp | 27 ++++++++++++++----- 5 files changed, 27 insertions(+), 8 deletions(-) diff --git a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index f8f9a85deed5c..0c102155d2f00 100644 --- a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -10,6 +10,7 @@ min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] + terminal_safe_distance_margin : 3.0 # Stop margin at the goal [m] nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index diff --git a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml index f8f9a85deed5c..0c102155d2f00 100644 --- a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml +++ b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -10,6 +10,7 @@ min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] + terminal_safe_distance_margin : 3.0 # Stop margin at the goal [m] nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp index 71684b4406985..424f48e88bc5f 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp @@ -109,6 +109,7 @@ struct LongitudinalInfo double min_ego_accel_for_rss; double min_object_accel_for_rss; double safe_distance_margin; + double terminal_safe_distance_margin; }; struct DebugData diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index 0b970f35d2069..d2509d657fd1f 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -245,6 +245,8 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & declare_parameter("common.min_object_accel_for_rss"); const double idling_time = declare_parameter("common.idling_time"); const double safe_distance_margin = declare_parameter("common.safe_distance_margin"); + const double terminal_safe_distance_margin = + declare_parameter("common.terminal_safe_distance_margin"); return LongitudinalInfo{ max_accel, @@ -258,7 +260,8 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & idling_time, min_ego_accel_for_rss, min_object_accel_for_rss, - safe_distance_margin}; + safe_distance_margin, + terminal_safe_distance_margin}; }(); is_showing_debug_info_ = declare_parameter("common.is_showing_debug_info"); diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index b981c3fc17770..4ebef793bc733 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -140,16 +140,29 @@ Trajectory PlannerInterface::generateStopTrajectory( const auto closest_behavior_stop_idx = motion_utils::searchZeroVelocityIndex(planner_data.traj.points, nearest_segment_idx + 1); - if ( - closest_behavior_stop_idx && - closest_behavior_stop_idx != planner_data.traj.points.size() - 1) { - const double closest_behavior_stop_dist_from_ego = motion_utils::calcSignedArcLength( - planner_data.traj.points, planner_data.current_pose.position, nearest_segment_idx, - *closest_behavior_stop_idx); + if (!closest_behavior_stop_idx) { + return longitudinal_info_.safe_distance_margin; + } + + const double closest_behavior_stop_dist_from_ego = motion_utils::calcSignedArcLength( + planner_data.traj.points, planner_data.current_pose.position, nearest_segment_idx, + *closest_behavior_stop_idx); + + if (*closest_behavior_stop_idx == planner_data.traj.points.size() - 1) { + // Closest behavior stop point is the end point + const double closest_obstacle_stop_dist_from_ego = + closest_obstacle_dist - dist_to_ego - longitudinal_info_.terminal_safe_distance_margin - + abs_ego_offset; + const double stop_dist_diff = + closest_behavior_stop_dist_from_ego - closest_obstacle_stop_dist_from_ego; + if (stop_dist_diff < 0.5) { + // Use terminal margin (terminal_safe_distance_margin) for obstacle stop + return longitudinal_info_.terminal_safe_distance_margin; + } + } else { const double closest_obstacle_stop_dist_from_ego = closest_obstacle_dist - dist_to_ego - longitudinal_info_.safe_distance_margin - abs_ego_offset; - const double stop_dist_diff = closest_behavior_stop_dist_from_ego - closest_obstacle_stop_dist_from_ego; if (0.0 < stop_dist_diff && stop_dist_diff < longitudinal_info_.safe_distance_margin) { From aa90138f879d4925d54e9d21addbd192db7136b8 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 7 Oct 2022 10:30:18 +0900 Subject: [PATCH 21/28] refactor(probabilistic_occupancy_grid): transfer probabilistic_occupancy_grid package from sensing to perception directory (#1923) * refactor: move occ_grid_map package to perception folder Signed-off-by: Yoshi Ri * refactor: move occ_grid_map package to perception folder Signed-off-by: Yoshi Ri Signed-off-by: Yoshi Ri --- .../probabilistic_occupancy_grid_map/CMakeLists.txt | 0 .../probabilistic_occupancy_grid_map/README.md | 0 .../image/bresenham.svg | 0 ...erscan_based_occupancy_grid_map_sample_image.png | Bin .../pointcloud_based_occupancy_grid_map_bev.svg | 0 ...tcloud_based_occupancy_grid_map_sample_image.gif | Bin ...ointcloud_based_occupancy_grid_map_side_view.svg | 0 ...cloud_based_occupancy_grid_map_side_view_1st.svg | 0 ...cloud_based_occupancy_grid_map_side_view_2nd.svg | 0 ...cloud_based_occupancy_grid_map_side_view_3rd.svg | 0 .../image/update_with_pointcloud.svg | 0 .../include/cost_value.hpp | 0 .../laserscan_based_occupancy_grid_map_node.hpp | 0 .../occupancy_grid_map.hpp | 0 .../occupancy_grid_map.hpp | 0 .../pointcloud_based_occupancy_grid_map_node.hpp | 0 ...cupancy_grid_map_binary_bayes_filter_updater.hpp | 0 .../occupancy_grid_map_updater_interface.hpp | 0 .../laserscan-based-occupancy-grid-map.md | 0 .../laserscan_based_occupancy_grid_map.launch.py | 0 .../pointcloud_based_occupancy_grid_map.launch.py | 0 .../probabilistic_occupancy_grid_map/package.xml | 0 .../pointcloud-based-occupancy-grid-map.md | 0 .../laserscan_based_occupancy_grid_map_node.cpp | 0 .../occupancy_grid_map.cpp | 0 .../occupancy_grid_map.cpp | 0 .../pointcloud_based_occupancy_grid_map_node.cpp | 0 ...cupancy_grid_map_binary_bayes_filter_updater.cpp | 0 28 files changed, 0 insertions(+), 0 deletions(-) rename {sensing => perception}/probabilistic_occupancy_grid_map/CMakeLists.txt (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/README.md (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/image/bresenham.svg (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/image/laserscan_based_occupancy_grid_map_sample_image.png (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_bev.svg (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_sample_image.gif (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view.svg (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_1st.svg (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_2nd.svg (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_3rd.svg (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/image/update_with_pointcloud.svg (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/include/cost_value.hpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_updater_interface.hpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/laserscan-based-occupancy-grid-map.md (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/package.xml (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp (100%) rename {sensing => perception}/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp (100%) diff --git a/sensing/probabilistic_occupancy_grid_map/CMakeLists.txt b/perception/probabilistic_occupancy_grid_map/CMakeLists.txt similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/CMakeLists.txt rename to perception/probabilistic_occupancy_grid_map/CMakeLists.txt diff --git a/sensing/probabilistic_occupancy_grid_map/README.md b/perception/probabilistic_occupancy_grid_map/README.md similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/README.md rename to perception/probabilistic_occupancy_grid_map/README.md diff --git a/sensing/probabilistic_occupancy_grid_map/image/bresenham.svg b/perception/probabilistic_occupancy_grid_map/image/bresenham.svg similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/image/bresenham.svg rename to perception/probabilistic_occupancy_grid_map/image/bresenham.svg diff --git a/sensing/probabilistic_occupancy_grid_map/image/laserscan_based_occupancy_grid_map_sample_image.png b/perception/probabilistic_occupancy_grid_map/image/laserscan_based_occupancy_grid_map_sample_image.png similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/image/laserscan_based_occupancy_grid_map_sample_image.png rename to perception/probabilistic_occupancy_grid_map/image/laserscan_based_occupancy_grid_map_sample_image.png diff --git a/sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_bev.svg b/perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_bev.svg similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_bev.svg rename to perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_bev.svg diff --git a/sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_sample_image.gif b/perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_sample_image.gif similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_sample_image.gif rename to perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_sample_image.gif diff --git a/sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view.svg b/perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view.svg similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view.svg rename to perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view.svg diff --git a/sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_1st.svg b/perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_1st.svg similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_1st.svg rename to perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_1st.svg diff --git a/sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_2nd.svg b/perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_2nd.svg similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_2nd.svg rename to perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_2nd.svg diff --git a/sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_3rd.svg b/perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_3rd.svg similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_3rd.svg rename to perception/probabilistic_occupancy_grid_map/image/pointcloud_based_occupancy_grid_map_side_view_3rd.svg diff --git a/sensing/probabilistic_occupancy_grid_map/image/update_with_pointcloud.svg b/perception/probabilistic_occupancy_grid_map/image/update_with_pointcloud.svg similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/image/update_with_pointcloud.svg rename to perception/probabilistic_occupancy_grid_map/image/update_with_pointcloud.svg diff --git a/sensing/probabilistic_occupancy_grid_map/include/cost_value.hpp b/perception/probabilistic_occupancy_grid_map/include/cost_value.hpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/include/cost_value.hpp rename to perception/probabilistic_occupancy_grid_map/include/cost_value.hpp diff --git a/sensing/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp b/perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp rename to perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp diff --git a/sensing/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp b/perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp rename to perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp diff --git a/sensing/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp rename to perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/occupancy_grid_map.hpp diff --git a/sensing/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp b/perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp rename to perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp diff --git a/sensing/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp b/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp rename to perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp diff --git a/sensing/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_updater_interface.hpp b/perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_updater_interface.hpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_updater_interface.hpp rename to perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_updater_interface.hpp diff --git a/sensing/probabilistic_occupancy_grid_map/laserscan-based-occupancy-grid-map.md b/perception/probabilistic_occupancy_grid_map/laserscan-based-occupancy-grid-map.md similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/laserscan-based-occupancy-grid-map.md rename to perception/probabilistic_occupancy_grid_map/laserscan-based-occupancy-grid-map.md diff --git a/sensing/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py rename to perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py diff --git a/sensing/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py rename to perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py diff --git a/sensing/probabilistic_occupancy_grid_map/package.xml b/perception/probabilistic_occupancy_grid_map/package.xml similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/package.xml rename to perception/probabilistic_occupancy_grid_map/package.xml diff --git a/sensing/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md b/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md rename to perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md diff --git a/sensing/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp b/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp rename to perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp diff --git a/sensing/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp b/perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp rename to perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp diff --git a/sensing/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp rename to perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map.cpp diff --git a/sensing/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp rename to perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp diff --git a/sensing/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp b/perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp similarity index 100% rename from sensing/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp rename to perception/probabilistic_occupancy_grid_map/src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp From 152d293ed9bf73d5cfd89cabaa14345b94f0d746 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 7 Oct 2022 10:52:51 +0900 Subject: [PATCH 22/28] chore: sync files (#2032) Signed-off-by: GitHub Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-differential.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 97c9c4495bb02..fb08c73f5790b 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -80,7 +80,7 @@ jobs: - name: Get modified files id: get-modified-files - uses: tj-actions/changed-files@v31 + uses: tj-actions/changed-files@v32 with: files: | **/*.cpp From ca09e64b482b53fae7c6cdf8c532b847eb4fc2b4 Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Fri, 7 Oct 2022 11:07:36 +0900 Subject: [PATCH 23/28] feat(tier4_autoware_utils): add polygon util function (#2029) Signed-off-by: scepter914 Signed-off-by: scepter914 --- .../geometry/boost_polygon_utils.hpp | 9 ++++++--- .../src/geometry/boost_polygon_utils.cpp | 14 ++++++++++++++ 2 files changed, 20 insertions(+), 3 deletions(-) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_polygon_utils.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_polygon_utils.hpp index 8bbfe681fa3ae..8952775bfc3f3 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_polygon_utils.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_polygon_utils.hpp @@ -17,8 +17,10 @@ #include "tier4_autoware_utils/geometry/boost_geometry.hpp" -#include "autoware_auto_perception_msgs/msg/predicted_object.hpp" -#include "geometry_msgs/msg/pose.hpp" +#include +#include +#include +#include #include #include @@ -27,13 +29,14 @@ namespace tier4_autoware_utils { - bool isClockwise(const Polygon2d & polygon); Polygon2d inverseClockwise(const Polygon2d & polygon); geometry_msgs::msg::Polygon rotatePolygon( const geometry_msgs::msg::Polygon & polygon, const double & angle); Polygon2d toPolygon2d( const geometry_msgs::msg::Pose & pose, const autoware_auto_perception_msgs::msg::Shape & shape); +Polygon2d toPolygon2d(const autoware_auto_perception_msgs::msg::DetectedObject & object); +Polygon2d toPolygon2d(const autoware_auto_perception_msgs::msg::TrackedObject & object); Polygon2d toPolygon2d(const autoware_auto_perception_msgs::msg::PredictedObject & object); double getArea(const autoware_auto_perception_msgs::msg::Shape & shape); diff --git a/common/tier4_autoware_utils/src/geometry/boost_polygon_utils.cpp b/common/tier4_autoware_utils/src/geometry/boost_polygon_utils.cpp index b54f888ad0ae1..9c6b84f3bca69 100644 --- a/common/tier4_autoware_utils/src/geometry/boost_polygon_utils.cpp +++ b/common/tier4_autoware_utils/src/geometry/boost_polygon_utils.cpp @@ -167,6 +167,20 @@ Polygon2d toPolygon2d( return isClockwise(polygon) ? polygon : inverseClockwise(polygon); } +tier4_autoware_utils::Polygon2d toPolygon2d( + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + return tier4_autoware_utils::toPolygon2d( + object.kinematics.pose_with_covariance.pose, object.shape); +} + +tier4_autoware_utils::Polygon2d toPolygon2d( + const autoware_auto_perception_msgs::msg::TrackedObject & object) +{ + return tier4_autoware_utils::toPolygon2d( + object.kinematics.pose_with_covariance.pose, object.shape); +} + tier4_autoware_utils::Polygon2d toPolygon2d( const autoware_auto_perception_msgs::msg::PredictedObject & object) { From 365c7257894363b41f87b36fda907c8d0a602111 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Fri, 7 Oct 2022 13:30:11 +0900 Subject: [PATCH 24/28] feat(run_out): avoid chattering of state transition (#1975) * feat: keep approach state to avoid chattering of detection Signed-off-by: Tomohito Ando * add parameter Signed-off-by: Tomohito Ando * update parameter Signed-off-by: Tomohito Ando * update documents Signed-off-by: Tomohito Ando * revert changed parameter Signed-off-by: Tomohito Ando Signed-off-by: Tomohito Ando --- .../run_out.param.yaml | 7 +++-- .../config/run_out.param.yaml | 7 +++-- .../docs/run_out/state_transition.svg | 4 --- .../scene_module/run_out/state_machine.hpp | 4 +++ .../include/scene_module/run_out/utils.hpp | 1 + .../run-out-design.md | 27 ++++++++++++++---- .../src/scene_module/run_out/manager.cpp | 1 + .../src/scene_module/run_out/scene.cpp | 9 +++--- .../scene_module/run_out/state_machine.cpp | 28 +++++++++++++------ 9 files changed, 59 insertions(+), 29 deletions(-) delete mode 100644 planning/behavior_velocity_planner/docs/run_out/state_transition.svg diff --git a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml index 44f623b96bb69..ccf90a0b29794 100644 --- a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml +++ b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/run_out.param.yaml @@ -33,9 +33,10 @@ # parameters for the change of state. used only when approaching is enabled state: - stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping - stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state - disable_approach_dist: 3.0 # [m] end the approaching state if distance to the obstacle is longer than this value + stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping + stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state + disable_approach_dist: 3.0 # [m] end the approaching state if distance to the obstacle is longer than this value + keep_approach_duration: 1.0 # [sec] keep approach state for this duration to avoid chattering of state transition # parameter to avoid sudden stopping slow_down_limit: diff --git a/planning/behavior_velocity_planner/config/run_out.param.yaml b/planning/behavior_velocity_planner/config/run_out.param.yaml index 44f623b96bb69..ccf90a0b29794 100644 --- a/planning/behavior_velocity_planner/config/run_out.param.yaml +++ b/planning/behavior_velocity_planner/config/run_out.param.yaml @@ -33,9 +33,10 @@ # parameters for the change of state. used only when approaching is enabled state: - stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping - stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state - disable_approach_dist: 3.0 # [m] end the approaching state if distance to the obstacle is longer than this value + stop_thresh: 0.01 # [m/s] threshold to decide if ego is stopping + stop_time_thresh: 3.0 # [sec] threshold for stopping time to transit to approaching state + disable_approach_dist: 3.0 # [m] end the approaching state if distance to the obstacle is longer than this value + keep_approach_duration: 1.0 # [sec] keep approach state for this duration to avoid chattering of state transition # parameter to avoid sudden stopping slow_down_limit: diff --git a/planning/behavior_velocity_planner/docs/run_out/state_transition.svg b/planning/behavior_velocity_planner/docs/run_out/state_transition.svg deleted file mode 100644 index aad4bdd34c4cd..0000000000000 --- a/planning/behavior_velocity_planner/docs/run_out/state_transition.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - -
GO
GO
STOP
STOP
APPROACH
APPROACH
Current velocity is
less than threshold
Current velocity is...
Stop time is
larger than threshold
Stop time is...
Current velocity is
larger than threshold
Current velocity is...
There are no obstacles or
distance to the obstacle is
larger than threshold
There are no obstacles or...
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_velocity_planner/include/scene_module/run_out/state_machine.hpp b/planning/behavior_velocity_planner/include/scene_module/run_out/state_machine.hpp index e378e5b385428..0ee34bf6c9685 100644 --- a/planning/behavior_velocity_planner/include/scene_module/run_out/state_machine.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/run_out/state_machine.hpp @@ -44,6 +44,7 @@ class StateMachine explicit StateMachine(const StateParam & state_param) { state_param_ = state_param; } State getCurrentState() const { return state_; } + boost::optional getTargetObstacle() const { return target_obstacle_; } std::string toString(const State & state) const; void updateState(const StateInput & state_input, rclcpp::Clock & clock); @@ -51,6 +52,9 @@ class StateMachine StateParam state_param_; State state_{State::GO}; rclcpp::Time stop_time_; + rclcpp::Time prev_approach_time_; + boost::optional prev_obstacle_{}; + boost::optional target_obstacle_{}; }; } // namespace run_out_utils } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/include/scene_module/run_out/utils.hpp b/planning/behavior_velocity_planner/include/scene_module/run_out/utils.hpp index 357ec74c9d0a6..0a16649c8ed7a 100644 --- a/planning/behavior_velocity_planner/include/scene_module/run_out/utils.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/run_out/utils.hpp @@ -82,6 +82,7 @@ struct StateParam float stop_thresh; float stop_time_thresh; float disable_approach_dist; + float keep_approach_duration; }; struct SlowDownLimit diff --git a/planning/behavior_velocity_planner/run-out-design.md b/planning/behavior_velocity_planner/run-out-design.md index 2772a39a363c3..95378350806d1 100644 --- a/planning/behavior_velocity_planner/run-out-design.md +++ b/planning/behavior_velocity_planner/run-out-design.md @@ -147,7 +147,21 @@ The decision to approach the obstacle is determined by a simple state transition ![brief](./docs/run_out/insert_velocity_to_approach.svg) -![brief](./docs/run_out/state_transition.svg) +```plantuml +@startuml +hide empty description +left to right direction +title State transition for approaching the obstacle + +[*] --> GO +GO --> STOP : Current velocity is less than threshold +STOP --> GO : Current velocity is larger than threshold + +STOP --> APPROACH : Stop duration is larger than threshold +APPROACH --> GO : There are no obstacles or \n distance to the obstacle is larger than threshold +APPROACH --> APPROACH : Approach duration is less than threshold +@enduml +``` ##### Limit velocity with specified jerk and acc limit @@ -190,11 +204,12 @@ You can choose whether to use this feature by parameter of `slow_down_limit.enab | `margin` | double | [m] distance on how close ego approaches the obstacle | | `limit_vel_kmph` | double | [km/h] limit velocity for approaching after stopping | -| Parameter /state | Type | Description | -| ----------------------- | ------ | ----------------------------------------------------------------------------------- | -| `stop_thresh` | double | [m/s] threshold to decide if ego is stopping | -| `stop_time_thresh` | double | [sec] threshold for stopping time to transit to approaching state | -| `disable_approach_dist` | double | [m] end the approaching state if distance to the obstacle is longer than this value | +| Parameter /state | Type | Description | +| ------------------------ | ------ | ----------------------------------------------------------------------------------- | +| `stop_thresh` | double | [m/s] threshold to decide if ego is stopping | +| `stop_time_thresh` | double | [sec] threshold for stopping time to transit to approaching state | +| `disable_approach_dist` | double | [m] end the approaching state if distance to the obstacle is longer than this value | +| `keep_approach_duration` | double | [sec] keep approach state for this duration to avoid chattering of state transition | | Parameter /slow_down_limit | Type | Description | | -------------------------- | ------ | ------------------------------------------------------------- | diff --git a/planning/behavior_velocity_planner/src/scene_module/run_out/manager.cpp b/planning/behavior_velocity_planner/src/scene_module/run_out/manager.cpp index 43846ba767e1a..2c4ab669cbf4c 100644 --- a/planning/behavior_velocity_planner/src/scene_module/run_out/manager.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/run_out/manager.cpp @@ -94,6 +94,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) p.stop_thresh = node.declare_parameter(ns_s + ".stop_thresh", 0.01); p.stop_time_thresh = node.declare_parameter(ns_s + ".stop_time_thresh", 3.0); p.disable_approach_dist = node.declare_parameter(ns_s + ".disable_approach_dist", 4.0); + p.keep_approach_duration = node.declare_parameter(ns_s + ".keep_approach_duration", 1.0); } { diff --git a/planning/behavior_velocity_planner/src/scene_module/run_out/scene.cpp b/planning/behavior_velocity_planner/src/scene_module/run_out/scene.cpp index 74bc9b8ac1bc9..e45d50d7429ab 100644 --- a/planning/behavior_velocity_planner/src/scene_module/run_out/scene.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/run_out/scene.cpp @@ -674,27 +674,28 @@ void RunOutModule::insertVelocityForState( // get updated state and target obstacle to decelerate const auto state = state_machine_->getCurrentState(); + const auto target_obstacle = state_machine_->getTargetObstacle(); // no obstacles to decelerate - if (!dynamic_obstacle) { + if (!target_obstacle) { return; } // insert velocity for each state switch (state) { case State::GO: { - insertStoppingVelocity(dynamic_obstacle, current_pose, current_vel, current_acc, output_path); + insertStoppingVelocity(target_obstacle, current_pose, current_vel, current_acc, output_path); break; } case State::STOP: { - insertStoppingVelocity(dynamic_obstacle, current_pose, current_vel, current_acc, output_path); + insertStoppingVelocity(target_obstacle, current_pose, current_vel, current_acc, output_path); break; } case State::APPROACH: { insertApproachingVelocity( - *dynamic_obstacle, current_pose, planner_param.approaching.limit_vel_kmph / 3.6, + *target_obstacle, current_pose, planner_param.approaching.limit_vel_kmph / 3.6, planner_param.approaching.margin, output_path); debug_ptr_->setAccelReason(RunOutDebug::AccelReason::STOP); break; diff --git a/planning/behavior_velocity_planner/src/scene_module/run_out/state_machine.cpp b/planning/behavior_velocity_planner/src/scene_module/run_out/state_machine.cpp index f2a92ac7dcdac..daeb86393b1e9 100644 --- a/planning/behavior_velocity_planner/src/scene_module/run_out/state_machine.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/run_out/state_machine.cpp @@ -39,11 +39,7 @@ std::string StateMachine::toString(const State & state) const void StateMachine::updateState(const StateInput & state_input, rclcpp::Clock & clock) { - // no obstacles - if (!state_input.current_obstacle) { - state_ = State::GO; - return; - } + target_obstacle_ = state_input.current_obstacle; switch (state_) { case State::GO: { @@ -59,8 +55,10 @@ void StateMachine::updateState(const StateInput & state_input, rclcpp::Clock & c } case State::STOP: { - // if current velocity is larger than the threshold, transit to STOP state - if (state_input.current_velocity > state_param_.stop_thresh) { + // if current velocity is larger than the threshold or + // there are no obstacles, transit to GO state + if ( + state_input.current_velocity > state_param_.stop_thresh || !state_input.current_obstacle) { state_ = State::GO; return; } @@ -69,6 +67,8 @@ void StateMachine::updateState(const StateInput & state_input, rclcpp::Clock & c const auto elapsed_time = (clock.now() - stop_time_).seconds(); if (elapsed_time > state_param_.stop_time_thresh) { state_ = State::APPROACH; + prev_approach_time_ = clock.now(); + prev_obstacle_ = state_input.current_obstacle; return; } @@ -77,15 +77,25 @@ void StateMachine::updateState(const StateInput & state_input, rclcpp::Clock & c } case State::APPROACH: { - // if the obstacle is far enough from ego, transit to GO state const bool enough_dist_from_obstacle = state_input.dist_to_collision > state_param_.disable_approach_dist; - if (enough_dist_from_obstacle) { + // if the obstacle is enough distance from ego or there are no obstacles, transit to GO state + if (enough_dist_from_obstacle || !state_input.current_obstacle) { + // if elapsed time from entering APPROACH state is less than threshold, + // keep APPROACH state to avoid chattering of state transition + const auto elapsed_time = (clock.now() - prev_approach_time_).seconds(); + if (elapsed_time < state_param_.keep_approach_duration) { + target_obstacle_ = prev_obstacle_; + return; + } + state_ = State::GO; return; } // continue APPROACH state + prev_approach_time_ = clock.now(); + prev_obstacle_ = state_input.current_obstacle; return; } From 5162d75c0a872ff081d9ab9a7ec5958c8b241a82 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Fri, 7 Oct 2022 17:37:36 +0900 Subject: [PATCH 25/28] feat(obstacle_cruise_planner): add an explanation (#2034) * feat(obstacle_cruise_planner): add an explanation Signed-off-by: yutaka * update readme Signed-off-by: yutaka Signed-off-by: yutaka --- .../obstacle_cruise_planner.param.yaml | 2 +- planning/obstacle_cruise_planner/README.md | 10 ++++++---- .../config/obstacle_cruise_planner.param.yaml | 2 +- .../obstacle_cruise_planner/src/planner_interface.cpp | 2 +- 4 files changed, 9 insertions(+), 7 deletions(-) diff --git a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml index 0c102155d2f00..520637abed775 100644 --- a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml +++ b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/obstacle_cruise_planner.param.yaml @@ -10,7 +10,7 @@ min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] - terminal_safe_distance_margin : 3.0 # Stop margin at the goal [m] + terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m] nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index diff --git a/planning/obstacle_cruise_planner/README.md b/planning/obstacle_cruise_planner/README.md index d4e66d87b5a5a..4d114c47bfaf0 100644 --- a/planning/obstacle_cruise_planner/README.md +++ b/planning/obstacle_cruise_planner/README.md @@ -149,15 +149,17 @@ In the `obstacle_filtering` namespace, ### Stop planning -| Parameter | Type | Description | -| ----------------------------- | ------ | ----------------------------------------- | -| `common.min_strong_accel` | double | ego's minimum acceleration to stop [m/ss] | -| `common.safe_distance_margin` | double | distance with obstacles for stop [m] | +| Parameter | Type | Description | +| -------------------------------------- | ------ | ------------------------------------------------------------------------------------------ | +| `common.min_strong_accel` | double | ego's minimum acceleration to stop [m/ss] | +| `common.safe_distance_margin` | double | distance with obstacles for stop [m] | +| `common.terminal_safe_distance_margin` | double | terminal_distance with obstacles for stop, which cannot be exceed safe distance margin [m] | The role of the stop planning is keeping a safe distance with static vehicle objects or dynamic/static non vehicle objects. The stop planning just inserts the stop point in the trajectory to keep a distance with obstacles inside the detection area. The safe distance is parameterized as `common.safe_distance_margin`. +When it stops at the end of the trajectory, and obstacle is on the same point, the safe distance becomes `terminal_safe_distance_margin`. When inserting the stop point, the required acceleration for the ego to stop in front of the stop point is calculated. If the acceleration is less than `common.min_strong_accel`, the stop planning will be cancelled since this package does not assume a strong sudden brake for emergency. diff --git a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml index 0c102155d2f00..520637abed775 100644 --- a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml +++ b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -10,7 +10,7 @@ min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss] min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss] safe_distance_margin : 6.0 # This is also used as a stop margin [m] - terminal_safe_distance_margin : 3.0 # Stop margin at the goal [m] + terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m] nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index 4ebef793bc733..e73d83e749139 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -155,7 +155,7 @@ Trajectory PlannerInterface::generateStopTrajectory( abs_ego_offset; const double stop_dist_diff = closest_behavior_stop_dist_from_ego - closest_obstacle_stop_dist_from_ego; - if (stop_dist_diff < 0.5) { + if (stop_dist_diff < longitudinal_info_.safe_distance_margin) { // Use terminal margin (terminal_safe_distance_margin) for obstacle stop return longitudinal_info_.terminal_safe_distance_margin; } From 3a7e17498f5f864a4a5963947542c84a95a86130 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 7 Oct 2022 18:42:07 +0900 Subject: [PATCH 26/28] fix(component_interface_specs): add missing dep (#2035) --- common/component_interface_specs/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/common/component_interface_specs/package.xml b/common/component_interface_specs/package.xml index d0c12c83c2379..8ef93d0f5f95d 100644 --- a/common/component_interface_specs/package.xml +++ b/common/component_interface_specs/package.xml @@ -11,6 +11,8 @@ autoware_cmake + autoware_adapi_v1_msgs + ament_lint_auto autoware_lint_common From b48b4f5996d14f06a375ed9a230f50a685ab0034 Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Sat, 8 Oct 2022 14:43:21 +0900 Subject: [PATCH 27/28] refactor(perception_util): refactor moving unnamed namespace from include file to src file (#2028) * fix include path Signed-off-by: scepter914 * move unnamed namespace to src file Signed-off-by: scepter914 * fix template function Signed-off-by: scepter914 * fix unnamed namespace Signed-off-by: scepter914 * delete comment Signed-off-by: scepter914 Signed-off-by: scepter914 --- .../include/perception_utils/conversion.hpp | 4 ++-- .../perception_utils/predicted_path_utils.hpp | 2 +- .../include/perception_utils/transform.hpp | 17 ++++++++--------- 3 files changed, 11 insertions(+), 12 deletions(-) diff --git a/common/perception_utils/include/perception_utils/conversion.hpp b/common/perception_utils/include/perception_utils/conversion.hpp index 1497114eee532..8aef31a92928e 100644 --- a/common/perception_utils/include/perception_utils/conversion.hpp +++ b/common/perception_utils/include/perception_utils/conversion.hpp @@ -15,8 +15,8 @@ #ifndef PERCEPTION_UTILS__CONVERSION_HPP_ #define PERCEPTION_UTILS__CONVERSION_HPP_ -#include "autoware_auto_perception_msgs/msg/detected_objects.hpp" -#include "autoware_auto_perception_msgs/msg/tracked_objects.hpp" +#include +#include namespace perception_utils { diff --git a/common/perception_utils/include/perception_utils/predicted_path_utils.hpp b/common/perception_utils/include/perception_utils/predicted_path_utils.hpp index c02282f9efeea..cb8ec6bf5ff3e 100644 --- a/common/perception_utils/include/perception_utils/predicted_path_utils.hpp +++ b/common/perception_utils/include/perception_utils/predicted_path_utils.hpp @@ -17,7 +17,7 @@ #include "tier4_autoware_utils/geometry/geometry.hpp" -#include "autoware_auto_perception_msgs/msg/predicted_path.hpp" +#include #include #include diff --git a/common/perception_utils/include/perception_utils/transform.hpp b/common/perception_utils/include/perception_utils/transform.hpp index 54af7c04a006e..fe4fced16120f 100644 --- a/common/perception_utils/include/perception_utils/transform.hpp +++ b/common/perception_utils/include/perception_utils/transform.hpp @@ -15,24 +15,23 @@ #ifndef PERCEPTION_UTILS__TRANSFORM_HPP_ #define PERCEPTION_UTILS__TRANSFORM_HPP_ -#include "geometry_msgs/msg/transform.hpp" +#include + +#include #include #include - #ifdef ROS_DISTRO_GALACTIC #include #else #include #endif -#include "boost/optional.hpp" - #include -namespace +namespace detail { -[[maybe_unused]] boost::optional getTransform( +[[maybe_unused]] inline boost::optional getTransform( const tf2_ros::Buffer & tf_buffer, const std::string & source_frame_id, const std::string & target_frame_id, const rclcpp::Time & time) { @@ -46,7 +45,7 @@ namespace return boost::none; } } -} // namespace +} // namespace detail namespace perception_utils { @@ -64,8 +63,8 @@ bool transformObjects( tf2::Transform tf_target2objects; tf2::Transform tf_objects_world2objects; { - const auto ros_target2objects_world = - getTransform(tf_buffer, input_msg.header.frame_id, target_frame_id, input_msg.header.stamp); + const auto ros_target2objects_world = detail::getTransform( + tf_buffer, input_msg.header.frame_id, target_frame_id, input_msg.header.stamp); if (!ros_target2objects_world) { return false; } From 88e932467a7e3e6d9ff0ea581288b0414a01b992 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Mon, 10 Oct 2022 22:07:22 +0900 Subject: [PATCH 28/28] feat(tier4_screen_capture_rviz_plugin): add prefix to video name (#2038) feat: add prefix --- .../src/screen_capture_panel.cpp | 12 ++++++++---- .../src/screen_capture_panel.hpp | 2 ++ 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp index 0c558ca802c6d..88fbdc483f89c 100644 --- a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp +++ b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp @@ -28,7 +28,7 @@ void setFormatDate(QLabel * line, double time) char buffer[128]; auto seconds = static_cast(time); strftime(buffer, sizeof(buffer), "%Y-%m-%d-%H-%M-%S", localtime(&seconds)); - line->setText(QString(buffer)); + line->setText(QString("- ") + QString(buffer) + QString(".mp4")); } AutowareScreenCapturePanel::AutowareScreenCapturePanel(QWidget * parent) @@ -42,11 +42,13 @@ AutowareScreenCapturePanel::AutowareScreenCapturePanel(QWidget * parent) ros_time_label_ = new QLabel; screen_capture_button_ptr_ = new QPushButton("Capture Screen Shot"); connect(screen_capture_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickScreenCapture())); + file_name_prefix_ = new QLineEdit("cap"); + connect(file_name_prefix_, SIGNAL(valueChanged(std::string)), this, SLOT(onPrefixChanged())); cap_layout->addWidget(screen_capture_button_ptr_); + cap_layout->addWidget(file_name_prefix_); cap_layout->addWidget(ros_time_label_); // initialize file name system clock is better for identification. setFormatDate(ros_time_label_, rclcpp::Clock().now().seconds()); - cap_layout->addWidget(new QLabel(" [.mp4] ")); } // video capture @@ -96,6 +98,8 @@ void AutowareScreenCapturePanel::onInitialize() std::bind(&AutowareScreenCapturePanel::onCaptureTrigger, this, _1, _2)); } +void onPrefixChanged() {} + void AutowareScreenCapturePanel::onRateChanged() {} void AutowareScreenCapturePanel::onClickScreenCapture() @@ -138,8 +142,8 @@ void AutowareScreenCapturePanel::onClickVideoCapture() .size(); current_movie_size_ = cv::Size(q_size.width(), q_size.height()); writer_.open( - "capture/" + capture_file_name_ + ".mp4", fourcc, capture_hz_->value(), - current_movie_size_); + "capture/" + file_name_prefix_->text().toStdString() + capture_file_name_ + ".mp4", + fourcc, capture_hz_->value(), current_movie_size_); } capture_timer_->start(clock); state_ = State::CAPTURING; diff --git a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp index a6e78acf29b21..8ddd390206b81 100644 --- a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp +++ b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp @@ -67,12 +67,14 @@ class AutowareScreenCapturePanel : public rviz_common::Panel public Q_SLOTS: void onClickScreenCapture(); void onClickVideoCapture(); + void onPrefixChanged(); void onRateChanged(); private: QLabel * ros_time_label_; QPushButton * screen_capture_button_ptr_; QPushButton * capture_to_mp4_button_ptr_; + QLineEdit * file_name_prefix_; QSpinBox * capture_hz_; QTimer * capture_timer_; QMainWindow * main_window_{nullptr};